From 762b00416260c37a516cda57f191d1246c4f352e Mon Sep 17 00:00:00 2001 From: mn297 Date: Fri, 12 Apr 2024 22:33:19 -0400 Subject: [PATCH] brushed board firmware --- .DS_Store | Bin 0 -> 6148 bytes rpi_pico_rosserial_test/.gitignore | 5 + .../.vscode/extensions.json | 10 + rpi_pico_rosserial_test/firmware.bin | Bin 0 -> 330748 bytes rpi_pico_rosserial_test/firmware.elf | Bin 0 -> 1516952 bytes rpi_pico_rosserial_test/include/README | 39 ++ rpi_pico_rosserial_test/lib/README | 46 ++ .../lib/XL320-bene/LICENSE | 340 +++++++++++ .../lib/XL320-bene/README.md | 42 ++ .../lib/XL320-bene/XL320.cpp | 567 ++++++++++++++++++ .../lib/XL320-bene/XL320.h | 140 +++++ .../lib/XL320-bene/dxl_pro.cpp | 64 ++ .../lib/XL320-bene/dxl_pro.h | 37 ++ .../XL320_servo_example.ino | 72 +++ ...ample_with_half_duplex_hardware_serial.ino | 86 +++ .../XL320_servo_set_baud_rate_or_id.ino | 52 ++ rpi_pico_rosserial_test/platformio.ini | 26 + rpi_pico_rosserial_test/rpi_pico_flash.cfg | 19 + rpi_pico_rosserial_test/src/main.cpp | 112 ++++ rpi_pico_rosserial_test/src/main_blinky.cpp | 19 + rpi_pico_rosserial_test/test/README | 11 + teensy40_brushed_v2/.DS_Store | Bin 0 -> 6148 bytes teensy40_brushed_v2/.gitignore | 6 + teensy40_brushed_v2/.vscode/extensions.json | 10 + teensy40_brushed_v2/.vscode/settings.json | 50 ++ teensy40_brushed_v2/include/README | 39 ++ teensy40_brushed_v2/lib/Arm/driver_motor.cpp | 371 ++++++++++++ teensy40_brushed_v2/lib/Arm/driver_motor.h | 207 +++++++ teensy40_brushed_v2/lib/Arm/hardware_pins.h | 53 ++ teensy40_brushed_v2/lib/Arm/model_encoder.cpp | 135 +++++ teensy40_brushed_v2/lib/Arm/model_encoder.h | 75 +++ teensy40_brushed_v2/lib/Arm/model_sensor.cpp | 94 +++ teensy40_brushed_v2/lib/Arm/model_sensor.h | 51 ++ teensy40_brushed_v2/lib/Arm/motor.h | 366 +++++++++++ teensy40_brushed_v2/lib/Arm/pid.cpp | 130 ++++ teensy40_brushed_v2/lib/Arm/pid.h | 47 ++ teensy40_brushed_v2/lib/Arm/rotation2d.h | 130 ++++ teensy40_brushed_v2/lib/Arm/vector2d.cpp | 77 +++ teensy40_brushed_v2/lib/Arm/vector2d.h | 117 ++++ .../lib/Arm/velocity_estimation.cpp | 150 +++++ .../lib/Arm/velocity_estimation.h | 62 ++ teensy40_brushed_v2/lib/README | 46 ++ teensy40_brushed_v2/platformio.ini | 19 + teensy40_brushed_v2/src/common.h | 1 + teensy40_brushed_v2/src/main.cpp | 509 ++++++++++++++++ teensy40_brushed_v2/src/main_ros.cpp | 469 +++++++++++++++ teensy40_brushed_v2/src/ros_tst.cpp | 361 +++++++++++ teensy40_brushed_v2/test/README | 11 + 48 files changed, 5273 insertions(+) create mode 100644 .DS_Store create mode 100644 rpi_pico_rosserial_test/.gitignore create mode 100644 rpi_pico_rosserial_test/.vscode/extensions.json create mode 100644 rpi_pico_rosserial_test/firmware.bin create mode 100644 rpi_pico_rosserial_test/firmware.elf create mode 100644 rpi_pico_rosserial_test/include/README create mode 100644 rpi_pico_rosserial_test/lib/README create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/LICENSE create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/README.md create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/XL320.cpp create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/XL320.h create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.cpp create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.h create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example/XL320_servo_example.ino create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example_with_half_duplex_hardware_serial/XL320_servo_example_with_half_duplex_hardware_serial.ino create mode 100644 rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_set_baud_rate_or_id/XL320_servo_set_baud_rate_or_id.ino create mode 100644 rpi_pico_rosserial_test/platformio.ini create mode 100644 rpi_pico_rosserial_test/rpi_pico_flash.cfg create mode 100644 rpi_pico_rosserial_test/src/main.cpp create mode 100644 rpi_pico_rosserial_test/src/main_blinky.cpp create mode 100644 rpi_pico_rosserial_test/test/README create mode 100644 teensy40_brushed_v2/.DS_Store create mode 100644 teensy40_brushed_v2/.gitignore create mode 100644 teensy40_brushed_v2/.vscode/extensions.json create mode 100644 teensy40_brushed_v2/.vscode/settings.json create mode 100644 teensy40_brushed_v2/include/README create mode 100644 teensy40_brushed_v2/lib/Arm/driver_motor.cpp create mode 100644 teensy40_brushed_v2/lib/Arm/driver_motor.h create mode 100644 teensy40_brushed_v2/lib/Arm/hardware_pins.h create mode 100644 teensy40_brushed_v2/lib/Arm/model_encoder.cpp create mode 100644 teensy40_brushed_v2/lib/Arm/model_encoder.h create mode 100644 teensy40_brushed_v2/lib/Arm/model_sensor.cpp create mode 100644 teensy40_brushed_v2/lib/Arm/model_sensor.h create mode 100644 teensy40_brushed_v2/lib/Arm/motor.h create mode 100644 teensy40_brushed_v2/lib/Arm/pid.cpp create mode 100644 teensy40_brushed_v2/lib/Arm/pid.h create mode 100644 teensy40_brushed_v2/lib/Arm/rotation2d.h create mode 100644 teensy40_brushed_v2/lib/Arm/vector2d.cpp create mode 100644 teensy40_brushed_v2/lib/Arm/vector2d.h create mode 100644 teensy40_brushed_v2/lib/Arm/velocity_estimation.cpp create mode 100644 teensy40_brushed_v2/lib/Arm/velocity_estimation.h create mode 100644 teensy40_brushed_v2/lib/README create mode 100644 teensy40_brushed_v2/platformio.ini create mode 100644 teensy40_brushed_v2/src/common.h create mode 100644 teensy40_brushed_v2/src/main.cpp create mode 100644 teensy40_brushed_v2/src/main_ros.cpp create mode 100644 teensy40_brushed_v2/src/ros_tst.cpp create mode 100644 teensy40_brushed_v2/test/README diff --git a/.DS_Store b/.DS_Store new file mode 100644 index 0000000000000000000000000000000000000000..a2e2dc32305491e5d426c00506e3f4b6c55f1c55 GIT binary patch literal 6148 zcmeHKJxc>Y5PhpDf;J%{u?bvlAu2XjUP45)5@LTQCL}`Qg?tEVbG?7U!p=s)%07jy zzre=-;hWtJ-VqgJL_~IA=k3ny?CreU+r0&#ii6r3kO7cp5lqcdy(8k6GA1+DBEd?= zXf@W#M`61&*3%gr1CD{e$bkOvv4RGU(T{(>>Sp-B38zNBc33J^TVa*9bacJDyznwC zB>lBd{hj99-k|QU7>YbP2+>6!6;#ne9Xr@Z83mlsR;NCp=YTybto6{AIciTgK2xBv zINfOR+_ug)AG0R6DdyJ>-`Mz>5##*HZcE9LnGQJ#v_2x20WBe!>XE%JJr%MVXvTWU zw~Kr(JNXE4o-Qu;Mr&ZgdBnN-{wN7P^3TG@g3eUdO%G?-z$$aEl7|7?O)^qr`xNVm zwWIEWuSdr7e>x2E_8a)(bK`kW9-YW{=2r5ZR?I3wdVbo0T)bnzG4Ssgkp0195%eua z2KClKrLO?Q6wO*#mtP8r@htilBZKr%lnEu8P-U+e%7oMI*?zvo$e;;_vX>8KpRDW+ zMd_z=d{1|W@(nue7;p?E8JIQAjGX`5AK(9zL9XQ(a18t_22`q4E)|)QJzK|;le5-i sIb;!$evv^PLS>I*U6G@BiA4*2o>Yjw#mFEn6!#;bX>iIh@T&~G0+giN-T(jq literal 0 HcmV?d00001 diff --git a/rpi_pico_rosserial_test/.gitignore b/rpi_pico_rosserial_test/.gitignore new file mode 100644 index 0000000..89cc49c --- /dev/null +++ b/rpi_pico_rosserial_test/.gitignore @@ -0,0 +1,5 @@ +.pio +.vscode/.browse.c_cpp.db* +.vscode/c_cpp_properties.json +.vscode/launch.json +.vscode/ipch diff --git a/rpi_pico_rosserial_test/.vscode/extensions.json b/rpi_pico_rosserial_test/.vscode/extensions.json new file mode 100644 index 0000000..080e70d --- /dev/null +++ b/rpi_pico_rosserial_test/.vscode/extensions.json @@ -0,0 +1,10 @@ +{ + // See http://go.microsoft.com/fwlink/?LinkId=827846 + // for the documentation about the extensions.json format + "recommendations": [ + "platformio.platformio-ide" + ], + "unwantedRecommendations": [ + "ms-vscode.cpptools-extension-pack" + ] +} diff --git a/rpi_pico_rosserial_test/firmware.bin b/rpi_pico_rosserial_test/firmware.bin new file mode 100644 index 0000000000000000000000000000000000000000..b669d3d44321fcac01d2404ef37d8a0cde38ad9c GIT binary patch literal 330748 zcmeFa3v^V~*+2a3bLO55nIu5Y%p~N@OoD-M2?_V8oXo*oW{P2sAY{JZo&mI7@9n?V zx7Pn#>uXp$Is5E=_T|~nex7GPmkmWLy$*S$Z=YXqY*+XB`h8OK%H|nfa&-9w$Es%L zNIJV3%NwjdhBtF$N-iE2oV(oPV>*X*4JBs}TQ@NNBui^-$WKF_|I?!8%wgs*xJTl= zEjwBu$10z#!CueOZT%Tv?N7InH_U5HY#4vBggsAX6r;Ml`uqliPkc4_v0=NRPKl zzx;D&&$VA6StFl8*~>^jLwfPQNx%49*>OC-hV-ld%ZYya*}uPjtPNV`BQHAvH{GjS z05?mWTu*)~n-e!bHSTqqBE%?}H$0NCHxznEra|`NZue;1*08JQa=im9>>^7e{uY*y{C+7}h%_=!>1PX`dBRVi&REZTp*o_AFpu$X{ADCx zGl}Gz8Od)7B;R-g5j!T--&f0?_tnu0zp|4&9PO*s)N8$#=r*?)(|DB6~eS^`q({eoLxMYboSpKVemZ*M-tAomo@zl_pDJ|L(Vw!s3zzfXf3S`>k?eV$s z9;qBHHE7c{QbVt&EWLfTyj(`Vyw1_+)}!>j4&MSFB@2cPUV|s>(|e2jdavDIh=D#< zyT7iz*6x?6w^lfMw3j%(RRAhT4cT(Y=p{Y$J8bI zLo!j)gWU9(0Z6;3fh9MmsBChaxtQasYn$AqH?=EWEGUG zMvs4w$+uDRD4zZrTXS3YZ7f7HG;vD)c!bSqoP8=0bO{ePvB%wXN(c#P@2(MX7nPlg z1)Z#GIb+EyFwTP5Uq7~NyW_c}Gf%gtHt5iXSfqiqE|y3WV#$tF&?$Cl_VL>PmeNMH zeQentbS`ImYK6$BHWq1J{7Ry)_LvKBM$()Uj z?s!h`@v0VopOkdjb$t>`)~D`6izHim=VQHAmg0-3fhLfZGW87}gE!CLs9s~0{7IK$ zwd*ut{+<8gcY)7+XC{4vMA=x`^{UnXlw`DO!Yujh81PXp@&$kwm-^U+zJjhmRKHY1 zQ%UR7H8e3@Jxfj>cKN4Es|#=OIek(`pjVR+>TC%uWTas1XEoWNBdFPX>b)45ht*vHnX-ju2C2Pj|)V`eIUJfHZ9zGX7 zhHFHU%}8%!Z=OQZjEJ&k7->k9lTnM;a&6a9EoBph(2r}JM?6Hy9IU%=nq=$IWbac~ zyg=1}LIv@XXHq|Me-zhxnQZsFd>>+MU%|Ta{!({6H{aL%vu2jO zdxVw!{S?U`CwQBh8$Vlj-ew>goUEa{8BJqxCI@;;=@|CZ9Ly>;^crCKNvzGDOa$sG zqS+;jRe5Qf^%nnQZaUHG>nqjFf0mW1tjyNWrc95Ea+zewXbL8qjAyc!1FWhY}#mC zn5->z5IwAO6?rCM7v!BUC*=1QdJ2)tIv>PplCudsBQ^BxRM6$Xym>w~^gxQ7L02v{ zksf8i%Q*vb_gu_Hm=U=MlCJf1_=cG?jAq0iQ>6BX?Vythu4QNRvGe zzp4CpafwzA=0zT|KY{wiWQbJIV;kDnT1f;oefE62KQF8c86(==A$M^aCMwPM>q9I2hES{D82UH2t{;3#{)yWW`-xkr zDH^=PuI)5TWv2`-Eykwn5<;dUEM$lnsL4tpeIzwhgB@auW6t4KR?|V2{0nxpCdR25 zt1zQqZRD(U0xR^$(TQXZ<@>j8&{N*JYzn!>lh?bN+}cq4;70!r_wXrlYDz7KESP%U9^YA81)PSWmTvFodDj0=0IG#CBT-c5dua{-{58e*y3h<4XO_cd`#IAVLd z;H>Rz&JhZ)a$=u-K{-sFt4w=ae3rwJmEAsao$(1(Ss}4n8+yf?ci8co<0S_%S>rU! zQrwg*8zWbC$Pi-H#t^x*kB{4h)!dgF`r()^^5YG5Nf*+%gisDfpo=U3T?8HXpIDn3 zdSOgEDJxb^*H=;Ons>=nGN_GQU-gric3%M?pmC1dmjmiMav>*T4BLOaS{b)X->ccg!?RNr-$jOP9F z6h%|&^7oN(?-uu>`1nI?H!xvugOzsArv+GpMVLRuzMdE#9v2Ct_pc>#BKol1JfL5# z=sU+9(m03LQSzP(!!0@J#R6#dN&3j3&(&;*bZ^azbT{Wm&NOF7&fLX-5#vHtqz`K! zHg-;;MF|GzjR*8rUob|-?P68N5O3qd3&yYu65IGw%<b`4G9xTlX_ff9-EY{7SOmP>-4Us&+CFExPD+&#voUX!%d7oF2 z6yq-QKBr%D*Tr>_@tvBg38CVBlOp2}@2k^JT5y`TxePd8kqDNarGsv3+}mU5s;ECM zJ=kN|J+q-gVd@UI7!N`YnxvjgY%Gk&^2Ax_=|QZ)YyA=7aqFvzKIaKYh_A$%Ggryp zZAi}}FAdxIq?tv#Ppsvz-HloF#9|-hbWxcYA4gTBef;)B6%}~AO1?WQCX{^=uN1S; zcElWZ|Mg^W@?70G_0I`5`EK_g6574bf1nMsN?W`L^vekO_P~zglwY{R%}zo_-d+^W z4|14)`axgqe#ihcnnPgp*U@O|-d)Ha;Z)S4O;aars3@$B{Abvt1&-0c10S6Hz~yi8 zxB5&Gr!PX8J(m?>z+U4A%#{^d`~lic4M%^m*6cSd8V3&0>z;6O0T7ra$BnT0EU6t4 zDuTeNG8=!^;Qi=ukfz&Yx>Y@EpW_?Gi82`-PiFG8-+z?z0#=?CA8#G^hIo6oJL}|R z+T+fNPlUXq#m*DTwK4Jbu=~?f69J9CCth3kzVxRzhZ7HM5Dv{Jp))n~?r#$EKTF;`!XfJNS<++u)=_=vHUH1rb)l@a#?GuzK6afUH0YXY z9w5NFM7zu8w#4{O-ZZMgF1lmTfR)n6^q2QDWR3ngO9p{yS&vr$BLbtkuvipw&*;}h zv|V;vhAL&HsgeOyN#m^cr-tqtWs{2ISrPk>Hz`dxon(P(Q+Z*m${ciB=>$ztcDpCU z_2FE*L97&m=1%i2xA|nDCs!%-nA9G(CN4M{+y>$_ys0N56k7G1df7KAHusO?QSFfl ztm(fL&*f z3(hh!qjVF#*2VP^R;>?Fxh8(3@K*`ss`QWq&Ps15s&U?}j%7uPeJ-<5z92ryTOvMX ze$<^EtE6J@Q-W0KQmJzm6?qJxY+p@jCY21#bnvlXKdib})?m(I#Vsj0M{+vFkTyKt zo7*Xbs59xRB(`f78TJimrAo^qsi7snAl(4x2lpgC{u-4J#Dyzm%Et8FEdnjOHt9b*pK zzrivqHFW=2_l9sgO=aYtxfAW=W6n{-kRPKEv+ps zNF0;t$|{`XoKxuOmfyEj%+-b{`ErWqE3mnLnv&CH^*9CpC{>8JmV=bU-gFg&CIYHr ztN_0$wq?+@j#XU~YsGJO%-Mc2CnC98wGsV)=wI&MFu1O0-4wKTW{l+KTlU{FcuVP; zn+H?Q?n{~D6dP<)bsK4;Mij9y$vDv zC;eyERIlYZ=j|c)hyAWwH>Yzg$R+w)Z|&aj?|$35-R^heU-1vD4ZGito4zO01n&e- zriZ)GgLryd;g%Rb%~g@jFZ|l0XkONa!_c?go#@_RU)N*+$3NAXxLz&?ElS-xhBfBv z`AB+wlR2E0OJtF=DS0nIa&I!4)tW_g#REqn+f`+UA=BM*UF)w~f8CZwET!D;8ksI-ju$#7etAwI)>fUb zw=YoH2Y}c6F)f`+WS8FN{tfgbj`k)oOLeu9OK`Tf{b0kh+Q_=)?q|&hfPc=m?zU*` z!1i$sox)DQF^g~`b!XP)?;a02HxJUma`%DOGp#|Vs~z<*3vJ|s_Q-~TwZ_mBc3mWM z2H>U3#e7JHPY=4tP-O{qZ(rq!2sSmh(-{8Picy^S?w~26e8^(O67z@Wn}D}5K0Y|jY75pNl6X4M)jcb`p^&E!pZK|@sVSR zq@9v7bQ^r%IxiHvZnoc#*=mVP$@$<%N7CE~e4|SX$~J9;%C3jr?1=KI?Q}u_kL+%J zueCFAW_?b`wO**Q#hceZy`G=SCg4<-->;86YtQhOoJi(emJKb}u?yMha~YpUlU*Nr zB;As$O^dTwWP>@>gwt3SD9Q(;n`~L(aiP{WV?O5u7+4?rt}Rwfi_GzY2O!@h>Jm#Ew(k ze@+ng7L5+2$YqJz0H^PPcF@~g>jk}QG^fd+ZiDrHKLXqDYqt87xr zl?d5aRp2d~^%v0RgV?jlsF}F7Np?PXRD%)Exlm3At^1%uB$tg`!L_xkm%qDOs9G+` z<->7u_P7mkBgSg$U{%ZM$<=Julgkr{LpRYBL#(~__Syz&TD`K+Qq@Eq%WW%I*}n_xXM2o`;lq&^p%3u=>BlIgw&> zt!?yi0yRssXdF!=xr*(2sE|Uu#;;NoxsA%CCm_{cwOyE3ZoS5?d9y^a%x@d8u_vtJo&Ca-16mAMXZNyelr#)9X@0 z4rpfvTLg!U{-&q)x3IE}aWz(V*w1>gD$mMD~u=Wi2I-Qu4 zAo<0F3lddz+<`v%cs7r97Y*D?<==^?$~13vukGvMt^GE^HOTwiH^+qesriLvkGxgs zMFXp6d963`UcF<7T$oeqyAsc>8Y=>|xj#{!t~2#wodsjv=xKWFz4l%1Mg6Yzc3a6C zt*uYCcdu<}rzuloD+~8G@3_ep;I*=1&h^dhjfHaCs++q0VeGB#@3ph4)>fR4F_+fX z%>4HzPDm}S{Ry>)zybPo!A7&6iWC6nlkhHWjy4Ve|e5`la>iJo!GJR`^1`lfL}s70sdM zKwS_&^ga!0kjSC&YCJD|{H2G4mqYGz@jxBUON?ScB#pyyrhIn3S;F9?SLY zaa&=JTF!DBEZ3TRmIjlrfWGg4NIf6#b2^GTnMrjxN`3o%xzK^rl+n{?dKRSKU@O6isI&U7c`5d5nr+u0RjVIT)8n7Kbjkzh9 z_tA4iK0$GLOFV(7&F8wd#9OkY%4ekm{@sA0bE(Vwn7icU*wClv9o{Nmw|{^ItIo$2 zXR)`qK78xyTWzE zKa!9D8*V{WaE6!pJ0c|5U3pm{606rZm{+QUpemn*eVKWi{1R}E=NasypFP8Fd+~j) zCvk+!V*)KK=A$t%I8 z$fkYrwlSTDO%>7vY^=k=w6pO)C49hvKNgd`qzcP(1<5NG!^0u!t7Y3wCZXb;spsOy zd$t-hCxz|GcG6f>z{}4(jg8_ieJ}quA9TY~U)TY;=mH})Ek8bP$@NaYGK+^NxUxN6 z7*k7nOwN|~n)w)Bx?sSVEEvzq_;+$;)ez zfjQ4#S{MGz=}ASDO4xz}oEOO2K@rlA`Q{_;Ph%_X6}`uML})oQv7KDbtz#8K39oxq z4fIFKP(q{%z?-HSm9V3B zU+Veh%RO7tJ%838+coZD&*lcY-1F8H@0B4f#8wi!2v5A%Z>M{`+-GB^&&IW_x69XE zUqiRw+1z^jZMQXVXq(Zpb_33U( z_F8iD$e=gsOxi3>wrCc{u^fP3AdxhrB|RCzLvmsBchD@Vp=R1bFA`&07!#PtG)%_~ zESp)F#AH^%6z1dOL7^au8jV(~)9LjFgVAU*Wo2b&n_&#+t?JOO0WF&-3$5p%{d_7Q zI~9`)Vn-EKlS(V7l{V2f>ZX_J3<-?4oB3h*5%448M}r?Ne&ClhlPpOjY82&5HEG#r z&z8$CGY^f}`+Wby>O;$smaag;ny;8mq#|AVc?^3q7qntG(gZv&;3CMse*Oi4e?j11 z5cn4a{sn=5LEv8y_!k8J{|kX+v4uWM1P?{|4E&Q{M*11ji~mjf#plY7!2kVH`bYow(T_E0|Mxx#dc-U(#B%QA zuE{)ee|Mhn!+qX`(;gqi2a!QVvB^|?ws5ti%s!cX-$%Tk;TSw4-!;kEj>wmR2ug+J>G zzXRV3p;!q^el!wvmB2xTraNM=`>(UgEEJp!f1VL`g}CcE4f4r-=f2Z&i{C1X@S-?9 z!XmegyGp5o^=C~>wuh!0W7+iu0bO#=Fh5&&x4f13PRmCLc=JE_i}Jsnnh^My>!JEI z3bdgLG^Prl+e)0hEzxr&h<}l}U+Pov8rMTtQhW|en3ORa{(cR73@B+mXX)keeFkub zt{`2~kb2i4)Heu}G!AokWy(a@=D8+8{3>4s_#oUFs0-BPN84)!|EZ1os_Xq$V$S__ z6MOH4PLMrI@C>muQ1Z@E*H;TC<;JL_{GM*NImTr8?779HZ>+uccZIWn2AX8qx&3Zk zY&NVx+&+ajhy>tvolg_bLpN4|_OM#%7PHZ!H{D|P#TE^hTbu_SohJDnJf?U%>(P$( zXa&aqpS3aNzi4AZx((%ArVY77G#@&c0Y#JXLBzpIeYg2Hu* zUvLw&MxV_+4|D(3c^BX>#5r^(4wm0T@~)c1^Z-`Wv)LyZ-CpS4Q9RlcXJ1Bq$yi?|bGJqIlwIV9*5SNVzunLI0vnfVtg z(CeRu`R{Jnx$|QDX)d7n(>Sae$?uPuug!wKy~*Ec-CWb<7W#YQyWB@lUF!AYQ9hSx zm?`)0$iRxzM#Y^2dd&Bx=(Pq!uPuQ1pD{}>U-w!hZ-=SF4)2B?9hPXG#-_g3A=Y#6 zRS{b17g3MnNQPGG5HAE@Iau;C_-5fcUE=%noCA>bK1f|Yv0=5(>a%SP)baQA*y9;H zlVOrRW=_samHP!~qspkszppL;ONh__kJ5D9$DQfA-1_uEDr0?0rW7l$lN$OMH4u@6 zep&K~3!oj*U@-}a+o_>MO6LV_N$(&YVRa$>G?GZ~2|hvmz{jwjCBJbFe#$A+66_$S#vv0+ zo=JherSzYBa~igAjn{UErMCoQnTB*F5+4`2$eD}^KGj#^)sVg80r*g6#X*-E6t|F^ zKcaWah#ZhTt9^X^=n6y`JR*WN7dB|ICtA)S>;-W9ee3+n*|XRYN`C1asJ|eD`dln* z7d4?3g>iOE`*+&y@V6<0zE2DZN3@R!$$vj5xi+b1r7Um%oN`~5cYk|1yau)@E$zAf zEH&Tv3+yXC*F*E5w;iNGC?@F;)TIDAq=qhp^zipP&#!h*h9E4~Go(m$NH z+2MsH#09V9heq0aK5;CUnEylN@8aM}u|2B>^uyc%N>;tTQH5@U{}Ov&BY z_w&3-fK2iU$yZWyysf@D-fpBbzB$)&FQ@q_q|tKD+tce!N&5w!tBJqsm;o-78v1#< zbV1y;gr*5`7h0bV7@Qm9wPwH%b)`Hgg0roDaX_KHU+xfy$k z`#t24eoA3~Y_fq^>0Di2(mJZCkV>j6lxt*s>l=Go;S@iYqAiqs@j}rwU4N0c_zTu) z!YN+vxiH-Ow8EdfW8`EGIbHAB3sKm!Gw&CTF|23i{gW5&YJMBgLd5MDuM2<03-Du8 zHnp5cznwBhj*rt%C1Zl)!}L?}nCRg4vnzn>8Jbj7X71NIxPN<=H|AV*GjrwXjws?3 z5o@ZAhgt%?0-o8lk=Tls;RIroVk?^eo(MI6l;CY}JeT|i?-u&yO74Nc7XGp^$EB*8 zhKLlQrjBZ)U#sG~w$<8w0)k zyJJ{C{w?A&yqX5v#<1^{&)U2i*6P06L6pCbG!L*hki$ogiC)J>dq>O0Cw)8J6JnH{ zI10+av8c=t_z$z zh>G_B3(9k2W-s|UhUdkwo0DhGU+P8oxn4LHWqKG%V7K|MU)x>7fJZ(3>$-Q+dFM|1|Q^;3wZIOG53o)UBVtKiL1dXgf> z!x4I7<$TcJCV2i74rn8{!j4_+(?ulTrnT^sEYU~Au+5isFg5fPr>P|^hxm=n+8ibHpC;~cI9jB?+#3Uzmm3cjC zL>fR8sxDTB9oKw8Tr0rez37A{!Y0GtKQ?2n5cz@oxthD(k}M?O8WSRn#AY!vmDFYp zyzH`)-V3~?3F($ruVt01n^}Z~TYcKdcYQWMpxAeB0-Ppf@;;letrfahc%C zTJxg>IZydV;5GFUe86wVx>lsmS8^lFH`qiKjibOPa_YT$;2Os?T|?Nny4m(+Zcp!O zISs3SUv0V$>Ptu(@CL~bm#|R?`Hmo{N?&b1+OR|oO9=ZiFZm&;xBjwJ_9UoAUhvg)!$6XY({w35nN#yPO@WAs(DV%T{e0>B>~iT8{(cL-%2MIuNmkW}uU@=^@7I^VvK8<1RqpSw zTFJxvm+l~!xKZ7>ZR5`Yn^SW?<7ss9rvtJOe@sSiT=Lta*Fn-14+_cfsDm1v*Uc)x z^PbUV-kY4u8WtU7AtCv#(Z=fpXLarsl=wP~)7OK}3N~HN`zk zY5J#e9!*&fuN0oR-`X6y4!B9N#dElKPT_?buV#|u`&&%$7WrtV7`w^2=#Y@SX>>lm zZj8}PPmFb4=iEH29HUq^dL3wO`JtOC1e{xD0hVvZL>JAZxKK^g>tn2Hpy#@|Gd<;p z$~zA@QyKyWct!zblYtAypz(Ae^edy4O_3*1DcdXG#kQnULLbttuzsecl)hTt z?xp89@SKdU_8vOQB^io6J-BiSbHQmc?kZ$gG|?A413f~hI=y-;FmipI|JKBp<2Q>J zz#_V=0o-Z|#Z84mSHZy@@ID;qaXXhZaIDyR-s`nG?c2#=IjBYc&hz!&0w;QMm=1~| z<76S(eja_r+;gq2uekG-Po=8>JBk&!^v`@M8Pi-)NUl2naSu)ipqk@GXL_~3jpc}H zAcv4#a(<3?D!f%Sk?sJCxHd9Z>&7Rl&TMp5yY3KQ7hfu){6LAk8LTc#Dn5~|Yfl&?a z4`4DSZyYUHQqUm#C|P-qIb=}Fi8x2hAH(O#U!(-enxus{7vjl1x%EQw@c9fS&6B(} zh)~w;1ixa=EbnqRa|pZ1fk?XsnP@lU)v@AUPD44pZCFH>UqDuP4@tt9Aj97~3-7r1 z2qbWv0dWGv^Jh=w%JSt0`CCK45|H4_}K_iZ*%5S$8`BwVixdqwclZ0V*aN3{akW&D+ zVT>~^JL3Kgewr9K2Omvex33kRH36&@yxsf^o|!M66DQ%ECzrhv=oR5B4LCtNpd#+r zc!K){{xQv^yRk1>-09B`FqwZp4w9t?_Zx7ZBSgW*dCgbB`vbjGaTb#OPvac$^AUpA zT(>`d{YT)DnLb6I>f7e)a_eIT$j6D)6cRw)^A5ya*u^?t2b6_sq zozRf)Gk{J@w8Os(zF^#&@H1T;pgKqj^&vr@lGc;`ANmvS!ph}GwO;KK20wnuS?uB( zi9Mqe!8i9{KfD6j-T+DRgrvZmX*}XXTa~^Nml7;#V@{mu1aF^I1GsAXm_iCuL~kGU zNyRS3FDZN;{GHw##5>V{96P|Iu2!;LHU)EFqH0Uem4B;E*AWnl&S_bnD{`@vm+3Bk zZ)B^K3YYcbx7N$w4n<>EEYel`P1i;!vWl+_+bz0TOh~RfSM4{;5&CE)>vF0eHBQA& zcx8A9bNkDj433y(O72W+N$q~2AwsKH9#B^|T6%f8-ube@q6BG+B6zN>icnW0;EnkV zN4e};=+{!K`=*+it~U3hs>z!}?@JT0p6|nJzFawrK)h$^38l@78O_Md$fXv;>k+b0 z&87J&|LJ_0E9Ts$Ku4krwP+oo=G4&D&`N;Tcr6tXe~?~m{B@wrsX5Q9hd-tJ z<9P;rOMj1g!o~jkRss&_D}&cKRea-)=S-e_?32+LA5~`W=;4nj#;}vI4&NE6#Io}D zkHJflkCEFilF0W&U?FsJM znC*0{uKGO5R~rJyviMG-uZK5=eA=)Eu@D6*u7Amjl9=TE zZ6ez_zM-0mmNwa%YHn7in2bBHF0d;iteaaT>+!Ip1zgy)RGwgc! zh%*=9wnbEv(MkMHod@oCt`NJM%Fm~Fo6VykoA)VOTTQEKH#hY>T3Z19Xv9Arnt>uB zR}_%U_vU*d{?(27UR%f3jV-mdK$?2Euxot}fO_E6T9rLpQ~n`t7i+$u`I@14w!^EQ zlv2*{M!hE-d@nsGJ{LZROLOCM;&c1o__-H5EK#FPsMjPPN}tJo2>V=q6z9J*-yx?q z&39Hpx?uywF3HCE&-cK8cs@ZX|aEmpEy`i%1MQ3?aPQX9|aXS>e;Z&%U}; zcf;m~A(O4&G;YudDW~0k5L$I;L}ENw=1&bBNp0A4%$*yb|24!`MJPGzympcYhT9Fkd}dr`x69-NHu$ZpH68xx}k@wB@|hE=2vhV}`IXqT8qM%CqhKoLoH>ay7ix zce7bCe1s8gxR)MI4atbwYV|vt`TAe#aa)4VIU7-s51pe@LR{1g;v@b(bSmV!ims;l z>HMLD4)<^5tB6QKzdC5)-bCbvKEmbsml7_2|7NaZ5*;6bUL%3ogp(*y`ytRcZQR~$e2I&hgDH-0T?#r(1%pS#HD;irl0^CIZh!y}@D zbMmi@nH-vW5%Jqx$MP0v!-Gq~Q-HHnAE@K`Wb|7{i)cLXay%JB#V*a^h(t~u*#dWP z7=n&{2Ek0J2D&&{6GHhBC-Hj*D!}o}(bqS}#7V~Z9qF~Pq$w7|NrT^7@R2`HVhb%D znKB&J(xsZiC+^(=EtfHZ8-j2u_+x?uN&O&!`+em6u6=bPWvL&>_-fLWtkWE7PuU); z;Wv34aUbnxCEBHJ?q?FPagFF6)jw7uEv-praP(fTf6gMqr1DrZpTqr-e0U^BM(**S z>Tz%WUC$0g{fk$8Srz;ztm4AX4t`#Dti`D!?rhc%zUQ}_I<0JBUdKRB7{=|9gV-UmbMaI#@z~U+|RmYc=;D{T6I-V*EaMwiB#UlzeO0i7mx3jmixi z*QaXZ6|?}Ko=V%(5epq+A&b`uI9lpCBoX6Sc6LAp0Z9$rhB&AM;vxPgiX^}AL1F}J z%h!~zZ$|E;^j&8Pcm76eTnNqInCoZbPo0xa&_VW&5{#9CC>m;?u~+% zZA-_4;ogoi(16s?lndPUV7Qi#RiD0#4EjgBe`kzMI{UW#0=J^5sXrum|9l+0g(1kP zkJeh|XDCB4td*Bmft609`xLw9`c}JVywC1oop~Jv^b6%`nxV|ZoktUveuHjbH*x7* ztGgv z&%lc^$X1+}Tp7?R&w*cQ0HZyyK*bhu{vxLDoD)1^@^#n~H-TsNgRhC+RqIT&Z{4bO zJJL~K{Cll;HFBdTcesUkc->aSClc(()!@wDuZeGU3#a&g zc(DMn@qj*{UZxw+dUmf1t!uJv!+nyFBM_nVHf%t=EhBWP`@rAMA;NH_%I%VtUKsr@ zu9R|)pJzY8ydtk)y93|vKWe@xcTBpr>N3rPr72YC6++#x|Izfq7^evz!oOo1d^@Zd zVQT2FBP>lRPU5bVZY2-0h5&8(V~uH8x~kGUm2(2-cv2A}2k5azlUF8N#}1Wsaoh0= z=Q3x8AB_Ay!C`#W3bJsx&i7^D%+C*#a26MF$IFeWZ@b0*dfdge&3(#+|t} zkxT2TAt!oD_6zBr{?ZS9I`rzMSh1^6nN;1a7(G|De65ww6g)M+LS8gJ`=k_`f&A7&a) zG$lL6_0Xz6nC9AgaBbYf0p9z&6r!`!nhV^>fc$TO3=Ei15!Gzox=Gz6_+Qy1%Bt zqz~w%V>G!@73Y^p*L2hdz6d!WHS{d>Ai6ZRyq}sy8I4GHib28(Al6*G;%d5975(DX zX6m{b_8Y8p3^(|IFU8&iH`By!R9*getm2}t1-dtb6vm(4^!rUt=zYNXT;xz8!-~~i z0pPZEMPLjgyJoWqbLaA8Ealr&hF}5Fn>aT$W;$h+s`MZ_bQgMa#d#9U*_cSl`{T16r)r9qzyf zi9i%Lq#;fQSevwuPN6{I*bsa@Tpw(CdW#P_ssPRhY2U3*Q&_`W3Hbl2mJY{S2!4S@_5Ap?_pRFX^K9!a;+u# z;iy_D$}6#c7f$?VEm4?F{q3osE9m6C^Y4XyYkbfXyTmR_GUtM3$+P5J#$>+ZA$tc& zc@?@Pe#asFaE8U?cvuBZF>+1wOsnUSagB{8MC(oUu4viRJ9X*7TPgX%Fmsl{bK%nc zhm-Mq@&3b7?PLe;JJh+H9#=i#PMs=n7Kg`KPY+Xa>9E5)g&a#^;dAmE5U)$6Z%1@O zy1+dU^^n1Eb0xWm_V7Cp735ve@zEZxmt26H(TiNjD7%0)vyd<6rF;1;h*MKXvA6j= zX#HCP4`b!?`mgRp zR{@>H|66g{mT1nB94}cHyL~l5dSxYZ$?{G`v9W4gyf?7bExr{}EK~>`1p`;L^x9~v zGTwbI#^zJm@M$iY#lH7V@S&k-);*8bYF)4001fd#*lmehy|>i9EZqdHV1bwId5Ydg z+eZ{u9a4&@RB^ebSRO39`r&IkaysS;SE~h+CWcX_G*bC4srzf_;3x>sT*HIfK<{GIgqn%B7# zvWC%{f3e))xeqtp=wD@L?VEgiVQ zaSxZk+TgXpX17jyw5AMY%SHx!IIS9n|Ar3vt58=@hi|B$Dfgs?uEqUU!f73L;%>+* z{LZJ;kUupa_2!Jod{t}t*aJ~kngvV$W4KRwuL62FqVwt+K+gcbr>JG+VYQ`EOcsuC zdGgYnlhGoQTwe9((mco|Z_N`s7y4hXVx5)rdS#yfWl8AlgO!!rS~a-Vhj!b1G(9_x z8??hK)c5g+h2N?IWs1B$+vVew2%ZCoCl0#YY(N9+Ot{+jlEOeAMQ^@ZN&S`izV=B) z%3F!xV1_Q6o+<5+N|vZPI3m41_pN!0{B!-U&lVr+g)x@z?;^db`L>aVi$kyRiU5!0jF zKlyI$)#|OaSNmoVd!m2tJYVr-ZKbxl5+j1{7GvTt{Fb8eKci}VQVEq$i!D(#)>4|} ze|63b-xvKGe2@DF{Qu^A3-jf0E23aYY|b^-Ha1NSmQL4|`bvGQ)Usp-eN(y5mtFK7 zX!Z@WzNHj9o?;rcPckX}6_Zg%0B6dy9Gv{>oV$e?zTwGt3mbfWljn;6=KFO5!Itb& zoUtXB4_-HL|7wy%&^XF!=NXH5wqh;REJD=dqp4xm* z=k1*aLPfxVwE9{${BIlBnjZpTv%<4N?mGA*Dxe@FVnOoJk9SsR*D#$p9!hW%!9+c}` z?6^KZsskkV)nz}wxbT2t(dK1|4Mw|BYgKbqOYi7hl8ZG&mgo{{F$Y~Iqyai%Ytnvw zs^#s+7v`USy}&3o7_91YcU)=1KA%u2Pt~4|DF)StuL+hfLoI)LH3xTh&$skS$28ui zbs0#PymRv!P-xpu!UyxNUV)?Cs_p_9ltSKF(||qX1%ee z@O_geo~O-SJfOEOPWGPC%U&z)JvgO@wx^e-ybXW0fjCZdl|R=jhF|H+RIK-mcVnj# zSI(GnTE1FIj|mp4l8=<}uy*`JDO67uJd=2)R-S1%Ezi}^F~v+#Wms8IQ>H$hxN>Ip zX?c;7e$T%eRy3-CzOQ7fFBbeMVSyZto1GF^GTe8UZO%aU15+C;A42Sw!m}m~_8@Z@ zwH%gD)fSp>owP_hU{CyG4JUKi(>1=Vv@L$**nK?@_uQ%Kv%juR$i5vn()iW664!2! zW|35(nUhV>#N1cAy(iq$sAgxksKwb|RlnWyb+yxqT9fB$p0ZBV6lBkpZmnU@Z$YhP zss^>}**BrBl{i0T+QN-jn*3}&zDQtY9*W@!K-%SDkll#C|vZz&-B7ZKUU` zIC*2un%X&PW*zO?z?2V>G|@jNgBk zjQ%s^IJN?|mmwDeC!xuosx#J1GHzJ&A32{|kKsnL>#z!6M@^AaLWicAaXXuPx8YG?uenscOFf%^m-=izn{%7xQ}J$l_OaK6Ys}Ns13f?JS*>1? zy;+@u)p)9By=v!hE-BG0vKDHJvY(Q^R#RfVt%kz8d!FfORtvBi<=J0SJMq<19D2?? z%?pxKMevN(RVIyZZh`asW@)!!7Hu+kM@ubHcf zSPL{0v+u>~Y?^ph`k2w=VAWkUhjMiBHd<@?gSN>esm2pC2Q|(;i_;~hgW3q*O+LwY zQHciUp@^Bjptjjn^?lpko^SNrh0%Ro6)%qNxyz%g)Kq0Jho}8=_oFrN@daIE70YTA z!!Pv~>>uH1OYLvV7sKK zTuDjGFzgh)JO|zF@GlE+Lsgu5`&H&RuCGyeN!A3@8ZH>rw6En1=xyrDq~w72m<*~#Z6cfn zVyq%iry9v{_T73` z9Do-ihwp&?xKz=5LS1g=koY7azLBYQ{>`k)#o9j8Qf--f+|)+E?Gj&2bIrSn!IO&( z!--1pSiS}(^XoY)CSkAHmVb`YF9+pbQ8)lfp9f0cM$H*Yzc5c^fD7mAe81_V8EJ`O z{Q9Vy^2XtYo~dHoElB-+<~}YJTzumZa{7;(k87E;M$x`eqp&x(xb?l;kr?C=h8x;R z(x>GQ+yQl2<^a9Z;gA8z!h_$RNfw{oSF?PC{lk4VU;HobtC>6U&-c|dT)eM_=8^n2 z|7X1Oe|ujI|8AM8s>h{o*5+n!>%spua!ixmjQt!0y=_qoHFi*7%k!&h@-=zcebTa; z=EWRtmt;@*vh10;#Vos;&iv~wm_Zy0&b>(##BRNLy?jFh*pZ> z{?JT~(b&pclotYZJT8Rmu9K+s;L#kp02-VNLrYSGn+S8{3q!5A6_QQXJ`%e^zo(Fd zkQmZDtlPUt*Gwb$e{bCb1EbNURz^|g3tO&at+$j!Tok@lR>=V*3wcN~LI|&;Y;J#w8h&xev1oA`V zYvo`S^HZdu>oBDCTz-0iZWVVaav9JA&&I5;t_$}qU^l1_-uRgFWwvBRnf;x>C6{Q5 z**{dvUt7nO|5K!Q|KGl=w8{T}-&M&-e)4H|9A4iNk>F?|^1JB&?z<`xiH(x)szl`C z=>Oe!Ri}ZO58;4rf@APqRfu!C2kIeVBIwx(x<(`>b&U-6j)cooRcE;M9%c1O1L9Hi z6B=e>$9$sFR|;7^>ORr7G)5S^M6zcv0;@y#OqI(7nI-EWEsdf|8J0KEZ)W=vku&k7OxDd=GOF0aiO7E@ikPgk z$(as}q=KbFKg3($Q{0@0yaGR@(7jpk7Sg>CFK4{f!jw`T$K#W-JIK1ESRasQg?kU= z-*=1$ibvkA==ce|8qcU{aB>}f!}OXCM{d6=Zw@PfU-wHH*O?x^aU4F594SC_XhR(0 zyU4m5fO3%gb0A^Qm8_AtWy`bKd@;mb#^#<2ahIphI}-vW5r^h8w)(-ZlB-8k7|GF6 zUYDfv(DzMPKfwAB7+GCVTa)R7hq?iSRa1SfQ;j%9-Ya*SAQv_Bwy}Og$$F>U^%eHc z=yO(kDKq~k=x{6Ak(<=&eyh!MqNgXUH)gQcq5Zr!R)*aHXBn34$><5oGh;r#3XPfp zvh_mPI_g~9!ff9M0lvJ)5k7k@P%SF-)bHbZYto{`*>B=zoRMwYb8&AUeg7sLZX8}5 zylcIWJP4iuVvFv>s>x?pok%Av09^yOEGt^M|_&9`A+5=K?_xp z{Xs}>9rhh{4ts}v9r#N%p6ENO-(6OPOKV@t-q83BwT6=Ne&j;EE0qJfQl0d4zu|RF zo}pwR)m8Vl3VqH)56uhbeObtnoBSmjPVY_R`)}VpGx2WW7>_bhX@-5=68inG@Ba5P zHGfkk(%&OW33)mWHJ^XkrFnXmXFi*@n520>PLS>vanj&HoUSiPFnF8&$$7Vrt56kw z*qF=-xkz zocYPC~NaAq#HEh&O+RoxP}*Q++pG0MujF5E3@D5eA$vEA)p9Lxak}G!8z_S!lyK9)Ev+j?l%t-)x%}61Jt= zRQ(qX{V3U)xb_H#XbtzA(>!hV0m&Bjj5b@$=#QI6e}Umhyon3Ho#cgL^r6kWK~x`U@bP6p6vMxq_Am<k-p9A=C?D$NJ>J?c5=06v-{~kk4Gkzfa4vQQUUrKMJH82fr8 z1MR>jd4UP09|Fl!V#fq z7Fz^A3oLkGq`pZDkI8JnKSI(i>lm)_U4^JV+MP4q`_hP4DA<;Zl)FdL%ggPx>%L>o*S)X%WQ*yS6)QtUtggxI>%j{B#^}=*sMKTQvfRR8 z?xv|H$F4kZfsl`jfpoiVx*576|P0wi$*o)bKJ>TSeCU94A+Q8k8%wWo@ zVpzrzxA6P1W(#qHL^Dsvyuf8>+1>E3DXaNPY_>4#=ip8D9vsfqT zmgpYrmn7TJiRWZJFj1mve2Gd!YYaW}_U5n3WmZJ-JFR&`vm0%}%=dx z3-68-f(_9#u;(Ezig=73&t1ieenajUERAMhk1}iQpl7(P-RL(Sbf0ha2ZmcfRf5as zPw%I9I}kJHu|u#6h&(lp-ZKM3F%DD> zqa9>2l8ZNh!h*CM*gl+(g#zYg=5_*&Z!k1*g27Jx`#N~e0CI9VX-8%-aN&K@o~$4D zy}g0FCm13SGUe6!66|`7T==6X{6iQCV@Y_0fA{`--@G4z?k*WQ8)bzhuzYzhs>q!i zq8x8?7O?5p1H%VKU_qGOifExx&aXrY zvg(y#S3s@Tgp@M)i%6h`8^_^~VX{6`(IhO&GF{EsL~!}T&1&H;wuI%k2wT&tZHRZ6h85&b zV>aA_-;{^RbHdAGDOVMO_q{NdU#GolWFwuwKbBwrqxwi6wL5zixa%D3+vt22Gt)OQ zMa*hxoGT=bJrNm7QY_Kds1jT=7rvXUsqp(4N=bRpyYwFIxnz4>O+3afL%b8(9qq=| zXejsU<5eZVs@@Zx|862w}R)Lcp94Qi$9}m zZ{i@myW5P&tt`{W@_D*Pj-?J;u*4R&X{| zNF_kzg?K1~aSpW_?UMnAkqf#Q!Q9QR9*<-v5HrFShKFPhTmsRd-^BkZ%52!R75v4w z8{1;Cn$2gKRgXI_YvjVRXohQ%o!Qk11^ZZP?{_EdWW&AXtAKjmGm8!T(ivzAr4ptlWJ5j3e>Wnw_4rJthGGbGtiVR*+B30oo;4DzYA7f zVi)9{=Rv)09Q!ruO63pt&MugSF{xrYcF(aHc5XhkBlX6uS6P}0eXR}wRQLW8hBI*3 z7RbKrT1Rn+xTSqV!@h$OFI(qR77vHAwH8}isG)qT^P-`(oKTHU^uE{KWBHd7n4)}m#|H2 z7xro8Qv~Wcf&4IcU>O*lgmT8tA2UkEVgXXTrb7W z0S6g0Z9k=fM}%@Ca$Gv_|8_)XGi5Ed-NdQfBW`2z{;)xsi`jq+5@VeBRRhI zFz=5=R$`Uco}D3;hY8CTmM{V6*=>?UdHzDwx-cWeu{1M(RB1h7NJJWADnapF5oW+L z?{@EHjjD&!!ao=j#hn3K`T6cd`#Yc=~sEH3(T^7&`M z5mDc3mw3xWqyYTw#5cdam-EfNt-UTFh18N9=yt5KN~}q5Hm$ZrLNkj0HL%N<>PoxX zd;V8yI z_1%h|p2oPM8KJv`Okb9rw>d-gKF(&x?0;O^7cLDgtFku9e9KnJvA@m0NKC+vgEMCg zS=jtijc>05vIN`Lp@R)Q9>1xlPA0&v&8sb^bY~N{_gUD2(lp;b#|8Ld7{=a+?tg(& zzB_ro7(4rSLc(N;;YtDH(u#7wC%S=4G8b!5o`lU5OoHp3qJ<d1F4SeQVx91G48k)I`)c|<%^^Q6aGSLb=E zuCC6?=9bOya#oXfX!{TApQ=k~u0O|HJK=Tg`g6sIR!q;Hz%$s5 z&-)@st8aFq<{X=s85Fh;YSKgYdGZ0yLiaDkmz{gC=4gPvt3gj7g4MZ~#UF3aFVyrK z3upGrKqX%t%EaH@L&P`V?P{)~b@cs^v!S_WN40&s9}<~1tom$F9C}+cRp=0vCKX`u zN5EoUOn&$OI$YZ@^J0-(D1GqMkbp>ul-uc$*VS_$&0oR$mUt_uGz*;^I(J6}+pYSu zYB2p&x<*5NGc2l~DMk*O!?DPkQH{U2Rg&Zst1)IKa(XuO{hEWIOlL*4d3`nPn_kF# zLFcYJE=b#*^jMnx}QxPn7<-^kmkbv!o->{G7P3h7%ZgmVYN>gq+%D@7*yT9Sw8}f+#l@2C1I@*^xoB9h zd1ZcMb*^12Tx^v4pY__dD*O#wb?l0_t~gojF}aVlb~l^Q#-Lp_ndYARvb;YP?bt6< z3o{|BhVG!9&Z;H*sEs1w%BV-)8u?&kY7TtwT89(IwL~K;FduX{h*nDfnt9%ge{{ZN za;^+-|5ZbwEgw<&J~2L7|4U$bo*JR?Hx~PW>j&`U1zBXUVI-f;UsNQ`fl}D#uwdOt zkLN%`k#8sL5FZ_~Vy$AK?jahh7h>y1ifz|~&h467K@NCQ!=^+_K-g4pXSTM2EkT4Fipk+&0ixKPB!{d<>&=~dEo`zauPrdV-QTMZvdk{r^o{9E*JqVJtaf9*j7L7lOp~1j<{vGP7dzNck7!!#^sEsd z`glHi61wt##Co)NfP&h}MA%Hzy)hV;aAsy)vJi z4XV=EyXnk^DDb{o)%!S`Hpp2@ShXWH{7hVcREeIZgaka5zb%J;)e0G~;4NXP;hW;L zySf~)QCR*MECW)ZU6SKXM4S!(0`JzU-ov}fvy_YaZMju|Oi%!~ks7wgX&=oBMnz{6 zFG+M>_0=lcRkf+@>3nf2Rs&h_j35VZG5n=9jx{S%YT6844!fjT;)~=VO--kS8U9*i zX1lc;Pd>-!=ZnTdh*!zJ#=0oQy-XyN(0vq0kqu8n@8eUc#d#Ke_`z+Dub>Ko4GkxTd#FYW76nFyepmr>F*2>qWTno)Vc!5#K`cT7NhEK&>lRxkYq6zL(PlM%c8TJg^ zl8mbMzz#@}WUwDM*>lK>PI#WR89DeuN<>tnoZse-^cj42SN^ziy^q0m^D!W;RnC5& zyqqa3oQ3XxP#vMKB^$do*f*seR=1`f*7$Nv_g6j<_;u?}l=m9;0m{qf7Nfk1Q(cat z{#sKC>kN2XgdEtq4`k)+542#$e9@{iQQ2oQe_*3&h2aOzHO|$}mjm1*zX+6i_`Mo~ zZ12WOuE-EXJmCI9R_ByKSY!NO$;EA@P6xG3(2 z^)jVz2X{zugFg^u1suHR9Cw;v2cm%NW(!i6+vOej3+pzyAn*2@a&!EF7g54xIq)w7 ziNCCCf2F*8<4V<`c*K`f9mQ4W^MNwNG<2_wL;uhFU(WW!tAfh^a=-?kPrnW>!LvW2 z)#Z$BqDYm{$U*KyxPsL1ikQ$=*H(nuvUW3ighN!~TA=zjwiUAjt!;s1B$9Bqm^YF4 zmDKP@<5*Q-%d<}n?KGuclDeura1dHx8F(=hcE`$~&htEjr0X!(5r=#((wE|yqs{UD zz&j@;FYPh!KfLnt;cxm&!A^i@o(8`JuonHMOp)>8wu?9gzVV6v_>Cjww4{d*^<;nC zdb9jyAorL*+sHZ=vJtV7QNG-%H>F&&jk_JH!Lsa2!8f;~-rE8Ffn)%b_PE1(>Z8`r zrE#HWZGoqx@SZC9LdHcBmE7 z)*iE-RoE()j44@!>%4()hq% zhi!6vaNRUQ5bN8U|iMs;|9C5;Yu!sd~8VQgU3V8nE8 z#J%fKicTZxqYed4jCH*t7J6W(n71Ay2H5VSvwY10`DvWNATi>*9hUwfwDQ#Wv5eE$ zn7T5JbN)|cwes4OSxzPldFor{xSwji&@8mTG6du2&rxY4VZWH@OAVilMzLp*x26bg8!T?%lxfd*^7c;7jBo4leAL=jk6FaX9F>t;WwqKx8tDU9HV2DTlBhFciFk2BhG|tU2w^093 zYiC6($UXz~Xc%ol+!&Q|WrAmVp!m>+`0BUcyiDqwsh(T}KTFhqQ$6>|*i@N61a4rW zo+mu1-zjs>e|dj;^e*9C(hFmg2Dj;R8_73|w_2wJleP$hLSB@pwTqXRQ$b)Lk`gojMI3$`uDQVSA z!J7}kj}T`)hp!&AH{95Pw~~>4kTOvH|7-k5+2l3Vm#`xC$(WFwc|4La&ViYMe=SH0 zy@>6mDQJaH7xKNp9byl~BMm^cSeW9F9OplbxrEJ?p2{q*{BWu@HLMt$Zc$qc*(S{R zn__C%XfqZ87D8_Sqo$tCy{6V!%Zby+!-|$hLi4V?eI7+)Yxk|nxpYZV;s~BTyL{*Gi+Rz z8@G9~mF3twyoUATj#6fBX8P5P)33f8zj8Xq@fTC-zcADJYL$wR z3+NX3 zaLj!m^Y6{b|>I7?`D$8=d&vo*&v_L1`i@)J$aXC29}x?g~{JU;V05tvdOo+ z2~K#bPOP(e89Yy@VFSrJ=&O|DXxw}=ec|nYFzn7r7Z8LE;N=g&7dXmVvJiLz_}NQF z4x%;SKU$(!GZ>zfq~bb~C}D>Xp^<2rDCt3|)z2dp>BJRmWXlPG6*NPn9z#ks6v2ym(E_FOY z_r@bxiE-@q$PXd)=q_L}sh|FaC;(JD0=-OFrB6KHHu?P6 zqlM5ijz`>4;s{owoYd~rZ#>)SQJ0a|A9um<1_03s!)ZyQ~H`=??gV~SK3!N+aHv`-fq#;-b)FpDy6P4uS z8}lWo_Q*Us_b1}bl{44{&l8^6Y;pE;E7$`5>@>&;)u2Fx3~^U}AkzFzbG3NLTM>i* zZhoV4W4MoYVJXP(e$QK;i8tjm2j_DkdVgajy)918E9ws#O|UJ@Rfm4)L8KK)B6>P$ z-n4O(7qrm@Ov@*tZ5wHWm{7!QTg>q5)OqDR&xhdrQh=MIxi#9$3A!yr+sMbaGe;ZJ zyK+50@T6A@o(J83bA!SmY6{hQUp#6hO2dRg)Vv*YDSLFW;Tp*Y(k~n%u#J*kbGzgG zWcl2nyW}Ir+pD=s&WOIqLMdSn)<&C`%U2-xRFsDzvP@teUV&Y*PomZEoZx}yb37sX z%2#J^rWhlX-^BCr$eK9G!zMhMq=Zj_qDL)ln70qa#t>uHbhVrY#g{E`5h2dvc)Fy3Z% z&cKJi8ZQIBQ&DAdm$+H@is&hk;-4SVFtiAC*j-GY16%BDND<3}*{e|U@F3)Se2~sI zM`yau-w5x%SWh=u&aX4GEZA!E;br5Q(tWbELVWvmz{GOVYy_;LVU!@AWq79z)Hbwu9 zh_>9e{>Cao^cz_%o-B*nBst@Ts*gN}J*x2HsK;~t)mIb>q3c}d*K_ceeZ->%V&XpR zldeVl?&0+Z)|ZraUb)6~a6>nF3W0wSGwWHS3x5F0KQY2?9EZR2;!i?++4ehVu8r6Y*(LY3qbM;BQh|=xW4^9+E&m2n1-h>-@UE zVK<@+-=4Tv`rV$`As+E4VTDBRXLIj~+Tx-9gTf#?ZRf06jpCaijQ(x~ zP0riQ>5K5|$MGl*8h11{Zo|Q0>q=vh<^_#S+JU8E2L_&RjMh|JLY|AgXIM67#(osi zFmQ`}cz#UIzLM6?G}t;sBl}_;MrJZ{`xr?Kr2P;0Bp%ib28>)A)~IH1XLhTy+Afbq zF2*=Byb>i-&736~X^n$(>wD#wOiyX#Qi`u*#H+mrE{gbmdIsLm!&TQxG^SOeKgr0y zu!>KtYx>?B9M`T`V6Am@IF&W32b7Go%QL_se2G1DS`FFi>R7XdXH$NeweTM|?6!Fhx@$KP=S(qe zY##rnQP5MGV>F*TQNGnD8JqCmMs;n%*Jf(0dQy z{i(c&mrjB9>y>yzrPA7!W5)S{ICjVIb~I=p$#_d9J;7PFvcnub=i73D$gGTNICgc`lGEIPGbwWB?mB^Egu(=iyf zSSaezRJ%{*^2X*?ta1}&nOL{vOl77~2)`A;oARNws#wH?x~Eq2Zms8D_aEIW-DCp< z9;9!z$86%xnB1eHo@HW=^1(HpjiyoDk-0w;TN^k%-1LJUJHbbEBIfsgthGv))no7| zs`UnEHaoN0Xl2RBe`1$-qVg-$W%>b(Tfy5qs300RgOM*41xhdgzuHmoQ$xno06<$P++#=|Llj?;k!~&rFuSgfN*{E2 zhD@n%t340E7n-U@W&W!t%Pk8(9cA-Gpg;~?`GM%|d-!eG*P$L%K3HBzBV3LB&7zoq zzBHIlren8a*Y|Of#}V-VNb76@A`AS-3dBN?wUCtV?wpl~)FMY+w#Kuxx^-Mhb3nW9 z0Az0qQBHmD{+v7mrJ&l@#kK1kK-}_3vwIzlm7hv!oWL8(@O&+v)BF0qU*kS_qFMB& z8c(i>XQk=ZIdi6`_ycdP+nFOPnXdK2#_+9m^eu1S2-1)CIt!A*l{t$|F9#531G_HW zy5|Ec7r-qDd)-JQ<}c%)V^2VLN^>?E3L)o}!OJ8(_<^2HznXODxuI#R=6Jy41+(x~ zZCn@bj+@=AaAwdfIJTuM;AUGUjomfbanzXs@%twmwQJi zTkU!9LBE;H%;ukfp8k~6uQ|l@m-H%fuMOV4naxFX2I0Ww`W?=k^k7)XErB@KAv?_p zwT_-0${|izS{NO;%!2*S=z$$Wo1HnS-=tc2ik`~wR2Lpg?hMqo47ZpYzMCTdJ1IUy zik=o>M-TJ>ut+{FX`ltX(=@2cIwNdm9rc^FSicBcng)s5=E_2rgIH3s@Wru9`ZTV; ziE7t-Vh()GCIvV!C>l9yU)tgDuSmjLI}1Li{f2iz*GNAD{?L^J+z!RCi2<+0UG_mB z$4fXK#Z`r9p=4|>=GTczYL_d}Ce$`08-*=gZf;P|RN=BQWv(%}Lded>92w9dmn&n* z!f5}=Kni%OOEIg?z(fACMi^83=xQjzEt0cd$JgMONBcG*PbOT_JNGJCowM#DG=8*` zD~4B+opm5rVi&RwBK*hCci^_5Kfg=SIIMMAz}{A zsbI9TXGLSd?z{umo0)|zHn(H7SH@Jip9P(5J~T4jpf@VU^-T zx^UIF8LLLQyW4t)XDw(aQSnM}#hkFLRPfe&`Mo+{kGI6bhhK`xwDpa$l%B@d1+J@> zy$No?+{n^~8neJd$%=HyTaLb0_1l_+tqo1}TaPyNY`xetyj5Toi*m|~Vb5jq^4(nd z5m5q@#~UqG)b6J*_4%@2zApx;U=sP3%b z?#=fdQ!yn*~IV(oq_2G2N5T|1wkzjU4PUK-BV8NwTDxH3xLzp@g{wSTXdG zyy^>aU~;b0*!Ez~yFUV()O(LqD?-czTRB-LSanKuQYMwTmBE!B{%CmNrB(~;Z=?Eb zjPJoY;i^}mMrAmM-^93V&xaU!AC6nF_7Sf57OA%MtXirqIR1`Vu+#)L@5YHbUnAX@ z`3XfT2M*Z6mNbx#fF#NA6BW;_qPmx|4Afl*|Hu?g=*{TS$+{nHJldqOrS?b7|FhmV zL*q43>n|~Wsoqm{*3Y3jQ#?gh*c7~HGn;oiw2@Tz_hJ+MNp&Z@bZbJkhZU~*AGJRp zv#>87gw0@Vs_p|Z6{EUumg-Jp;Zr^3z8Mkvpu=OuKM7_wvEt2$Xt%b_ zR{Wy@laDX150ybzxvVUQW%!u2q9l9anZRL4&XvV$LK~V)O&UJK+1=FNlquIbnNsh> zE)`bE@GIn~3~3?V=>%0+Gb;1fw%Kf#56Jx4Z5Zj$F^9_)9kRz1`?rI3EE(ADQ9~cS zAHFKoe#1@4!lj{IHCb2l|RN@2S2Kkrf963f#Tw9PGrbwM|C0 z*U7=hwf)?&%`~Q#0q>BE?2gHY?t$0hU)}heqbEo$cwmfday}NI16cY8=+8eeE%%&; zHt-43WiI$#=wq=5dQQG$zeDWb)>fYbPn~Dg-I>Pk`ILpz`gP%0EVp##(wQ@NvL&AB zxnBj>dZzn67uAJYJo_}(_E68W8ja>pe`DnpuLjh`Ukuc`<{I}qUik;_|JVS(>T%aH@?DHjFtKn|;MR~yoG^6(PRVVBIhZdg}Z zvzv9UE|$vi!HD*#q3LsxS!}KhZ?*@B^3eMuJaC*ehHok7I_yikM`Rd@M@Kl^xmX?= zkxRC7uZ{eEL}{B2JI30kv$=dRw0ubQ(#WyRDe$bjKWeBZpT$7vhPO#$^ExPmW%N>sYL-Wd`VoJ$EJ}2aR)yJE z6)yc|RahzA|8`X7p8!0X4&EfbavT*2**3nK6OOj;L-2AZ#C&?%<{cWx%xu@>t>ZIhOv zC4xMYFC7eYIUFm3Kmbtv6|{nYPlnxx?J8JH^lTd0_|(RNx*ydQ)Q{9XRX5U7u<@xK zgq!$#l7pYh%Y&togyHCzc9LsQK_i-sd~aNtYo2Va#b}rHZE~!z$HruP6c~LgMlYRQ zP5+3H{gXYLUJWEE(N+w_ckw$gv-ZD!0FQ0Kg8E7qwuzj@7BT6>kHrqV6&YJ ziTZ+|817x?y6@O5$WGze0;PKzJC2NC9oCq%;N!p`rUvVGapnF%{SHJqk~AZg;Cqsh zCzJC$ABe&(W@`v;$hGX?Y(EZZi@)k$QJt|Ojpf>nj!#2!sU)ML-;POo^I%k!TmEl2 zv)JfI5@+_|=oDx6O@`*LiF#Gz%4%Va*6Dx66v}ae{E^~|D#MwIDte|Mbxe?fQBqii;GBaq6`=NUt7ZKxi zM}nT7OPmvB#qUc`Ih%;5|A_WuY*87!y@rBHrwVo(B^yYmsttb;XF~ZJgU|rKnHZ1% z;q80cO#C$Y+)h6_yH&PFmMh;ow@T5T6+B?gv7})Kp$%V%D{^5!Wu8-GcXYIIrjZ8b#xU77(FSkm$AdDK6!jex7eNaKnjI-3POq`oz z@&ZDcrF5m?%7`arEUn9c^Q;(Tu-1C7s=UXW=CXRvd*Ru+drsqz8p)ncfhZJz8CTQ* z``*fxXEkfXZP-o!7WI7>v~U~t1{d+0b1SD;LjE|r7kJ}5ey^gsqMX~y%>uft#>iw3 zC1DF8Kc??{9CPniIJ~|43Rr&Ts@s|MPQ;7+X2c%{ufqYGFSqFjXyjg>q zgoW&~BvJ@-3`D z?N?g_ubKVG`;>RY%Z1}fqf66$z>7Bby32GOS*@^aMY{ko*r7X$eUG5(hSkI)Y#+Cj ztmDJL8EM0x#fZcDZvGnA!A4cbUqy|7bGfOND>F4y+*YDZ)TTF~Js-j*`3Z~_$g{SQ zbc#oG3eKhtIWb4LAiQi3@bl#0b?aMjZ1MJK5lf{AT<%q)8(Ub>7r`$@#$+yejfwmn z;Va;<{PHJh9mGz2YK~yMV;%leGSBlhEZso>)3|=!unmzCZ^&56Dy%(xn#4mO`A=Wbs%{M`Q8 zm#H*4IcS(f=(Xke#F8h<9hJ@&SE4CQ|b2OLnCFXH#FIJ~_qUju0} zmTt7|$-Cr`V$0E{Cx1rT>n}x$D{&8~egtEJ+92G!8#c0<_CG&}sLhsXOHR+!+5Lue z>!98rP<1#xTt~Jq%l=DHD;De+a<*mJSpP4EIQY&BHu;+vqIPiMM`9-t9!n0K52C`^ z)v$qr+cf{Q%Lai!eFDBH6c3Yp2-*saR7jP(vv(f^S1IHiu=)c=W(8e>-}G=N_?w)d zqfG{h75WP0=7S5+5BBjD9)+LpmUU_o6H(!xW-%Cc0&Pq2GCi<*q$m|y#K|P7e2~)294ccTPX>Bm+Sng}%Jz8pt{1YKjpGsJ*fRL0c|I@=QUN}^dsLN+hzG90 zUpQ)rC*jSf?+c343O*AX+HUb=fs$U1zIVX;2sSob6#n`x!1(%v+nB%BSC7AbUl0Bc z`i5__3#65h`|G`hZCrTG_^%qp#s$|*(9w!k4zjSNt>#9qd?`F$Fs&PQkwu|G=vA^k z2e%lt!q$yjjYOBX>iv&zJ-?*`v)?cEKJk@YxGa7Ey+5>NW=+*JGT_n;a+2 z=$}h*emj1NUej8h0)N)}=Te_8@GWm8TSyucDd0P}P+FI~G=0DP5!pj&`?-DmL*y%8 zFGZ~L_TGDp{9xKnhu#y>Cff#7#!cRuiEJV-X zbpQx1Q|Jzl(we_@o|fw}vmb69kIWi{?Mc^xS>q7{eETnheTWjXO@Tgij}iL%ICNHt zK0-&;mSoQ<3|KuJgdu~^q}+74 zfsvKmbL?()M-H1iC$zNHYng1P}{nuHCwK8s$b5GUz^*#0&#Z`M;=y?PQ=99J*ec)a5!Jec0k)~YBVmkI7lM@E4;3 zBS~Cl4F}ylHwTz6`tBv%BlZHipMv|(1E;4P1c%kV)DF~nC<)s=;JG6eQEu79+dNXe zHOl5+K-`_#Xh$!;F#}(LZBVk=N+|qH-sm(~l^wsDI3v6W+#A{^%H{eAS8S>Qe zGx(nz#k(_EuJpFzo43mu-d~^z5lz9Gg7*vYKKytjpj(mNZ5jOvdz|}@L8rGzzE^>G z@Uue-zqRI3gVlAr@v9rMmnN6)hXiT1YxSHjZv<`zUJ-c2!1>zn5hDLUPeBopxakvoGX3o`mhd#cUq9e_7{y#!{62H;HCpi#(fOn__Y* z{G0{ROge$!e}wAD3QvcgbPV+eML9bw4#kqmG#O*5IG({6_x7&JC4c;+E6kI9AW5{b zZ^P=#Npi}Yp#5VNdIPm3ciBWr@*6l^O5K88_K1P>>N4Pr$-h6H)7c83HnX{N&}YFP zB(A~BqOawuaAX0t>O)F>0yvK=k58qU4by>qK<<4#0P zg|9mB*x=a0k3lLSVL^&i!JT)|ewSHVZX+FxzAp}4Q4j8oNf?%7Z_1^h5ag&BG&)ottqx}kSop)@{rt030k`va=ssmoM2|yDb=v>C%~!< z-?l*{y&Y`XSQdC+LdvUdREM}O22I1JIES8#M~sP!B47B=5bNUn zHBfP^Rlkw03D1ZRiCL3AR{<8W%wmdm+Qas2C#+cAc42$BqbOv(=Ecpjju$tZnd*r0 zFvTeUFu}nOpQ=lVFH}r^;lucM--6v(x7_bHk)#qkYV>&xH|CYg;o!mCO5i<|u>BgzcfBP2a(LuMvB!XJkJ)`T)w8{)f< zfa@h4lop)qJCNzn=-~=sXN7n{SZ5@xOdLA%iJH2TXVB`SA-+rYomQ`neI`;pmZKh* z^z!-B7(!69BD?aJtb==)BH-*vE|YqNbZTmF$&%;K@LkcBmt2uk4BH7=R|SwcSH$F9 zJ|p}o#MD*=)^Kj`)>&w+N0O+~PbDrQ(yIcEP9JkTjNgh&KiKa$j3t(oq_x%%VXSnwj z*Y0Ef&2r{+%Me@rDtPgc2bFW~a#TqB7uX!cw216C6q`0lv%;}n#K>X6mFKXPK|39H zvG6oVSw0Bym}5lM;@Cawg;{vY!nQb<`%b7!kV{v2xC(~;ASk7)nQ>L_8zHs8S_Ngi>`$rTY6&So%scp6ij;EY;yoJU<>YBlQ%0_erT=8{#ZKt1+Vn z+hTnF$pB}$t;U8K$HMz#Y9Tz?uKQv(e8nxL+ar~z0r_pjnHsyJlK~H&=$tIPBbJV@ z{ZLAG2Wrb%>ZJ4Ak#gegD`WD>JTH%(R4LBv3`|{rKUM%A2iHq=+=nqjb#0EVT)Ym} z^6Q{6P;^8i$D(UpUt5Q79u)jM;!Nk8nY^o=ZCq*n;SYbf9`xWqG$yF6eqh>?WoE`n zaYO$aS9E1r=a!aWZ0(8ev}Qr7z7}I);_1uq;aiNW%h6iJ3DgoTyA6(*&dgmNk8FsO*M%b^k4;_!cZ=)4k32GYT`gT3#a~QbuaK?_#rsAkXyr41_#|;$ z&J!|$0^}N2;>huG`ad+t*jMk%^)cvRPq5|57=o&(7wQef%jB7vL5=jeIEYV7$Dvj* z1M#H^97-U-e+%B|RUC5U1)c*V=Sj$hUIQACfum8uLQ(EASx*wjY{`SveokD~R|x(j z3mghxr0wUdyX+JvxYi-B&a#6RKyEmNTFRWr6MRD;%2iC*7E->PaKN$?0bAZs>|Wh0 zG;?-Ct^8Gw32|b)SFVIS>;Uc!Doz-hg<3hkY2v=VS79EDjE>1tZZ^xR*E==g%Muh_ zjc`oeOBv&9PV#(Jmfhg=URgRiJ85j54Zhd_f4_HcfaPkir|B+RO25K-@VaYrWWg*T zhQ>%QVKI9)UN;u`BC0Z*5m{U{$ilCWOXrYpB!%Hd^*8rl8kf$)kK(?tg$YO35Fbap z+Qwm`Rh3uW2kFff*Hl(PvigW(&sgO1sQg)Z?reBntYBl2k3hYq2bW)ChbD+w-dWwl z!t0aJa#pyPZW(X9tZ@u69PNSMHIlah!WJAzDzVxUr_ALILsnFQ62FHO&RM?3lA04- zwhVqA?E5QAU?)GXy27LN81g!twwmUGEVs^6#JZdr?q&f|lemg9it(hhtd*PG0&BYN zdEVtbX)v+Z%VxNLRCyiZ5M`+;$L6l*=T4+Gqiv69ul z1Ky3=47k9@d?z@&FNp5{Sxz1|1d;>!mwc}bG7yS80L}t(5AV4bT(7M+n5isllCz}W ztCAdO$SiXNak7Glp{KNDE8AhRt?*ZPnh;-%h29tbT|#x8mG*C zkKqs3|7DTQbK5LshagjRDEA+9ea+?A1*X~`EEAmNP8-^7hk?Ap!Y{niu3zR6W_8<1epT)?xvdOzuxzj0=$82(XM?QKz%A8nGzj(12Wq}FPz%XA z_1&ucOw%b?bZa-xwzNW0yA3?B$$jVbv`4r-p%%ukGcYCA0xzs=l95Le&8}y-FAX>3 zcB~j=>JD|+oi2mD-e8&4#x#3nU4t@%vrXMBsP-PP3}Pg_p^$g}#8Bwgbe0)Zotxc< z+!x)-&U{GDwJgr<5kFe+|{$h;($os`slp{c3|r=|6?-l;5D~mi8{D1l0XOy)_A*bFv)rvRS6m0XxrAE!or`$&vTjA^7;w8vi^1B2F;V06 z8@^XVHKu-{Ubz9fSxbVMN#00(^3UL8f8+xbS=mUN=puAUWMm=JMTH@ zW@ z3@a;E0jz+)n?uVpkp!m&OWqBaq!# zyKr{BbjIOqt%Uua-CO$t;`0hBsbwg4*S^5FtFgO(7SWfnf}#D8-wEv5@)*9i zAvvQjtCyF~ua(X@>HI33)Ba`_>(7x1_Z;hV%Jy(Y`Ou_u<)?T(n^~h#>Fqo#c50o? z7Fp-)S#Ky_W{Pro39gNz(a*NInT72kUT_$E_D|tMS_2)swn`3p+QgnkU%-TZ(ZaO; z!qP6sSHWUfW{yR25}#o_Q8|}LYty?qvmv>-=a?M30$KYnoqW->5bgE3Wy(`VZEL`3u7$z(B=}@pr@}OxraEAID#yEbC|uKzXKOJjWsy$v^IGkgsO-!WL*1hxdRQ z76>2t(dZ0}uiNkrJ=eQ-aQfc24HnNy-epg#*4dja)ttqt18v%A*H!DPbZ-20AF#Zk z(5=>1Wg42zcKI}q92^DtXxY6QJ&uqFoDbNTg={tP7}M~J=m@LrFEj(~KoU>FA(Q^e za+T#88#Ep%!QyQP;cc(gY=>9cSv94w^W6+YJ?tahDU13XABS44YvG^7P{puXz=tqP zU$ozm9lUoNKi?2~ZTo!RZynP@a^dvWR-u;N=u9yVZ?VojYV!tTvqL8H^KIjd_0rId{?q>3+>eP3!gB6OAcQ#e!!Yp(h_JVjcNE$LILcm z;#u-zRf6%7h*h+a1q3IQG#~du(pH`ViPiCDb@<6dN&$Bnw~&8G@Xd#B9^OA}ItxDw zvJQ*uw}!_Ys&@;SI=m(Ey2waYv+$xQNyZjq|B#S%ABS#;?_$94y&SOmexCDufED*k zQb`uRKat_$FF{=C!!KeFP>ALK+C;0B>srfdoGO>P+HW|!?H}7URZp;Xw$`u+T)TNa zAD%P*Cz0Bt9b<#qhwx5ldXC!1i~d_sC7-(?NG)zc-^{z}h+)q*S>ZMPn(+Ry*}VA* zb+|cB_7Ba0z1w)`Av4-qFl*5EWoY{{x$R3>45b1|QxC6^H?$a9xFy{!v?i>8e30&$ zw*Mc>-UYsiD(xRXGr2bDCA|PidLhZQP?{Ford%sh6D_4xQFM0^M5k1A3IYY(6-A|h z7YeJ}HlS^Wo76kHVwGKAm0ea=T~^yZj^ZS4J z3`wRlXU;iu&U2pgJm2U0Fw>8;+gB6#sOPU`ijTCDAtG83|U zk?(9x)Ug2)s=57$H8ma_8&)g+ipcnUt)$TtQ+oWtb}KNsg$HzkaoR%L4q($4c+XmW zg0b+7b+7mJYnOQ!*g6y)N?%}O3p-$=)Dg(Q@vu}Pb2HnN44?Am_Bdo6Yi*xvO^+9? zc08fOnt}g;rzo%?Zc{5k1;ev|X!lVI4ToF`8hnn8ODvC?-(X(@ECqCrOE zdWYXPot4*T=%k9k?iIDa?f>t-t%mtC>Vi%i~|UIKQ@Rnehjt<($P>p7y~cX&-*V=Mly zp4kcO7CrN0w;$YrqaP#_6TqizMwW5dy<`nvpOdobEMu>K6|6Cvt+&X-v;4jLA#w)SlK_GI7wh`tbQ{92zdX|I>`^ zzUSM`U|Fr_dYJ97!4b!`!T9XwyhB}uh-uu2?DJP)1aI)NT@%qWqY%MkoH1e3SN0@u zxEN>t88IYe+e_%1+=_3Nm%wm)r*#r)=8)^hN16Y^+Rjy+Qi?XY<}gjk#8^~qogp-| z-(f}iFZpVoj9XOC>>z=h`f)3h>s_1bvuS@aQowo({QKinzvmylgB_!Zaq{!F`f<;< z|H!=Q?Ua({WZ7m2D5Luto{TT5uXnDhCxIy|)9Q;i9cDIrgOX^yqn_F>FSY-7XzzCIrE zUFRh&8@yi~dCls0@b~i($B^rj-?7)*TD&tm#*(xt?|Ab%tib!gYk;fy>sdJyJ-23< zv|MF&^9P=;!Ca`fPlVGQ>22xgg=j349X} z9N6tji50y-!MawSQQ|h$TEA9|o^+e3BH)!f9C+6AhBnDi@rhDQ_9?V|wB59=bd3KC zpCKHMKD=|_^dN(B^%BK-(DBZqZh2q_Iaodien%Kx zATY(5yl#`3Uts$|q57@%2JMZ^r_peK^fj>AQeAZ`?tfo>29v>qf$BhcxO+v_8rK9T%$!)qyDk1g>_@EKXfx#wxG{S8FKhR-&)zTIyx=Q7jCgrT>raxABd%-2%|c^im}m3z7-TzLPB%s$P<20 zXpCJN^v8kyW!xA-GeM-0UGQr{p3?U}NORVAV2@X9*GT!b#1S2Pt=p3t_`;#h}cVEGkoe~O_6uKt@3GKIeOv)ung&?sgR~; z?XS1*_sa5z@T-CoV%(vO&9=9E?bzvy?N(v|V#n{5IyQL!rwjg<5pC9+=*^F98a{Q3 zq3VymS!%By;$K8No6tV`PQJ$SzX3{HJr1g~B@kN$$sa4Z8a8{~-J9(-4ST&w9j>)0 zhIAP=SgBe-WNLb?m9pji1K#3z#E%+-XYE|W>(E9xU_43wY1xEc2n`@pJAJ!~Ls+~% zXFZj9us|rTi$;P#er>A`*-YEDa zQ0`yBesi!qSy9IX%0xzHU`^v2Qf%ycE71rn&~jm5_9$Y7N}ksSObrY#S~cs>pxvB$ zALXf{d--VizcHd{?g=^`$3m+k@`|7t_mU$^gK&Y!LXd4JwIS}{SWS>{#J{>>Ndsx^ zNe2TY-dHMhnl^j_J0R8xwcxfpXgh2j2)m*b3AVL7Y9-?H_L}SHeb0m0kUio;jcNvH z8Jn@DIx4~n{Wb=e*aCqxZ^P=a)jLss4;&wpg=erbj3=uaJSy_bgMCm2@)RGyd`$|z z=e6Pr0$c&fA1yCwa5p$G{xmY(EfGmSHFAKAr)LA+&(w20lHQ>S(lg+S!~XIc^aY|0 zEcfD|GLUlK>9Vv^0xHPe$x&JK9~8 zvAMlkSc5h*%>&_=B8-?VEVTWIQ3_tm_8z=L@Qh`_x76&!dm1Zg(6eJZz=1ekV_D5QJ`9F&O|m;q&PQ!k=xY)tW~RfFDc=pxztQ zx+lV8xwL#&W*U&U&@bU(8Y@lT#5APZTD|rjAMLx21eE-8bUYF5h}$^6t6dQ24strm zz7h7YlUVgPK$7GN-@%vmBJ#*E=%Ha{AIhJye`)y+l%0pN=YaP@C%HFyQ6|&v6^`CE z<)Y-)px43WIe{`lQfvUtXii778Yrwz?~E1JBTb`@ja9l~gfW z%6RJ7l7&m|dOG2z-S#ruw2VKhZ?~cST6=uw+;rp7dM9zrX1BI)2JT3QQW(fE2f5>M zs)wFNIT9!njbG4uXn|J5^YAp<>t`eEQ}I=|Kwcm-XBSq^ZW|`L^KqJg&;b9SzMDn+ z9E7&e5SowKc(B}sa&{LGa<4hoPe!Q>*g!@ygtSp7(K@1tUyiMrw1>6OKEB3W4l9rs zc`Rhl0Jya&s{ij#Q!OGjBR7v6$>nlOshr)28n79Z5%FMoMXbK0Yz0M*)5rO3lpvJU@NGPY z{yD~S7V za?J`IKF>>sloe>-794wV9Kz9yBZRr02R>QJd++TCx$09X!D(oj?R{s~$4U}-5I0f}rhvU2cZ&ZXwI2qr z=!f&Ltx=|iTj6s6Q$yXKA;Zq2O}Wr3tT?EC@fPx$QcgU|CQ0?CI^cL)5y|~Q)oruCRP|A;10*+1qVqXfN~p47Y<(7uuL4p8-@2o)=}1(< zY9!;u8D4k5Cb$GJ2+Ne6o6hiq<+L8OJ`Nm(c>d%2uE&}R{`N=6gc*_+TA#r^O>VF^? zah>9e&>KalQJXgl3^nFq;?V6YJV3|MH&^r@&6ANXvF^#pdv>*a3UAUNWvgWwFP3$R zr*B3X`AqHmAFsFHvmd@J~wT zir3I8>E0uPg11IlJJv)P=!kZ3#M5W28+l!shd!tCd<{M?y}OKyeaD}{eg@y0@HeUl zU@wQ!u8}O97t+wTk-p(u@P_GHHjJ5X#QIGpBqA?{K}v@G>^*o74562hAYH>6l{zENl! z!~2cn?O;}*oCr2>f6xe-@Bz=7J?jGAaZ=j@45XkP>pkTXiOuh$7c{P#Eq?r}*-{ES z!+Smlso4nbxC^I%KBuFH*2Qom)TX*> zqBZhD-P|KIrtq*j+Krv1f(zK7T(_nhe8SN3w0@F9NTkz2Zr!4Fw46SHdm!L_y-O=TaufG}r;a1PMUEe; z8BIJv$Hlk{yOfj5Da*-kDmE+BXSfIZDQ%NE@AqBf$g0ZSlLL2n*7%|Ma)kHTHjxP_ z(A-Jr3;2ywutFO`I_SPSDLzP_=BWd+{0RK@{@-D26L9{K+%V*_r_K$u@3}6<4zO?+bOAlGQqPvC zd~?W26>kEEkqy~!X^d0(|0?7}2aXFka=+4A=sGYTpDQ3oBI^iw0H0BO{to9(3A#WB z59`{+)#-oB*;j_SS_hc!C>p359E{mFaCJMq2CP+DtX2DFahPdDTG+4K{&2q?t285J zR@~cv67v5jWSs+uZjXA!4gIv0OZq?TcVmTTu(sdUUn=Bb#E0B*-BecmeVF7MWDjh7 zDX{-s-=9y;3e)=OZ}9I_%;-NOoZ`xgMhUEvl*K%SYQckpYVPSetlU*8OAOsm1o@z%=ST;a+dqzDSF{KCqL{es44 zC6RE?5F})va5XX2tq$CO?Ed}euUF8f!#KXe;hIMMH#8nFUZkAGx@IczMx#~F491J% z(+doy&N+gq0T?4EkPpa0zW>71`%#8lUE501 z(zh}az6-tMSXHx16HgL@t9CouRn2iiPdA`ijNB1OVWReKBiJ@n0h z7P>*?0L@(X_YuVAHF~f^q_#ZFiRd|uiO*0b9S0i1HYR{ukLp9L*t?vr&3l4$r2h)# z|8{_D(E7I^i^*?;taxk1f~U85&v&#vwA-cg?}U9Xs|=X4_C9DN+r+(1L>B$G}S?~_c zm#28_WtwINtT1-iF#ldOH1?(u4HDgfc zJ1OjKPdDAVdemxKMsc)s(?RRh`Z|2iSHE+@)Ors;4i-@QR#{Q-*z04gFH@YRvMi!$ z-lLc*V>6rXq`y-Pl~XUybVJC6XoZ92hO=7B1RPa3?CRXmjHlM8;)=)jO+$-mWL#lI z81|XnuBQz@CcTASKIQtM^CM}1W=E>$7{{V5WnQW;jjtM4nT}{#u|2h(N*`YX3=kE5 z?`Iw48H$-YwG3E6?A}jHhlEm9Udv$Fr}o$Micb}~^K#0;dpP*!Xj@J#Lqyl&vj$D4 zke``I-{kudQ+=`9fkFZ{E^d7>#^CiWOI9RG}T6h|tJP&Pq z{bKt*#i#BY_-Js#wBteOAK%JnmVbx!rJh@|B^`*XZ|}*!cj?BTA9MKwo(2PE?Ul71 zJD}lW-1LliUrp3{(DudM4(P@WsLSg88AQLg>=TM+hM(xw^i3(7fXr@2bPML=SHSyf zkzX>Ft2H44+q^1+Qc(9#BV^e~`1>evvg+L32Mdp0)^P0Qw_kSvJk=vE%xx}{&hE1# zi?(Q-sbq@}ZIaBeEqtxKjyll2Z^OPB-scrIugDVB=JAD!Uv?peyTA#l7t zP@3^9tVB!8)3Jd52yDVd3A+F^Mt`R-?>#0YlHHTNB~ zdm0W}^EYMyTO+KzDK zZcq9qWDJt%j7Z-!)}7R~o3q2mL1&T%^^VP>`iuJ);;2!mHk%-w7c7oTvSuV~i0Uws zsjL~b`qtHyDd!L1ZUCcakYDlxkg7uwjVX84QgtQUyXuQo{8RMo*O8a8Zhf(uu0THs zbPamzp&rBJqiK^2+X|sAV^$x7P2`E1r3A5Q#Z}+Iqg_+;^SysKvb&~E_yOK9Z^Iez z?;Npv*Ru`R^GEE213TY(_x(%nfAgU<&tYWv)_M%BXON93QOc?~)vpU^TQe&n;SVG0 zft<4XM#60oq1rm>eMRd;jKyZV`dLj0~s)xzHbk`%@~N7v-QfaOxqdH89P4 z9wNG z<-|P+t7hcDM#!2T0eP6YuM}WY=Nw_6qujU`co4dV=OB-OR<@J4;6W~(4J*qx?*#UX znGWB4-Wj>Hp5*-#zPvK;G3BiArLqxLle;!Q3uc3{!W-Um5-A8tyfA~i!#noUEhd3VkG?XATTVju5y4v4PrK4#;-5x_O3j$((`b- z!Ppscl?th4K{bx7w-lPsYDdFJxaLB2`;p$}CK8!qZ{ zPbudg>W4*Z1Nt%?g|be^2R?s9pCYyhEgpmY;V9VPQlY;k1K~mnG*W2X#IoQ-ot%>i z+b?iE*F}GG;2vN*z=TO+zNjBDSBF(!5w%T^qJFsC5|mVok_s~j)J~0Q zmXQOgLdd1|2Ks(D+!g&sajc_WlSo*=wcksmu@tYeNYxtNi1sUOwG{Jg01CtJ?L*rr z7t4X@m#S6pUucsSGL`ZaLLNX9g+n8EENYP{(Knw6yRYlv8eR+gdweB#f3oo62Dm3+ zH9x_p@dkAqJcwRCBO#wIcJDO9e2?&rS~lIU({V>FltfNdLBU4uQ6UdjbxFdXhjuK81|Y94S9YVW3{ znpOKXtb_j#{wP`|#ro?S4b5yrB1z3aFkE*AC$?u`uWAJAnGmhVxqDW=xUwHR(OU=CuARP?GK#*tHtuE03NpNw zvVz3<^nFp14;pgfoEa z(1Rt8qSz0X{}p5K1GQgF#0;A-<%(w4Xb8#E0Yx$wxF$xHkP#(-y^0pRsz>lSEdQv? z6E?sLa8A~cGGS0T1k6l8_<+Z7k#6R_!hAkncnnrfGf?+F-g2NxSdVi2d|2s#^<^Wj zJ|=AVnX9|ht7Y}-4qWZW)zm8U2h=LOKa*&|)JC{?Qps=OKjF>D)R`nT@!P;oQOkeL zYl3?*GKu^OzZ90P5}*d`b>RatEI@wm5Arw4d7RbC;NAeU!i!PFx4UX!7XYpR45g)5 z&)$jx=LpUksxyL5zqq*0UgrwFb;VtKe&(+A(T|mTgks$Dk^F%09uRE3@(_CIV+l-) z6aFeQMYg(RJmYFoTGtMa8XEa{KD-05C{EZdnE`NA1CL>jA06N3EtX&OI^`|xP3^ZM z0_~MST~?8#A;!}Af`$wDw9~Wmin=r;HP6(o16eBqB_UsP9> zy{Kl9wyF&W>>5>E4Yiv&M=_QgaXgOWO&mb0&nBTH6)*kVB*wCFxn+NkL3eaxgQ#PV z&MVY~z>5H%!+)OtgL=Mhe_c*h)Sth#=+5c}wALzOMMk@P!CP zr{GyY(@?%8%Yoazqc#?{LKoVAU*H?GQdvNMQ$N?0zgMZhH(mbwLs$IPVzv4@O64F6 zo#tEoWmM&!MJ^CSr}DS*em+&*2{AI_OsXAtyN&^#r=J-EyVXzY0C8!ZL7qpgehDvJ zoO3t6-4bP8Db66i-2jhhTeS>X#S9Y*t@8k4SZQvYvBQo`?qL^aHUN1mxJp`SAX(LM=teHoYL+D=;&)ophHzfL25f>}_D& zhVDey-aEl4i#3Q5!6fgin{+0Ye{vjYWSY84e*Qk=#rw3<1VUOa-T4(pES+87jL^9i zhuXz{_v5!F^cU!>W)j+O_B_6iX&mi#bXg{3cac!SkOjyT0szwI#`nR&X(x9G#_3xj zzj_6BN}IQo?hk-l^TV?9cfN^-$IyDaVDio9mjw+jzYqKHqpk47$8$^|mA`DkZ9z2e zAcDFB6#ev%4kFGs%|wVdcnb2|U0|Ato9fYwdv5mpj3dB=9|g)m51SKd-RHa3o-|?7 zai;XH3~_c#MSSgJ-uY?`@T9;Fds4x)<1bnn7uhw&m*=~ezo|O0I>hheSMhx}=LFO8 z*sfHvz#}WSnyf_B2 z3w*i8SH*WACs+Vh_dWb}{wQJ^mdt+F;xDVjS~0FeWqx)%>03awQ&PRdQiMEhd%K){ zc2W6J;qL2+^ifdbU<1Yyrug}CwwcB1Vt|$JWDs}zD*1Vp3&>oQ!-933NT-4t*VC8* zv`<(+;`uvT(QD**+6h*iGv_=|v>Lq8g|-_pBN-2o{yS)yM576q(8GuU_hnoSc3fZ8 z23RFO4DR$!k{=RYwLZjq;jw0li1e>u25)eUhtwNWmIgh}=;=v6ZCzyBVK2}XB+znT zTMYeb$d{p$XJmo51DGG<%!9U~N|Ju7P-a_TyA{3YuCn;H^E?j(Gwh+PnB*qi`+|#j zjVlLPr5C7mZv_sD?VvUPW03auKL$SQpJ&qMrgR13rWSXSW!9Gk&A7+CIglyM=*dOp zsp#cCemDObEJ{-4UZ+t)8v-G#du}Ik9BQ2xsK_RIi z`8a0Cu6`@Sjm4;YNpSlH_$SrTS3G+){~iA(|H93E{iMLy1137_Er=Mqm2VTeuwESN zhhC}_3&v}hnLs_ssftz6PFX6=)OH$O#*(-Elz zIZ#Dmu8qkVxZIb)*Zt$117>hKa_lA*o*JY?6;$w&htl^1x%DRzH>!*E@WQp|w z?T^?RApq@juw1yjCe&U29fDRuxGl&_YuS~ybB9-Ztlk-?Uuw-H1zbuXwa&p6lYr0A zY!EfBa&VMfUwXT@>RM)c)Ec)}i;Srnf2xR#KYp6SiFuX{)eh?$@11CqlSO2h?$nUa zKx9TZ2Ufcu!vCPV5Gn4NLRTF4e#Up`1976hMYNBC)S=qktchCnzH^;=@uZ>`KeHLc za`$I4WfU%S1L=0Tq*qZAG#oB9(376Zr-JACN9*5}+cV;t>~)my)6G%8&g1*oI^bK6 z-QZaqEkp=5pxZ=8|zF?W~)B50oj+eq{jVC@4HzqXMhC+ zdDGJB*w+jt;LhnH+#blEI1goD?@2#sEla0%<_vh+;_H~AGfE+M+Pb$cH}mVd@9_L> z$jltqY~N|}8ymHuwgC;gKHd+`twCh_@VkYC#{5UkesinAQDvLxDX;39 zlV8;|bBN2IYegjBR>r?n0I~wlEXDf#VI(US z3DrG@Ih{<=gz6iD4wn;*+OsD7k4)U30&{X$nFW7oM}`J>IZFKAQ^&4HwDRJ7M^`RM zZiOFz+RcT@P0?^9k`gdCrdrYJJhnGaI08>7Jk8Y{XTM$=)G~r^Qx(yGC??OFyk%}r5J+LuF1G22+5e&fsDNBWO46e!kPV@n1y7**S*cw zx%MxWJmFTI@u<5Nc`#ayEvD_efo9E>Z&4QKldi7d%lCbGA05L#gezfx_aG8=a^+9g z5qXA^vNIVogGDc32j6Mho*>2t=oPzX0r6Z&dhZ%@Z4>}Mu_txzA|Pks8K?C-zaE0^otfO;QLF7<8fE&WA) zwEtZj7rS>SZQlp-ulrNBGx;p-Iqzh=t&1hAeapcocI897o0-zT%hB2RV}71+PXlu?- z)+V@Wfo3@_+Rq{qYCmupSZjjJq*FpMe4Tr}M~`PJBE}J?ULo$^x@W(n%Sbast zIwzT*aXnZa_gHH^YHCE)q;23i7CW8Wg7OrMp83%RBpIS7rJ$XW+D7B8vFOt zw~5UCcS>@mjZYOy>%bp&q6pC|M!lvpc1{@+wH#hZP}Bu)5*U@Wrnt0>B<=Ty)`3YUa)IA}n#Y*A_FTlT)5~1EP9`!erX}woNud`&P308jT#j@Gb73in?Q3s-~5vzr_ zc;f!BN9!yWHv5Ws7s>PeN!INm?)Ol((H)1kPB}kU37%T$uDxKmm|0q<6MND<)kd)h zGF{(d5Y1r9dOt$fkr&l3&e@}Tqr|V41%)sy7b{%<3 zsmE0X486`M861Y<4L(b(zY4AV^9sE(4R&IOs|Xr>F~7z+9dEjrTwk1ASA=#ZsqJLo zleyH+PheYjaAx!bN8G+#-~~1QO-fm|kvPhnm+P{JsZ|Ss8t?Pw!CdLWy9>Tv$RP>dSL8!d8%ub=XKwA z+Uml%l8&G;0>Msom7oiK44)4p9Zav|R|}qMTn(LTF6OiV8TufO>BLh@Il+wTT0-PG ziU+cP%u%x#QYHUvNd8$^ufh6Hui9Z#=Pi*-A^Fb>kfo}mP{8LG#!T9>Z#2;~{vJ*M zgMW(iPom|w@#)mkUKv#1PeMoXLJY#`BVz9*~` z8flU|Li(DU+}CwkNtrvp%RTik?THiex)Iw6ZxkoISeaVJ@yOnw<{*d$|CFG@)~7+wh4DJF1Gmu zu440UmzVEb==vcBS$AH-q^DPy5=@zx3k{i5)PB(vV&wj zcJC}|pQ%7*LqdETY|?3uGOfCnxM$<+#wHK$JLsHEOlTW{x8N~F6~y(H@9P!?+DEb`tf94BJRx4Xeu7Dg-BXN+W?KIPSxo7KHC#14TYRystB6yua3+F4 z3HY&yrio7%viQ4rVA(vU_)iqd)7&q`fq(P%3=_wM zfo&_Xd;5m5ow4t)0toM!YYxY@ZCB2=x z|6F+Ig)6V^7}4Qc?Zs>JhDPIBEv_v@YlPA-tqwwC5y|u5wDp({rktL;AzE5adjy33L8*HqaqYg5!Pz$Eg zcpzvg>yI5V1IQ1$eoSTC^3<}ndvb{r(VA@NB;}*Se$zbTKkp7*$R%+=$iIeobNa+p zBZt+TE{yz|@Ha(|r+z4ZEgXUz{x$lh1br0!JQ_{I=l3CMht-mE;fxD3TH-0#P-8an zbKv#=$tF&5W${^B=qq|T8BgFMdhDpEhj2X6wisuEqkZ5}SjFk?S|@6n&7RS2V>h+N zK_+#^b6RSN8`q~;@RmRagt7E}mqz_0JxASWSZA)qy6Bq}XzLt-KN233wAj>pa@4MYPTVT9yltAxq zutJ`-Fs{LDuI*G<%oR%Owl3pvU_i0)Zt#l9eM6lV$ zHgCVa0`tY<@p~WbeN{LkOe7uf0U#Q7x^Z%L-lQ%MJO;*YPT0%W2xs{8JbRa$@~U}U zK-?~ZuV#-B;2H6O$}?6!&$P0EU!m<|e0RZ%l3Hf=Ek(T|;f>LmN}J%WJ|!%z&PHAX zH?fphJ;xQUc5k(tEUI;QzN)sCbOOH%9As$gz(0{0iA7}Iq~2UY`@&dAdxO@F)(t$I z@MUmasdJ`^zEHM^x0zBP<4{OOr{wi|kzdbdVKDF>H#vE7cDBN3JQ)?|bQ{9KB z>O%7e6!@#(@)qHV^f|`D|36P+pZVMW^OJJ$BwZ`*m97i=ER9URosWFn&k@FDETwim zmJC~s(~;dyj(KiUp@)iA)*tSVwR{4+I6$(fZza~+^t=R|GZq;=G}5gSZ)G#y3Zk_z zCKeCPK;1S%k{yDl2WS;yDYAIJLf>19G}RjPzSZNcK8aq?hW-^rWUP2tVOtsBgM7>i z*9p8gwPg{mZoeK`w~fTj{}A3h?8~?m@5mvd6uA~)_ahb5yLxb4{M%&zu6=Biz6lvA z_ZphCO~%>UPjpS}D~w+gx&ir4Sp0iHpL zDP)Rh+_+>%UvVGY0sAt1qVuxqREcfLGE1;FOm{CdF5C!z;~v$p_w7z{tz{{FU$W@m98;e zNNctdLz5AB_79?D92sv2=o>SeQ`flN*GVN^3GRtqMjXUFMIv0PpSUu2n48_O{vl&n zaOoOHvEMfj-MSggugqHnf(rz5*ehMa~~6FcBZ znLJ(jW&|DXBk+uVs1zVWS$=7%|JIC5|E;hG9agXWS~3Leh_@r$cS;s?E`v15>3CTa zvRuf5Cd7i{UEeYmB!1dleU~;gEn?GfIW`dMId^4a1qS=Heyoo^k(DyVG)QpRM%^C( z(N##&^@COp(*NGs&VXa5sqCKF3#{onyKf9Z-sw4?E6ljNk!8L|$rR^jWHv8AiwD8Z zW(G3-pV-@&T$y6hwiLf!XFQpH1F{CV-7BSdQsBNHxfhlNO|8ZW zalJ{cxA+!VlVB;tSn-(rnT;PPzwjZl7k5&<%@oK){tJ>fU7}C3lfvn7c`4nDYis#m za0OF%sSN|bF%(TV=9P9OHWEiB-gOGDzBZ$9dLc5JB#H~HiO|4J&h6!oUAO)EQL?^O zFET}O)^w}B$>_HAnz*FaDj#unpe~uB5f%g5Hy4y!|2xbCW%$PBw&s{S1kF% zy*K&>;rmT;e}Ov}`hJ0kVd6?`hSpL1CU!su@WInIi)&&vPU|)VGMkCZ6FgY{@Hwre zk*@QYU>-R9Fm~6`Ieq2(ATA?nPur8;Rak1FHNtUwMrPB3izQC)HU>7^_supo8S}Kg zmVmJt7XIVLCK~x~49xW!oAnq~H_GOK#Ydzs`xgNvMWny<*8*|L_09%I_)Qqy|JDE8 z?97*0YS^{$!SLk?Su ziBXs>ltK_=fVw_Y%1+c(*qR(M|TU3^48RRkWl+?EDu9({P^;r6rNNrhL;B;EMG>UyL_;I>G-kelECQ}|8NmOM^{fJ)ue0XG(`nhJrq<-E%(%DBKL8cMcjoHbVxA|GU zRHo5ZkF7EUqSlP6PO=b@^0{Cjpncvom|A74)MGc|_wMYnBI+y^%-driUl1?ozaz-F z(tsGIHU2*Q!5}OLfx9hCv7y;GNm7mi&H4}PSISuArdy2p@H`GW7Z&346b`yqaGZx< zAM=HfeHXwG`!I}-4^tbkMSVwx<_zqL=6ei&T4%z2dgGPP+l=SkZ81(F`R8HNkF|nk z)-+-*c?fICG{oo=_bt6kP*W@MQd}95B`WT_AsHa40;!eKy3l46A-|8C$zJ@A zXc@QucuL@`{fIrK*$CUX(Qidhjy`TDv5_<(LTmf71lD12gF-hS8LhVFK!0rH&AKpJ z%<`w;o|WocHXgSHVq-Br66>cIsXz319`csa`xjn3D?&!#ja`1uE$VZCpX^Tz#7h20 z#H2oHQ~x1B-y#im-^~X{~4`kmb!BP#8{ucbFtGw!nmS)!=U4IFhMC5-# zRJ2J`(05%jPL57i%{-Lf`7+^0a>AvvgejF_;o4)ufwA-Wj=4d8py1{z((Xp6_Q_|-Z4(f4>IH4 zsQisrw7yZPt_RR2_Nu@4s=xo{XpoPDZjbgfHK75l zc`z)H+}maPi?|-Z@5Nx=Ng!0`I%AFBn&6KQB#5J%$M{!P8pYJIB!5z11#r4VdNQ~i zXSSBtTsIc$j14)KY!Q0xc_2~gTt6SSMenY>rwa6WWdUzlcd~dl#(+k)V0|R=_&#PF z56O8^{~Lt^xu8VL~seA_C)@3KjCh>;l>-|{Rvx1b~`kWsvBQL z-0K7~8~K&aBl0Q*o@Ou&xOYjY`L^eq693y8aWZ zy)oTy52UO8{ZH2z@rV|=(Xh^r@zW7Cdgqv3Z0Md5T1PtG&WC>&u>_LQ<9Dk%Mw4RS zn!fEbCAo^$?L6|OppQsM9q0I*39elnA&mDRj(wO3yVUgs=l;BH((bL%=;t#h^}R6( z`#jw9`L)sLKW0*_9Jn-8T;BVmvAY6JaWs&M--RoNvAw}=6_NSK_7bzzd>5X9{H{(y z@Ardua3rDKH#E?Ct>Vi$hjqxM+zW0_lSR zrg2cAF#_k2Zwh>%V%qFG$#0B>8Q&uxD3HOjWj6i372o^dOI}LuGJ@Be#KV(Mdj@D= zoTXKPg%Elb~pzZh}>;rJ=`b9C*6O1h59f>>R@3wICEc5rA%SYn#jNCP}v zwmYi}S$)7maSd__Y%k|Xb$R9*rleva13R?E`=eY?kS6D>*`C2rOxwgX*)+MZAX9d@ zxHZOceqU;EB%C%p8a+ZeEGfYI7O)l-78ulP={}K_E#nriVN0?ri8}v_ zh!xSMn$WKyzaA^MV5%0D#<`QbGRg0~na6L#t~y_?H3zl( z5?Fz2OKonZYs!o-@Vy$}wOzlOaZ+97&nmZO7-hVr0NawvldIaLnk>d|2m)^eZNAJ) zu6hMX_U~ciDuqw$VEK0{Za%t>Vi8wfv>(RC>bb#7V|6h&PJbH1{g=<*uAbKcC;wfz z2iVa|7Tb}qMIGl3@*MOWLA{EOT8d)->6*w8EkAb6FL4b4&n_)1?cc6CGn5MpXbQEv z*0%9&4U~tE!@8U*J0TKC=w8^A6C|3;h34PQ!nM?H`h}8#Z+)DH^X2b12wqLT( zj=pH0h2;xOi#4_24CtlhF`+k6-oIq{UJ6z33s5C4erz4RLMyd3^cX(rG)+9LKAQ=N zxb~2AP@y*2OZHf5o4quzZyAiub^pa4pwWhQXra0r-Ml9B;?LTQU{!(*=DV;5c;%n^ zN*J1m_9UVgXlqgp1xGvd$w%Wj4`0SH4r*m7^IjJmcd_+fD>?Y~C0eg2a}BAT)l10) zBfRU^d0JsV0cJaNa)59(HQBDV20!k_clen&-pK7~pk>kiHOuhG;P2ouS9N!dM6Hp? zFBYLSU=Y!0E;E5S6!sLprWVMIYV7&ZON^YVfBR_NfhNQ$*5Hj%PQEMq=SsVoCN%D6 z`yjNRtxc+>@i2&LaIj79dYAPuGv6m^9-Tkkrty35EyITB9zhHLw6-NvV1P%|gl3Lt zMbfy}>+XP+ddK#1$|<7tFDf_wJs0+A5@>C|#it9T$2V9>;8veW<&$k_*EMfwpKI5) z67bB5?a66}>{6pkm>-L|h78)%~P}TH z;MAQ7+}G7@-f+j1>c7E13xq2@7tof%Muu~J@SCQAH@tj_xKF>;u#MZLX(SVqWQ*gw z@W}y<$Y#x3q?NyNeq8l&#rNR_gXR1ayq^CE`3Dv(p>dOD@FX%EFr>izQ(w<-VLPOM zvx9*m>lg!k@=~C^kOOh&J5}#gdY}o9mj77g!miT;os{z-mL#N&yj7JQ(D@N>Ew$rY zDz9rvr_v9111T3Uh>6X>ivbx%HM8?!`>+94JcgsCWJ3zE(hKTcFI4ILClo7oIyUTd zV1*APiELPh05XKkA8RdHssPn`WrD=pIojjI*f!NWtXmGtxFi=U4G ziCU=YZr0&vDxbw)#G#+`lI8d-)$3ftuxU0D6$5xa+=(>>OqVU^!;v9sDLfzk>yXbo z?^+fye5{}0M#D2W+HL8g&t(G})xAF5=|lg+owE?1&y>PvgzJdQDjJ)`^!ZuWbTTfw z`ypHc?grMWhlPGeHNFI#OKmp$9U_w*=f1ZKxus#J)RsDMrX@?0dvBK}^vetG=~EZj zMC-1oRj3-WI`Wc^mvN$fXW8PaLfFB3%N)M*;Wp%&SXA|B)+g36&A(9`XpLxZDLbc( zZhTisXg&n*98jL9!>wL3eWw3I=yb_`r)cq;{E(a!LqzCzXLCZ3fpw8^&Oow%YdI?- z7X)l^^eTd@Xg-pgmuOw1NZOR;xg zJ(-BXI}OU`OIDflVA7!bgLrY7#ppQ+d2|-?TC3U&LhF*o6Y?c~e~sf&;KV3a49m() zM&0ua%&hjUsCnthBQxLn8^0xY^G7p>AKZ0w>UAA6sokL%wz(A5K4*z|P#(2I(3;Z> z$+W&nu7%#bvNx|7H@6HjI)db zk5fy7eDw)x{UY+z6Bhb;{CF@?OxmvZ8@3`5fLnv{m6%6*=bubg{qm2UB;(CHjN3_m zqJ(%mxA}NN0DL*vqo)#M;57E<#^wa<&lCLAQs$H>9*@X>I;q`B3eu!$Sdpn*m>bas z7-CSr2S)VBrbN&F`hr>1KC>X*?AJ*}1U6ipn-S4AGRRTDgqDw_isnXI+KVUch$*Az zCPo}0$uWbEUel{b-XtPFcaoy&(rY!yJJDgCCorMN1qYY9&1z2&4_a9=ma~I%0&zzt zfp)ZOF%EZ~LD_gnp!b!_RPK+K=>2`RewJG%K>;y zN-+8+>lBQ4_4$RQsEY1JDhB9i!2YfTITZZo!~ZovCFuF^)dP9z{w#T50(OJ{u+qKg z&FXk3K)jy|Ur_gpF{$<>^bnvePExe=T37^Qd!~EnS@{d>|HcwCX1{Jnj}NnkV}bRh zHGX=SfM56%bq4AruzX53wRIbYr>UQh4j;hZ;$eGz6LaP#J6mWb9qV-de8s{vO|r`f z$-r?C_P4aMl)(Q~fe9b;*ecvE(9tzlqH>rx4$nS^s4zNP&mm$9JW6D1c@jacXjpw} zu1lfVEzIy+258L5?FK7MS)>_G)z> zO6ShGFxdamBco5GsADb^jLoT6(Ql2=x2ZIsWxt5uo1$skXxV>OamMGsmap595^$q# zX^o?rYOWh|v0ggV>sQx#oEEyx_*D;f5d3%vZF|7sGQZa>U9T-VPA>QpIn2lxey{5@NCqZ zmwzgi!*67n7JCi9I2xOs^M{ZbqmC6_0Ytj18UW=x>>JMH!5=rw2E6}K^B2^b@990FrF5($viPbiZ)D^}jWD<*MamKkHu*t0O5w&H_hMp%otgUR7f zun(sO&e%Jwsebb|$mtxD__ksOgTt@-=p4IfZ-C8#&a1RC>i=OJ4sjzS__98V5F=7; zAISmFfMzdP+uLA!Oa)%bC^C~6kI|n1oic&OLEyUCeb^gpo7)E|DlhKK@Z8atO2AKu zzj;)-X6n5PR!(GtRew2;$7Z|5udXvvU!S>Er%J;egA6e@QYo59JvhBxeLAe=3p0wi z)Vg>)FW%qLmm*Rra}M&2N(_r%U00+U)RfBKXn53+PAn{(_X|k6Nm^<%hCP*Vri+-P z`v$d*Un$eb^ous|cvyNqf|diM2A+EFF#D_llEM-&LB9~K7DzB!=9xhj*i%F`;F`Y- zqqe|X)9e2^3`;Loph9?xM@jUIb&wPk9Mi&nOMlJ8wOF-6F9Gk!_GZeb4C$TI^0Cto z(vr3h7m&_|PyPsg)nn)?oley*F@2jCL=vr{8PxcSR`Xm#5@?tL|pEk4|jn%u* zJtXy=)&UI?kik)go{0C;H{Wv_QL5Mn=)i|ZIkJWZ=>gqoT@bp|7dYy$pN|K7?N7V@ z3t`Q05%#9mpTSYFp#?+nDrZWnOi@xXbQK%ohsd}>M4)D0+})m3T=@1mcDKiY(x5hg zSp(csJyv5xp%dp4ivDAcQHubq1wcvTTrCOJ4*vTtnBI36B4BE2p1TjM-MEv4eudv{ zcV7rML1N{Qw)Jhx=S}J{ut$-rCX_iu|2Ga@2yY(xc#CJK4Hos==oC2X0-J4ITw ztgT@IFwQk#oU8$B3?p&(9f91)CCU=#l6PkLGW1|~&CILp%CAbjw#QI@l=fL(rM+y= zdg5BdyJ}s0k5<>|%b>9oc-Jz&xO(YCo=g~X*#bb@dP21TQ2jrbyfceM6yFEx^?#N! z@yyZ4cZ_=+S;53wGI2;s5)%1$(~;4@1%WG9*6snu34E@{+m;jq$xfq9Y2Co1*GugY zdm1PcR(gBedT^17ldb7?#@~-Vi$wqYc{Ci2n*Trc-aRg=I{zPkpE+kP3?O5m4p+}G zq9~#uUQo0SGk65Y3u(39ib256ctH{^Y}>-jO}l(PDq38;ly0q;EX8aym!x&uPxl?v zHV{c#+c4PjAjla(ncwq$29VtL^V#3y@xA@A=zGrVeZSvc@7Kkpjtume29kSY(YO6a z$h8}T(7%xs*P)JvAKd%$&w{JDm)=ez&wwmD+SU&5{(LQ|*Egutco$S^JPr7ozEr8^ zC?2Sxi9=c!Fji{+vCpEkH9Chb!z|rYR&|=HWM#dFrh3#%=~eE-_&qs^0ncy%(LoNy zt2g<%r=$l#CAZri&`j3@shk zz@3|Iy9GJ6OoFM#=l9L6_oNNru>7_ma8{rLJiOs%Cj&b1`Of;LQxY@6Ff%@U8u;^q zCD3Yw2Rm;n%Wo!=nkGtjbQNUbl%Eif{Lo*3^Iz0x_f2IUwAUIY&y|?rDTIwaZvV(U zUD|1%GxH_sZIKy1NqA;@Sk2;4GFDe(ko>}4l)}v)NmrbkoD6Tar-PesI^~|eK88Fe*#^}- zEG`b+1gTGfHRI=2VPA@}-;|r_Se`WzHJs@0uPoa`AW7mii?p{E56{J|VFq z-c1qn>hV0m)=wPIDb_6IB8qI0YmvWDIX){<&;m9NT8%7nys8F zrO_v6?s?!OXMO1poLL5ysR9~RI&L-5QDm?XY|8^4ow4907S@UXll<+!%u?a}a!w)_Y4A?%UtH*DD`tUKFpS|tmCmZVZEPEA=j zZ>*|e_(#LFz(i6hdk?@R7d#SN`C{P5xQeI3!4n%^;{3Sg4XlwG(A1p+Ui>XL1Fo0f zfU++NBiR6o^WS1kA@LpVbu;70PLv~9mD)#V^0WpHsZ~gH_Qr>mI7!@<8qiPX(yI!kbF1hic#s0BvV5u$n$h2H4)bv581itoH|)2dZ+sIejzJCBG9GwmPuG5_B78sPHVU-@1ICrt zt8McG+NK_Dv#%x!oJ|@?w^`k(gT7~ri?-zb-4yFdv7#qI6Sxsn(hs}d!h7oNv^Dal zNI4p5Zx5YB_B*4|Hh=EvhwW(PkKKElim|GO>vn^un@>mWYUwU+g zKI)x|FQ6U6NS0(6hjn$V2NGr35@^Q5U0Ne+x}J=nbwd%MRF4lH0qnJ_bK@V=h}4CF;G*2 z)#@VdzS+cT&z_7E{m|h-#4#{rTm^XzH}Xls{h{E&e>oASjKO%Je9<-@ob6;do3a~i zp{e*b>~-=|sJW51FngH2Tf)g6cAMsl9pVk)ge^o3$t3Lt2e~gKclS%7iP(FfXL924 zunH5K{gUkuZu(X-Nn$JZ3PJX4vG{`*L{Kt*Q71Gs6@Og(rw^Mnpy6VPAGq)Nlv-%v z(~#^b+EGmHj1=&!kkl!7Z5h>8J0e8}HuS}##*!+PnomQi`AYn@-BRkiz#+Uf9NIm@ zi~LLcFj~ta1`=jmW)vw(h`r(dG)$9XC}F^x`3Yp?M}VWG)HW3Q>_G>C(QpR$fmd+b zS=q=`u;ryocAKfp6e=_N6XvolGp8jASO=yVc=xwPcH~hDR1;5&LyjFYgViZ?2 zhLqSd<05NTfFds59UnIqr$DL)H34x7y!I$arzYmOQMCoIORAljXqsw{i>&kA5OQtz zg!)xPIe`z43&q_)H++$8KD4hz3BZw}_3@rH0_81%c0N##ycuy8xVp|JqjiaWnE8Cu z7}AKb$(6N)F)8{u<3%la>63upz`GLp+LGhQNx!DVcQc8LO;?*(;NrOwKj0OjAeV>1 zohSL6-)^o#_z==PO$j6>8!{noYARMS;nEnK1NPV!HFSg}0!KmQ&mgNR$j!tI#cWv< z6)cnrEV*|eR|-wG3qtWyamY6Hq9%rhg`S%3)1jJ*3h9(><^@nFqeNpM4f(F}{lkNu zJHXRnC;?UpQnEvE_vC>|_p1=jkl}tMx|a;-FR$`tcM#-3>M9JoO9d`TXV;Y+K%H60 zfG|L^0i*}p{(25lv(QgxfZM%TQ`W?jV^Pq4jvo5Gn~gbz79lZvY`?#-C)|QHhL#}w zmRfsqI-Dyxikr_v()+g64NOHx_;K6Bi<*jhNdqc6Hf}gH{tUs3+i~c9g!TkTDK(Za zmX@OA7**xg>|p0z6%o!vaJ%q?nM`B>dHx+M3eDpb&Z2jfXCkbniQekkYA&hYi;%%X z=>#b*CJpAXC=x%mhK%Ka!=r5*1-ZXNt&a~JDnzB65~w!xc?-fo3#G9}g5M|+!Ynky zksD}VuiesAWMTEb2l#ASViQVy7fP(FIi%;lxQWSYpI46v^b56UHOW15{KUYu%&1O;nIP$6NSk}q#2~}Z5gGlPM z(0EeIk7E+|*{-??--Z>;UwZy1vz;khG;lk44jk&CWN7q2!LU`gEf{kEH@+kdeMyKJ zI`nQbl^80fffq-=Q(MCB#4A^lA2>1=7jeMY$GYjAI2$|A{gC^~$AyANLyukKu76xcTlo z<3EM?yKEEda4jL4Pc?toYwJ3zsmPAF5XD)+zgLSgr-X-B7=XbA#}U-iMRRBN+HRgr z@x5_@_ihAkz9~+v%6*3&4wwtJ#1OB;+}UM&uMXTmG2B$E6V#ECNeE|HyVdy?WH6Ap z1~-ozwx+BijKS;p1%aFFPx&gGHBH<-e}?3?zd$BbNR!&l7bo4VlV9mN3JR>RN4mU znZjGHoB&#N(DuJE1c~;13vd?i|Gvw}?wdcy6Hsts0I*Dy4nBmubd-$ryHL5M*gBAe z3SqbvLoXsyF*Pn18CeGQU#^$Ig&eL474*!atH!&OQ!VyjQlprrggIjQEt~j z_8;!bTOh9o-%n5$ri(yVk#4tU7TGyWdS%Al;D>kxZS^$j3o4$2rYIe>en9JJk-yVa zMCH6|j$)U`*|Zb=H+?yM0VnYT@Tz%Ld8|_tRe(3mWtLD!DE6J!&gr!U#S736*pLxP`$DS=jEIkOw50Lw<3v7XAQvU?fq z??w{p2uuGW@tQKNb1`8Oui`Dyj`720`^B3ZAdw&m^(e^=O)4@*Cxc=IvPiwmM25T$ znQ)^CsW4292pt1#z#bb{Z$SQjF~;#7O*!Ee5B7$COb!1-6J1Mbxr(D%GEYNz@b8}u z=b$w%dLF1InX`t3a1CHBg}H=q1{yN~v*+sV^+DBU=vBp`l=)JV04+ud13{_7^X*Nn zgg2{b=$^y9E6}aOIgv_9(j>6B-JKJ#A~*|XR2cl7(AWj(oeaiTc)$e}LT<(|$d*M; ze&zUT5-JQA^xvOn5*8c2L)w3ZEG$q8L8jkZxM}G@8=;-0AzIv)Gk^pCE$E2TvRUXW zuNG;YXx->Lz0qZL1(N5Ff>*uXinfm=BV1!#+0rT8L-tGWL9;5kKzn#oH{PUUbu|xJ zG8`G{nsP7N|5rEYOHoMDF7Xte`Et^@k{ppMdmh?8t>iTJ)Q|~=l6OdbsJ7&As9y<( zQyerJl@Cf{c0xuM!6prA%kg;=8F^wyxEm@$b(rS`UO-xpK3p6*5i(O7icKL0-giC#Gn8w zOHo_F{nv5ZceOd9u6%bUO@{>V?i?`&6jfvdIBh13k_JfID{c0P0oy~*h7RT`Dx>TJ zoWkc0X<~o~t*Cbew1Ku*TRt>^OFU$2s$DAT%H|^_Dy5LK?n--pM*S^4BIRnXOu^#(3ym4<6A_JObsivbugTaMRH) zO0x$lkPK`qarenw>X zFrUhxm`|Ax%57b> zR2FD&e6g@k`t58iBE8(rl)4KDs8xhO{eor-#9e(@++|CT4_hF>D69k4vG{I3`d41!uq9 z^o*$aVsoW4jf4aQaG}|0Jn|dHS?rqsx(JPoxDjmou5Y~@hw%fss>84s%=8y3%=>M+ zi;HbxgMvqCFMcR znIngemVyw2-UKG!;-l{ho8n|i#7txCpo{*N5yUU-&%zY@3*taRqThthNT%E{1vi4E zT|$mHf?N=W*pms1@j!r&gYRy`w6T)ECBycDxGT*ccZqC~x4s}O4x3EsgaCUqB#@Bk z6OcvEO&cZUioeC3pSq!*pt(?>D~(D<@hUfQ+tgx4#W-Tphok2^x>ML+k#PT2fg0eL z=CQ%xOeSMu+>%JObg;K@H!CBt;cgySx4Xh#62_4;g3-P-8*^*V>)C}-ds3N+!y$1m z#64knFyx~dD&ozNPQQwYVNp)HPiALB{__FoSG$QD{P3J?KB1|}=%_|Gv(wLkl?fwe zfy)cI-H$St`})Gj67o6lD_{6Y*pC_N!<*zOI) z>oMMgU6Wnh9wAIyCNPhLrJ4;|(C0NUWvOQ1QcBsfR%NJ%(uBo@Q9Xhj84|0#sCWF4 zgon~MbyF4LwHX9j=a{LjO00+C4BDG~Z-$R9kaXxGy6Xzs$nL8_+xEjx4&;o zs11PrsI8DoV6?@$S>EDW44goY%Wh{%8-ji?|1u)nyvl^vLFoIPr;Yt`B=B>cpvl$& z%gq1>*s7emxo?ZP4+qHf-~jI?dD%aNz2>C2)Vq5yfQ+o%AbfuuAYHeBO$Dy;QQ#UI zRg7P^vIN}w3}ht=wqWPJE#s5uDfas&iZ_!_1OwkY1gl1gM4|&gm!{p$Y%ihjZ#=R7 z(nt+|`)!*P+*sjB0gP+Qy!{UEh&C^<~xi(%NE2D`k@U*LXB) z%%R5fP~!wQaDAw;4KJ{Ox`>)nKI=y0$_J?ar-UihuWOCq5(yRQ~%|J5Pr;RIITHLu;WYdtO=1e1lxAl3pE zV6zsD!W*#B!WS)#NJ#dJ9a7sOg%F25+}r}WD9reyz-1JNZxlwt)!!ZmO^^Btb0luq zpb2u;`t2W_&Qx zD~^tnf^jyn6s;Vottqk7*FdaZsFBd;BdINo1uT8Ev(o#lFy{t($d60heb2aD17H!syA0=-=|r?v!^ zF4mDRgPJTD>%F0L2-T&m?`*+1xdNJnA7QS+#ITI%)wztR1Tv|a6#8bsUD)B;Z`0Qs zM{3={(t-$+GqeEr+p1fN-wlS`X!2mCdM=-8JZ>^?=geR3HJm0*p}z+eG2so3qX_72 zKO=HzCzAk*b&N1im8FQfQeDZ+c(}TMkDJF8tTZK9X&7iu3L$35Fn&J2f*bMWVCfZ{ z%(Qqd-|r;W94DRsWCY}nl@v-i6&R>=tG%GnU?Er5FtOYoO!i6VfI+{EH}q5F;{}k` z1`OPV8}^6>H!}%XFU*-+onIlhSC7(DX9V6RZogc1Dm%M&JNDq^@=58qDkJ2$DkCHT zGD3*_L+5doc0CC*D5@qACq>!@xUsrv*uXDo?Pwdnh!mKb_wjQ10-y^u-FUgA>HK)! zmrh+L<+;_~gkN%r^w#uQ!P0CUP z$*=OM?tgWr4emG7%y-PRH*kU<32J)=@@@U?A(&pD^_y!scg(fypPg$N4z{mU1@tE7 zW-CS^O#x~8X2<`I`IZx*i;hcYOX!T7fLy1#NB+|pm)vj0z4Q+=ZqFSvZX9}Oh@(>( z4GKozjQhut(|F_f7CHxi_%5*YhwprIkjC?KbSb~{P^!0bn$20S(4gnwk(T|Fu zk9T8tH|6R0Db9+>PyQ@DKH-@RiVq{i13nSWEQ-^icimmU=|Ij#l-BJX#nn9*&G2DP z!B#MX;f)1dC>Q0mq5K@oR>VImeQ+t z^cAu8$`Bcd*+AsqLI!ewDI%&2k-jiA#GX4s_~eW{bs~}&92|*~z=t~$`n?HrkS9k$ zE5c&!i*r5)EFjfhNBiscSkQQS`Fk!=?i*DGi0|}$12?cRNJhB_(ij)(2YvZL^gES_ zz+cV7A^m0W`2^sNVI1K7Hz-y$4mu|3U6F^&<2O8z67Gfm3o1!YQT_mZkMzDmWxZ3L zO6vCKZpNaSxqrd)_WhZrs+9&pfK4Sq4%3NJ=pGmVDf6bP0no+`eYOryQ(zC&)&m7N zeryU*-2xoYMQ!;}dHmLQXxGhVywishz8K%P@h!sl0KO1*%OAzpiSHZu1|lCSbM-Da zO=W=FAHV+UFZ5pk)~dg_`6A`nka2!hS$%_!-FPt!3e6Z@m8g&-eKk^!W!MKFIvA=hL`G2Q44#ZdW2Z=}k_LwML`*C{0?(&I-Bd zyUU^7OlW@mZACd~8sSAW6$4@#JN*#Lm)=j)xTdBt?&goEQ*Zp^*BC;1{|2<$0yNc}yh_+9#muEL*Yxb~v>D{Qq{BWwQU1z+h zU2lxBGgL|lWIn}_V)MdOI;X3}-=NQU2lQ3og=z>earDN6TFP;qd^Dv%<$+R`l|!Ib zje!y>-1qR3$JK;5BAn2S0F^3t%?x(DW6nxFMUDoU?I(jwGY2{fg!O`~ z%~)`{Wng0PsSNjyVDuinJ%)REq9`4=e71?O4X!HeS$nC!Kd7JSj8PPGw=c{vgn9HQ zVQzHyhB*M9VjAl%H4Npkq_flK_FZ=hW}q*vWj*1#yXj4~w=7@6b_4GpzVI?^gW*Th z`>6Yd65UhAZ+qN*p-!oBJU3~mueyVOQm!LC<+`EF>hgvD6GH#A>=k`sesj|o=Iwt7 zv!yT0`)WS>p>(e2;HIN2@_ww_2&s8gE;J8n@f*qzq(0ksTcKg%o_0I4okzi3(Myh-sh zR~4y~C1-GUO?5nbw8Ev?TF;U5%NrY`?{?I$2o?m~HgX!TwrMwlvkOu|$OuxB?4aCE z>~`SCfII#L-qg6VtIC|tt8J!@Yu*_*i*n$RxSQ_NZCU>rKbtL&gKn4%$gSpp#hhM4 zsmz(^;?VV}!yG}R-W4pc_9(oh4eK3HHf$I@`xMS37BL#A?OOcVnAra}N()xdybdud8{|Te++Rb(c1= zrL?@=p4Xdx8fQD!KCIdTDJFsm<0OG0ZZK~@^==5m%O_SjovTE2%J(?ea0fsmxL3bN2ELLj)j|r=*WKVyfjmJ_A>d`4 zQkvMkUgcc(bYYh8D`Bmm+o|7iRoM%Q*^j$Pgp_PBV z=AAjSZnv>GI}YU}M7F%6^|4nz;>zSYW-?$_H z8F%=pL{4Z9oS($609oqAEFo~G{Hi4M#9ZyVo_y*$Zhi?_!D`2+4 z{1)al>SrYL*B7qMTgB(BT%EImU%iZvS;wzPf1Jc_~s!mL79eokK2($$DRbsC>B=e~*K zvu39*AdjwgrZ1&Q^)hpM*d97;|enySv*SYf7A{z99+ovqKzc6o2 z;gaR6rTish3RY&XUAB77D%a{I1;{x2;k?2n%hqJC%6n|}nicWcYjP2Db%85q^;r57 zUzodMY~h-mu{o<(ty-P0x@9fRF3cN?GOk>go2R;rUAw*@uW*b+=4BTaEX`Z9W<8(j zBAJNK|AN?7BT?R-W=H!{nu=#YU$G5l2F}o>_-YwH&8y5N#*cZGX#GN&k=j8d2I8F8 zF&i{HnRV<21|bss5(jOFd1|L-oneE{FIj~d3Tp$5$(q~N>gs5n%?8c? zl%9?jPpc1Y90>wc6wT06Gy{reparId-KG|H8x2QBd7&$CxR>nIp@^hf8-Thon>5so zrM@icWuhLws-a*bD$pI}FoUJB%R=H%z0^4g*__Ub}$> z4$qHchz93%qStCP0{uKqKXX>|g$1sBIyVaW>@|6O_M_RZmDx*I=25S87?wPyz@1)1 z{ll6}|DH<6@Oey)yE1#tDn2Hc&tADEFFSWV=3F+0doE3?V9n}>F^G{{c8;2MX2x7P zv)1PEtLVhb&$}~|(fqP?`8jJ{tMjMuB)bqrp)emEQy9%JLm~5Wr|`@0QC&v!E0F~9 zjwy^OG!o;eQKR_G)HxY;9*~jHBJ#d82nk(JOgmvdgvooHn5O-bm}rIkHV{)JOd?Df z%*Rjr+^0Q3Oe0}3U~a)QJn3`4KVQnu&qXQPT^hik34q~$JB&H275mOAl+4!cySYQ~KgD|viP4H`gnGLfzhEL9YkWZbzaE?7T zCSiQhXcDuIjE-67`#%y(=Jflr=FiVaBQxh_%ps}w-gmN7qd{`|T2 zK0tMyl`+RbGUq$8=HH)5rq8#h&dHiLeg6Hk?j!d3saf{9vomK+zi+x4RE-Vad$Tg8 zlU~dGOlmviVob+jXqn&b`BJzF@TdLk)a@hKYwmFS`VKn{_kZH=^8dzsTmFBf?fGxQ z`YmTngJBBS7pmLP>UC?U@N_={z+0yAbMButYcyZ5di6?v_Vn4AS@Rdp&$=&T_Vl^; z-^aTO`MgyHYuA(edcxCq{Myy4F);HV9*sF%M8nMbMMh@U{n!wb#?cLN?09}vVO~xl zA)V-i-A%-F1#hq?-|qPyBPM4vAt&A>rgj_wEk}td7vUZ}?(?_Qz%Jz!WUVfsGe4_P zTD=A(_Sp)vQ0lCedHH-CKaTFgY3cUNtht%@Wz3y3KWoHiatgmHZ`Eq-*ek&q z=Bw460eS=T*x6UFA+#x`Kpk!2+I$=vXutG!l*Jc62g@_gBC85fI^UYIR?1$B)pSka zTE1ZEx@GiqgalURVu@a}E@v&THYUPjVR|%sB~CfiA^vW40VfO_q07%(>sr=3ipal~ zXdZH1Q;;R)t|4ml_`9XYvU79Ss2#Fu9m;~!*;*-&FQnDLf;t^5Q2H-Y)6(YA9_DdM z;(cjYi0k211zCl8`PdZxwanEBv_^&5`L4CttJJj>yT}SG=qp`?Ye~VHyhmw`Tm@@X zIR5T@x)M+8aX~W`W-VKjhv0G8=`a#8h7yXF;g7fq(1F-*vS?$f{m9=vO>NnpC}gdK zZplYvY!kjFcjaR%$m0uKc{zC&g2qL!(##V7#nwcgv?U4T{ZaXUsiw+0PQ zXHvnswY^7d8r|!C00&av*1L3F;gq#S53gLkiewj{!%6n4g4}gDV`e>8=z2V_$4cFL zz%@l#%dnqeATBK|%vtvE6dbDa*V55eNOIP#$wHUqt)cx)9xiaLM&`7z_{$3+WLxn6 z9YfN|44VJ{slPN^W~SMRMX%@Y!*D|WnE{&@`4VOj%GWTBkoA)ZNl7B44)Dj2WOoeq z$h!%F<}*?^g^=L!gggba1#Zv7bV2mR5rmx$|9_Up|Kz^+;y*9n{}guyBu&sT`)}P& zV=v&i9{1k(kBwoVy^|r~6Bx33JVP!49y;!)Wv+r>Z}|ULzUv_*e_us!;;NLCq?-uyk7HD5sN!`85Lwi;K_8hF5)SkNA z_g%G%e%q8cOX>G}<>5W_`!}Uj_5W6RT8(#3d7^^4|5^Ea8U22&)T-e=QWmNHA1QCE z>HI;tPqkMoX{xtv^p!)woiBj#~D1T7HomMzC|M!*G)pVJUa54b{*}rTYB`T7zgF!Rlx1o@N0odv z{0B<6>i(vZqQ-kg=}^;uMH#GyJFLiRxP3~aYTu`Pt%iR^=~BzNS9wz{-yY>1HJ{ze z6KeblWt{pgS3Ii!D@vo9&MQigYA@?cr$kNnDZC66na&K4eQse!nGE8;< zN=Z}gU-h{EMJZLw`+_oG&Hn|ZL{0B`#i6GEg7P0~ye-OFH5^U*-+%vZfq%Eazgytn zE%5(d3!D!xR__(KFp#&SeXs#=k<|yA0RM4>4>ki%i1opEC?>T-HmGr90YmDY3MT-L z2zgqClL5yj`(Od^%4Hi>_jJH-9Pz=KfDMLcRQCmdBf@;J6L4v?4+aqk8U36OE&yEn zz7H+}Tz%RH7Xvn(@xhw`7k%u5w*nr$%?FnP4w&UD&ntj$*7@8I0Dk7O4?YUm{C6Mx zE)5^LNiAD74O9JV75)ft+A^QJ8?b4gFU?xOB*o|6NW;J5gRcO-(gVwYKYP#T?g8xi z$OjWYLXN)gOUD5Cjq^Tt6X3=QUwO=c-|h0b^MI2t`^pmwcxAH>P5>Mm-2@$3fSD}b1wz_#VpZM=svsbgAIV&|K@{D zfVU3cthR|6@NfKm03)m3qgA)K}F7Sm<2Fx$?!2;m(OMP%U;AdPuI1}*2 zQXjkkuq1ADrMmo2u&zboz2bnkXNsw!?(H+u(^9I`{WdH8!F9Eb-7w(or}5Qp(7ny3 zGvJWx28Y+?86ihW)l}fBmcCOkV+{H?z_WQ7)xxK>EjVBB0{N0TAZ;RqHS zv-TrAft&(rul>DegOHl=1*qHURz zW(pZw7I>|pwov!I(%p_w+aUKqX}lv;IJex?xF3|Q)nY*7WP}L?_enDS3T3v=nu(5q zu29=ecZPTm=p;+6pDr*V52i8E@#%tyVOBw<8kM(u1aVA;!I>_`<2O_Nb&8__kIo2k zj-DN#5$KFhk4Npf>J7G=wcNBLBH8_SyUE&+`i9L^Gc4dYWW?;zPRK+LAD%vZcB~Wf zbKQ}W*2yJt3Eb2h7dIS@c7$gHLWg^xbEWug*lQwq`TPj83HAKyW_J_%!5pIN=~qm5 z0=+Y26c&~NFmP@Jc8G&NRtsXrH-N%;jw#6U+_P&AjQ5wxRj)G#wmf+E5hYC!tC7e_-UguBNVerhQp|AD4SDse4ae}z|*eUTD(O)!(shCaYYf?@|%ruJwB_?s8b8I8^ znHN4VTtCvU&Mb|B2nxewvvcIV3#EIVi=5G7sI((rY?x`1HrO_w9_VCS4W#Ny_kXqnuP4KVpkLBqIJ8Of ziBLzT$1pln(u&W8g*gX1UTHOO&}ly<4Ag3iyc&#O_N-a7gKF$X&HV^@(EL0&`9ndC zIL~YtHytiHPF6x5ny1bCpc#~gsW2OoSSQtXN*dFggio&O%@h2x79pAwwerl1CWqB& za^%45hq(-6&4wLjKg?wq>r&WZ_QPC;vF5-IvmfSi4k)`%V`LD|Bt|vcFn)T+Ro~dc z_`3OyMl~-iXUR<(fey2tKlw!b>}^LS(W_K?M;4KhlWHL0cGs{lojV$3^wb+lEux>C z-w-Vh%NUlfl?PoM<{-l&3MlPf^lU$Q+r>DvOp-ecS`QQ4d$&BaC7>}*ikw-u#UvT! zM=ydiN=!Ir1|_{tK32a!^px#t{b0vP$t*F^I{EMQgBwHUBo>vOG?x1JR%| zcF9AY{-8zcUy?RXs`U_)<~o@-FKlMoS@WW_kkDafza5u6-@ckVD|c?RbiqS1bJCBP zr$FZMhb@|b&pi>rWQYcmda+e3U^feS$uz7y?=KW_P_FqYQ zdJg!GwQ@$iUzrwR5YCs+IHX-NQuM1xMaom^!M8p)RHE?s`pJ^uFiN6W4p|g;!zHdh zrZH@rzsNNXk|w7IM{a_ar!X=6aJjAHT#^)agp^E7j}ybTYvsZ9DNpoDD05i(!tk-_6+JFoeY_)FavTpUnsR*MmWC~1TbM3wNAiT(cAc+mcfEK8eEU7H zro@__gdYC>0`#1F2wxUnVO|`LS{L|gT#VY1t=o-ZDCbuf!W@y3pS+=g!FT;Ghb@iNR`V8W*`>fD#${{Ub|>V5Mc!FMOjXE3cW zbPNqi!54<3;|O09!qc_FaN-e>MNT^}FnrY&gWx9*+fxpIy4KRSuK4fUQuSg0$~CUR zbka|r&@iQu4ClqbRvoikJmS$g$xHfH)?k#^)REn>GHaNgCUhjTyKTd3Z&rED_p4v~tP?Qt{gjKZO0&{85Y6plLC%`>~!d)0Vb{usP1~fV{T3!Iz79Gp4}2g# z*Vk6~$sfVpt1P}XTKu9ZxhgZ8Ay?l&@-=k$&S9bh#RQ31H1Z)Yu^6KDuxaGqcs22i zXsXdS6E38^I9KORkSy)R*(6#czvLY)c5+c)rpX)^-l&a7sCJTjzLnvUPm^J%v;)6P zkWzcX7JJiVo-;H~IGG@g6t&S+S3H77UWahJ2w9=1^T?B|W1wi3^hnut8Y=*+N;V1vOf{hER5oTUq87(uK5=aYM zx>A=^lAW`1uIxqos^Ol^TM5~Hwkag$EA1_c>f83R-6p8jo3l0M8wzHaP7IPA-a+z0nB$(o zGGyh8gXEPSUJRG(ZhDnxZ_-h0!u)-+98yghnIyqLV!LY2wDJVJ7()tX*rTk?6gPk4 zbUMbm=X7*4(HI1iyMQrR+#5_C#*uExc+Qe|n2~pvWXy;*8>z8iSZnMNRSvtw^p9Dd=vi zQphl4BiH&U(Y6#5yA*tkOYpXF3N!vUl_xw468GEW+GLblPSr)0ALT?YF+t?UMT*^R z&vfWT5})AaMaE)0#9OtkoWa|6t7FDVUK}ZU+oTQ>dmiOwc+v<1n)*U-qNo*ZB5K># z)y`P%LM-%j+vN_;n^!802dSOP!dU6ek!Y&pM4-3jH!p_#zNCM-H{;DeD3j%iqwgd#blH+vEz0=Z*^#n$i4aO^eV|c`HWKYdHe#^ z07Ps0E>5sIaWhijmxMVcF^0l{yJJ9HVsmDwXFsS zKplR7la;R#iswa_$c{rBT;~uX$sLQd_I0e1Rx#7VNh3dDQ0vg3u6iE#M{k?1W7@G~ zv>1`sU!W~V$H_|UQ}Dka3c1Yw{3Yx?}(w}j?R)djs}W@5qe?A3Tdenx1+Mf9>kpEBMprV#BtRV zZ`&vBaggFP$IT^-ME>>H=(w!)QkhXZyLqcW+PPSyEp6jdljv{0X&nVAW4PBZ@xYbq2s`1GQ+DA-#x}ytUYlWuCs4u zb#9ie2WeP38uGenSoE;f+xEqEW;kioiE-c!*SO;jc-!8(o*<4^YfWz_XFc32`t@0z z&)wMO;fg~<(u%tV?ibikFf!gFS)E&M7{+t*fv=f+46WWou4Rk=>SjN`k1OXkZ}Ib1 z8Yawb-fYmeY|ws=n+fEKwmhr*2zM4@iEKow9_qV9{HR4|Kzbtr8>fhR={^tlF|nQv zUA@5GO4ugIqYymY$f2Sz{b~(U%1utnbCVT%*6FFE{R;ZyzA~mBheJvu!}*FFf4j zM2YHEvYGv%mx7l28%QD*QEsz1sMR~+hqIcp*U0Q}ePfhFtWSs15YtuP!_(u$_H*3i zh*s}Z_gQE_saPj!S~luF^$_w!i_sX3QnQVVJgliTlS^Tyyd2?y#PB+x)2Q4fZ5iaq zijeWx)^$x|i4z4e;1K42J6CEbBP|dsA$+m)BdHzU4LVZZadZz2;aBx^*biS2A!Iv5O#o&nD`j;n>?|Yty#!Mh@-!iDwCe zu!L*b#GU~R`93$RTZfYBO59+}E>M>?OZx|6gU9sBIIO^oKVll5@i;5Fmd%D*&ys=M z^&w9EUf(d!tAopdJ-lZ%5sb~6)xs6?IaWhQo1?(n1~9=C0;WgwNZw>>tBN3M_km064s zw}{)(l8f3OmYA4g@qG}N4vT&jYnBBkViKK%c7AoIx9y{AKHK4~wB0}GvAv<%-b1hb zGW2=j$kta6QQyjIhqfMudw^_vU121|461v--Xunrv4|KPE-Dbu2 zjj|(<0TJZg?a6#Z-|9^s+PT>i)VaBh#LcZ|4`7F67fK5e`c%izSh1Ep$g~u*=R6k& z(){jk!yGn{nE1vcWsLPj&&qM-2WUUgaWtv>R8)8+d!X5T#=JPR#KR>fip<0^+xPXP zu!4yX`6e}K2k<@Abm^u0e`HKA>GWh>C@-RME6xq`GJMvk@CY8 zh_jUDpzEf5pW@9ouv#r>JA&W)+YaM*UfUu3&TV7(K=e;sXEAaK=^Tqdy@#w{|2sN`~Oc{j}0H<~Mdhy+^rx+XhZ8%zg zUmG<2HNM`;>))?jpx#Y(L1J`A4PArpsq}9(7!S5QJYlRF}G+<65Gb2cZ#ni;P+S8#^CqyYw`Gf>{=pz*Ir}zq`nz;TJ5vQp80j?TE2vn z*|2vA8S$b=NibTcme8F$Nh}s8y`1v$i=Ga_+cv1xBF1l}u5=y^fNe~lO^+TL+h-&2 zOX#!RkS*xD-gwtw8`o!Rfi0=e_APAVw+6O$XsluqTFTgA!L3q(Z9Hr&Y`v-c86hY1 z#rp`hiG8*YU`y_^y$9RmKHG8Frfi*h$TuD?Tu&&C6E*bgr;O}^%zrT+(vkkq6(=TO z%+N6wcYO?8F^-hqb&V+M8s@p=dBho@(@j>qLsoihp79`)&`U#u=PIwtj-tY$b&J5 zl29^o)T@McCgJS0NbSEd@+grJC()UtWT0-7e06K9Y|juUAul?2-e~VDh4PEedE(^K zF=ezA_jc0up{4e=mAB(tHmN)r@Q(Imv=&W~M~cZkDQ-cE$vr7}Jq?MkR zd~GoW_Mp~uv40DcBJ?741b4R`QFv?0R@#D-5VBMD#iI3SmjhcvjQwK10?Cj_m0}Dc zvHO23<0Lcr?!#qip`K@^vNFr!cI{3}=j5)s`*6Y%5H1NP`6rYV%%G8C5*?att8U3w1v(BjtclPi_RkzQo}6Ng#%Rp8%aFnMtJzuux%c)YWOzd5d-?2mAw@Zm8mB+HLbZR${11K>VlfW=O!k%@mikD^h&o zm^UuatvR{)JgocXkQn5Gdou13?aSl}zFF7d}$_>wsDX%nzJ z$-sO6u?7eP)LTNm>9=SezPMAJ*Eb4*Vg`Mt1 zoEU^VRGBzkghb&^LtAjOUr?Mo$Hj}$amI$ru0=ZimqNz~hC~mL-@3ry=7M{fWp4W) zmky9;)Kz;(@$ImS`-Ls*3oBe3hOmisEOf|FEX%vND}Ge7+Y_7MI5zzl$k%d)UvS?2dE%SDu>rB>^tZCA!H zv~M6VIY%3Ic$`+qfQiK|)5?t6;gPI{)8{=)l9*8e_~u$y%fuGv90y6&zeK>S&+zmXY?#6R4eaIWGpp<+uhn_UU0WR5gKYQtU~TS>X(n1`;?OZy(KeccETo;U^FpG;@R(-SI02*Xun^pA3^D-k zLepxg^eP*@zqTcx)``r7q47V~ycccRqSere-V~Io2%KrhWUj=Scv(7-8_4?8O zWX#^*SAOAI#L__dhf6sw9r~IV>FDl1Vud?G)?Q*Id$WN}g2wj#GopW64)2RIxBU!K zfBz?`_ix96cZ58M)Q8$9IrSCgtoA&`2N`*T{82sAC|ql}?@Lc(Vg<{bXQs9RcP4L8 zPDEiG&@mc>+WTV!EYcbJ=H=yD@-iI-nnv=nI#y+G(%kk>(6_@c=D4Ec0@RxNso~)t zJwX1Xmb}yx<0TqHxOU&tIB|eH;9@s4rQMm=;(mD@`PsZaMP71!Z(a*^{qx%K4|y$7 z^Qx`?xx5zk%j>b9&FeGd^4j489&=YUz71?Gv_fcW@ASWB zXf_(~?ZQ~uHB#Is_;+$`TDlj{g~Z;|DulPACHFEU4<;YxF_>bQzt0DL8(#+d3&r}< z)hJLFz9tqO%8WI&Ud5y-CvQ@`*#PBZt(t@dcD*A}Y%w42x_*7S zorZGP8?7h0+O8j{q!{9RY(f8IEe@0)xpaG-6Rw3|t{J}0acQOAnS6V$1}&cXIF?oIqi?LKCo#SqvsAUA%(_4dAVdqoM9hxDa9xBU+&@mmciTbUptF*Syh0~#|=zS}Z=s9zn$iH;MQ!(Qc2 z-gt9e6H)QY{?N`7>7+X$9erf@rlZB`eT;pHiDBOouvX3!?H#4SL^8MyR^knJ^T`*l zY#;*8eAEwk7@X-}_p%kqCo9q(O0##oY~5pP#Jd*owW6=5X+M_rtSj`rfnxIg_8QgI zrFYj4l;8gPcFX%#IS1O47eDrp1Ui;~x{e0QyVUT$)~74(cs2A#2u)YD6sK1?)|dlF6o%wbTOWG~04&$)2BG`G(ifwH%OwzO|&{sJxc@aQ5ybHOIh`SS=nH#!B;%$Js8G(B* zsKQ&6lb%U;;GF9@kv^9br$BD9Aa5zQqp#`NV{y;fBT)XWn!oSt;hSl9qy28r$^I?9 zt*@-UkR#E4Kb@2PYxejZq3=RV*shrh4DzJf+ill>jAY*t;|5ktUEk`^e^$=ABjmUB zthDDRt3&^CPq-uW=k+>iU3l*Bb@pk_WXV%S+lgZ8G5^GEIF|&NVrF_3bLW{NX80a~$j6Fl zsE2;0_ZQK8F5Vt3^z2cLdZdaePJ6RX?>kkesI$u0nd8#id)LYSZT4Sxq>xpgD(anh zr$8zGc#EE3_3~4fFv@>HN4Q>IkJC->y`X=K?(a)SxE6qtq@W~8Hd_sI&*hqX8mCC* zCw=k!uz&TQTm$9JeX)GAny=SL(f!Jvs+Run4O;q1^tLpd8Qxoq{$nNgj&yEbxLpfq zUTS293)kX@_-bIj6z5{wi{~G2(cQzinS0uCCIwbj-2n&4TS`^vKjjl!u+ImIxat@0>|KHAmM5e$4ib=%!V@S-0KynT?CRb6&;&Fv^IOc5^mVaBt( z{FIH903&=bNo3{SUuzGrWn8)0`k0-SFMO>%8Sm7VBOFd0ID5>e;odWsbX{*_*}w`K&&@+G=v zc$F)s=?dpnPI!H59CMhiGlBAtmq>IlAP#S8eqE&fDScr+-aHqh7;bs2*qEzoWJ=H4lg=DG|0zlUpWaWr_%Gs!ipY0c45m7TR^QD z7>sXf`D0qh9HewKrYf!vqBKIKSo?OtuusMv6I{KovsBhFjDu~dCIvHIfqySt4Y=S$ z0Pe$n^6`e^W6(2I=;$ z?w^)6It_1svp=XIt&Oa%b*h%&B_YgpzlWP!=X%JMZJyg)8S+f?wPDXRugUcb-Q_yx zSyDZ$S;LJJmI`}TELpxRZEo}0S4ro*d#f{}19N|Kngl4uk-Xni3F_SUzW4L{qpD6- zopb8cS)b+mJf}jpM%Q1_Z*SK1qcm%ny_e-0&1F_I%lhJFxpdWKpZvMYJLVzw>Iz-6 z4rQ5fw&+&@&R%5SpewFsZI^V#wg!7+^(9@S?F0LHT+iDiRovD~IT8`wO{OTEvK>0bMAhYS!RVD1O5&BL<6yM;>k#yU-$_$B78hjT1PBZ50~z=FVR`-`DyGG zQbFwc%Mwk8U5gfl_bMH9+9~#$gQ#OhYQ3zn9TYg!a;F4g<{)ZXIu{}R5?yWYKU?8a^#g;uESCmzLYBbjWGLr^xAA#Xu19%h*hj_E9JVL%ljTX< zIy_aL_D9yEJZV$qDNUSFfzgm6UHEFz=p_?Ig8@5xSJ*$&Rod3tU&HmN?K8U**Dq{_ zs!O<OrM~(~CYR_B}ftQ4=@*0T1A1emasIhNHSh;gOiNDaVS=^vL)^Gx~6D zO#cxb9X*WUgYexF)*>N0hrd6H7!!>}(=&$2m>+}-B@*%gVs#jLF=8(=MVHs^9Aq#W z3>Xc$N~84J#qH8-!5y<_Oxzg$2Iwb@N1CT=xdps%7UaJIs2Trz!h4Dg6{Nl&6gOI> zy{iaWORtcS(LcfAz=73ZxrXoPXn|aYa+SPaiND%AQ7^88qZ8%JQZIE&R5&knc%l(rQQp#6O z-01J2d?o$+7x)(Zy&V5;_WK3Lb|&nQ7UJs_r~`Vv1<5R>>8lV9-_}~|=l21*k;11PX6D%aOpe`e_UZ7Q z@DKz2026ZYB`DeJx9C4@_7|sK0X-w{X?s+Pwa9nTRk)byU^Y{WL|MfD9~ev zxSkX~#mgF_oUtc4fz8o6v405gK&OP6%qd}!9{T_}j}`UyU`L088<6`NUVTz?Ky~Pp zknP|=X|>@Gn2an?9TH_?=u|S3qdH_7mWp}Mv^|L>{05|oIJsX~judaxybeks_kLo6 z>NITK3J>sC`Oc!yup+dGmxZz+$HVB9!ukm{9!Kl%KV+Ai88v*uC)rc@7L4(Y_Evc4 z)$!W*K&_X#V0Y9~6`xlRdQ}T#6IKlzk3g@p3v-5sTpx)yJ#N(V*6W%j8nOy=4Qr4Z zBZ(ylX`UD|2f_V=1F>FD*#gQbpE;-@KOKpoe<42AiBC1)L6%&V#NB?nw1~#lkTw8Q z^gyrtr~>zS8j?D~;NE&&SUq_^ZR-BdQ}Qr|#ub@4uS5zcoB4=J&&?{H_mc z;A5KRcpu9DkKv3JjDbp8t=HdOGg*SwBQsY3_3>}dmXGLHNd8;AyGF90F`_AFR%poY zhpp%n^lzr!OP`&d$}J1BNqT=qyk}n45W~m{DltPJ{qDJjOhZks8s99IGM|^ArM6o& zr2Q~<42X%1i%*y~U6+`Ytj)Xc$vDuilI~KUvNX=8wx?J*pwUu_XI|!{Mk@m>+jgS~ z?eq>L#!Sx}ppWA)UW%$zS<%CpJ{G&}NHSG{y+%o>#>j+r8)=DY{MRA#$NyVIIWtg= z8uHXAV^9G@A|eoP{2G{XdPk)+*fVN(IGqwkWKUgR?7YB&|_FVh0ZNzDV-!5S5hD{uxQKf;u2&Bgw^} zt&3tit1+7@IEuHF^XGiv!4oJCE+^|oKM{I!b=U!fz3X~_6Q8XdrFxH?1o~!!0ur>l z#!x~AU)VQvSWsA!ku&3tBxi!VMZQ--K1Qzx8e@XR7@>Qb&{cIhzU~Y%84Nk#_|Hcl zrF@S?3MADfp;vEu6jmPKdpee5RuL@{47}t-WH=fnd>(6HrC&LxA~^b$g2>`iX3w>j z-5&`jOSBBD#$VY<`{%uoCo`?Iue`ET%`c~IhJ6?(V|aGnjkomO-|>!V)sSBfKsPU& zA4>NDuOr6dLJ~2QiCAClG@52jrSMFpcy-|1*tvB5)YH(^Q|G{MI;Z`&n9Yc3O;?Bh ztMhgVLpvu-8nR~qDCiKIeprYWYfOR~OACJS=vG=2|Hc7IQ4_h8k_gGL7E=HHl;%E1 zb;wv#v9Bt>#JA6G>OS{agguI64j!=`!44qj9@D;;_O`N&LWEYkv={9izCC~>bu&uL;n*Jo;nDl-iOWtnMy?4XyKHmJ-@ z8eWtc8!FG7=GP5wp3h~*gwAJ5hd#)R8aOr|VO-O`?7BH;!*V|*6{CCi3@ z`DLFm?*B>yd}pCW8eYW4@lTNYL5eS-@+pgTH~DKj2g;Ia2A=O=OwqjdX9;e)W2OTr zy8~ZsmkbN#M^=)X!@s;Kw=m|Ufn>r)cQ-9)*7!>qQP1=;&`2%7Z63jlfIWp_c@*0J zl}%3XN&%b&E&EM$h|5v;OO4WF2JC!2Hj3TK`(?)rGo(hA{C$+xvO-+ds7;Lqx*jE8 zQYs;r21-h?9+5u{EElgI4e;XicLU4B>-mAD;N;0eyF$P{__F zBLg~6L5uM2)YQAV;*}9-A+lPkL0D)>#{F#EKRz%^EZz2jbn*JgfVo;%6+!g>YEUTp z4C1pb$W4#9Kf*N)*NwQQ;<^sk8Mv;&H3ipuaZSdxY#<5gsKtI4W>dNErIx6cMqhHB+N=neP~WG3{FvuztW}t0!Flc|PwUNS%SByO z8#sns#+-u`Tvu|P1iLC65IT%kyOl0(TO3hxDS>(J7itamfN)0pLecb#TvkHAIx8;N zS=GX5d-FYPR&*fB%j%W+QBG-So<|yDOgQwK7FkHs#)ULa7Bi`)^=*4s^NF-4^WTJ( z$c(nGdb)CV*mNx{k&brl>z7J;JFC{nBz?)UScaeVsogC37uRHt4Mce2 zYJ-ZX-h9{9<|U~TqLAdd*5^fBDUvi5U22jCHlzd`Tqw@XX37IGp*R+OWZSQ6omEB>ef<-+p_?-BdJ3tjt6<4;$bNE%msIX14V5i`>Oi+QVS zU-3AzwyUwgCB^>mdS250O*0;0%3ubj-39oc9#w;>ELUV9n zE_+77n3SQesysI|EtOprfiTO#^2qd_@QVH-YPPegXq;KoSz)xd37_fT!D=bUOZoQ% zmtN-FO?n4p-q@B%w9pwowk?iVhR%StUknmT7wijBmD2+85f|f$OW{%61_NC@I&%GI z=YP*JIkZpA5mNa%34^o89n)uzTYrMM|5tv?@$Pnh2>;}?uzsdw+_t9k+PMd^1G@2$ zF)ct#KHV?=Cl}X8YkQ%-&8KuV)YgGIP#V^}bUTHHTIA<}8qE_C8F`?PaZl67`SIsr zeWp^3p@9`k)76`u`YhZNM~(QLIDSG?&K?hC(Z9+V4`q~GmMC>SWtSx?W3{rUY}~P6 z^&`|j1e3Kkz!K{YA8O@ZKh6JukYdDs*jbW5$vC3~#oC>LYtqyk8QyS#vT;VmkceMV zy{P=TEb&hAEBu%C0%z_+|J6pwXZNvr>Ea(p(-L2OJ^TZfg-w4YTI<0qng5|I&i`;P>zSpC$BMi7sFsKuSnFCn_z(M zZMvEU8%{;mfgbcWgDRxYlKWo|-_I&CC!f$>_+jUKpIf-4HQ+pd7+^G1HAcA(7%p)`Uw|6O^hWwxsa8AoU9*7Zi#bAG8lhT_i4di5ao6k zNrt+rHnEz%2v3YFu9mKi*sraJ)lYAchGN{)TiH;IXL_5ddc&S2zG!d0Z%%hp8O`(3 zI>xLRr0dx#i%T)ve`i;MOW#FTp{V|7?9GHeOf0HZWSXk0ivER3oO}FyY^d26?W*zp z7<1$^oW!j1OR+zk+AQ}^1Fn-=+Rzqc)hPXr=+>kFjWrGXGd@!0vBveqd$#!K*Cl2( zMv~UzyqTRF2gw7)6f&WBZzR^ZXqQ;~JEpZJ2UKF}>A}rN9go!2Nc{p*Yi_4D#D*vG z=q#f}>rL}&k$##>+Y;wSf3~21^?WF-ua6sdAX*8c5^^nHziG3nSlbNm=)}*N^uoaEo_Ct8-YE-H9b0Gsq!6IoxBS0*f4 zl&q2o3m0`&MY}i3V*6Ts^E^ghY@IZV^{cZ|0$6#mZcKL_5C-t)s4eu4m{5JU{M(+O z8b}c2Kzm1X@lKSuhmHeAqRqh5?D#gd_YHHrSR;c9ZLi8*-`!QE=O2(Q;U#_3VXwr6 zB0Y0ac4dErr`!=AQhC?C>;7A1!0 z`q{5wdsUt+SoX;9OeV}<6p7VN&u^5i7V{4eaUrdke=vwtn$9YxETXUL#dM)y(HPEo zixgf;TPU1)E}gjgE3x`duG_J_eyO(ifS}D&`&P@Z!y|f z;cQz`;EHqWHcK)ST2jPzP7Koi(&bC`O3iWoy`b{vku3w;yAxdru#H>7dH2QnF!E%w zz8Fsu%?CX~0XuMA)x$(L#Ejd@JFs?e0foyt?%1wq(cr5J4_4|TMVrE#E8Lx2O7DW9S;FZn2q86TYIan>5`7lku=>~eLnv+58N-8;`Ed5Y3) zluF`4^W2J7v>IqIN;4`bov2r|Xx%GP2Rm6a=0W=1wcbvJ^Ud&1Cc-TN4^-Vx>w7!u z`!O74I7%1I!?>S=@zH@^VulA1ZktXqyLX;j{k>9s?c0Y^r3B}BJ+&tLCE<+4Q>v~I7~Q3|$Njm3ew(>dhed_x#$`6A0&P{YAL!#&e7gN zpV2uvUbBisY2FN{a$7`Mquj0behi&(8hLDV7}uF^ZK3lB=xgRs8hL1RK2PV564+Vn z2x?rB;8)%Z>o~O&Xw6nh8#8+YFZUELE8)de(|> ze~7n5_;Nf$%M#&#j4b42f(|u5eRqUM5>~NMp~uLI+t1#OLp!r%UNFM@W;lxB@Sfh^ z5sY`~JoTMxy5+9+vh$sE9g<@9Nfl=wHbg_olEmWp*0d1HhO(!k?1zFIpp!z$5pE6A z|Do?#vM(qTir$q8OWyrh(06<+=x}7?Sc=2a(N(ok7Tp)^uJUD^WQ-<3l0zx*0+u4R zqrCIT%Sc_Up`-EfMe(k5;X%zbH>IW2{@kfqRucRPW?3Ma^%ATr@b{&cdoYttaR+LD zez$}?Bbk;Z32rNGwKBb|$;*H<3MoxWx2_npnaD-ZcOHdujd>Q>5#Z;IR~?UhD*w9xNtW zj^5J|*<|rlv3Z^fIs?Bac(y-H9H0>t#oe9BEaGUR`sk|vnPshy&Q?Dr?m<&^WZ1*% zs$xAqCO;cQ8d&Y63y&_MR4^n9#M7THJfc~R{OFU}qz(7gn(6KsakOFQJ@@UH&*F_; zqr{3f8FLTrAJ#;B%6yTSN9ExAmSAN|BR?5R7Ya4gTqQoOTM907a>Yv{Tk(9JhOXV~ z<<{`e9Z4Q0iywz!h(do~g4HGs<5%sCXgTSVyEPs? zKbk%`fX3|T*T+nFt}4UoX%0W|*30(Tqik(Y2?!sY@eq}-Sz$&*3aI!nQm-r=Y8 zhB??P*w_U3M&1;fd=uAI0FNeV!K4zk`*)jxzx8Q6a`!ay(Wu(Hv8h3)3DIvxp{)AB zNRJF9&|^kOBlCxg5@}xZ;issa5YRE0d6{Cem+Pv?6lG!H0%vA`qHntyr_Tb-&SpI` zK6ZTK#@F3+PTT&rx+>OpUk#Vd1{q^)=pOsBamV8;ZR={;JNEa?gb$cy<3}F4$F|aT zUyUq#PQN^x3$VsU;SJOF_u}i~i8OkpJ-%ltaXdH^$4Xm#os=l0x4pt3UNL00M9S?$ zdU_`AI_UTtm$HfM3W^%d*Y zzdAGvrQkO9K#Ow0C<6isejG+}F=x=w--rKMcebvSFTN}RHjR_8S#JniEMGJ!d-g&f zM>)-S@Mn&lKz|i~;mF`O5$~w&*}A%gb&9Y?O;ah}`r=u}kYS7rFI7TQL6(o?{G8rf z5neJP%GM1UqlG^u{L#XY!jZ`EAGtYBsh8$WXK@=S>+P!jUzI@R%NW-1oA{hV9}8z3 zDddv@ioSf#A@dgTBb^!0o)>cS(F^?;mw&WCf4I|GG~K^3wXJg`>xm$!jx|x{7g1U( z_Gax9*0U%byM`18*FzrpV6L~xE0gzDgm$HRJ4ehYjcrqq=JP7F37O9NFUvg5nR zKSpICDZB_l%6L4DJUlFWYat)~bBc#k0S^!velUW0IRo@Jwb3s@?yH8WCnV#sq(jLs zGo)nrfUsol$HI#(1CYCCZTnQA?0r?C>@#oUuzE`tQtk%yK4x#$MCAsnASvM_Y9Pq} zu8&0v%3x3SF8m%Sdy=Sj$2b#OU}X+wm+Oo(50aW*)Lkb31F|l7hldGkBI4`{-o0!` z5WNlU0ek=9cZ54E#~^t+S!;q#S`#$;@Rkvp%0Ex)r%##$wMB}RV=AoA+Gf3aXIz}M z*mqD^Z!!DMAP!wej^Rpc$zs`xT1vJ{%n^ZiFg{#zS>I$F{bU@}V6pFju(Mz)?YN`z zcG}~XO+I|xvO%ioJz4wh`(5dQzp;`l0)mr{iA2Y4#;@=gceJR zXJf@3-t({|NuQjVBAdmwzSsUA9n<;Wj-4yg@Bu-2MA8PGkwJPa!w8%s**j#a`t2CA zVitK0{+DKrU!Iml8o7sUM_~iSkRHdvnnMEXfK^n+8v;{*wq~y&$>qTtR@$f>eTlx) z=M;)8ULQYxWL7V*c@Nv1!VfJ^bwdj93l z*X^-{*Dds@mc7D+g`*)oLVCosG{Wy7 zV%wgio?K?3$IPPmU){JBUxyb$;wY}P>7WbY{72~>cNBN}sXJD@vrgSfaCa1*`#2S~ z;Pot{`RRxjwTpbl9dXEK+_7phS7ukG?ZTK-gmX?Qi0>BCo9><3K#JU}Je40&*noi+K#w3ZlCrA^{3MtmN9 zd2fMJcnTaNE&Ef@#Y9ieMAzgMSc8^CinpfWQX(BJl*)T8CAp;wL`^nBO1)Tv_tFu(E!PEH=tAES_$;)<#E_-H zCp6&+os%@=gPSg4M($d1tY_p-#t8~DfkuoW5hMC4d3YLILfVE-3)>4Di*m4!avWca z)ud0*R%{{%p!eQHJ{>$+yAP{GyrB>67W=}+XU)4;h@;jmmG$m|Bs~LK@}=Z2@XFA& zqf=RjxeJB`>?Z7IHjde7^72ImaDJA*NkjiDQO;*hD_BTcIv7gB2NuW zeraF_B%#U(tb43dj`K7n2W$~t2UC<*UbHE#r~V3+uTVr2^|wa-Wh|c1hUY|U{MzvJ zXmy}av`s4Jl?Ny?ge=jK4lmVxig)#KKt5!X7_?CeIV1ibi*lXP>Z_cn8(I^kWYM6$ zipJJj*O7<4cfQTR1J@?hrj;bsGibrGK}xU0*V7e4Z^=iiE+;!jOz;cZDCqV2DjA8r zMc-BB#`*O83Q{yA{vE!v+QPIsjEp(H2i6Bb)<_Mrz^j|=gO7fJTrh4%BP`PcM*F2l z$yH{YfQ}3qvmXRL~N$2Ww{sGy^;GQbdNlzXS{*=25`DYU+@VNKoBjrnG(gSJAUc8~bU@oLZOJ`AAika}yr{|}U zuLe&G1qm1lRbNe=`KkX0CAv*53Bk}64t?nWnDNKT+%%>Zw!=j(`nm`#Um z1N!J!F|3J}BoQ_E3cFXxTH_!r&_8>~pF!d5EztAMo3YyIBs>g#G3?gpc?Qmzxb_Tx zVTb>sb(b(l0A)|ClJf|es-cfTk1N6V_X;nr`>vJV8l0TFb__5UDi7H!>{320&Sv(3 zBG8_zu79%&GeNMJVJ%kX4WYd74PlM)v{0@ypl&eh%+7)A;k2+uS1R7$mytt$ILhcL zstn$iLrU0nP15ee!oM7mPS6$GBS9^%-yXyFbhh%bhopQGc{SKAOxu30GwDz_^?%b6 z=`P`u5A7oBhL*HrY^a_Wm?NMh6bXl{?a?ioyLE@O?ZbktLvtwMRmcF2d@Rhw@gR;2 z9ECWtag^g&i9?Sg<;Wa_w0@$N7sdapqWmmf0GJ58Y*+;g^Aj%!5ol z7apwUh04sy{$X=oAT6YLc}}Ra2C{CIrY$Sfl@jNSZ<~cVgW|Z?lLZ5+mb7p0A_k&b zbW?XfAg}Z%LjKBSMfZ24NR6$f6J!5zBgV^QD0|F&j1&9S_vFJr7!y*z{AA*9uBg>i z&&3VztXZ3~Y1y&CyZDIqyM3zmIoW=ZOCujO0NzSPY#J2xRVGR#7LUL?o$R~|@ z-kq|sri?@l=faO1Lq2ZgcGHpjVIx;ZWBjHOdaK;^FR|pYAx-=9MON}|V{SXO=$uaO z8)h<=`wOA9iG+M;2JwtC8F%}w?#13u1!)BbADe6|)#Yx* zZK7twDh2KP3&2~|k$VP#n>uS2|Nb7-%kAgILlmXSkYYT`MZA*(k)Z>^OOSsuWPamf z)P(|atK1WH;LGH^*0;+ZROow^?X!I~HQgz*$y3AYyA|y}_I0P!)XXN24{M>tn$&_& zu7&DC;03tjVIQp#MPL`GHkR9Eqwkn0J;}$uleL50<~ns3U4=Kjq;PWMwzWsEom;aO zNCXL|a4DTEXeCYi`^hEn0>Uy8Em0xmLB+v{gDU*H@{rT%`V^#dzX-nzqiU?a>(Dx^w133GMrZ4hwrohw_1kFtix&09Wa1`B-?vfpVRr{KS|2 z2ZR^JmR#2m(M~ylH4WmQ=?^Iw@`58ueD<6}C0-jGPT{yEA2VA>@NZv-zy z^~#>2JWw?je^wohspn(hi71`iKQfU4%sBb79?~exEwoQR@XwdV5=hgCAG0pK&mq6< zj}Orj#7upmZa~v6_ns+Y$Vc_Gr@^D_1DwALx(X}#pngd^Yg)M7WbYGnuT5$Or}=-5 zx#mt^B5Hy;l*_9iSyF|}yVrK_viEa}KGoFo1)%Y!lPCJ=7^A$_;`T^L&oY7128Yik zkgQQ!_X{n>zDT5?G~o*I&5uajfJcY`hKWi-%p{}VBScyT(GHe7lk6&ATHT%E8*M23 zr+VfZ4k^)Ng~i*dhNRAGb`UuI1%AWF{&%I)f67ZCCi$b#6)Jf};LBaZCbI8trFF&aamW#%Y*9-K{M z!FuMdyyK|%{z5*_lkau_Lq)&ZBT2HqlhjhA?%yb06&LSLdca1t8kz7d@&Nb%Iv&lw zSp5I*#vF!h@+8u&XBF;p@=Ms0-46e>pUPz)B-ch1?Pq|q#u$O0!gNwQQpQJuKcM-c zk2@Y9kHTjA?-q}AeP1t-Vbprg>a8RFak5X{SxL-&(UM?L5f z)T=L6{UGIqvUb;j|Ir!Rgh%v}tcU=3k~|i^VBnWJJR||~n(P^lZl|aWHc$u(G1|40 zyfng)XBbHa^xzrLgJ;P7N5a!ILt%!oUI7L&1dpsOpkA16L9TVEB`vI;F>)>Ln<*Bo z-YTX|dQeRwzs9PDRqXvgGqe1EzAfXr-QOvl)Os_)@>&P=-tYpSdNA$aE?+YFba=hb zWPe9U(NmfKCE-HM3%c{d1p`BlzWWaT%x33^f|HrmEh;B-^^LuiRVw#d!NAbzgvP0ZHec72dNQhoQo3m;b>x6Z=hBsBx);-c!vbC9QRMjDN$j$9mE8cK7& z20Vr$D<%-YSaNZZy>u*9l5;~D=({V~G(>1$%Btp1Wv zIQ6E`NF^F_|71PW^hHYtY*DUKo`JmX_WG}ODVz*!2~f-Bo|}o5-;ABxO6T$Cz^kXa zCR^y3fws^w1A3Za@~amN89uHm8Ma#kTiLvUO7;#JIFT3cWA8eZ_-kAhXoY*GzI;gt zis^&jrrC%z8!K58Fcd~5c}PIYf~UUi52wZ0rwyrIvoCq_8`b#678;8+$D=3RF4q|` z=9zEvO+vm&l@V@@ku@pFd?D4l$u|del_B<|3|Ko}5(>m{ficw^=YvGH+Os81q?r>M zJhe;~_}PZU-ApEf>m@;(%cgsFwD8fNCyY1TUyT2`{pH&=^6#|(55HZvd-ebJ&kAy7 z;(slhsQU`mPnK+;{%|dmVNfbqDXo=L~d2m8fjVi=_L_rRC$fELJ~>W?1u zDNp5^FO$8=HG_&JeNTVePjB~u@AXr0EGWeO6o=Nj-CO?WzCe3Ft>wSmV(wtbH*~xm zo*ZvK6ZxcDM?2~2r;4|7UO8m6HE(;`s>MHU_y13oLip714|F6=~ zk;srgd~Y=W@1=QFEX^A(GGp6VE+!O6NEmRjI`CQAmfz!ex z1+NxW3>xhUAl}4PYV|41R~J^(T5on-5;|ho-19h7UePJch>7R|Wf9w4`?u~k;X#8D z68UWgm9J6QMq|XoZs%IV4mBycN#j!)QwFRw_ZA#M54OZm=>}uclBU5_mkndyFIe)Z zt+gf3@|j;)B!(B|Wqn5H9PDF3%(uR4H4kPN&lV;fSY7OEg7wNBZ%p<|4sr*j2WOCb z2J%BDJCjaZW&qmtfr^!XWz$`-JAibCFiIBJCec5ZDa6iB;9K~`uw|Hm@C?Z17V}qE`C< zy~@>+0Z`tz*VS2&T&diwF`IlDq%H9y-xp{f2mFp(Kr=}DXZRwpQx80{e3N$gZ66(V zRGxO%APZ}rZ1Ru6C=t=EG_(FDUi*ED-V;rL|>^?7RBx|4P{ z_>$^&Vut^_zD=s?r8D*>NC)+peHMz8axwUlr@#G9#9%4B2lWa~(n>O8M2(e@HFBhL zRN=~iPY1egLGuDXM2f?Z^@~z|cGf@say#Cuqip)sFQJ=&75{H=X5b%v?8Z{%;)gI`jDQkQ$is-Y`xnR6(fj6q6cC4%D&=Bl6~ zq0dmgVvp0O+NL>nU#`0C*4R(3Qw{<0{3#BhjISj7AgfGpDnkjNWhgDBgoaanauzWR zja4`LGN3ip8R6&q`dD?&fedH<)=cM*SD0~R;mCGooJ@O*YC#KmrSsO=ADsq#-sP^uzO+@Ev%zhY!2ayRx6v7j~Q^KT1x7_1~=&>?cWMez9bhn5tw zY4EtfFuPtn4w^ULE6vYGJ;!yQ2uoFQA$fRa1gvr4cV63_kCv8%@?Em903_0_vAltaVP8p0g?@kJexmNL=QDgZJJ6TtBS%JxLUh9kAfvFa6Ro=+ z7+0W&X^+exi-Oy?>Ua!o_mFN(>Fm9?dhj7LS{B}#Ipuf2?PQaeRY=_PK){a$er5Xw$!9IP8Z86-YSD)m@Iicc%i~n-WO#I8#|OJf~+( z3s8#Uq~rXf8&hQdl>BnRR8F6~?tqTl@C&iFKY?b3Q63OSL^{8UbSUMsBg1+X?E|!D z{{C93H_fAT8od#1G3Yx=$a69})K1xfQ-Z~MYwVqC9}6W%mij2Q5*=8X9XWVUHaq-u zc0_>E(*3CMT)qRAwfAGLxLc?2Eq+F$!JAQ*IL}1VMO|E5s&^QYT~Fr;fzhXVPoO`@aF)W#UCzZh7x}oX=_oUA5Gg;8|NFdgKmZ;&AYHod=c0v+BO`@2i@Y! zl7qA0SCzI4ttV>zZRHchSpy~8zVs^U>&}P2M7v!H_Naqa?9`U;99uy8=2-lpegzNHW}cV+Tc)T}5W!x+0WnB#>W)oDWAI(RFj3fUey%8cM) zVV&D$`nLbmR1EMaO2>WVg;Co7;e{XlUq2i}F$I=5ph@M>rcs$g9%htazf6>E(|(#k zhKFa;|9>9;T-+iYx$}A8Gt6i?2f}o1qjhAmCq13lO*s>WECe+sG0gp3Uv(cbK|*i@ z`#4=1o&7o8>jyj?e8HwwQE3A_-xv%Mw!|zoRn?-#;(}N#DGaJ`+69 zP#RI7nyMF!xRmz;w%h3YnRRhf{>SCWfE@Bv0Dhp5hHa?MYH{zV5~Z*M`PkcpK@ zMSl5>2@;rx$i^Ux(YJwQ3{T!`L@%ftND!%=H}A4Mh1Gc`jL{fl4ROH^nlYWPn0!)0 z{u6q!>wyEX2wnl1$278dFvE91_%pO%?83dc>M@=huue`VGf<*gw-J_donMcIxvyhPahPQjNHh3V`W)Pu zO$DmQQ=Mx1evB;AN$We0Vn0X$m7hp}P^2kKMwoP}pL<|KTG!cH_1T4WU;924bh+NT zL0=)L?Us=l!*sa`}&bdCEuA^i!o+=F@RHxvRbZSLmkl6~B6b@z0VA*LiqnMDeR^oXUC z%_ql4A#teI8+28S@j2O8P{@lZs9yCcRQ^=SoHr5LQ-133@yB zulo}wDX7)VELz63g1m*IHLO5pPz%{b0XMKejJXi^>+%PHlB2wrTe#083%NvFwEIo; z$xPrQk=tBTmm4#ix(nP!Vf*kxO9pxs_aXL`^u{BAwPfM_$TqwEjqi*5L#`R9$;aX66+5}%S z5DMy0%sBIa(*GeR?@g>T&~&+KUvf>dPnxIC`VzhVh+SfcCbOX-x{vNlmL>J&Pf5d8nkWyx5{SN;;OT#Zv+PQVq*Hi9 zds=u}-wOY3mxOmk{_tJHe|~Yc_MPXr+ZW!Hy+Mq`>Q_ z58$oVZc2%)YNW_SNY)36n87bo-WMN0H`c1o8vz2VF zmyqqnU18fQhODc<*g1h%>c;ZV=y#N8Q7!l(D>>?rU1=8gAgc8x@#Wa5k0bvH?{=~) zO_C3Uy%uG-O!6T{&N9Jhp|$Zqg>5{O{KDzmYyFgi_5jM`I0M)X4ldWtNwu9hW>a(64h+yu0%<+x~8In zfpY%q8?6E@87&dMDN1cS8@9kNQmcKf-9VnX_l|K}R9o|T>?C>qN)-2Dl1F!I>={x~ zwa;D#9PKm3rg0nh!C1V+lSJ{GdY@) z9)&#c;Yo=_Ov9jk<2I~p52-(=+!WGlh6E{e3)t&RQVFU`c`lC38!hK6utIR;r$M^k z2yN>H0mQ?1%eXBS*t@u6nPBR0+S{7Bu#UwyJ1T6iBlMc>fRL#***>=!e6W9EQy1Vl zo@MD5__hFJVRT6Hw%A^`OBTFtORCva1N$A*(Z4}257ryQ;)W_6(s8ILi!rs408xZ^~Yk42%oA#z{tflFpL&64a1(3HhwHM^dUU#!n zWxdQAc9cYP)EZ4lvlmA*>n%ub$D7RVj_aWYK$JyE|kd!eF z;6jx;asDp^*ZnwbvKw)xeLVMwtu~z zG0*i=y=flk`bQv7&{!txE zbn#0O0lK1O>KUg6ynN+jv&gcc8KHbg%TM?!spiE_dZO zvaR-?WB%T1!(LQjN8&N;W>04e3FzBMk@I7EUTT_{IE~}BOqBBF;15-AK|0a_+|lVH zpS9n=(1#w*5Y|em$!$Us9bC z%JkG~`;@TKvR}AgyI)wRe_N1-q6ioDtFR;*n&(a?gB=(I$Htg~ohTJHSH`qo*kCF1X}lY2 zl51eAU>uB4w9#jfx3w*y9^b|;5v@C-WuLu}m*?-Z?Q51V+*f}XF_L|^#vZ!HB90Vw zy?1yT@IHry`{6ALH7jC%7*mc@a+Yc);ok$O>4*Ru*2=-r0fUrtvW92|vf)c3C}aDg zW^a`Ch$DDdG~FEnA`WaSDs!!%CC|sGg=J(O-o91#;0R`6vp*O0GB1GROMpvjt~q zI!Y6L*g)S(F{@`ns`22+xzBT;=U_m&yxRbtSrs3mB}wk4I)bhS$R}|P(3~vhZkm!I z#~M7;stA4Tu&@raJ*}}7pzESU1dO{u>-AJo+@GgH;eNFYJ~X(Cn-7J- zu|zA0jX|%|Yq0+sdVQXzP3!G%b~S^_UZd;j63X=&x7XgF`zR?2Ep;)ekdJJWLk9Tu z4LSB+Kc5usbnXf4q1cL3!U+p4)to>!WIWW0igo53H^aK=B<5rAN)3;Ho+D}`?rBg{ zyQ;iRd<}UjnB79(Zo{)2)b-@ko#45%TP&z!QTC3pKJaiZWCK4TeWO44oVGP>X=xzG zOLZU%0&>*U{ivzQ`#jM5Iqu1v?&;5N(RIgtp6yMp%5kQOd}OxQvn2<5A+13n;&cqK z#JFF7wR^I~X#4qP+Fo}p4aN8ZGF6{8l)M|hVs=v8D!e-EVz7_TZSATDl!fP^&p(@N z#rk22*fueZ*m5%0-khP&M@#<+dp&|1oTaC-tYPeSPU;@q7E~~O>CPN@ZaLb`?FNU3e*To$ zr!|oLHwyA26nTzPLvz6SDel}rw1YI(*S;M0K5>j>)vI?G`_!(_b17%_&Dd90>8hVr zuXahXb7g17jWN;Ec)Q&KV}XT)J_#H$>>`R) z@LHFxrCO2d7i!3F2eZ9OH})!xao^-H<`t0fOiHVciCWuZMz_F0nrDete5*0<5Z`nd zY5t6PM*#UTCc75+6Qs1UfpeW~Xgj%Qcv{8+zb2^8NcT&Fl8k9UqHGEzhBO%_e{9CO zz^srZV-eoyuo} zhn-$NrVJLY9O{`@8&{YQ@~yMwY1XyCa8f*+pV!D zuUQk1*a~?qbh^}UmnPK7-}#rx(O`Y%?(t_&VTCb2GyeXmcmFa+q!ezC2eth}`(Ra) zz1g>-hBZe8I)z_ZOvEaBl6W2A=9*?X^|WT?=pFSJC%oMXIr&f(XOHBQU{kiGViqJI zHl>{Gg2zH(+szy4H`n{t`M$ER_Z1^gsb6C{>Y$c%!h1(5z@Ix9y#Rl{9CkYv)2~jS zO22kO#)ptzcC*~K4BW&K4wgCKKjV8iJp`lI+8WvtyG$zwtS_Mz!uq?Ck-^7(V? zkB6x@I?fywOd(dRi`n&3*c@F0nv)^3>aC{AN-1O$nV-#>QOLhs%3-z$kOpWMtYmt< z6_mi`+8peCOJhgZ!}d~L2n+a$u^HqzC@rd6jR{J<4}ha$#Mm_N--)pW$L+j-!2dH; zU1zSlU8XAz8L-HOe4Y3;kI2t{=AhrIekz9?6I1s)=y#x#x^Wzqar8TKd}lqr^9M2C zKZY(pb@Hj(Ii5p~TIOLfznx-!zjR!IoP+htz!^$CtL4*sw_C45ljZ`&l3_Da2R<85;o@*fUZn*l3y z)Rw>P0U6hK)V^M34eu4pAU)1NI*@b&SXsZ+dmNNM&84#P#h$D^j1kzjfGN%^wMhZL)#&e9ba;pWjhWxk;dtcCf zoqs@H?Pu@QXV86}RRI~i&&c7MgoP(ex{qZc>@&E~kC(CjRm(mN+`sfPdeU0-r0IT{ z_pDD2T(G8R?rdguY>39D2v_D%AxZ29{&lu8q?s)b<;<3b(q@AmgHCQPbaD|>^uG~& zD;=R3jKaRjo@!qR%5ck)&5(T4(ee5>uy5ig!$-cM9zAFAUu_d^temj;X8M>rCP$h8 z&x-;^+Srm-*a_2oH2fuuF)^>)O;dU8{$>fh7f$9?_l*KHU>dv|6XcdYam07ncgP2u zCIfryUt`y9u*YPETVo%NvBslS<9hb^H)GMzB)wj>$)2=@j=g`?@4|eb!F+Phzs)FR zC?hT3ziyrJrGlqAlJAno0(CQ)?}t^1jEOY?ZINukK<6ipu?k{#TZ3l!o`V#mf?GyeF zVP75?MV0Mc)q6S}(pi9PKrbu_0qG=wY-*IKwJg5WABg0Te}CIs_$vOGvY1 zK}Dk@i_WA2%n%tSC^+M|%-7B0WKS!;hXdox?R1t30rLG$bwKC6?|tu&r0d?gb?erx zTlb!O&hPwAmwtwj3jGtb=BaUzCgUEbct{je@)p_C(mmo2h?-9RUPrLUy$H*LB9%*u zX@Fl?T1;}->~3!&Q)?_j%zTYst+^d2@GH-le18*vNLBbJ$d&-HzSg`X!y+JtSwKJk zc3`Dnzt9YpJaF{Q%)_35PXnu=clI1PbSPS!U+Cv2W1lm6_MFx>i=al1%}*nRA%=qK zS3EZXe`=0%-jCn7iMzP_PjO}*R&J#rPmUH8P5coRP-M3PX+1+GB->S9Xc!DG(QD9D z$7Pcz+c56Iv*M{w9bm12)_tVlU8YFOP98G*Ch)=$xLc_IPi}5>zavptB94~Y9yb3( ze^20c;0{xuz0}&_6XZZ4Yf!q2@sndFT*I|Wq<&t-$ZQ?QV=2 z>Db*(zUs855w|M+-u)l6Ev#Os7GmuGs?9GODpZvgIz9s1JS;fj@7fE?s!J7nKLV@# zHv7>%uy58D*p+*UJK|!@yV>vVg12TFbb!U&*weyV-`e}udTQ+7LE|_?O&a-_hLhNn zHK-5os@$dY%oX~dj4Q;5S-a8~8PfrO_;77`-Q4T^IC=RyyPL5F47q=?Xf!m`#kprJ z=t}^59HRNkD`88Ju5Ff3YY+JHk8$ON$M|wZg|c!yxZLx>E}ZJUx~p2DzJmK%%+`~icJDm7jUt}vOlz6-L)U%%Z#@|y9+QU6swMBh-0nq(%mimRE$2Wy!!l& zkPvP{g?Fw%7A)SYJRa`re{uy{zGCe%!2vxA_*vUV_z<085@+1I9kJF!+;e)pqut9e z2h-WMHg0sNPjwt4!m?k|-b}MAurnRQ*0u1HPul$64bm)}j5+w$0MGp(555O?Z5zH# z;9Sk&<&)rnK20{GIKYk z)!;)5RitUb#ipssWcpAoII|N?dd#fzy5l6Sfm?x$?knILNOtRwD7#l~OvFg}U6-yp z%x~4o{nON8e!Fglums<;k@Rop$n#}1Vi=Kk@pO1ejs7iX3a!|{{@6}_Gox{Je7DB` z3px3`i~$Cq0{9TSCCqo8tM7X(8|h;TiE+8C1|B;<|Nk%dxcVW<$z>wqj=RS?-j@!h{Z0f zW`Alf@!{T<6yew4(@qq&u=);Nl?)jFY|D@;ix6BLel6a#Y+(v`bpFEj3}F~!k1VnHkouo}E)so5IuHsgAZ zEhzq2z{ zM9*XQiSeDSq3GlpU~c?X;{~4zI83hd6DMhMp78SHt-#}+5|8mF7Ttut36&=p1wyqX z;@jN<{#PFUhBRLN5?=!4{V>>Pb^{SUtW0_&{%ABbyK6n<19N5#AW76mVgZ&nK1M!iK=} zAG3vwaA*n_y}RM2m9RVgsWoiueCUKB0lN6|e_iA5v%yPAXIg`I^J(Ygg<;+0+t#?! zB#)kDLbfYsKjy(sRW+hrRT1~KwP7Mr;_FcBQRlW zAi>++in{;$Q$&Z+yLfriigg2wm6uQ-%2z~?W8 zGkzp~Z+IBICVJPcKul*?1->JL92UC?kZPqBip#(X#mSqXm!E5K)oEP|`5`XiC<)(7 zvaB3?y&8KZc(NYa4(&?H-7orA+tUWW=;ZZP_@W8NLSOWjHo~zy$o?tqM;C18%!Gac z>cs*?izU3m;6CjS3CFy@J;Zk!!2{VC8nRd6JA(eCQ5*tJxhL{Ifc2kt zOk3DVAUnSnyK4F52l2-LQELqh+g=SGk&p^mT7~UgXZZH%g3eTek@LR4XyJ6B#I<2z zqG^XK|9A`#rY~b{tMvc!SXlQD&li+uA1f@+#t0{$(S&pPKp1|$@m64$UjrV_ZLTys zd~MGWCQc^xKyZas)V?PEkTRs|8>}`-Ldo&PtfloVJXnU5Yuv+yhHuY81Akfc!G~S6 zOmidRe9G;BsrPO)xX`lDiW}=+6aSMlyYKSlMAav+U#SWOqSglu(s5~?d!v|eaTN-y ze|ND(_~p^;V-FvXL(CIe&t5J*ASM7gI6H;>rCuzicT_3ar2ZzYWi*RV2Tsi(+`+0g zqj7)VY|Mw}IyXuso8e1QSWNHiDD?T?h(-K(_DGuy>yozeOYFm!7OyuAh4g`W(9fCM zM9a5v;Anm2$R~&b_k99b=lH^;kjD6V)>Rhw(BE3?wk}P*ZjdFyO2(&co^#!sV^7OB zGBux*z3hcZKc|zd9l98IWPLjH$2r+6Ur2LnE9WWYm%)hw28O(BEp!G3SyXwDJw|~X zeRV|vXO4ysvO8i2_jS|`iT_Yv`9(}Qn57~Rag|u|h92F$iW^Tp4t!dP?O$Gcrc4W5 zuRQB3(@!jT7OQ$Hz1OAe5EvV=I+O>;5NGc1Ry-)lGo^lc1yn=0R_zprdK}buiIOE9DXoAcYEtee}3tqz)VQ(ZP-@^K|eBxSC zdiN72ZhaK|#2lWxd8Av8lHNnk6$_;8ZEa1!H&obGU8MTr*j0Ff?m&9!#US2WbA`}4 zBn5_4XR~3=T;hE1kgA7|V*W5bgjuCOkl(AToL8W6^WgsouZnXYgLH^lSo5Yhm(xM- zK8v%$x7go-Qot#f=Ba!(Sk?OjkM!!QJ{6}qd06sT3Z8=p)0F9jBOi&KDgA+mdI?EQ zZF>Hg8FI#=w$Z+k<8;2Taa!Ln=u9G^Gl_!EBo;c82Moe#Ve?BaA&bza*N2&B0q03`g0*Dx>+o5U7z-e02ffM5#>1*>WDalz z0`JW312U{EmDulg;8#M}S!QC_Nq)X77$?~<5=zWKs^+kcM(Z4S+DXSvjkg0k10}#A z-wu=nN`N{G=6~I&fxkB~(^lB-Z{3EmrUkFpA1y6v)s-{$m}I#JOrHgcSSXuf~7pn&<|tIU3AVhrtJzXdW=?8<^z3` z4F-WrO(Gf6g#Ah@ax7P&t<$8CpHw!mAmll|k{v`$jTB)fGdCv+LyQlwl~QzIfh__~ zGD&#Oe#SnBsT;rgHaL^q^&D9&tigDv5~*0#Ynq*suP|{8gp!PuIg`Elwz{g*-HaXD z$6{fbE)AOOkXZQtBl53n3Hz!;RlNgo1}RNDz9pvCJ{Bx^bVU+)$du;=IA)j@HSnNH!wpXmQISVR0#+iL1)0gm`=(!8*sc9CjlX0PqZ4NbnjNcE}P-O4%&n zbrOLx=Jw*M+Ap9t-VR1DE=3NV{bjLL`Yvy*FJ!XD7$7jI_Nu}22At2rtf6_^w#!VKY&T0-sIhCRej<%YFtHK64jRG zO$Mut1(70T;S<3_Lo-{_mEfE<#zQll33@^k`vv0XkOp@gTh^E;#29A*!;Pq8kOD8O za93lzJJvy5jO1(bJNV-y2|<6H49s~^V1Y>jlbr@vHGt=n46yR}&n9&Uco(IL`1$1Hl!kr2*c=M{ zGL@*_l!k~MoQYCV;C_qkIP(&pcIKH8zCdZw>*lU?c>(9`!0QY=<5{C_I>n;bG5<4q z{vnAH=Zlpy%)8EM%uFl)HRi})+fvNqBECvi6TxfejX7!{zs^lYqi*gf;O zzkUI`zZIT5+-ZMkxE>5T#L#rYu1nT?=>5>%eFf|?GufZ;rR$8(U~j^O4@1Psk>OFE z&G7NK7hS-05cA=Tdn`k|i#KKn)7fuYKJg{nG4?do`LOZHzQlfj{DssmO*wYG{?VVzKFfrj zM|dNv6NSK9?540DcNQM8r`SiPW?&o)C0skk;kLGH%pRmAQb}5(<--}wz7}tQUzt2mx&%kW60RBx};#kD!aoNeM zRGVz@ZnE3Jyt*lybSSyt<~t+lZlJ5JBArH1cM}Tc^G$4PN4ZY}YpSLi_)(u05{9Nq zF{{Bam(s~r!v3`^lNceZN!28fT2@e4gP8ujYHCk$bL3TYE4FrlC8wfg)#Clc8W8+ z#1D2qS|uAl*{g*_HH&R*4cH^$JqLewcZ@^w8idDM7@|vMGC3IJxgoFpz-KASmGELr z1Eqhr_%2Ho;qy-p&P8>N5x$VBBlZY;8lwMIZ_=^9wQ78^3Bf1E zcaCR%fQ@Mka<#6<``d`W!MP=UCuY7E?5FLEM5R+F+zfa-v3>(jVDaQF=Zwqj-(&oJ z;1}&nasDRsN1uxtPJe>VRoH*Pxk`WD@}&8f@ZF`^Q-#kV=~dWi&U~otbJ5P(-FeH+ zgJ(@b@JuSsoWmU^dGnT6+xy*>PfmBI*(>ZiV60HDsoGw(j?P>X&*{?#&v1ih&Wq;^ zdCNt6rTu2$-A*c9m7TYIxjn~y8ab6x&Wh{}ERK_`V3IBDUaH~IKkne({6ld3z70>3 zJwmi(qg1#^8`{3T#IC4XX^#*tEt@B-wpZH|jwxO7$ESj?IorLeUU|r1Qh?h&zOp}1 z#SEtJfY;cm3-hTaaGmG3cl;2|)Z8bs4freMKaqXUXR?ht#i2YzgxzSzPE1A??-$@l zP1bIjML721b{f~D5BFHe8ZRLeLxCW*e&~;sSJ%bM6#hu98QQ8fkf!PS{=m0vAuGkX zIPG^&nV(MHqx2`JYw2fD)qQ}91AtC5t6epB12bvM{QM8 zTZ?{=w!#Vy+dJo50~yA{ITK}`TI4FcbGzR9)m)}g%YBMO8B*Ur(@;n9KUvt9x_f$$ z4pMphj| zto)pL|^R# zgXw0Vs`pr_!oQI_icz<(7xx^*W21K^J2Oe7C-9wmxSn3iKoa-2~LZ z^Qw(@l$5Vz6Tt8N^Kv!YpwETRG;x?e1pYkUqVmE+gG zc3(nI1(D+B?K<-?@J8GZJKX{CxuS(#+1noC)y$$^cwMbVPoHb3nRsKKz zmtODa(L<~AIv64_Fi3eo&4TtyBhQFZ0J#YaP-{_{IX}JD0=`_8_7$8o^XXg<7HLLzmJ2vUx^9hU?n(8 z|EGSLiEAsGcniI+5HIcesAmQOojsJ}6BYv>@js21Ff+{*eCQk>^;>kq9W(ZOU^LGH zTfiz_W8y^R%$tGR-NONVSI|7dK`!?50$E&i&?PASugcWNZwL1I8Q36x!Kshx@umF- zY^Ui$Gi-OGnX5y22tJP-bQpSKU8Qv1$jA*$9-vu38D5a(I;FeZRA~1o)l)WveigXq?y~;j4Z8Hq8sq7n8)wvFD1< z09U2He5ODSEi0jm!5NRIlbflu+T{e&k>)=caF68SmiEE{F{&)%dPq_%Mw-ec^WF}` z_*G>J|Ef^lpfRib!}%4$tpMvTnFF6Y@X+WmEBxLWhW|0ep|I`EDGups-FyPkX|3!b zVBKcP4JJsh{!zTbbu+M{`(wMJ8d$LnA>Q%!NJ&ci6nhkpp$@Hx@@o9^WL!CTCkzfd z&;saLS^2xW)rbxwFaHjD!35c@fY5F7Iqb;OWeeY>AnFg~m}rc@m~I6;^`l|!<(RDa z|6NnI@KZge-dK1S={;$?gQKvzZdJ0iv%zT*fG)wEZv~zK0*zy>&Ywy=h7!MV9uPO^ z4~Rtu+jUq<{cHF=wsY|E`_%ny=}FjQzKp4|MS4~En!mNH{E;Cy17CKPy04Z(v#+n5 z9pYcZp%lLIb6pmG$QW=Za?4!01{kQ&CHxjCY5X?cZj}g9~ zo~*W~7W#*u_fRPNzJuDEC_G59czqaWzP}p~7ZQvdoPlt=LF63x!{>$_QXv+0m9Psu z35z}4gvFi`h&%un_|xmFywkM7cN)s}bZBvp z8v9ComG2brOvaP<3vYz~uupEps)u;#1HIaQ9w@4*k*+&9p?y)LYL zeYiku_?v{9ZtElP!IAF*A3_Qw?F@KrKFzpBnzx_#%!P+Hm;9`xK^*AK14eQa>~|~e z%YX`h+iu3&l_8qUL+s(kWcvkC=cM)jxVr*&2GagCijyrgC+e{0A^h4rSrLnG4fmPr z@16U?itV+nh-YUZ+M&m^Mv} zwEVU1OGpj;OyRnGtdhx<=+Dg~5IxJ5M-j9Ri`FTJMZ@EV#R-qnFYCA~6~+~%8SLQ}ItShdV--@w=uWBT()iLtMo1^7^12K*V=#BcuJ~PV-OHVX9q-v6 zimX=l&qE^6jISFNc%mIkZOjKQ2rCzFf2Ga^E33+%#jE`L)Vt~$>Z0%sybK=yE21HV zPfqa2F3FNDUXyRX_=ABr=;4ozxEm?ubpwzC^gtrUWt7($;J4P-j1m^!RAnU=gz~y* zjI2}Qcw+|p2Q==)f&&~5)iPLyTHPU?fu5Q*8bSAbathJYbea*5eqxxdFXp=VS>st9c-b>mTC3$W~QAb zO;nE#{RLiFx34OobEO$w9dNIGP$$(?Gj`iC3= zGJ{uO+)e0QF%j{}z)6$ZXq?C~k8@b#5d41N)HEt5uJnKzh`s4lOhjy_;^%$Q6VI`O z#lt6BI}aBdkhiz^Gv7lfAv!}E$Km&{&Ij@TAI`BjS5kc0w-~AM#Y?6Cvyr#8_?j;t zshr|rjcf61Ee>g1jo(+CdH5e+yb5KWDBk9?BQ?F4>zq-%4mpn%Px^K%au%cXM*IrJ z&*J|h#YH%mRlMTc=h3Q%i(f#i9xZ+qc|viX&$prChr`^T9K)DGH3a&BDL3Vv->94F ziPBZ`<$Bemc80`wrTnV5i$3f>y}MmClz*zdPsm z2g;ZM-u+s`^Xsrw!?FsN1b5a+V9(tjO+W`E!p=8$M7^jOS8%CG8`$H zs!=5zhHplNJ(LM;YCOAwRkiC+&~IJ45(qZ5&8TFG#x%Qc1LxXo*Gwfmi0pvel@7a7 zsi6its&{~zhyNBEn97Y^k1LXJhZ`Llspp=6)jk@n9D!C2Q<=g2ME8nmdmR0ko$?6& zuT5F#OF=w3#gUtVKQZN-x+#f}>{t2~m@5}}i2wa&;A3Vk1%pi}d0q?z*7)gOvwZ`B z75-Uhy-SRlnuG`gwRvNGC&iH|X5X$lK50^;-29$6GQxlzM6BCjl1Xt0WJbgaFxz1J zioi@@1%KD#YYP)($??#5&abnvww9-_T@a^5(0iVil9tVl)dN{OLKTMpVJa>D^C~s| z$Eg(fKTIV>kWg8IcAFBe;b!43PPTp*$4(Jbj|y7e(kw#r$nbP6j58acnIA|gTA*~< zSPJZP@o0T8ngiN`He|5qMj)#1r?yRRn`MhImOdIu)$ADF<_nmAwO< zc8a1dcI-z0{~R8H81s7muihA@?Nw_A*!&>O5xz7a@)p z;P_Jm+63hMT1M#u%?HF~Q{yp@zk*+tk2@HAGKD#v zm14%7je3rt9s}wTaC{8MagC?M(y0`C{eArM=J&-zQ@Jsx^73MrIrMJR!j<-lxr!+< z6MMX)ev$1szP@5^!G>%{#az5|qm7-#YVz~`4Qs5~0A1@IJm;pbQfwHbdC$ucqXf}v zeik<)oju)Q5PpN}E1NRA8uP5&1@IDGK>t|K%X?eZwG23Dg@RM;dywZ~`L=SL%1V5( zMOe!eLhz2HH7ItLY*@Z$D(>`DlX<;LXjDIQB@Z^Qr!HUJP~|A+WLKIU6oswDK~Y;* zsO`}AR&$TTB35dFE#v7E;>oe)7?W~Y4UXt*s}oO8HM4Vro=iA~mN-_ba~SGuajXCa ziRuWK>fntvA{$1voe(=wQaNQt#M4r%&!N?) z#}>gWYR^`spc7^SS@61v8*lWMiErT7;N?xZ8(r?Zc)zQ#A%;Tdo~@Cy)3+?{Jj5dj zYL4Y>OaI}mS+Fx1vBFNX&SvkvjjssnXz+iABeY&-&d4djZ?w52=e#2d_N`%?&*zlb z>FBx5CE0SElP{F#oVTOw!t>chbGZg?ijH$;Mq=F^m`iUC{vc%(skC~-2{G<)r5Fo+ z@Cro2d2b6hCIvfdJ!fNYG`bVW8;g#2H5O=OQxwO3tdrd+k zf--dPsgO4zQB0(rfaVZ!zJ)@Xu%kEo0%1MsiR4*e9HB7v1ynr=lhoj*aRPnsf}KTs z&$HkTMHoReB8o*soNFXgSl9)yTOCeu!WOqq@4}40C0SXilN%45mb0?d);VMoKYdr- zUfaY*gTvZ+J;ll{wUxOIj?AuY8?EeX@EadasVYtHS-6ClEUC>XL>6{mC>v}il_1s#l=H!#X0VR)qTNZF zZjV&QI>Y$-7R2Kj7!~EETp8j@O=1rsmJZpfWu{5s+6vaaF6-_+@C#PfpSO{6wu|d6 zRD){FZ?DP5d~{7S=J++5jb5qM!JmmU%8zJGBkg^Gs_wI}%?9I}>MZ+!N30=BDR!QQ zlt%RscpTdh|3rp4k)oaIESynqN=J+zS`pSZ@y3_M>H0L_Vt97prmD8+EW;}^AFDh&w1utf}6EWW2+h`JWkS3b3W|1VI zC_@|+Dt?P!s>5N1$wz0wn>wGucACws4%sr4QF4qt7|#Tj0&vZhi~u0H!O!_ zL#uiHZM-k=LsA|;Q=YuJvEv8mu%avv^FaO&^m+&Qi5l+ZIh@~-A)UXsIxFwJ1jn|AiQ{2VF&yIgZ##wFf_I9t+{ zH3R#^>G&qp*yH8ETSY$rKhoU1+?w3Hg72jJ<>e(`;>_grN%PLMvkK|Dozivj@aLhc z&fmFv|GW1w=Y5wOK6wADxzo(%w`20 zvP5g(T}aWhnH*Rl4*r(-;t|`DumH_Zg6(V*UA5O4k9b-fd(F8I41mdQLQFjY#GaMy zaMCxlqG0i}UbXIW+t$?>`4SIeO1xvG?YQl$2F)1A%jkO*v>X)KT{Gs))?rK!j#Wrx zTg+#`HkRUo-Mb%LdpE$nXC}Tq?q*+XU`Wp9L zKCf-STxWyNE7V7&SEAIbrV$IHtfbS@duKks**zuWqdGeKdg@H6j>(8WA=w+zt`YFl zfb`fU+mwu`KciT7>l9lo_C=7OP2Od@+`G3vSFe38->rRq1+JaVFJpfP>Ya|{q)D+Z zXGbd)U@-houbd>9fdQ<0Vuljy9()i}JmO^VN9)Ui-|Owb(B7KD!)wpSo#@VaiN8pm z#0Fsw`?zU`h@}DVAgyDEn1Z7@th8|-*Z_8jE4Y>LV6o!Jf|(^9zbW{&(HRROg;-Xq zjaRM}BntcbQuO=!EQWo3D=eqyk{{~4IcgyaXp-ru?SsZdhipAGr82Ge5jQ_c<$sUo zz1e2omyOxc2FwWJ=$R;*;Xv=TJ5+B45Td^>pxS<_yLRqASm0FxVnCu^#r#x^0FZ3t;)y@9M#+V)+vHKAb|U zb7g68eU>*Ze=P!fex-+hkiRd4W;5vJ46tXZ5wBGxAL!+7y(y~oZ;C3*JAPia$X4U$ zx%3+{K10II%jn+F{zM^4ty({cwW0=;)yu%fK8anC@Q98Sv)i1XD8vF0r|Yy9heMa78?)nhtx+?eQxNWr9-r6{ZHhK;FFIeO@Q>ydmcBsLf4jOOiFAb& zX%c+BmPq%_!0K+^*BAJvcf!O_#Q952IBX{*eFxP*NeZfoq+8m2J;8;@s15(fWSx%x9@so6azhIBNg&HKBaFtM98-@t9 zx)hjEb7*c)Dc-epHaPFBU>r!2Vn-wvSBbn{mNd#+4eVKhmpn=d)uw{fdXOEi2ctPh z5vlv2m$73dO2U}X7&o&(s|89u)I)ykvIKx8jY)}r?h@9HveZOj zxq7w~i<|Jtym2(EZKaYVVRjiZyKWZU4m5QC9K-xOpwGvD}5lHp^_+H9SZ;7P|^ zwTz$7u0eJj!`?&W#B^8$FAgG;|2w+bz-B=QFoHdRnM38D#v9nMwo7wHW9B6-?FxG` z-roaQ>kawT=Byx7GtjCU&rAnJqJWj+9$)iICc+wXST73M4M~@~nJwvnRsuGeM2v(` z;BuaBkEbvFjiaYu=E6RHnG4;;PF;9I&X`IOJ2hmoI4sNdMy)u@$4|v^(N|zyCA^iEZG8_>bx^4t)InbMUg%*cJQaWy%Bd?6J_}X0jdN zMrDwcbwbFl&k!Ausdm0T2ltpF4zv6@Hk0Xw4C$9Yv$NLrIzN>=h}^90F+awARLAdk z+Aqe)$_&8g$jc5p6lFe#vMd|+=yXVr|9g!u|1ULCO+D>O)I_WZwPK`m=k7o4-m%p= z`_Hkj#CFw>0g^RbK2?m;^J(~R*lio)(JfpY7Zd9&rB-ug<#ifF(7U>9NI$!O1G>`TD(-C?G zEYXvd{vp_8YZ{=dS!=KxFWr7v#6cmF(%TXR@-h^>LO!{CEWu@RimS3^w(NsvdA!@?SP2fsc}UHM#5&ILFZV!Pqj+KJ2KHy!LEGtu;X;)A zZTyZBPJ$nkSPSCjr3zx;H$C*_kTkZGjg{_hLNsHN@uE&V;ZUC#h&$Og!!qvrwP(0w zMe~q(-xktUt{%FAGc5(rH?{b^-G^SL9Vs0*zjn3oQq0x0)$v^N=MDe4mhyk|*)FaF zfBI7#;4&BY3tYVu6?9q!2;2E>M+igu>V6)xeWibwU zxg9#0M94_?CQjzfYqwH3fWE_9E~Ytf{aoJ?|j)zp5$t{a_6rbe~(Y95u)XYshM?DNqXf`U>#K5BCL2sXQpP ztkKW$={Gcky&Y^K zwAGKn{z@|YHob!l2ftgGf4GbThB5<~?ltUCE3x`G;1^&;na86X@Hi6spGWt=IOnmP3?SQIE@uOhe#Ck&K>Lub_T(B&%xsFU}w?J9pc{F9pVA( zY@8A^A2DVu!ns(qYddx!p>8=MR_yD05q18#S?=4{_Y#gCfn55%JPGBz%{2vd_q2|R zpWXeRR^wykPm?ZS1z3qicwWD zS7PISLw~AF%#-vkE$YA2O}J9>tGUU6lGsqI_M2hM*GhXh*FCCMw7TDH+x1pR8=?On>r|(ph z+5vkG(6xM$%p*&h?uEC-x|#x%)W_xT6Pvi)bunl5kp^-6L~o4abtB$QyOrBnry2wO znc;RI-Ct9n_CKYHaij=OfYTAab`NxV@vR}|GUYr0TL{l0MH#dw@0jQv8id7lWUU?O z-3I$p3@1WTmf^o1tH^5hW1GzQXEYec zKx#yLb`(7B7&lSw)gjGo(0N}iZK;c9@^IesX0p;_o~ZWzV)syHfR8wD-t!D+*80l& zCdlIfCz;()-Zye=bqr_v@|oSwgyP)7XDnyWI}|fD;G`nWPK+`{9ij|XhHn2e z=3f-c48$qF8!J@krF|ILw8tFi_1}4yN~A>QpGS#(7&#ekx^Lc-m*T*`h3Gmvkarm} z@Ob3MqCHfD?h@TWCXcetM5|UK)?N(G#^+yvTuo=faqr|aG{c;N{P!4e5p)mWYrqxC z&p40Y%i_twZzcFGn%m&JUceuXK};dF>q@{z{qn<9HqsRcg^Qkyz&=@fAG56m5Bh|851M^v~@p z`m;{)$GD=omQzZsfIDjwp&{ZnrgtVpX0y52gOHwH4Yaz!taLdM0|y=?WeOLfuFmAs zoXIz_e(^^iXFs%Oc3DU_aa7@Y9JX&mVS4AJh-_dy=q;^fuRw}_aQ;-&YS!CyMZAFM z=+>UD2-wkV1@0*H|H-CP;3|XYBk4G|>D_zztD4?7S_kug+4Sps`B_cx+&f;-WRXh9 zjH}t~rVWyQj9bi^SF;CTyK^p%f_7&E&P|2AgO078e@kD@RyWaaW>--z%HXM2gU`bN zF8&rgt+n&%Md-mzRLA@#b*%-qzCW(ux$!G`*mTwAowce$#8fgXTs)#qg~2nVMJWpw3STzSKr*`>$xIHc?Dw3+c1-$p#RKRjwE%x3GFgS!TGAvge~wojAB3M`F_ zl`a)xU1ziV;E}~8PWJo)UzPGGp^+YAi7oQ|_Y2$@z3-ryHkC^jJtzATXQ*5!`^L{u z=BP`wuqvS8*>UjJo+sU*`2)^30xF8()F-Jl4t;ruVd`X0z{_h%aoTN00qfwzfm` zIf-{iaf~d?obhX*Kp$gYHJ$~U>MRgW<;rShby#^=#`W!{Pw@sczDGr~9^U&o5gA~b z$9|@|?u@Og&0x;#I{YkZ;yc8B&hfx!AVT?IZ6_Mh#-7fUZ1zP{=Joj@68@(!99)o38qfs935qLG5V(RR39x_>({vi zV|9tON0&l+xmCalQw_lsYC!qjQcjq3KC>$;V-+iwa)u1%Jd2!XkwYyCAFQPa>CCQ_ z9I7+3i%L8pT@x{Q%?rqR3_0QGFKbUEp5s?Yv3sd3q=ILt-&V1C_sT}0Z2G;jl$tSE zHVRKoWmE5!jmFvJdu1s#8Yyc}v{aHauVM*OS!>VG6iN-fS9U1M4nd0AFm$k971DC( zQLR10aCQK4j!tSXr9`BH?}So*q|TYFgC(ycMfD6rJy!JacSsMW2H#N=a)5t8nc=wl zB2qdN9pn4kyb4$hEw zj~W~?N~EgW=^fF?wDu^FcKs}^L3)o=TZr`D=JpKW{@am5V^cf$uAf8tA*8`TD2<>^ zNDm+_A57=BhY#M5M}2wi!SBM_L#b8mymT)3l|0&BgLr^VPZD}>4U<)2KFUx4a~>{~ z30xsYV@`VK)Z9u)Hg9#%{P>86A6!iirC)%5%_`ujNLsM!*Rb>!crIcmoWl-v0Ac6j=mWhkA zJ`z*);0)434mXAz(V2R&XXnfxiBl~H#i3Iv8o{t(Jm&alAVylb@p#&^txh~G#eKp3 zjBD7XW-v4%lG4OFLi6WmP;MTpXy?ZedsCj9pYmf}ymW2_&LIW>+uhDj)I!#8a}&-D zHU%?SJFpsP!3zkES?J>=G?|nWN^$|lx)N-VuWSnQr^<6!0%Bm@Cma=~iAsIa356jP zx||R$q%Q0jG@@APa@aO_PE5wEpK3{%aWU@qeKEtL>MCvFtwWBg%<_I!6kW+rHH*;+ zW-)StS=8%(R|gM-5a2c@Uh>M!DlndETw(sHa;#2cc=Wa6sM4k0pUd{O>v6Y4ZWH2p zQ=570Pp8WGDXZE0ZPtm*OEGQ`n8?G-sx}qeP7(z>3xy2s%$(YOqK8VeF~|zT7Uz< zs+7m3x6>Z)bi)_W@n&A%t<8jgx3zPlxoVEKjl8$Xj&`j3P=3AN5Pr-r(=spa7vPc` z8~)h zVS~j>%73_3W`s5YCFZu0|HpQLYST7z$t?}IbAPDc8WQ3km>KGSC^W?P@40+vs6RcF z%2VH}UAgQUyq>0F3|GunfJ0@f^Ko{hDf8x@d*}Z)c)lul{_x{i|5QG$pVuP7!p)EU zs_+lIr)&dVzxXX$F6Zx~QABSjlPO^<1n;|#zRx`D@h}5o+&Y#M;IKTPY|D;ayy|iY;m#{H~F|iY;ixx+O`F)*b&vc$*bv+3^!}>Hz zPvJw|P7`cpCd@G?k=X?c298%tr6=<*nbJ^xv~-5g!CaDo+1Q5f|6UDK`6xH?H*r2I zu1lA$6Zmkf!>gEvO6Adgu(>t;(p`qUJ0ztd9h6`7c^V(xA@H+YO5c#uX}Es|Qs1{^ zUJt?8w)Ujqx;r+xG-Efl@M8_a%=v3EBN6x4K=1b3XvyF+zaO!RecqBvsMVg*2;d3f zUk+KZ=vH8xKb2(Zp8L@&e{Y%HV_Zjj^jm=q{=2zfwOHKzgA^-|^7H(>k4oJ=d$t9; z_Xqu6s)6b~)$)nN@G>+l1Nwv=;?OisYU}$E)S6Z7WjqV?L6Cv4mUR9)CtaHFp98l1 z)f9tpqVHA1sXoOlYflJYWjon$N>r^nCC+;^v&XsVM_zedCYS8rSdVh5xrW1I#zKzI zT(}qVrRESI5>HBK-*DM@H*nztz*g1M!ZsY zP|`-+3fyEh1uFkjJe?US=^_H&nu5$O+eXS6iuFW|xn7$>sUb)yF)lKsb84hiI5$K( z$F=`4cB*1x%$8WKcOP^rnLW?ul7BmwoZ`XV^X~(y^_9&ZAr73X+qs1^Z_#q_dd4i| z3OhFBIM(Z@Q`FE8L06Ax)?=4|T#8KSt8s&{IW{ z{zv@B409o_1afQ2)LnXwu+6=oF4F(Y@X+Q+zaw1JvVr|lULB`DCPVD7C~=z38e^@C zfV>_vo#&ptGcb@*h?O#(utN$kee&`!p#u2{Ea`h864L9*E-89t{oR)h1dFUWeVjR_1f%*n| z9~aFVMp<8iUIBREeBO9LybSHYtHo=Wu8GFO5%ERVD=qwz~_T9FahNkSIxnyr1 zjTw`pao-B;?);Cn)1d#`;ZOn#?aQY;XXoD?wRUct zh84GQMnX?q8Ayaj=>tUrz26KV&K>J(9Jl?6+z)cE<&G;MeO(sxSytIJ#J5s5&Kj-g z=lRlQ=VSI{N!tH(9jw;0J52GQ6ymc?^vr@~o==N0jml3$?I3^x(lG%N^gwUZz#nat z;xCRiMf-ktV{SNqG0_x`qn$XKVAA5~&p5J}lsHn4;xA6dc$|i7=}iHh)j)5Ga3gZ8 z{=5;m`yg6(Jt#+H0@`J3+JTlYwo-W7!=U=mlXjRP)#_pW@2 zI7d07iT$B15&BDavjVXnzxRR@S+Xjb*_H|sHl^A}6~b>E0eCZ6fE=(u(@f)N*1%!= z-yIrY)e@yz271#5czAcKg|yuzKv~2%RaBK_l5OdV`kWW)~n^+{YVe!DcgKtzh z&|5t~@lpQ@54VBdi38IF5f&8@<3l_<(EACjEJbq(A=D-soC;zlE+Xqzr4U{}3asce z5%=^D7}b4X5$Fwk!^pC~)xH479v0)KcvS!JhWfxSP(*kepys)s|583s^-|s_SVq$e zirtDM&`OQq%3^_GI13JXRn*F47QXUvex$ta{9Gr2}U^!U;$#kH1zP@Go2~nE7r6-eX^gIxYrJ-wp0Y9r$@}fj{93_!VbKc`?1sIDac}h-KkS zB^&R{D@X91qEm@G`z|0&(FpH-~g8Ly%(E0B4Hj1^jp`PcSbtN3K4Qcu@ z2Bon|eIK(_!iNuFUt{bdKfAwsgOLQrA;y(>R&y!>+*g@hzu7#{+c-c`JZk(##8)tk zN0gT;er8mW+@itQ*GSqZh5c|XxKW%cL1qZI?-IItb8cdH0F8~oyj{r7AGO~PEJZLq zqAWY#AE+Kojg(UR22*iT>a}hI_B!K*cq#Qtcl7;9LPFVMAsjwj-zj@AepQG7pM>5> zg%|7aBkDHdk?8^dUzk6agNLRMe@NdirGw{EdWVBooHPOIkHU}2$_?Wdqph4vzF%>$ ztJl&WU(p#j-Z>t##Y`a%$6GsV90?UUj`%8n@8<(?6$w?m;P36hQ9O=n9Ga>A-sdp; zf-5?!H;~Glb$r<<_?2k|!4z>Ip8d6jdW1g)&v33YkldMQ z55bvu_Gyb9YdWM$vp>+;6;Z~W;Ef^24Cc;2Y-a)DR-fj`mplT`FdAIWt%it7@J!+E zieB2Y@))u8J#?h-U*Hw~&t=_#j_wGwMcaef*%Wf5ClHHB2z1;Ni0+M)5X_&{sz1`< zON)SQQHJ~-Jv{VyBV`64EC0ax12QT7pp^a!>6>`BVgARYvcl`g5e4yNL@gk^9tS7$Ym6_8SEvUBYM00M_08UA;?go=za2r=Gxsp1ZuM z>5#cBu%W%0@*4Uv3~RwdSnDoxnxi4dx&u#2qbpwssqhCr?7l1(rCg11i7q3>1X*Gw zEH(DorW+1BM(Mn+8xCz5r74x(#T!G*v{i|i0ggf!5DF&l5cKWoJDSSSs$kDHb!*Xo z`Q4%T|3o**MZ*X1CD2?v<@?DB|6x4Q%5H`K5PpA!-}msl1iv5Rt;q3P%LRLTHShsp z(57RS1J;4Fr;4f#ItlYI(E9*b@zXpG`+MTr>^HU|PK@dec-neYG!C|~58=h*ut$UE zyp&7DI^^{E)5t|;M?ZcfD1H>?Qfq~Z?xO((J3>41bfwT zyZ62U+EsG~X+|lgc6?Ln7S~#+H79Jrw#;mVPG$33w)=5&vQ7Q}+LitPY?tGIY1jP! z)~@gF{JdS8Pmyjuw34&)u3>`a&2*N~qOJxyd@%Y$PhfJl?m_u|39ufjm^NIdsL9v( z`05oS$BiG_Sd%-%cQqdjYx3mm5FcN0H9w}FEV5T~Lwp(1FPoAVySDt$wve`~x zV4>l~>fRstbvM4##AiJmBpctRp1}6*vDuGjbLOr^_WbvN;ir*9-{$DR1$-M^;yMp~ zufe=H2D<8?piM5Ue4E2&PgupUe1Na z3t%heMr&xbQAneDGVwXC2i~9J#c&NTdv|hM@fU`_)g3z#hh{GD=3g(@32p9-f>8HB zZ}cs2tLx`W%tsnF9G;StuCQy^3y{o5BRUCbCMGo}qJL%h_OC8Ny@Y#A_lOl1k5~qK z#BBQ>+Zg-nwKCxx@ov zWi|qFk%-lqa~fE8E0~DDO7@o~VuJ&|z9UhH!;Cx{K7BpCPu`U9v4~gV{O42&yBTKx z2y+r|JmN56o(6wntv}!hWHOBwSmhL0^dr8DQTV@CZ5OZVRbZFUVeYht@Z~Ch8NO!H zUG@bsIx%ZSSm!DC_5`}SOvmKtFN20FSN&F5Ib#7ac`2N-gF(En8ZlRi6AYdnygx9c zcbV`c8xHGkDSy=A4;(_Qx~WL*NP%6YmUB&5h%*tqD-ml)nGqhmDcy)?mk6Z6t0_@u zq}+(^z@NK(ZjxVKO_`5+i;ODFT0H@00N3#2k0xV|{X^&Y%H+WrF$?*2V5WocWQXuoOOU zrjAx;wM&I~8ztcD#M%w5nyQL=bpR_#O#Lt5BWz{b;@~$*a>`tP@Yp8FBG$oFhLoB< zn3^r6QU_CWq*U@?N{~{crPNi&Tq!leuQbYp`DG+Yz8tvfpgYjLBK!*E&y(`E2I%ao z{smI1)W1;r-Qm}K#2KBYhszT2gbM>RFy`jt=u^C9&SWuDE&pV}W2r^o0MHy*H1G zs^0&{-)Hs#ltHu*(awMiipu~ls4e4wBZ~?ym0C9k0UO*vz{GClxD{I6P|Ofp$gC_| z7}P$|29=d{yZ16T`&`$Yta~%9>lw}ra{yz0&)1m&$-8{-@Av!X_xL^T!27(;>%E`% zzCK?-MpW=iu%@MWQu&nVf3KUyM`NsJ^qm)d=Gy(mG%8xzW!aaxm(`^2%YqaLbL|Vo z9{+}bWp8?24n{qBZOOP*PJWAR$?*GWaY7DP&1&WWI}!f!L7$)Ko{m~E#ySH&zw4V3 z^7+=T4B6+Ivd=SQpJxX$_Rg%E4WAR*X7A0G!`Lrq>nJz5UDuhNNyqbPPX?ZQJu~s#9-wa1L- zlPj0Gw=uW>GgQk8hW?;*meIMz{`*BW(tBL#EFDg4Qa?Eh=ki$soli^yj`MzxU9GGM z`2QBDcBbJ}Z@~Z8fZa*64kKn9X~2H5DFXgkoyuo8oKkzn$#A>-MGvp!llq-JfL$r+ zb>%b1W3BEMAYU%}!5!r-4&O})e-;cbsSa&q;cQ@^$ElQHF+95l;)EWpz& z0duEE1DQ<+J$BtqomCQgHitEXbDM>O4jS|Ij6l!hUMr0NJJ70-d^h5X(aIF#zPqDs zw}V4V!OP=18W$eNXo}EAeN-{2M;;VVF#WMC?O|*jt!y$D|5_e#{{5Jf4k6&3lsn+9vu!B#)y15bW z;toN+jgRy6?Kt;tf)7b;{0K843-5vC$2Ue>O|Pa|QSbIhqS=qpE6&|hUS1S1a$^y% z(E9~}`qaR1jaxNbb&Gv_!<9wpc8B%%i~0liF~+(RJ7ojvqW7UJb}JLn3%M915-Spc z!;^S}OG!IU@_rM|sZ}+EAOl%lK$KMjdx%hI)ipFn_WQ%Tirie{GTijZcl{5{%~me; zWzc}XqT7s9wxdyU$}tuk*!+-OQfV)UW~xAc4CiEjQ9m09cUo?L>O)~fP#F2vU??Wk z;g}Y`|Lab&OK}0JemHuz20Aa$*Cipp{@SJA|4!#Aoce8A^O>~R)Fi1)FH65M(K+B+ zyB6|xtM~;#NIP=o5ou8aL#jhIr(CzGAHgiP{*i_{+|HqU8Z}leq(HLj^uyKCE5N|# zraM4!7AiRnCXLCAgHl0Yk_8p4gdEgnf z)^v<%_idn+LCtfI%64$t2{zL(2Ae1#?i`(RnSpj3eUcyFv6f*xX)_%_j4%rUZqYHM z^x>)lNasYf7Nx&bI}`2HZj}6DchbnH+kY9WX90h;MC*wuxR*}rgVtu+*;@sf5_}Wg zkz8b=GOXa~iQGtkq+t+b32Cg{m~ z_z=!!z89r*(b(j@WR-hJQ-S@=idt>X*U@8cXjS4A)Evwt`?FyAK8sYf$>p2UHdwwb za;om@NOA9x4l*rnyzY@+sWxM^=3&Sqq4lCfmwjB=DV3Yv2gvU{YV&F#^7P53{!fz3 z2n$eF`T>v12wls`Ox&vqzTbRO@3z2>C73(u0sjmt32w&AxwS=}=|TSC3m%=8qza;y zEv5Bd8PNZZ5!-3r!NY0d#D(@l|Xa*f`D-;bVT zUn5TvJ<*3GBmZ7&r~3x9HrO+>6LPCBwy^CD+Fj9g4mqvskk*+E{p@tBG}XQxB}^+= zPQwQ!!x=L|8TN@0Xps<#LA#fbezl_?Ykmhe*aF7cV>J72cA>uOV^Ffq@hB(NKGD|> zyVWGg66l0zfvT`}67b)RFClpi0smcB^PF^QBUg9`=Yt{)sNrZI4AnYd(4js6F;-`0 zI2lDP6WuFKyRKzgBDYK*NLlVVkQR0XbDc*mF|8KdC4XqlZLa9i{asqf+v0ZNZVYUq zO{rf68QxUqs5agQ92A>Loy6h%v1RS7I)1sE(yLXr<`<3HiLS!5_d%xnH0Rq ztsJ9wrP#S-_+_YuOLC_b?mk5+_HkEQD8)YNy4GTF!ymsGgLxU+i`}Z-|2lofOV|?x z{#j3ZC(a7DZ?@ls85)oQ>v1=#`Y>(^4uMo(WzrH!VLmMxN{70TTV1UPbsoZhr0bxQ zMkO_nH^oIpy59E8#<|{iHq38&wK%}DUB3Z-$tuN}MvuS$FI3KG?i`dKDWwO)BHRdF z^-}w=9YgGkC51zo1ayeJXoPZmS3Tx_)EX}As&u|By~b=#+-P;p9?!KN+K|+wMC*XN zsAwH}p44IoeQjzWY{Pr(H^EoP(Mwu{*aI!B{_$d$6xU!Do^x>HGhI`hFMDRAK0sRS zsfQ-e+4be7G@QXRVs@awh+vpcF)7md&;*5xdVp}}Y+wy$B0jnLR|B!&;h;(&OhCa<|46T;oLh&jj&7jBwPU5zjI3>oCGOj?t1@9`Oj`YVRFx#rTDY z#WKXg2&7B8ZRHcsc;A=4F{QmZN;-ZEt)0cnV>vOH)@B2drAojQ8YK$FPVV= zPx(k~)l|8sl#YgDjJw3X#lFWr&+c0ky<>oVO0g1W(Yethfq(K4?!djfVPzAw_$z?) zkKGi!6?gJYN0F;K+*6|S8a7CSo|81Fbv9(x1pIgO+Pl4Tk!&vy_N4a}qa&K*QAdM2 zEecRlgXMAe7U?}B;kHGf#A<+v1SCA8Pi*#%#cl>OwqcFD$*b}WFF%GGZz|u|@)0)N zcSRgijeTlc}pVr#9uY6J(+fweVLElm%arIf3!bZOc9J(6mhUzm9W?fPO zOXnfebo)_R&xKn8OI%NNjGA=V6Sz%@I|2t%qn-2IsL`#Ti;hu8rH85q3z2%xHLB?m z_b8y4ae9@TgWMTvPjYG3D_-S`FID*x*4`JKkEhhmBw65(rHHXIcD~6W&(X}!jx(etjpsPS%`3S`*DO@!>4qJwttN}-^svm6#&B)tC;=3dub6) zJN6ex?}!$3k^NfP{o#pWu07IOb(*tk1IENB69k=%gb}?t{C-u^;?{6rBfJ60E@q*{ z@owc)=r^8{G>-I3VPk%~A@`Cl6Zbe1r*EL!oLw7UUIS{sQQ)-HZ_+qt307XHufez# zD-6dlCT3`fNNN{Q-+=8*2$o+-XN?@rzn?YYyZCtAK|7Rn|UAsI0ScVH*t zmKyDW776Y%uv^L|Fd?JYmloMoOMJ0=I^xOo#zDH z8jA4(*FVO072-P!Eic8^&>PObj;$caR``e5Ztsol&yXb+{O03wY>&qea4V)9Pc~pb z$0u$fS+=Ji&zy>y>=S=#e}3honPlb@|JKe%{qbA5t+MWs8d7Q?HR~pAjtiCf~-u3%b0qUz=)ZqBsG)stgA`TmvUmGjvvmsh$)695v% zwKDsqoU>oXx4Svu@m{bGPfoBip#x*Bjo!F7_pby-0Cqb+BAiU&f%HUITRgW5^6|LQ zR*b`OpY1;3H{T3(zqx@;*yvTgd41?qM<~os`h@u*WWVkIc{@7@^&S5%P7LK!3i3N* zmf1iJH64+7f8M?$c7GqT*xI>|Z(He#IDdt8&bMR&LBj@2)rc zyD@f=?djr!^?Fh3SCU)SamR1^8*sMdcLras%3)rmv`78VfW4El*-4n4kl#+k+y9nd zykq+X+iqzbU)MxmuddzI*eQdD0#=ELd->$)ek{?$N~LH?|Na)DXr!NwXvnbGv_(?jTlpMkU!rKEjL>EC+L2( z{yE%F+^fQgVBND}&roXK2Dv-R2|*++nupj0?F8DTNd}UZPs|q%dS>h1_NXJrV5de0 zX)!lMCJZ5&SMN)Ve?i*C-{2Q^LMrluVqqN)BDAl$YoX0P7TF(99Wu3NBsx|=) zK51R+dl>V+-iVpDizUu$O=?tj>BO2Yk7#wj2f05Pl@)Bi}ubV!us2Aq_r+xkooXYEfavOJUKtSUq7JT#y7pn&YV=hBV4H za87l*?~vtS^H6JoeZRCj5B6KeHIBx4bDVH_s7!ETcaG-bES|Vm&uTDBApdBdcx}8L z9D5@LCq^GVjQeLQ>k6lG1rSegvhOaT`IG}Az4tpbxc3|I=LGcbLL-Mei7;UwFDQw73^NaKfU_Od#oz#KVFWC##qVV=jzexZs*9p(y8mOslw_813E$oR?a$ z1G}EaV#qA7DZ#l_?p8&$W;|<4+jRco4T6?U=H7!k0~KI@x3lpKI2?q^9_@AHM6@Qr zC2FTeiIw6Zl|!7_Sf|;7Iv>1{VahCUrcePX6EmE01k2`*yc4U8xW12Nv z2%LJz4U7VO_1c8>0%{Jvb}e@KF|&-vd3}7}b}0&RHyG&q-fGXr&9%PYH?)uI?|{WZ zd#?Y=^;2+d?&JD0kl=e#W_llgn&D67Ve*C2H5dnjf#N}NsA$i<6q|q)HX()UZ=&5u z<`*A?gn&$0Hh}7oA8XSptEnm3s;rF%*5J$SBduDu7P10VkQLw+|Ky`_IV5n(b1)_R ziZqcg?czcoWDuw@dXl9Qq|yB*NFy*J)T2Hf&e{3JTu&_UiavLJERVK#O3{w+2On*q zyo(W(dKLC5G`nUMt5^I1wM-5C5{lad&sLPSFG;>Z7!dtsWdFrjzrnn)r5)!yHqSgq zWk~REiSattYIhobh0zWy!Yw99PA9ns?c!f$y!i`TevOfTdP`r7{G};17@xOp0UEwS zziTnRA`f3c-&V+o^NMqQ!S6lmWr_Aygu1k-6+ZBLLJ~d*87%x$28<$MYTHJH9Q@&qKO@<_ntYzRUG)f{WLE z>T0`e@{Vs2%>O53ULj083rPaimEX~7U{L0RU)(KhvZ`@nOYM1Dp{UW<(&-fz(GEE( zn{XqbL#&nkc+#h??GShQ$feR143GbAk2I+M@PqV?G{a~YcX$m=F_@8zgj~6Pk>Rb% zlkcF19OUZfe#c{oyb-#5WPewb8+I_KBVQEpYcCKNDRavB6&FZX6~Fv~!ie34c=ayq zFW_z~=f*n3PT15lVdUnd9qPIoi&A!@j?cTGmG?nEb0`y%Y>16%2_zyelcg}QF;iL> zDJOl6mMtp#^sW z!a*)A&59t$@Z@HzyQyHs3zDXKx1^hR*jW!05!FDApg*})(jDmU9;}J@I)8-|GN~<2 z4hZtc&{t%63sxMKzBin56s$N?m4uZBpc&Pb3Fpthc>ywm^dw1wkEfb-v&Ji?c=>o9 zJJ5q6dtUw?RoK_@Xg&UnR#{=+v1mZ$0B4pEI6vKOEDl?3Q0q=adv{GxyIffDtC6;t z>NEqsE?7Z(H%eLZ#F?rK$sDBWKBiRE9NLkMULh4ThJM~5ZrH&oJd!uz6~7ay1-5Ud zZ|`xJhy8*ccNdbC*ij*ug3sJOeHo>d?vg^mB~$>jLFZH@-0>~x^+Q<>oKC->smpG{ zts_WggG3R+*xNv>3DnOseXw5Si8I=crxF5QuJ`+Lh%qoyHX~o_sZL!hi3u>dtrfW(z6k4pCXCoL zDCftioi|x3??PMM2`L|PKR0=Z+|N;4Eo>SvZCB$@-yXEf$i?#8C z++ml)xxEs{e}0+cwl`MCZL-9jE0IqpW@daIV?umR_-mcU;xwG*s}LSKt#==)S};@N zI*2{fwcLEP4Jq&~SjR1Ldy2DxZIw@0TE9HK-;4pGa zZ!FHn$YI0DEjaf?z3}l)cDSb(j_7EGY&M3PmSA6ubxZ1*H60G;JYX)ZWnRQ^i=V^! zkAVNlu0%*u&$33v-v`W`)!&-i!qKw^^HYiZEI7T%n&{Ld#0X}6l1&A~oM6t5{C3O^ z#3DTDQQrReMU~E2tcJXe`vliF!5qC8d#Mv!m9lNz!ud8Ba=SRS-BRhWYLL2@HgDOW z_N>yA-1Tjc@s4>bmx;7_yX{HHb64-ZyaOjgJh=);dc}zc4UaZLP$`tVc%0R}PcVKH z%(Vw_dTgQaQz+E2Z7oh6>ORGhA@y2LB@{1#ln!7k)od_o61Fq2-t%x9j25t{bQfQc4F~mS*23$bF^q5RN$AcZy2(J8nxQzCNrcCG`0Eo|K^8 zW0IT-lm;typjVJnLa}Qv(gEW^IUVLB6`qA;Rw}!}R4D$Y6zwY?c{`BBsmFM|jd}(O zHv-{KJ9Wys(M>(Z^KF{yye8@q-e{wgBGV*{y<)0Ma1Vugj_S6pRtIcQkJ%yaYtx|3 zukE!v2zCuE-&z;BHT&=l3N0k@QLllSXSH^pzLs3k?q|DL>fHpXyB*^FvJdOq$ej&* zS=)=!4fWI>s9inryL8gz*460*lX6Iu8mBT8f?3J!%$*EO1ALk$2<}h3QdJYT*Rs(&=#7ZK z(MY}eqCxRH;8#al+4usNxow~sn8|Gp(Jwzz_;DOgdAJ%2^br$pp76N6;-!YP_c4o70T0-7hx%YD z!;K+!d7JuhN0{wRd$shV`GX<%#k^q~Ipdy94ITF+0~a^y_p$q8T5v`zVMe`lPqKhB z{bBdhOl%DHrbox4r{cz7=hnumEs4zvE9WMR6PFajsVWPd?0%R>#W+8IJUg8kIrkTj zbH**w=qNRA{(%}{YW(x#VJS*CaU^B&V`;dN&e#jNk2WBbj5^%cz1xJ@JY-@nhetGPRyRe ztS?BH`2R(!-?f2D8guIS<#6Qz>F=fyZq;+JqnO^<*m0>8?zDke#RTQKxCsZFVVZ8(L+Rwf1iHkglemYJ^WlX92U*POwuf9oF7mHmt z{oa6IAL#jp8as9|Q)_G#?-P)?fb$2b$3WGdxk?pK)tA`0lqELW;|%!!*bP}yu=PEU zvE3=$3Taf;(3%KNey8FrPBqSQnji_amWvf~pmI28M_3EyO!Z%04vV-q;}M&>Ry!ki z6P@XXZSg(7N-zsH+4mB=uB8TI5ZJ5@Cz1(7)FaqNBEs!Csa>q0w{(PM!`p>YJ zyoKzcBos6e=5wMkSS!%Rg=Ax^h52C~0JU_X#tQj6$q{(|SW2~SlS5ftBZVci zq~Ep%>)!&@zsFB1(VsQo)X2oBf$?gbwOxfBYO0H=&L>d^hoCN!?4W%2|4KKfDw4ul zF+b6WTgg;;n9?7+wD?l2;Q4mI<~-b-2(}TFC%?srm%j9_rrl^M zEzW~zsV3syZD$!_8>)rvdr5*r&_^^;`!ahsT-x0n3%6-8^7N6U`e=Xr4 z0f7dp1*@KoP)DHN0&g>Z3{+wu;zLTs5~#bO?t!{wctQFJ>hFe+5%-U!R;UwDX|Q`U zlo`qm-U}r`U4>%MQ$gvVBA^UV1EFH5SHO-c;y)29*8C3JSMX;?VGT;{0PKyv$#d=+ z?0#q4NGA->Ok;LYwtYtt#&~>KA;yDzHl8;dzrfRM3@bX^(a3*cJKS-E56eH?@fM$* zkJWO12c8oD1)f*=uw_`^HfH0gGVZ`rXZ!-s2xC|Q@U@NEcn&n~z%$191)j5wUm&bJ zthp~t4qKkHymXddPVE!Y?0Jt{wAew-oA)I04%lwSI?K(ioDiv2jhl8-F)pnY<3a_b z6t~`_hkQ(}V#0*hFug*+m4Gp0PAbMEwmz%V2uh7&d_wE9`rzBJ)?)}q37o9iQA2RX zDK84B#Lc&2-%&MYU~?4aoLi;W4U}5ck6NRsCNq@6n}zd0a--7^ajg4&x;ILA$Gd@d zOgHg9bXM7QPGCU#+%kOvw@^-ER~+XI@#dD_w&CswGk%Zpg260`cO0d@*bm8$f5upv z+c^+>*SP7{a1IF0I2Bdz6Bl?Baq@04W@cV-sz>Rjcc18P3$6m5bkO-ppJ;}yOnLr> zH9y#*cc1u&HoE`Cgijqo*&+-Ps_= zp8Pp2(CyTRT7$lvg)cvQoTj0WX^QnEAI^4=Z~CODbC8R`W;V6m&yCTv?)RvbOMsWD zRA4Qcr0wE-$Ybp-&Pt?6y+abKy!Ey!=Tz(dDp9;BmO|GJ-3M_}-EA{DldTt^e^#X3 zdM$3@y??R$2`+_Grrg4+XQ#4PUsa+URUKg*2!{v9^4dW1+88tMVJz}BQksxG*|tQQ zY8CsuSuLTp~;4(zr}+5qCS6$K@%PFTcPoU;Z7`_fUU@`Ww^_ zP#2+ogt`QE8R{pfpP~NF{ozXt-kF-|m|3HfsgA7&w*!g;&jBujs99ss57XbIAFdyv zAF1c{M*S##qJFeKUZ0>h>67&-`T_b#z?E=%4M6^MdWBx8*XzUd;d+%`t&h<6)A!d$ z>5CK-6;bi$}Av zqJmZV#jE-9qJoOzk~RE@@@f41qKb88Yl;f_5rzD+4HZS@d_@UgVK3tCMfs&+Y);YY zlCll_y7K&ci>8G!{lcQkifR0aRfUOAIitt&8Tl3YztXUj!`D6*7F6UHtb|Ts4xG;@ zD_WC}5GwLlkyavf;fJ-XsHhK{wFcq!)yTYaPOmXM37Ydse93)9Wr${Bui;pJPJSi7 zIvD5T9&dUg3#W7PSFI{3;FsqYuUc1D#21vTTSK2y2qQV3{IZgYijvj5J-?h^R#db` z4q|;-aYaSZn(ORL<4u(#O2_i6*01h)Em&7p*7IIbQW|`PGx|QhJeUq}REf_X-Rn-~ zU@2=2KKdVQ*+afxvqfpcmzI>Q3Z~!aJ|Dk+LW#YXmA#ZLkCUzU8jR(yx0koFBCC*J z*pn;QG6Zi(sUkUn!`SNeY;_^KeQwsAyxG(Eviw^{pnxn)pCM-sg(TbKiz*9>@Jfjq zX1y~jgEu9Q8&Mgyd{zFviHQC*0jLEjAI>a!<`Pc z`W6SXJyXT%pRHmGpQ~bz?Wod6XcA7=RWSveI^fO(bq;R-3b$Es`#Rk2h1&|a zZGqbgxP1+7Z6UW3+^VQ;f#P+Hjkwjpobw#)=OhQ41h*sLb|Kt4;C3S1u7X=0ZZ)g5 z>}|NE=39@zGZ1bE!sQk^*mi{LgWI3swhC?qxIF;3XW_Ow6mBBkOY=t*-h#R^qLP&s z_Ib7Ud0*B0es4ip@B0W-%A&q%To3baUV5zbP1y!Q*pSBWM@&Uk#ZPrQZS2KgBZkT8MuyL|+2^3#_~a8i2oV5QTdUDEUW} zei5Kl{(JaL(uZIM1t^d7Q>cUX7*TVOm%pG7k7fx)^_n@H|B7z`>wr0hzd1y=hUmi~ zS{0%@LiDi^{auJwhv=>l-5sKPLbNtS>q7L|5UmfU#6Rb=ED+$=J>3jIrL@oEkX0q$=7&Ue``=b<+hMMcv*j2P~SY`8b3f2 z%%Aa~f1q{+R8CJ&m4mT8pp@Qqpx=X5fzt13PCLkJej)qx1!T^#7MY@*4%rX#a3%Bod;Ea~3U5%zy_wyt3;M5>?S;WTnaB3T zrzOY_4e^FiLH?#5a~2mt?lsIXirkIp)lZTAN$llkhXupAjU$S3ts-hw4bu`;u%Gng zetfTe<{*9-7fhEzBtg)Yki99xrwpg~5T$V536)olX%(ceRcPgWpmv4K z&xg!;_ItVBpcRqhiQ!AA-Wud|-5P2K7#k>?{|RN9{6q1P>6^MB58E=YK!T9DfqfzS zt6(?FJbFvnUj=FknJ;9DP&hi-{EtW=(#OzVrf;C$$^NJ^WC|%wGS#uqL;jj%p0QVc zrd9TQK4!S{e#}8W-df6=PdSzfBS3VJwGlV*_RTG(IJB1sCK8azXpw zgm~&W$vmD-k?ju(**_oRi&)V9crIwpa9M!tM`6TDl=>B-CqjH`$o|z3&oB}pa|PS+ z4AHJoetj~xGpHZ7Wg_W!hthl5sE(li081?C{}M_sXS5X5kKGhS`d67Ej_8MxS7m*M zx1fG7KBQ0OGf(mBev4yk2a-MN;>dhq$oyLU`nCC@ka0J|Y-jbuhj(ek1>Cr`1j)`cnU3y|cNf6#mkXK96w$>0{|nre01dn-}%Ei~g1WXb)umIK~U) zt|~f6$KH6}O#ZIwbvHItAL=7Xzob_`Sl?-ONA6of-_w#2^rtYypH-W03dYMShm*(h zWZIJ-KGbLO_x_&mFqoev`#sbwT?NhwLBI z2jjiH*L|y&{Cl(~yt({b;(yn}Glx0of0*p=Mdd}goTg<5{jKTsr%;a9b0J>Ab}PuA z=R^Fr__oR0)+;>Cz2lGpBq;QUf z_zyzv(n8}5uyQ<2}`_HG8*3Vr~1`hF!^4jSjRK);7y4!&o+ODzkT4-A=WL;MyrTx1{PTG`wi z;y+PyjNB(7!O8qn@Z=uWWd2)Bgovkjkon)hlYQzpiT^2NZVK_(wwBGQpCWUA$h?QY z8Zu7|nd9`K?0*lh1yBAH-;+K+Kj&Z{zV2Y>-f*yvLk@Pd!NH2&bg<7s&q1w)*)}Ns zYYwJ%I@m9-I@t4M2lgl7ebe&}_6bz-K?i#rYB1CWxOcvUH8}Y9IMiQ>zTjXFf^OK4 zH8Q-N|V!KT7(5%{Tiza45E;xiSh?{6K<^WpDQsI_qaB-|QdXE0O~+-!sT>$48| zyCUIGh4j^F@uI~;t0Emdh{{t>qD+Z8)A#4p1vwS{khW->b(HTbF!$>DC2O$8c>Hnr z_HXPUn8(Jy^DphhP^Usa4Ls}fOCC&2J&V9EO!?2lcVc`q>b_H1;=GEw*8rt%$$amCksY(ufEFI%_@#VJwc6OnYRH`d^%&T_gGl{3=PL& zVv)6LIAb|lj!Pjsj4hg@<2V#h?M)A$z1Pd{q~G$JFpi^whTp;baE=?v*z)DeS#?na z$H9wZbAMu{b^SPwCmW2JxAf<@IL3x&?P4*zA{AUJ)>Uu40~2$Dq9-i#(@_cvi++xG z2Pk^{=YJoq=za3akQy&A^C{|{+CaJuu~ z+DY!m(DzOJmv#p9DMJ)Gg^Mr#r+Gvs^rO5EV9WB~mIs6@1m^xzJ5;*fLp}He`I-#1 zeI{d-(1RA6YG&*|NNs(+s2mddj4Yb{+#8p2TLE#`RIjtt3Dfi zahGejX7B%Qo7CT1TED_@!-oe3>sCz}HhX>MsH5*SOgtPBH#Pg!lXG*wc=|4}WW4?F zo1dsCDR{ARVCC_xI>l#?bp}4DzPu{$fd7S#585i%e##}xym$MdKV0cP`%dkB3sVfj zw}1Y4Aa63q@rLzSw`U_v6Dt|LVLJr7LghTR^2&pIl6;>{BR03>K0akCpJGZ$W+^Gt zCQhAZn#%G^d4}B+o~_5G2}?7jj89H3?0K>CtZX&U3i1nhmcP2Ra9xNjt*GpIE0f>K z3)l6&kXc!NVR6aQ()DHKwEMzJQxMAP0(<@%o)s=Ht0?DLMI}t(F?L50{<4B`KQt3cE$R+hllsseUzX>m!(x(XC4_U#=U zdS&LI=Jl46?d$?5mBGG0nB#}fgt9}eV+$AYbJ7>^{4~Y~cLGO@7%lH%@${Pp+s{9; z9iv~zKlnAj*JXZbX*tVZy1q0&_$+3$C2TJ#uULwG+GX;_D88m(`MqpeMFFX$g(c-n zY3FKPIeYR>j`c@4)Q$B06|81Um$IDsr1#z;j=6uX>NRcvPrp||4}{){ci?^OVvbdT zZfqo-|Lj-Y$B+Na#eZgtV(IMTHx;@RF2c>TJ3D6;+qd?Ksu&1w7$$5Mlc|&pOq3JNEh+j|l!9Jy3E9}$Qpf1EK z4W`Lc(x!R?=NP9@sx(@io*$7oI$=zTDLle5%bI$dIeqf9o2QSvB{O^D;{2J*R<0^3 zZEpGa*k>8ubHzogQ6o}}!%gF@lc$f%+_?CjmCc`JZ1bMuQX(eJu)^!9)6!(8OO`Gw zT+`e_u7Uxne-+Yr3J1aU26e~cnSDbF`Zsw>uW!A6g+iY)H5mS#1#%3YrpT4CRcl#B z*8G|23&*ii`v%$>VP^U1fXrSMk90Vo3LsgakG~gH0p(ckMHO?idOVTL{h(vU6U!#% z{qp;M`Td|OfYfYNwQNKgQj-rasZgOEFTu9}tCOEzJ?Y??#(1wjpq#??!iP%s98Ffu z&*8nA`-@7)bnGwWC;yuMW{l1yJw>H-WyR9v#j7gt3HV`Hgc5x1S6Wt5vGiUh6Dr+5 zVKJWSI;mgqPW>n4b>H8D88i9J{Bk>;BAL0WXf;Y2zb={2OJ@JnB!$mQp$2m4>ikMH zy+un`m6Vjq8pPPwl*;YUsv>5-o5PN4FziKmPYk`U!8?Xc|Ih}NS1eyzQG}YXx_Hgf z!gUoJmKJO%fIrvtOV$)ul$0&4z{dME-3ohIQMnzhb@{qdR#94jCcl8K&o3?R`;GK& zL*aI$ajd+sv|x2%(S5z~sO?bm&N*aDw?n_@_sIhs zdmidhsBc61FM@VJeF*h)NUz8Kpel|PL(wk^bi`vE^KIwYVyJ)i`y`}4bXZ)t;~iN3 zh+}QAxCx4eVlA&vQ;^)dCN}yB@|Cfpj|J&3 zj|XWVuTYNYOcRx;;Mu1BtRLDP`cq)e9f7t)2OaJ|dJlumaM&cbec$zLD%v{oQw`H= z@7L^Lzy4pi9mtwdod#h&QH|R3fA76-Sbg97`qNjx@B1G14Lko&!tHD4*YElN^cy4C zTWm05ABA-Mwf(;O|LXl(TIu`vqhnM0gmukr-+cY=`+rm5zbWwF6!>on{5J*u|B?cP zrlSVtdY5=>8v|l#m$+F}0rPcD@teh>D2QR>H(75u6*>L}NMq^*#^S*7B<1r3J7KN8 zV0*znaC|y$eZOEE2)%S!FA}(jk&v_0DXznfhy%dlO%MV~lE`ojoFYL9bUe;&m}5%V zZ~wDadqN8YC*7Ec=A&JrFW39+AiCedMuxjpK65$UIa0Tp6frSbxVOO)T4r&RKd^Yt z$f!2W?9*G-6#pA=qk`leb&3@}X4K*aK$m!v$l^Ca;%anORgBr*&=e8BApMJ&Kjz(T z`v_Q*WaCrMDQUPVV$QJi@jx8x5!c9&5>IM+eMi#!O)22x5`fkj*7*#VsZ_qJP#+xH}L5e8v>tRw*gZC&r1m?Vs>M z0iMe53bZ+VK|-N6r>NjeaZ%w5wlv6Hh_P`jW2R-6c`D|qNqSZaKD~Hg5_hgsyzyx1 ztn^~s7fn)G!_H~4IABu;{9A#?%Ngl@iB{P24&>}-5IvH_j6_}T;N68 z421ugP%33T1Wo z0EFA>WX7$C;e8@xz$B<%wE$<7q@Sh%8yT{n3*dhzX96BUYl`tF|GZAM`;z};_XwK_ zKEBE7+*61JFib(d|g+QPFxkyMT-`yk}wXj_!s zWDie|wo!@S=n3LQK~@NpYa7D58Oi_^jeJzW&T7w%IWe{ybC|Ex7GoDmw2bAzntgv4!LDKYD2!l8kWPVIiM>(9Y}O?JV}Ey;D+`3 zw-k_j#+rvCtlcO(6G4AOc`ZLWC1=WPu4W2+;^F&H`^aKJe5s8~NU){mjLaWm|1N)~ zq?*ly%&V{ay64?IHOx9b6ZrStUhx*uE57JwLb(+18@q8NQ#kQU;+)a56Kz@{vXi%w zgt37Cjc$}CVRRR7*9aGXiO=Efv37;ekrHd;b9&xx>V0EE3((!-GUKv*;tzr%eu(^b zK>!X{<`C$e!&_|DkW8O=Qs9B7JqW%B{4w%#ba$fN-1bCN!2fV}08)r}`vdR4{>|&( zP~G2+b%1Kn$5tpAl_AROo_a-f>haUt+4jN62ds(BIO1Ttr*mxQTMjm~(ZQa=JKb3; zJ$mDuvG%d=Ht5~8cU&h<| z0sFwQ>?4?((5`i$MbuYEQ87cHLoWJzAuvP3bl+!GZRF<*NRK?S=lKUl#0LjmW994{*lYKY|_J&Lxmt zVEGE#OkGwyFkq)68A68mF!$d^!|Eb~ssMH8diy#+1v zYX~PgM*-Y2W=A;Q(ivxm>BCiHbtmy|V`2SGTtajwN?W?&eQi?2Nd`>zbg!dgVE({W zT&hagsNyCTD%oJp%@Sg)k6Hwm;r+aUSQW6F?J+S4f>xT$^JUuXGQU zSm})mInzP7zH9LO!9T<@UggFCpcVxbXL{Qrx!CxabL`M>2D5}qcYm>vgACbD*XJ?c z$FTU1NfMR2{_d)UTuL2uRc?b-DYsP!n+Jw8A;Qm!%NaVGjXZW)sf)|Wy>w6q1U_k& zb+kJH_i%Ofh@qa1h?Ug*AW4rqyoy#1cw%e4+$7yN(M32d1%axj{y7+bT>dPKo1(s~ zSCZ`^_xISnOSaqQ;wDE-w9fnrqXglR>S)v-q~9Uh?8M^nz#NLn5PS5TefH>FC2)Q> z4&f38WGg%M9q$?-D_UYBGa!YIBxocBSQ8G=PmY*mo!NdS-ukW~SGawms!N%m&CEiN zD$EkZ#~WDlY~(40L19riub>Xj@UrBzqm}|lYA7g@CFy#_+kFWuSrT`KyT$KHdw7Wo)?G{d^a~Wo(6$v=Qr2jEsIWB;el?n1%k#3@HGD z*iSHHR0I4Qj}>|mnJLgy3SpVa(A(g-9eRX|e?{!@6RIG-bB0%3?F5A^q@MJow4`tT z1ohH_H1+2Wwa>_+RC^|1&YqF;iv6otbM`*Nl5}p@TI3||@^Xew&a(p&zrEtaBH5hR zJvFD^qY96;@3rlO%~RF5}WC>dWVb{z-e96_>&l0DZl* zOR*iPNqPJ-S|74UcD}f*<#Z`zvsSjbz45W;plz}{D4_Fjx`>I~zS@~@o*|u~0a@O1 zZovP<2lCq!a#=vy^rRD&2deWVi(7@Z=}|B41`E2*m6@0PLm?p-H(%PBud)=fugbNi zdvhDQL?I31(Ka!$y)dUJ`{S7W;=^5SVnKHN=xAHP+=4kOxsT<(PPH@O^(cKG6{u2i z3)^k7C)wjitIu61p081S&3qp%17-uBs+0ltJu^M6zcMS3&4Ml+m;7%_$v|GW6_2qS zM#Lwo5yD;YgM;6kTOo%q#9m8&$Y%FkXU5%v@EsRim;Ae>Y4*=AGfiXXX0gsZ_@>6L z_O`Sf4*e&6-+t7bNts`mIopRGo{R1TzHZDyDA~leYA61+gqIv3*5BLK%hSen4Oo8r;6Z{p_ovp87;lcuF}DR$hT0NVu%zKR$D2!pjh0w>{1G9i zjs9!K(+EUi9Tpm2tm;y`d24JIAI~5e_pcp{kI525&KEN$(N-y!nbnX}KhEAJuJ#@6 z5(LC{-OTi;oELqaMMKeZbZ_}_7d*yB~{#F`x2Wf z2hy`_rLzY9%-mO@hNEuaqJq0r9!GYH_o6m*h*#Uy=-u!7#oRsyUrT-8litn6>BS?R z7J*r)eNnpO@kZ^-=KRst^n8*OTWanUpEyDzM-?Q)SIaY}+hqSvw9f#FJ;}u+ftl*Nv&46%+??Mj|8~M9N%F6(O(hx9I`e0yG!F> zr(K6W@<)GVfb85GI0acx!_r}nQa%;2k}5prR#D58Ge=$vH%Q6 z4UpwB^kk<~kpv9Aq=AqOtZWVVe+cx;(YOQt?*b7y3efX`aP;3uz1d6bs`w@7I}MQR zdm^C85rH0yImr9LC#B;=s0^ruPb@NHfeGZCw&)M%Wx*YYvW~F8ROfP~rPe zcib>{c+5y|w{@ft&}e+jdSJ+~R&K-*AIpvWilpdaJZlN~UkWrdag%;-RE;~}V;N-c zXIJU_keBTY_`e7wTNRjDQ~Hxkm*8lM#x^w03+6_r_*;}ib9;Y`o;$@iMY>I&2C2rK z;>tG88Uv)fFyy)q_yQAv0Kyy{z=c*N0&)H12$#<5PJG*EzKwS=J`bgPmw2*CD+t=# z^pS4vHtqNc`MOgP<29{GtCU`I!C{}dgtZ!+)*Oysna?Kt4BW_z$%IAy3Fsw%^3`i) zYNdGV9E~**^SqH)=^LhJUctDY%HJ{HRHS+mM#&bzff7wrff9}pf#fzWD;_mQeGX{I zMvGupkdC?S+#L#c7~1GRVQdML5N=_i_{vWF^1777J3a(XQPhC$AQ)+w@62fe1ZXX+))wGsfW&c zP%Ti$z@Gs9K1vC<7mX_Lf|0@QN$CC*)dJk^7T`x?zL8QoYew7m>9rP(E2GV83Xff6 zF+&16$}2{Tty0_o8r3d#I_xT;wMz}DMsW%+WJ!<|qqr32?uQbX_WnlL(Ijl;l{H>5 z4hRi#inr10Z;ihq1~A)=OCS`-xB<#nX}+rx^1C3#$D{);2l;ga*`F`ZL?;7Z3vy*? z3=)(#T?>q`AEyL!_#2_1ICeD~qdLvq)((_R8b4_2tQnIPjULBFtH7*E*O*EwH*duZ zD}uYpL3ba)-H_ERNqHuzRF*ujiMzGUWs=>?(j00+*+S%J$njr$vCbW zh)J9R&*Pl3n%V^w-j8wWY8|hsX1un#)T$EZUbO))jS24n4SvbX5m?f!Wd@#i}be1wxV_xA(ULOL)x*h zri0HXe}9KVmQ)AlWsBlu$nHD_T=%WggUNF-e^m*F!&k&vat+GKJO-JQUa`|}a9$B_ z@#&nv_U0hLf}5GectO0wql`EJ`H}~u-*Grdhq0tNJKQRY5x^6v<`{n~YHfyx1J31E zDPF+?>v1PAJ|?wd7Bm7Yga~uY{K>GB;^CcJCH4G?Xl+inF+LS~iJq3m$EA@Ba=L^_ zmW#eK>=jN@^vm^{%UBI>jYRMMc6Zn-x&%(*ZYjWO%FvS7d&wS|3NU@8yP$aJy+)*u zG1DtXc=$|FJmlwdRKBfc^WtJ{%9PW{ErDNbQ~9>7-D?BBj$=tajUK$>-ZlowZYrda zjNG)P3jI2*?=+!Z_&t>2 z&Vo7g)?#Lyh;_?2c17&=D0AxV1m|Ckhk_7`o|jBH5M0D`v)^{=}g z>k*6(gY4z#oX0PkRo(tNjOk;5AB(mi_=lwoNH&;W$|W4JJ$#YpUXo_>FG+b&bD`$*hYMA3Cu2Mpno+7%a9Ql3 znRT#bGNF8I_l&gqe_+ig5s!~n#sZ0J!LrRO7c6VRH#Ifm_F=Xr$Mw+Q(x{D#OXqFe zTe@rG=~A@Ya{o{3J&0@W6AeH5U-@O$+*xx{?W$^ZO_CkB$V*wub({{sk>lSk0uI z0rtW6h+W}3CuW(3>g~$9emnDlaj9$JYOaV62uAA|JB89EjLYWseIYSEF>7?Tsy5Cx z&=z4s+mwfOmnVGD4J)Td*}6c(?DqrEdz8Slo^V~bL(mDpF709 zvq2@}%U9&YAZOYF-TpuSLMxgb;zZ1NnXyA;ezkQGYEOrF*q4M^hWa$UzwX1_G(BnA zkN)3d{k=o{z0m&^9m;{HjmF+5By&Uft`6}rVKcZ6u?m<FUqqy6D^5qp6V)uPy?^I0;pv(-M!Oy;wg!+e%( zz0Z=R^Bt_z`Yf|FK8scDJGhSXS!P7|EVG&KVCmakZPL-MHeZDA-~$a^Z9UELjTb#=GvcItPH$x6yj%49W=s|IO~21v&lSgm@ZInEi*0Xd0SgS*RKJ1eO;(MnWKKksNr&l`&IV3drhjx|E$GnECJpFN0j zaU0Y_P#I7MQ65e}J%;vrH_rOdUQ7MM9HhmN+*cvjC0#Y`YzVJW`fOOU(buf~wm;^I zXz5?MD4y{}CQ{xhTo=W1->Pp}eE2KT){DS&HwgWK%ACLH(Ye$5-D)0;d<4#h|KI z%zKs30x^03P#9bDl7UJ4mJ&#MrE1ToL>cu6+X6shR03%ZMnj zv4Z5_rp%h@=@Sn&>RL>uL3SZ~>Y{kX%R8H_qp;4$>6v?z)r>Jy-6JbW0Zg5h?MDvj{bFxXywepdyc)-l+*uRb&g?JkK`Wkr%YnXD1 zAQniG*SsWYF3i<`AGMSkSHxbpR(vGwj`~O%n8HnAiRWEYAZ44=jkn&2l1C%EU;7vI z&4L}5i{dt~&dE*s=?6A$T`R5joSgYr*Cgw$RyOJ;cgw$UISo6L7a_BnCEnFaU$iI` zmxYiZ7E!16yhJI_b5rh|dCtW~O?9(CBy;?OU+*GiBATaJ?~kMSummc3w|aGTRI2JM z{ZKY0ML!F9!jRgXO5eBzcP2iPDx!~pmzv?%~jbb z6?U_*ZfAYls)v+J>Jk4gx_#Uf+H-5L-ZwaRrg$c}_a<#AJ=zcJkSCokXMg*r&coY( z-&DSXke)G@cL~KhjA}0X%6ITX69kpAd~>q(XEEQOupJ}9=?R+>ZKd+uot}}5W*h$8 z|BJkL538!$`p4H=`w9Xgcmcs&>@5o7WdkajS_rrlsqoUp?i0Sk7f^E}nAb`{ z4JAv(3hi_f&68+`9rL`MQ|Eg?t%I4Tt#na1)`GQRFRuIh8FOzCJ)QUc@B93o=g0F* z_8eo5IoFtD-fv_0z0GeMDv_njNrz9VQ@7GO`5`9z`)j%Ag|*z+`L(3```+4e8Xsd) zYq@4EX7@LgSuUEXq|{P998mXAwZ79=R+QbX(Aic^7A|inqg<0wqp`o~up?Ka&^ms> zxiVjFG*wu$Hiw)DRHQB(<2)VK2Yq_WxyDtBaTiu7+cUo~UX!ljYZV z@G#0f&f0sX$K#7?Q7?V&F}-B1(%SB?irn~kwP;h6QHZN35v`N0QPQo_ce_GsMjnH@ zAZQTwmCO>JP;Pg-CcCvbv2(iy)GVmdL<{v=bFfw8(8NZ-Zp9#cHFpl>mG!iSU*}&Q1r7W> zEFK1wM?i1CZZ~>>oo-iK4@r^d^fV4YU#J$EoX^#Qw zxm~;68fkI$fO$B-M5v$O2}^>UUv-DDdG|>-2kXQhJFVC^#~8E$&h7fJ#-5GY$fiU# zC$Vq(GW$rUtZ<#drgKMV*Dg$-)EJz+IRpKagOA^k?K6*y622|P`HS9BiXQ$9r@L@k zNyN+%BWK@#`_3|&$J;pblI*k$%ec>L>Qtvi<9u238Gb!yUw^5g*)TWC4h`Q!`ACUQ z0S<-I9vV_wfgOd~%0zy$HaT$ofg^IAXQe|DtuYUlY9b z7!nc^%q5!r5X;wLHya&$(f6D-Yw0v{1$G*cM)Fz_Un$y@v}sXt*dR|jWEF}mNNOeB zCc90AjZQ8?FYU#;Tx{8ITZHpy-Q_dSl(YM;4nye1x>_>7>sf=3*FzquDmT%)a1 z3khCOxQHT_vo+1s2d+imZfr7Ol}`3!ZS4FbS``LV&Q|L7!m2{MvaFf9_l_cJ{0<4`s?cEUVQ z`*;ZL8s_5K`+!NA$1^uC_%zy=+c-+8J6^#;${rM*hyIRAkUB|91?nmZd^pQ-nlFuTM!^Ajx74T*`d z66eB2I!m%ym)Xu&{oX2q-(c4@_Is%fs~&urkKhlfimz)KZn%VHm(9^hQ-F~=e5tCO#7W1^_>FCpc2!#*TCA$P-?o_L>98BS`L=1&6WL@7 z{O}w-)BYc#_v}?hf(B)P?|j)tYxbU^wbofy-s%~Z?jO#N8;G{5-xF||#=dRMb}1Ly zUQNhhv+SwkV_@%IgVb?>?g%B>F85YsQvT*0_`_T8SMn{Yktnx7nm4uXXF@hYv9=+>)MG0>X+KLfI9=txG zGH4fY3*D|4+_Y&Oi_#{C>>gyhh~367t5S9c!|s}-2-grL#CF(h7#^{(9Xe-(qN3LBjbE18ypP5ecfjJW5b`5q5^1YurLo->N zb0GtMUokWbMtze}OW&z(<1k4=(;UQt4K=U>Vv zP6t6&zMm?g-{zO+CsdwDO>PuS)QbqR`;_vyGxYTsp`~LTzki`>mZz2S+%mWaw)5PO zT|C#ko9DhR<*KC~S7hv1IE{RQr!Pk3%R=uRTs^#;#nyot9uaA`>A3Vwfu z8?=Y#M#2pP?qZ22PB+pT58R*~9+=W0mkiu`xN^8tZ}D8=-kaf(`|(Z0uZBAa_jU!( z9fkXExJz&p|2la36>0aTcLU#i?_J;!z6@#R!yN-W;-i~1y|g31%bWwqE8J1IX1Iy( z@Z55^_u;O?b;A+;+1vR32l5_!8;sRdG1NLpW!C| z9(n(O=l=Ew@c1FZ4)fgWh`VwpXp#2wfIp~0-jCqhM^P>a`|yv5i(lO_o-@PEf?EW) z6z;#^Ho_@zZny!Uod|w<^ZGyi4uX8v!S&McALBh0+^=xIJC5?LhJ4^^;I6}6Ie~IL z$#dzAJA9w)*wjHIKQGTXp5FL?&y%pm;emCxz?|GvW5D{jw@#;HUm{69R!nue9(DR~ zu_%o>_=|F~c~ChYpCnfnqxGQ<_txpXpH$>!q8;rH8HARz>yv+$3Y>1Ez$Lsca4&8W zxa1P(I>}3@dB zE@U@r)$!e?{06`Ym2ae;LtBmM){jqW!6=@e1wIlgOBhz{HUhi2*j#WmpW5|ntX&W3 z_67FdVneg9(a`LpMZUy%^c~a>yn=o}*G)N%dz@kvu^3%lf;{NN;ubej#{;IYt^dlnm@1qaX{w2g0bPGZEdKby! zzlpBk;esH+&qKHJQo&8SRM4%&H$OU=P&tQj^&+4T`nbB2ag_sH#YuiL7jfgrux*08 zhlM9p&PYva)SzE`1mUG8x2u}HW>~)Voj0#hlarNqtXVezKHs@D?=%YoD)Q1B-zRwN zlO3BoNy?CMN?^n&CRbe>NhvTQIVFP0yt{RwH1QxwcwE=N*B+1j(f@b(Hfw!J%HOLg zTeXwwXHzQYFO{ckgbgP_PCYpwt#HT7bQ1qYZ!M`sE&1idf0m@qE6Ju?BsrZ)atq_b+S)70O^nCI zeen8u@uQU;@LF6TUygytTioR-w$Lm%VNCwGJgi+TYHQA7&m?L8+!|<6K~-({D0syfXUX+ zE89;X+r$(7OUct0C42iKSBD^5PEdPHsJz=-vu^-5`b4^{^EuYp-rn1*4s~SZ1x6$= zzAK&P{7i2TKqVfWd^NAP2lzi7RJOWFU(Egq-xf|JRK~D2_NNX3EwiIAp)x9UKYD@_ z_=-}^p+|{K%>sOcg^yp$0~3*20nEV;4U7kjT1&l7cxnSMdpoqid{d|aCM4CI?{>Y> z!JC57EB~Kr%0UoX_G=vpm4op1fKu3iZ+uprP#M5DCk8IXQMqt zqdiOjoP&BFyG`KU1nv>k|M%|*z|3V&A-`_{W-eS!#;%*=RqwcU5xDo@*26v5FZ_0V zLghim%XIMaA~<_DHM79&n$+PpehY5d_`u=~#xu63r-UX{zLh#0p^*qRT%;W**jtp1 z-f%;+!KW;BsOlq9kAb_rkjV~$EpC_JEinw<7)aZPdf6?hK|*RuLgl#-pJpE)oVvCP zld7A;2Fi7QD52=W-Y@BmMfV&}Ih>+x9_3S}3SybcTY`iLiDLRqa=R|J-!t2YxuRSr z$N|-Z$A{Jq8?UJi9-kx|3PT!Zi7pypTPaoZyD6Ds*_ z8TrDtefgSgSMs&nA_{cd(omnCY8T|Uk012%HALm_cE@OI6Dnt?(hk}~?Nr;3!)|sn zcC7sd-YX@wY_MyajG9ODJap3;U9y+X51a);$}inQ6US&`y)=QK5#*)EsYd%&RpfN1^_qb_`kRKJG?EvM-}9R;|Y~vtRA{l zYLyf1)SjqS{)*73<6O;@*97i7Tsg*rd6?^*M>{x*vEmfQf}hY%e#ZXbpMkp$cqibG z0l$m(G8=7Y8sg*CPJOnuN+H zS-w{S`lyB^{1{@ss8TQX2z<|}36&40UWFubKv4nuhZubppf>^C&!EQu?Wkch7JWkH ze6Qpe0K18$c`s6$$I_%4G+Q<2UuEmCR5r7i3A&e%mc-JU0_ZtFDGZtj$W}uoO0%^@ zMjr{>6E)ja!JdWrgfXg&*~GpxHNCMOZ60@hRoth`4Dy}AW|9G_QC5X>#z_n^0MZK! zjj;^kkULANQRamnSBG0WepXA|dUO5{_*Qu6fg@La6Dp%qdt5i%T9#fy^v;lPkb!QrWYf$D>fqMXTAsM(*)Qz7| zr{M)5vF!Ym1wDk)^271g&$!x~1JSzdj!VtCuEgYBGAU9^CV!5YHUj6T+Jx zW+^Q5#6b^3s{p}-mpqtX21`AzC){^HZaZJe#0()FGI-FvAHI9xTj0J5-#zf%<2J2K zsGJAi9M2b4X04=jV3XHGUrt2Got`hOYUm5$%?Xv$5Hj8qXI0j!-Z%n6;t?XU5S)11 zO{*JNsDKooF{k5HGof-KC~D zl|t<-{>xb}_r|y3`ymK*P$)~?w5FjiG@;UF4n$~OU&&uXKvm8f~iw3=Xb z0A^R7RH(fj@}@GHrP7GJJm%epNT@u(WDp7&EbPPWWw?RB&F#az$#6R0?&`ypFeceO!iG(G`sSYONF;ov+_5yu*+Shl?|*s&xcUEp>oMASjW=+ zJJL0JWlrsgYQfnq8fm(VdPl)kjPe91m6N~4!S7hCLs;?8YPnj}%Ll#%KG?VNpJgfR zLJH?jey@JAje3g8*@Z1%7WGdrRr2JBW`0JTsrR_-U0TczLkIf69`{dmynGa~?R~L- z|G&h}V6puXJDA1Zj@WbiV!!&o#7^pqJ($J*9b)_S#eVjGiEX|u_JfFh0rzh``A+{| zVry@UozS<}5zZv(?BwO~eYg;YYXr{RS3Zz_-V*Fjm4|p%S7D(&u8W`uI*IiZ+J+PD z;bZjUcC@31;rh3eHxd3J+(ERR({R;jX9;Lm)8XHRHk64m{tb)?b1`R>(YAWau>UvT zNX45~eDiI5v;IUv<#x=LdR%3I>Q0ovPkYuhqQBlryI-%T2BD|zacy8wLgf}VUqtzL zYEY++uf2-ez5%^mUZ6&z0;e$Sm*?h-y>FiWI&ip^`J*4azS&sE^=EGSR2=CHq%SPZeO3x5rh} zv2Ru8Do+Z5j)s+7NyO@_4CYJrtn%$EtLEs0ojmHBif`!Ks8 zoW5kcDh6IhM1>-`oMe55m^N1)&Z<3z~BH2cf?I1HZdak3U15t;g6f8}*pR zkqE@AM7&?%P)o3HLf_<>6c0f*GduQS_k{TL$QUwUQtdBA-n0*tQ5`gLawRk;;Y&;_ z_dtp~q!`{2vFhqdPYMB!EJ(3es(hb3g+6&|`sAtYlc%mvp87s{k_>z0NfNv%Pm<2 zf#&MI?dFwN3uqS3VHO^oIv=U@xZGGvPWAFZ=K}$tZ0%d0`Y~Q_fMzuI0B*0#KcZec zQP0PtzPF;UAA~-8A=*S=Pw{M+_N|nPyk|^d!dod>kj9FXH<12WbvxdaG+>uJz(bMm zr9i*CB4sNmJ_3cGqoJUWqF}iv4b=M;DX)N{0uO0wG_2~Q zSY`91ftllq6q>CUf+EDxu)2?8wU=TwQBY5u3yR^6td~JC;TcwosRv#PY`CL=VV5&3 z&C(xHE7mN*Dkq`Rnu>HVHZ4#&tp9JegB2+@tj`|-ZHjucjBQx2B~(5D>@@Xe8GEn` zfSsV;EMuE#IcRAeX;#@Bnw7B!D*+p#vY8mLHWMpliTYlDmCdR9VW$HtAQxTo}uXS^v)1omHUlXqRxiyaH>759GcnvyGh#$;#?F%oxXgj{gbsOwox zQrL2{p?NsQo)HN9Gs1jC&svhgXl^?c_!I8l^+zvu5U?M*E7l+_N0?w^lJ*Dg9XI+V z3sOlWY5Sz2_JnrhRvRau|1=JL?(3L0e202Ciuz=@B=oyBxGcPtpn0@L9;xYet#w!A z(cbdAUbq0K5@3@t~XM&Rl6;>7_$0_0p|e-;YiJ-4x{GxlcX37J`?%!Rt6LudBVhjq>uE z?}fv?yx!f%>)njk7m)VdjMuvvug3qttF0do#H+LCw|RY{A06@P=;7qhPidbep>i=w zroPA113m!%xgJjsxDfuYdN>oU1?R*6XV7H9e=q!}dlD+s(3e)^qx_MUa_To`QSlsh zEU0&!g&6Pk7@czRrJ!EiOyKqa=g11{!%YLOw8tphHJ1j_N|55l0k;u2+*%Lp#Z3Ti z4R8icFD3?(JjW#XKV&I34=ng_xrZLfC(j9gQK!kTaitvLjp-aPID# zvLoCFz_oVYlpW#T1+EFWUfB_DKX6xo^T>`cZv#``-CuTmKiQT2hU`A;_QX5$;*w z^83kxa5=y|$7CUxs3u|5l(K+Z%47i?Y7*g|1n$vpnxm662=f>)3vZEy&`%Z*{Dv&1 zdu5T{CyO{Q=AP8vS`pn%IhT-IPd$q8$|lJxi%`fS@fKMGLKdkc3-6pWiuIvW!JVeN zZr`vU?tD%AR!D)^{C+^*@eO=!+{HL~X z59Z>7(QfX<`JD~^BWN#AVNA${-;>IAZz?Z$ecbTxrz5Yj(-D+^SLJVnuJ?voyLSCX zsNEa7plg$tkw zDLu&N)P8f9u2(2e!~ zp{o%%sqw6e2QZUfn>5$(To`_=Q9|K5$h`60OH;1;7#UJkbw?hQB_ z`s-1se-}_M^RaH+1$P5=auNFQ+rQJhPC~hPSJ+s;v9H}8tt(6{z8_O1QU4k7p69MHOVr8fs19r6E`+y8f5JmTfz;|}@C|2tWD_7$kz zYzpx$S&>5XLz+Fj*wMSY;Fqqpz#c%b+$#^u1>sVogK*5+1;*)jz_LgUq-WFTB&ur zLOK>)p%WHrvq2qcEHt6g;O$3zI+CuWqmFJt{p&%0Nc$5!;FnSVuI8EZgS6;ZGqds{ z3Wg^)}p_F6BeiJFN0!49rvq+OJ+}-goMsSLy(`d! z%E_$meT!cF-^bC3-m&mY>>hHa!6iI2s0Nn??phh@j$ZA|IyhuEA2+0ANO{<<%}J}B ziw+Ljy&znJ+Y}~zp-QE@$mXhqN-=c|<_8DWq2<0zSKWxze<=s#snx-|qN}OD4&LoH zce{3}Q+MN~lgdv|DIZ?Ol?Lq!DW6)>?OLvCrJyod8P>wyT4_aTI(v1?M+9%H#+&y) zp&hv4(y>;|g8MJH&2VqSjYGdZ0{ylVZAOBlJ3w?F{nf*|5}mY3(pN$+sHsdEu&qg{ zX?{2@JdYcfC|B5*Wt(ICE{B_<@Gg&Dnzbq$TDU0vxBO^fOqHZ_XvgrQd57N^&FFo2 zHPEUIXyK!ZB%xM_3a-=PUi|{832(F$xdHHZx%RoW($uOhSE>6?It^ZMkZ-`&0cBj& zeYLW(i)k=;7Ow{Rfg1c528PuQa11C%`zsZ;>UKxr9Ur$%0}l7feh$3Net)46+J?sC zMOuUjX}#+nQ2r=4pcI-m>P#Eb+qzfqca|L4ous))8e&&9hdb!)rKVQfG{>NSBh=9l znz=z=TCw51R{KMSrXW+8UT6wVZU`}yHf*>Q+7MzaHE;Yr^yg5YH#CkRY4pOMA3b#U ze7tzoAB=+@g>KhSb$<0wyoeia!+ZZg>_BznR~(Qw+&UPqB4j10Sr4tW!MQ`rIT3H} zIcS+>Zw>ufxkclCmKE!u4H#oB$3i7dx%SQEs(Y%q$Pv~^t7iMDYZhoJ8dnn{S)jkj za*Br*#o>5uM)A~Re(8E?hHXm~A4#(1BF0HSVNXJ=B27p?xlX#FL3i?W+nyx(BE5lw zp1PWGh==!SdGuQ9C)Z)<`=polKVct&G)$1rlR&)2^1IJpve@j^15$r-mAUy*T8D?K z1RC$+ZEq&IE^6==d<0&EQVi0aMCp>=Og*%6hDvc&JbN`)n$&d>FKF4zLk|t=+Z;b> zsBJA?ts13b6Bkh??NLYNHYu;j^fG3L`}7emDy|l~M059GXJl_K7Z0s4=7!uE<{1+{ zs;R+dY?xPObmmTzuI9<$i=X_# zk*96kM7hqqQIsAHGZ$uUd^~JvA@0e#-^(47I~9@*Ja%T4CdOF%<_NCob1fgAVcl;% z^WsgJ(yP)z@<=^txY0K)7)CeT(i=BIpRT{e%Oj1l5-!t=*y+&SF;A*F(x~*fp0>YZ z|IvN`T0l*BgX7WTxHSXsf8$O5;66_1Fsds@;1#mw5!>2Eqwt7z81`~VVg`96 zr)hd<*cdx$r3CHdSFL=UHuePKCR5z_qC^RzCdLo28f^n? zoHNm4X3*Z&#Mrsek3?@zjmKs!^QkUe7Exu#%dMZ?yoi@gk`Zr>;-Ylt{Hi?r(R}1iUZ0B>aeTC2&0$p%53A3JuN>Bv9#&H?zG23Gu8ra^L)L3^H7a|H?Idsr%&xE z#JswENQXvQaK~RlsydbCwB(AV<-^O5oDMmlS}odgM^@HTF%Inq7u2r;xgFZ(VjaKZ z)->~UEX^HmSAqL@6{W~WQi{;(Bi>B)bJcF?O?Ly*6_$!2sTS_6I%#hd-es$;Mw1S2s`*`wO0kPGuT#fZxblBx zzMpxr*?srmnn$It@Cy5@fg5VhH2L_Pg?6t~knlUIlzSE<;2w1@{Lfg=s(USd5R5NrixeSaC%?%k-BPGz<$v2BK?EGek&T8>k>&!vmaeDUzCmbPN&*eOP-*$vOZzqaXQ8Qzq`Dh+c#-H-D%wPh1Wx7cHX&*t z#!4slG7{S+A>5CJmwLlrZ{v|KD)m_CXD8j8!+PN7$oE6{I`t#ygz`7LC%%I+_p5hL z@WBgG9q#F)-{Q8+=Q*vJLei@~;Y764{jJxQ*zls>BsD6pwBA?s5yQUGYI~Zr0ugp) z>lln?q-kzz&*`es@C)#7>e*UFd3v;J2lz;?et-GVW_!A^{%f=j@@eXMaCq6G0f#q~ zb|)7}`u=)e=W6IxdaJSpI`&D2pHmsqc1CN!ECly2JGdyn8c|HdI4HtVf25U0=lC4d zPIxK@V-fdNjoz6zRPU6BZo6g@Uh<>8i!?{98nt(1M^V?+*?iLmgQo5ctT2jaYnj%H zCp$K%cRIMSlWXTXxsayy-;Z18U%m;Ypla zV!z2tf3AOSqgjN9>(9ZO z+>&;GE^=?9G*a5*G&XaipuxP(!Y8E9UgOOAFmNU}VU2Uqhcuc(-_fx>sTkMACgnBE znK?POkQ2*No0Rn}Z=|9(27YbJ_EfwuhHrJt5Sd%b$-lQ_lnLS@g4rBx7ItIx%iEbzZ8a7`vtkbDwm+m@Amo>hx)I(E#@A?>|;|TQ^ZLk_a;qUhQQh)i?G7a>e+Hx8^+MGHY zH(Dq2x?UbP_KVrSo*lg{W*TDhQz+($sy{Lw1qc1o+iHCTuDm#+p~2D~6vO1VuZys} zDMotMv4YS2nnHr{0-5H&rCoeqUUqu%+3CA-C?ctk{=g2 z-4PgJlSa;qLC>vKI58V5zbVaJ)CA0GeS!N5_1DnXa(iXKnViaJ&fY%3(*r)N^zQ-t z*M{HsQF?m76vbfWCsWUN`aD^C;A+06yH?;4T)|q0l%u(9zMk&<617-&3!nXamc@OPi7k(TQf|4OPrqHa^2uLr3t&7x z_)A@P~wUqJO!6ZlkiOxdbioRkFnb z-bfNL&>Ba4UFqb;b8?ZL+SQAyUeY_>Ptw$pWe&r4K@Ptu+=Lfv<2P_IN?oplW&%bw zGGZ(>K}Rh6B9GCSW&_0c`DVd(G*1A>N1I9pK2$q7U&$M<57X)7+@%_4t_F1Sn#`DF z`r6Kp75PF$m~Q;MWG5F-m{&WF+DJ3ECL%bI;B_50bK1YwaJS{O3|}Q#P2LckcqDJl z}-Ig~4G;ZjBvp0L>Hp&)RgLSbz zE8c1>hjdDP%AounudRi`8+lYK@PE#eha71iFDA)9?;pG&J96R8}wwE}~eq z#Zymg0L2nUVbhSFjaJvzw5M~*l3q{SUL!_EL{>B#jb$}ulEJAybhodu>8$alO#1hS zKf+#4Z+X)kaJ3wQxg0-JW4%e=zn1;2AN^U-FO?T#23m=)X{_A%uj=MFj1fZRbLjQ1 zD-AAA6i|{wpr?U!niAjdE9M-#A@twCBzoNpB2{N^UgHz4^WV?RQ7N?-76F z<^FwP|D4$SQ4(h%WL3t_Pd=4&4D*UuDQ(_Jl+VK*T;yHgaV|I%Dz7WsygZ(1EksXb z`Hh~4TE)VCX@8!nD2=ZET=eI6W*;TZjTPl<7xjg{(p=D&(vh?R;nL!oVwlGa&GL5+Tm!eIK{qg#!RyoUBB;z<9mBt zpzN#D{Yy@kdrLa8g(x?;bmf8#tDBm$)Nav!YskLqPP};n91i#@;bUUFGNCoV!}{Je zz+Y}lE#sE&_Ai%@Zlk=%rNwuHlVhyf^7pH5mU@3)clX6fcb);SafqX_>TaR$FZH#3 z^q#y8N8U8nSZN{Z_D^_KneObc{-R7%MCoD3?3mNQ_HIcR)ey8x1^WRWduLANJ!dR5 zv(t>x?Rpy;e`C=ef5cr9ua14p&vt$^6>}44sfih1my8j?_wt!r)`Bw_FE{&tMLCa= z{nJw`g@U^l9h&IZUPisB|8={a`03aiOJ8}-th7>hnA)=3(BsTF_G94(zWLK-hM ztncGZI`faN&DevE0^JDbTrb^6jLrviKe|>S)P&H0zR-7AsE&m$M`##A-AZrVoh($( zLZ5&h9nxx_mznOIn)RdWZ_s5=ur(>&DJK8uI@^OBVlSFjTtB)##jP$14~8EWq0l#b z^7Hixt|kce`V#7O5avdI#jmF<*=Qm8#t;R|#t6yLT>Sk@fS*D6&zAe_tR-G*?`-b+0-|a1)GeQ6N zZPW)^mutv66zR3q&m|4Eu)NW_M6@NtCZ6bZHKd~zdaqFUpG?xk?7 zF!ni(u-_MM60O&v^Ha3xtkA*X*23l#?buAkievOATcIoV;@zY>Nlo`d%nzDpweZ}J zwqHm;eAFuFl;r)O)yl!gh31|+k}OTjn}*r7kWvT9QyZHK0fU#Z%HC zm0xqFNoPEqqDNeAVoTldT-+Ve{cNkSb%yLo(w&RR3#*zaWg*r-evXuQ^Hp1sbYl3} zwbLCBQ|uVnI--3xKVL^+%-FhtW7Y4*IKou^bpy0)`ytKD*{(XiNic4F%+MrYr)Z{+ zK^3;*8v_t(;G3bT75s##!d^c(K5iZ?Kox{giUyTGy*cHfaJ^%YDjY@{eghDzA?4`o z&(8Dl!sJ0Q$Lp}Skp7D@%r?DRmlkS^sM6u|#uu~sZ_t{IESz*Zla6Qg zSYVn#3b)-MeNxq6E3fjucdTu9(!e?=^d~z|5`R}XbBxvCm?}luoXU4N%lSn)tBjMl zaj+?2j)CTn&!s!v;&tUZY;=&Vq#Ml*&prz6_g{(HrnSO3^+KTO z*=;Bv>$B0=(OSiH2Fl6_tew(p-+6X9QCjH4guZKL-?iTI-67B`NP32$x4fB$CPNN= z2*tr+}DgfFBn$T6>Nf~gdmhUc|S#P7hm(`s@2 zytX);4|#mC<}+DXvjLmZa(_Jerye6q6u-(9EcgSf zN%v$$rY~$qH7Zk^eNr8nSZ#Bb`^bh(T3kk7SF;PtwK*qF!jqdR%X`Ys%cN+8#~X z9#|S9{c49=bcZdce!zaQ=4q-Su=s|u65d2D)Q? z?9<9=D`}7O>~b3S_`KcW%3wC=oXYnytt1sCUh$3kqNZLQXR&5{QB$$R6jiTkErj{K zSOLt{jBmN{uT4>d*-qu4uc^$*c9EjI$kxc%Qo$ZXEo$8;(TbI`hH4@zE9uA;Uo%C9YVR9#dD$G(-MslAAko41qr zy0e&P(#?5pRa(T?mgS>8~KT*o+5Fr5^l*Zt8owUdj8G8rV=|KYYN z%4aRG3S;o8MGJ}0qlbSQTKNR#%WNAW%LBCt!A%u}JkmDAnfn}_mEk-c@WM8p)ni4u zm&GC6T;Qf7WjcTP5t_(}Hp)af<8~^_=9V6e3XRH`!yL|${jj&`#yxxckqy-sR6A!x zZ5l4ykIZL~4p6X6^~#PjT_eu015YhSU0F%>Cffj8sy>&wSe#Yj#?2^u)| ze9IDW%7D>EH4R`noZmuw2mz;P3~=L=&|)tkox@uPVhqoEfyN?e_uO+FcLqp{2xq*m zJlRa80BabqHS*Y2=;($vV6C0bx)SBHc3O|#3EhOA^%m?$+SBFJi-y~R2MW&I2(z{H z2!4ei|I8)S0)6~SlNz!jmiYFyLnAEfRkV&xo&f#zLOr$m=$@=+M2T!F!j7Ps)?)Wq zkmiCrr4CnVJC!Q!zHhQaU-SF8udw>nYjZi0F;PrM{JmKBtwOoDT~oTDyLtz$R7q=b z#qw^&j3z&wyr=o+v30A#tue z@Z=Alk2mDUZapkVXdU5_0BauDi$twsdV1G$H4e1@yHHOag7};vMrWp zNCt<#Y6@)E*sWADu*EXJmwVFV{L0~U=O>u6#Uiz9n9Txu;kq(d_D>sa>bR~ffKuUL%HGAw~f`L>6%jO(weiZ zADJVq6@`0o?z?!-7>OGl;0QMfo%*C18I`uM)WA5-+@UO2re=micY91NKPAidR?>}2 zL(^ar0NNyRAE#7Psx8%(M%jXq3+&bPoURT=uP6q_R+(*OuyH#Dvw|;hivzYJo5PJ+ zxQX)XB@rib$6Xxmqj>a0bCE5$x0E`!kUJ<9a;wg7;MUx|5$7g!8{&>yjcuSehrf15 zf=7QxbWXH4bpy>gGOs~z`3>cD7e6I@GI96|zCb(SHhsB1&y!?0v<~vcptA!mF`MGanvI8R;tTWQA)`}%Fu$wg|W66@K(1!nnD<-@C zxfZM^QrpUc%aRDv*SFv-+!&#e;^z5O>KrZLD|VhnGDi4RUc;GrtmJcOLfVA6*Pzc8 zy0XQgyT-x7i=9_p2VqAFH%;nb*>OyfnwM+D7!Z|hk-z?SO2nPg*J_#YtIN_&C%XUa zLH*_|N24Tz+}4dc&T;TV4^@xj>H4ZHTWD&L>c|aA6LwO6rrD|8soNQ48^UVC3*GZE zzu@FJ^>fHqtQs_zw7MUJH6c+-MH-WsUT)7VD6ZzzhC=Sr1E}zD_oi;-$Sy=7+I;t` zh1|HWH*lew3c1Cd8@bkvg&fU|gft%apc-6RSd(>W=$wt(oQRtKa+_9?(c(mu%42P? zWWK1uo@O=|`kJ!}1E}>ya;)X~gG+wL&9*nZ+fohf&88wX3u`}Wb5v8a+QuG$%EKiOAH|He7lJm3x`0!d8_GRxX4rrYvr!s>r-)Vq>uMLoSuM*ngO=?| z8cK%d%10;ilra~TYpeCoZy;~eScEER@aNNVmDFuGskt68suhljDOg6}_4WgPK4I5+~ z%Ja=+S>Rgi1(gemhIO9~#l|pP99qPr^QvXgG=_b=nP8fySt2f|^MgIK3mNVF_zUX& zLp+#NhPi+81=Z=rBr=Q>n9qlKXc8Fa^MpX$jzVj;8RU8utxhji>E#HO__0s9psr$Y zY6roq0KdtLRYrMZ55aGO-z|W7Ig-I!0Ap%gCCJ%s3Qq)lKj0p+mj?KLz!nxB+C{Jh z@FWI*)=uywz*89<)=BWxSj?1QKm3Av53qXq1mof!P|XF5S3=!HH5YIS3y))|qyT=5 zg%4%)j{zPR8(c-SJf0gBK1K>O@#dmtrn}qZj zJb}eu1=!Bu(+su)-p9ACEx=m&Dhq!T@Ls^Y zY-Q=~1^g8Y$9p))<}1J#80_Ka0^nM}M!A^Du@ItuAUvGm_%^ihB}KxTTmlJUF&GP|au_~%&oHPrv9NUz=X ze^`1`r+CH^t$g8RF6?;}Pr})?Nh?*TTg9){dTs{hL+`XC;x6Sba?rw?qqZ!pnJeeH^fU94Z59-P7AuX7~Me7&GORudFh6L?ybJ>ZWk%lGBNj* zVK>%~a1H3+Uo3~78T=lDbFqEVQkV}<3LjT%ww0=@MBlMOeUD;niFBM->*o(o(bLcS-dW#3Ld`xVw?_z3?YPlcHZeABA!o#n;jKx)7zUbvrsx|pEa>oI|~TVn!hH^=zZz8b^V`J0D0N@INMs?-7t>H9z0y7oE#yAW7*2!myZ z*FX^n-TvP|)BO)ILftU)T3B8(+i3Kmm3DbfDORYSG09K|F50_9<5=OlVHl6PM2x_Y z-9wPsNVpv+!v*-IUOqh4PV-T7yE4BG;|-sCbgwN0x`PQb2N;+&0%nL8a~Cl4H4cnC zgS?o@z}&AZ117+W83&A0Hy^$0UYjp)?TQ(g&kdXfD@WYZ;%c6sxt4pJU(5aO*FtVY zcOmz;gtgo|e=o$Gz>SthYq1rhiq%Ud>>Bb^7TjpfO9#}&gO`Y!h+;KSSFFA?saSns zNgXRGSS}qh=!FC7BljOrAA@@W&I*?aw*>AfxMv3^w#5t)A`YlFK)Hhrky`k3;D2WD z0d;~N_^e`8%silud#YHSlv%8r;UeH#mK3Xp@jGT|gpJm@h3X>9+^h&_;V)EYSt4wO zY7+ZjXC;3!{uiqOpdXkCNj-&E{w%bW{dcned)WU;u|%KE{zqkyKZE_x$uQY=f`=vX z#p=@d5;Z+=qambbt-8>nG4qj}saX9ED~%s;uXXN<1L~y7#p?W}2h{r_fqy_J@4T#o z^u#GeQ z!_LANakx3HU!+D`7R??~htRm>l*gCxGat{oQ5}Na`l*=tJ=qL8AzHGBY5^^7rrl(D zJ+xH$7@MaWsc-qnvTJtTC65&jd42D%3fqsc`feL186Dqvz8iW?`Mi1RNv3vfNkZ-Z86 z3IzNd;4%j5P5ywNruYmtntTC2iG2^;x<)IZJLdEoe(Eo{^gsTqLau7uTCRPKgAMA7S*#oLVk()oMUj^Mz*5Fn^;3*Bu?Jspy+JUD$_Ir)! ztM&7CKe8!FS1ZIHZQZiQRo8pFovV2a{Tif~T&v!{h>Q5bL?`i4SdmSXmzZI^4Yy3K z77ltzE~txn><=%PCMVUqVWm!oJ~Jdc)ON4D{h~oK=REfchaTd=7e$t^R0jCIkfbTiny)Ljh9q0{ z9{%3gPP_wqzo8=f)r((-ofFk)`3r~8WkEX1ycY->kf zjzN}_F9O!d^RO<2)m6Y30BhvA2#>+ke-wlN%Hn_11uM2Jy*d{EHLM8_ zF!(DL-h$n)MENhwe;>1wdxrU6V*XRie}VZwhF>T9szhJK{Gv)L=tTKYp$03K1A1SC z-w%F1Vd?KLB%Ba27T8o^Pc!W9!f5IAywhpe+uXr#H^{}EpQa5TVfbs9?bT}r&KP0B zu8Z6CxLdU87txH0KY*l0WA(<@P+vdeg?U* z8VR0PDB2>V{kGTBH1e1DZW+{`bMh=uY2=fLWo5CZ7j9sDjEmLD9Iz=28^_YR1G$;Y z;BkO;@{1_1dl)AclR{06f$egJ>-SsZ@` zYuhQz2YybT0WNb{m_cF}T}Kc@0Fms~D_$VDR@MgB8HAy-a%%488$aBToXn zfx$mB`cFZ>oxxWaeGb02g~69tcrL=VpMLPqS?)sm z^-pYx4SW>KH4|am0$V9dTkZXj%gk zLDQK#(=l0`?l>h*b4(Kx95ckpj=RKogfAB@j=RMPj%0D1BS#$Tm?K6xQpM4Zx#B3t zJkbP-AH|XQ|C1Q*NE3%U9uY$vkBUPbPl$sZPl`c~EHTirR19z!=lVIG7JVJhh(^b= zqTcbGsCDFug5w2|bF2{Q^awUcrF(H^NqdN#{H}eVyz3(ERN(EB9&eXMM__*0uB?WHGOikD>?ZaV22&AA*%4FUPXgc*tbJz5t6i zf}GT0w!IRHc{g@Wtv1-N08D!@IG@D+Q9Tz04(@36;Oa%JnitaBi(hU3Qi5A&O5Aw0 zE&@GF?LrYVkb*9e&A8pJ2Rp$NAAlKU@7Qs_O{2%&$yjn(weR)Y?!P@?djrlA=HjF_eD{cQ+5`2IW6@`0r`7yYLyv2C zk3a6^1;EN`e;PslLp$tHSMz4SQmwS1!M|*7)uGgD%0MNmite~w!#(qnFabZZ94org zS(4wOH1xX9;B_pO_{JigEnv3^*~jYG7P^ClX3SfX`LD&+SR|uYRq{I=3}de)k;4-9RN9S77z{YUB{-e3OvMbEm(*K$Ah-F*+5GsWzQa@Y4<)XX~H zasz6~;n-=?z(dq~fAAgMr#+?4fK61beCRv<#OAtmSY|t`UbBofpM{0`IQ;*_GR2(k zT%CDV{oIn+a$(Us>R-io)YF!9=i@KXJD@-2zJoVR#p?EiuMwjdw#SND+;pcl_g_kt zf|@26s|TCySAoG<-OtK4#f0_XId!jq8X2UGn+1EglVM3my`S^IyWBYO1^fU9C6p|3-vStkD;bwwA9E@c*4PBI7Hrj}PJ~75yFA zYu}VK2v%pm#jdbFQH@%HwR(Ytd~4NI`t|05`jfxmT!Zpgp&k-RHfylsT0F^=6Pg#8 z{cYZTavj=s-W2Fo^(n&n>6L6TTN|s9|ABk2p!+B!`#!n;;+JY7r)~XVrI`J&G(leS zz1|cx;$i7$CAP&=$M)3suVb*pn%U#Za2u;b%&%RE$Qfu(Y;ni!Q@PlEsu009s~W!9 zDbSoK47(ZURi}7HmEo?5=T#NI|DtzpV~sUM>X5Aly#J#Yyc)buSciG7xBPnoot)Kd z)7N6ID+*OqMhisVf&W|tEc%7V>gDC%V#go-x43nH{P<M+OD#iCvgmRA6u?p(P-bA?BL z`?+o%Uf)qlv%3PT5?gM>yBvDFhO^>5WTs^Y-bV7Ux|nDJ2JI^oyJ{OOzNX>!bm#s5 zm$f&Ki|R=ChwJnXf;Nh#L8865w4zA^inzoeXe*FJG@2NrNdsyc!H7!|%`$0Z)tDLF zW?ZshFcZu&Lu*VViGf6oW}6EdGYT485I2&U0|)3M4fOB(oNkDjn|t5)^ZwpH>QvQJ zb?Q{rspY9>tF?ApH0>z<;PonxRVL_~X3a%kN#7b9H~*%*ZgRAG9>Aq$jn>1e<5Q_1U2I zO5-D^ZGbf!Bql-N_{{7<3|f4p{G&<>N! zWY;Iro_<|8=+1Gt=30RN<-1MVf;|cLt9u%* zYaiv<9N>I`rNxqbW{y*d^Me_aKMp%S$>04fG*pnx&k(!=9^1-4;@03e zwEtW1wVCQ!3HE5}$PjEa_i z=z*=gB{Ryde)j=>WSz;Xe)q!j?=Imc1}4_6Cii%BaAvguX|jTccnn`2^K2k zC5jSd$>1a(7nJTC$f+EZVzv{NWMHx!eK6T;t{iLUOl7uB;z4MrQVZXZTBru*x^Y1s zdj{@{g?a2H_}d=IW3R)15bA+1@*D z7WTwfLdzek{QJP@6&S(PGkRzoy#~1f_jSXPJjTIIej<-8gdYZfBK*hT=fXb;{|opn z@PC1S<#FU$n#azg--e<8h)(^h>;!Ia==SkwnuY9-iJts>c`EwyESB=@!5*H2u~b;0 zf#&9PzeGT#<4Md1>N6To7O4l8ptV0@M1ex#Sll;uC{LU5QKX%g(q3~c>`MzYv>8*8 z@~M>aC&%2r6nd-F_yE!-qfg`cTt{+Wn$ln~&Ou5k-dbO4y#wB6oC)|&!0ojOcfd=H z@qmY-q$RcVZ>WT6DQqX5r3o8yO-8Yf6F@Wjm1C0I4ywMeibfKBkj zN{!uF?wO_eLp=M(GV&mzm&c~=XYAZ-j5U=qwhHn4;P#{= zEiI2d2Urx`O~ltAeh@DBb;j;S{Js?!Q*cZ1?w{Za@Ln!lYPDDlcRF4+(t^0lQZ4e9v$#KHpr%^f zij)$#*WgOwzKh51v|NRJZ5C##79A*aXLYr>TU#xb!@aME_6zEvfUAkG#@VSFT(N4L zrmDpoh+nl;gI`oFidv!%lSBr|nJTO`;yAh9*({uDm$>1O7?>c%tEBh@#C2+m(}a8A zn}s71Ob3qa37HPCet^A)bM|Q&8wq@Az8SEgfbGX#czQn0vN8=~dy!*-oN_FiuS0x0 zQWre@gBU7(=M|~UP<-bHDR*8w8<~NVb!qfj(FG}=X5smE#YFA+Hek}FQjWDKFCQG; zW?_}|Zaz4=7p3@eDSi=gGtTYJ!cr-2o)`yth9GOL^K>SCe?Fj%IQX~+27OEwK8uE`ACJv>To$2dqQ?t}vS^Pu~N z-;<1-*ZrbjlW=2C=}H=HiESAxA9wCvNn_(agqd+~x()p_2{f0CbezQ?E6^-hBnr%i zSOaA6Nxtg8Aj@E~`7khyix1<#XA)+pAd$SD6@!a293v;NO<|?B+=|h;9%kZ_^=9Gg>g-6>kbpc3^~<>;vrz+i~#X=eB9k(k7ua9hy1q z#W}9@acJWu!Io~Rlz|f08q;t+zEz01e4S1@38Z-o8pX+;IIOzA##s;D2u|bnd1)QS zZP&Ro6^zO4{fzaQ$HmX|i_`X|`E)}>Nd2cu^X?-7k`tguHG@V#YsC%Fqq?Lyd{Bya z#hCokjXmxbzeHZMu5XqeLM~Z-vdfi_`^ElVmENm2f6rdj*By*XY z9zW`u@R%^tmM>n(_zZ2!1U({EqK|)q9G@Al3CRL*v9%fN%GNcmD_g%)yb^<39wM); z-(A(X-V40jZ0Tn*u1{ZYT-UHx2`OrvhGOUpGg_Mu%Z4*r&8hh$RbF7Wmx!-1!!sPH zui#5takD++Ko_Z&W1iXGdd8Mvgl3ddU-OJiU-O&^Bgm0+K)foKx%B$|@VOW+S{9{= z{H2zS;zr{H+G?JcFW!rqTXJ-KZJi9~+XAs}Z8#tDQ@(gULxEi~IypLp{h8az@t3+P z62M(oJXBBcdy?;w;7a~3Z$*O5mRLWxZ94w+tyc6iT0gZW3MU+NIO@t3OBMetACmydJ3ym|Kv5lK%e3kcMv-K5S)>164!UoZFVino9E6 ze)zd?X?w6=f1JmbV9y==ZXTn5UW&a}X4N^FT?U))*P(61s+Ml{$>SAP^iS$fa)*qw zQjw}`Elp$Q7oZiJinJRobVAfyAY%Y$gfqd7fEx)n3U0K;v{q}%SPN^NmI0Bwt1{L` zu4JQhnZLMOyNSlpn0wk}+QfJ*<4nXqQ0mnfyJkoU=+`x_)m#6%_HMrWB8{!l$)o*a zuFO-BpwE~rjW|>C2>*!tshdXJJ@w@{=NiGKbYoAnrCAQoZTkcx@L-E8jUA@Z_X$Sd z))t*K-gGHCj5l3M7{*%|q)8PB6HT+p21sDbfMjioY`ZquH)7@6 zNv7In4^AQp)o#dH--(e`U24f=yZ(i9BcI1EqK#B9!ZB_* z3o^gTBpKWxx6`s`ILk3Qxwdk9TDDurr2S`^5xay6)+uM;%xpk!FOkM&PJFX)9lg0} zr6fb1I1MnQe|z`vXa1r7;uLW?x2S z7CDkq;z2=}lahoHl9ZB^EZY%j_2K{B?szXa`Z(>d5@1F4#N=-G7RV4Va~80>Vg)Ci zZ>E87oKZVHh2;F`j0-9VPB}6@2)xxtYp0|{!veXEQR-xC9N?@=h7yud!cJ9^mCiXb z{(bPLXZRtUbk33SkdZV`^24H~bB>JP-ID`(2YT;-bk33SgS}=y#3G$@aC>@>3o;IL z78-9fN~OQlLsAesRV9E7lOR8KrB5K5HM8&)x>?0{mU@w++l^U&Aeg+Xz@N z+`&-ffwLEE20f)l3|*+OKI7CR$v_J`azTyRptpD9_CC@Cy8x?iz}A2Vv#OBE`D_K| z5|8m#1f7RK+b!W^w-Q<;$f2Y)R(XYX;=uGKVVB!zSGMTokv29;W6DaqCrvb*g+9s) z$uIiXj%utZTSA*(*&GjrSUP5CgvQ<6&-1;PLbl`^IvFc7)kNo19u)8{O z2RraJ7XQr#&JfZma|e%|eXGBE_AOu^7w78$X_e9wWQizaT!q?nE(2vGZ+KW#{4ABz z_1ki`+)+-@@0OErtG|rOT7$AusXiP3r?Qea{#vL1y{u@Ibsx&w@;{dK&HwANxL7Uh zPc8rZSlIRh=g2;WcExSnHrY1CHs!W%_g}knKIIHFKLV{pwRyjLjwGYQ0k_d3exO_b z>F~bU;xH&d`ND11w_TM(B^e3Y_d(NyjKolkh;M=K4#DWK@voiFp?|(G7}ibYED%ox zQ{$;*3OrSete$EZ?e!<)^4To7_0Y$$fhH3i?Hfbi--~e^i!qBa)g6`3DzM+v_{upl z%=*ga!MJ_+5!sG}AgktlLhC|=#-B-OO@%+ER^v)&wILK<^H6Jh!j1%eZMf^(%|uUM z%}>R68vyOd)%+}kLQOF?Ie4lL%LT>2bCGu0)JR)@q$NwaGzjfN=+9Dqf>Hh-L=9)b z`W9^EI?1mxhOePGGcJ~V$a^}h#_-%g)w0q^r^-s6Wb)q~u+|C;CeoFSxyVB^M97?%r2uoJ9Xyk79Wzhl}%rw;v z!w^7%0QnIsu}h-C&`uwcJP=Y?9TN30q+ToS)B{prv3rL$MSBNk*zJC?OH&DJwGu7! zwLV%*7S@F|aF>qdv)AFC`6!>w`#hheUIXtFVX7-p4!AKn&|nU=s%!6py-6)}MUPqn zp}CuLEbP;PDQCs%RI)Ebb`|v2^4X;27%llSzb^-`g5bdS*Yt)QYkYa)Te%Pl5pJM; zrM?^%JU9WOef=suL!IQb@*a+h4>J3O}DH(?DR$sxuEOE#c}4)^RTaDV}SwY z0p~Y>_s_EubKrS7bP)s0(DT!CdWA~|?KKW`N~RA2ukq@PtqFr`-)i5Krk>1=k)OXG zxE4vC#kU55kEe!2tpUEGHq{TOv=Z@Id|6?gTB%4;B!%0@@zd%Ep9A#RhNHMw8V)vj ztxD?<*vt)treu@w@3xHMVTqBeRycO6reo zKS^g)q=0^*LS5JhduAMT?1tKR&$dX`AExqCeu8fAMAf(!SdH`bH_6T^AYG=k{;dD& z>RZCWHcL9`J87lZTWvXrJzc{_O|lMv<*+#DJT(c|Q3D6dv|bZ*0;B{cRUP7D<6B!| z-bnblb`o|<2fG)o2o#t(vF0dKS#CkL|D?D?#mq^de&;#ZC@O2DRMr=LWwo~McAgWL z6lQ`;=wL@hMaebcM60HGvs{-8cY!JS7wiS6+q&g`+ z0P%My9?KbX9N{_4WyvX9y=bKk5)E=kp5wSfo+~pY<|<5ixg@zr+V)Dn-J^8$`)WA! z%Uq@XD|@8qzU0zNFlxf=^|aNtV1Af50)tx&UR9H723^F=*++!a3jn(p+BFFTn61O7AWC2O(hZ zZ_CxMW0F4CZ%ckwD*3sZDc0%!a!>V@+i-C%FGsnP?kKnXzm;qG-Exzqa#K*Q*QbC`InW2}QxyzaH#6rPL{U%fcW znv-d9_D>lA?%`I;?%7|7)vyJmh*gbm#VFmWh5QV6$jJr(=~>`9P=vt4@%8id`L zCn_D*kI!2%M^}`s)`1oV9I>@*H7uE@)4ZYh-=+9s@R>P&DkQ8T)0k^C+8|=xA{q~< zB@?0NZIZuBH0I(Qwrd>!_(fBS>Tg!qhoBV5T|t_29RJ!yg$Z^_AmKu>q>GAu%DsCN z#@2=bA5uV)Mq%>hEB;NsiT->;YUyp@H}BHh&t7DvQ{vXBe~S93!!3$?18OvLs+;9O z7h4#MZw_KItojVAKVdbj>fMD4-(C3by9=3uPEsYy_^5;bN*6wZz7bB@`{uOHoj zeR#t&zIEp>75gwpS-_C@w!m%(aM{-ldlq9w=lH*L`DhMz=e-UL$($x%A8C*87|0PN z6+CO(S@EJJ8UHrl;(ChyFfSN*NM16B^@h#08g{o^OPA4@ad<7(zhIS&c2BsisSGmJHEd2gAkHj30K3r^ zNH0qGLV1N&%+;OA$cc)LGsfQ$fx+>ftH1U>#dRLUN;9UCD`;q z1J$&tg`Tg$>H#xE@)gh-#`+gEjyGJS`hV4KL<7(0Z3d@3q3AYV+ z?!J`|MQUn41nv?a8Fs<6Dv_7TP0K@FSAqKy^l*FmlPcH0Bl}Sd)Jo2@H$izG`Pv-F z2O7ZgsrU-?8P_xk_qiu0#o2mevF_NU4SlhD-4l|IBKFSeCSi;_?%A@{;eX)9ay4>e z__L-}dsK>Z9A-_Rbv)kz2_pv^gH}v->!tm26v6}Cxv(%mDNVw7KimMg+zm@Bez?I8 zj{w}=K|NwNd~(>hYP(W#j&?$>M(wnH%8ZeauNsLx^h3A@;2wp05AG8<64N#{cZ7GL&NH~#d40MG~db&Ps9I)p4N-{NL*owzGlZEx}3hMOne@pd_AS=t^LO4 zSAha*I4;h?2@L!|=wIKLvpD^reJrFzA|YY4m1!!&OpjkN>}^~v+x}LzqC~ZwzD-~K zKpd;D%aZTtw>>=j1JTTawlB_>l?QL9vPqk~|MtBr1O7Y!`5)42w})qiY)2cmr>`2c zeX+gXuHLTMA?N=N3FZ=fLu(pyWfbJ}ToX@%YXEyXSe4?Ud~@o9OWGC|po8WG7m$Sg z=N`W6JoP{J0ZUMo%*a79RZ$Xdi(DCs-jVrZuGQznh?0K`&qB+0Nz~V{RA=H@;vbS5 zSD2nE%MLPd9=XXf^#mj^X-A9X-@kz3TpxdV*g z09np&+6(&IWXygeX8$157MCRjK>&zsYAA8zOtEvyxspD+=a~Z3K zs_y=warNHJ5+*xWmsty&^7WZ@_}(IQ$hpR+_ptuwEY?_z__x|E&I!_t-`M`eA?#B) zO=%1qp0q-(yX0EkEG%lH9=Yo>+v!?8Hfd}!GkM(E&^%{`@%+DjqO~cwQ&TzEG}WbO z=~6{u9Xi-Tt5ICLu9E!tc8zn0X&lP*x>={$x<8xa8*WG1>oVuBJSol`$xSH`6GomD zce8S*e8WCi@-X79Q<#e(z&dt=-hUgm*KNQVeHHT2)lRxDn9T zTnoDZkX)&eW5*lu_;DLJh1@x4xm*>JcstI)aVkYiD0fvz;OSIMF&$!4d9l(Li$H7w zU+s_S5gX4JgNsv;kzwnXLef8hDRS5$A^D#G$o~X@?$YJ{cb88>q38~J?HBzD*fWC) zm;>ivsw)qAn|TJaziqG1j9*od5OU_a{T}XUSRyPIauf5Qwe!im<2IZ9ZQJpP$8-i> z&ZXIS*zg+6_+xl8N|)Iv9RC<0PU~cuSB2rw>mm4gz&|E9LRW>*3Muc(M&SbqrdxRx zwnEl{R&Wo$=%T`U6#o=h!Tgh=9kXkPc&{FI_qRiO%czLChd+BkWhHwK2J5}Nvt9-I zo^-BJS*$M}^FfEzi`T^?!>w|Auyt5wi1kOT^`RI&W82~nA59nm33X;9Sd%cg&75NZ z71kH)-)2Wl=8vh{$`O{*dARpjJ_3=_~3NIXqJGKpdPI4N`%&iq_Yd$QAEtBXZj6ajB zwoOBPNxK7Mh4J6yPR-;-Im9@dL!4|&v`t;9fK^Cc=Fjdwbdvq3k1#8!MWq78PGgNZ zcu|H)$s4x3d z-U1c;trR(&0#3Oj&Q4>k(nGb5=U3-~Bgv*_zUD7uo{%rDX3=OD-=?e{ES~PeLvwV!_a7zQ8ddrsN6Yvd|S4ExeRq<|{);`Z3 z@Sgnmz|93o;f{io={aQ?`QQyMb~I*WWWBKlH!+}J;&4W1{0_&9kk59o6L^Z^m!PFTuPTiV>bR75(=lo9DXvx{TEVC+dU?d_%_45wC%pXD(m`b&MUr+I1ze zfYDq!2mb*4Rc9I7jl5H#!ZsUz$mjyL8EzZii$Z)ToPclx$}ETf5L_u)C2Vj>R_wdw+`j9AzBik;B9mJ*3 zN15#5_U%~BjEB!cCy_hIj8E`y)eUeZ+83*W&Ow%X-mEavhCL~2qizaW!Z}e3jjE1X z=zkrgH=f}4*D>>TSp1U1%F|5bc?^;ZGyQoK{7AGr$uNUwc&u5vHY#gw*WRlxfKvxYV$tB=P*r_Q^?;rCs9(&|H_+My@2uc+l}) zBANIhCW{G_CX-P&(^3JwghA{7Ra(tfbCjZz-}fNu-YXBY##hw4`ZAm?;be96)eseej6|xqFUS(c7tn9&=FYE z3R{^|VbfwiAc)JE=%=4|ftn3{R*rPC$qEed{Gnw68L*qehF0KzQfM9I5PW4mjWSu) zXa2q6nG`m9xb2w~rM;9V*o5qoJ%uQi>>rCq>u9tCJhN5LAaF+h9zHko0npTBTT|U`*Rgkxm zj`@pvk`U*{4!W=qb8;6Cy=bSpT#i}%ZL7LmVVJ~!e4zx8xk*7Tb@@X{0j`ITZz&&O zmRnWlA4pP{bIo}iwYU-jA<*fU>RF6V790p3Os32Gj;ROS){^68hsL`3f{- zN+JVlWoC7)y8ON*1>RrXs;QKl8g0Mk-UclcSciaR2{mp@q&!Po^_7iw1uROa{v)TZ zb}#H2O&qj0VGweUm2z8KsV!zH9N%h2c$5^Lf-eoi`)uSbccFJ8zvwdRjgh-E6&kH@ zufdhV9Z1a=+pwR<@W+1&OR+#M)Xa2}#CfkRr!Mydk?ys_Kbhyn{qJN$O(U%otm;GX zoQ}ekV@;{Tzn*bqGy5CDJ8u>9mpu7fb{lELq< zafaL>@2i&NefwjU{M6;B43==hUWstn)wBms3HA$kGRekY#0UNUq z^8@bZUy9j;#|Vd|5$&_^=5eoHigOfXG)ip`)tjy3f#G}I7agT#X0&7@ zxa3o6NB<^enh~-dd^S?XOLD$S!)xFiGT5(+#d>0rU=G7b@D15c27SpIX~l3DrqK!l z$Wz_LetCKDd;A!4uf)8^{fN{*KKolYg)-jPKl944R=_>>P63+*_dUW*2MbsW{K4-Q zu&@IKEb1++A8;*j0dE(uD@Zs0tC*!$5>HzRJ$ECt98^gj_t)TKlb!=C!a+Ba^c-#q zPghVrDpzKeB{93l{n6*FY6|+&IbNh{GIG^Zx`VF5VChPMlue z?hf&QhmJ9PQ!t_jM&j;Ctmlq*Y~a+Cj7l2>3w*G7SmM(*FhPoAK(fbO*(0~wDqWBq zG2-rw5?BE)O^dJ8XOh(vk9#gSwKoKhn`VPgb|Cbt&Fq&C3)mv`(NT>32ago6C8#Tn zx;Q?eZa|VglirN(*`Jx_G`(bUy6o+O3$je6XI%FEneBoVI7L}nnH_Zojc}T(-Tejn z^M-KRO?)jXlgg@g8m&P|@z5_hejA)(SaFf_{d*`BkmPljk<~q^hCO~6`x`>}$Fvq3 zstQ={Nz98+3s?r~SnM+2R)QLy7yKxQnny=Px;YqVwA6$Vq9!c?}& zY+VJLccIMdeh@pV-d5fE9VAjR@inh|10eDI3B*@O@x@a7GsH6xhmI3?D)G24EA2P) z_zBG8C!~2SlWZ0oa4boZW8QzJn#NDATl~=CBpG7Wh(*`YY^s1<{3Ft=WBfeKvUvU# z$HRTIDZWF=#X{Df@h6e?Qthvj{_!0OZW1K@8GjThIha$QsVs(>;8W0^8vwcZ6%s7g zFeCYXX;yhL_ehTaGu0%+^kkCbXM8(gB*$N^nrxVoJVk;v1Ll+CuQtRQVrB8z3DA!seEf!l)zRGF|49L(|4;v(#=ykSa9+kZ zrE%~g{4k^+fWPJ_@Pw}l*xShW1?7WpK;BD$eSM;UDZhkYjkN=A;ui(j^KS?nKgyXs z3FqE8jHIVP6-agBL>Z&BDRH(^CabWLP3GUb#7Xzr=&jR_-TWSF3fvXAUf%i*+{NXi zClGJFQ5fC9Mvb&_2HY|T`ygS-Sm_{_30WPnBEe-dz-p#XgJE#e5VW{ggTdpz+_k%M zpnp7=p=b0tETh1pLnq->BqQ`WEThoM+9KgpH-w=btWVbM)f(W}a994TfR&>!sxaS{ zB7Ps-HaMDl#ZLJ~6D$DU5PBe&Xj;=NgXnS32Hl7-pBq98WYXzf>YL^xzP?eQZ_c(; z3m4Xm#~v5odOz-)=Ss#)dmR2dpN;u4yVl${mglzZT5})CIPp&+WlHUc-=riP4M>@P zJLgkMIXTrhJOkE8o-ahpHW-DID`#wFCk3*Rf^Mt1DvVF zY1A9bKuOpw^~;m(kO>6j@%G+cdj!2kR0NXc|0pLIy!qW&`R;F5OH$dbF~eL6TY>E> zn;AVhq5bGnB&#jN400_(d|dk}lpF6HXE_Co)B=d9eS^&gnQLfTuj3$j-5wKXrCa4- zYuC$0%VC{|Vz#t6{4+im+UvSAVzvI8R7H#~QmoCHJ-6+2Mzy#s)(%N#D`< zSQ%nDvDM=GSduNJ_Wi2&ojsW}Simx+w zT5H8>t$IiCEQPf~99WvS< zZbHY|+=RI`*TW`>11n&AUmTeF*34P6Of$pJoNU%;aQ8?+V6&1-um&~z#{V~qhuaUYooBB?GmN#!!0L9wM*S>WfoE9>fgfk*Td(cWYNK6gbM@r zeA}#)v2BC)1UC0$+%}>)_lw$oNDZq4nrg=H_n5YT;~it#L~==kCAp*_l3dc=EWl5* zv`c%n02|Y0STh(`s>b~uWHpJ6c%)My)T;x}8MrvCSUfit`uMNjU@EVBxfgZ{CIpXz zjZ6)VfU@+1S)tl%$Fc zITd#3(64>834J90U;F4g;lKCMm%{&-K2q=5en{r;sSLk@_f)q_zf2y)(q$ zJJ3P+ANr;4cl+gq|D|6nck~N0REW{kFMmAs$N#&2iT|B`iT(ejU-CLlf0X*A@b~(K zp9?Jn>3{3*XxC}{ZzHv9>#3~|NdNnR|K)#&{qCFys#ai5{Lre{H}}?QnY{UH-06Ih zYs5M5l8ChbhZ&*u&j_V|Mr=PMZ~m5}{~XzAf-({2LjIlYk?_Jl$?ZI7=RqS6V}*gF zk4M&)7;WU`GH${F-C>O4xg9-gWG%zl%0xr_3|(r(+>Wlbf$^J=#yCo2EyES|#E|$j z9i?y&Hywjp%(~XrXO6O=J=%91TuUO8#Vb9W;jK+v z6qQY1I-zaY6cN4s(CG-REd$@k@vHGjcz zQEwsU`_^~bhWx%f1;5FIm@khaq@jTFd>fHobcXs7EiNmPH-7;=5y}%D-%!Lxj-LCd zIMI^f9F;PLqjTFOBgs$joC&fc;lSx)>$!=+h^ubX6;M@V`8 zRjW&>ko0!xHpn4(zZ2)XA@vo~?U1zNdfl%ecW`|OT57A(#bn2gva2A_V z+uJ{s!b$z}uIJbOA!xMJKW}<|?H_`YHAb&{r{{F#V1I20sxl4)bh9T1Jwj66ghPAX zd%7(CIL;l2Z|jwW$Kb|-j?&k4M zHEQV_Iq!8>NO6^a+>~|aNbz#~Y3e6K4}GKBup3{bcv#Q$W4Eb(LIJw~|33I%!2c}{ z-s#Tw(>$&V_eeC4cd;f)x2ox{3xh!Ah=Zh5kg);sFhM5V*5II1=_ODCX`Q&+I>gEa9ZBSc~tvlJGLLnu#&u|*ZuEqtZowK=))y?YqisQQultbMU*=dww!KO z$crj=Bq+D}YISejYYFO^n`S;;Jf!Y)3;Uf~E%N|9>yo>VKU4Qhqj91WB0pc?&J zpLc%0K3fZZ?WI?Iy(FhzdZj`fR(elgFAe^kUechKf;s|$i3K*F;0P;g5EQ75=8ir> z-=L4=`vRN4;BB) zMk;Uyd5bDwc<1KZbF8u**M(csiQWR5W3shD_`Y4XPrk>L?Mxbvz&rt5~sVc^=ry&P$MW2}<^@4POBt2&`Wv!H5>>b*F;1q^x7O z)rF`zf0L*=zLplW%wN7%!$6E!5n%HEiQF} zE^g#Xf-t)SQ`q)yw-xoY*);W7oh8dG>STqf6OuGOD%4p&{ow9Vg=}0)F^hsv->SCj zoY#fLprbT`-$am7d?CI)$LX?_+E`18Om5Z2>_|uywbMFbRTdT(EOh4)$$t}nisThQ zk3;V(?e{~jNpHQMk364|83WoEGtA%z*V!`T_?Z{WBnSscP+ch?Q!kn%hzt;UogR?r zi;b)4Ejb{a7hJ33_%V=MoWbwCK=g|1f~K8wP3K4dbOm<|vN5-7aTlfc9C(&GXCUzl z`9Ix;dYlCt)GKK4>|dw#s#!ny9}CtPwBHU0^f#`u@zjYaqK<1Wo;Esi!W zzXuXf^!5Q*ENfiGwnru_c5vIr!k(TCPqSUVeGH_eOlW5$cF_Ak3B93=<1_1R(4CD1 z&zoZD^`&W!!@ls6dVN~zVH&$yFG&GW`uuv=Q|vIca07VeGr1Y9IqMF<{+iwyD)r?x zu^9Xu&Tv1!`~s|KCze5~vT=E|$+W^JH&o7D5p*5Ck<}y32;vPqHldI?=NGccaKFSB zvIj8EsIRHdedA{12bg${`m5sV0XgYdjqpk?Dj$YZQD?(R$uWZy6p#!%u zsqlZh-EGqTLVvX9FzM@6d<&h<^g=%!(}KTqP2x^J25Z~i7 z(b69nA?~<^1!5f|zS1aY|B? zwv!&x`}*fseXI*>3fThm1=aZ=!Y{#Xd$y1*g?s6_LKX&>1n0X;hgQ!sI8m26`{A}K zm2H+S5G^q?izM0B%WLh#?YK0yuM7WZ?Y*n&!9NtT-PGscFa0OJ6NEk_n&WlhBZ=Qm zd2*z6acqqWJ#E35|52PduhZ=o5wnIsJ9&E-g|rCmLC9?F53W&!mqNh^-7SUsAv6qk z&l0c8>mDxgN^|g)yhAz1CZ5^MmKGJVRe!umkJcBCK!IARVALBqhg-`o|lDeXZPRnkB9@$ll}}fPA;bnkaqm40gf|80|Bp zSS?~}5SuQ=Y7kqA*fc2y%O221Hd`kn*6kh#eGg`STp9&5yCx=2#3*oMt-?Bl*)Syd0>_U=d8KJnkaw(9BE1^}s=U1UE7`+hENBDs?em>c zpbmsG8a+fEs5bVvKLF2$iw(Z#X6>+)VSdeXvNYf#znT2; z^ZLq+Y_fHivCKEV^nNK1{+JVc@_+U(^*M)r-n^}lDc>k$Ew5v|;a{8pzaeZ(AzS!f zA^RC)h5ixEw;J#&G}vX|X)$FcR`z$9G9MNvf&zbCc%y}z2+U$+BW@8B>h+n|gRW>MmGA*ZF(7JoR>t^=el^YPW`;1*uT zT><*E8_t1AI_R!r-Qy=&`@8x>16J$U7pB|jVAq8OsLdQ0e%|+(CN>coX^r+baT8jW zU6p*%w%4!sSSs}cQRm0KDPxtN5zcS|mgxJ{!NPv?7m5)Z-%8NbrHWBnrk?>D4TKjA z243KM&gQfC(Od!D#p}vvL9o5Rh=*Du@-YO@bDkB=8VmX%yahMhz(&b&(TuxBc=>f9 z1U3L+_c=y;?0A+hZ(i2pS^Xl_wXkCgiz?RzCgpI&xU#MbojmrZ3?Kf&p|4!L-0I3G z$2o(;h(FGkN$&>1GS1GN>q0G3PoNaiRRv^igK!AsCBkZG*2Z^i&<11ff6n9kupbfy z+y=0LI7jdwiu3hSO-F@8E0&MZV|Dz!3LeLU7CdIxVPzaj4lE*d{pY{17=OgX$0r{%M2oG4IMA1OH|R-Ihps?yq!ZM_J{> z1Bh=BE`6ki=8+r}ELQa={LAOz6e&YD;I2nd_*qWQY}^G{<-2!`XyOsziF_5Uw$d$v zUuBa-IMwDGev{RR+I+=tni<%l4IJLNr85;@GowaiY2{n*9yckzFMME49ppYK?NTmi^61G!|>hS?25 z#z(%qsXjW3W{t-Rarvtv+Nnl_%tjE9Cj& zxv1}|5W*cI=eW3IKcYW4W84u3ER_bDHf6Dq4)G1iF7lgE4srFv4si|KI=E-xo`d^j z-X?L2Wp2km)|HAIqC=BHjo?Ymr_uhgcObM|R>(<Z9Mp?vX% zoQtbI)NPhsScj5s#O#FA!$Qx^7}`sk(AIqM7VLZvFw1J`#*KR% za*lB5<7raeCVQu%?RGf>#ntPM_QoMLPOg?>k=|Iu#>*+?i=JX-HC zPx-=|F+(bz>YXEXE5;@6%Y>t~%k0G6FB713 zGvb=?Hclh7PUXK6pSp!Hen9$2fn*x|4;bbTLyi=-$gWfxSM1eZ%qaJCHAauyurtv>9dNbyb6`@8HIvIO`;g zpvB#B&N%CYq<@NW4zGK3&uP)l= zgi~#Lw7>ka4gZ4v5D;7Ph1Tvzzqy+xQy{+nGx&5}A?(Dde z;sP5=jfKqKR?I4a&v8jIajHFrgHgt=j52@59t>#C{uoEmN=-#eiXo${HMq@wpx_5N- zLrf6_+aofHztZ)gIA`K<-2qWG4ehVGyHv)kS=WJ2F~Yhnu>v*O5I3 z>E7l{dA|4!+$!u4dW_c}yEJCl7(YJ@tE<;NwA*orK`OP24aExRbr0$eM@<`H=_e}C+jhmCq$T%_2B95KuE zIEi@OF3%s6-WCHDlsmcWsFOo!F%#~!CP1fJZ!JRYpX+)rtol%%I7)Fu44lBlR_opo zgA}q!!T0=J8|-o&o>o=`q1r7rh8fz;DV*sqaM>Qc|+h<~Sy@Az~r z#TR-4k-J9uh?M&w&qAdBfZQ{s+*Z$g)K8{@jTtFE-NQkLTcLVL%00>BI3$n2erIC5 zj1`E<6Yn<`h$+h1QmWar46z54v!s~8GZQ5*>1%12=cH&;a?(9`1>!R0ef}N{_EaB& zB!`>@`0h;zjV%!GQcXhYC}|YD?U{fY=~SFCL5jcbNrfHyaMeAKU8MHx@{pE!gep?{ z>b1@SahQtWPxb5+SK$pd_QBeb=*wN65twtEBpd^G0(qtu^nmD)N6^^DO#lQ7_h^0NId&Id zk%tHSd(-F{h;qgS`ew{f&j7^Cfxey!^#ma{HqbZL=5+?5yeO4f>cwQ-4_Y8bs|b4{ ztu)nCQAYf}_RJ3xv(dh+-HC6>3Lc~UQYLH@)Qno>N zcbtk=O;+^;%K0Nem9}U`I-9k;;|IuKr+(%<;)qjzRn7D9YZ1ZSQ zxynw6bEZs&{S4eUH6;#^ROz{3$|QtKrRS0VUz{=l;SZ%}#grI? ztEJ~>Q=$<*Aw5q|i9+~0>A7=?1>qX$`NNcZ5k4I|`|B~KPTpp0#!?w;4=iH0;acFj;ez`Wv94Q%N{USldt`}G!WpN+y_Z_yUr&w;}p4eR!s#O)T-8lP20!i=kU-#yyFnMJH3 za5G!+xQ~Bh2meMT=}?L89!RLqn!Sz9Y{gHl2 z{fIgXt2ByT%3Y#6)a#?yf7wS{95E{M$zUB?e0-4({k7JwH_{|@gTwrT zoH5e*4bqbx4TbfzQ=6i|Eh93+EF18jl3?5!z;<-Gk3fc3ZwsvFaC3TqpG&5}9S)-V zLXWR+zLEOoMXW_s=1T=dtP6EK2%pv>hciH`!^uTv)WHJ#lEjY?-9b`~_@ztkFmh}`?5)RLz3-(q~>0!UZ|B{qh(w&Y{~z*%Wc06tD`n6YF3sT1e>Mi6t%G- zm+cshT5>x^C5^s=&Mvy|1%1>~Yx1|in5;w#HuS{ZA%#q`5Mv=t(e0Ld&P&vEhheNF zhurNR*i}+_1b2m~c+(}vQ0&rrpFNSGb{X`fIGl0=t@9x(?xTd}^-)57?OM9Ih$X>Y zdZmc9!%Ya|uUsov$DE^vxPpMRktaj#Gq z$6^NMsmuMENH>v)?z?(?w|IzdLE`Juh!^lEa@4%U?== z>wWilbh#f!>ut6u(8h;h>~*;_#YK=NB5qT!=1e$R8ZNbTX!ngupDkL0^{!+Nqhxt^ zDQ++6<+#u&F+;AX+s#Y*j?{-{NoJb~b(|^C*!ZkzZAM!9y0T~IcKm&9*>m~g9#B7f5;9e zW+`F8|0ZO%zyoCU!j?Ah{@@qF*Rspd!&kJ7KzwbRkDn&GRVb-RIE1q>@zc@`v>rTv zO|m%)npz=rrC>*=9c7zezC*KZM)C}-10MG>$+GoYi61gOdAh_8Vf>p|9ZGFa)pMh- z+v2QKlBOhQ*)I$CfWi;$m>Lx<2A+dt%w-{~eL|8P7R{sP)C+gD+0vQ$!5TGE^_iDp z=YO&lH1V`(t8HbyaHDlHEDx5ZQA%oiV}Ru~ej;TTU=(NP)JH_j>yOChb*?asVy#+_+p>5;g5 zGJTD2UZwcw710w1p8+1B!d+rYjy>oCE>Kg%l(m>&XR%jcUWEa!!~dlIylXJW{xpPR z3qv{f1sv#7iE7DO>x>+qbbFIUm=OQ>kW9ni=ZVM|YIveE2kBi~9R?KFks^);cutu@hRJXO)-@l-@Vjb~uA4D^Vg z=w%4UMdypb^DR~*=4GU{RhYu#UQO88RJ4bJ-m8m-9nt8B6eUjm5$Uut$#!vgDt5_t zD0i8xak$@5mn^zxc;wJ`V9w%O}QPnRs0L~xgdpW10vY7%5^6EMqr@cl|nF?$`3>M+N7 zJadpU!g5(~`88UagkKJ8kC82s5wJxvGP639Nw!Fy$|PGP+{BS-WRK*Nd1Q~|xXoqn zwMB9Twn#7nEW9Lhqr<5A7~F5dhIAMy`@k(HJJ`U9tYtRnN_bqhV&~)h-_HZvkR$=Y zvrQ(cKj2#6ddlnP@eiK2rKw#m{3oxw2s$ccUxOryrlSpa4=rZ5!+mXtb5=vA@L9hW zOOx;_>QA^0)!`Y515etOREtFd;X7FZaa+d&76jNssM(4%svDiN?&~hK9Ywuxx1Cfk zGozj!fOVlH=X+g=Qc9Qta?hbI3N_AX~eYy$du@S!8iU=qA9`!s3 z_l2RD9f3PI%va}B@HcTYXSXf0Nth_~jsXj5PB{0>ltM|*)Td=SBSnFmo@b=Yz$(J* zGo*d$)NSG(t**tLB@;poW#Tez*-CCy9_)`buB0={1GfDupWtttzk=8k{8ix6W2{U0 zTlHlt^TY>J8>J`R#&+G^(UYh4-4I9f_lb2>VqLBYwi@#nJONtwXBRkd-RJT1FWkWD z7+XW>!?8|p09P*`H+VlvT$(7C@NTR0&WOX}X)WoN&npNt%*z;(bVV54k~l0llFBpL zcURdn21>f;SA>9;0&xqY^2oN1 ztq)821AG67y8aoC=H_{{hIDv6?#MoyNSB46Hq*-{+z#v0mDO~W`Z4MZSZSp5P?Hc0 ziHh1saL?p|V)h60nGZ)Afsy|&i60Ie$uI&VzZSOX|5IBQ=Q?Q1hDqA8(0u+s?7ew> zmBsZxexB#KTlO0W2?D~!fC0jC14yV#4O|uxEfEwH+nb#vlFcL#)P6M~D~lMG5*3Rq zvWeBW;#yf$YVDHRe#E7wSEUuJwb4X_A6xT#pEGlB5~TS3ygskr>-Wdc=;hp*XXebz znRCvZb7r2ohzWZ#FM#DVNc!;`{K6SLfvPcc21xqtuXn&wW=-RPra91AaK_v25wNS+ zqdMJPs^1FOtZieqjb26nxR2b|>#l2}VI$T^f7?#CO&fd@*5Aj2-=2N^H1ttju5C^f z-avbkj?4>m;&y=3!*FxcoAgWYn6m>^&7J-zr=P{sckuKSnE^8q5a+etq^FSE)!kd_ zF{FQmQr8=1pa-R{Pk9*k!@SA-m>cMPuKS^Ruiz$)-kis}_s`pVdR(8J1KoR&GrmvG zj_#evnb;?%1uc9eJiht#N1g%CnBeq}JdE{j+;+z;HFWPi{fe~u)K{-~2ZFvxOOKn; z!>aCAbf4b9jcG%lx$5)uDai3|J^hgvcSxrp*Ui}0&TM)S`5yCv0sn1v)}rr!_CnvG z_DRA0#_5x&jo*Q;K#pL)4cMku#wQ{!|B;pqS{Wi`Wa%=7B+59|r z!I!%#_MZN`ckk&>@cC3)40Iak&F8u|pL1`e)aQDvJT8pZbIrWXYOG#DZy!VbC-8a7 z`wH&ldj)3)a38AR8v&_&^UDUD)SKO>$G=C;e3_pan*OigChxkbuOP-%dwQ(MCT@Ef zIRv!YR(=fMcr50l7S35*h5P!_NAih_YezB-Qb42Eus6@&Cu(f>fB6b-Y~-9|Jbhk2 z9iyK%{ z;qwSSmrsF?#Yg$>eCCbMIy!OY>Xv`0vxHxF|4z+WVm5;8L*p-cG0>DS$Rzw$zNFm65pHCLaxJtq3$hcDbv zs&F!H?o04@9lN`u_3t`%j)i8M zj^8Nk>(?b-Fal3(c#`~w^FvS4MmFJ>3jftT_-plcd-X^Ue(jMEJ#zl*X?TY0GslN~ zW#JSH}o&pNzx^-nNLEP^SYiKaNeE?ELae z#A6>HG#|FlDBA^&)3*6Ts*S|CnN!NUGAqk%BaP;mD{)t_ytP1I@0eMJxEP=Bh7GdC z+G5*c-vax3PS};n7+Vv5Z;!2|XZ0^obiBary;X(1LVU)qYLd29d}1)#ep>w5r8tL$ zD9#12A2VIh55K^z)4XfPC)@Cj4{j*&WX*ra4UP%^w#?VvEAZa@%ct))E`P^{)7FXe zcVwzxsN{K@h1*8{)jb~fB6x9nt?x|Ek{KI;C+Zdw`^Z^(&R+Xh@Qw0WI629)c=TUQ zm?w?~48Sa^d;4NBiyW)##=aik(!v&q2eOUONG?!TRiJZqmj}NcHyPURyw7(aKT0f| zK#t`GE&h59eE>c14}8R*ALD7u>iE;U zyKkz17m?L*&)ea+@v;Cr)h9dO!s%k%C-z0+|1mB}T#;8m6F$RjS?Zpe?(U)Z{dx9! zvO2PUKK%v8TUC^kkzJgXlTlc*tQ7wgR?_!>-&5dw3Vct2?pT$RYpQE+8e5sj|6*fX=dG%Gi!wAiy~7SPV}_-6S$x#fi`^UAqGSx#|o zPHxWVT(T0oR?KmR$7&Zt|@HgtGIXt+8B*Gc|{=2 zE!?E4IXOSr?0D{s{6pmx6@?YWITz(~nH3e;%Zjq{D}sHSoR1e2&Qhr?H?Oiht0X^f za=t2xic`ERQdUe>$%+-(EAvWn3w5`$@`D{L%`3iaw0H8VbA5zlL4sB06_=GRTUL=* z*>AvlxYGA!=!B53EDPM0U4^;jbZ%*7N=jBf)4!lRyK1txcNPjOD?tmdLXy2IOCivd z2x7Y^Kf7wG_uGT-rQQF7`s7Nvsr}1=s4FUq3o~*mi&R(h zR#lc|@eBvao>fv=QH96BbXj?6?uwkslC0vq%SKmF<*JO_6_vMSVINl1xuA> zG4ZDVuZedCSB1C^{TFFM*fA?N7qg9_f=?wbmZSXQ35lD`(^2@igY z3;N{u7v+QbRa4X#50?);=~uqsKb8+YVHp?lD3X=sl^2$Zf~d#_yO-on_m0jf zzX%E>h$<(ChvBicnR^fP^k}gHPoP+^2$(WRwaRi(DmX#XL|#cnUPeVxX&HDDIt$#T zxF@88dgX|9U|}VsTBN-!%Nx{;-k@IeW{Xy24huHfTm66ZO^M-jh+OYbp|`R@f{XIC z4iS}*wNlB87Uf)Ib^Gc9gA9is^qgm{8>u zY3F}d8A?7llbAj=TIA&x<}WKOs;s<4&0JrNzAUep7bTw1P|KPF&S;v-a+Us`j76Y0 zIA>fdudHN6u@)p=`g+&3@>Mwn&~oZouaJhy2Du_7$Q3DyD=Pce>npyz60+XZ5}aR_ ztC54ndYi>cpvIn+pB-AU(9sI4y|;ja^YY5{n$bT~k(`Irr=(Uf{WE*jOl}U3#yfQt zv*DD@6&r$^ss25N6u4pbBFu1yx&lSx#1HS+h<|SV~HAQ>J}OGv($6$01xIoGP@Cg|VacQa=zy;Kmi3VONc4Bn9mEzT_rt}17;J5)$+-pXJL&}T)ZA$G;rpm~R{qR3zz zhZJpSLH>`rjrC(uX)nhHWvj1bvChpYEiYfiqf$H(Bog{wQd*&{yDVmQrIS`vRF)R6 z%nF&2{p|+E(Q7rVSb?!&!3D0|yo#I**w$sGP}q42SFgq|EvqanE#Xd-WtHXTWR+VipKJx`hJ zdPr4e70f=&Um;%NgmONXfhu+q{ZI;$u=gK14Q(A}63h;pEb3IOmcd zCHYQDkhG143N&b#&IbSv+qF z;lF`89jDU$JBmWXD;X&aqP5vcH&kc@B9n&2M;q$2KCzxpbmnQ#G_X|gv{6y9AFLht0)1i^7e5Ne_bzgQ^mDd#L zEw4Jzn^qk_d7gg!dF0>j%ih-Y({!5j^J<+=)9JH!;6#uA?_%DtB>Avj0f5;FE8N^29sI013oKcQ(g={3^I6)!o!Kz#pJtMY=)pPNW zDZ4UfRaI8GN`%BMxQHN>2MdRaSFDl6!!^WoDt5z3W{(= zHUbv>Z;JdoSukd2RpjONsfaiuoObUS^?8v3tzxIFrqNSZGuhY30AHMMkT2dh)Hlp`zHf|gtZ$qz**D%d!8gN~ z=1cco<6G!kE zcZDy-H`zDE_n_~3-wnQ{z5~ANe2aZKzG`2MZ?!Mim*-pNtMujjcKCMscKIImJ>qNi z9rQiq`-SfV-$~zJeee6)e1Gu0?t9kvobP$xqrS&{kNbA}9`Nn)9r8Wxd&YOzcf@zp z_ebBKeE;Qp!*{~>rtdA^+rD>vfAIx;@A*FQ{loXE?<3#eeINTS@V&7=e}BRL`wqOh z|K|q=Vw?^8Q+)dlytDrg`~STEfddO4eC2@oV9JA&AH+1V8KEOfnk!OLN-_}c<)EyD zld_gGnQ82nTKdVMTC#7d6*|wJQb+IppiaK?KeuM*tjfvKeVI3SIDOQ%13-h0p3oC7fDy{-!=46#frY@EfG>B6u z^mVc{A|XZ?nvyt+sECB95R+;+IHcYOQ&lHne`tbfYXm4Wa`TpDtthI@z^JLOKxA;> z8-vWf1+>*=LSu$7gA!OwMRxiYEv~4_C@-z@2CM3H${A@HnxL*Iso)9~!2&s@d6?p= zQt1%9YX}u2RN{!iA{ytEGtwax2)JQfjJPOorJ5>kD!Y;`9v!e_eN-9D(&%$4D<)%V zm-THj3wopSTca!}%rEHMLiw^RcqJ=JP_lnd3!xOg)sdposQh75KR802Lqg!!@B0gDlxIdOZ{~S0P2G%j{3vU8S~E~CN{L}r&EI9rmF2i)wNXDCIT zQ(nPl-{ky^oct^?gt-q{m6cH2XZmp8it~obqj%-`P#D~^Wksc>th`rdXF--=HL?dP zwr6D?tV%3F*Z=qdaU`<*ES!dpRVod{uT) zY0mP(l60N@E~R_Qu1OnsGa=-Os`5hQm3WhN2#bIa1V58f<1H)~CA>6w8 z(AhEAsroxGR11bkD{*083?oBya8UhsV5k=iQPzKba&`<(TKgRs)(VCgtFiIh7+jbO z7v1$88151bvDObRI6Hn?-SZt7?hy=e*3Xxm9YX|d{|*e> z1;Zd~!ROz`;LN-{Gm>_H2Zr5(A;B{4JUfOc+W#FG_6vsdtjCl3V;BRu;66mt6W@X1 z3Bho_5bem25^7C3+Y1lT!Aub^(u)(#Kp$D;ZZp!lmc2lwNYpd3~hx z+!&OU9&$Z8@az~^O3#f!N$GR0OCIfu;nGkaSW3^0K}qRh*GoS-I|i20b7N3a`jYEM zB4a^1^!94V*h}bZ(iFO!o-I^BHl_dENsD-S5~36rb34_ zkgc!*jj|GWd%e7fJxKN!`|OBi=h2Lni;D|$=Usy;+yuH+mQ%nORXc2W^qLwfBBo9u zsMh&>#452GE~LYVSPk)3_tQrlA!-fjqvHrP^`(1yNEfixaBd7rAN@9h()wb!CWL|Y z(YY}wee}l&sy;gg)<@^Yp!CsO5p?+M7+4>j8-vnEfivjPI||lE=fP(eROUNN+0!{L5E%ptdGu( zLFprVWPg587=rrf+!&NTiiqsb54{*zADtV6(nkXj0PV|By%<;@og0JFMh>vBg^7S-AoSW<&M6k}EI6Dg z8cw!&XT;(3YB)*52^uDAI8MW{8jcA;-eGY#ldK?Q``Y2W&{A-ehKU+ppy9|6C~}JDBAioGHid-UphEDUA1>?I^ zLy<$IQ*~P859uj7E%Jx7$Q|HB$-hj)AM}VE#$4PZ@)q-h9+9`0R1K%~h}^|Y>lr8Y zF6t4vi@B&rzENeBF{1SZ5-+Muu$5g(<0A!F7g~Rq(`NP==6CZC~_V% zxF-lj&ST4BlN%8%7)w}w%=evD2>YZ$5PM}^X=euU1C?BUHz zM~q9?57YTB4Z}mvRXu0uxvJ;Xc%8bOJ@lO8s*aej9^R^B{0cgIRK6`#p11TIF_y+- z>rrV#_s7)vhQ@2^dWOz7L*-R}j8Hm==l>0euxuW0xKvawW4k4zv?LGq5zZE`(vevm zB-SVKNT1{jI#VU(Iy|iWBJ3Yk49QlMlq0AdEUY}Q;;f40ItLA+L?3%hJ7?G} zLHJgJy1h9mI;VdFd6kuL165gAbLva^stg?GDa^r327)9fuL#lZzB#>KpeoUC6uf1H zK(elzvs~;gIHPx=bu@oTb^lKCzrW0ULMDanqufw;r-{m!>OtF>>7a^h}3zR&di&Xms`^R2X@ zkwZ<-oGF>cfpPd12K#B_Zob!ysK+{udr0`+z`u4@f06d(0Q~lc6F1ELt#c^uGy7}j z?YK|w2S{DeY0jULxuEM;Imwx)U$`pQqKG+%OJnB@!TljmzvzC_!0%!lE`7iA$DapE z|JIq>N%*y+)F)|F;T+>Z+;O(Wz^|zOt>@>b9Ax3HkWn2A|I9bQ@!b?$>yMvZfqN;q zgniC*+|+@4`tj>u)8!^Q+_i^$tS5ZbGsB7BVt7j5aTw@aE_WPG#w{DjEq|x;>aOr@ z_-%*Hw$G|9+xLnKN#VZ_ekq3qO#5825qaRH_mFt@EMJBXI}NOQ&(aN9kWX zyK%SQ7u^@&Ze848-xDbPyu11<1n~nAqdmBR&14nBl^c?^${!?Hc7c}u=e}S4jN$X6=1IRFCrRX*83k}fUA0lVssI6b^CLixw`#v z26g^J3P`Gfj!UZg7=ZD7PS1#rG=0v&x{*=Gp%Vki?IVLzIN<;=c)V)i3Df59Asl&G zJ}Yl=^-!ZO)9mhkQFQ3j^Q{s$@;UrIFF zcs{F}5_WRQ9N;YWukG?66O$S-l*dQO7~i-LiLT)yOHy~Dz52yzSD{N-v?cQfRF_P} z1$2#S;aLTqQQ%h!92T7OhlAvp+iOjlX#oh8q9&Qv%N00TgXzb!C#c}Te*&0w?O=u* zOoK^x3$>0rNC~^l>ST;I6I8Oe^Jx9Xz(FeTH*#h{GP=vpK14}${$rwL()lGjjrvT- z7bhM@1R58m75Sw*MD-P@JAlbV4O(@`>RdskW&hH^i5u#j=yqADCz zqup*c)j+oH1Mgz&U|}A6J-XCQ9tEly`~_D`bEX+s4Pte>GV8dzi_uWAzkYGx36q%h z?=!2b!9Dk>8C$1Fw+`e&>Q!;U+u-J?}GX z#wRgO)t>2K=G#iAX1}_$dzV7ig47zM6l2~?r~D0FOLk(k^-EB%=%u{HnNL6$@c5LF z{8H6JCL`OUaPAg)@7_rTvtQ}*+^34{>CJ3Fred3e3fV!^;O>eTF0OupJRf`$hlWJI zJYkyL>xWh9;ozW!)?9?SP7#Z_4q6JCelUaX;HNCNQO!lx4XkFKvfgBH$a=FK;AzNF zEya$dR=SO1lhHwoViT4M;`qG#d}6Qshpn7MbDcrh_@8%`{s-1fU}C zr-`06u&L2F{s-X5J4STxG6Md!?y_2IBdR++Qo(SV4g-Alfk|G}`v4kczQcnQ3*`r9 z-RwjL)r|84Dw&-CVhVe^t7-oX{I16pG8Fo=42<5D5m7q@jK7el%BT+5RqGZ-UMy2Q z*r~u!Gn$+2P%U(r2DjdUdLNKy6-yP@t5%(ltnpF8Ui54mW&T52zv^N&asQOew0}zG z_+SgB1CoP*nT+#mvzmwUwQA^VO=~ptF?ntcc5t<7k5%5c`f2dkzX3fzPxO3a)JT_1 z3#bhzGQUh5=`?Dky3h=n1^)TA8FmIV!!G?aoW|-*N0|Ex>1XV0>nJ85DqJWrV4C$O zo{nd%-2h}-zw(OuT^?Lsq92iGu~p{a ziAiMOJSecluC;an7#?degY%6B>4Y^xQgo9aScZXHlPIAHvYAM!O%|`y#s*cLuNaSZ zz4wImQaiePD|wDuH1c^Fkr`#xaLLgY;Tat>ngV7-^N;13wb5)$%ONAl*bs>B@(xz1 zv1D>dQmJHW^{*rMc_};5WOxd7K&+ zOyzQl#>A?5&o|tDUY!h!0oHe=0GqH#VGYo!fU&g8n*-f?jEw84b#Vl_v#Ir3m{i&Q zkQGwvjJr59tX)>Tg7!w5@nc{CvYo^@mvEQrZHE{%T8AA{{R-WeLZqB#u%Fy(oCelo zkX{caRlyZYtxLIeYP}vHrw>6KshgDXb&OFDZf0HZ^)UBeIYsGiYEAPIPVTm*%_aAT zx*nZMn?fx+kr_b=ux&tstSV~u-$kjr6_r*Yg)u8u-a@_RG3cBSXhd#LWsQ|;Z__t}!2 z^jX=n z3otSQA?49LQ)nGK!P?Hx9yMUhe%`W$TA`W~?gGyPG~?$8(d>h4&9Ks`!A!g78XfI1 z7^Z21(QW*~=%_o66z!PxR9DLEAhPGPQU|nF>(1lZ6XQ~5V^vEUP!`Jc1Xg40Mr8XU zo(JYSpqA;MY4B)~xxT#tT?%4RVo#pH?WiZCh2dX&bOcm^X;ycV@d~xh%IA7N^*1Cg z*=^RsVliH(0R4AY!C2^4HfCvg`zkJ1|w(fLztYZI5S^|X#NS>;7d zGB#$$*L5XPz_X8<#!4rw5_x9btj7L^wFM>77thhV8~{6J-eq)GgKcQSVb#H?NviV$ zOylTX=%*1!Im{YtTxJG~7+W%92;9!i8t>`~!IG^^mp!1%z@g2sMv*d3QeZ}{qb(Df zmf1}z7y+|79b*4EY<8RF-ht@{Pdq`bGylkP)HI`(yiYN8Biv8Qv(_i91fKVgtriBK z7}c4MhBz-3wEYoS0H7*A7kb7`1z1jT7X`)86BtlEGqQg}j5=DQ?sx*JC6@as-3fkX zwmoS&(<8_XMEK$n~duKOjpPQ=$7V%G3d4yF@eHDlu7neq~8j+beS%@K#uOcvA6 zOcdMOOqOSZ3Ux}&G{z3Q)x1#ba#W}W(*{dMiQQ_BGwtIO$s8vY%w%0pkg@AKa|D?_ zDwx?x<|HZx$oBQ+9%wh|S*jJs9h^-iFDU25{k&GEsGw$1PhfyTmJV4N2wBmnMcbH* zz#(@>99?7@&>AtLwX%Y&AoF@E^xsd}<>uWp?;`VhRj*u^RAb062jf}HXw~Z@y7R^s zdt+}yCJh2372y3C@XK;)jgtkXpuO&~3ks0hCNhoGOisZOW2UWpEW5zm9*5Oyxk$fR ztOZ?nK9~u?gCAfL6a+fI1u8bA3seV{gqs{Mum-y`jj<3JR`AAcG-BW@_Pa3giW zEcDDpd(witPPd>tfmNoF;)W}N{0tUL0>upl7)o)dckMttqt zr|cKO8E-=RlPOM2j=|`4@saf&b2}5uMCSwkI;%>C(i(fdG-RcM-Hwy_s2PbhzAv9`zJ8m6YOVgVpen`JXkVPFd=7E4z8B8p{7ETPyg<^tN-A)YA; z8R-@Qu%Bw#6nSiBH9RoOh8bfIlLE$v`XOUJn~fCwm0Y@McKqShQ1zGx z_s_&3_8C&|8W>9Gwfi~POO_Qhq6Ubqf!TEM7@TG!LJCOLAZ7ovX);TNn=UXBGV4Js zdnb!MQ_0N~R8Fri!MK=H)gU?4eKky@hda=hRyZTBfoL|-aiWH;3j;^f1Mm^R`qIIJ zkm3c9Vnwq=P&bBR<5jZ|*z_AYwHnP@iDu2*V`L43If7H6Bgr%O_~o^UHk-hM*5z8Q37cA8VOoG%e&$6B%(Sq}nFo#4OA}~GjSuu0toLrYJK^PKc_s zmhsxpS|gCV8qO<~U^)_)!GCvrp1M)V*i9JGd^>)7r5_g6mph=rqI)$MQmio*>p#Jc z3V2saI*u8`((eMTMK!lTYZ!j$WV3qd9c0~Z)-br$wBF_v6)bIJz-A06=o$8GSK{q5 zD`L+NM+-WxuQ~yHzMZW@9hgwU)rf#MgsV|{jiET1$o0na*%ozgMC%dcnW?HbNq0Rn zAwZD+YBej(K?&y|7rX+Hz^uJX`#@3;nOf`%Ugjc}isk7{T|`l^MNzN?>WLjjiFH}` zV#)iEtb5rTWS#Y1)MH~lD5AifhagUv)X=6xvyEeGUJe&!Ltq1_prX?7+^naiXBIqD zuua0VoN^>S4QupqJQKsyI$+vf1|^pZNN<4sDn9A>lD*$@HMO8Xnp`ghr2r|cB6@$b&Tio@r#1cv6wkmIqvC zgS`9a58f@2QfKWa5-2FElX@NX#`J+XxEo))LJAr02PDR|JwbtiOK8-8$*kBm8@xHx z@(`Y3FRM-{VH=|=up@?Hay|CI01|Cd{YDz~MzDGfb}dhy2omqeEF0!%7kwmF$ zjJE;YpQlY&jBcu;G5M_C}gjEMU}4#?$@_+TyE?YX91{X*FtK zh|sCby1tpJ!p%})T8&g#yt;1%WO9YYtBs~i1dI18F>F<0_$c-!c9U%-)WvRU=4TK} zeg>g@)W9|_^wODP!J0w1z)If>Doug5Q8Yuz%mS+wGdA;Xo0p%Z;u#YJ$^+8DVHiYe z#Hr`lp>2a%J!=HnHbQ$}PO-C@o+^Y0C#D{m;E-lD6fS~PeXs(8h8>Se1;afPOM#$P z@@MV9^xK~`9oXTA93lFHEeb)69U~UCC>4sp!N#3jGAS7I;Ar;A`?1vVY9YT2CVqNYor8WMjz@Ok@CRpxz@?=IgjA{ct`-IrI zOTnO8#}g*ImbT}_dmoYbyz|! z-r?m~9_k%IY9UgJbVtO(wH-nA406NoNXPmBzat%*@BO|wJL*j0>aQ7V1JRgwbTAlM zXO~6=2D#U!ir1-0WtAt?P1vAlb{rCSoIE%8t$>&us-uD`a;;dLw$~|O?jz3u!-AoN zVLlBZN!@8Q`WxKZCb9*rWM-6rNz_TUw-G2vq-!_;9X{ronPR@$Fe2p`1+Gt|X)Y?j zmH}sC-He6ziB#+$A*=mDMP&BzUc(|Ky^gP^z|tu+ZM}H3wo^zY(KKb&gEfRB9}}^N zs8wzRBz&o(%Nsz9>=l^J463`J0PD7u$ENCJKCGUsJx_PY- z***cIEmh23p_si2%r4ZmkMB!e*gXNn`BL{OT`)~rPuTZuN$nG(R?VvR=7l0(Y}@=* zDOJb{tI-dsV8?v2U#j&dV#Y|NDb@&b2v4fvt_zwRTHzvd7&4g>SUa>*ZAFZ%uQp}D zQ=K?qxZtZnfS8`6K>~=AeUZ66{eH5iOAN`L9#rDj!?uZ=V7#4vh)o>To+h2NhiA4U z?7YI{=qCFOFgdz8#U_W|GO*t$;%mQA87FLeH)0hPbHwf!EZQ8gXX=#Mgbvzs*lu;y z=SU_N;erilAu<+2Dm$xvUC&={MNE7yjlK=CvbOH! z+l_izvaphvFsXP!;p)NY2y7I)*n<>%^6WtpcFt$7!^Q(9#pV|h7iK_*n*r^?~@r?Ck;;Fyk9&@=WEMZtZ7I&ZsxJ=-A`*$i3zo-PJPX!Si?AvQF`QLPapUD+f&B%^Ou)e&|9tzN zUtqBTK@J&MTG>qNV;QIFBF|%e*iD}OT+eoBgPPmtxw>t%7|5`pRkJX&u`=VJo3auV z1%Ia6Td%;KR$@EIb6mnH_E(gt2`+DkUV6oF!3<@dM+(p6tjbOUaYdX}F;A&VcNL!}k%O$(Wvvf$;Y~^Ly+hiy>p^?s=SDB8>Ogq~)?{Hr(ym^YWfGxu2%y5K0 zRO^35TsVmXQfwt4qU7Z0U7vsy2OH5{4#ueteheQrgDZsV3TH&H5>*9>*RiQ$?@()M zha5<-cNo*JMGMtN^UQHOy=%n|v46#sw;$RhEm%X*L5|HRV!f-XBdkm#gam#zaa3R4 z<$BoY*Y)7FX3(e;avlW{kk*0Ft$D_IcQ^8g!gvwhWvuZxv~8`!Gjsww{OxsjUuaW$ zX*V`3Ht;hDbJxgdWtg==L&K?u+X-1o*n@!E*5S$t9ntZ7WDcbcoao^*o_|p0-DfKG zy0Y@vv9)ZrH&x~_P7Q;yk_sq4N0x5U+7Mrslk29o)f!9e~{rGAA} z0=Xe$T<=w+5H$QqrGAYRW(=qM_}Ob1=3H`rtWv*0YCgGD6rkg`NG%X2dmzlaY#HB} zSS1gY0uaxF3L0FsQ&Ko0lbHrX=`aP-aCro7OVF=-r6owO<)req?2(FYgfL9WZZTATwI`SYZ`OHfX`5O|_<-n-X{IqI4Lkyk^mullg#L%I3 z108vE3T9JsE%*##-_Krh{6q~U6RU-o{H)TAzXea*y@3%$-l~vgDJ~Z#V!LOxc&)nE zigcJ;ILoo8%zA9#IXHqPF4PXDOW7GX+4ps4J4{Hxd}qT7nRkcs zfj|&0lB$>?daF7CHbDFU$7*@zM%Y|DBAEc}n((UasMc13Uc6zZvEMI4F{7}UM(`X# z3|)?6i2CKas<5@_uX9~^jCB?iwaEvs9W8Rg6o3zRI$BgDU$n4^Og=3Mz{hbNTg_UW zMg!mj#*R(u86N}v5Jk|?B;#)_ARUM8utZ*BL+czi7xpIf5L!VI}a*e4`YoxM6QYSp6A)bF_S3J-jI0JY-B#wHD;oy zbVsX%j$@}FGP`=LFB6ejM5VJhZfdpcfsx;05ZpN?-C>?h$KFFmokT7BkSa6nIE>XdbgVDoFmo0U`VT0AQwoHGA|_U{?vAfSdpo+7ko+xZOBG}JZ0Hsu^LC!Bh5*0EwiPeX>_LO%kUyy3M3y+7j`$`x zRO4V=suY$bsGvA(A;A#~7J=EcbYiH;I#r|@MX=#}C%_1bV|NG0Y#6OYjt|70bG&a5 zOg}73)qZp16F5@kH#fyKOUYCf42Xx9g)ObP^@>AqfaU01a(vuhPe_G0ui_=FK#Ws~ zi~*CMyPITaL2sQ|%K<*+3ZXBJwCr!#I6BTlsrIvl%ic9_C$y%&NO2dcX1~(aLGt?v z)NOzX?u--b!to81{}kBl0I7^+yI|3sFqpw`q{?26sj?%Sc?r2eIxp6h4JdMg+#pZ- zAIZBO;5m85mOnq+hG&pzIIrvBF&rmnEL!kMk%gB_k%d5Zr!hn|dv|-I4RiFgzhPtR zdS(<>qcw6AS&?U|0v8FtI1`NfGR+{rIERYra-N5c;^R?qDVm;KU1FnB5;7LjS#c9( z!w_dYS#BY|Y`Zx(TD$!Mc1em^in*0fBs(`UC-ZuA4L=)i@=;{xSf~U!E*CJDljmNe zTBKNT;x$`?OHP8oE^s9AqKGAHzx4nkOR({)dJ3}U(VBCJnqvj zj|mg?Hu7wj>ft!!f$D>l;Q|4&ptGD;24yVZ`8|!9Vj4Ki?Yt6E09nV1J-_Qpl0X)@ zrU2O;lOGf8NBa0FzqEy=VHz5!h=q{_yA+wc>@=*?aRbLz646G zryc(Ijuu4S{g*hBGF6cbv$6U`a%NyQ*{nCK;q^GnASAG_cf;6QM+pyzrgbi(k{K=D z{AI>qtkVg*jUfykpn@Z{gPnz-#Afn5pr&d$G~dLo#^tQwS$PEfQz&&k`Z>8PzXYf` zFo-o^Vpsl8RRu7+A66x|hxo2;Z>4H)r7=vkH(a$Rs8{u(PNmd4fqGh3{%s-DXgzSn-bk+n*^7La1BScxXj6B9PpX zv<`#5pFI0y431-Ja()Ib7rvGW-)PoirHs$jMO0rlS$ohW$1%yI0hs=0$NEYz{V$SL ziXbH>;6AKQpe~rUCcG<&Uzi9j$w~L=CArsUo^MaOACuZhNjuIQ7|*owb`#c{#B-}c zs|j~1%Ig%OY3QdJC1W?E`sxCh2ST1lS@$q|^T4n&tA(Ne_&|^r^6b$h5E*j~fUR*G zI1j0TaXcd9)-Dg5F#{v3{Xr7&Jm3iBbkGILgJaF0%c)sc5d;XQk_^!d5Q}Y*b#rht90$e;kAcD8Rgw3t2hhRrbnAcserBBD=)o~^ zp2WfO4057N@Z1m=F7Tke4}-RT>$UK*dK>aLG`j<+j?TZQT0pNCCQ8U_A$o?8*TQ5u zaqWi$RI2tK1rsf>jd3bU9OG2{zONYA_x+2p3~7eb#9LvoV^X^$rig?njp2OgbBV&C2>;z^Soo{jqS-mG!3*n3f6CfPo z3TFuz)_hXCG;D*}Qu)Nhg7}Bhq-O`8)UUWmb!c|mj2v>EZ#0U%B*%j#IqU z#kg0QHE9FUYk3{Tbr~;9YMfoxShtU z?REB~9xmyw`kApYVDb^lhBT1iI<)W{dDIJ8kq-#6IHe2XYK*5d!)?u@IMe15KvyJ6 zk+yNhHz-U9r87hcV|9jw`CzBdA(DHHX*{UzRqGu3y0^q9qjfJoC z+F{hcjN#Z;{`esjOzbTO87W)ndBI&1y?RGc=2euMQL zIIp-{z!e!vwgA zQ_j~Vb;`e-klGFqscZ(bT+)Jwhqz12DQci;JA4VbRI`InIEh#Wm}{St&6eyQG_!wHmD3^Vp)~-?q{qiIX8Y9<>p`AdD1R(xA3Tnpjc~W+0$6kiOAj(X z#B|JPfH^6tFG*rZRZ8i^j4(R( zM;=OU>1fNtd0MbW07cmCBv0BT*M7B_T090AF8?x`0x{(LHxJVcztR}H5O(BdBaFd= z=)?kR|KE|B$e9QH3n+Cn^ryV(5}46wbYQf6f?+3(0b>??W?(l$-ax>%e;GRA*-XD0 zWjOG%IR?E0%OD7Xf!VI;F&Y9=@@b4O74`(1p*zg*x6$3Nu%PfWvyNF2XKFaJ$2!QP z{WsPe9JcHM7ub6C{ad5PiPp84cbTKG*-|nr!GOZWpk+F`@1fS=7y|+m?FVUW826<| z^~E`Mkg#xAgjt6{hYd1quLDF|kD|RW@a}Nf&`RFJVywp{(+l7Xa1UB%lB<$FD~0R%uok>XVLqceVBj?*^=vp3*%o#_T%i-f8trSY z3rjK0gOe!ihh}XufJgL1ShCC*e1z$&3-Epp7fC|(3>upRyY()%^$P(Cf2c;347SOj zd1F=Thh`lk`yndaB>*o#Bh{L`S(?Sm(ev=ke~{*JsBD2_jXFOVb}@=<<07r70EJZh zP!fer!z=5J6qX83uFoBtO0DDX5G?*RKR)mSq~=pZEJRdZ8N&F?H9r(_O2B~xEZ%4~ zkbIoReI}g`n*o4kXMis9dKRDI5h|%b7KE#NkCn_6oTI3_$8_>k9W|@x?xwI80Uies zc550%r#yF2lUkOr83iu4{_q~oK`f%M1)Q>NL<)yn!WL0rZX;du9`q-Wsno{zL=b*` zC6mCuX0htoQN>a>s2Mv7v!av2{3z1W^U;kE^cF%~3dePNKJr6fgEfwtPM+zbXb*4F z?V@HhG86Tfmi9qF%)LOITKbbA=JJ)QR}K9Nr0A zp*pd`8qWkdicaLC2s)8ZE%yK{>+s-Zd~{!Ol+I`M!J$tmvHrmnHojMGfGMn+e+r_mOo0+LO)103@JgH)!3+XXM$ubHBknVYrwl5*;{d)`S^@^z&=* ztvSeaMx!rKzj*yq-l9N?-=Yw8(a<&zL~dW(R(Mn)W9LroQ)WZZbqn7xFX0s)HL3fk z=nQ}!@fCu7%A7AduBnWDBU!QPCe z5LYpPf(Ks20>*ohXXE+5qX@+Q+2B&Qsol@Jmax*ff>i${t60vwJ2RdEQ?T)0n&fIW zkE6SC=vBIO5=Dp=u8P3}pr4bkmNzj8}gL zlhMH@BZ3xu?x_jaLN<$$IJoL(7RT|E zX;j_%PUQM&!BngF9df7X>s8RuP)8fDw=g-B@nw_)%Vv7e>TM{cZrorl;<##>n#OL^ zd8CEH9qOgr=TzsN>P=ntLZF`Z(kbYr6a3m5zY7dG+R$CK2LNv)?dgviLz&$5AivqR zH8d1u%!UtCLwP_tj|f(E`{u|Nl?shPwH~RjO^{U7I!$>QSmdaFS1JUZ1Iv;*QvURX zGU4zT*eDGjd6o*%yQw72Yr^5@;AVKbuts>QEFt0JVZ|nsN4?_^?iGC*| zF5HXM67s+c(s6s1=t^&EYFhVnSEkn$Z+vDIwy)(9{7I9e%C2Ug3-6S(Mr=Wg^374_~5a zeXYSM2!cMMhF3t?s%)Kg2RXlCGn7M}au>#SJu7;u#IFkfaqyYU%59dHC-pY;bHt$Z zJT_Rrfbl#%EtzoQb3&SgnVRq-W$G@oDJ_Y@Z!%y~;WQ|0MYC&hwP`<$%wmou@DWjP za@2{S7>aKnUn7~_{WDjidIXQ*6b`ImWquFuP%VM-S36X9Lu(vDYWP0NKR|`U_Ze%s zgRqkinAOmA;r~ZCD`JgR!<@Aiv`)Y^FxFU3)tJq=^C4Vq7$&b#+}fZ?Zd5COMQv1R z@__Y4?;-{W<*4Q_Rq3TWm0rST4O)*J#nk1)_|niuv*}?pv|FB`FKiiy^D1+Y#_`tM zK?=Xmh{O_!VR8U-96OqgbfxnD!gpD%+}-WcUic0%bbC{5;f7Mu!hCfOP`9_PUkbx) z05V*DBAwW8bYR;*wgDl;aD)(53%^#Bcvz(4%3mW!hS-LQ& zV2Z)vXo1VdXYzAtIg0%KxG@;y!TE`B2GE227B9Tr8JoJwa&dMN>_&L;{l7QMY zB2`=(IQ4a~aKqoX9^$$Ehw95|F(AWFgEg=W{=;yf2vApV_`T7BvGYqp2+X%P9Q$&F z(b(QFYU3y>@K*Kw{U4Bbyo)g$2i+Pe{2v^5t9@uVV=*Jtc6!7pu~fsq5U(fv3)QnP z&O{wBfm%KLZ}j?d^4z6*_HQ7=Q2q^#If=($&H%AEbAc@a(t(E7rHTa~VbYku@GgKI zvkqDBVH4SoV=xe3f8Cg!bIdx_i%5lx^${*n%?gYCAVvgTo;*sL%L@bBSKMW{z#xsBF`G` zH3r7O&_h|5+K;+<fljm|K%Zh0*mesi91>pu9)@!e00aEHIxDeHIm#*U5 z6WHu^9%s7_^2a4jgPXn1u#UrNQkifnT0PS14Jfkj-_|&;{u4nKt;zahHQFDug^Sft z=H2yxa8GFU#oS7?!ilglP}fV(K#(MIehILgoTmXw$@vvPGCBG1z?sV#)DvfR_gl`u zD5tQ1rJj8q<2T8Tx!qJSVhTn4)VM3tVI+MispMOzb%e~Hgujz$M_TSzP>xUgo4$b) z!`safx6+Oo(~$zxHmd3-s-Jx*j3pZD5nS~X`-MF2do`7e{bKUV`_l$ex=mVe zdce?)i2+(pAAObro?F$?SH=)8M@w6ovxKo*9+F^A z#KZFDUc^4rn*9hx95ArqJK^T#ih>7_S*kOWZ@y9X(IXy)#Uk=vD+Ym3Y0zd>;Yrhu zvrQ4KbV6nthQid1z==-`I{8Tqa{+mR71SDVNTOm9&ziL}peoZ9vS&pBhNt&cfViEk z5xZUyhpFIo2+(20rrK6q9ekUUFVcy4Nj40lFG4VN5y5wom+2KVB)@8q!Lq5AET|G# zPxGHqeR)mRqljme_WrGyF~BnT{7#C%`9U}_ZgFCU_Bt`G@H^xc>&-(C{zLqgh_{u$ z!WRrVd1ZcnX*iZ-q+q*&&z44aRjEshBHmTL3_NxzsmwdR-l&n*eF#h7#c+1EaO&~k z`)ECBAe^lN+-r0Y#}6~%XzFJunVB%0pS9!JheE-~vACaz-^Gx-ix9q1cNZCQ9}<>G zXs{}EOXF*8>T)GG{Qj+U)mUmh|DPZakky4_?3dysNu-IW`{g>*wjMiFnO3};BgjJ? zK+X19@;B(bCCagV?cvBI7$AIC5&#E%A?S^`9RmA!C<&Pch_pZ@RKSf(99-exW<%Fi z>e_@z%dCeo#>DlK+#VviSq(0TAe(EPl6C*sg%*R)z{#!IsCb*71} zx5&}x%VzsS7qZrnBd~B@DFaa>JR2L705(yb>RuH%g#q&}@@OV{M%>&;-2aj`#acf> zz`AEd+eE9^>rjt%Ph=|UO(D;EdATog8gv1_h$kI%zK3V?$+L-?D3OEO0e=&91JIDJ zYu0eUJ7^NaR}*B@aj16@jrxXD@(D5@*A)IJjb`ytT_>i)=moj>lYyjUM7Slc|MdVoN3nBdsxq-JV^mP&38V)0UUvc|S0N|gQIZ@|l77tK ze{}1Kc6zldE9Aie2yWdwlP!o*Hz!I5G&2SaCwa6-)7%jI3IU9SsZq zHi{Lkk5fV@g2O@?Mm3ZG-sW^-wZKY()0yHyXDU$>F_eZPVU%Y5KGH2iA@@%>g{%62 z<&yA@45J}4bhBREkCEaHF6o48qRFSANI6tEZp=M%98y5uUm?d4H9jul2%($St z>jz;gLR!gmw+om1LjcjG%!vaZqZJKif1W_OK1y@L7kD1 z^O#Zb#`WBZaa<2-4c7fY)>*Zp3$QG4NL@E%v1<}F*WCDH(&)BZpg}QjjScj1SY`t>M<07CJAU>4d3P zI(Ij<-*q5cpoROKabZ$rkFXbucI;C)8@P;?ytzsVDIDR&+!&#Z$Z7BvH@2)v}g z-kJ0hMR2!>tRyd(&(FkYd1DL*^;rd3Bf577Rk{k;Nav##5Uaxk6v^pfTT!kI6l=}k zHBLf1sE+#p*$f>zI6aqiTU~SxtX368<)K$Dn zHM9^W$EL2Uu?koMx0bi}J8 zGV$t&OgtN3IKCaJfV^%>@zL1DKSog%=A}#T2T<)*SoKVv7lds96qRJXMT##agy!Ql z+?|Q#EWFPNTFmqt@vWG5Y}VkFZiy>OdtRR!*diQ6sin*pBo+CNz9TZIDtQ5OT*eh_ z?wP?uh39y4T~k7k5rQjeQ|#-Wl}J?7S}a6}tbYvQ$|uh~s`Za`CN7rx3q@_fvkda^ z1uk~px?!P=egvFs;?fP~ELL4iv+yUSFHt+Jk?3I54%90p&o|KL>cYvjt~gcRbixwT(N!u^W~gG)nAw=={n}u|ojLH>C{47)mx> z!`oyHi4#=B6J!5q;SW1c?4*xgpV@h67r>m(7F>e=`jwqk4^UI|?|Cnak3+QP(ntP= zSNGM>N9}80J-!-X!>b?G(y8`MzjoFsTOVdj<_ITm`1(!0C9VlJX7?WSrNxDp(Wbr) zi*qlqZ0Ugfooc_kW656Qwsve(v1_umt@vZ;!L4moc;y5l8jn*~utuX0|6Cg1^+r8X zLn-PnNDc3LqY>h}4ToNhsn~3jI0~Dg!ZryHP$4p-K9p4k8UlouEjqB_+i(|1$64InO$4cCB_*&Qf{5a{4pnQ7%4H;Xx7Q!-m6oSiuelz z?-yTUYw3vRlyXrdKNcDz@$y-4;Ur5c~3ggi+64?DTQg}%RcB3P8U{}X} zVbgX}v>Us?9JLh#WaB6q5yl?y9-{FR%mywJXV$!V2Sty7U3WhV2@7nD3o*cToO#M$ zSO@MY@YmOsfWf>k(s;dhHUg>VX#7N(mB`Tmurakl8YuOClPC&eaGk^%LVlbI2|Xjv zkjXw?^cb0k2$dO)^C)KvZnDZu-p(4ObB%L0HU2Vge5Ft4T2`=bUNuk(%qy(5_H}ec7z!Wpn~Fp zxG|z*L<2a=7)KqK8J!O3fG{r;Tn1*G(fG(1Tpsy-Pu0DhbY#?dpWp9~-wU7ObZw_j zojP^uRNY!=yxp1QUpfL8$Pu}Gq8X7(V=8^f5fe>*TSLSRe5pF(27F`KsA2i#4JbBD zUYM`0mGEM*QbQyeHVUvo$kGhy-mW0Uz<82~+0rocB#s5mhzZ=iom(i5b{Aot=s?L- zw)Y?gsrfyHnA~xd$Ma!6#`#jjn}3&F1VW(i;&E~Kf`cS+PYLj}07B2lVH*W?QJN*|m?8{aRnDYw_sfl44iLV$^C6ekyz@wkvN=#9{4o7ItoH$eESm_<^t zIGcO(l{dab%F&}*f+>U45`wJ~LA0lB3x+d%UJC?>_?hOTu|Hxb@AjxWeJhx_TaCk> zlW5mxcLNKbqzRi=mk0@oxQ}%yb9%~+9O;`3U?GKdfw4BtEG(4!9-POlMxy!6Z9^{AeSe-WjBBj}VxzHfz( zy4pZq!&sME>|hArMM^8BEwI@kHrUC9O}1?3ae3d!ODvK)CBEYChUnv9xD8-24u%hu zPl%#J+QA}6u@->FgES+eg%>AQRThlmBXgu)jJ{$8E7BlVo?-rAIb|;a{v~D=fNK=< zl6Ir{!wz-~wH4oz&+w&OAlt(t6Qt{D)mAKSMvf3`xDT@fD7}|HQ*R*yM08&+t$K{9 zkVw4(02U;IK=?+=&Dc^LiNye@1jcA&#@tCPXkdlsqbqdnHr;WJ8Li_tmjJ{93ViKx zJn%49O2up!k5`bD@OhdX{2B`*XQ)4Eyb;g#mEk@l8NjQXgHCb$A#;8TsW;?qja&BV8Etw(~a!+kuYj3gzV{( z&FlXj36er-Pa9H(=x6dRW0B9u0i?R1^)X0YxPdV8dOym)RUNf z=8!&vFkodJ`X%xK;d@Nhp`|08xT_NYhWzx2Gh zUP|iR$|kunPJ^G%VCOXQZGyZ|2BZvTlhy)E0^lX&z?7!!>sU?aZtpYrD7YeyP!lbP zqx(N6{RBx8Sfn_Z6L~vKX3$ z&4Cgx`E2MhtO&yFjoiz1Bxtz^Uw;N#_>8;{N)8gaUr;7^o%09=(>=7BO|uEiJE)rI z{hEH^{T3Q!s~l-Z3BZCn(0KG1%}J7qF+)MOKZZFFuzY+D-FJ^P4tu&Kt{ffrql-St zoO_%-u4inJ4DApS$^MEYyYL7ak{F;o(DB^R6X=HBLQf3r=!HTF%v6;?Bs!i@0w7}2 zaLh$XPsHxxx*!&V#`G{2y9XeW#iG9h=NBk}fU2xCJs~|+cDvjn9=VD99EQs|rh69P z&vdsdr}JM-)z43_xKcBmb-h+C{XT&>A*U6gbPFxGIl#zBF&g@IQVKQGr;9>UMSjB^ zuS2bo!){nfOJ zBWraMGJ0rGPcy{@H1N@Dd2TUp)SEd6u`rL#17Y2z%nJ>+CQ~}!x&7K*S&&vVM~1eS zcms}Oc9+Uqa9Ob)$JwE6NX^jVJ5(NNhGvc|_zvDJU>DR(uk7Y2$60Gk@cD|7hw~LF7e4^4Dq@Z?eaQserc#i?x#gsd? zbt`a^4;&2US54%hQTbd3=aNN|pHcmAteF=Z8;0R*6IQT93Am8~OD+1lWEm9$Xy!m% zXnT-dToOe)T7^Bx&)Dks37-8`WWSeBLZ6+XC1Ip+pJa~1pA+aRd4%O0!ccc0(EB87 zoyePtD@R<`VaA9@GWbYe_Y)Yv?pU)ILkN3;9V{dZcMQVn+EnrIB29mK2<=H9`eC9 zEwTf(+;ca+aER%Z6Md}pIALi&eNcO&s!KWBGYbSN=g7pNxZVMAojtR1*cs)|EaxER zz906?%7yPE;rmO^tjX|Q5Wc_l%$fqyDs9St_$= zVd?r^ALEmG(DfaEkq(u~1a@$McDR#IX+XT;0_qSf06wLV599O&=@(`Bl--w)upl3# zPISs*JV%A>bSD=UA0Vc_!!TFF*`Mzi^8FF{y48Gq#Z2`}({|3Gc_>g2PRfU8I6;p-C0VAq|PCNw5hL0ea``N-Ub`j^R4Ch745C3hz zTCMp#3%kUfsUHG>p9H{90^lbB>~ba$CqRM#xMB-|APEvev^*QjOK*Hs+TFQFh71a- ziChM9`K_#k<=-r!ODe##6C6w0{}_w3yDNdZg{mjEnqOsxR2p`>^(GvEhHn!3`x{V> zeo4|%KPa6v3ENqa($@~`32CpmJ;*ReXq%}5Kwpdgj{OYM-bmGlH33=};-puO+VX{mJQI^voHs!X_OD3U3qt}G1+A{5pgZ>VX{dBX5>(`trI)W((YpCSIF08 zH?yv@!7O$?ue5Iigo+v#H72O*u}>VJckq8 zb2N}upMeTG#%qgwq>$ns1G!N>M}xqnJ+i)nn8iP6Lx1Mr3R@7LLl3BIWxMX@`PA(! zQmx7*9w^laKtdE8%DIGvPxPbwJBcp`N_0}MAYO9vsSt#LX6%OF@qBUOQ+v*OrUd?~ zJI#x@?d=_2))n|1OT>|(z@y!XwU`GW0~SS5F~eD`sUpc)QR(*~-sA&Awvv{jfnBOZ z{h+fjHlnNf2*h^;Ud@Z5e$}X$;djV)CzI^Hb`RW7j|Ne8!wi(ZpGoBadzoZKAX<7e zKroBj2mnKVlW5eRiT3+>KNbv_6%e;Q$%Zd^iyZ?)P%O0=Se_lEmcYOK;1#9XyglO$ zmtf^Vq_7smKl$(sk_#7LA@EE1;?Vr0>-x7m@W*DOB)(!6B~ibn69^I>u`^s@T@zAR zN+>e$BjiDN{4Pqulh~(OavMz?sB5b#oerBvLE%C(@ORapV^P7l(-&(OV>y$t3P;Z^ zM@7n;aJV5V5CBO68OMm{ungK{ccOq#O8K-%+#a62#(StQOjON1~6>Bd&`mu(D^)ulPgW zb%pR%vE=6jEk&&MwJK@ReBNck^n#IMXGhdRxp@W{c|s1BAO(wQ!Fz}oDY356i&@C) zTYA!$@qD2tWIBx-Jx|(%md3t|O}wdOdN)3*UKE5?u_t@k?ptss2F+0-n#u+fH3Bc# z$Xjt=WmGvyGD^_mFx0^(ZL7R)Qs{*TtF9fs~{ea!qaQ%V(^Z_ zL-X`nIxYQgUUFnFMg+(_ju)itWyzlihFrk)2QyjJ?d&2zib3soAQwI0j;q|45VeKh zmk_m;h^R>4>box?<({5JcMw}~xDU24vQt5C$e~~GK|l0cDL&;5bTw%>0X$caju*8H z%JGhpMdA=?)E+?+?%ohsWC(3EPLDqMDS_7HH(2PeILpy~=&4lD7LrI@Y}2}uMeWDB zeku7dux~hxv%s%aZ|HrIosami=hfq^Yv*5jZ7*P=3Cf<3gQ!zJDmSN~HL>QAg2heo zYJL4YHHn~FD^IYl4YJ!CQuidu?$Wo93f4WPvJSO?6n@9VL4LQPA48xOeL@s<2Zj-`B zshkip|1xBrWRQz@)SL1~T(TPV8#3CUj3IT;frI?!RlKLDzS@NLTl)Mw5>x186&aXy ziX}Y{W}RlbHo@I@coTTtLIS5KF$_pjHJJ1%?_a?7fU{ynEb5hGU6K_;%aAX9lZ!+=f-FRW`=hXa`tL|hurwv`1IAH(OF&VSsz zI7JXKkzE98^i+IArur!*|G3#Rkz4o2p2kwrtIRkNDySbzmJdtG=hB`Glps+Fj;Cfa zBOcxE{KtwtxdQd%@1kDu++;{OM@Ch-lrIe>;vbeG2*5~$1~cZv!rj8pUE}pLG>29K zw5c(lMoN??_%a^?EvPaDbNS>2W}J&Pt0VwEJ^%z$YtB_m7X+5@K5Z=F z14_)V)$G6-NI1JD+{sds)NUbg0yW_*5jacG5nd%J;KG0rp>u1H@g@YmOjU70FL}g= zj<6&y$)RUewh}){>Od}g&LIawe;OSE3$5Dzyez{Zq`-k|e9**|L=q}3sCGbF&#_RP zwIqFp!#>bw8I7|1)Hr6uqY%8QaO?$QBNpF7@nvMfB>1RLTO0XMXWdf|m6t(uc9q;= zJqBX|i^Yo@WCl%ye47W9*C;jfF2f5l-irD`1$9W+Tuq}zFoq@LPb9oN#if8c!g?+!O77Je5s2FE*^ObI@(C<2P@vAZ4P!Bi-G+&~5&aMKyPbu$i`wqe@{LG| zL!fVbM^820$=SNaOtgzS*_U=xD~`87%>-Kw#mxpTWusiGicUwoQ?tO5`B zF#$qEV2JA5!{c>+zT!9csSC;6999^69mANyOA4-2t*j(?&jDgTmN zK}JmAU}K`G&>YJ>|Al@eItgyDGX58r&(N0yUtnjE=EMHa6sRuBcY)(f`IO_N5up!! z`IG<%gpm)K;G0m%$Y0z?HRAn`Q1h!BnGZE|!6X(PAk%yWAYeuk0N;=v9f0W$<&)P# zc|?zZae_yp=gC{1;-I-1w{OqG+S7|1pfe-MdWypfv;wTB3?t+X0?>q!d=wXh+sSy` zMv9A(Hw&;yq})VFM!=HeU=w6FI)U5s0PE3H@xnFDCK?Y5_B_O!7zV3mXLW8~^89#i zo<}F54!(ylVZ{m`arXxv!c=j}>m^V|mD5JzSf$fjNm*$sZkZuCP|pceZhD#m#hH4-y+ zuyr2V0d<(edlhU`GX22Tu9R^s`7KUa%vNoxuG)jDkw_DF?4K920%{I263HS9Jte@K z0<;V8H&`rE=_>IlI$W%6hsQxMCF*JeRvn^`$Qz-BqtBwLXegjTG0eS^1AKPmT&g6T zvY{4A4(nOi<1zz{bE{xvwTQb##Nkf08LJT|@_7VzYp=##w;y-csN9vdl|`g3TqRK7 z`s0~Q`BE0HfIWy^s|&zg2yHVI1g{Z3wZ~yyiawUEdS0+cD8T6X5aH_5)7)5KncLCP zPh%(-NpMRCdU!MfF-H%5frNc2Cho1tP%KzCP5xU?@~>pxDffy_a!6GAPX3Z?wAh3b z-NIjzjo!;`8vxGFyZa~ZzwOBsAL63-_6Kf3ph)@Pz*%|p{eCj|fFB1RRZ|l21G?Id zl!^Xt&VJQ8pLb@yG{6^jH*p_K)`6cPQhU#02AhyEUZ8kMG$gDQo3t4)C_7M>~d-VY#@A@#e|dIC3}#bB8mQ1W;AwuD+>Cj zsC##R-F?eG(U<&+?NN&rjT-jj1x(Gr%Zmx5f*9sGHLq3n)?ZOM$lEqX=T`#efBlt? zq4It#uf?jSrZ`C}<{ac3Dq|c>>B=8^w}UU3#yIeJD7Lx6hhaCy!M9!_iR17B3Z%tU z@${{e=@DK>^5-mO8kunPejJkM_HN*E7E{N!L*RP%fiLWS zCXl_0we8PY@{9a4Qsd)-7Fh7$L^!_tT6Ma=i@A18IUfyU96+5k@HB48A8;C%PcgC< z$$`YWMQDI`VFZKMJ4f8T2*~gO9Z85iQ1{8_;1hCI%oj{!R)}gY=L@DtQe6UOt$=;@ z$uhhrOskVIm^Z?-1vnpZcErY`SPS|y)A8>zIQFYnQ>}wQhVKt-CU&5RxXT>q-I91u zig<=KYEXvn7R}nw%H^e&4-7H2s@Mq8*ex{+yS4c@ce0p0vP2|_g~2#+cWq1rq^B?_ zYn{BABod!)QgXPsJ^5Kr7T@h7;hR)z%2XbRM?JD`lh?znh`EiLN@^4vg77_uFGpLX zlbxXlOkHTWFx-VNYP3aeCQ)3+GZc#q^z|6C0?ER6(dfIdKQfHD&uco%kqmL$&CNpe z05W^`J_=)f*OGtY5(RAA$axfoHTUtk#Ydu`hqRPx62Cai|DItnbSWs=Hd+QpN)@^q zw1$0U@+p|$t69u_Hs@d@n_%;ph@`Cl@!!$&QKO`*v7Tk;k~E&4PdlOLc%{9CPBwTgDn?w1gk?mO%Z6s*Hsiea%mCzOE`&-kMQjw1_$9 zKU#?Ty(?Jot`O6Ag_3($4uGW^^Pwo{eZPWE`4#k@T99bCb81Rr`41T&xO*RC74JFy zb_j2(7q#{iR*585Uwtx|vXaGo0?}Vd+cqF>OP69fnr3|1&6^TT8=)_zg!Vj1_tSET z?1FFmZ&*u87<=*+&}wx242Drh9k(kx+2J@62X&Tht!Iop1qIZv++Fu7#L7Olqfa| z`t0+NVp=z)Q<+jM2!!m?&gn)v7Q0nGjX7*52|K4c?w}k|g6zY%4}&S;EPjk<&q0Q~ zV|~4k7l2}{j-Vjm+)5-}%Zn`*UvOeG2)Cg%?!z5!i%HwSIKhWhX&Y`5!wmw?13NFp z&czaj4XD){cX`E_jM*8#dQ82QKwRq~k4N2OF#=(s2U1S!J?;u|`yuuZ(v~=zxDpX_ zlCpf-*|7~9f8X5;+z}B#@-|5qtp;>S>S!TbCij?w)(f z=@UIt@^+6EM;T*FMEhxsqyY>M8{$Q--(d%z_P!y#2$YSTw=3vvYUacC3?7_nnQlotSyF#7aSN%p=$?M|0)o9wI$1$hNYabf}&r;Txv z`a*dN&PDDe_H31o;UiYb$?j$MpgGQd*@7GX&dA-_+xe4Wu`Q^(j^4SW3#IqsZ8C9k z2zT~}#I~qxmClO5u982}oIyBV)Qa?7!`=n1Y4S0L^ew8Vxdr{ryT6*cxTFgb(ri6_`-44~(z zv{^`zhvUSv-oP2;h3dlIiXyH}y=6h|d$BGXxY-8-6<_6;(3Q1dYVks({#iPw}Bpr#is@wJIukrj#pTr)@tbr zTUx6`cj`nRS#>^a~( z&A>rkhu6SJ?8mf;`jL+_*>N_9#nOT)82NLUy<0ktex&(Sbx$KD8nypYrXek86^8Az z)H{lG`lGx%se!G}V<*rlY+caBk+S+bzi}e=9}uYw7ClMY*%b~kML}}MQ94DK-5o2Q z#){=16Im?Z-b}POS4`=Sy)1g_PC@lo$bdi`Z>23c;OFv)ZtRe9o{8wm#@Z;qG9GON zAGXm$Y_fGwR-E&-ojN%VZyX7o)q)pQEx3bieb({@MG)CA>`E*G!9>T>*SVMDq$!h+?9 z<0-NA5=&*>IqPA!5)gsuXd|!yUvQ>Zg%v-HdyTL)UmifzvOJ zn~WM3ekBc2cA)I1J;lEAP*Ct*wV+A7pkf~~%t`tSQYoV(p#y1=2PC06dX9>0ia#xs zFQgy!_OgGKFJIbT7U7RGNUK8uVF^E`5hyozf>|b&YO?wID@K91+nn2UlL>J=|TCRiIAiU>K<0tntnMO7cPpG_6{gvT!b2!GayhGRLsj` zjbyYLad<+P@fAcC0*Zh1cmvU6IlCB=(@(I0*(xK}(5p-Nwr;8(;<09iUWH@|U zHM*B(iasKGH6pZ;MCc`c$Rv&q=@}y$ec2C~t8V=JbP9|{v7Bdk*Q;y5?plf)a?BUE zb>Plh9@n1_+dcX#*3UDKuv-U|zz&!zacBSqjq2G8BctT!+XnK}zq|oBe?)nr;hu#q z*FkwmLm)(P!ZwYgp$<~eCh1AZ(brtMz*@-e3zEqfD4|9;pcuIK1(c@?r20WM?p0h~3KqP>w-m>{!>^6a z!M;krYhw?IYhznWwtaO>Yd=BRJGg5n_p8$+w41Oztd`)9TDu%e=vJZ{7al;38i`JI zSi;IIUCcn|$Kw7-Ny63HL`wtDfWy4J`7?POT7~;2!N4+XEk^Gs*%Hz1mqg9p`a{_R zwd`JX3mz|lj7w1heawjPi_<7GeJ^Spwmaxg(*G5l@{h#1p^ToU)3}RH5<1xpDIvjEcWwfN;~QVsfcjw|3hGytKsGKiM`M=Aa3lCRFawgr?DbD# zmiCv$f~};5{g4^;jWh<(j7T&99kVj(eI#KvxS_u}c$}|vsdP;@Q%Y+98-ldeh}afbX!=f=@g5@ z4V)${{fqPHp~IoEf6Slq)Ak>e>|dt&QTY{QHyb35q&Ze%&G^M3x?^)JMFI{_WL?6K zwj@6e=BQBS(5l93;Z~{3Ncl~^bRzu-)z4&xzvkg1Le=n4h2t6hwm($q8a0HHv*uA8 zux6ecejg0+j~}JwGpOOf+fLK}O-%JoJ5aTa%p26YBXC^wddTDqDr_=S9!_zZH5@a@L zbPR?XzXn6C91Uvq*V^?}A0GvNqQf{Me;dK8@kMJ#t(_7E$(a_e(ebb3Daj{Kyc{l1 z#(;mnT+wil50wtlKl=R$Zzp~ahNWt_=wBp9qW)TbqU!kA{7nR}#s}m#6W+n)qZ}Si zxez~cL@4=Lyap*0e|iDf2+@w%rKF~VA9{>M>s3GVL1spHe4ZK)a=BkcrDq|s@Q3JB zsQI;YjQ)^L^{Wv0C_Fk(R3uvM3DG`$YWRSB?MNRV5>DAz0IpP~zi;{fSNSh|%`LNn zOVikMZ#`yZE0YRmjJ;+io~hw~ca41AD4j?TkyvI%X2xWzDYed3TQkX1QSC~tN_D$j zHL31&cWQNoXD$72U0d%+b+4|ktgflI*QKtu+uhch>IQqN)n!kuaobWojTO}msh+w@ ztEWD-a;>$lKDE5w)|BdW*=lO5owihfQv67*EU!G z^HjT>Q~5`t{18KWHmp9?SpiMx>6RYK@4|g zF;Za%T0i-a!Yp&=Dbw?ov3LSMhyc+W$!$)nz?!OETI&J=K(*nx3hcvZrKa zO)=#nt`AOPeG&`;X%>^{XSDb!;?O1%i~wmCqI`ewOG!@fy|1sEoEmeQy z&(MA>Qh!+T2wUIpnFVF=#Fn|*kNMh<1=^1l>W}Hb(T3Lk}!nw26sJU9=xfp`x1@#CB|K$kMoB}_II|F|{zq~H-%`kEX!y{GNWCG-7#$N1VbTQz1_g%< z3B}!I{(sN>g0cC_7Uj)bWN(;u4gR}^)mojE)fLlBP3aXT=B{&9aE~b`J%=^eox+!v zY0qR8_68o6nPE?7c1X=%_%Jb`miC6k)SgRMbr~ znWp5KNVk<|P05-(CCkn{P}P(vElp&otg%*k2&E|#|4aizGbk8g^v9a&tu>W(_BGQo za!CC_HP_jur7>%jXa#>!(vfAp3Qk#j&onUIR}YEAGW&6F;JDxDsC4MH+Ag}=&H zUFEJujgf{`*O&%0`()FUOxqM&)|9mLDH*w}vBso|Qd&9W%31*-EUl-UmFgcu(RQb` z96=;a9{1Whn+t-9_G-#tRW;T1Hb-f>)ni8s)p;-)qk)KmD=ka_Bs+otxsSeuW?y1HBx_+dg`t9Ydvc8fugpXO3FR(qMfZCkIROHHmYH@ z6Tj9qW@ePuf%ek!b>Ogq@y%7IjICe=>59`;uTa!F=J+T;AJoUBGPAz9E5B7TZ_>|q zDbwfWDK>}I>9p5)6l(efRIN1%vbeys{+#|1QZBAdZo@`!M_(kw|u&6>s!&}W-?rN}W^i2Hz^wdl3b)bgx(q6%nyGyl# zL7ZC|oQ5#E)%KveeGXaBsrB1ov%VJS&*Wlt;6e zqK8TT*SDE+fd39*@;gjvRe!%ag(>&rx55Hh>F=5H6c1O}Lmf%r9Yk8a@3=ocGp_ZfGG4T(X4JIahfuJDd~19#23EC z7Y_E8a;d4a*RQQ}qMhrMX=q<~xgKc&d2%hd5~H1npkE?Nu*kX^{Zr#11u+b~Tp(>O zHwjpcQemyPGSPQ=9?$A(Hz@V2t*K{jTe+{=^)^ku=FVQcWX60(0c+jJj^?s8ltSy2 zHagKIeZ|?znbY1lFp`KAx|mhCoa5@z@jw9~s+Rc+8J+Rb*zx~k&`@T3T32F|=>!BN~NNahZA*`#bomB|8 z+Mr^-8{u+!>}$RoJg7qG@OAZ*sA|@7s}qq|t(z+INQB{|lvH;WMjnt&r1jUsRa3!J z@XFX~KtQR-v9`Vf>bXA=RTeJw25#&q*D6a2N*67+%w4c}#&n*Mx=E?vF4Wh6R`fs~ z>uWI+wA$)1V^ug7uI8!r2VnUAgg+YNlG*cSq!#DF_$K~vq}5bBw4Mj`R_d#5)C5Xn zb-e@Plv;@~#ZfOL^+)7@Cd6<=BBMa!EA4gt#ZW1*zA7-t01?%Ww-B#3v0X@Iyi1DS_RzVIKSp}z6Ql&_^ya+wkj7Y#QaP8Sp&Zz^k2E%adiNAzN- zcdxBS_u;}_TE5n^u3umf%BiwJ$)OXgiTdMF@9&Q%eKJ6e-7rmYx$B|EcrLYQSXcFR zt{M%y)`6Waq3@L{2%J;ZKlKi4y`u7*^dAk&7|+oM>+9CqAQz~S17_BMnsKdN>VQo| zD;Wb-&wxa*Zfi~VVJ{S*^pb7?2Ez&hqyK2zn9wo16_H|c7I+&4z$`r%J zzicj53Q$>$aW*%aOxQqV8p2p2o)1E(m8Z&}TKn%y$$2m^9Umeps|P7W-oEyxS~Njj zy{ps>!vc1(e;ZI5o|`LZtu|LJ$o4OiNcF8OemCk?d!4Ja5yrd=+N91^KB%HU&}?ciTU#M|*$)S<;?Vm^U(TL9?TMc0{~h^Q`U87^_J@#PtsHA{ zJykJ2$YGd`DKky_*nI1JwrIwT`AZZrJyASsZ8m5mi1VaISKaE0>bgl}%uj+PSW{iD z0sOR0^3+#QP({7VI?=}Rxhnr3gOnrDe~2DY^w-&63*|?;2hUX#V7W(?P(NQLnx9N5IT$|G7HcqS46?oY`EQ*AT;b7xahj=ILL~Isb;7+BW_92R>M5 zY5Lprq*POi!W=bonZ2@VM!`&!%Z3)Z+Y*{sN=%1$Y+pudP>P*(+xw(zQfia(hj>}{ zGkrmY`|^7`0t-jDhc~h0Z#!7`+CKM*n{aW;L~m#N3P5j?sf}I35)*<(6bCv!zog$- zcQo07wBDC5mEIY+PIla$8uUTH8uA&+HeS+iGo9%Ft-Sp41&(2CLQq1}$|C`UVME=~ zL%j*u)!U8Hq{-K zeUt=@xo;Uu4nON1BPmfqQI6qj5*$Pa8#BCY6R_w{;Ef&3hc8_SE&JwzcMQ58(wW-y z%SNiW`fDX{N#{1?hj+xUk(3qdr1TYo@R|JZ;fbF;-lRah%a{-}+HsxAr%)et*R5mM zBs*@uF8G5FB#gw6JIq^UHcpx7I?vp!N2) z0A_BIb9Li~pJCk*SL77KwNm25!r@KZEyE#Qv*QV}F)Q2wi4+#pH4bqngQMRM7&ELX z6mi!Sj&fw-dIQw3yY5ONGXZ8_8PBr2M(~s$zIXcxHkM+I;8CF0Qq59iuhL|7?3)=| zC}kxy{o{z7aX9}UXZ1+GDEPwrqNL&O)degubj-eytoyV7UR99PWLy)Nw0KQO;Yh~> z7M-a8;}n!5{epF0`ET+Wue^2P7RdfKg()imL+0q)jOa(99nDEWvw~-@3>@KjttcR4 zNB-9xQj*cF2fy7|gE^jvMH&e=(6>p2`)2A-ypV_+B@1O!f`iG+&FxA1S-e>;j4yM~ zY%d6JmdxQTlDWGrdR+Xqn_DxsNiFiO+--@oquIWh8QTIe#N=+HU!!O1TIg30+V)p{ zhi2;b@0-b#zTT64?PHQyh_Wa!>c&Ji%o5xoA@q&D)|q|1zwQfc?LM(<)le2_o}3?s zzBR- z<@Z=eYL@gx-EC~FbZuPW=GKR5*(AxUq)Ht`+YR}ny-|fVArIQ6qzZP}@^QSrutNGc zp7{UCS8RNww=3~21_~1oHhr{RIwbD`WotH;_4U4eh0@f1b<84VHL!miIR)u66fu*b z=qD(5MPYZ_NJn$h1h!w^+&aQMGC$M1tgv|QeXEKKix&(pV@V(WR89`=c>JeqVt_a4 zcHGVD-QAVJ%$ZN*f6>8Gf;$!zlFrn1G>@5AxLY1xHm@*r%>6YaLnJ}(e7mZEB~=6( z*HjGEWh`DJCCYb6hnlbH>;37KM`eA|$b8v5!qV5fv9CF4r93j<=#>&jSf&+DoAZG? zAmf9^_M~%6+9My%dpqw{=}=#1lg6mr zUEi)QkP=6&xoHjMnuT1+g;6@nbq=|rP$s1nG~UK(G_DEY^ig`#75$h|g_Jsh(=;%3 zg_=6hmwFhmM-@g%!|hMyhk7B@v#QOkyX9M!q_Ct$)_wkRyY%pb8y9B4IUj24u0>xrjtXYWL?LZpUSzG{N;JnCn%4; zt*`gfJ~lqg8&nuHXaB08*-?&_@%x7}<+o$*%Qxq>AAu%EnN(iaw|#w=+vFV^w+BEw z#*VlzpM5ZD#D`5skHoP336E@OPO2XDb371{VX4)Pv`9&d%^$gKXxs3PF2{>fdwe=e ztY+Pr-zHV>AC_e0ysGk~TKztQM;qqqx2e>93Q#BOHllmOR|se9gzq zU>TDi;~nl8gHe2a)9uRJLxvRYW|H~j@(}dKm%a&}6KWn_)_0-*-$utU^v)s!Q$9vJ z^uhkLphhgQd29e11zK+Iiz=*@hSvmI9%>Z6SvTe;oJMBg>~=#8k+M2biZ?{v)C2u>g)ZeFS>GRWpPz(Rrd)7)6&548Bgjf z7hVM)o(;sqZ0*2Q%Q3YV48--xAY6A9%$c*>wL7G|Ksq_Ti_#X%&vdSJHo9;Mv0J%( zS3&+9t@QGO?h|(v+~7;Ugr}b}ApKmV&-P2tQm#2?@UrV}ILq4JvY7K(hm^*;b1!SZ z&si2xSO#ACP5!h4w097PnDSQSTftICyCpA#wXyDyuh|%ugfwmJy3ljJJl)YgJnY1G zFm?xC_N9bHmIMtR-vK+&`%=Ns1-X^CR>E3J5^Zs-E7w(3fIbD@1<#TgmHF;hqD-0L zL%PBesmC!d`2ZZ0|n(RslNU}^-!}>5{ZaQ+C zYnopuG+NSxfYfj*nGLJXYkf)J?{2%RfQ^lgkUFB|kgVuPKq(;WF2LPP&Uz0Jn+CGp z3zIU(F8E31*tyqNMuhJ;v;5bNeuMN=iGJA9Ru>ap_cf6qO*EE}i<~!jN&dCtNXC6dXK4 z7}-f_@|f^Ci!nSZV8ifx^Kgd(a2azX_7!k7b6lij59WuS>^>ox2zOM%*C(Z^ml4JW zg!NwNZW|HKyv<$V&$F>3LIXMy0O>+I-zgdmLGJ6CEb@F;{E;2uPu=>zPhj@ zeqa7SPfAnRN&Sf(H*Z|>)rGf?Y>02+`Q0;hO*`_x@k*vIFUZfYDVQBHn+;huo9&z~ zqX)DX_`+`P57Y5j{6ski?O1sO9gEr>-3zR8)%)_8ZYz3zPc|T&(^YW}sbg*tF zd-;~@nSP+(TJ7&&SnKcqYLUM`bx{7io&ND72jP>J_{ZlB!auaeKmO@K`D+LHcTs+7 zjo(NtO2T#LvSi*qF%*kL_>_PM{KDiy`{OB9kE{g(Vpi+>qn%~Q-Zsl2rR^+WGu;J4 za;4eZW=bbg=Q4edo`eE8hcTrAa~Jwee_ICp?k`Wo6=g6s7j6k0j+?W2i{UUoSd0ZM z3tTH~KRxyXUhR*liFHf*2^hz*@yYl1(7plH@`Wl1Co1FbzVSnXH?e(NbaKQx&g^uRvn8*{oz7Xrw1e# zuQ~;g+<4WQ0LkU5&J0LymgfC_jnpD>eNN$_zS^&xIQ{4eTa)(sc z3P|p_>e>Oxy{S4cAh|QD>jETqQFYybmXVY+8Q!0NyY_(})BzEF_sk zq!m&@I-Mqdt^Ac&ZezrQDV+&Rr}W|NJ|Y>J}@Y$rZwje+<4X~f? z^^GMQwYyea2=v0aBzu*;)a4sJ9$wKVkhPCUu5qDyjRr>wnw)jVBBx%{0YJ$D|V@3$&T z71E{+n}g;+mtqPQs-~b*EkH#dsouAurP`_5sJB`;a-^3yy_EwMgxX-Z$Eof*VpD7I zwnJ_6RmCH&JVz}fjh&^^g>nB%(?OX?3m`T(ZU)g_TFbQCQ&c)5!92`$$rbg!l1(jM zbBTlM%^6;bZ}YNCXzoy=+s(?`sm=HIM8Ds?zRQ=B=vJvLGd?dEQxE$rCrllr{R}*| z*=;7KojPYe67C&TSy^rZT~r}DMM`Mht^#Y_ZoJ8wGjK*!D6AyUP<;n@mW(K=(nnUHqGNS_Su+Lle!Bzl5Fi=g8o`xf-ic^ zG==Om@xD1=4(6$K{>$w)Rr7f5PNUStzf;eD7yit5*<`ATwTF|CqlHW?ISZ9OyAFm3LzN1bciSa7xCR&1@|UMVTc7vtUg z5v)C8kU>nPh8|4QSQhF!+*1%NxYDK+1hdJmOeJ!)x|g80t{=CrTDG>|jY_ zcZjs*<9+_VNyEJyBVHfg7G8(TMUt}--T-f&M3BykvNVh^B+6QkHE6w}^N4}6h@vRR zlM@gRk~RtbE}SCSenjhiV&;of1r*AOr+hc{obQ8#A;@H>>QVlNzI_G#%FEkN(@EFq~!@^H7-dImhT z2(3yDy#_4*8Q<*GlHnEQJz2$<`Q=rc?N_Uh_~=+j=_`?zJjF`{8Dj}u3Hv+gym1Dq#BIMoHlO;3lwo&qwtU7!x)A~o5+Y@vs zE!VNKv4rS$;r_cVY|dChm|-Y!5j|-16b6dG1$m=og!lsmfda%bMa@S+bNDX}} z74f*xZXQn!-IF4B#FI<)WI|fxlb9K??dM}LWR4{=6)0keOkw5AeKpG? zHr!`R<>3_q?QAYxz()idzF-Nf5?0VJ)vb;Vw%L^1 z0eT+Gjoo6ex93LlV)f2E{8HJU5;j^tkQckp`54}xPUcuSJ+h^x$xb4q=~JUEYF?Ky zYKa;4Mt##y(5%9Q7>oKGC+x)K#v`M*JHR)4#VAD=P;N}>G(K`*1(nWEh+Vm{`>R8j zIs@O!an(nqsM;<=~Kv z1lruS!Jct|X@3PrOK~pESa~+eHN?)?j-iJhIx>~AqxtHcTTGPKoJCQeczm6w-e-um z3~W_*`-V@FTPm?0w6^EAv%S>LAhm=CQbV~ZvB=QI;_E8Em=GSIl3bKe4{TE<_fnvm z8e*y3n4#@}@A8DTE9Q7(+8M{0Nr$OxgByJIdG8@=-;nV@qhdW2Ti>maXHXF;Goxaa zA^J)%?~v;?*Gn#9vg9^bczvXmj*}-VYL2ohOO!l@M|0ZHn;og4AC4Pi&u?+sj8VxW zL?@vJ#@JHGMaXgWSW{}~#c@MXX1t8nRZ{%&H_1~xV2G`&{BhjSF%1Yv?wpQEkiKWn zO^R8%oX>Cc=CqmGC$(SxJ4&L;c@rpMMvALpCd@4JZeb`5F>CK48 z(B(Ad`wP2hwkiJjZim>Oy&HX=L4}l)FDT)GT08AsLQByHm!ka?|5|c# zS5B-8rGGU!DQ4<&X7`&mdQI&)2POA#Gilq;4L43gDORA_XEVhH6i9p7;>co5HqjQF$KgUJ%%IyjAbl*H650p&m>Z9E3Gw3(7cb0E@!W_#3 zE>Rylv9`b*ozz(n%kBtzZC*=Tc86QF`Bo&1vB~XH<&^03j-uG)Lmev&MN3cdJXeF} z%af6kGjzabPXv#eJIiZcwcUHvymx+WxtIBO`@}>9dQg%7cyen&BAzE!prm`z2d|xo z36I);ne1~PgNFD@g1K|OS$oatcI2h8T|!a??LF4SvE7SS9F51{nbb+8Vj_ns$?)h6 z$x50Q2zv8 zy9}}aikb|dG3vkPo#XF#)J8R=WW?M`j3#(4GsZx@mUoyZGkV!O$Tv0I^NXfz)qH6V zMu1-5l;cZ5z)Z_I%a$t@$n6d%qh_ z-m^tGxP*lE)XC?w&*>*{S?KH=DPq4z?+PnNZ8 z6ivT7B?zxG_Zr{q%|amGTNb)5^lCDd8ckVyvgpp{lxsj`+Er&cq8`PXuIo3Cn4+(# zKWi~YGn*{!nbCZ3ojE$-nVsEFz`EGb=I~kLoRhbWN#LRz2h8XxQ{40kKSS3zv1sK0 zC@u5Ra!^Eg%-AIsMt$>67-NP`r(;4YWu~Q)8B$4dSE;F?o5xtu^h9RN`TRC-J!U7F zklIvM5U5f(*iBq|Ik$NozULD?hQm`><(c^8*i+f4-^oJCj~TldMoB}bR2j2DQb)}o3SN_P z)Z|oRa%`hBKepb^wBHOrZa}c1A3UCIjeVi&%=f%vW5GN53~EJn9w6iN;+c2 z$Q3=3fsrEz<5ot@+?LtSXN{|Z8K7NrY~@O4^V5(c_01nP1XdY4W`Sn@Fl>y?qUkn1 z>h=v|^e8nZs#@ojWhV@=QAqLkl7^U2W=uFRf_x4$y7plz{YRXq6`~C0F+~>#vkk`WnY| z==j7{0r$1_*YT07J{Y<-%@K{EMh`TO8FX>KTI!o zZy9JVY@UVO2FFQmxO(5!16P+^bJak~{r#lruoztuToM3+9&@|d&7v0tE$tMQX;EhEDOvD(nHpRsiALU>|M~G5$ihY z%o562e5%}>q}ij1QHO{G4~Bo-``GnuDv}SYeX!0B6Mx{mLI8( z=Dof*6St}TO5*go@X-aTPV4{SZQG$4CXTgp*pUqX0Llu4-@JcTmy1HO*yCvDZ z#o1hM#)yBiJ-JRUgDgtjF^)dw{rOP3f3-9$qZ!@&AjIbbi2x| zF6eYuUm5ys=(n3Q3$rk<6FQCP=gYl$}rL{j#Eh~ z@tNVy0&`+saR06@X#W$Xc$8-vU7&*0kY(hrNq39bnE^eYEq*!%E3Ln4sV>J(szK@TX6%OOlFl_@B2OMB(9cvG1Kn}kw}`Ud4XRTro|JyG=VqQZ?h<)J<#%Mv!RV-Xj;erG_c!YZihZ}(hS*agw9B1EMe|A zHel%Tv^=mS;yxzi!=m|GefbH@{lvzWOyAbTheg{Jtv3`37>euf)oOBbb@-CQiu#_zAQ=+M%(lO{( z5Gko4&zK2P-W2_zPdMHknjCv3sX0lLVcXz*>pnN#bCvUMwAMgeOU}o5bT~a4Vch66 zK(fs_OQq{zH#_Y8*l{W;V2tbzoes4p2d|qH^;{=ZIuZ@nJ$W6Ul}*8{EdPWl_LOsC zY?&0Bn3rY2%Js~-tn|E$x1-)^iawOi$+OvjxmavVcC;R|u}nymcgD6kGP`o3q0N?9 zE8ew&g*+WN#HFS8%mMK+T#FD--qm=H@MXccGsRsB^fJs z+xDVo!o8WTM$39{sW(Ej!D*@XZu6FTW8~aWj;E~RuaM6Nz_VIUHgRi{?7sJigc>h8 zS4Icy9k3yi$3dP*Q}xC*Z*CMS*VyE;;RLyl`pgLn>gs4^m22qnjjZDFHOb_`O*G3K zZ>heax|ZrUt}n1w)>G>m$6B`FousJxRBI1rV8=EV2(X1&dv~gL6>_cP^c^%?N_1dW z%KH0`egJC>$%D84Eh#oxdo~tHBsB05E;aP0l*z;O_W{*!9#oje=C$??_0Wtd7?FO! z`MG!|-RJ!Yw9Etc@m_}B{}bkk6u-#6nLbS7&5}&Yp*bX1vbOsQD9YdXO^RaIQ>pDS zXtkH@5*C-)FLz46E4En|Zl-|T3~P)fO=nwxeYGX z#wqprl;jrMa?@1%Oe)`P1e!*SB5h+-{EW|;$af1JM#%3#O6;QI`>VO7Q;JHlhkdr= ztZO3e;uPyN9yWA{U9Z|wLyJ-*I|j%tx_JJ(Q-wj}A?HyG;S>|Owb$=79p?ii|Ctuun8Iu4ced?xkR_GDpfVTmFIMIN{Y>}3G}G%FDHzL zm(qZZv`fZ>0psCo3T&TWNY5licP?c0yU9$q$u*LE7xWQc!71&o!ogb^Ms=~_<;J@j zUkdFAiJQd`r@3K_ErrV$VIV;ddf5U&h=**hHI?>Aq+&y)bZKYAMG=p!d~*eCL*iEk;k)nf72kwbvm{vN%BvV9%xim2^Y%b^|^h#yRiQbD*JXKRVw|l zyQ%Le&+QLMZb9zwT@@FWq?QzvKJ>>0L1eJ8B52>lOAU@6^q@_lH*Gw&VZ0F1=I&%! z`kmS5-&s1|jgscZPq(!BEAP>?+v%l$ zJz-2!{jXCkCgbn;yT?*2o#)G`GLw{kvK<=3NaB6tMC`_NOqj6<)=2*T^QlnbpKj&a zE6JY5pC>1S^RP~^OR9A4;%i`2&&P%H@!_5vg3O-DN`45;N@=)P#ti7K6nlkRHoZQB zmo5GWdW!}m1ae71De&TlU%pRxIqDlpgjZm` z#3&v?kOJ0Le?kAzX=QZM>d6oDv^ek-g0MjlgJra@+Do+1nnv>7^R3oWDUW9>&(YdD zka?!+QvG z=KX4(Ausz**suQPI<3AcWO%!L&UkL%exDudQES+wTI&@VinTUFnMOZQ@AHo)`rNL< zc9!9Hxk{9MN-k{RG;8eCpknsqW0oIrx3jlEGvxdsahoyF@KPUwMqaFY1!5%nk2j*G z5rbC7@1APW-Pwq;ql3ODw1G05xpG32aaT#+PL)tdO=jc{t zC^;hc(RyfomO#A(dOmKhu_~#dd;i$L=U+T8UccjgrXzDN9lr9A z+ZfDa4#fqjcS@0Jr9iH-5!jBMLfgD(_mL4IMeurp#er~-L-AZu94ua0sn}`1x)&(A zS9yYu_==B@4}Co93RWuJYCnrqjwZbB>A~qWUDs~B)^Y8rYl?y$u(K4dELzp)KB&s* z$=tKwMGOC992AaVOxaf2gAe;A9S`@Kf77wz^`u0iYF^0aEvcdR#$|dVnHoAdK9V&5 zx?{y(cstM^FaBn9ocG809T%gI$ZN*>kqrUZ@D)@q=I}CqMudQMSDsdYz-lBH3))sd zQI*eNeVGO8RU2rI#~Ic~KfTAg?fK`qf#?k}bN(^wHLI_oS%!Ej$^Wgs!Foe@h13IW zB~EgmpR~hRQhaRPx?aIgy%KtojB=PFeJI&H@VV8FoNmf7bQdyv`PHZ#v@^AAY zH>@=Ut8mIVdaqGd$^vvf|U;?gT4*RVL$Q?B}FO+-ZaOOusO|p9pp0lDy*YMJX(*>X2MG8-AC#rjLj##Eyrt^9JGU)x}#4b$q@5 zvgjo3-R|H2{u@s>ymsWJ&9T>y9shdk>5P2^AN2NGbMwe-vKTWAnNpURE#$CCfL|by zBr=eREEq#_vF7ih3R+GLw1a+1jO}1dU?P*4k(pT*voaf#Svm7Eh1Um(f+$Lo!C*9+ zOlGsil97>_nU$4|#c-ah5&4>ta|UH1_esbn9H^ zApDbGM)(=RPydJTi_fIJiu>0Pe)E4heCqv9FMR6%KK(QP?}cgq_xbvZ2y@J*1qvS4>bBRAA7k_emw9iuvFDYhyUqX)y2P$#)}1Q9y~#d;ZQ&j0z7wF?E0Kbyp>q3xu!8IKyxketeROu6l<g8VmY5C6@1Exc3B+`5xL z<-b{b@N1Uwd~0|`W~*NbwB})L)2HldbxQeuzw)crJovi#mCWrsmB4nMcBisuJ5SrG z{AxQ-+o_mg#h@AlV9KvK=dbh6Uu(`^o6cXqa{hY1GV%T+=i@J&zxLzG*IHm9ohi-u zuUipP588k1%Q`XGR9=`F9&AE;_%B+CU$k<#cVAN#>$8a}TkKRjR$OFzJIU)dcD{_M zUuITrXOzmbVS)H%id>D&Wj05+u{keeBmd3n;=ehk@M|mF?GsL{cfwb;_jL2O=;(S@ z;nl-QzZ4d+f(AlH{)>?>zplacxHLn zD_P3Hb zK~}<|qK6&I-wVmY=@E!h0AmFmTz1UE0P})-r{Zte+3<3M*ywM(v+-qEq5G=WgGNdbya= z_f^l0?}HOU{5Pwc|K<$d81D6}Lp_{xvWZibU(G1wbmdni;*>=$McqTYe4Z1oCUa$O z*wysD&62SiS4-Aj{+pA)JMO04zM>N}^K{dfoR0A6Cg~zhSErjeUEvpWHQ4lHcrcgK zcrSe0Dqdc1%g7Jcg>6~RoVM`su(aT{2zbSG%dn&Akq4_iTN9pO`9sWP4nH9t=s z>$A0QkFhq^dB6@Iw-kRSUDUb$fSq+o+Cw8O#uk5Udkt$o;&vlth9hWCw)V|2iPQq_ zZ?rM>163__lcen!Q3}Jo!#z89@%MJ_nrJuP*KWbv2hwl*Q*Nv;8~~=xBN|eg;Ipu= z5dMU=jD@M8g{fuq54F@TY4s!JP1)MUvA3|=S888M5>iW$TG7N)SB`9J8nBnGb7ai5 zHHRH&>!I-bVW}M6hp^j<%C9$_qWisq$|~J{L6OQnPH-=^EXr)X`-r&JK&(PMkQ(|+ zN_^B)cxxfS$4Ht_Cl^pdpm&Obu2Hx|o{+thPGq*07Y;T|j2NdICPs|GhKUhluwlHH`^(sf!Pn)%)I~NfkFD52 z)n}8mnzL+iKWxwNXerMDExwRiXbZLOZ>`vr1S)wLT{8Wb8mIePntzP)-);U8eD>}i zdAIR~Mkow3TbiZ9A44KXAd!cAXA%E$;wxeMyUp+~YAvncBh%r=ACu(f>H4<9^2(SW*0B|p1qu!K;KuLCD`QOx3elom|{wEjAk?f(FHPcx_X#mpTl~}4>9&> zJ#&Kh9ucBt!N^Q0YKR)SpFf$RrNI~J72D>@pW8g}-J2HgQrD}(!QByuDymX@3}c2z zHMFfqtRMF-wM;d(Ik9=t(qwu_fLFM*@EQ2D(>s5Nd5@%@&b~l z_n3kiF8Ec!Q%nRp?2r?DjMiwgQv=HM-e024T8|q$(Xd;_1N{em#aE)8siZoKe&OUa zF*@ReXS(!A40w~4lNxau>0Yc;=W5@=J-g&``@K|-*gc5Nb(AzLL29069nM+BVomEacu+NefjIN@E;rB2i;|$j!U|}YF;1uRaceQHz~a~PTKF& z>4WRH1dQ~u1HM!zAA@etPp8*4uL^Cz3UjHn5?#as8dP#yVw# z3BJeD(#G|51^aDEUH+|u8(7ugYAXAWgc&8hmNb{XdLmc5DP^#iRxG~M|I3w>g0J&< zRcLi3T^5*J* zpfMG|W9FaZ^+_XE09|Ac7E}ztGwY^vkEeO%^tvmOnebNT^?q|*P4Xv|F|us{Qzd+m zE}~jc;RK&uoTk>k@oQGEOb*YU;3vrdmuS%ID;BH);kqlI2(Bs-PQzJ9!!Bg)gL9UE zr8Zx!w{`f2j^|^Ku{m%;Wonk%sqR~0tif)RajqwG+P2Ol;`GkxpYuexXK8Th%E%0l zvNT8~A#m24o@Z$mEg+{*Q2w@3(r|UdlMUU9sAY`b1J53wGGG%mar}|b%?+kLhp{vr zA3fKGwp~d5=-kX;Y2a<3^mg6M;KX&t#C2WC`FQd9xF^_Mw?9ptZ`Zlbr^)H->ALCX z<3;DMg)4a<>>MdTn<695U_qd;!J%wYoGWo(<594)08gDYgCPd*CP%PaA+2sWjJAiN z`||b{V@>~ptm61_967EWV~({I?@h+F0HGLR4#EXl!EyU8c#X@6yYL<%zI7p4=Uhy3 z51xm6a#ZdyR8Gd)T&?R|nJU#fZDk7QbI-U7YxbC9f=|OMxPMEBOVkEHQ&=?*ifR9l z=a45fIIP7xoB7&sKI%kY;rhAw6+Ua3LVRxlI25TKBKO=%M|fY0sP&A`XdDR1Ut`*l zQTbK{*YA!BF6CDKWbdf*HNnNSZ;tN!TB_6-XWFAk+jr|er0pCXIRET^JR7)m0ME9M zR*=#pXlqlG+_Sy;#Ab_eVcA;W#^r0_MmyVUUADSt_j1h@ku5CS%N7`25yGz4I4e(; zvx>X1Iv$aQrCvOvxLCn+x+T^9wZ^7Y)rO)y%isK3znEIOs_5YId*Sok=d!j~1iv@a z3r`hSd3h~k{!GYyICF(OG^f&u_4Fx;ykHmhFinG|QCmH93NlW%$I!r=Xl)j+W32Du%A(y(m{}ILCYPOXqm2?j9d#;hr6$Hj;k& z^jImbXl=qfxr?QXY7y2n9 z&P&PFemE9tal^kb3GcqwH@%aVXg^4Ol)M9;Y1lFKJ?1V?=X&@;uJD2{N3MT3H!(l1 z{Fhv<=X3qWXL9}BCZ*-^7FM3CZ69k04Wvtmr2h7wO1KRr6c**jE4LRGSwE>~?)e-; zV~@AUEuj{(t3`?cF{TBD;N6XLXLkQHG3MGb~ib2YRCK7>B_wy(*65MPrNh6amq{AXwrYG(Qij( za9U?mF1}|a(;>^?J%w6bm>DwoJ3tTm{#58T%+2ZLg|RZw%k+2^YF2=KrxSe4>%%$Z zJEPrphI1YshBqGf+Up-HPw%&AX_8xIH!o*2VN=+`GszwJghxa(&w3!Bp!6<2amzJgq`1zr(CW&6S?W@ z1U&;`mqGS~nReybh$j=ChWScnK$PmRp1Z^31Ui=+<0sdIPFiYZ3 zF2R#`;>BrnUmKl3WdaiemrUO!w~P}NNV|8GQ<@O>qX%6p|iCSHjuGJrgClKB9new$BBWRuP|6W`RZ~FtJ)r?kx zR=$j$#rYDqb^A8LFIUojG;E-Kz8Ucn%o`u^0eIAB#aW7d$@z63yt1bvG8U*bf71b_3F*xMKGoee)QS$z`vZU?+I-D2G=IOxt`8KA`YE=Kj$JtnnN=D=Q6(3_Y*3fm!_s z+Yz9*qg_mUam?Cl>QSpxLj%~;K^@$GbOd_}+94}{Fr3pn;<^`iH{k@PiMOy1r6UKU zPkB$Im`bGD%~FOMRP*dD%QKW9PU2|8x{S3aUYx>uiL83AmTD(q&iIv-tTGqB`!Y_D z`8@O=GtMvKa)4pKOfqE*;x0Y1@e`EJrSHxr)4WX+f7nA@!?bT;?zwV2VKG?_h8g%nno8)I=5PA|#gK z*BWOoO(tzGHa3|@i87- zo_NzWuclT=4K=3YOB0@zG)G8yko#P;cVwKuH4k+2TKaAl_7VvRCsOmlhpC})EaZGsFe>dyzzBtbAomy zw7JyK&&M&Yya)-2v9+&ymq{T0_gR|cc#hr5tbauK2?EED%Z}u7l3zt%{?&ssd(ylH zsi0NEl9Hj_$|rhSDek!($c7XkZRzkVbW4WzBaEV?IgrM8b4;X_rPDICMdLgzE1i~> zGFnkOzb}qK9~!py@;%yyA>`}C z`x(JIDX|{=@MZ}KGe+6(r6$gvT2=77iLV3o`1;|xa4-MP4VvWN;w+M&RO{H7&6F=61=5$`TmMigRGdZo;lAem_Ka?B4xSp>>#PUxAUOk zVNdhug;I>4DTO0CQNr1zRVy6-ctW;#{0jC&DLXOy)q3tbV%TeJhXi$BRhxOh1dDfP zYEy92Dob=zFavhBd03Bv&32YM@jc(HxLd8n&ZUy$6tf(P(PQhOeQN!vb3wl$b}ja7 zOjnFCo3gD5dxDEiF|o^`WFANjJpnmA39^NG{*cUQ@}OP9@f^BWJ)V43O(ZF1TSR4A z+@*dFvhF{Sn*nXA!u|KgO+_0|xzuI2e+kd8!Sltq-;d`?|H2@Px>Sa9d44r+b9>Z^ zTI}DBiESJGdtl{VW1B(}j!Uvq3^JiAL9;K9+uYPy8VvYjwtk$rW{j7D`tr|;O#-ad zg~y~An}M?};`5q>*wemem*3*E$%6L6xDaC`Hi)s=B=1#yC|9wd@AW^5<2(77A{byS_seN=aS?;sh-6S!IyB}!42rw zeKyb*Ora8|F)FX4G_CQqSI1UPX~xZ_1zIj zxd=F{ulkRmNo$XJCAq+H+Is9@GC@jAXj=DygRI)rbNoH7bIb^q_spoBxpL;J(m-hq z-}?paEJ1T^i5Xn7C1@7*M9j`gK*O73iNAc?UAH*}k3UjeEEM>QGj`ti%8fL4LK1y8 z^)2>E>MZ_z2foVmV?Q(5{T6)n(;GRzzI@xAc%JX)dwVu|^YHwo8(|sP>fgF^>(7DB zKWfQJ|MsUrzu}Lxo-eNa!;veYy^03}?JHw0s&ijiF%9>(jI9oCa<8tv^Z<(r+6`lM zSJnkq2Wh?~j(s|_Cnv59EFzkn7hgnmizW?x4)+;}z$%*iae|*5Rujlqc;I_97txiV zO^RQZUUzx$-14AQWK;eT_XZ0UnlHvTxi3A4F?4JRzOIYY{6L&_Ug^HQq71dD9J>-4 zbJ@X7<$^YMtO8j6E-rd#J|%=Inp+cRmHkJryl8%)>|j~@es^lY?#OFf3zy9ark3sA zIv1-E!l8N5*};AG`S>kIs6beNP>HY*VG+Vb2#XPxAS^{#7X7v-W}6i_bVEX$jEmXVdknyXa_A zh1`1=!4zWusSkb$`WiqmFpB}9+)`m#U|D3Tv@D#mqvVbUj5nKi2zb793M(-$qUtL4 z082lz*x4+33YD-29fnxuoyEZ*!k#<5o;^2NX|r2xcG$7Mtc~ReQn(!BXsc zHz5yaFu21R+=Gx4^?EXI7O+-43)JmHuM66rM}mu90IzYp|0{muye4dBR^H!IF3A?C z1QrZJOhiL-adlPmCSalve?Gw`dIKf6odWA@}4z7I%9*$>(dj*s_C4rpi=iKVcrGt}sxgic^4KU$VORxq8=*mMaTXzMCadVN(xauhn{WxYvw5PD2SQ&fh>d!-nRY zC$veNSyQPx?S;yE1-lfXTl_O=UKpA4egf-oz-(YcTW!OhLB8ws zQy(zYXn?%bhXDIR+CS_6=e|=j=p?_#5Hzf0IPbycp6=l@^tZ;QV$8V=wA2S3(F`r@ zn9U3CiOFgog}i;m9&e<0Gjn5ZAO!nt%N1*{)W^K!WnMAZM}4;G9X{LLYemr4qbYR9`kOt zM?5r-5`CT+^Z2J@hbz{KmNTy*-7YWAS>&>dr%tqpw}*M+?wwxD`;E~?gDcvQ8rp=J zC3r1pEsv=Y`e_~Cuge4MM)2#q^Su7c_gWS+iZl0}z|yJadp8zEm!CMA#_~<{_ADtb zVs6Akc!h|W6a2eQ<2lkI2z=fKEdyd%P!{FTZa+a6nmMjvqhK_3Jl2 zn-R!|{2q(*T20snOxSxW#zD#G2lEJD%i_-;!H!s7NA9bt_1tqrY7_UecI1JxYQGRL z;IyX;xvaags`ZXCc2dy(a+W-!Us!!b0jMm?v&r9W7oxH4RpC{^E>((IdC#ohb#S45+uG`2bwH|eI-Q34?3?ZR{+5V8csP>s9EK;(`&&hL zeIQ3ew%py2#n2^n zq=u%Y_*~p5+r9uhNq?5R&hMZ~+e=9Yy^<^n{vny=o?Kf+g{$fv^~^EhVZtQVmsvcifu1Fao81Xh9nDMbF>iQWkW*k^iYKCK8^7su4+>Gk!O zV+V0_oVxDE9?-81_=AIv`DKkKxDU(o;}|8=CvzmmIc2~r`0F%JjAM^HsN&o(^SG(Y zpO15&$aR19!hqOrba$xqSl1Vx^G$|6>NrL7YM`557EigMF9mi-=GK(e3awpR=L9$^ zKqFfSmk!YE8T}2_0YA>;jKyq!OlHY-ephXd?T6}P%Fy;dZ#B*w`r>0-X?{`vv%6k( z++w(BO2lrl4agQlZ8kOt`a2_8uGRj@!Ft=2T61egxMS+IS!<_!O-$Y8R7-cDnE0b`Cg$ChKyG3D4+bIh?N zpN3O7KTa%$oy)t=yWc;y@GkETaPBc%zS<2BqkPCl!g&D91Kf6qeyyj7bK5;PK3f3p zrn1pAw>bh5If73(HZKqPo!RwAAFiGTn_os7#Jm6a89!L+&+A6aaN@ah;N%9R}Xt;bRk>v{dkK0o2uC1m(SLAfMO}s6<4Hw$R z+r-=UzjLO+beFZq;t*;i?c7;DCz(~iFm_=6lO8+BZAgzDKga0K`lowr4nBr_8Dj{4 zkIQNJV2v@rCTV{=`|oEN{NQ}bn@G8EmO*)sc@=YC*G!(raiZT-&G}e06^>;(`ATWN z*GA>YpS%XhyNs0)HPfDF&tp#ZGJH%gQ#Yv0{SBYtgqUEeQ|-hleB_QFwW6h|Nnv>V z8DIqDd|c9p>nVH)2M zo*gcSZy0>UqgjUwTC)#3TTNt88P1BMIo8B?Z>Kr6ad>R_%T#e$%(k)h&^CTP+k4x{ z-4)&#c7)x*)3zV0c?^Cun8OQQ8bAaY{_MXbE(&;8+e~6fX?(RR^ti z0ZbbF%WtKQV;thxl80L=GNV^PXLx;mRvT&8jX-N7g(J4(#%Htleu|k(z4G>NRP%Y( zwt+RZPpaE(7S?1l?lt37VFT9lpK?69oaSx#BlfJ%{Q~~i1Em^T&X_UAE%oMh3(mZH zRDDAoRQusM=4{Q3It9^BvZo<5(HCxqlAS&k{XyRroZvT$Y{C-%krl=^)80m28;n-` zOxp`%6+c;P@hK1de0*_pmnCNGFm>iR_IyUKoDIDap4EFTcluf1$*kN#5oxoOpHL2$c}*)$@qg_y@2lkmnLOMl4Ck4lNboZ4Zv@Z+#sfR29u1#l+ijZ3mo)ukuB)@Gu!zF>AXTU<&SG^9h z;pQ)smD4QuFXwTs=bJ|gX)@??GFhV2J<_3=joe0Zgm2^+LXLfk;6$nfTNEtI(fpVj zewlf&!%(ygWqo5@EV3kSO!tj7EwQ+M%}=QOK+UtUW!Bb-G)z^}snVfickG6h#}dP7 z&~KHDT2x;chSuoQ6ktyPYk|YwbVUg>$e;{*>nKhAieDU_B!rCHeSk#13~O z);`~!_JsYb%kMt&O{_18iMw!$0bzxLv_B5J!BU*ksLaf1eYPP{PD}CW$zjf8+{=zd ztwA?%wAOGWah_G_nSL1pBsFwBEJjJ3eeu7NNb-yCB;Q8g@;>GLJE8ZH_Q)`_S9{ZP zrxEL3$C)f(t%2JCxy<7ZUv0r$O1l+Oau8bO9X%M!cBaq%fu~$4WI$?Y);Vs6 zHebQ(YD%9wUk;2@Lw_D;MQ7fSU*r~bf9l;NFQ37bdV!V9 zp}V}!z`Bq#Fj;X1SbJXUH2Q`2b2QI8ALm<7S@m_gp?T`6n>TzP=brBOPg%ttzIlUt zVnhVr??4|s07*8~+gLrRrk(O^R@JJcCG`2!e`QX>0D=I&cdH)}CZyw)Nnf4Fg=bY?K+q7j#(o(XtrEOSBTaZN|&B59> zAnQ12)d?+X0CfV)XbLVVINE~a07az@&LCwR1s5h-XGZNqm04ue@dR*esY{{I%p;<4 zP51o1*J+E+^1RRQ{e0d(UihRrxzBy>bFbHZ-PiKHpmk`-aPtk#&;_w+84}Ti&-w^S zH$j4e6Td#EQ#ig)0T;K~nF?NmhqU;KWpZEIi{zC`vy`(w>Ewe4*%QljZVNN}cZggg z=|hh}2T0Gq*mog9eVlg-Gf=3*)kA$Ep<{D!^C>=T;o07<^L`pj~Z`yl)Kvia*BKsI8Qk$R?} z-Xjq*h+B`xYmqG#yJ6E62Eow?K%nzFPiaJeEsGAkiLpm-WYXUFCmmG!^z20qY_ zL^h7GJiSD6SkW7hcWpIxZD6iq@BJtaBtBU)Yn6Zh9g~5>E>qB=*t%`AxS99nR9WvYiB&Aod2+R%6 znBZ`Gmg#7|0b&*ofN8wIUSrdq1rx)XLYBQy45oU=gZol}I`XM3ss zO@2e>H_|3inD?~t@Qph_A8zpTK4!Bp;-$Dkpq0hfY#ph;h>|}79_;6%`Ca}UkmB6n zclmlEz80Y2GZW3)X#HRw^JNUj)$kEhw=!})-CI&P1yNeSxDU@vz|yFSaD z1P)~n5L=rB;K1as#&784e=3PJary6e1ndDDy`7%t_ucA&oYXEfCP({v6^ox^p5>f{Ry=s` z0CWBk@*#?6!Ju~)qT7I;se{Gf)QYKPjf^W=woC_PrhNCxs?DwWOP;=sMUVAzwp?hj z$6{UN;CeLHMYb}>ir5w^vWbUGa8+*+b{1=et&Ba!qDy+M?mT8)0u7gqqFpSF%aJf_ z;4XmqSq2^qQA(Jd!3GL)`ps&NWIvFh&~wC3jNz>%N2m94;O>&6`Mv*t#9RBn z#Vq?*IT5unY4qe8k4583cGRVow2%++r!@G>o#LXgUP!l!gWf}|N8TUkR7xm%ZIDyE zO|lBeEdIa3;4`!&FHUwd(;}CrB*6Z-nzLIhJDpB5Hy=S3I=8um4;q{XmH`@QW?-?|QZ{>~^#ao;^gKxI47}er`=_gQlZ&g*L$r$8J;-{#9#OqDy|U!=AW%vApV#gs|@74%>52) z`IzxKQ|j!O*%iyUS+`sr0XC@s|BVcB)iRP@j=ldd_z1EAYBP$i)o4kHQGiX%l78AJ zC{GV~4XrzE^uDIz0iYVI%WSMWLx`sIgNyutrB7(3HV(*bdKKl-Gqi8$L7(8yYg4j= z*I8?b16vyh{VgU7*j(H@*4GsxTGb0(z6!sOAg`JozOI1f)x=}h0?V8~qryu33j7M; zd>m_#EVG?jx((woyoV%0Jsx}%Ty z$+0%mGe37Kyw8dXk1>lmrb>%Ng(;h5df%Ki-E*_|PR}plsq?(&gJQeKXm^W~SRhN9 zb+u_NH&qN|Pg7-kvOQe3VexeKu=4?re$rErMr&sN+&S5Lh*OAdMxC?0AP0GPP~wr2 z137Qbx{IIg>CL%|zthu}Gh2Ax^KOL0zgUZU1I=u1&w$$a9?#nB1%*M_N*gN7o~zey zU;iAZvRs0vf_gZyJSplNevapG*h-4dhg2*cn=sJ5-o|cra>1#EMb1n{QtdP`(=(-- z#+VZryEX~F=kDW1lHvwzm9Ai7sv@Wak}Nn9Stc78JjS{hctaIaS@h`RlS5Y4hBxSj zxvW2F)vzCU!Zoh_exUR+(^Ph~hS^du7C)(Ksfx!A#EF9aVdzP&+!Vkw(IJdyHn;fG z$Z(u7!t5lTQ)MClx2J%D?U0O+^W{sxMieGiOoVP>BI+@wTNv-2P|X%m>~EAI*S$>PR19SJJud)q=elp_zQGID08b4nQ`h)Fw2;DeEQB z#t`&C)E~;Z+`MwQ)#ya%^IEW5OTd?%uM_F5jVwjH(?;hTL+co}T>$5Wk~^58%vs_r za~fYt2j1XdDWcf4Dn4HM6J{{JG!gvaNDBM-CZy~wO{>`R<2@Sf$*NN0OUdre(YyMO z$KTBi`ik$+1*>3H_E}t0@g2gT@g)Hmh9jkEKK{c`nc zX=}^)rHk3xL_vBDr&GN!t{v+%QLDW1a$1I(h0HL7{^+StMRrLSUkmHb!1^!*{qd*|0NzMVYG&D{dyc{$M4doXfBR9v;YJ5rIu3SIT(^((?$&cNE zQD0Mf=N%*IH+~$h8B0ImN;$<^%2_$)KZ_cBp$9q5Y);pXl9W=`O1eMl5d^2C=kFYO z{`QYg{ZqNYACIK_KmPom(mO}f@A>$q%kN9G|8F>xO@sf8Gubp4un}!w(S*SfoJner z6*H1>=BWSv-{4Hrv&keLchIo;1{GV0a!sevoAgh`1XC*O(u!Sp+jzZ0W_{6%*l|DAGvAb8sDXInFZ z5IF^|nkLLhzcqdJ=|iQK>7{2ZSBzt?Vb5!Ie(5YK$rtIY`c|?MGqp`*wzaNhCCf{y zN|z+&h7%LjVU{~t$}%}i%1gL;iHUvETBbV16;SOcGMiK5WZb-j(|a?{>lEQsWy+#X zwP{hbwL@)jn}Dy`p@yWXmF0a1Te;3KPLqXyRy#HCsB=Y(_w=(;N94-sd1ovOoN}F@ z9n1RCIS!hZSDhK+sfo`zrGXEB-oioP;wtD9M|!qLw-#C#Ub-dYl1_m&$XT^Y>dQl=8Hu-L zE>w1=NB%j7jkBlAIqr6@UG(@%4}=~I{X|sj?-R%Ce+=YfuQ=OCk`<;{Xe?07(lbbb z9w@B~HHDUmdVQ5RS$~iCNa#Lsj|sVQW-AVvCMYKAXB%%T;a;mnuH~WvxzhDFqO8?8 zyN#3uWOYTF-f65ZnP$8h`~5W~s@Lj54alL_SBt6oRboA!tfbsltzxawq%iBX#;TG# zjMvGzjj#3bn-WvRD8D|@AYS5ii9+~}k@1_KdTlWME_h`poxFpoX%urdmfTu8OB@-; zbma--d9@XzmvDwFQiZt!MVOnpG?A0aHD5-~$|K3mo~dLO!mFS-3(=N;?KzsQ=-bOZ zCt+7-Ip2!YZ_U)+dF$Vjzcsy7TF#bY6z)S#_(njQ?p(M~SdjiQdub83@P6fq^m5Jg zA9J(s((LCSP0SX5Dqc$asrXzPH|q|=x58cN`j_73uTGpQ9t^!0xy@VYGHHU#?xDqDa32mg_5A`%7SJ3cAP@EH80t{;D=${qRSt zO5a!SF=(KZ(!f_tIGL)fH=ZzIy;)#?^TAw(^;Tq3eiIqOSOHQUdQ;Y7DP-`rg^r|^ zevxJ8Unj!rE6iHkMb3IcUE-uW3FCFA4J~^im;X)gxN%%DJHxDRO&qt_f?b9||53H5 zc%J^WK3{!C!FD@$IajzWg{PfX>;vs$2mV?L)u;8Pd*$?$63J;nnueX2Xeks|2oc3WnKl98<W>w>^ExPH98?RjVtU8yOP!U-ykXn_HWyp$&3#e+mya*0%$j^iSSW$(f8{U@eK)z zstfzA?X8KcvE#Ry8%qjWjEfJNSsrvsFk)sF%e=+oQ^Sgr+&pG1FIk+}e=241L0Aw{ z|8}ZR7zXef1ZIPf(bA__92TIOSbS$>&!0o_#L zpac%30)M~bP`<-gj^Zr+eSGDc{|9{K(}*5ygr@a7eC6^{d}V6OlUu*rga2>wmFcu6yE=^JI&0yr4uXs%L=t5O9;}5^L znoSeJ^Y19a3DiN=`oep_so{Ko6~2|_Dx7E=;XThG3K_|v z;;~NTVHySImBM0Z;bFU_k^KTPWZf_#IhDs_KSmz<9fih$%TCToSj^2uDIEsbq%qqY ztD>zl*bSP4H~vaI#^#k2I^PdnafLRYeV|_WmsMQRe@E!q{~c@n>EZu-taZYbdDb%& zTQxKsyR&yVc3uDfjI~af)P%J@9INmBU$E98S~ubY{R#)`c;`MNY^?AbYi^8~tXfh&17wxm zy6FAA3Zz~+OwY97nRMjO!v_-MGP0F&$k&7N7#ms!WA9@e=^K&t;U*l_H&q4`W`;;boU>{0ada2^x()rg7FhY-ms5xOtlir9FT z;n+&V(}7;mil>lo@lX-tZC0Fcsf?@P;VH`{A;*(r)3 zZny;t)7kV$n7fiqJsak(N}l#!7}l7PuIY>|d*ti*vR=e<#(VW|%9;o0GDkcc;4KLI z*91vdk?KdJg$|=lTfS1%Al|m`n(b!Dd@a1AuiaR%T2#2drZY7Dy@NCJ+ZmV(=wEJB zWBr|`Qp5}xiNG;|y$Q|kgM)=QeQ?%poZ-knLkZs2f_44|w1tFbk_+F&1UFZl?mr*m zi<({0Gb>@SLms2g4H;~4E8!qKJ!HWZ`SLbHl0ff&7oU^(oWqBAul7?Uj5b)KQ98VL z{7!XSGRZOMH*C`U@i}8T+Dcyoox>@L>?Hkh$ILLj&xEpnI%HaG0phcR(dbhXOR`UPJCX%?*sVk!u9w2)z_kP@9=qYIsHo`%{5%Z2B1$h zxn@ZlU?;AY5QQ~r>V4Kvk(~cB^en9BnPZByIZ}Z?O9zYxXN(lXOpnWg~**qv`3vkP5LsWnTTi++3vMMBcp19 z&B!iIuA@U0-0sRf1??`dX=b}a@N(k9iXeQFY%|Jv#6V6$OnNJJqXNkJ-|ZJ*p>y6i z9p2!4QG@G+Gi8xx|0(z8>;D zmSuK^l5$zc)JS49Fp!Mhrj$A2j`&hs(f4=%jR-`SIGk$dQCsTu4SnDCq@W*II7zk; z=g}H%7o+i1NJeH;7t^M{$?9MXu6Q<@+C7A*Xa9wVcE zeLrGk*7~6s-%I6w*dzFlM>fiDd%uV7e}&p(4kCJSzF%ELqjcqH%3pdkHV0PhHxY+l zb9kSsQN!EYl1)y&kP}k^7kX%pvW}N}MrP?YM380S=Xz+4LkbPL%B0*Ld(9*^3;3f< zI?z*HqnnR6bp(4zdS>gxZ@gC-(Hv>Y81H+n$7j#kl8KxV~|)v!5W;o1ua zuq)nofo!R0oax{9=Yp>#4Laui_3iaG^Z1NCA!k18aAuqR&xP*KPwIHUl`82M=fmrb zxP|BX0#@P@iDsS}^ugvt#~whO7@^|pNWjW$gcY!FGUC->z6I<%VXe#TBastd!;VDy z2K8dHSkTz0vzGJsWFDT?+gDT^idQ=%_N0ZxiyhdIoB{YYx_s zmzg=^MPO+aX6z2VQcIKu{I8Uo$xF1S?u!q%TK#l&EZ!HP^5B;M&VmPLQ6}4^QW|`d zWWUdm`{dm)QX^m|*r_(O$Iv~(W6NYVzmlEOp3v?@Uogvqpa2&4c38gC{?A2s4v}@9 z0E-L3N?a827|q`M^Ofz!%szM#O~BbDrSG7(yMB);XgcUQR~HO**Mh1@3#X3=Rg{8 zP97zMfMb37CAr{z@9xX4(kJ4XJ`yzJm zufy8xo&F-9-mf=R`?DOD@S`qM2koY*VWPpw;qmS%=>KtUVIOPY?PpCCA@x3t&HGZ) ztV^cn;8BM@8xBY8{+saYys=@*Cf{MPiCMg;R5&JkkBy0Ei~dp-2nT%zG*1a z5T?I2xrT|uLRT}&-{}&<&Hh(ilcfaJdv z%ZJz0P;I!`pG7F`??`(;Oev=$6Hzvg9-&`E2VC&WJ{>08g%^&@_!eja1?GR_EZNJXrWjr=~@_v&anjhKHluduaT{zq+onCwHXeAx;Hxd&_`pOxn+ zz3)q$`mvqM{y}N1q9&0Ez)E8|BX~yY99_+IV(RQ)BFeUHaW!V664**Vmod#gB{ZT2 zhySASdcQUALiph+LZf2eQt_-wxw~#=g2&{)-nccR8_1Eb;x7YAbUapsnoH7=8V<6e zi#6v=r+g3FII9p`DV{T?Y<$Llc2ydyD@ylv)TGP)&Aa`l0xa+MQrQ(wyJFutP_G;N zev7tJ{i7|DbH-s#s#ya2+0hA3ZaVcNt)4rVSZi|qz-0#2eYk+(3LLf-GBKyll^-T< z>9MYE87VeRtn#b!yTj=^t0O7Ap=h&s(O6eR7OoxGRpziX(C@8-rz0%qqlnG%E-Zcr zW6S#=2Jc5XJL@P9=-%L+U6$OoFr8X-xvyar{Af6V-Nznaug1sz&tvP@4)8D6gC7}Y0Ukc|>BeA4<}MDkL}G=+TD?dZJWfh!o$YHSXUY0dbICA%{l** z{_{0uMOnN8ZLnlG0n6jG1VUte#!XdrWcVM3RV+7$D?*z5rm_LfvI3GZDz1()Y7xVnB_y=XeaUGkun_JQsW5@DWVf>P$-LUkwu}6w6{+}17B8A3!2Ph9`NnMOOSgK(8rwv2- z082$HYYL6vLU5M5S`Xq*e>eyFlCs&s5ZRX%q4z%OciKr3^CU*Nu$OF$X->_tjI5m$ zHzXpA&n_s=_GPf-iYtp#e2w0w4Li(DRauC$rwAu3dE%i-Y{9IlK8gVi4pK62J*frS z0TB4&vH3u2oKe&lQGhQfzz1?LW^Ycx^u?OQ_=vS&Q)s>&e*ztR}-AkOKYYVp}mDh>2TeON4@r^C1K&MvV zlq5%RWw3YHnwysx=C<;d6WSPPEMfFjz7m8L{~qYima$8b{JgJ5?|&}!L<}uXnYSE{ znZe(Vyz{#>!{xNiEpAvrX=FLjUD#z+*puF>S>}j^C**(AvBRI}PP*3YOYpPDP8jv> z#3k@-x0^vT-v?E`02DZ8D*!H|g-x~tVaY!n8y}x&IfFLNL>r6nDa41`yBQ-rj&XSt z!uQ)#{b^3#A%?5{oWqIL|D=2_oF86LW~&kW3l=MIzD>bQ1ddIdv!rxc+4PxO|85s# z2|ztRxS`n_G&ffXcKGc1bVZc!%He7^e|2y2w|^I6Lv_WTU<_ zQasvES@@v34?f}3zLaS9O&_i} z%ciAD_N|@Tj@x1S++C&q*iQ9d)t$*FleJnJ zo9>9_xqOtMeP%FL-K!1e*U6Hcd=2KzNJ-C!Z>~59%5)~8v8*nK@761+uOxUXJS)m~ z;yn9+geblpMpjlmedh8Ct$%xHTO=t*`yBa~(pEYP) z{;S-;`fNx%oN^=qB_{S3m200(zb<&7Q+`O#w6d7__S*)zbV>n(xOEC(g_CW@b;T zpcM4e8IA1wwI)J#YcwM7^qlV*TLV8>=@Ri-Ni@=l^^k@S(MtJWfafjvN7pW-(|7mQ z-)zWrWQVIaTr&N-`U%(yJ=H_=uW#^2?jHfM3bIIPLr*rFJ}XaN12f@!#H6a8X77Ow zdH(J2vHWG14SN*}H+9imy)d|{C*QF&e0Im!4syV&2hKxn$i6P;-gMm@Mlk^N(d_>6 zrL$krvH7glg#GK$ftU+4MsuclL#3&?TD&~#?(X@S%hEB;Oy|Ak4ckINH zdP;h1TR%5dZ}?61No_(nry{r9gY_~H6Ho`?%uGf-kTrM^Sg5dnI5nxqk1?K(QH3p^ zv?-E^b^YT=_tsp8R>}wVya{8blP01J8YyKLaWnkruKe#bb9@hMm>pk^-v2C;F4N-z ztT0^#zfV^*97`E|@xs`6j_q|cjx=6l|A^Ls3%3l%%Aiv^^usBtpBSz>~xWB;eUf^+$MCb%sjOoL1QEkO|tsZRn$~0c#P`hn(JsSi{Q_oj3fI z%024J#68J;ej;`QA%B9z0SShmTj5$>qOYhoHoBa$W{J;JgtZm>WP9juBbd3iCfxY~ zv!BoF3kPf`*|*pi$`>^LIv`!0ycTgi4ux`nZTcjvICi^|+gF$y zLK|uuUHXns>hioR6f5*AVG#gcpck?}v~Y*7meX>$ao5OWAqUmrcz_eU&F0U3u-5W% z^3~ci;K$#Qma#unixu-_U4ohFK9L1OYs@9aABoGwW#X|A_xLYDGrjz7tx?#$rj*Mw zO8X&s&t+Aj084WILCy^-VE1MV;$ zyC;4=BIIyD#(7aR!^cGl+07>8E^;b>XzmL3FRggSUE4#-_b2qag0Xdp zBN{o#eaPM*0S;dF`l|Xow3h9$U_`jbJei)#AB^`?-X5z??=8V`mCg1 z`946robJoxrDSd3nc=au8=kP2>$EwZUw^UY$Mw(G?Fk(Vb!yYYr_x`+7;a{r>8Ehg zg1qz8^Icz=P3W0s^o%uQB6}EPn-~6vjPRKdO&uMNmt6W&vVK0?oc?LuTE$ve2C`tf zi8U0np2$W<<#H$Al1oiD?R2R-3)AOlDI@lPl6!~38L)@-hFMQP-;2Q^&;wN26r>aEODC`@G?H{(Wx$NmWNZ*HZYhQ>2 zp>KIV!Z(fF{W&z~45OLr~<)mvvn5E zkv{5a$;?>e>ycb9d@!?CW5&RC{KzDKz^-7)m^Y9Z@l7skdl!0nZ2mkkOmk!G*JHz6 z@RCresMJpqnZ3(fT|33|RNz9uUJI`m%%4&@HxQJe|4oQ49PY=NK~Y~)zpbu0R2O>K zr9PDo3Sr2=?$Ke)2mpg%In$aejbBHEdS|`SEW+=DH0tz}tG*Ub?F#KhucZU6F&Nq@ zQ$<57Y^}^e<2V1YZ1OMTI!>B*eXnfa=*sx69fiZT`f99-J)vNT_|m}8_gBQ7L*K24 z4}o7Td!RzDaxG*!|6Z1Uv@DXN1~INTpsca=^k4GRB-?BA!ujEHKYlrsU2kE}A@>gK zth^MdiEGm!M`;Evo6vEt4t{N*QOm@c%xD~ntsCNOd04ISn01JoVyUI^q2B(*&>ZqT z0X^zQUl2FOP|HQbJTt&b5PgWZe)rDb4}E_me>*fXeq$rIPQFW}t{vha6Q_2zA%fL+ z&+q%E=XVd?Z$Ddei8DF7ym{i;jUzQGy#)lp|8l(teQFf#=A$Zu-zSQ?EKXBmjS-p_%Vp?GT4|13+J zQwO{n!j<5jW_yQXKY~?@l_{TA;QIPOw|#x7w=~VCcqY-75Um{?Z`Igx**dKF<%1gd zpEDMNEri1PCv7#Gy0p?%$qfL{iL>qV0rf<@!Po9HZU5-5W^RA!ImS&(3TMG4wz_n{ z*i>ckJm5+TGy5Ify`~MG$?l8TpEJkqdJG;mH7cc-or5RE4IZJ(JaSdF(7teHeW+37 zaiT0|<15y(G_S{Wz0t{~cv33n7>|2aIuVJ{Ug50dXpIiVZW#hK1J@g{uZ2I;Lemy+ zx~d3ghreL|@E0;mfEkuC&amtOd@JZ0pEqX{e@8Y?1F>Xqb__Dt6vmga=$~cWhJExL z=FtlN%v$PSM66#%qr{@Sdi8c^PRioAt@$>k#Q@p(lmSA$OD-FVg%EdgCRR;6b_=|A znJr+6$2{?b=$(U{-M%(p4=TIYs@%IEC$f8JE>Z8MEGt(r3)K@ix`>!osZxgBuzumg zJNz8xFSB-Z@ZuLb9qAQImf@b5{!J~19EfE=zu`-WDv_7+#bfb!z@7*+cW6jG`U*Y# zp)!E8wih^Sx+Sze_S=S_GYi1NYz3!ApBV?V_6@g@jtktqlST1q!v}4qabk8u%kgbo z(Y9^d@8Z?~V*>c+v_=CqwR;b5_TU5pe1D>S=;6Cz{fytgfOc*d>J5FRyj~93Xskg& zJS;i`qx)uxtjm-!7wKLau&`OQu1~ReU8w~lT;C^4wp2|xfJW|Ba2db{0ZJ`>-_;K`dm2eZ zp$$bYDbB;@koJaxf`n)v^i2tvIl#VVS5s7x`9}Xh?9Y7`HV1bP_M-?ZMukPO)_-=C z%IgP~domk{RmBUzgN$Ha@E?2u%!|(@!hZ-sHdX0;6`uR{+aU%1(0aRNJ?88%!;B>P zdp5gzmIIOvopf-0_j*Ff2*56z|MWjuCH)_2glTQm#0T1YivcVHce&F)Jo&qcq?>!-gr4bU6u-DCCq{ZKY5 z0BUJMba_AheWV}momR4sJKN`L{lU}BkXS)z8Ts>r%-8Y+?05~*RMe63BtUmbr(vou z4{dThRxa20b~%2^)AC%Ru{eYlnBcvu+>TumSlzrd5Ic;WeIWM2&;U+$gaJn*YLL+y zSoB>W^i%7|z{Mx;izD~h=>4Ok_r3peKiZdv=U8;l=>66Ia=&Zz{-)9UWuv`UP#_{k zfm(vd4K~kB*D37BufvH<;<4slLfv7fN;Z&KUkRHK`Hn3rqM5e4cVwpB0j+=BE?}HR znF5WpXAyc)Q7{x+&}VkrJ%Zi7eFWL5`7ST<65)Z^&j&f1rOE>RYjCYH@~73R5%X4SKYm$io+J`E^oRWE0y5iRY_g+_58HrOZc{USD9o+0jSA)zO6mK09{>ISS2@T2Ko_#azh5rGA~nj+xFNp)CVyqB{O1;tx&AJOL^ z?ff5~oa96s{?l`au!&e~khp~@4%q-~J9&%J<5C7 z`;K?yNd>LJ>0FqeUsFm?M@H8bjR(yp_$g*;!nb%4ZCI9mo{C%6ty$*-9dyHf#Eh&x1I`SOvtR8-!`{ejq} zL6UuqAhRSySA(Kc!~*PBh*;oj3D~7<#HmtMDirKURSGj&0y+J#U1YY|iWGKd)kI5w z%rpG_8Y}t_wrE2S!Yf6vrgF`zR1~2NpK*mxu25DquTsK~mxKN0xn;gquZFSP@!5t? zuO0g}zNxN=5zwoHKLXZ&m_lzy2)C>c3`jL4#>;pV3vyG_b4?#@==n&tsuAHKGL3$%Du58Y zKB!i`M`gSghvl&s_Atm>P{KLCM!m;FCuRnU7|XXvX^ZV>GyH<)+daE5Qlu%H017yH zklB+e$geR0@wIq1h99c~&R4g`;XUZ7Tt{30*;6~b!F9cuFVrW4_-Im@W!Z5CA8W$d zg60R-M-$^3H?w7UXfCMA(?@58vYciP@iQz7b{Tkf=vihMX&=oW-R1eCk>?NUifBIR z>nwOL*<{;*R-puM1P(L%sr_Q?1Lq7Blyr+0z>_uvF-*d1<+Kjky;og6H$d z9MHJ8!IS!0L^|mqgPpOFpBByy=5jFR{S61v|gg9)1~Jz_I6)Or;_%X z35;+flx2glKfw!S!*C(+1sHVj&&v6Kit-5~K)D!%6eV)Apc{&7iq*jVrt)6GeJYRm zmnDchkO=EI8ecy8lfHxs@|G}2Zf}=4@wCSKbKpLyE7X?1d4cBxewa;*Kr8(8HRmI~ zR`mz4uSYwmeuTkJvqS?P$UbaGe;UollfltA;Z-#1XF++z8dzw6MwI~fT&Sf}`vVz^ zrt%#MwB<+fG+n|ft{@Q7tvZ0S_<7XR(6T=x%Sbt>wb#aVt6Z?a|;BA87rQxmL4(p=E0gH#_PLwQm*OufZX<{B*WD_^(qFDnXPUse| z4mg4HfTBoO3kIOA^m9c;h>bqdYq_A6N2kHx3H8&ghu_HWnBj^RW#&rhf%R-Ekl5`9 z)>m&6Gm@pKJ+lDf9Yl!b5FxgCo2rYm&(H1exDpiVfuRH2y4H&siI;N~pQO8jeD|kA z+e6j0-L;kt-_Mc#y&P+iqq)|;tr>DbctD<#HBxpwQ`4zVd(XZek#yJVKm*CvED0y< z^`*IpSjim$&5d8ts&&5`(YQZ~WB^w)ZimBkUe6il{03LBBo6P;G~nw7jUR$Gkh~Uq zh&uy%e2P~A&G#^O<@r#CkM#P=CAsLKd;6zieE|as{qha^g!+bLCGd^O%#;jF8U1Wn zm1&Yn?CFT_$#*26l%nByZh!mnkltni$4fDW6zq8uoHzaS3-M%TDOii^TkNU5t?(Z( zF#8oPQx_jR`LB-S@Wk~#xD^-G+t z1?+B{YXpZT{9=s*l%B_4{^wo`sB)2~$##!-1@=4(^qYl1ZsP0y-z;k0c(6v9Z)oT2{gwu20ElyeP`~wS z#I!7Dpmx#Q2Q9U*9l;nW%D#;J6m6lkPIFs8ID zOQl6#{z$ZVuFcBY>#03!hIZka>?{|fMTNKqM%<9F>mQhTZ}(Xl&&ba3cDc25uUu{| zIHZP2@Z5r}&W$5&UMi;xh*k}GHtYheY~BWv8IoiPm^eeJWz_bWECp@XfiI%SA?3YC zM%#X5I3wE8Q|UuySQn+;Q_%@hxf<<>|)ThFH51?>d2{iDH= z@uaqs{bb#+u#4p`|F_nk8?>@7AAt|i;8@!`2Gxw(ey!YgnhT%d-fX#F-om}7anE`A zUKj3NA>V5qWK(F&C%LWc%;-G$(;#<+JP&4kh5jf+f4nvXyG@`Ze=s;YA089!<0^zk znh&-?VV^d7EdE`e9L9V|{txpZ5GqIStsU(bW!YH2{QG?Pt^4OkZ}tj%UR;mJRFLVj z{5z!78kWBvk(^f4JMwSsF#GxZ>Tn@+7YhnASc;$7<`kqCzZZH2k~CHR^6>RF<{FAP z-&E5sN26ydg9r=TUPTZ%Ca%)34ky5UpbA&PhoiFI;kc?p2&UI#rbFixEmAfJzf$hs z3feKRW2;vq$6ORnYJ$d_;<@v~J1Ww!8#1ZnteQLmq|&o1@jC-Hm_IAO5fQ~YLrSDB zISaoLTV;)j?H0K__=220x}N6L0>nIx$94`Xx_$&G)<|dANW3hm0g7=SVKaWFzr_z zWpY_Txh%C^kxh3PaOx5o7P?OvRY2n%=#F2OztzkUMhuL>sYBM&Kftp=x81evr<1w=;&Kg&vD=NWCJWY>Fa=bx~v-{6JZFMnouPxciWNH#d?br)D7)@55t7ca0Wc!xo%k?v^l(VISQPG2$i6gx>G?yC3ekZT!OEI5nS4H^{>b%O&(ZaI;8yMLH%5Ly7EOsiy{7seo6Id7yr+N>ztAo7 z3m36dJv8)i54C@+KWNQITWB{^F(r00$d~)a_OcP$ryEpeE|abyx_`x7+uTvQe@p*d zner{~CkjS9&W-&EBWI!VQ%BhXeUCpL92l-Q$2BNc$S|8Vj}2 z;UUtUXrng_eSc@u=BEHhwUey`{y%oLqIl6hnTm0Jmf8_(WiIC~*M$i0{#@SMh{jv4 zWzZ8PN!!0x-hwv|#lX$+x#%A6yq*}^O4!_uSZyD zO*Ms!!QW-Uv-=zA>8fH`f;kWi;BIJqAjc34;`HZnGw9$QM+exYDkf)uumjOPr|M!QL5g- z6$L}p+Yoh9mVlN*rWlX?IzG*NK4Ra&92=zTGp*Y=$8BL<{@3j#8 zHJQ-&-JGN++xpd+MgM`jGWUHVb62XqG43j*k7nic?{Qb=zVC5Y8;H9~>7OTaSu^{x z<*}H{vcP3%qklkrX)R*TeK!xA!DXcV3ztE=sTTGO%{!`gSZaf2&e8B;rNO>!S0t_M zQlz_{Id-CTXKQI~KNv}2LQy03AzspfvfU^5=)z%~d3Ml~?1P_1Dh=JWn<9S%&3b1b z9{*Q<#SB?OhL_?t8Nj6zmv62|eDe-&p1C&53!jSo0pKv0Yj3F0=W~(@NFX#`QXneCK>X zqHUV8@z#yxBclXr{@Vk}3fQyOaYbnXZ8RGv;@_dYHQ)_ZPG)%s-@m78$mAxsz=kl3 z->od4Q^f7&Cc$E)!o-BV@SBS(jv898!rBw@@wGgb!?IHs-^FbABEH+@8UG@%d^p(K zDjbFmnz=uWbF+-ax@i|7B_Ur6MgF&8-p;xd=*cf42fWrvamZUfjg0i^&yQ;M9I#Dy zt09k0!g)#qIjOEe8$HvXkN8;HhBBP17J1d^!zt*)FNVP*HR&2Qdne@23>QvP?=kD_ z8>=>&_32678#(*IjYXSSjwYzF+I<#wtM4ga5BBuGcv%KFzmdod) zx`|G~AMa5qF!D-@z@LTaTVjr(&~=5-Z@p7j=3Kg zZmq$JtMDhlkIO9X^rtJ*#J~DeRc4Xf!$n{34cMm{EBPm2i>EGoF+wHo?t3o8{pxgN zG3vh>9|f%ye6PpH*TS;3knm#bM&BO4UjaFt0)2Y?ZqibH6(Jn_pMmPfFej)FqAfd* z3cIv>{`yEVQ(MQ)J2f%E88jx_It{^)x(d;p{TE#v@V2Cy zU=2f*0TylSKaOxd3h3?;)yb)WUjv|)g5$32gjLxg_?IgmB^eJiE10PpN>xqiI}d_0 zv}YW!1w$rg16|^=mWun7nHiF+UVzjIV?~m8X$HojVyMKc4DwBMCMfMw2FF>A#_h16 zQ#PU2^@b^>%@AS4S1|DhCr_INheuw~7D3R(&bzazi z6x1!ck>58CGDH@=0(<&Vti7o3#Z6yrdi9Y`$jirB3qT2r29It+`ldX#b)B|p4kXPw zqFFmJ3%6^dZ}qCdf$uFnZ&m~kg{l_?fwKNkL}mFs`u7=(2d%lNP4Gg(?(D)YkX~WH z*q9N+oXIeQ5QEeJ8#h1p4%$E3@R94%Qh!uv zNIH`4=U{V}jBf_4m((Mfb=$Wp*-d2}d?Z-#M#zF#`0*~7FH5=8)g3B}s<<09=zhrQ zB0ERH_EkoM_^Z%dOfvui4)Zvb^AhEm*j329-V}^L=D>f!($eeY8(&Eem=$Df!r^3-GFZI{ zc6)yNPgt47e`n!MPw5P$6RuQcB<<_(4%D&%hjBK2-bcBx1sbkTKzWH^Q zja<=uc(F5`2fj{u;aun*(!B>anRNEeYc`vRE^jsjpWJ+IQv+6iP#%5aD_OL7-~dLy zYZI_vAHj$}Xb5&b0t;a&AG6eqorEGdH<7~Pz}2~*3c0# zAihfFIy|{=-!(tPJUKBsPxP28@8O!q_sDtRp`-d|v;Bq_5}(cSFRUZ~CYlp^@Eu$@ zsZlXAdB5UuVQn~yp zVDqiQYExni*AI|I<%`hk47ZX+#6U!ky(j?f+zPg>R;Zwuz1uenYqlfWTwCd4?Dg0= zWtS6KS%XEl)7O*%K!F>3ErdrutJU>sxX!i$cE`ptX5WT*z#L1SwcnL4J-CIRZVdlr>vaF`5CKbJ zKef5eUde70^``EvfL1b< z&L~q%y0U5Zb+k2QQLRU+elB(&Cgt z^nIbi@l}|&CE_$)4R6pJYK^tryrx<@6O=&9M``A*+`N+^Ga_1j8@^#HS9mgX!)67d z{+`)FxEZMxD`d?hXFIbANOV?u^7L>WxbI3vPd9DqjF>n7JyI=xf{5Z@BBJ;w%UJ$r zk`z&36dU`1i-vYl`>1V?;F{(om#b`7xC0PU;FRPwV}0`2srn<7hv*a5sRifIIETOY z!rF=a6b1af8~heV6uklsuhR&d@HF@nBz?&Hxw)x4S0H2y%;C%>j?0b{*oQ(LKbJ31 z=b1m41dZKABbS%;0dP|NamzMQ2NXfXhttD$)@a0CSiDU|R7VxlrR&>5M#$C+T9sbS z+?z~KK*v<+x?~i+nu3eQBd+I4?r>F_PDPX`z0$-NoWl7SI_?~93OxN0ZGzvO0={xb zNDH*m#?T65x;|($;|-^b8TgAc)ie`qG!&9um4$afGbNIDiyhiqlB7=_&IQ<}pbvzA z1|iq04Rs;S%Z7Td7x*TSP~1zAJ4_1X$uiDIFT`ylWsP&*2Q1!c-ghEtEsFgNXP8iY z0_+0_bDl~eJ1_xJ7y_0CQB%>zrFn3YL|i(PF~y^*FnY|(IGb)GSuyyoN%(+S#(|GB z;scuH+>3p_7x8e`O54@EREW_%+$*q|6`J`ei0r0lpHZPN81MZVtlp=WMI+{#X=N<` zQz?*Tu3KGqo;&C=v>$LKwclty6nX$Vq2`7IkQD4NvYf24M-gA@hjqV!{Ki&xDw4TT z<%J#oNx}1kOV>WR?5}dlFTvMQ%C{X2@Clqy!=@(!Cm{imQ4T|HD0l+dsdbk)bKo$n z!FL!}1#Ya$jIUwS62eOF5#-`M>2+xV&`%CF?a~S3;sD|2KZp4?*3Q4-I)V?i zHE{!HScs2ckF~s=v0pqCN`Ut?Fx$EP&W@{E6gD#jo`Wy63ZrSIN-@tSIX5%c>%n}YviF1Dd@{zr)J2JD* zwv^kQf|&Pfj8}Q8xc>Elh_xYWx z@6-gQnSIC<$T<}Hmis@Hy$g5~W!gUe&g9snhx7oXNn4UkTT0Vn+mvHPY67LSDhlo{ zg1A#EIt9T3x}vBQP?y5$whd^T;Ura8#Z|1b>!-4dvg)$#VFu`Kp{<5PJ1V+H1XFrQ z{`WfpWxw^iuK(}qHO*u)^UiyG-sf;X&-1#sQ%ahfl|EfS87Hpe$++T%2IuMq5}3Ry zt)XP|5oU`wD2dkF8>r3nO8aj^d+TvD;h=pG#(0~M`R*`yGO@$#M*G#?qwS9zjOSX> z{sxC}Tmj}%vQSXR?W66cZKZSkS$w{Y;|m-b=;}a&^7Imw_2_(OQMVFMpFg$Ck7$+LJa)R57;t45hUpm_ng{PQ208)#kVjygwLE?L!|0hhD$i4F z%$kFgo>N&j0m%3)P;??E-$=6wCe4L!ubg-j;qoD4>#&PE2!q&DA7D?OCOj)_f#qQ@ zGBux4&rb7@CcnSu4S4s^eL$0?k@Tu81DSI+OT6$BraM%?8-^V6tty{W`M}o*Jje;e z)sm7M>SrIZ5v-o`=zk4H0Kdy==$-kIhHS=hC;Ke)r8JT!cGrU$jZbxy!h4Hxyx#X8qo9$tuA}{xf>M-`V#wSK zwB1|R5NI{b>*5@Vg1ekWO&HkU={x=vVM@<-kO`m54q)dfvd)Ncw2pkMXe#OYr)??5 zF&oFgf%iBAYN{uTFelQa_^xE)D~py{!FPrMJbzh0UG>i3oHw;cz(viyOfMN2ighcmXMzv1ifiSXF65(}hkzgIf8 z(ffDkHD4IfX1$Ky{3u<+r%pCh|K2xS?bXBl3uxzUXdfMuFR@*31e4W(gYsC&BUMQX z#!9ZnEnfGDEwn8z_x}_Y7hJb3mNjhxb2+<5xHi;Q*a+PwObO6j)D`dtsQ;o)dV6{?0&JL%#Ea@r^0z>;^0FYb-QeVd&YY zlu0QC>BbEvtgxW8G)+M8_^Q7b_f z$l96ox#!?v$R2f}M*d-1#un^>j!Jle;cN`_*o6XV*$!&H%{xJU2l(4b!qcGSyNDcIg1$6Jey{GBXv-Gh zzgTclKCc|LB?B|ofp!;XZ0V>G)}qZ!%V79lh<}wWEKdIpvlRZN9o-m1`1@or&7{SN zaT+UW(6eKY!549yiu)BEWVd&;6ko{(f$Epd=o{Ve%ElK^axP&+K{%0K0;K1@!RPFS z!XMMmsx^-Q$u*=bLA|Tgx+ju!vb=qsU1%}GpYTGW-g(#8S$e9R@erv2E0Ar4IFhg z_E)-3Sk%2L8TI9K5o#k}5|_8Bd;Ews_gkpGvrCkF7j?YR2!?(QWLw-WK0E&u%>4;3SSY z>^9^f)dD9u7%mzPCBlkwHJfLm2V}vp+)q z^HfL=I{7e=v4lIr|6T2eOIP*7w+eg>fk2)QYyuF-^?w8ndk1ZL6MV&UI4FOSlfhuV zGq8hfxy&m73r$FYNj9LJ|GdNsobUm-Fb3X3=b)n}c^6e)^h=aeukL>&FHK#~$;fn- zj=A+oG``wF=-G)VbTAU7uo}sDd4<;l;ph_J$uH9=8FYmos-X3t^?3zH5z2gg|19jO zh@v@K7)}oNZD#x#>-`$;pxaIBcG^!|J_y3A|jK+HYY%~EJy(_jc8OJEq2*4>WtZn znFz$5`&kKyEeB%M5B@>vy!REfO1k@~pkUM}8hveq0gq@ytQPu?^&`Jk9QCnvUQRzR zkKK!x`z~)aW1;m7Iv7(%ZOQwoW!_89FRMCYV;e@DIavr42V?lq7#>x`2r{%YjjO?U6~W=IU|s-zCS zR9TraBZ~UuPVPwykT(=_$UPppmrS6M6P(aLIqLS$PAFpJgq#&#x>GVB_cY2DvY$mi zRT3timvlKV+#OOZIsaBDEejtojI~(?n_~l=hvXT1CuK(C&Sh zhcgDK*V)UUS|)tHRC!TpuX=WU3L-XXSt$=*0Jvxg$AhkWNq&_iR(2^2wXo)gPH>M->OWIZjXPv9O1 zcz=sbx{ut%J>aS5$gdD{WzPeIa@S)vvs?Q-364d=q zaHO(?_hfFiY_56Ao$)w!I}LWd8_6Q$s~uJv#r9}k21lwq)`sK;m<5ULF%nu4*@N-f ztt@#c1>qQ`D_Y1)2K3bwWtzY(8+0DC>HQqph8~6OeQ| zI)XW|G0aqQ$e^P3=g)BMjGzk~D-88qAkq!}APCa3{tx=y*x?!M?YH)q z3Hg}uA$OdLkoe0GDKN+$=;TtMubI_fK)w>D_S5h1d#Rk>e@-~VpF^euT9b?+?M^qY zc=(IhV`%#}qAjoBV9~a2d{XV^$0N{LqF1{+QtP`7OlLGq;0bl8A{X~tIJPQzt=X4a zUq9PUzk{x_vbORP;#2s9)^&`UE5UN`29&49YW167yQF?=MU{xq=qEJpB=qWqc%nF> zbuc1q*5#4#SorGdSnG+=eK8->44E zAZ1p8?^AIp(Xe^wlu|4Fmi@V)@S!b{uybe%EX8ZM7(n$~`N8$F~k ztpO(fja7TNqE+1p)fZaznUxj$1&z;&h+LW>P{=^h8e*zn6S(i>eFxBAtI(!q9341b zEx&@{i5F??09^~Ec%#v(4@crf@u@`yQ|Da4)CjLBClEBqOLXm+%;HtgcZH|Rj0 z@M|=9e$^luw+G*XYsTGo_kF*)Pr0v19k&70b*w6znDFN7Mh| zQ5_8BmX|zPyG*p6S)v6lD0fY4kEZhZrEs=t+pEU4_3*GtwG~IKo<)klcZ=#<(C?xB16u6%k%L9>whTpqr)ly)LZrGktcmD(%!wCJCdG1T z2-}oE7J+LvNUYeik|NIb2I)-y8Oncmm}}Jfw<4O@uY#;NzjD!2TfN^NYkz2uOXuH3 zv|LuXR@6LwhfRa1Fm36R)KN5q)(;pEWqw_d7hFJFJc!7Kn!q`0BlI*SsN1%I{m}WX z37!!ath22ntOcX<;w2-eC+~M;!J4yBp6s!eYg!n1W7wd_2>3KDS-w+3)q~~-RRqg} ze}0f+ScsmE>r0k@U3OvUV@_7f*OcCM3ntdv`$?C!fJmuwT6~a5-r<&$U3E=9_Iz>IVVhM z@bJ0NSkh5tMZsfhhM zSA|MmPC0lNM~I8I<;)78FqVF0&~!R3%iiT^`>PR-+y%53B0Y3i8%W+?B;w%i-Q@ic z`}HR8VaT1oQK&C95hh+Xkli&I_B=5pr;rH4d^29P#o^urfO-|G5x+?xBjw zcn8(Ju(AWaxNyjD@3o-OdW^=TU^L94F9r}PHd`oyZ1f$t<4agYU(4rKeuMp`fm^oK zj(iwj-&Jt;@=ZTJ=a3D((STKZb!}%4Xt-F67)HFOHflYT{@I;0Ldz|v%bEijM8B{6 zV_1XW-)?-_zBy$x@iQ$RLj5wo7-67$qUW>)2@&YhRT`9nx(^SM6_Iep0CBSF+T9Ng zk6zYr?DwNzkJ##e9C2Z7bD4B?e>JjXtHzm1w))T}$qe1Xm&*O91C@On_rDBTOatzU zYA9Yr`F|b!jVd`2`Q;!-a!93zpE!1N|4R2}J$5{!T)R~SSJWD$CBLc0h~+YMeh28y zRL~pGu(nC%KIIQjaTt5-r{W@kVK~|GDpIjM-GESA};)1KknXV zARUwu>M=1Sk0syyD3urquZz~+bI9gtJY>})r_}haA4YB@yez8atXLO!RsKSu?;a=3 zROJy)2C6Qpkii{lEd83|t#)nO)6S~F_R{52Hy|2uHih=LmAmt7PPMJTE<<*i<> z?qvH`f3})`l3q=VzKDJ6vo&-Fx+u^+=#7WE4U>+iO*CvT0=JA+eG)p6Cu*0|h~_2L z-@pQ0Tl?d^|4n31ZM|?2)+=x0IrzOCwRtzNjkEZpHp0Oxc7yxA<@de*P@3lmGHqx* zhPHEv3YaKmRi5eB1+;CMm67lVkqw-vwfaWFA4h~5>%?~v30Vss!i*SuK-3iz@XL|# z!GS#R55j#ZRnE(FP#ZY&5ak+}mc0*=mU?icBgmgabq@`fY0i=U?U=K_#X)7_WB8;z z?-%%dQwK;CXr@Ova~JJb4eXLJN%8+0`$r<4Mjd$ftH-=Pa%Hs|#ILN}it=>3jdVJe zek)9Dys|5egcnB|46qOt&WEh&;pyC9<=nd`lkDLC^{&~GOYn35@&29~DYO-I=8*b{ zREuJOX4=C~;QLp?J|^w$Kiz-g|Cqa(k#7V;(~p;#6fuZ)+lkIX;ka@g|GI))3-BR4 zuF&0oTz`zm)nlD^4Y079ALTdYbbZ};Q(2|Oc_Ch+bh)OL14M5 z5B9HzD1Cw66`19NL-m(6#GvuNQ1$1av!!_cg@F%N=4H*3Tx9Q6Z#pNC+#h=M&5=W} zLr!R1^+Co-ajC1y5nFqR^2w9oVL>L0mmXbLwr&!e<+E2OJF?10 z!c8MZKDrA`S+j1<=l@5)Z5TlSsiN4pQshtpS^-|GjkaRpP~_lL;0W`HJxCf`OyX$P_0Lzx-9A?LV0~7WJJo#0doQk z>mHZUNwK&3&;vu-tUf$#2iF0+R9htc?qF>rMYB(+9DuH}e#=tOwikx;z~Kw^Iz%|z zgJ=*h;@fBS`&OM><$2g{Fm{GqWkPCs5Hxnlx}Gv{K5HDvn6z~`Ud)3eAgmIf5)Db6 zo`<^)@yA__$xa7BE1nq%KSJeg*nVHcU7xMGQpy;4&HDHN^s_C=phF!GCA5*2Y2cRk z0@te}z;;0Ap%29m87}j3Pb%L&)DMl;M)YMkO2{2_e&BN>XwjMjdbD^909%&iSZR4)HsKhPh z0pT|g9z6mK=IYu990X6QrT)LzqiC5FpRQ{%w6KkdBsC)gTD%NS?8tzuYJ|6;6KW#N zVDR0e5I5g<*}L6|S$j=nCQ#%0z|V!;dXj4pb#1lvxvPxaU8`PL)elK@{-t&6rmdr% z{BN&|dyyjfht^Rfe;lHgj=N-lXIZ*L{W3N^Wd{=6LFzD`1!DM4BD4Xxcj8A@kj3NQty`4yN}^+KklYlnctyS;RBgO3lB+x?2c9ZR{mq& zjELDuQZv6Di1IrAOI{P)hnY#_m-yw-bd>@%V5<)wl%WCgdoRlWR=&kmty~29O|6ur zgmKkEF92KtA_J6RKYJqzTq68TD9?yUO(iAuwt83ajjNv8`y)?nh<>EpC6wTq59J4h zcYrwSkq6OBA4%|V9{(rgQctf>#yhShW%V8KD@h<)auGQZ@`)3AO9uEEVBxaO@uTD0 zy(RJsUZ=dZqq*ZY;QwEOw?VO_A;z+Wf`$wDw9~Tli@P)=HQ#hX%g^M2NXplpc#QuO zpPlc(eHI7+Hhv)=;Ku|#8BcaV9|AOLm2a^xIlj(njyK40+Ln%FpRCZhPTM>Ft&mV6 zA_{7FnoS6KcZjye>X}&syEE3smZ1yi`-@?k6M+!IS+J@#7@tl2h7FtUN+<7c&>(Wu zrW&J*FB*U^qpmu8N$nDCbvq8|HLAHm{y}r4Iv20pt zInZs;9pBU_>e%B8igcm-qSWT_-`Cfw*Xs||=Tv7c_9bGgX(%S4G4N1?9^aWy7`}qH z6z$>bO9rq{Q*??NcMlrS4={T&)~fHW)P-i^+o6h(mCkt<-*5O|-%Hi+1Klom9`k67XNBy)SK9ANJ zL;Fy#evQxO-yrF>5o5Wy!@P28c#^; zl_$TzjHRpVcY}0o#i4ew@2}#!CiEWoRWk`4Fnb=~&oqs8JGw06v%5$rVbB6(3IPD= zQ{%hveYcU@1>>}BpkF-#JGtFkM&$$G%>2;o{Dp7kVKKDcCYXE+`4vHf%kP66e!LBq z_;`*9q^j9%RShnDc!QUQ;ZaY~PyaYZ#D%6A$Ty&cAD_Dm-XU>QJeu5R=Pb-P3Jmvg zpd9qjIgz&gzUysC<0tkqWk1gl=d@PF*FEN4sMY{)3hcBc6;ADa!OFPE?lHc6-`)I8 zHHkGLem}pO@4GoCn3m6WrIJM+S-CY|gSXhtD?J}8F9Y)pbPK+Bn;-BTR-TyiD7VG? zM_P;chdu8oeUMM%yY~tXYbXCQ+IKx#=jDN%L>^va>C;L9c}=OTG1kD!)xBP+61G(| zxR8DtF|J<>o-{6qW8iDRS7?0I{4vDl3_$C?m*2r3hY!NCId5D1~Vm!eVzZK+AVJh^Kv3{DP`Q zWFE?45$%UaXM!5nQ&<7CPguVnF@W08Yos^r6f4f1`z=tf8jR@T^c%4v84r>E7PL&H z=zk{k@Sqm4=B`Cl3Sad`XeB=g?($BQ9}-@+KE!)rv1W>i^sitBZ*YwR)f-cu20qT{ z>9(J>E=k{ME7TPx&~l(#4E=1-m!XrVXK7lYZ_6>xIFw#oMeOs1^7KXN^U;g$YKw0N z&+|YWLm$eDG>hi`;1XWr%0YIAMQYvKfP-R>(VG80Nc;OA1E2ISFlqBrx&m=iN;=63 z>x+UW_i=9yXi5uua!Exhdby9^!@mN$f0L4y$9Az~QOW1ZtvIupSC*VrUWV^Q6Y#?) z%@36HD&`v>b-n04(G`e)xa6No18~(Ecw}|JA~?|Xfp7wAJ1-U3Y#a_8w?a1l66RU@ zUE^3HZ1j=VQMRCvRG8e06|%eE%5Y;b>wY7+eFOY2)!A1vXAS=i|2qHt&3*l((AW*{ zQR^*&**BkW7rL-toa_f*s+0)E>zElpJ;|wxRnbmfMCcqC?q_!oBJ#sm)t~9s_9u!)Or3KE z5w)v%mtt_TVtmhj z-4oK~WD%JjIyK}II3E(uf!!_~?uPZ0NO4aWx#Gk(yyK4P1976hRkV!))uG(n>>4PMr>ygsg=pqJhE2{eQzr!M4=P9{ag%ysa$t~WWEZF=B)8Bt4W z-T&@+JL|;^hNL2ox zLSxT{VNs#B88<0(`JfpL%$<#lXMwpI&Kz*pFrEP7#pm;8zX`r^#BXek6H{NNG@dCU z(z8JZ67?vw$>4blsPHlpD=`}-B5Lt9nv+*b{Uu86Jn_WbW6E-2VMd{B@GOVM*c|AF zo|U-VyuKynWnD}1%bFI>WqfI#m2J^(L#Ac{$O^o(4Eys3k>r4Z++ARmk7Zony&N?0 zx}M~=6tT^_pxZ5sujw|-?PQ9_*W3_vxSWV&Gkg5sk^AYdz?>XWX2V{3EJK5*9HoBm znUk}!nc&g_M^_$6Zi5|v>di&T&Czfqk`gdCrCQPIe6}ZFI0{QBEX_3>XT}j#ivwg1Q3-fixp@r)< zbpFWOF7_vjhA4=b4E7`A>-q+8RQor|T^y~Ew@K@P5@^BR3m<60|iumdZ zvmd)hZx%tSubyvxB)fZzr##XB>WW11TU)!gs3%!8BZK!8w5Z!K@p$qMGro)VG&{v< zX23R4+H=N7a=XW5l+!zp+3fZ=;9v0Q54HKet-Jb}Nna||#`i;?ejxk%zwedr>)nWY zA5^aNZETd@lOOGWJDrO?yNkB(efj?WlpRa~OMA{c38QtnWc61f-_`$p374-d?!Pj^ z%(db0ozOv~Ll^!~#t-#LkgI>F&-XRI9yNc#d%ioLn8lk*PW6-AuriID`Js)w(l7UT z0cw6uNJYkycJJ3c(SDL0M*oKoAf~*3i(sycC!`5n&B;_uGY{_rrUe)m=+vOO6{yF9 zM__U867<|Cl38v;=68!=EWM)bD|jv)04@W2O^}&*Mks-;bD#HUFG_-3in4a6tFtjA zQwjrntmBl`S8S|zl7$(w;EBE0>MLPA$@TA19M0t@V)M6OVkXI;rcdrSw3vvm#OT*I z=~@y=+@mSt+VSySOU5U5&4Cg*X>E{sH}lkF;+;GdvagZUP8pRK?$U+K zBQ!$rchT724`&mY`^YEibszIx^gi|MG?`3nf_HLqW;&lLl+`m_@u^~Xn;7+)&e%0w zuu`vA&k1+zjttT}#uD7D(_Xpq(~H>oKkqa+4JBKA$s|qqiC`>F=T}pdRri^ohZH(} zp7i<-Xb@bWt1d!vZuRcGeq*)PZ$eBVji}q*JtodicTElUNL}c$Vc2eGh_|~SgS(-d zifhx7Ht&S4uVjq~?9qwwK`nL?zt6+}ODPo^9OF=bL%G&_E%-W1W}0B-mtQWMExQ-} zbRX(K)IDO2@CHxZA9QP-CBhb83GX8LzCXyi-NgM4$~L;=FzVD#f3@JL1Mk{X#4$6< z>UCnb-BV)}i$T-%tp?EyZbRT&^-A8D=jPe{PyvhsUfoRFJq93P|9Ubo|&+BxZ zX_*=L-qWEYZzv78tB|4h86|_mP_ofyiS<{Jm48m5ccwv4>~Ix>qc7ptI;UZzOUSH} ziChNC|E&O8s!|FCxn{yx zNn7`iCYq*KVFWPvw+iv(wyb$X-_#8B)*bL`(fjY#JL2zn{((xl9S;X3;Yqg zJ#M>kJF{K4eJ}P%ljITXYj1MT1WQ@&F6eSkd9NdJeEtcV;Rd!<;f1Qya*jvTG&S~D zH28;{6+|oU2G{#F<_G2VtfXd2LS8>s=5<4jq%TVU-X$-pXTQGuy)U|)TtDTUl9+cC z_vH`GC318w*@gd3a{Yh(t%UzI?>^dfEB5w{!Q0$#$%ew;$;O;(g7>)}k{(1h=GPRb z@Mm2{X9EWh9?{7&(8lT28l#>idjDSV`%GCo&(#5=S3|WEYp^y*&(L$b@rez&eMx0+{;qB6NrB`85(o{v0)1l~bR;n0sev2oYkz8zo;*GsKplfMY_Bb0H zF5w7CE3 z2y%HbIkP~6C=1~20foMw{yZt-Mr34x{00N&z7#wex$T-lplWY`qAH65$mB088ZEUK>cF1 zi`C??5=D--_4F9PF%pe(b&q6?UrTGbbbP!t3)zTc&y>Ienb!Yc7E?BUEmuRYmRv6D z8sZczoQc3u0(LCoc)I_Pb6P!zo}|$Wjv&K!9?-+O0QI_shfpA3<48UH&UZsn9!Kt- z9GyIcpesX12BA$u4l6`?y<`xvE0ZMPN16?zI}L5NOcQSxviP6#z_NMH@Ehz_YOEX+!0M zS??O()$F&5ERpXK+E-!^ zI^GT)tLC_aEGW{3-W!ewf|f>_vB75`)z`jZOjY~J)bjSb@`w}Om2BwruqlVio95~N z{d5O>I^%$le+B;G^o^@Wj;OH|8Tl3A&x#&z{XqUwI1D;G9(^04R z$z2Ga9iZM4PeM}|(}`aQcMtra6Q{Vc_$)2>6}_B{H*gU>Br0kl97nXR#u+ph^P|v; zQ|TJ{=3302(Qe}js*M9p>WoKLI%wi@`xFaCNhdOxOBcE{>L=-5dFtKDA?rqHu@(wD zW~Iv-C$n=4a^6`c-eP^pThUE@&l+uvYsi}H+r;0-uM@PbhzcFZ1x;VaN5Uh~|51sRnSUi63qdhMR=Y$F57;FHDTR6=)DLa2+mj@OD;|WgK z$JYwyczeFB%T0`>7LN;v+a<8o>=gn$BR)`d&g$oxHa74xw0(^4=dhxrmYaRcQLjjN zQ*?&XF1TyX2+M1-5sS=CETvXYufo;st8tShbq>!LHP+Hj;CF$84BbBPPedeT;h8tF zCy&s+Fc#6?ptYlQ(*&q3gX>DoH(XV(xGrOkURe4t$FmVMPFgg zadnQOeKoap*3xq|eR!)boX2-o!rr=l`E?(uTf@DvAyn>?7f> zVSScHrf1(qKI-QP<1&^}y&g-3tj1}GDlNw>H>u!5MJwwM_s3d39#$M6S=3R9wbq`W zfNRELqlbFBRbf=NU{v6(g*mZwa60O?36$(GEImN05KFPe^9B0eTCAzjp!cmFZ_R1+ zf;P09W^5FXC~O)3sn@X+rVGH@(*Wi8RS zSiRE_5i&zg!>$Plcw#0`cfRRChx;fjqaP@Rhzwj%mg=9Mk?E(Al#i%)ekmCOHu&2S z?i(cwoSQ+K=ybfO30a1-zzMOTSEKsYu_7}?o2T#6hQ1j|*Kj%TXWZr7osAv1fwSw! z`sf>3DN{@X1&40b{XP&~MZ~VZWaU8p@1ElfICh!J@0zp7YS-C(W5_Ax&bgl|Ozxe? z0Mo5xiVHI`TNa_kmn6nz1~UDhkZnw^OfhMDir=(7vsJs6BSmE=I^xFXozMr2umxuW zkqxYbgCmbsm;#AS`WAq=}Qj!cYo3hur>qi9+Yq7WvEi>!&@ zz)j8_6_3r_F>92pZ_|rRah%m|)i)d6={+Vcsjb>aoX1d?OwkC90qvU)6;rFE+@4`{ zYkQK!YF`pCN1rN|f}x%peV1VSO>%#RCl~vE0*_(hN^AkwQSv$@AcM%NZ5G$YYMge$ z5XfvHE>G}K#mom0=MTIPbXidk41Soq>*<=ldOV2Bh}zTk*t?3#EVM>AZp+AQUUa#{ zX(x<%Ynawj_%=ELN<+z3zBO;vvBzN=N z=li!*YT#Q-`On?`MllgmBh?a9P7tHx*YB_tkX}o6QtQRAJE|AyeTWU)W5ylW!~50G zo`&FP_w1gvbGpe9YY8z5bA&QjGIvFeL9er>I&Rugg4jQ>8eI%;!<+I@#>KEUY9=h! zWf9JoL}Dc;xsUeh#SFVyM0}uvaXmzC58mlbx}3S#B=Oa>q#{WEi-f6oZmwGI>|`SU zIykm~^t=;vL5ildC6%AjpTl9k+RWgeGEdS{pF`Y5j-wkJ*lI%{YR#zbB#YrGpN9wpw9n6uq*kX_=^>5yy}P=s@H$I9!Q_qs zeW6jhZx1rAG$4j)jW34(J_5}_;7$uuVrVf=l$7H@v;M>Sg)$cLqzkbg?!iIVLJmIn z;h?g@XILwTa1gS8n2rZfQ%(lijpLn0>qyJDnY67+>ueh zM^df0Sv0nt90Ph{vz41gYfHBe_J}dIa>AvzVE+0?;r`nMHne3JbO=vetBexki_(d$ zF20y8X~BN=;Gkn4;~$IIfmCwRwOXD|enu0jAIMVg&sLD_5^wz7h#ucZ%Y@VWZOT}8 zd@so@b+f%a}=~WEboL^Spub(dBJQdSI;BX|sYFU}xwKSkreJ zTMTWCW07r=(-9!qqIHXH6IN$Z(^jwkRV?Cj0Oo-ZE}|Z%W`R+fiFeixIkUqu+|29NlXpv6(bJLTme?#E`52t^K_tqt(_N z?2pa7*~6p7EPo1~S*5OJV{dvOHW%X~v3`1i+CzKu5o?$}zxeW15i|lL_WgTqQQrgn zWPf5HR`Ne0CiP95`wt8HwiIBV4kO#qOTfp?I+-GRK>I!pmT8Fe=ionG71c+zWtgd? z>%E{!M9fBbMVmx>9gPtE7WO0fdgI+=BlezrETRFzm9GrxNg4n%&l{eq-C{DpUD!=Mn7| zCGVAtBIi}4!e9f|89S^ZRM($ITJzzA zL6FIPt?CzE(fV4Ix*vd>*r$Hqr+)uSA1Sb?_gW-c8_0G_!R{s#KXKB)q=c}u3xe=7Ci965T? z79u~{_n|_|!6@~;hcg?_exbapU@S4F&S(Ro=fyH`T@0T@N%u%}Ha>tB{!BKCcFjWA zHmMf;A@ts#@cV5t{YG35;QOi}iqfP!*Ewtawgi8CAVD16GRD8E$|$CmC;5{C_X4L& zq+bSC;>xy)+L>dq&!iJJlpdk?UJTznMA!PoaL&-3Rd-b*++BIVTYe&0yc2UkBU`XP z5_w!7lgop0UgrM>V=Lk1!Pp9WVK7Fc_YVH8kC}j2La05F|JYBsTW`4W#(00iHj>=| z&ZGLqm*Mw1p3Ff^)QjP?p%hq}k=NP1TSCpZKZ||g`Wtd!Ax_wqK?0X)utBsuL%l$z zS0`bn2fPQ>wqFdtKXfttraBt5#EapBgV${vH&2?3{wY9z5$UgI zVdrftt;)xhskjo54xgnXoG%^ck^w?#nUH`Gw)@1kF0(P~(|LGbd9@QeAG4|OpembK@?;5k44c#?DXBeGt7sKM9C6J6B zuOFndrdhFVvv2=INv@`KyNI|k=pzK@rt_T241@%6gfQQOIQC;D>{j;|T>InpiF>w1 zqo2;0*!S8*$a#3?)9a(rf6Sm*ImFUXad`z}AYB2cNHe5<8@3EUyn(a|&wS)Bjp=H> z4eL~04SnWSTs>4lp9!nj#?j<__`7I6@u<)2zC>F=M+>|RY~j@VgA^K0M#FzW)M&f@ zu$A${9}^x(?+-9dmlWzFa1p+`h~Fuu&AEg8!dR4XF^qVidFN!y9D4pIocF<&yqx^p zNb_gK!;(*X254YhrB@8q>ozX+$&)@Nn7gtgd*(qOnWYRU2J9Dmdik%v{TqRxV~pa=8Ur!wL)2vG&CALLStNn4w7a!;>*+fk(m=wi;4;j>b+D>WMxb4 z(zR@9b`??AKQg()+f);p7$vU9DlAy4MP+gB}LAI#i5@gQ?Ju(Waq=}ksq|MBZ&P>pLLLD!RH9-T~|=-S2VT2$Rlp>m3w}QdkEs<#`3XK zEpbfuI}$!Om^GbICO zebAepQLgA_!yVssT+z>tzO0{x<_nP#YwHj*pof;ngkDE^|B_*QDN?O3K$W=ovGw#0 zt<>JwZTPs;G~tN)ZYCt+-ow%%h3aIl=wqpFHny(MhtngmweG*%1Jv8l1};>0qnp=+ zgrOhP89}QA9nAUg5IhTi=mlYL0@{;^UZAZ>H548{rcXW|$9ed2j&V>eOSyMuF!yrn zzf^K?_BmRwDDw=doi)qJcq6RqGd*q4p8&HRIz2$R+S+Vad!rxE;v9A+jyH098);dz zf6X#1GWflbw5YthMxxqCCiJ%mtpVdq#Z?m`eL|nY*VX}X%NHW$NC_2fUQfaqy8}PYH+a4Z+lmCGc(>LX~;`uPuKW8ILkVLP{5(?ljD$ri`?@XI3_kizQ(MokpgW|$*${yu>m;&9^2>qtLfrCQZ&kllCJSpdc zFG)xnd80Zzp!37uTI#@ADz9s`Q|gDOfs_jv#Kach#efW>oY{qNZqxuR9>dX6vO$Gd z>3Q|3=c{%8Q;HRmPC6tVXyF4%A{!dHw3=v}<|R;n^(1l3GwGTg)p2ICPn`2pD=jk} z99LWQ1!RV6tD>K8UjA%E-p3;Bj2EDRdb;Wv{PLR!-7P8qa3TB<&4h~2381!Y6HzgM z7m$C2dg!pN7s93})f8R`OA()U!SyVB_>fJD8x70gXt$+{zLyPbQe}NA>0eOy&DrqJ zXUbqR!hOVL6^$*TePPyhos5f0KZHxb)4)1)v*7P2$CrR>sV!!|Lu9h!+;?{&9}M)A z+A;^Ov}S4Y?(Wir5{KQ>rYuSqt-GUEp?c8j$WQ7m=S17C@}<>?pKa|acla)ZUqkew zCDo5+eQX`m@(aa*)`+&&^7G2*rni-Zmcy{l0p*E0%=enP=a3Q=KGOwYT zDb1;lhpo;i1MksB`Q{7Z7WJ2fXip}5@XjJc^A)Ykh45Zvwn`%L;tGq=a~kyM0A!lK z;-Gw8(l|n1$N8H$Du5HCSTS6m!KgCNz>FH-y|usj<-cI z?q_BFF2nB8=m{dvIz?QRPkkOUxS47i;UX)m0%5k`G>Lc}4G95dp_YkKq|GzIdrrzxt=UZ?Shpo0qpCKMTVaH-p^ zwgmBzl_g_28)8nt@8~qpjy5gk;qKG$0JEX))}vOn?$!i9m2Gs8`D69^8R|gWO0Sqz z8}>~Rb5pE8pE_-ZbqV`A);j6_5AUJCR>M{h&afXopWFk#?STktx+vDyPnw z(Kj6kpAw+zFNBv2!(vj3**8gtYDj zApeaeW~_eQ&Tb!84aWlOOKbep5J5cPkJS~ZlMv-oLVhJ&--!GT^z+f7gZM2Ty4TmS zW`5AKg=WyXPS?*DEJP%dT~0^_jziGDrIn`y{$7p9^;pMN;WmNJu6Yur!^Cl9&V}$F zRVnvE_@yDlQ6k$ak_hs!j4vPprfz3Sz>T`4HH~VnojK-my^_^>eK$mP#IbtK9x5swBNo&%6KQ$-yyNAx zR%lDb6v}zHo~&Lv^FsK#tLk(pCIbi40;5pl$5G?lt9}*nYZ5HM%=G-VMfrnLCg>IG zUyPbRf?8e=B)g&cf0V0NJ~{Vss`~!NJ(-NKyN;8SOVfQ(mqA|cYV{}B*dJL3=38f4H|J_Gtx*MDoQ)XK`HQy-ffCLW9@c~3q zDv56?a+&IFh;ePJ_rQu{MNQTMFB8){T?ik56iR@senOeVS+Vo}MKOtsv&@)##_q*- z+KTs28lf%Tfk+O2fPOeNaL#tjn(8-i2c6C_iEk=qL~!_7A6;XY^$pND&~=qoPVGO8 z!y#@01z*ue5n@ED>mxacGoaarDC_OeJ*EOLWfYl-jK}Ct08g1f{UC7PoIc0~+voLx zipop-GCa5Ur4qy^#BUyzu9ol_|<(z>gzMN=~QaC^AbbMO_Yiz z(sk9-)u+Q=zBr?pORbN``{Mn_`cgznWzK`XQHo*ltNV&ni<(mU8x6x>S1c-8@DotF ziCU^NhCY>WrpuV4doF34zEGx;X_s~2@kJMqU!4Kso>HQ_huCKfpcEG5SVOijs|6H{ zmU-?H3+ySp8gS2hL#QqA*7W{=4nfn49jFMF;!zU4V!cEP3r}jHzop-1;9l%nq2JKC z+LI}tG1xn&7C_Pu(vo%z6_bP}df&)^LrefFJr`64a~EFyQwzYg7ixQrJBmx0ASoP= znM!HWPx>5UrjL4o=rJ09k){?*hThl|xFcgK`e-6yuJf#&>b{+#pX+DzA#!Ioy&rk` z)cZ9u-MwDx=>iU%xPzGY^vR5R3-GiPAYonUr4s`z_NsTh3DEhQT&zmP|1rQe8HnlW z`!VO3(#08X0j)rPrS*RgQXbo6LN-kL?d<`0^odL^W(F|uI&oJz-3zYt$$`OGpJbv> zUg%-uvxfHLv3eJ|2c^EVI-o%UGGdgWC*u8dJCIJ{->_y0?#r5LPl z!mbF_>pcz~O87v$YwH~pOJOtIaU5|G8Jlm*hAK#NY>(+4l0UCkSw^mzD-ln zUf*q~I8OU4zsgp=cLQ-P;aznuzFVv7^kqT zN8Xyv!i(>H_5MFfnRw@D*1l;O*E@9L9q7b#=6TrH*tPdQ~*uNfnL90_)PL zqUNX`s8`XVtdp24UH?61Svpx?t)F8RhQlicEeF2|Uq3=i-5;fR73!lKS3-S;S^K43MO}Q`D3$e@}hKdjb1hiakeJ~yY2H!Bq7Q0%Q3bNXJs;^Ui1-VwRM z(LgqN6OMKn7sc%?pD$$k4ugOE2_FzX=C|-|yv+YzS!~i4rgXK&O)2`2{LXqn(2RRk z_2X=?Y%0GQu@>j^f5*FC=RfD4RniJs_+Tw6f*&W&tmc(P@Z)rplgHu5*=2s9s8@-< z=~2f4_;I$zKV0-r<+sAC;C`10Z>xTs|5p7tXRLzY<~ zGmc-_by%?#QV&C)<4f^a6GTb9t;}P! zy&rYZsNS&wEBs61e~0i!vK8tXN2h|ri?|a>lN{cq$KK9Z%xWq#kx%pt#|?h(;63sb z&p!fRoquez-JW1+#=R%IZ&SC8b$(|Y>zKq=I{OlSf&GoY2E|E;fw*15ymRM;-R`!; z-E`V0-h>%2)sAjiHeW$D-H^>=UCB7vB;aU}? zz0&hE)>ALj7W^%soC@08;-|3Pj#S9zPr-E91}Pu%J>1ibS~XF#6KA@mV#LnB>cVvP z#44Lj+<|(&b>Ez@Q{_LC&}I;w4_bfkqqUMLZn5oQOO(x7)cnf5McB#s?s3bhp5{Z%e|Wt| zz#cA<>2Ug9ntlwg<_XL>O+A4hn=>6}R#@RQthP)zb8OsnKW0Pk+ZWz)K;F$K&~CmK z-PTKi?h7~}yd}|y5l>S@iw?PUM^ZH7*^81{lR5pI@2v!3y0(SmZ04J|BR>fzN?NU> zyTl#X2Z7x1D#inkV6;imw;4f2haS(~KC9JQ$W0TO zY8&Y7#0^a74fB?-aB?EOsV~rmna^|BMNX721s+1rDiSYbgrS^%Wt_+e<8JJh6S^uA zf5AkYSNkVctIuM^D5Gf-Yq2fL7}d2JJK{2ZnHiJO3#>`fw3y+?+hUdpSvIFzs8Sxk!XvW@PU5eMzk}a4ch4itWH4gl?;59w$ z9{F|BVa(N??+G{EXd7dEuV)fFjl8Ma{zU?x9+nY)QjN3pIhfzTx)S?KO1Ztf7~}Nw zJZpvF>mCtv@v0Ub<`t50FAv9f2JI&Swgm|2<=cS2kg+Nyb?dlLEqyR0{y z`Ys_0a};i50hJ@J=IMPrxmu;X78i%fLBu)ee(0))CW|l;%fMZS9FT+$v zRXbwb!)>E*pQ6E(d77uahn5_7_v5sCTSBZn&ivMg^&&}ZX+t?O;p9bJ&UUPCT$6+w z?6VUbCgcxc($!r!MYKJ}&8OXso#~1^k(+f@>uItU6Lu;Mp6iG8}0bj zr~K9J)|1C}yG4w`jonVSx|QR88r)@^tm>M;?noJBA65L)rztFTV7zz+ZzCuYOFcgk zJKC{s=j5p>%rbstyutBePpU`64*G~wJcV*o6XMLLP;O!;-v5-3J=ilkmG9)+hg+ht z7a8rIQ8nG@X8wKWCDV$;R_jOIU!qUgFKaFKeoJXP61K6Y5^QdjJDL63a>SBrQ#ou7 zm3fo(A4j|g@DiC@j}!THcdY2(lKDVF({NUJReUBpCS~)i$MAYDlg^+9i*Vnw4=+D& zzae@XyBjCeW@{|U07iT{0<9#ZjUGLd&0yNLt8f-4>;ZL)_yAV9a&$P6 zv7$+Z8T)h}jftITfv&;5pHfCV&S-?8)rdLutW|S3EK_x||NgOu@lK&OtsN)r#*Sub zxlC-!bD-vIQ{x1=s%?D64PELs?G6F6H6n7{Qr}Sj8{og)ntvR_5+=MQ{QhCOvampuQ#4K!Y!>NiT))N-h)Cf9P z;ppm7UHvEA-1cYO2^E(dF(2nVSwzXDz}r}%<*0$Z2WT(ErNC=22e79^4Y!w}{|0H` z?^#^N4U15QXrI9Sse*k8YrWAsN7;v=tmXOxIr83yzQCWbmg_fTuR8YjC*h!bzv@L_ zeDL}%_iwxSuhurb9g&!2qJ8jj?7@9(yza#Q&CRB07H>(ws2J}Uf{Nkvsv_?9W0le0 z?Z+wPL?PZ1hSwnv8SU2V3$ag$ceC*hlVij_jGR&|rcaPJ+3CJMtecKi_VC}iFUJ~& z@!p&qlf&fXrgA5>x#C^{XJcQ+J=fp)2gbM`nKKi6S`3iY?T9aS@jPir*5K6-yb{_J;V?AWl3NRfeQ4#;H$9K^o4txw zz*%M_RyF;BtNVmxFV-|GQ{wIM#b@wl*KCYi)Q;C3jjM2%Wk#&8e$`{RpN{66S-P={ zrwn6{TUL!SW8L~f;4Jvm`)0w%u+u5HEsEZt{rkE4Ri8P!;rD|s?9DkqZwXR==v4=e z`)Ff7Rz^_#KQyuzsc)dIZrI7{3#>&iLftiub)@L+!w~W#y;s(IWf-;6eVR}7&A>y|RNwKun{YD~ z-FB?hSrnfD?!LmkA53f3rSKNKBJ7uX(F;h~XbtbCd#Y@>$6AY;Io_U7{BG8nKy~j5 z#NI-iY)7Y*9~I1a#mF3uojQ{Aj~>yDHLFy-J%@4EFrNnf zM7kwOFpC)79kHNBaCqmmX(JpLdUoLUPLBMQs6Qd=5L$Qw?v_PJx*bpjbDQ==*yrzY z^9t>!p#354!op4=-0Al;Mp|Lm8=;;jFf~TYCD_&VKK2pMa*9p^!~u@*>std+<7^i5*0n8keVSd5(3*t6TQQ>snOk#oOTO}=H0-Ei<8aa@Z-P70y=}kMmapFye>i@Gs%?L=Ez)6m$L`M87vUAt z82uUSEmrRstyg9J(%N&ZtVpwcDJan`g(_3~tTwD4^Xceipp5qCoj`|(yCcG||0uyS z3g_h0N^mbL`Z>&mm!$*NUJZN7aFy?tRcs>dknjiMFA2#_W$Lc?Q{!~(8`m#`>N%z$yzN^}x z_erRE!q7KPk=+H1DI|yJP_Ykt=w`OgqD{yX{q?~bteN?dmqwtEa$WSD`!3L)J?sK0 zaqo5uTNtHOH;qGodR2sgR@pRr9!v4;Uwnt6qe!a3)EjqXVjMPxA-eNtQU^a zU7-ExVeW|Vs5}BYjhF4Bx@bfhmlcN-7>A9jX{xEi-4Slw>4Z55jEfHo1?B_yTfaSW z0X-l+yK5iY5{<@mB&2#0qXL{V$4zv7fwLC{^!P0H!s5b`GXc{@ZkkQyOg_8H#_qF< zCrs!QjmA6RPB-D7mhrcwd4=upu*UwqSp7kW6U& zqDJYG-gBx^6yzMZMxzJE;uPX6e%abF}P8jW#OL&qbR3$LQz)wUb?6LaeA!?RST zdm*)t21*;>{*F<#eG+@iI2t>J{>K`9L}>p!nMs6|!o;kS#Le1GnC??er`;Q^& zKGbtZk?`)O{f=2IPOn$RJ7-Ato>n{-DL?kYbnz!F zF`{~yfH|fmVk}N3vq@<_cM-kPAzs4RY&%O&^hua?i%EFUlFeSVgxkuTC|kRpaMma9 zD&+ZNapPW`FK=ut?nl$MWg160bZz+w$qs5Kole~Uya(^AUBn1}Y`If1_wB0F%@u46n}d8Q%tSFVdXBKYEn4L)x!A#)3XDY7Ra%)>9JA zvo|UV z_UKk?Y`6Z@=rPKjC1Jkp?B3-m>=nyx7EZaki*|9KT|UNe@(Jxb30CrbHuDB1tx zrWa=PECO|#xb0=D`IsK>M{U8q1mV_npD3kxR$xw`++(xx)>Bbm8GoFVXskA1brA3U zE>Wi+9gq3B^SI4kgIR8lIY69yJ^R>Zss56%J3WG?4d36DEyE_G&b29Wy?o@3JB zIY6qnFq?|G#3xp75-rwP$77pwbEp^lc@NE-`8#4U-#ZeuMvI%J z>aj0Py^U{cq4hV3nSSh`G{Rmnw;JQK6=*$#HZ8_#e8&@b*N;v3#<$-(`N-w?jt|CH zl;caWMT^$Ta|XwFB4VsUjF%wBW*_GI5aT+;IB6ipVlc)oC*MUeroI+Co=h_mnDylT z+2^o#6}MLH4$gbNh#QbzbnNYV95*&d)&g!*>oV{zq?$2c=oN490w2V1jyA#zd&tlgo?&QFlWMAO#y&N}#y>)uEM~yM} zYA0c`u2)ZUtgSDxu5zfJT$a7W$a6CsUpV$UV!eA^xEF=z?!#P0 zbK*wJc-ThRGVs!4SetPaM%dUBLpmP(>qX@YPbb!#BKLjLNAHN>-L9?|HxFxFp`~@x`0z^Um&0CyO|rF1N;uqc!?Rl zDdC0|+)2%+)0%P-3dS+^@mhW~jQ@Ml6KO2X8$6D&$=oM(`cB_Z6M?=KD zvfBI|wpjL<`v_*xKf)UNi|o*H+}4H}xD)4WNvC{#3TC}fW-gt7AE7oAshs(Sl(RQ}pqy3P)fh>oG~wn~|LWfVwxo?1RMLz?O4_f`gCCFG_8j-yM%dy| zyxtyE*2;&JHRr!9YbADZfGdecVm`5L0%%%5Qz;$)UzE4f&+v`^ zwFl+dnInykP?@T6dGwiADD<8j7o|7e$IL9+%uc041V?Lu-30WRmvdw)7dWs zetVYovku;0KeRl?E}*##<^0jt0pF$mGaWm7=}gC!b5@vn{+DMGn8ZtHK8&%mI42^^ zqd6TK>*_J5gL^iT)xN$7s^fR3aw)-Kv3lolDcpMje9>8(NR&vv1^4gwqDO)|2TnVyy!+G9YW(``L1a!EAECGl^#rTxR3 zl-qjnvWM-l+a9Yyn~%GCQgMG2y*aGxD$vNg3Y1+a%>UQ3G>b^5GlsFR0~7I{egEl< z^MUQ>!tFb;JILkkpJDC9ETIN=yz6ni!mEPr8@y8b^^mk;rv5ubqEQ;KM`g%q2q}^J z8T~kf;TVFU+%vMFV-(ZcRV>+!bGYO2zBl7fN^BqYiioKDG8}hf7Epz`LQ1d8dEw2A z{dwW9bUtMcV^MZPM=S3CkF*=n%Z$W}*mzUcezs>=P%&0E1_d&(QY|`^keNdl;It=09#s;i15S2(@1pXuBf4o5fy;}aq z=o6HW;}o4Aqu~pn|E2|d9zcWW6K$ePG>LajkfsXja&3L=G&_iXvOoV~zrVrm_YAmK z4!G;#A6xCv?vmedJMky_{)yKXX*3mv@{W6{;S%Uk8|I-@K@UFNNNfG`^K-q+k3y;xyntNWF@U**yt>U&H zc}9CM8r-$eQe&aBIO{Fj9US)o2|E{Cjyu?Pm&Icdcg5q@p=&K`EY~}hs6L1Yw^gWa zu~;oh&KsOx>g&X6@jHF0Ezh>YdCDp55+A1V$#=$;g?@Eo_(k>l@H88zn>ujsQU>0n zzrK*l72Z@wnn`xN8G%)zk(dqpHt-;J!!m!yc`224fl8Rx{TAmn>BTY$^EI@Zrs|5b zCn3j1T?ibAnHy_=&RAObBHI^bw7n2zm>X^PTGm^>4V*kr;~`&U3D??=M=r8lZ;6$^8WELezlXDV0O#UG!q|;B?)(T+=ROg3>w3f6D0Zwx!annJfonjG?C%3L$`xU9JSuvT&o2;-+j_$=F7?h?j#hx% zE!G6gwNm}{eY0T4>)miw>aL;g)DNQa?Cpq}7d787cZ_j<;gjrzlvnWHHq*FgyEnRDaceQVmTt?o z3AQX>x+Xik-Xhp0hnqEFHlzNIA`fyN--gp;Dub=mlAyW{x0a1_SS@9aW07;R*sow_N=V*?^A86>oe+&I9-LCIoLSXQedYON8&cjQDOe}I;?A{ zw)+D&^nQKDu(9sB?0Iwwj%8f*9XwO|v&{M8jtsodQi8jqRhUVfjlE}68BcAFUtc)J z9>uynu@=#WMeTsOHyk`u36EgSDFV}J?!oR3o;n(5X!WmS=6MJD@79Q}r1`=Qy2*q2 z*Pk=nrrM~qPjb{cC^Tj=Vf4B2jA2vo9NP{7`&FNi!=#b%w}GFWZ|xCViQn)`PxM^r zXB+B1)Y=x-%q*J{m}KV6hXd3b%t>7GcU0T&*+(_-ny%IJtLDiZm{uc|v3@ts^0voL zF>1H|qbuFvar6Z~N8duV2mACM4%_uD-3QpJ#!WBT7#-06p%09c)--5$2SzQB>* z*_L^hpI90!ng_z}_v3!QzQCbg)@HL9v2J0v;7oqoatm&o-EzG}w-r+UY29-R=3SO? z(fkbXHM(nV@%2e>vKV8Gd-Mbi-gQ)s|7X{?0o8dL6V95e*%RxXHMe_zH%3?L)EmI# ztG$L)OR?t3Zv%Iq<=7A3FO8oYf|5AZH+-AO^@CQ9jKMliTUO!4lS{*=D!kJ_)Q!d;l|O!;HNXDAy~&H_c?>^)2u| z@hrWP-Mzn`{~X6%l>TThXboWu(yjo&l2p>wjAO-1C8sND4$DV{7|}ts!2M(B8T3eR zX6Oh6FdPhQI2#D$oDT$cpFbBEb}kS&b?Ljn>*v42J3{{q+=V{C*^bU4{;W`ZM-hL? zF^3&|B^Kd|p9n4R+tDzS0~&g#Pv+ z@f(^RX+zTEHt<{DP*GZ4zp{SvGEcROl~+v3%Fi#Kl3SjamtCHdl~q|*UY=d)%5zRB zE6*;N%Ia$C>s@soXI0Qst=CgtQd3#W%+89utjdCd%JSUYf~nb+1?5@h{DNHblqvbS z`DSz8P@nT^SF)@uXIaIRoUHQfys0@k+4))J75P~OIb{`D*%kTOQ}fu=O0#QfL0N?} zKW}P5*3^Rhii*m-9A~9-iZj>j%ALvvxS!ux)!-?tt8=cOg?QA|dunS~Zh3{dydcL} zkYA8f;c~j*rM$vfo^N*L<&;%A3;vbwdCv88i+fW@VLU<+$*lmp3J=EZ3Fo zoH{knIW^0fbJ=TARjsojC;M{vET4EYS5`Xnomo?ydFC8vc}`_Pepdd}saa)NmHBMG ztG?d3(j`^a)mBRtuC<-D-Srb*R7$0}#tN>`oK;C9wXWsQ}UuDVGKl3!a} zT3Hs9A@|tzy;{HA3cQ`&H$=m*Eq;Nkk1Uih5b)pcjqAc@vx7_ zq|<${dti|L(L82&vVa+O!tU`w_D?|{Kb0AHE;Hx={o!Ip+prb(PN<$i_OC$y=vAOG z$WBCfPr>{fzzcvOnQVz`O{1&6VUe@WS=~>b%`RkyIe>nPgR_}oSP?Fcgt`vUHj5di z0zR;T2jDdV4q2ID%^*Lo0RK`k_?rVcKuv?10`(~Dp8-4xI0!fZyTT9bSVcmdCS=umRqSWZAX@EC8 z6mOe$<26Xo`Wsi(x@&HnwF^4jX^+8Wuew9HxWnhYMR8Y^6~&E$slURV7jH(R>CzQI*3l~>i4 zua;^nrL;zAb@9zoxwEDQktuUYt|n)BL)Ci8S?>0@*19TKav6@z_A%-Tlq^|{S^_*t zwQF5P>;c}tuXa%q80^Q#hHMyC<{{yf`ydZNm)=U)q6cPl)LIBXPrxOu625 zmuW95Sx9-a!6j8w)~#_34P>HJ*;rHFfaYMD#GKT2kzPtot520G!6a3=l~81xiBc6v zAndgIwEA!sK4HQHX;I;V5}O2FI3pG%g$83E+=IIIUeuF-%=?%@{Xa@w)YZZap8(DQ zocE&+d_b{R{|xi+z=?+XI^glGiv2Y;sNpNX2Z=~BH>EX&Gnbd*pH?reb0R)LF<9K`O7UY4FrEx}+ww4HDwysX-a`tVLlCdS{**M0tHpc`4z#ni?cZq0(}<3uRe} zJj2L{v7RUJj@>VqA@50MI1Y6<)PL?lJqYLk{0L@BtTyPk0yv<4eZ5?(p|zYQQS}Cm zlya4{;F@{!CQ9Dg+A3-O?D>mImtMcLbXm##*$b~(CVA>5SGBicJ)^z`;gdh9p|%!` z)vTO|G;AWAdDoRJD!m5vYfd)Ruak47>UvjsJ!9v=!&e_L!)I9Iz2?=R+Q|%#zcIG> z05kjp-P;2%GXph?=U!3VUwI2=ce%H;)=Md0TJNr{1ILP~z7$-PR=H}V3@Mu`^;yNX zMWqWDEh|~LU}@>R*$dbpum9RpMv##f>GNjyp&oCN+ zQg3-#X`QRGytc8XA$>e`EUIf!VOQbgnG&m^2>r+sD)!nsMxvM|xohhiYS0Q%y7VVh zisHW<#S={%I*-#NB~PKV(ty%bSKlCc(PyFd1q7-pP(EXAM~*5F1G z)W9>U1Vy}_8Wek%Sxqbvlh{*KuRO$cpK_uI@Qi9RNd30lqzB~b0(Tp zC4hbh*&U^^B1lG}ex0)n9kzacCS5`3d-!Nsy{6h zNxur}^MKO|J!U&u*AXV|k?kcGeH?2U&?hl13jqIF=zk8J6GySu0X^P>W^vtE|B!K1 z>?ZjAIrMTJQtGL%Z*-ybdC@Q+6)z_M>L)azN^(%KET!%=lXa8~)1+XLn<<&Ez>_ZH z1=Edc)EcySs6z)xptviE>K&*AWzqxoYXT&ehO}0$3r{Q8}lkR!-HSZm5FR z$b3pvBMkJ~!EQsX(%iu}OjHG>qf}No`)h1eDdldbr)E5>t*op^NpGm7O3DjWM(?+l zhpw^%=@chLM9$R^%wVap3d+sMj^(vp%3f6x21?Fg6(#$rU+wXN(|Qcy85*U5Xg8qM zRs=n-Wa%>QQ6UBNYf+u=^o5xtVCJL9^3< znsFu7S@m+0?5SCa$`6Aqu=G8L+S+>8n(tc=i4cl=UBhIGnzIaDO7sY+xf>d{V4epO zwVO!nnw72!>MRiA<#?dgmNDeWVBA>mLeHtOp#qijWh9C$AaiDAm2+jiG*((xRJvrj zZQjDAvuDX3DfLPf4p4awO2vANA{(mfreVM-cUfgBN=F`cPuWmcjVbfd#UIh7>(AAHEYS|m_SMR2a>vL_0q z+EalZz63&)x8)R)qfKI0a@;^PgS{t|0u<37#2ko{G)Q>xG+_UqcxYJn--O?f^{cB< zX96ApJPQytdZXFV#062M)`Te^@vC$VP<-UfU0T*yzy5NDfvwC{u*4T_muYnQq) zG<6|q2Uk6VkT9gI3XV7iH7Qiv$)wOjzU&n(JEl{Eb;=bkb?CCAhaGhK*U`I7XMlRW zx60E{s?;(hg+VBguQGa+ar&zi!~*p^#JCc<-^>&@)b6PMWOiLOn1DkYDHro;5F;un z7fK5Hb;~ebT6+Bg2{jFAi%J%Nn55JP>A~T8HSpGYYB9lu;d$YrlJWnF=uklp3G+X6 z(Sx}FkwxYx_ae!Z9+1+R`JwQFc`z9JAHtMnFc^=@dugR-NQFqbpw87)jU=dRs4c~q zz>8^(E7O2*WZ!bdQHpB+`|e6|Uui$2##d0jSIsY3x=fC}tI6vsr#>MP3Il}TkXLr1 z{E05)5MF6A(K9G#_7}(1F2tb<#pX(G$oI{zy4uop=*rikHmR#E8-ns5k}WtcY^+d9 z*?++Hl%o?GoFB)^NdK2kU%%n9y2)_mryBTz_J#7t|HY>uSmh5>W8eG8U6O}B|7ZWD z$6)SuK@s!RRI&wy3s{Y_25(|#=j7()PbrvMXtm9nT{OtTSyo=*s${OTDonuO@@+^&+eto#~#{$xP3;>FZLWYeOEH|s$cwL)}^S&vv)pp@1L~4Tajj~ z{Z&P}#vP4CCJzny*aGJQwq*9~1*|UzOlRZ-G{+I+{PLWa*5Q!cA_y#J7_y54z* zRH^h4!3y=WwZ&6NeeC{(YN(b^+Rcwa-IDy;OMix%JNBQe^|pRK*(1m9ye@aGjlHp8 zW%Vn2ZS1P8j*pjrV6)uY(KPDm;j!~ zUvF#r+bmP2IYVOZs(H*+xpH<9cBO>AkOV>!2uUC$fsh135(r5kB!Q3wLJ|l`AS8j1 z1VR!BNgyPFkOV>!2uUC$fsh135(r5kB!Q3wLJ|l`AS8j11VR!BNgyPFkOV>!2uUC$ zfsh135(r5kB!Q3wLJ|l`AS8j11VR!BNgyPFkOV>!2uUC$fsh135(r5kB!Q3wLJ|l` zAS8j11VR!BNgyPFkOV>!2uUC$fsh135(r5kB!Q3wLJ|l`AS8j11VR!BNgyPFkOV>! z2uUC$fsh135(r5kB!Q3wLJ|l`AS8j11VR!BNgyPFkOV>!2uUC$fsh135(r5kB!Q3w zLJ|l`AS8j11VR!BNgyPFkOV>!2uUC$fsh135(r5kB!Q3wLJ|l`AS8j11VR!BNgyPF zkOV>!2ua}oP6-4$RBTwX+Q*-?n3?~nvn)N*wX;6pTr0w z>s;VKg1gz&%@VAl&%`F>7`=b%=`@XGZEUn9!TNF6*wv4&u20%-WnI(R%GD18t7rA^ zt}&Ir-(zB#IXyj$89I0hFYXJx(q}l(oXDhp^9wK+z&ys5ry09o=b7F@d^di7}a&$-EQSRHZlB!xW=}g=h$Rw%oO3ceSqFDSuY(t)gvO_ zjOg4^_na`mi7Iu+wQPd^gby;0(ZskD)+D-#50;wXxC2xS2iSPt#iTPm;f@PEzEqJh z;F&uN*NzI(x*RKo7Vo~@s_!zc;nEH3dG-xM=$Wse7wF(EK9ib_V2PU1?(so6g%5By zemxsA!M$O8*zw77+~QSgJFK_2-A>3gXfi@r=#T47VP>e7-gK6KI!VU-@VyNOSQ@zwgN)QZn}=lxKB>v+Zk;p2&hrwR zzS=M3?6rP%!T|gwVLeBckP^JBi&#o{YU?QGKYM9ak*O(mjoP$yjn+QOJ(0!bN}zc1 zQaa;LGQYN$Oz&Je)bl6g{Vgd>dIzd@uAw6q1#x zdJT~GhlNb)Ol1bfnE~>&x6UyfcqNrdYP(=gbTeVOrPI{Lj26Leba>}<7U`S0MZbkx z{2g)QjAQTIm$Qj)5w;d=N-2qBt#fiVshLz#u!(e|OT;at(;#hs*SBYm*w#9SNqvFC zeVwT$rj?ecW3EnN@wTuo4%jKFI=UQD8G$Z;>Ney>RWb9=zofFO<|a5u4yctDJ)g~_H}aX(%nghD9W0HH9cjOF z-^0~xGWSWDyo-37X&vp0u~%t#xwxrC+Aptl<#!PAqEap9&7sO zZoWs@3eMJSbo2$@l+&pC+;43>Z!P<3{}JTA=tayNy{HM{-eC84j6%ISk+lhT?n|*DXwNFw=*(3KPP*p174wQu$09SO)WLJDtNUxxcV})5S8vx)$20 z&J??vQ|H^a2?>t*_VCp9D#}BYgWkWms)(5?)Uj(ShKV^#*YFhKe!i!9Okd#E-k%Ew z(IuL0V9nP zdpnvA>-Yq*>)5SAfz7(S(2FubeheLbfiL=4dW277*UW8Or74MVuQ0YHFzFAeJFJ$% z&i$y#5hjIq`eI+-*$&~Jjd!b1JB~=&VP(gYlRj*EZvSxBmbm-&W|JrRzQS&nW2+WN z*|=$`Mql3al=`V*EJN4z(cNDdKf2v?&t5A(&P=;+PiNi(AGtU4>x~nb1lqm} zK@86dgz&c>1E_3tqcwH+1&;QWyA$0jnC7VIo{d(qi>FZS{U+LOX4<$`blRNWIn>4j ze?0dkxl=4`LV~Y(%*QO+mTDdDOK_*66~C=%gY>3OXWz!S^*SltkPDcDLse+mW3MTz4Lpl-M)0@M~ZyE z?Ng=LZqlU8x{3NF;iq`c#w#dV4st2j{z+Q7S3>Py%-ojRHtq1kTPnLM*?6^2k^SOY zL#=m?s-rnYr}_QJ#TGQ*zBg>lf5&;$oCi?%*IZL`UG0e4zQ9L)ah2CpUbk|@O8)`I zm@itU7kk)Hx%gkuW9jHGNu8inDpTq#8cgexA++u=78c{MotJ43tc4}>+%4C}!wCh8Q zdB^@A*IspnEowB=L{+AqLT2%v!hJ6(^!*+87qPUsNZu7AX!GKtpmJ5-{ZO|tA@4n? zOBm04FM{W$Exe^NZQhK^NPWwGB^EPkD{cAub>hoK^|rr8tWb3(yigdcueWs@4<)>- zCAa5hwd}9AjgCs>{cfWp64j*t>9C&(Gi`*U%N*0aB)rbnoUl$T3MZQprWJ{QvHaC? zFutOw(sp~Iw@8(z$>Hp{WsjvZo*m&?k6AT`nMux_K^es)a`TxZ-}LClZAk33R1`h7 zpD41!d}^w`&K9eWQQe-fy)c3it=K7?odd0AnHJTtk6FVH`wwt4(T+(xf0$1{3p+N* zF3{ueNYXQ3^J)FFEG;Qq)s-lWh|IB()RH1#;v=G9g6!I1YGV(=L=rq1A#`mst|;Vr zN$eqGMIp~Ef*gxvIVw`@EV?YmhxV_tbtV$m%KyVKA4)uwI8wjPcB`r{qB-$}LPfIr z%$)A$X2nE|R!_4fMqKu%_#ph5s;l*c-!JL$vSjpEtt)yOk~P2d*#5ncQ9Y!zy|7Z#bZY81N(RF zcOgYBiN7fvu20sJK3_FiKhu_}BD?KY)nTG7p{E8}cWto-j!<|!cf0l5Bj2Ik>d)_n zj!jn0F=pCf)%xDP@wH_<=UmS{##ZY;5A$j4u;IWxH*Q>ZuIJGH+l^bSG>-Dl5u5I@ zUhr}AcRj+hYl=#=B}{j13HzT}0&;n0(SY5Jm+eFu&%%It6WNNuB;2hQk!`WG7fI7v zEb*u-%8QObmCFj_&kDtN6!DiFbJ)R8DwtugS=W4}`T8N|_#x)#Tdu_a%5|lA)DZV~ zetf07?$ImFB@3@K|7eK+1Gir39#8lr@!xY6!R|pLGCoW=2x#1+*=;atQ^nXkD4vJ2{CDb1c zvETgEm3Z@qm}Re>tTR1EiNnQp2n+BMU=Z2=Beil{gt31AC&e;}AUz0Xs00N;us|g! z4#Fa+1j~cqfJ)#Ff)^@5QxKY=5^M^>7N`WRL3jiz!JZ)OgG%sx5IUg}yb%N+RDxqc zI1QEHvmp4P5}XYJi$fX%v_UXHB`^j-f=ZAc1T$2Ef*@F+5)=nv5mbWZL2y7Na0kH) zm7pmI%}@z81z`(Rg4Q5B0+nD-5cWYOcs>Z7Pzl}$f)6Ueu^^m=O7K|_{7?zb27wJn z`~lh^7@!gugCIdANDqP;DnUUIEKmuGgRlrH!SWzDpc1%);Dt)i6oh7|1e=1e1u8*n z5FUX_uqO!npb|VEgifdgZv?>ymEc$qPD3U5EC_z61ZRVQDKv>d8w3MX0%H&)s08Uj zFheCM2!aJFL2(ckK_yro1P4?CcM!Z#37Ue?43%J05Vk-iXbr+6Pzm+~VINe2=Y!A* zmEesa_@ELT3&Lrr1fK=L50&6-5HP@z2(&>kKqW8+f$CbClKG+Ue|Ptzi@AYYl)C-- zwcIeWiW?@NZTU|?b>-y`%_=KgYAY%E0a5)Y_aE^3ADnp5yGNj6@7@3HOz3R zo*8DN|M688Gjv_e3~P#*VewpMD4fp>ccLHh&0=Oq`^lB!2uUC$fsh135(r5kB!Q3wLJ|l`AS8j11VR!BNgyPFkOV>!`2T|h3dey9r^{L9 zVSE&{>ingd^O;5;HebhMRB?PbA1NAn0-s~EO_S2+EVyR8l$AXxXOfxy7K`I*#<9r| zJ17dUt}?0sx>mp#vI>5jYrcS%bM5D(2;ZPz}YEMlA6XOZ*vxJ{0c%#YdIq22qI9hAc-+{kjTkt0)lI@b=YoKtg$^b^i z(}aC>qU`(@=`AS_z*##+Gcq5>u=09ldI}aycxp9cn)DZ-RfSc;I-jhyLc(HL&me1k zScPXTvy!zzNCI)q9I}qXwi4*)k-bs4CXO@BV$vrGi^=P?gd;IAj67T?z7CUCA7-qD zAK_(e2nx$3WG2MoFHH8R68=K^8uF-R;zVMzRnv!ZH$OveVrY#88n*n4{Vaa{{zRfa)O_#zLbcpN>c_BWmQxBURI2 z&WDx)G&q8eD#D;FAY89jHNnyfy#=7Ef?)wP^8olX^d~HjBOcZ3hG7@Zax*0u)7(oA zMR7z?aVQ$EID~*gQ|1%XO5#{V5Gbm%(^N$Rxu+e+pG4%lTeWODD;Lj z=pzi|RV`|<<;YNnbk;|cSGCw_Vp6md7;`inp%DmL`jc}RHa^wDO-scgx)Hh=>b1~P zNf6{e8J|#Pd|^5qn3jUl&Vd$U_!jyo3-mD^5Zz+ufKQozj31WfA75dq5YcU+&}5!K zfyDuMJJkZ}pRa?1MBZxvZh)L;Xs?{e7b!6k`C@T5Uxb{DE$ys8X8Kv=KnX~^J(iOH z&-g1yA^z`%UJ!5OGe0e|+L9{N<`|1X@@)veN+=UnGZ!Q$Y;AUdEsz7WM_~-hlBB0R2dy z(}x%!MFGP`1#M(S@h-=Gp2GByxQFL~8{vtgr zGm;`e>GdT*rb|9Z7>%%C;d4QbS^>Eh;O)za9L0QGB6*Ai50r6akCedbp2kav2%9#{S_UWK77Ql4VVQ-8y2c@NC1Tx8C8&e5+3J|jZ@eh87 zh$h64^K~#^14tN12_VYc@r3vCz)xVTcp{fHJ0=6uA=yN%-`SFj!+$0+cgqw*#xonsre2sz_?w0*nggF$SYT0F$a4nIplMTh_%fPTsHp~-BiP{F) z&m!UDFc>z zpPoYg^0TT5%COyGHv1d-H*ePBBcL$ zGHIFInbyB42jx%s1Jdp7C1lT2jza$~>CHT4CiFhiJ2=x*>~K1%Ujmx-(CfRzo1kct zkyOK)4evmoco=^fsl$*EQ$g^CG2kRD6MrmhI;6|PdO=hO`y;T#uxlX^RhSVr>ae3k zDC{1jN?6#7z|@AV#J?`=YS13dG?ze7z1d&}rNlh^O`MIt$k#zvPHmRj3R)E6b_X27 z*5QwZ>G985>VqInPCvhkoOa4iUw|wRt4DA`SPU`4^u+2zfM5<8^L{+UnM8i5LPTt- z2tPjvVH71{ZX)+3F8a^kA{JI zUB!SnLP{DBn`@w<(c0L&pnnZHeS^aaFw^kpCIG&OB+wob`#i+H6Djibm)H0APbMKz z<=B6nO0lnoXAfZ9OdrrPDJ}WpQI|maAMiqyzY*XgY6RN-sBru--TQDn4@dqDL~usO zv0s+m4$Ni%{}_g!L31B@W$G`H8GA^lbo!{R$;NR|`GfCZf_|=E3kQAx4v)hh^^N(V zK?WsDj1Fdr26$8NM~3=f3%F1S|Gqy~A4n7{8hrc)AdW-iKbTBq;cXb-05CO2cIbwN znE|~01W;swbf?Ri2{_cHlf8CNA+OYnxkOeZqwZNGqtUQR1mxVP28~lAiHM_+TXc^M zBg*)WBYJ;P^DdZkftU^8ufs448Y>xIfMGE-^T~kot867SG&GANuSut1b0V;e-qS!tgvJ$EA9-TzO`4cD{0*F)skItdGg8J4}-R9!140bbR3;KgIQ)5H^RE6-x-uvf0c3moL+P4Dp~M4*1LV4a&@UHpBB|m_ z1YI)-S0M6l6(G<8(BbXWe~{UK>uMsL4GI$hGW%~WC&CK=bIEG^Bk<{=ijR6Nr2r$v zh-e8kzIj_3nH4mvtI4b$3*vkl?3#eQ7Ld0L$cGSH#VeVF^+0_mCc+JU*I+qpthj?B#Q!T#>leLqF>}nd!R^eFbhF@rcOj=c%FPJbPQ8N_NcjJE({sOUZ;m)r-S zYXQjeB=Q1{*Pa~)e8_2-#v`~4IZ_WjC{9TuW6|&ma|~tJt?`ubGhoamE26wj7Vv5qsfSe1 zfk<@|1>&qF>UAOu`&$5UufQ$leXwzV4CS&8*!_m=-+}#9bQ2zoA@p}(^*Uf0^l}Xz zLlJvu1bO)i_MZdf3`NrEL{P{;NadL$Ztw; zAR6>3a}n{l_(jfho2C#u0#JGpBvY56R%(WZNdVsdLO))!iSXiqHyj{#;;-3CG|kXW z1n4#dD{xkXaBo-hpTj&G4mJSCNf$I|cG~X8N!~N6{jC4&h;r$#q z)Cm-SidvwifM~u5<8J|%BQp(=@hXw=!Qowi9GR2QoFD^5rU#l&0RJX3-@?gHxD=U7 z&|CoEi~kei>(Nkgrca5?GyP0@CK8k3K+%v`)bT)bKog9NIXV~_haBk?;EV#uJs?K` z(G2#0$P1Oxaus|GDx-1_h#dJO#L=bnfbu~i7a+H`R%k2$1n!53mXl5b@OEE+;L8(< z$s2$~16Fb8cR(9UR%>9Chwua0g627HP$cl~Ogag`+YML!Y0W&Sw$o2&4*2@XF6$o%bq=6*5|f4_s~dBDHn?{zr6O1Q+I51MxY z_|#8By_$3qfVc1K=kID+ey8Ai93b;|wJg7Xz~~2D=8q;}3l;u!s6@g5GJlEC3?~Ee zHyxU(fPceZ5u9cbF7dY*nuP#->KwGBd2whh#=yke%TZQj`Q;^0V%`L-8vrvJy^QCj zQRZ)iaScH1jN&YB5?S2~<0gR2asp_vkKlKT!t$eVpji@`<)@+9O9o>3O=#W#$SkLm zH~K@?QEIBAa5_S`#PVrq{sO=ke~%i2&$uHfI1Kno;iiF&%=aX@i})2#KPPncm&hN| zdzcBG2orCgfMJ7-Cyk=`si+?TxT>;-aVei@^2KsAPSE5j+AKCkiAFrIMgrt$P}gn@ z87LZg&}0GRXnaQA=x-nzOW?GKa48xz#k2x|FMbuGF+yI8AfqCF8e_`rjgUvKw*vKM zfQ|-S^ohU6pHaQ?$`EOEY9Q+jF^lXCRO4ib76s=#JSB;L@5f0Ja~1o$;5SyJk*n-C zR?JiEm)(tZ1A#`QG7n!0sU&Tg=9hvzij-OSN>I=vK>ihBem|L4gbc;r2lCGgu73OH zgZ3lzh@yILoJdum+=)@|&7lC;h%HENVP}#^wTPCM|Ad|Sa#tr>c9>0cwf7*Ig`L;R zVT_oIloIYs5^0#E__!}y_CdlB?kiNVXjM_zm?Tm{C|DbFFJo=ADOj|iD6CHsX=I>a ztsg{dy+Z5i-y&9`T97LM(Q+M_QKiR;+Ak|fBbTv4#$Lk$D@~*~fbZ$@MEbAMS!o6P z7vO=u-C#xiBXo(?<40!09Gp~F({NOsVVo^n$?NCANp-b==3G5BzLZ>)33hcFSV@8RoKTCK@!J|e8 zjqM~06@t=?iNj3=Og)bD6Jrr$rap&1jX7>Tl&e0+-`IbWEzQbnmJELsN^n+QO|$Z0 zF(W8I^=SmBy*g1wrCE8cCFMNXCquTnW&g&Bji6qjvyT6?+_eVY$yF4g%+zj)QXLL7y2nQ`?C0J{3$+V!c+V(n{^2Hf01?` z;8j&w-#`1FTa(=MPDnxs5JG^2-U&rOM5I^|5fnufL=aI_6hXy;3W|zjEGX8oU>)o@ zqKo#dhbye zQFnaFXFTfo>st6ymsh4k&1H8PCNq_ynX?nYh5P5)Nuz28F)R$KL101`;A4U3b z@cW*BFjc(rMqW{|aH3?l;`b%b-XQ3Cnab~bo*qfxqNsa8wsE&hs!TTlEfwkmINikY z+9gTVZku=g6T@+f%a+Soe#(kdkK=onx4K*<9Zk`*K=>&tRzBC;iytyjWxEyuHx?D~Kv;%YZsgqsxaf;TwF*(B^rB|3okV`a`; z<1(ajJoGrw^`h_DtGoO=;B8#7eEG8YoF1(3LGAWIV5&0iLa@&9btSIyh#m%tHRAg) zC&sUSkpkDd5?PxI-x1XOPcC1@9E0T10RK6OIiM#4?tuFM$IV7P~1T;vkbGm)4lh61dD8!0qr16&`< z3F{!TiDZH7H&gPy($nrVhHR<(_JH)9%jKHJ@-7YX9*WdVP}Y+fv($CnLZ%haCjs;=3-nzKbs_ND z>9ncTt(orS>M0G^QcDF*U#Y89EpJ5XN>HYCuhcbZ-FplAMPSpb{6D8xyI^|7DL)G0 z%RAD}V6N&eP5~%xM=w>=lK26rsdf39UHwVutqhvTeS#S_33`HfXCc?$HE8-D34M@w zy-+Y9;BA1uP`tYc1_r!OiM|br>nUtBUMYS&N}64%CVB_FbqOfeQMIn4;`3I%rW*rVUERMf~*bD@x0UGo?2c^WbcEEAl364eL z7!X#H{}Y^3p;mxoglpGi9s$3YCQ}0{++e9V&<*~H5^W-_MfN<hS-(*B>`ln+K*R!*>+6!YBj@fR zY4w6{cbUV9; zD)=nC7^V{N*kZUwFK-<^p@dduckiT|1 zv%E%U)6ag%x#pGhh-;BemdHIlTO*G!3k?T=_VNhN_LW087V>DZF1Zrcm@O1>4&<4j zrdM%E~0;6v)lLov(+66dB(nEg`q{S)JOqFDYX{LSE~0 zV_gNgUaW8Fg?}3Bb;##Hu?`Kdfo*O3uAABx!$tf`TB*F!jVk*|gnnxOBV{=Gq@xfx z5`@J!-?R*BDIk+tx`|A_?lJ$=UQX4?JMl>~Zyhi%^)!(uL0CfOrP3Td84PIsGK!Z&ifd#e z&YHh3NfSYKy8k2UfAa@^B$9ym}-~HGzguIHWzc1)o5%px?=xsbX#*J z{-j)SS9vJ8tW7VW^#u^vhLSC}HRK)mZ-G?LRBOtp?A&XmCE?ne3;z@eK6w_na3$v} zxvdNTj?`~JSPACBLq(i)z|pU}T;Zv-I($3HpAR<&Sc*U~V2tIvG;PB@NZwYoiiu*L zt0T!Bfbq?9^@VBz=DCz5I*2UtT=G?65$3seMP@8Wd9E;J`@2dqy=UB$#3{f$R|d&W z!EZd57=9}^@LZ*upV^Y!3vI7NH2cl}ABwJnK!k}l8S)M0=FTPmYT)I4O=8N;>F|kb8#|5i3P;E#K2dxpLcZ419J{`FVzg$eSNICH z>^29fnryX;7eL#!N6u8uw#^4gut+Z_xO$DDK=j6zx>o*#>mM~pu?*E(~a{re? zUJT5!uW5DcYfalG5^e#BAMfSD%Ut$-koN$yPH7DnGvsTFx?uLp`g`5KS$tGU>2%WYus-vR9wqw+`vLB zbzz~OiA&=J5qSW+wD<*mKLfk8i0OtQuuBW&FjX=nU0U3#Ji4?fL8J)SrG>FuhTEw&gUfxLqJOXksu=RcU02#x9koy4}^Odb*eyWZ6QWA~@Hs+^QNd8pF z6~M+^1%>}j15Pb!56{N@JR;`+Nw^tuu;78ZK{UNT$npI~=YUWWWT z7$CPNDgSG_jt4n9y+;%0x89Shw#*v&_PQxE-?nDoknszU(AI20aE}s+DEPgR992>U z-;AVyNFE4o45>*pCwRA`@UL1~=N9S;&EEr=oac-&#GFLUp;T(jn%2fFLSTZnif&9h z*%EJu)O>}t4W5ZeP-Sh=n{)^;xK{Uw+@vNw7BRS|-C&vQb<(|@e%8!!BDvNlWM-j9o); z>!cpqDUe;c?vZ*qm>yy(Q2l!Z_bskL-PORH%O)bX0CO%9^c84BE9a7h3Ue-75P1-o zbCELYD}kL9VYHOT|7Ygcz-^ z^y=)wt;$u4@^$Yf5Uz5~5+0;p$48hS@_OlAi+rc0Aduok3rTssE=6a=Wiz{jgoqnu z35BUQFhuwbBZzUsjmd} z=xuLq^j?D@-_`pX>a@ObEbUILDD>ALTdVnzSkcSMs7q3{@O#0%8(;oskZym3w+A;e zy@@)<@;S%K(K(i1XGXjSg>#Ujb1dDd?_%dzAJCucsrA`RefgcHGg9Esqijdu6s%DE0`x?O6kbR? z5xhGRPn}YASMp4fV^#Uuch&zQnbZq(snesUVRf5?OgP>*u9xKsUqE-ff4;pq=N0iX zs24wq^!U*7YT^y?aH418Bnj$azeHnRGjXr*^a~)GimoRfE`0NRh+fG%AtGMQ>*Ve? z0jci)WH87-q{D5k`G>a6KP<@a)qFsf;b$P!V>-17SGuU)f_ni}stsPx3t(qV%uuTu zo9U_exafCEwctyM6scZK)ue?Ea8a>}&tsQ&&xyQ5ITFgX498m9&0l<+ch6`=-K3~y z$i3NHNd1WU{2_>SV1g_siv<+w-COh?e#-TR|1|<%0)IHfe-Zf?h+LG)5mGkU7t8WG zviR4M5Xb38<)=f3K%I_+uRuPEH~)@;S3qhW2yKSo9H`nUpne=+g&$1u{4_6Qi*f9~ z$Z(Zp6-e1biB+`R6(V0rntZ*BLv$t51w?j-kg%^nwZuctR+fE9=z~Nr5V}1j6_J$c zP!QBXWGu}K$v=jcA(gB4+_J9tnpOq>Sfzs%6G=F%lPoz<8!3;VWokJXeu=B{1VTh%~1_%}N=M zNI%VMV?6WVdkQoHcSp9WmNK53QTAtGqp+FC-M~gc!XX8zQP`j?GM-0}co^6yNFZzh zdQ-+DGMeV?9EHVFsG!X#Jd2*ELCScJBh@J|Y&auE8>2Cn4 zzS=2hGq584G_TFTekxf7Qg(K-4}WZ6SEB3`U;}$Dk=4KkR>Hml)sk6~rz{%SOOUu2 z*uY94qCj;>%@UEZG;im?^0Y^FNP$FCvt%QBt^)L>)}tS)(L5^*nqHW(IvH6-U*Y;E0X0kkatfXL}zS4=D#3+0Ljnk zS^M!oy5~;JdPkRgzrZYGGhGCd=Od;l{Y5c?9@8{{b6Uj*kcs6&B&0>oM(=ZQES;%XvS0DiO+4^OMJgWC#T z)+ku|QiuJ5rhkS9v8Eq8M3ZhiS>FWK^kc_wkz@t;sbKAFdYEdsiBhn$ z=>!2U)bwkK zTm|@9)3w&MHoX+q(dni)BjQ@V;M&TXezcAHhh%*RXHhl~d;d8T=A(5lFHN6Ruo}g{h<5XF{&|XNL>uMlJATk`dQiuse z#)BNC``zJ8hnfcbeh_C9Ia9<4h|7pv0!;reF!=p`_-kM-P#+XBJDL%3E#GhrYJIT4 zhW}%9YzNi{3vBqKdLsi^AC!`jJMH8=Dr-Agtq*EQt(1f;UlJj`DnlQff<%tu)(3qM z=>;+?5lLCT`k+=hzC$YLgVBhL1l9+85ZN8%DBb$tK&S(N^})GBR*O&{TuGz_WHzEO z-3Jqh|Hclc(FZfs2S?%)CRrc6&x&AuFk@HE{(qw5Lr{A!{2BWy)lH7-B<{crWz1r$ zlL2fInrVwrd&nZObfGjWdkboZKn?&^>nTTW^0XY%wJ(}o@+IU%(k6gleN<(91u#4} zv(i>9o@%Ssqiwcg%_?eEMYLkgAlr0cE7lQ2<^WrD^R^smse+ydOENb>kQJI0y)>zRz#$q<^?O3?ddkc_Y^SKy(1#FT3vvmwZPVa z%ZaoATL&Z^c5cr&I?%J-M_XnP6HWt{d%G6Wq(d6UVyn<9^n)}*CQ#Gfnlx!B* zJi3hqjxh_YCcP4vxsA1ob%*Q<%y1e}tZ#al;fyU>N`YoL!x0z?%y1?U83)X8BpgzZ zGMomonBmMoVmb&6ryml&f;NUTm()4H3}*;wPC*;P5$UISf#KMqJWjHk==)uZ&5-tl z_7upF_6Q7VF^U%fGo+J=ECXgp5)3JbduB*+y3h>iEF{hVW=IkUTYyx`kVHn)yq$(L zT?!SnF{BI8a{=I2JQN#heBGs;#%&xZ*mZ8>#MDg^?MZ_hJsZh#IjA_3*6FCr2CBF1 zN$-b$FQ|%ARH28zCosRz&#spqC+$&SU6PHAQ=l&CA6zfJLgLH7x@0?%cY$?@1bqdm zE@_8m>ym#W@fol#kw8R&+L`JSk+C#yXO|Si4k>8UB|oC)d%!QLtzZSoZawXEgOfVI zw)yXOAR_42N;Z)!&_}mcB<^oSTz8)DPgk&<dV$RJ>ILBb&gsktzKEH)R$BC!hy=E4pn zd`0hO$U*&G;gQ1JqA0ZK%%J&qbJbwI7nR>JxwalsRy-eNPLs7!?hVnnuN7W9zI3)k>a2})zS89D|j zr$8#pBf86HH)X~0(|lDja}b=L9oy59MBXNn-l7)|rMQezxIuC9E>>Jdxs1Dp;wpd@ z*MO8$pyGH&K3$wxewuH^Rl~93>WH*0t~xk7(tYewogHy>G??0y>gb4*qb(@*`le5g zMEUYxCd$E)MEj)=j+E+E2M0&GeQiRV8%fBk4$h5q8`$_98yUY->R?E>#XG0Yg-lUF z>Rd>Ky0$Dh7P7Q*I~6LoQ=xJ@6)MkXsa{b&jlNq_a3W#&oGR^Jbe)2u1B4K92$C?_^}kYb%T3>J5cX)02-0!PDQ4W;7fihw%B8U~ue0V~vR zz`Ld=Q_*wbBPn`UI|UnyKU+`A=UPbl4IjWIQ*a7a*yhM9)~&Re)WYEFXobO%S7C7E z71zsKvE55&NubT~S8R{6#m2Iix9s>UHm7uzSZ$8KV!`p(_~7`fFm>{#ldpJbK_7(U zdPytZP_UQcKPhM|Jd8iXwh#<>S_~b9#Rn9eptz30;zJ70RebSAmV<328;BPM$6~wj zQCNEgXn@aYWDk|f$a_lZY(!RMnuvz%PUO#xe8%KX zHf1*!9J#}W*mLO@R< z-u#!foZU1KZN7&pKBQRZAsE#hmv<-WogXFdB3E#d@~$KpxDBp8)*3!kfs>NX|3%it zuARQ9)8(FX@E)!#o`nfS9?=p}p4|?o$a;+Ha_#bOqwB+wM_+=dD61wV9?^4~t}43| zL{_AM5?yt!)aOQ?r7EsN@_Oy*!l5 zQHGbjlwjZ)1VZ>c0_Kr@hALZa%vNW_7DyJsgY+PB7KT3QMO2R zI}sHkT;!RrM064n^5QxoiS+g5DC6zufyj{DuZd^>Kwzb7{jly1D~APMmqKct8yS|X zFONm8Qc=ST6!#)}{xQ;A{13@S)VRn9Yg|0iL@!20T8*+IlT@QoMkMWdugES&WJl~V zuQ5jCc-d-8e4ccU^;MI&&Yt}NHi5d>*>iT^xJEXjv*+yoHp)cKlB~|2vxk=Jn`0xU z+pv*)+vSfm-uM74h{yvul-iUYi_u z(4BSd^mUPle?}Ps(tA!Dfx}VRHCKDqi2t!v*1)JQyxUZ+9uDIMI;^2c1`_dk7`?hy zR`^_6h3~cd;8oU(;w`2kJcNJvdOUU%I{a%GVQYQGRHkX}-|V%(1pBTqZ_D##GD#Z-Nn5E@dKx0n-Anq8ycxy)%^i*|grUS)>(N zao)9Loo87;NN4pbuArF6yHRQXRa|SIn&R!DM+QO@Gq$VT^XS{qUrkIOP_bsE`fR2q z!ee>LGeSwG!D>6H8lKO?1nPv+H`L_2XSe3&c7eEbZRkmT;3U;m&E&}*ceWT7SO;cn zm`nA{cj(Lwt+FF^om}7^7Q;%FY?~%m>sg4~oYndR{;~aN3Untu%JhKU0^3yOCb= z8ln0r^pbSl;Swc^_@Bal6NRq>em#3KYi@SWAxQVrp;PG4j_fFJcBNZje1h1AAmeQ$ zu3!(9v7Ly7yq^3^YOlpz4^6|!+LS?7c7ZLfbUO^MBik{umTjjUw;<)+ubN!$B3%%4 z-@vUvq#R_9rB)INDZo0s=&4!HP>8=T2@OcpgN)lrlwEu6e!k8Dm#r3m3jGi9Zed7H4|vI1CKM>21@BB}j(I%v7%*rF%6pNq zk~=@;y3RPym2ZJQl*HK}noZ9hkB|js9Otcz@avJbrQ=yh4!XgqpCg^jMcm~Y#NnQhDk3*bJqEir-rVLl`Op58J znfH(o{kRMF=#jF3)_A!eVDNpk&uG0X?ib3aH;!u2FO1=gcf)Qidh z8{zm0l+~T>5_?d8v%n|F`#8wxL#kO|^d2lwR7gQQmElx1cpE9NA^Zw(PeOb`{Nq0_*AHTv0hn&2}duG69(F?nh)F<&o`5Jft9P zyU)-;X1lWyIS2%{y8{tlK?a<(?JgjBJ}}$;mPDr@EQyruiuTjYR@?mQS1b7!3?kyp~mTc9Hh(M>*Ry-AL|@z(#3d zFiKmY{|d_FVeGe&R=9<(Xe-y8HbQ?V`59266dR`3pMMO-jPOEFn{g5%Mt~ zBJ(~-4U{6jg0=(oCFwhW4U`hC0c{6LOv@&w1}g9}irCLa>S!04PjhXg{)M`qfQ^(^ z=P(Y0Er=Jo|zoUD-`@qcz8mhh732b$u|+%{>gc&|0ri zGkY2~#ZZLSh9~QLMQ)nASTzc*joUg-ZZEu?ZgewU(esp5uXVgq?o+?$YLZxw&m*No zadV#+QPw(ObvO4Jtl-KK(l^q`QLh!;R_?2iyb_csrJGi6Td{9}bra~O6`P;+aeAk9 zY-*>a1bI8XNg;RFM5pO>kv+_}DYXK)mi@R$m2ca_4V7=ZAHAD_`L;dWSoOdw(0>O# z7A^KBxl(n)FOc7YDN>{@m%4oFzKo$8<8V^+DB#m043D&raZTDtw`b8S1Ezh98!YX8 zpc_HC=IK~x*Vwy3j|FA76X+MJi=l2;*Yi!P>;4XRCYS--BLqi)xxkB_sZf#Nk7b&u z7bV@bq$~l8f%_A|Dd1!f^q;Pl^jZV8)UWz+@{A0&_@ZUqu4PY{W>Om~7P5Zxg0J%?bhu2W#KZaZSdYCW6=$rbAk1B8vpXe_@=VEOjG zgsThu)@Zu5tFue%y_(h*lA*iHyB_7#M*n;u&t+*q^*a&pNf4A;ZSveGm9mAJYz9Sl z^_TR1)eOda&~E{o4|(n=T`#BSLw+z`%!j@8JfJHGDivBgr(DGsIlHIg>UjJa4d!Bt zgQ~WNR|a$iQW{jbFJyOMYok?C0h8Zz#jdCy`)TvMlM&einA6pcY?|`4I$h<_NXzkl zLLF>vJPMH`L9jMTgvS2X<(@$DQt*G_a?7-@)6X@;3CdmM@2aHM#WTREz`Sh>k@cWV zdpiC60dWG>M7`o?o^}%{H-Q@M=k$w=mI&{h^m-=6i5W-FQ`cxKr(bB2g!Hb7_HkRm z7E5V0d4@0exiVK8mIcY=w;}WrFq40e$UDjvy@JWBpJh@Px*C@?P?_WbK1b$LW!ePs z1Cj5PNz074v?Hr2a>1m>weW>fFDg&tuMO)jJ1fF0*F?z2JyO0-w-UVG8Cd#uGt1`= z@^W8-CE6)aCj)c%7ZSNZgdF}2M6L!5qSl%<(yqWf6eavj3AWa} zg3!w#Llv;KW}m}}*>LfRYrfz#SwqG(r*=M{Gawe&9Q>s09{F-zT786y4}nd=Z;5;f zYzit%NP)&yQ*a)6YzoGxSOf%9@M}bT1sRe{U0UUntgBO-fr2JCEH|VXScRf?z-C}?B0Yi4K#7NbVVE@o8zry3jyi4>uo)ZpuGCNVm4$f_w#3&SPlqC!?37eD`Gj{Zzp% zgZTrg-vO`JQ-m)d5~`5M)74pZ=k}9Vu*s*9N)4kq%3{&sU|7gp- z?C`9c@9eC$jG@lWz?ygGaIt1X&HzF4?y}~c3VkBTN;glBvHnN%4hUHPQ}dRz6=~bN z^L~?%YMwrod37pbNoq&7vwbo{xZaqrSU*lodW_?0YVTS!8S?b8%o7{boU5qz-ndJ8C7PO*KCTyU)CPASt$^ApT(By7h8E6TOhbnVXdCP>(M z!b+3d6MDROT7%rFIa-7+fnF<~ttY41dU8LszGx7vC#!5dc?$Y*@m|zYaE2`?+o9hD zT`#3Vk5`hoQK!N;71ZZSEBwIh#n424AV~HoO&%qoqKRh0n7(2qGLh|G<5EQ ziUh*ugPM@&3Csr#Au$(k99{HfLi0q;~@m3p zqC-3M0n(u$OXZ%`^%UvQCVd83rb~x5>2rzb&YqX4J4WLWw*a5YEvCG?lt(v=79+Aq zd33|*R3a;sCnulPAk)g7q_0xY9S=ag+JWw{h4(UBcrQZsd{8O(x?a_K3MqG4Wg(9j zTC;8<^+sUL`U{b}K(GW}uPQ0PQn))?c)#*!348>Rhk-4DFA#Ye*b*q|kOH+rOW*?X z*b?|pL_Pz-61WKwUx6HFdI|iIJ34$9mQlu<&oGpdT%A=*Q7Lghd+@L`sA~CB(`UVYjEX{lZN!yV! z93hXu6sB&_^h8g0Ks~j>4wH-mGp%d#)={SIOa>z}5M+!b(RL=8+9-(%DNrZ5Yx2H8 z-u6nnA-gNEz0y8J_5!v|nnUCe5xSFo9+7iIXq&Ww$YsFG)P{E=S}nlGcqhs1|K{ENs>fHJfLI2_rK0&DJ# z1*=qsb^uZ4Nf_Ad%OjElynU~tUvX=Cm<#tB=PObJYLE3gq}JS=Z%Ixs_Iwk8#U5e) zq_5~hcBP-%XFD`npXZXxR}iNNcS=>fCe`N^NR)$&LK1^M*S4=5$^x_bRb`uyH=A!j zwjP+x4<*tUn9VCoNP&uw%^$2X?n2otL=FUj&DS8}E6{MJZGIlfhXb?uIuf0Nwl*)? zPcvonmEGBD_k!!47o&1#bbL{D90v1P6dj}T`f6I7E)fOUaNMN{n-VKXUJh(ZtRb=* z*p!fDNP#tj-QiRg6PprOBeDV5l#oQ&0<|JFB}7Nl%=DBvR|*xhof5a8=O&=v*srvw zKDbnVyASs*pN8jJ9G=SdM+XnqR%9!}n}J>b96VX8(zlRb0=xb>_^`IuKeKx{1h^#6 z`wO~f?<&%|22^hSuiV70n@b2VoBqcL!bfrHe1< zlwN@5x7PwRorHbCpsiH8mP#)sNSvk3>Y{w9Kc2+nK*qBO$VunCOGKx!GUmnPuw~*X zm|+Dn2sgizjz4UfIE}n3fh`kjh@1<&_Pa5}XCdwmL8V(*;0}Xv1xc4kb~?n}MD7G7 zlJJj)vlVI!$kY^8=CA@47`e8zjE31X-iE|Wz^3tgMBV{>p#lY$BknCkUF7;A_d1NP zNcv2&&p~AM!g@fxt`zs%gzSOn4E87K4c>!r$Fhl7`kyH|Kc-TGUXi?ZHT?RXjJk=W zIt7@w=MK+yYhZSyunxd)f#^Y`LBw?s1BvtpfwLl8Xioxb>G`GB%F(2b1lGzui0lsd zWoyi)>6=>a0NXOUU255jOk9oc8ltjWw0ib>qYJY|KJ68C|KyCUs~|QIpCAme#4RhA@NN6iJ-y|lv-d@%wSlY>*93XV`uZ!^U<7MVv??b8dE_MpOnEf>qgqq6{=V@2AOPyxMbXvSG z7(9!qJxbY*hFT!bL2&jK=PanxL9lBaW4p!;(3gQqZEvLA|2m5LvF)cro6X)$>Yc!B z_F*Cq0k6H}k4N6QnB*sz?9(JYnU;Np$jg%DpWlCO+OyUJ)DAU|L&ZJuZ? z&0VV9;NXs$jJ}2?5FBg{!vqIUHo^V%#<}ZNr~&qeH03g9oxFUpo|^J`;`25f6zC>Zr(f z%|VY|CZSJ*j?(%P2!7h5Rq)f%fuKI-7P+HJgfE8_2;R|Gf;c;=-x#E74hN|l`?spu zxVv&z9d;!CCwQnTccb#07vz!03G$rRM|rAL$F=5?EzkL>JeOc8k!7}WINgj2@+@n# za%PbfK+T1B=X0I{CpsdVZaxle$S0nLkWY$*2igjw)(+q?J~6uoqdB zDmO<0bK2`^Fkg>n1e)gbYHi<~aaLTvu{0`rddNCd50%(0Y#0r854v9w-5nhlvPrGo zf3fcF!RW8`tyouE5EHes6>IWB%+T~L)?Gb_BW2KD?%vcU+ETKOxUWYkl2fsgXvbG^_p#;Sy@0N!*x zB^>78H)uNf{nDSs5%nX5HKo6bW3%mmZ(xV@-{br1apKIug}!cO(EQB7gA_~ZdE(5$ zW2|}E>bzV%Pn_9c53%@K(%?Q2-h-B=Q10)mv*?3dX~ps2+3n~sEPl=l|$dec$nIKnY$uMd}Uy;FL+LUaNp67iLP1k^y_OV2DK2Z)fq zWkePNI|tb$y$Y}_k8_@)VLkY(E6}SE*`PcP5SxhHq&#w)5)Ub0eX`y7SKKPF-S}S- z*#d&y_}z&33Nj>@x(WLX$xi{>jo(kAQy`C?envpFpJv`eLR4;bt3(xGrk<;Ji7Qmm z4y3$_wr#)_LA+1oJz#_NG~(W2^ho5hjy703Ncmi%8rYwR`~W!E(*wGTk<;a|{~|=Z zFOvb-Nyk4_AqA3kJzUui6|Kvx?uc{)c9}JRNI&3ZWbtT+wxV9luAP|+ zLewUtz$8=G&9l*S5U}5@70fxoyN^H*>g!*nb+-rg$Fq@IPs(l@M1J*?=$+s}{dn-8 zepuh8;@_AzlNt{m)Q<-b>c@iz^}~8lKN>u!9}gbX5C4EL|I&Q1@}#~~6+E0D*0-sm z!Nd7If`{|Ncs3qCDBlnWSIMX7(3JmcuHmb`o*=BJ^<%-)`r)5o@Q=<9<4^6Ql6YPc zdO|-oq;Q4e+}8B?r{@>)CmuYZAKnxqo?om&!uoJkyej_<#otwN!|mVwg`ZNqxr0`N zu%5&Zk1&4E(TS48>!ii>Bz}24F)ya)@GBJ!$Nmbprjlqp_8#2Mie|<11b)LOL~~<$ z{@%V^R~^&S_kAT$8`HD*0~M`{>B;-y`9vFHdhUL-qK$f6&zqoVpO~Jx-&4^6F+FiV zUC|*iJ#Rl-8k)Th;;6Km4b+b3jERQzuzlhXUmwT|>tXwhlXIi!OlA@^@>Zhf|19Bf zC4(PXp37^1Ua|{8Q~1yHKaWwXV>{^GpHXlF&1KIsT-h~!U_|_u4qkN!4Z*=X)1Sbi za`JdPl=L-h!pm}C8nrdC37<09ZG4or1CGtZCv#m zZcs{gIrHyRa(d0cwTxjGW&c+1(^_R+#>8C;+G&sdxf1Qg!+&P0r_U#04Jf+E{1v08 zCqDmKbPV?Du7h_OiI;*L@iXp(b2HSRK}8SjUcYE>lB!)%7xLsNo-vG+&4}C$=)kv9 zx~Y3`+aB-!DZEEWei%e1r!-+2)Bt3-%zaWk%Osv3e9kjhuLbF6!t#<|M6}y;XTX0E zZO;RD0>s-y-URu7P316E7>8ay{80`3I|)0G_#8xbOBIN&pb`Z;D}m(%JYNTHk)o6+ zLlUs@lO5pw8$G`OX6=1x5&awUFWrlfiGECU;2wu4B$5v>k~-96>v`;VznqgklzNi| z!N&024jRMGNY(%w!}nXq@BHil9W&Y{c?igcuHV>pJy(I7{B8^gV!_5?PD z$`aN8$72jXqj@=s+ZfJ5plG!$B~Hhq3H>1Z~F<(ogeJW7tJw zh{w%!3Z(6$h>hQgXgVI)_^l#x8nE$`psye`ew)=ejo-ycTnKFZBoI-c3Z%wQWGv0w zIerzeLkc9C8o%q%a}D6v{=6d3yVWLXBQ4$n%e7=DQloNfCymPeh;9P5L%y{+ibZ|_ z`5B1nM%Jbb&GCG$Br-sO&T($b)-ur#vQezX-tESi2{9e?`JNKOAgalFPq9Y&6!^=4 z&DwkI|F&KU*&92>cD04ZKa{RgkZF zEa8X(buV`CPb}U{;726B2f-|!BE<^YSb#qO?Z7Nx8fi{J8w(KWr+I+|*d$&fSq0SC zdp+^4YN<(FfU-O()g-PW(jJ%*NZ40^foc*zpe!CHyH#4Dd_*$x+-!Icp#hkQ(Nz z5cCza8Rim_i+~ODjifmRZH8H-pXQ~VwcOy_Bv>HftCM@Fw(^Hv(AEiP{;dABfG$NMBVLA#a%*t$e@$b7V!&`DHq z35e>h#gZx++EtK$0%ldmwOZ9uv#Li(cnB1|%a}-O=n~B0=;H6GQI4V+Uy<-K5-)<3 zhv|b{SOL3EZ)s5r<75{2E+TIOGrq5h>;UFrBpkJX92lUU*f-k?52A@6@GyfA^A%|1 zQ)^5PsYzg_HU6R87UXRS&n zDa$pq`W!R3VI&NYqzrC9B2z(yHWU){??ez|8_Ecnv8^O^8K~1{LJ|@EpW6c0U%MI6 zG0|pZb=pLn4lDEmtdxQMnY`BlewCZcP&&WxXX3}BKT9L*=JyiqW$O*P86HMu=Y=gH zT+sj?0iMxWi%@jZ1>wmTgrj;O;6Phn9zf@PAgcQ|Gi}(PfqV)SaNA~o7PC;q% zBLU_d|OsQ^HJ8FmHj^-8f627K6cGk_DIK zMfKIbKBn>%_$LEY>!rh5yPyzR4P48gP@UMu{IBh-ZN#}qo&{KBf@_hqTS)z{!`?c9 z)rGEp?bp$!D%-t?4C?xx6v~RKZ1-{<%5+1`6!s@03M0O*pyYuVA87uReWXAWAbekgamflI^A^Jak}SvQ;`T@bg`T zE>QwGjtnH{Rq4pUkGP5-Ta!36u%yb=p@9g^;;ht}fm-C1rp^qstIA3p8CY4BsUrgs zat~dD6N8{49qq`Vqa7J^yoO4xueyaHj8wY9bs8^Djgq6Bm8*eBT zXM7;qFi;8JP|fmj%*bj8*CLPLUWDZj;VA~x40{J+BI#Nc&LlPCT^OB6?FhUs%08WB z3*?-b&dT45)E*%3AQH{Jc*9$7UzIcab^Gc~db5MwzB;^JaQo^wmOlLo4?rTgZy+_ zsbd(OUqjcPLy%lYkfFI8DJ|%(xNbK^rxz_`Q`erdRO$6x~hK zi&fK(J{5|)m|no|(@F7=m+>^SFx1!nF?NRDzYh(`cu*sr@8pwM8h$ijf}{&{4u?OKhi3c71Im&qb#0`>Hn?l zV)5))4EZq@&+(FKMuy(L4~_MEqB{RA1}64qSU+_rhc*1OH(9 z%dM)_F6>C?!^Be?-KvRFyBhj*5Iy&MkALcZBdqHoH-b#!-W}vS4Y=U{Za90w(z&U4 z*C`Hn?HcWFhqVrwwD(S~qq=n}G#CYIPV#c-!fZOyElH{*{Z0g~rH1WIQ2iwxRsH)Z ze>2GDu+A+RcsD}NLp}q77A+Yq<)1@;AfB~o$&o51ITZg4x;|kAouq?7jJ8AQ;C32?Vg&L*vAXsJ>Ksxak9css^=uu9oq_di zZz4^AU(QyB;8bLt0$oJyoft<2LNCG}hRhHUUQL?XuMxC9<`TxsQCVx0Re?P8wDJ>_ zRU^48*~S7ZZ%-mqK#=7sWl^B&O|Q5mon;mh2c)wcO=O|6WNtz7P(&YZQ~ngn4?ju5 zFEXIiYhHOX@h}te)Mp2g1i`2&XD~-5bk(S>KO5{$l>RiPA zm7qHP`=~nG(C{4a7|;rguK5o zh;RleJIz(zYY9qh!aj#0Pk|;;w>&HJpA_*~y3C)6e6KRS0)4oolVbV6wfx%JL!HXi zL%Gc?rl5gTPwS+4Jw?(TUGO1>+3s{o>w}1Exky*0wg|Q>m4*g#*MXuay>KXrSZ|ee z<|w$sL4_v%O(<|h>Zt0(&hg!sfjBi0YuKU995(^$%!Nc20B++|Ghtmp z)aedY!s=5{qxvMYp>PG=Z$v1eO@}Mk_1}uy@>Q_^*~*=#ud!riNM1j+-nGcJ`IbAg zOu1J!vuFX|v}E>`mJQICif7s~$4c8n(D#6-YLU#A(zhUA0a@xT{agn%JtuMzWrQAw z`E4^Z7liJE_?5_iiMSOaV+0F22we?PM5F-NuxRko!-6^<_j4TLqY z6mBLETGlAB&Q!1xWY0o&%-zV0g&HN!L2&jHX9m-4c3EC^UbV>X6WLLZSIq zpUNY>BefD%9_%gBU$0cp2+e7)xGECpnA1x-da^+Z%^4>ZUX>c(NL{KST#Npxo-{F}xL*WF_0D6Z;p*tw_7rGWM{iUFS4RVBg?=X= z!qiAz%k+ZgXuitPDXISvmHK>M>OVaNS5eW_f2Nux@!y>OM?+j|Mh4pdqDnmp5Y>|a zk=^ZoQKg;)i2guE{$tgKpty31OFdrDA)Gp5&3S;dnyB{D{8y^IAfjRPL~9EdD6W(L zXhXpY#eY)JX#bF^<95Y$nH9?~R%4>6GwU71Q)k4r_60Eh`&4&|O{V_)l;W(BzbcEq z0LFix(%E?@-l$AmB)Ov=q1!v;^^#n&?|O)uY$b$~d(*R_j@eI=5KkUQ=Z0#H$Vgrz zqLUF>$%jOAHX_^0c~Av4kAPM04?|7GOp+5-iCf`64xOb))@B8r3B2~&JY>vxHJucE z$|_@8Omez_H?fp#Go2P6m!KE2Eciwma#Z!)WfXIaNX(PzaR@Srg`PX6qhbe*#1DXo z+ILKYR4;`*24Lh|P2lCYvm+x5?k!E`zK(4jFO}|kI%1*Z0^JXX0^JKcN%tC*tOllg zVGrrP4)SVXx^K`{B9*GTPyFx7{2mFgzQ?%;pu45@ww)w6!9TJ@0XS?#5I96Cm)RnKZrha3pGe_Hh)cL=Hr z)}q=?N~V<`PEOaNVUhAl^-_L3S{9|1PwK6DUjccsSm#4b8m8P^Anyky`p8nLZq!ZL zPU0)DUIek@bD`2d#ix`F(8a)N;-4V!5y)N-@ja2RLB^M<98`g612}m2jAmzhnyRDW z0ndLhCFV;^M##a#6YvU1%>#Y`;`-UBhl%j{=&}^gGKm))JQViKktDM9v|`WlIjZ3} zc$Fxs0B$%$6Oo?4i|w5%+w#b>?v+eZQ#T*}5F`dE%PfeoM0Nog*QRnlJm|e#yV3t9}^y4h2^Aqlqj8tyQ-^Q!S|aHOiu@pNzyZ&{}oc^t-BKR{xu-pN*a~ z0kTzXs~(2q_S;!?>qAw2|Kv(tgs9gqBHub-Ro_753eZ~hu#~2%K2up#^_!9SGia^4 z1pc$vHB|qLUcU!De*x?f6%?cXV#>i8u{{c=c{iFQ`dA4RG~+(qu-5r^JUrK;>8klR ztU>edN%Z{{nBN%ISM%=+$dAO*{2SJ+`Ioy3jvtix>G{{Zoy0D%I)dNNzvi;d+PP}} z4Md zI{`_?HtE_njxZ&iPl zeA|Fk{e2?uf!3m$w68{9PRgYNFzpeWJa?1V-JwE}e{`)CAZfDh7r|kG- zKaAX}9vwq2U{%i}k^@?+Zv7cWF}+@(EUJ2YB-(-2s!QNMdtF2IznHRJ(bEOAnX=<4 z=f9t_2`!lotyA_Sa=I2-qNZ#^S54VL=<5Y+$~Fwpdb~g6K4NLgHjL7gJqmIjD0znR zY{~4QDZ2{RN>G?KRre<8{gShp64qgtka#h$4%$p+|XuTAD}s2NEBE|K6i~Md}ye z|IMR(OSd#82dakhD8HcSXJ8&BXDs`B@CP2HsbrqA$fHysQ3}kX^d!>VvZRMeonjw0 z=#|XJ7uiq^LSlfj$fN8+WE5z%?Y168|3Aw{YZ4L@LF;J!e|VJr(X$_59{k>;^h*B0 zT_ADf_0JOHJ?Oc6GS!8|7kT?OfwkK-!A!y?v|Ce+1O!TY* zZRYCtl=J(!%K5=;l~dMNleK;6lf<>Rt6a$Y0-B-a^H(ULzY@H%cepHYrA4k|#a`lIb6bY~9*&aG)Iw_wbUtt`GGD3{n%YOzszh@+s9SWf7uwT4P~HgH z19yRO0aR_}7mLPK=h*6=6w?nA^5qw|YRf13PiS;AkyyKZ;rho_68BdUI$!@IF63WA==*md7WS`Z0~_(T5s&(p zR+GtZA|Ch05hnbha5B7{tXQ`*P!;~i;|TQ0-ho0dbN1XNUTlyN;qdFIj19~FnS{6( zc~I1FU&ZIdV~lEO)&8=kN!)1cV8#3In}W}^g=>7LCLYHDe+}gGPZB3 zsJkV7fD!TVeosRjWJFfD=qiXgM&xE5%?yamGommk?>H;3G<@?Bh@E6ag%_Evf=>1y zQQ?1!o$@(_XC6H72rsrGS8*@=z6w9JSdBO?^U#AEz1ZnVRdIQEkZN+H6>(*Fl!yn6 z*ch%B@tzUahwDXrYs5`i8zD-a`e{?v&BVJ|{LU=BA<}5^%~^Uyq_0yi-=C#-Lbel`VMnTU5(t=QqQO{0qhLw{r_Ix!f{>ZaKM$QavP;dGOI* zqSC73Wgd0xA}`U|h;Uf{wJ*`lh%$nqi!MD_B^$=@((!UQj?eZi5^EQJxh zaFVgyimFJ)1H;Rl_B=^`ckNUB!T53K|2rnbdz=-<_xEP=9rjD%MEsZGME$dwyfObi zB;)=Z!i29U_p7`T&5L)@6*RK_Cp5BMo|H%YtsTAU_G7ErOqRusfv8tGR$ zdzu<$4Z2ud{$X}Xo2hIKydL`JdD)$!Jpr?!XJ}o`O?WSH^4t>0M9~p0kc$Y)3 z2W9u6Z;n&e2O;kUO`0xlfwM2)e*@zSlcSD{OfGj zwPxM3-8Jb3lBF*geAw}xd)8hRcayyi`&4`06IR2sk&jB=JyB;5)wNp)vGm)+z1(k6 z>RQzLA>ku}_bnbmdgxrwom?P0or2;Cz{^(8)*#~)U@H7Ckgrv9_3RNy%mvo7#}YZF zHA@d=QJ^eqBApVcEUS<>EuG~8B5Rc;@e7r@iE$f%oQ!S=ok8X+U?o+soLOQ55&60k z1EENkw>;F$$OWf_kUbCEk6G&a*(7CmnwXZ#q4O`)BC_STIaZ&}2ZLMZH5;77;bc+A zypyU)ADKokGYurs(C#nh1cI2CI4&ihNgj%@2ZvHMl0{9G=aA1(bm*<9X* zynE-%(6DuF8rsbxwX4WF;9BI-&DOitsNieHbGr?UkP=sKTJDG53~JJI-#-_VbluD{ zKOx~GV3zq4k?#O^|MHZ-Q=t|+|Ie+h>omaTN1?t16S}Oze@iKPTsCxBKa1yC!Y6}~DGWILxoonosz-a&~4*@&sAj}ZA#c~sOlM7|QCqW(?f7tl#Xov5M|Xh95J9pb+A*VsIWCR5l6%|oLauOqoagDfU#}#v2broInx`s99UCcQv=IpNee!g|P8Fcse zhUfV|&%dAN+&-yJojP@@Zr$8NWyb3i==o?DL2N^}EDK{0q5(juGEq|R36R~~X&Y}J z&{+s)s(is_q;9vBQEoo~Wwin4%Tn!?cG`2VM0Yvh_S_plj&Ow=(A)!^g4c2g*A}#= z`+&(x7I=rbENF#r3I$G7p)Tuc$xon5n$#DV4_WBwFnf7t4w>9x_EX5Y`fOGfu;F*# zp%@Dfvu${oZNnQ5Yqjox)4iAmG z2n`}SFpBjM9*^j_DArea+W0ywiZ%MrK$YsSDABf5OT)BGCDZX~{6+40pJGkUW~5Xm zW`ssx6Tb98ZH=$D%fy%Yy6d&z(pnx+fbFhw*_I>VWtSgxkg=1>bZY|-h7{VWbs zaBP9w)#%>i3L2SFd}kq?3`DO-p-h}>pso_96K1=Ja~ISWaR$O^6z4stx5ViRXQ(*; zhWZgmtibOv2a&&%3Rt+G!Fclyhn1K{RDp^uIk_*nH$LJ$4kL@C1n};KXb;jBppb&F zGse8#P;Po##umWpgR~b=`TLwakWxSiZ*Ii91m+N=g8=Vrh_N7}0Sv0Z0vX&FgCmNe zoce5}yX4jP0hurLDrqlOTeOjRJ3cZtUuGF9OY&t71zE2$nE=(d(aEH9h+)S^HFL6x zOt7wir#lO;Mqw_b`+#rE=qW;FF5bq&;v{OneZD5u#*`?I9>XVv*pZ+;BI!QQ`~$h*OQ3tg$f{xFfz?}nprE*#}vILf_n zlzZVQ_jVZN{l zll`N(8v4P^vK7KL<|FgUWx|bl&XPHu+*z_q#n)RwyityyYH+uiyVG0I+Ix|j;OD=Q zwVhuO8g%Xm-s5rbcrZ+OUj-r^Jj2uw9egkRo~BHHV!K*nCfOC-AJqYkA^tnaQbn<& zU*QzNCt{zM8_98O_dQLI*n$B(fw zNDqi^L8xCXU|YQKp^?}^wD;XE(=LZMZtp{ZDWJI{s@***S-!8C(q2Z-B{k0g(yNx6 zDLuux8R}1fd$MrKV6mQqd<=+oB$@Q{?;;guM0UoM9R%-7gr5Vprxci?e})JTxvoGb zqXR&ic{%QlQ~653wn*e^8RuLnpfN<$FP3CllXsDqk zSC4{cGwrvi%yd(zLAX)FJ>u4}8=FF$A?R%!?JBDY?nSroA1JQZsk2aVePgTQ`cY1? zty-nu0)W?l>Pd-lw0Ia`{|d1RWHHcA&pPvqZSMqoGGXZ)c?$Ec6V5{G4=SckxD@1K zz(glO>E~(9);038)b&o3o00xm>a!v42l<=Si}LDtP8pz21LMY(cn*bU@+IB`dHp|2 zplkZ?lP~cF3ZLam7|vzS}8d8X3Svp)E)i&|XTlYW?=6*c)Mu zO#F><#cB$_=3+I&Y=|@)x|!?bE?OP)3F}%T-)!H63sxhR8&s8o)eJHM;HR^~TI%S9 zvN1RNo!Bv){URBsVD>zYQvc^Qj;A$FZua}HYaA{!ELzI@->Re+&VIQSl=lOy+`i%yf<)^S?+Yi$=XO|!a)1)J;V<3DpDYKHDG?dyEAdPGL9B&voOX6aTNeF~3yR zPVB#SW1AgzVqE!A)NWpD)1UKN}MerPZZ{D`0%_>sncn7`OaJ}y8vXp(BzJ{zw{OahD56Or~> z7?{{}Mo-T_$sCthNCKhp*vD|)$}nBKYTuP6-kcG?$oM*bijVT+Sn2Qr-Q?F7blglu zcA(3IVQATwEglp1(ltxWzyVt1UO|Ul0u)A295_wB{}u9fAh~~UR$(qZUW9xeD0(bF zfuA=4e+ESq5APLt?;v~&C>B5d0i5`kPBk)_=IDne?EnTv3UR@k4gWJrd;*k6rj#@h zy;M~{R0uUNq^v)9=>YiuLiGp0q)u?QX`!@KdZ?%KX3?2c0eG7sia`oRoCQ$>(gsN1 zo+}xdg`+i*?C9URmrDJX)6T1eRZr>80Kc*`>R7ESR4*_dCh*UB1?;-8cAxYhj3zW2 zfWn(;L-z&JodP)?aAED`!n!}?eqw!p2N!~?q_q}uIZ&iP$h_ZxqrJ+SX=<@h7l~8Q zI0+zN>XA>;a~mBh_NiZvuIrU^Q8^pfp+j7M{D{8QM#1P4xk&ozk4w?L7%2G}S=b+n zv?x!T64VdHsXZg zewxxx0vrc_KzW6?F1*#xl&$PUS14EyBPrsav%<(-_&ZNf_+O>ui~0Jc<=0VvecBY< zREK(ptgm*JYZ!Exr~;;7iUe&6tP;ct+RTz5st&YmmZ&=Ssv+Cv$YWHXa}5@4dEMX9 z_cIb#Ovf*qDfkJF)g~;P87*PuP=tj6L9Q$Zi!AJuNb zduPxw2uy`8!h2h5Mfl3tE>8NqOCnQ$xsUYR8o%pqRO)xl`q6C*g>;q^>>f*zYmR-j zCpqNi*!G>nId&^{^;>nSoQZx6`s>pHo>z#a!ByiW`PHd`{BCn^N&efZfs$YEHkrlq z^R1^R4}!YvP+0k0s5|z^?LFPp9L~5=9Z7p1*0EVrtW|gP88)TwvJu4J*G4)f8$>m0 z$4;eb<z9!K-nCO>kWUH&n@X+#L2>#ylOxerlmB3pASS(D<{`daygK?0bh!$ z?uB(aLI*nImO9o%UabQ80@j14%J6 z@4=~u>I`JQfEWrg5OB_`aP(C4ypy|~gU~rY8|f}UtBQA_R8HFIj=aj=i1(68y7!LG zGZ21KCj7pwqU63hGHNs6|=OlU*=P<-;nnzRVRVT!&zNA0-Mc;RK3? zMRRZVr*2qW&hkXZ&zGq8_|4u#JNIBxjdZJMgf0k&hyK|uTbFGo{J^c z-kfuA(og2j!6_fPsUQ9*#~*qa>$J*vMbYokjm9A2HClw4=*iu{dk7Dr*Rght4-_7E ztH1cL8t`;I#c==zlzNX^{bYcON-wEeYjTl zhukcUuC`VmZo6L=d)nILQGd?WYHJ@OI&Vv-$=1G%&R4Eh+i(gxKG%(@);2tYQmJ+I zTGK&3sx2Karv1L@qL6fu@cve2xsF1+h~d=bnp1CYx;!DKdg;qN(>Hy`tCO(A%pAzp%M5|zXFjHuAk*ZwXR?iCPH|h^Hxj5oGaPn>1dh!I8J!o){VF7LekmC|9}c?Sp&^Uhl&Jnr(#J5YGqBu~Sl zx7fdt!sW6s@-lsNBygEVB%>~t%1a?hlQCLK(VkNy*(Af+XEDxg!b z;ND7-y;oXm&#AZ`M=5ir#$9oh1;XRAPxBE8_;jqFY-cZ7Htf~oQvA>ZvAGyZ#gw+Lz z%^eMEXPKA;ITrACr@Md1Zo~FM$OXXo5`6p%q3XG>`LaS8Sojn!osJ8hME0wM)mLWL zqPrTf??D^~a*T+VAU1)V29VB2LCX0cO363a@JdB-$ow9Zqfa43!|8lD3B<)Bwf@8hV8`W5z0O!V--6P zxnZCZiGy>-+%Whjn$JmF!{7~&*MK4o118gN$-mMiOy65Yo(b5NhmyH5u(g}Uz?Z0R z12hJ<_R|0@cBe%=SHs$PjamB7(I!n+2&s{nfj#BCtA z0<0AYpnmo{)Za+VrA0-P;n|UFop!(^YRzzCCGd5lHgLFP&^CI%+0jrNvz6%;MQI$Mo_wIM`e+r@ zVjy-5De%Aub;y~Jr;Bwd(SKmNSl2>c4!CZ6$o0_!koStEZhP3VUWEK7KrtpaU=Fo= zdI{lU8P&B7*+)QY=e$DLpGssrP`%#mlMkQk`}SIybA3 zhSR+u_lVGNdK~0Yz!b|!j6(`jn9p1L1m4?6A}(p4N9ms`rKEiq|cV}0EqI&P9-il}!IPHK~jF{gvR9!V5aOu00P z0Q~;5_wG)lX^iW=1JGFrxZYa@vOvmj687HjQ941T)O+WGoDI-> z-w`!;`e7lIZ3&ozUGKHDQSaS|(sh7(ucc1C_YlT4!hK`21E7-ws+|Bw88uQ3$omG=wxI&1Fao; z4hmN%E>u%B9OojO4Y&?n2C@Wb?NDiN@6f{$t(UGk^ba7LL})l(1acwJ+M%vsu0wA? za;;R=p$~%GFG3yq49HUezry@nXs?iOSBI;+*Ac!dZH>c^Kt2$mp8Ou)|`mEm`quqME^oRROq)7<3Q2c>R+r&HmlyN;L$IUaB!Cc}&t z2i+E#GhBdoMKTjG=|AI?es(QhY-)R?_RjagTZD9fX}AeP%X^3D9#2#HH8b*YpD)e7 zduRwEmrlpERXQC)v6VpVqDN30DCxzJ7mBr>o$GO9m14I+ZUMY0G70Sa&j0~OT?xweE|4y=Ha zz-!p*^-uwKq_4xI8Fa_w&7?L!NIDEi`TKB-Zu-ZagXFI)*#MI-sXgBBE5V z2aJ>d5jklOn5A}Cs`Hn-HuUPb$Q)ECX0J*ec`b2o*;SYxB!~BQ2a!-_GGJT$Y%WZD zca{AQXz5#k3)9{^sha3sC<3k*_nt1pb&%}<7rA|0ts@|Z0o_*aYxYfQ9XJtcJW!)5 zw*R!(*|+d>nq_O@?~1}q!1jb#46;Z>7UEzKzUarDE)bhQP7*O1;$@H*fx_)W?sppa z^BP?qe}?1}V26aF5n;lZb`KB&JEuVY*=g7cV>_pzHMVnhZjJ4nIWD&I7;E!fD_xlP zaH#2AkF6OloF~wIYM5>L5SuRRX0(&ZpK;`Sz=d~@Bl02H5rWtViDL6meaP{EE#x0>;A{SMhf5}J0?nO5w`w9?l$mE~JGvR7*>M~;^- zm1^0j)|Tz$P$kfW5)~$ArZcn#Y|oimShnR!Ou9x6sFB4z=d)V|wAUNZMG@Nobr|4X zNQef7$Ni9h0JhJQ{$x6BP|20pa{cxs!pDJdc;6Wg@9_KzW2KOH=CC+xnBJ|ij%Qdp z;@L2UNH6!Y=vlPCiIPm`^%>}^#15x_3HIsApZq8*ZMfuD)%O_0JmRl zaI6`Slf=@qt$p1*um*Ak;2NMBz2P*VPsssP=^Ai6!eaqbwG`=_zixnrd7zu!{eYX@ zBmSN4UCyN!65aYH)N3hcTk0!v?$=i-uxDfKbU=Zv@1(%q2DJrn-gk4ZJ_Gp};QW#) zzc+q$E71$BonO&?$QZy>O+Z@6Sr+o=e-qf!Bj~ga=$nqtsnhaKb#T31fvG|uwl^8y z!FBf#$R=Q*?s{d{*wO78XTzBWxanF(!n6%1J}gf>U1PB#YITkw9ETMZYIYl%Yb!dq zp{E3@a_ux_KM<@-1D!XDYeu{@=ppSm+Ls3XrES_jPvU#SgRFX53ks(=JaEHXio=5; zPO)q+?9TLc!0%LM`feX4m6?8TsU$RYdNcijq5d!EFZFc#!Rascdgtq2>J1829_!56 zFi$6IoXQx_tte!2jOUKSOxbi&wxg$M%c*qqwzr_8=UR{$@iet|^hT%wrhT=1*le?^ zKxcAXsm->F>NaJIu(rwmlIL%--Sa+evQ4fHI#=awvQu=n%C!Fw2fd?gTb+)op;vb1 zx#Xj5sYp|H7LglZ=faNf3o=w#ViaBM4X~r-O=4F<05RJUY3hbp;F_M5iL!&~o=*0H z&_X9Wq}4(vyOS%VufKVn>?}tV%3LSAZy3BdEsfd7!oo2-z!mO|MK5MYxVB7XW`l71 zA8w{qN57Eu|3!&5wBvuiED&s!39R{OQM6g(9Me|Ln5(IKP1&YmYO{MJdEo%`+IrZK_(q3&_g zEyF(;-CR@8zypXuB24=qm~(@jLtUL23hnM}L%TY)f;6<-?(cL!aIx!uUner$-D<(b zU0tp1y2+uvLa9z9MP8$agT2Q8;(>V&K= zd$iTvFWe{V>m*vJy0NKMb>nEK+EzCdagVI8U0$fQeg}i=Lxa7ww>^L>h7+*Pg z`nhPpG$q|2N?{jEWO{2|cO$Z6AZ*J?ZQ0%it0U4Hz&-#m8f2)5ry&jkSpW=r1;VY4 z?x48QhFmm@k{Q|1>gY7IPEj$fj?M=;SAgZ08+X1&ax(}OH zR}Ay3qotMXKtWMd`vd(*B7&yVD7FRGhz0CP0DBe0B9MK7 zlA9q;0yzq($(MA+1GW{>pA;_@e;0+f0ayGRkgtG2DjptP=wgSN+>XI2;IR&p%kbz! zKZd2dAbc+VoQvc+w`64Ta52+TcvUtQUJH(e_f^Nj>%Xz^7KvEyrT5=aln*q{y@!BrFir<|_YZbx5m)aa;2Vqw3THSN zzQK5m{=zG|5#3?UHyE9PH>i?(4_&d`9oDpfTh#*iqZ~gwIZ>fo`H~A(n)c5iG|82# zR+@UDfv0;96Wt__Cl{_X173w&>5UP0(COecUPUkP;nJ@4R`dqnNqC*ty$|?!;a$B# z@n;I}ndFYOeS|f5wbD31c#~Hqjdj8YC08z5WsXxt!;(ut&l1|4Ttvakq%g)igI-Bo zD|~_}lNS%*pKGvhA}7h8>-=wENB#;POlb28;*Pg~cZ%62_`$l2N06e2z%tSEsoF*x z*m@>%KYziY{+pD@rjwOJQSlbj(u@Lm(XRNnDk1wAQ}T;^veP^Y&% zgf*qBqb;h*z33t8Ui1)kFM5c&7d=F8Ml*=I7d=GXiyopE)KWI;Ui1)kFM5a$hm$nf zF{uj8-JZUVnQHSPwHi;K$4s>o9(ejbW~!s}#(PuzF2d8EzL1&fxd%myypNf$Qhnup zt@p9?`%9A@(`}2XS;7Z-dJ95op73Fw z9)eCSkey~zCYGwrbxgI}^XOxlsr`HfrEDk)N8}Z(={!XpQ4w=@Vf!~Vo7yh==1pW? zR8ND{T!FT!->sHQocATw>9>hH9z&+$Lpt)&N#wMCb%1RV6+dDm{N6J`OZFp(Kv%vf zZ66)3@^(fy9yNU|BYXg&Mxgs1DJXv4oyBN8R+4JTF?@ZU@QH%{*s|Bdn}GH>!1Tx$ zAtsaq?9+vGzq<@u`83?N*V3^2G~@Yl$lljO9{KmEx%UllZdWa)1%Hu&qztsYhJy3{ zFCC>jn~G)tJ@;G68OdHMauDPJK>8(0-tHQ4ETmpOTO>P^q9jH5{!dOS*uGjeGv2O~ zEDhL}og%q9uIr{cuA$@=KwL}C>zY)@-yrV>(sAmz-qrCEB%iJMuXQxj)X!*C%i)oH zQ(HQ@rnXU2TY5i8y?$40*_IIwKg;2}X)v0KwJ2>6d(d)IG>3mWkw&;MZ0IaI|K5-5 zia`8GsWwQr{X!ZBq<>^iING^56mp6~L zWp#hG<+O#Ii38$#sCM-jCE<0DSBP~I^3}7&dKmHnAiaRL9PAu_74k(OC4({_)RCD7 zSDp%K<4nw7BK#ESEq*2oC)l6F1p2gxxQ8N*n9k@@X(8MKAfw0d+kjMx7y!`?q?3qI z5Mw}g5-}O#cOY|tlrHtin(aqLdnfjY;eejRJsjbofYoc&P6Ig+FvTySsz5J~Z4dMt zuoUQ$kMhXpAg80muiz(!ndo3A?At>kRu6ApgDt)?XsjOIybWZFhy=t_Addm1{UCm( zoZH~A@&0Hh!Fw0so6;T$@g2xF0KYcR5L`R4SOK?lDG(0RiNn-Sg^K*1F7ge9x>Ia{ zdz`WGD*AW75N!cn6ryz~92BA_fG%+;8Tx5Yf|w;a>QqO|HY(}s=7KTpRSB<&9YbTK z5X@3z$3^UP7~TP>1Em`wx*~NO3K-kgo(8V~VM+>z(X_gF@dS5UPI_~O1P%C^uVGUZuM>D)nHWn0&cj~ca`p5kh=ltvuNFbq*zBm9uB0` zg3Z{n^Jziv$TbPI3*K1>Hvt7|#5E`wy%5^Ajkp$Eh2#oJ)dER9N&WE==l;z|{tP(x z?*X|B;FprCH%j|3wEINbFm2j_@Sa5eI8bn4P9Z7<+c9F-!gvwM^FXOmSHRweo2QtS4!Ch-fIVXL#+D~98!x~G!K^a~I~MpY`+ z`~(~0&&et!d_7O;&uNgrBuENE~liQH=s^zgQ?Lss5;;PBjA51ikc znR)Ah^QiI}`Ku#c-g=;f3QL{R7+UBd{;04~I>zOt2kMMaX=78X(#FxDk`8fsX6BOZ zO6zy9v_7;nK#zfD^cZM6rBCgO{9`&n0Z~_498N#32VBCO4RX2&rP8e+H;Pb_{R8A_ zplBQ>!t4n%rkyffzdFFSXm)mK{RztNtF#in@IX=va5?U@Z`dKn>yUH=NY-_=;S=h- zFpADMHqeKQ?WSv)e;7o4*c+dV;1vGthP;ZtTx_qsj{6Q#Y5A`zS4(Bq4csb&%GbYA z*_*Y5D!LPulsksIwIQr!z1Hshrryl_mAf~6^=0(P){4QfbI$^8f4n^?!cy*@crW)R zy1k|Mzj<8V-4oB7=uQmng^$a}%G9x}WDQRpsiuM;cf-FIVW{!qx!Ew?eek?)g#Q%Xt2F6X;VD7VZB~L@`f@q4eB>pY(B9Nbv$2L;F zZ=oDoits?7?BB@sWYqhBmbA%T#_(y2)uw1J6>3@vubag;(Dq5N46tdXx`3Nw|<@x{B$R*3Se@^3RtFg?RilJyuw z1^csZKbhRB!{)gNex1$wWU_twZmv&o68=e0D zXR319FuWu6|20*MZo~a;KyfZrmo>Jg>d9oLOV!N(CRGDjFtIlX$&UG|XRQOJN8m7* zuO)%r=uo<2zAluSvyh!f&9*!`=1@~Kk8-wU3~`SuPb*xWo=T4KmJkzH>Q$y>`wGZE z0*PHI#8@#OW6rsfm=8zEtl7GZWNviH{4mP*0wyW>!BpV8-KDSn@GSE3Kv?p?a~l+G zMMY{ljOnry>XX>xOzL1&0JD3ZNx~+7-)c4DD}2uIhTmkeDoJn8fJ0 zK@KK}*tz%^W^yf<()1rv>G=@rE1YS3;a58O0r7!!PC;iHW=1m7TFq2dgl2w3Wq`}} zyL0mE%Bg{0hlhz@crq-qN1Et&a}#qi_s~T+?|8p0-Xfxfa=LxV%ZS^SsOmS^ z6pXCC7e+*<>k67X&?VvNx`I)T-*HSPLN{BT2FkR_3`L8(q?ubX?HmzUoe0Ww%=AGL zw>lG)>EejA)v2IN&y3Qo$m(2Brf){CHmS8b8IQhN+>hW5yPy`31t>IYt5!u)v5l{i}Bkx|1oUE~3MS z!r^UnVra-G(}+P34C|otO?LVHlpJ2Xzm)B9e}EWKb`^MFhQ1@CBmGr~f{x8aDeALB zBZR3YQw?scZm}xrm}!8BcVE7YHF4LS!L#=7zeCVFGYz8FzDMR4HM=4`?KLcvipD#l z$qq_FOmaOmER2Hex+qvvuKHYPWZyA8Q(h~kdQq<;$T8dY2QL@HZ6ZrpeHKmjug33T z#uis5^rWiQ6U4>UF672u$^NRi))9d{9{u9Zj)+^G+byooY@vN=+nx1raZlH0MfSsu z5PhAuJS-x~07q2XnKC`p5jA!{8EAH8YPoO+G1f`ytUfJPyt5;^+Rvpn%@IBA{<0P( zN`rkzW#&3blifv~=GluxoaV~Rw-Z(A9~`m3u2((hIN|{N zn$#|E#6h-)D!s@N%k85obEzX%^LPWq)z0+6R%gtMuW_+H%+@N1*A}aAZ z{Lr5TT>m?B8bNKvE={cOiZsl^A{7yA-0WV)8!|@ff%JHNL7VfKU4joQp;FqItP1t` zlLp{FqD=;ZmJAH?L-T>baP#yRO@2E$uCNk3%cC4Z$EZ1^}-9>$Ppz zBd@<1lgIc6Lry?r9N;g7m;5zYZn3xVKNh*LpM7I8krW{?(uUuz3@8comh z$dBuLtJ9C8mz?A{Bh{f}xTlHRxsxuOeJaQ!?K<+o>W8{BRmvzg?Y?f}s34k;d>AZA zVhYyJjf&Ot)c+ii-X5#N6sup-3G`g3zC!v1@LxmqXDW1|@(-dE@ZUmp!uC*=qEQUE zP;~<70F+7YLe&qdFW^Eo7i2dP3e{qe{Q-Wh?aO?tP<{08Vmg)ci!(Gu1xK%*)f0X)Hs7avW`UoCzLvInwyprYq7yhp4=wR@Wu{AYaa ztDTA|>Eb&c{jor6dm2ZjHZGa zf$y`?QYKK3^{swhfvmnz=Za~D`7$h~7o9qun~UfveJ@}QTfJY&nUkQE*_SK4hcXxx zUef^Bma`}o*A(-N>$$7(?s8yz)poh6ex}StRLZVCeVgIP9qS9H-~XY`y5|S*gj|6t zt#y^^ta@B`2|w)iRezhS2Sk_*rSy@ zI-v<(4PQ-xy7OrBU!3hRGTQPy`Y!D>*tg`JxzjDa-=vDy<;;gWI)gQ1?`*pQ-QY(A z+tBz(&J;Yoqnf5hdvC$HsQIrT_zsnCq^9y_EF6dET$Ofqtu&o0FR*>cwz|zndk!R(G%zZgNw(UrG!KTS)(p2~4YVo5OTTB7BfQgvu2b$Qo z1&5oWS_HP`DMYSMj;T|h+`N?g%7Je6#MT~LrY@*DQ}}U(>Y?~Abm<8WeHgXB0|{Oi zR3tM@0De-BbXDKN$XW9=UQriy>_W=BI@a`29nVwf86Y+YyKBbF?7tzowco@xi#6{n zigjN`+kyBBYFy`P91A%dNPLTFjRrS*hC|Tk^rd!Y;@@p_!|O0kOH^Nk56ni4Bj>{z zg_yg!AG>Q|fw9e9`s3aHj;a-f{sE3^u+1i`rC__8sd}!vZFU5eP$7-^7sXv;xQUKg zZx#M50b&Q^`P^QOB*kfvCjs%NVeOd}>k7zAfao~vXh}7Gg1lbM0^?MyW@U8ZM%3-> z&ch^eRka%nXYBTU{5;20-nf1I*k0Pl-;LGVfqu)@tTtmuE10iBJ`cqIO!0B<1)SeO zegm|w1YRnmvT?O#SaU0Z*m9Of!1ld}_Z}K7nC_;LWy0NFqym*PKzVN5s>yWTzHAbY z6|73R#Zx_sodLHZ7zolIaEpQQAY(;n-LxCXY!PlT0J0x|C-)=M&weRiCl$=b*QS5K zEEA*lHL&0#Hh(~UlgfV!@kbD@)bMMak1WI2PAsU2A=hvFM7?vu>|E6ZV^ngB_EroS{j#QJltr(18?y%yiD z1Y8$(8?G+A7m|x%VSjaZ{q+hY*S~h?FL&>E_u2=Euj{XENI#NBey{J{jAulC2^wX> zU4Q)>l^=osvA+n-_Wnw*U~L1q{;C0K1GxU`3DRAJ`fC`-5E1IHsUSN8JM@?LSH-Az zL4=lv{Ut_ge=R|MvC6Bz4hC84$`}0+ef>P$GtZ~a+-xhx_Wt6KWzygJ!{{8fnoKJd zSKGO#0&D69A!(D{nf_1`+7|7gCOeHbqoiS{yDFxu*EXn%ny`vFVrZjL*D+!`yxfEn zk7PUS%lPr`$o9X3|0A^0?tfuFM!c}hJSq#m&kFaoGc8%N`d}E1?zpXfF_R9T4ARcH zQm-TO-x=h5%;;rB{?=L%zS6PENuPHM3e%xPy?b;`huw?$Ut5#e6)z(#6;DZ9Yxv4t zC?07Ut_5t#>Sdt22sN1pDG=G%UWBjVSi-G5k&Q09Oy+?ignNcUWlPCw$k95BD^>CbLeKhKH6kI@@Dugezk*ORC7Sm0>`%0;HDc z%D(cbO3&O!SB3V@6298CxBUT&Omt1y^eKN~Z5WGqHQGn}Q*|jXrb~JC+o(T1G&?-B zm>xPrSmnh-#T_RPO;&YeETK#HtQ5!JGpF2hu!~N;F5AVsW)D_Lz5OZPwX^zdn(3;+ zsh?Y6w_JmQ+iM@Y!kD7~w;0XswZqR{ch&Sek6Z~$JVc4;K9Fvw-PIkLVQwF!`0m1cm4o_^$r zIku7tf!Y}Do{?8T&WMv1hqS2*RHWMpy$(Pi-Tokbf$eVn7`hcLe)ES{-#Yl$eyzjQ zuiO#CY@>U1j(yxn{BS47yAC3rNTyMxevdzo3*nh?cQw-MQOWudmV5ose|>rPe|;-g z?q!y_tDWw$j$c{Y3sauXRtH-v2(`(-yYfa-C{j``Rw5qlowyw&$$hxdK1rdRW;vM6 zBY@^r6Eog1_#JI3=8HlBHdx;}{O^vP1+=nza(|uvQ@CVo?Q2EGK*zLx!#2N<0 zH)M!L(H3~NT~Fb5dhtQJ^R3ZPI z=3xN!ER>z_T2|x&G}< YdY!Zb4M$s%tY)_(_yF9*B-WVQOo{;Y&rf67(rF{MZA}Mn!YiITM)y=GGTz}6S6886#G(o@f z80C@hVu;nnkZ5=@Bod~8)dlHjk4g=~NSFeV@WMzWyaPEBUKp|8p}-x;tEHEFNt-T= zME9>eUaauKh}CD(xEr|(EE{Foi9Xy;;->H-iLCS|N6Kr19RB4+(z=X`-p%3gH{zC!Q_b8{F6R@#Mv~f3I6}B%~Ebrc66O62O5z*zO zpt-~D{FP*jD*mntIyTeNwwV>+#&g#$>N5L51eGh7t~5pNd#iEpW9%0-I6>M=ix}jH zBA%GUkD|f;;gl)K7FXz!hUYFmw9gsUnQ5*nIHR7rzmLCz8H+8xiHgYve ziO=coE(IEe9W}V_gXbdM#|%H0gtT1;-2}^>-Kp(-HreoU(O#;S#<34Tr_-GJSC9hbulA!7QXG&q_Vk99W!I(5MI$q=2SG; zHm{Q)*~zwE*8?X0PKC5FzFJq`59UnW=v1JM@fEU>`tVcb718Dw$R<0{Mz&YlP*t}RDBlFhODbZlRhIpTwyjkQ zu4i9&4N$mSfAP9sf!2M{_lS2Qdyu3ZCcUlD&x-dn29tKGc%MOk2$WuhdG+Skd9Sze zM5}H?44-pdLy7Bu(}D|Il;P10uqlLN&2r2gEZ9Ohky=I2faGzlCBr3Zb{L8IbCs0z z3yU90@yv2oCqMUo9oITivK=sb)uR24{kd7nd>U-b!DOZVv05tn5q+x84yR3@ZZ}x# znBU8wrsPk13LT2E{y_I5*dOcX-A77(S^Funu|jK3MKBwUT>zM2F6Yq2q^P0_v*geDE<=ERzQC7a&l%3)SQE_I|si)_6gAQKOD5L_jKOXv*YXx{5Ecf zySQm@>kcilyVCRbw$++qI$05Vr*YA)y#)1gdnji51LOBwy1>}Kxm85xD6P7$q#8RB zpX0#VR5AMZr^J|x?k+&eqVtGjt%h6)m~Jg(X`7PC)D>pRd#X!Gdh0~hbtFoM1HC%p zr?mXM>YZjn9aY%T(G4sHA4k`=q)Cv(9n`W)GS`H~uSVfohn5{j{w-$s_g-!eD8|SQ7`PJPNnRv>LsHJCYL2Za zM^<(vtV_jO$&=M5)M|=M{*06J!`aW{FyHj>XiO9X<>;JTuDLZ9g*6ET6SrdG<*>dR zRo`>e^_c4GeiM{h>@7uQLZqJEdHf!DUm*Pq=<`iZA&|oOxaM=q{O}91xW21c3{eP> z&gY?ef^2D{33ivrI@!A%eg{8DuwdPvGwI{519iRGG~dMNUS1tLkKA=6Ihk$ZIg2*yS# zJrYRiCgrBWbrfuYJX@@`B*c)6+f_r}1Gv1DE!3E?fWD?7caB4=Ohvfdo#GIsv%UB+ zC#z0O=WfiFx$sqq+?cK4go1J1LV<2>4mQ?&E`eMMHa3NL58h>*0-jT8Vx=*EMd@4w z;f-+H=o6`2ib{6va5C^bW^TzRp{rm02Xw3sqrI)}eZfI^v{V)zM+M>0RuCRLm3P2G z5FXA2;UQcQ9>N9TAzTn1!eK+lML~EhSP?`{qN2*kCbks&lD{J15&4mf*Zmup9t2G_ zfOL+L4<@~Gza^%NLjx202|i2XOPqT5g*fqbUcE=0)90ajPluwuKMH;?_bIJpQQr|1 z)>Q*%y|K7Cuinq0aT6OU>rKA0Ep{-Mj{U)fL%}1>Y^vnUED*bWVIMB>mHJM9SEtGujNY{= z-QeS0mzt)(&&$<#@0;=~MSWX-zy7{2*VB6559PYq#QU-QYf=9y&x-nYxn8SZqm+nr zw{03}knvCZjy*+0!BCUzagMngah?*_p_ss4C?=WWZVjD>Y=$eKR);cwZKt4O$CR&32OXGxv( zTm6DlsOU8Hn^pUM+oEd9%H`L?DVKCFgw)$9mu>H)T$;U`a%uK{%H`e%DP>!&`ZoBd zKM5l$X`5BKHte}diA>ri#Fw2NWbrn*9J47Y%68b0cmq}nLawU%ZR_Lnkr!L{*n)ic zt=wOL)k|Yj5eZtwbbYYJw|r_3kH*;Sc&gPpWCx9cHc4yt+#u#LNEtX+@N`{F_*r7Q zP!?J28aKzt~-W2V{Omre+t0=N(yC$TNAOUs&o!mHG*G35l5zNTvvGFV#sA zQNwvJSgx+b1F*WG-5E$c0nrRHOvTGl`c-kGyEC=F`!jtLeqU}IvDSX(rriGSJJuur z7vGnQG2t2S|NMP9zCG8T#Ekubx*vW;E_<+whI`DI&b9^N+346CC`LwBs{?Z1R4Xfr zRwmwoPIKJUt_6gzr>$FQx(E#l^s&euLgNMcR%BnHX%kxp9&Pk*fGXFgB4ce!{|%mz zp^EV2Q7_PVb#zy1^xcE}zI%}0cMtOW?m>RvJ;?972l;*XAisY>EiLiggZ#dGkl!B; zCuu5o;v9dXSF}(ciyU$^MuX3(AUOR$H>U7Xii|lUuVbq8QR3vy(W}tCOI)jsLiC%B zX>$@KQ+&`~s>$V4c@Ri0cl02QvdE}Orur#*)y{F6r;`LSXInld){#>vH>Z;r`;sDi z0g+o!p3_g#gCRL0G?BBVwUbzk`O60yP_9*}3k?{Wp5IJ*<-Z&=4oC zujSdpLN)$&v~C7cry@(7M?JrDkKO(g-ZSE#FaGK9_b8SA2k_n#{|fQnhQDWp_}{?$ z0%&&|jj4mtUbhX{y~-s_tiwCN{o?nc;a@C(7v6{u22{{?4?T(#UFvegd@qRl_?v}{PQe+1L(ILpyv&S>z>r>S3 z5!Fev3Og0nI(p{7a}AN#{QJEybDsrUg;yuQU1YYsY7zugN{SPp*nDa#d{q zh&Kl&l)(_+!&b2nV~)!esG;<)dR7tco+1PswR0c z(Pb^4KdMpOT@p&lWM+(_an^5Z4x`apvD4J3xh~WUqY)mr$iT1t`47KM@m}Pipm<$v z?%Bkro9IF2x$`HoqH-5wei;|ebDi4AFOC{MXW<$y;xoD!6ALfKl!vSLj4sB+!izEG z;Yz+dT*+s=LL`H$7Gk43T-BF{tNP4$uwv7yHb@e#@XN!)gYs~ppQ(~U_+$zSnin&= z1`-dSOv&gJYdpLLGHeT~720IDR5Dtd zCc1x?O3D4ll|kvxziV_k7^gogn<%*;@bGotb<6gW3LKGItTYNPka$ zh6P61W#E3-=_+v8Bo*)o>jsl~XcVgBJon_2v%Qy%G8OopCP?WK40(Q+U10bR!U_B* zDHicRf*I<;`-Fvw2+9K9tYy&bmvut zDy~b+wu!|-&V$`Twa|k(Az|ZN$&KAZ!i!%@s{Jk`{P+X{H7_KBcpWj?BP1g6pKxc- zkch^Yj%JDpiCFw=+CM)eaAzl?wYS}dCl&Id&MvXO-sf3=+6wj!;a5jIQ@>^tCzo=R zS3iN^EzePbsf#VNi5N>a7sLZX(_s@9g@lbKnpydUgy*8O(nb!Y8b96%2UdsS4dMsU zgf*dBl&_#uXswku6*6BJzrZF=%-3_FO|^E`A49^%_aRi9L&A%{Pv9>O2|xY=-FRt8 z1n~h7mxV+mZVAZcArXzwr+cmpiJ0k8gx*!Qf;uZyaaYxNHAu&cK?;f1TQ>44bp2+k zdfOIC9x?SDn~ixVq`XM|JTmy*kg_qpDj0dw`r5&aKAzUTXJaxrdchbL5MfAZ=o>bn zWqPA*oA}4{<;VF*zK`Ozd^#RV)_#%?-XqldX-E*fmoWaBRXr6lRqaJLCl-VBTf6r` zCc3#=`OM6_l7K}w_njp@i8G_gm1JGf3E=5d*bG0Hjr$;wDGx6dW^}2Lr{A_wevZ3T znCc(@J6b7SD@+Y65l-og_{->8VQP4rYr)6pdS80jPtw%I!u0Us$E2Ck#lm#{(YKzu z*q0vZKd%x)H2t*g6GKV1y>_APlx_(3+GpONbYOb!q8Yl@PoUPbg47JAm8*2-sj=+jq}U% zrJ@}WeGJ@xgQ5EiQME(-ZYiQ#z`(S_%J0QKQQd^p4i70?Q$b(Y5h3N(oJm62<^na@ z`Zd=OGdn7zf|@U-xl>4SU;Qq2P~s4*H>ygLI*BOSv0?AHEVf|=c&P^&0Cqy^ya=A9 zzHEk=m{P&g)E6o<&@@0$!+AbNvkglXEFyC&T#U>el0KDlbB>S zIng=W?F%z$-A+*W4M8fL;N*Xi+$p)KvUu8fimr=3k}qZoOQtZ-U*YyF?}%HWjWCn` zknOwyBMC?G#JUS8i39dljyxa^ph+$EDcsrRH zu#yEr@rq*Mz4mAD6rWUD{4AMKI4P>x%eu|>X~R{(1vDfsTaE|GrG4Rfgrazjv!oAV zhN^`#WPgzhz-@Uh=TUI3c>WXuaCY?3JlhmbRdW_P<#oqx5{6e3VAb-L9~`ug%D=Oj)Jp+2lcap&9=$p&zX-6gJVM>;+Egj$bQ<9rPnj&7SWZcxk)5)q&zsG$DIla$8Q5rhWj`ht=VhkX-^KYM zSva3C6rAOH<3vf79dsVN;LD1599@Hb2rs z8Gi-jB>=p8-lm^fJii|r{QU5bt(_gIs-~*oIz$Q1RK|3+GI>W%QFD3t zv%5yB#z^sTL^?h1PHU?BjP^-9rN&7&&Xm?SvoeaPk<&MZFVV3r1=(C%Mnv4>Av&+x z7I1AD5ou6c20=H;tlF|u==U_}Nq}q1=#aM*`ar<7MOFB&A}p|CiB!EW7uA*%(K#M4 zozxa7##$9eN2**q&P3r1DVc6bGP74Ci{3DqYI!p6bFWC9{JR*n3jybIuSk=4w?p3o zIG_85{yh!-IN*G440)eHe+)RERfTV~#e%VYBUKkrmGe2do)s$)#$PJ2R>j6h)dNyg z{L4@(m13d^CGGr8w~6FUP2`26^9?wyEEn{eFo8Ov-wtpMs0kBj2=oBJHJ~1ic^N zn)hAc2Kff)!vNR3??c{2&=&x%d6e66kbf6c={q2X~=V!_yFgQ{=x zjb4P#{y^Ahsl-|pp9`wm;k#?}YLr$=v7iN|8k*kP=p$+8{jSl|k=3b=mPA#q(f0># zYCDRuhXbzB_XlojI~V#)z%}Nf(D56fuLWFV9u9d=LO&|KPp5D{VvyBx`eW$#0oOoP z%XG(mcZ?Q_JrOYa1FaFY{VMq6@Y8l-68Kx=+mXAhTRi3 z?9b4D0$jsXt#7o&9b@kb+TTF+u3_Jx^A!*_Oe(Qf#k+&{FGx}8Y7XbtU@0cXp|rPa z*o*YowXR{;9hJWgdTN_ok6jz4X({CrK;&E!``Tcqb0|3mdI(VTD8*V}45W}AFI!Dw zY=x)88PV?54sOTSZLjIvRTogdA=G5XUsaDz!kib>AI9$RAnYwvJvtY2UeHgAkCUK} z74HP*zVm{SnnbRG=FURX`Pc^-&_SWjns}QIQhUt6ny}hU2hnSPWQlQNR5&X5op|vh zh%69!&)Hk1vDy~8TD-qFy$#}ZgRTd<^r9;&7nzMgstd)3!|EsYPOwW9++%}|3hsU| z_X6A^qulj*xFu@850Y2Y1lOU5p>qge+ApDdYf-dj7Pig^GH*!dNVvx%KNjdBLG)xe zXF#2E*8PrT2m}9%x%ZB;s>u4ktIjz$cHi#XiH4>#O@<~TnWhCK2$EG~6c7+l zkR)bBOqfsv6|fB`!>FTRcJxulFec2|aSZ5~vlvDlb>7dn&bz1BWm zJJhaSyW*)jRdTj9RXusAXN{uuv@m~Ayq#GN?!uES5RTTVG1)R zXuZT$m^sPcA<1G@b@(hs%FYcEn~)67gf#(;8OFe2C1`v)GE@c?GakG0+DV%6Lk$l>z*E@Yga2)oLK9Lu?{dPN$5R( zPgBw@E2;UAAMYKKPmWS-wmZGB9l&f*nTo<@{zJ(g6~tU#u0&fC;PP@Kfg6Ms>2W(E#$e zUsi|X$soh;CH@9liY*CRsOKYk%P=Vh`|TAj_x zJm0Ny6uFhcdA>U!9{ZL)&MxrVN-U=S$S(DZq&5~Pjb$NH7TY!kY^Cp3A7e8ogPi5J z(c5M0Q#v_&j$bVEW4kASoEwT&z9my%7W+iMb2$lMs#=h}z^_#kiak0KCC%VOFRu>a##gvM0fE(x7E zupfKHJBec|--YCo`Q9tplgy7^8|AVrc8Xk(^4(Vf!u7IfEB#P(m+DKH{^o~r!>rH^i&vR60~=lD)%e2=HM6`<%FyfB`3ew`vRU4E8T1YK z=c0W_&79>OBTp5qVhI^YoP;VZFYSL8f#x2-_MoY|W89OVQ#q3rId8~CvyAr$!sIOiV{utEBQlyM`@Y*ZmJ7E41NVG#h zUG`yp36L%I1;-f1G`)&{ff?2mDSN zrx4l+m{cXowVc+h{YsKtB?p+9^j06*ob7Fh^eEIu+(X)0w`AMVhB_7_Z|~gKsL$Ql;gedJol6hcDGG@EQR_FvW_Tg4JK(i$1v=o_90p?MSUq7^|fr&s+ww+jLuLVj>0P`FaMFw#A<-L zh!{hGpchDw)l@Q|VjRd!ZmVThwR+;m~;ln`6ROjs8|Q`8IjV4^`y3NFNUxc&NV=KHyo`+4~G+~G^wAU z$=ey+jMaGNovC8FiX)!sy#muL#0ITGxJJlEpg0@^L|M7NiSz~N8ElHEdLD37ej+{K{|lc0nx1>qY3mEatp{61TFxQY22Si zQTX(v?s32Wn-~yO!+I5&mjP3y)>Vk0Xa0^;p71Me2V~T+-i5zQG8Oluc?dEp>5j0Y z4@3AI)~7(C5zb)cqLU^-Ro{e!F=jWJr6JRiV?h1T-sq9d_2I+|xMI zq=v)M)FM;gO~t!Jo&xbww2h?)kNzFPN)lQIM85(#kHFbNegV0Gz&0UC)IUw&VZc=> zDe+94A-mGAn$js__E)gK0K(ObgPe?>P&DJJI$45RruiA6pPZmpr6m$|PbXOIS8bD^ z#`f4*OltsBQHlvo2o{380=s)l2sk3O6{2DU>nk2cT&+ zK7|i{6EFQjM!J4)j=yd=uV2om>DLjEPlts9misI}f~0kFri2UwVjjAO**il@4cKf1?kBu(O7hHC8yrdJV13(4=e zIJ$2$y(UBYE+l!0RVFcosnT(XC5|Gngn&t`K!tV;`9-nO3|ZlxBxp5Yn>6pJYUoB- zsEN^H9-0&`>FY6iBvJ0QDXSqee9ODnx^+U+quajlw!?e5 znYZ0`)J$6MCpX&y7Ytt`ZnZU#0t9%UosM6>x2^xC)s4PZq1jcXdkJsD^1L=OS&mqoBa4;g`-_ExcCe;9W`Ch8hN?&UUG0byv z&xQk<)sli2pG>cXgtiVVvl34u!EKa~pMcymBx}e^t%9c2Amv)K_&F;kk*5HExa%mR9PiVO(E25o9GoWas zzCm@{sGm{%X(uz_xiNGpA@z+t)WigeETkgl`Xt*l;Jo3KyUiPJMPu*)Y}4FcByGR% zth&|`4GoT}x_`i_%INp1l4s!kQvg%*&_oL5hE96x(y~nPx>3SM>BAON(-UKYO^&IT zk&wA*KQW7Sab2)!y1vjT*2-tFX|9wEyzc#4k@05F>s{!8wGGskk=oS0 z;w+YUfr(#2Pa+jQakbem5+r*vNrt-v2!280UINT1OmYMqiF@uTt@l90x4T$ao@)3a#faIkaanD7HBF?=} zB~9p!ZiDp=GG7Cx%`C8)==I$*DZv^H)X&NMionl6o4Y~gA!FUsWg?l$vB-Wi`EH_{ z9zC$mAHc+aTfC5wu0D&J)}8 zNcmueXqCmGV4)o(LDS=Msg1ysyF*^Y?(29BN7li6uUrl()`APyC_05TnQIh zl$5D1YXIw<;p-(SAQpC$B z(@d#o)(eg@Ts@Gf{zA%rw%y%Plh>R1KiiN$U&HMhs=yS4ZPVR!|H1i?a?YmsfKHo0 zUS(wI4kx-9qzz zCBSCqq4WA7?Hs$XtOC(Rn3)>WsXa)I~fZI;s?@E2e-= zYKsUz>Ji@L=6*OQ`bz0JkTTaL)C8H^4)Pix`on(Evje#^zd2kK(cvP0r1v_EQ1Y{S zjQM{#;u5)dKV)`$0iv}rTo1-smf4E=-_EiW>oCH4B=W<<2rg45zm~}FSs`8|KRk*c z#Kt&_&Cg2vcM_u{a}q)NOXg68If)=4#;{#B@jcW!DK+;Dk&)n!ZQT9($OwXr_mMggoO{GCfDbgTg)S(&x>ON(>)10 z_t_4I5cJEZAm(qN3av8ji*47$7N|)r=5{MnGF%F|iheFPA96f-9&$Z%Wm0Z(F)@3& za9&csUD>B>A7ogN{ShJC*O&SZXCh?#l}l;F-&kd;-ETfV3))FlV5sSwlElFDpCJVi ze}6uNZK1CKxBdgdp6r+w!;o8>OI_P5dug?cL`~v(RCN(c0k54N_w(S|8)j&UD#zcy zneRf5pF0s^m$W{0h>eZPiN`i4;5?~Zd&;gU&?J&@)BS=lom8s={soy+WiHmq40vD^mA?-T`ziJlCYVK$wZ*(t%|7 z@uX6G2j1U+ST%edtt^AjaY!bph1+6T&zhEulW3G>%MXbbb=s#h_4}gii0#ikFb+bY#AgPw`!TF!PsobZQ zvEnCK2Vnnej?JB$DsC}XQn`j>&H_fT&>RK?eYU!315v_hcGn0_Q^njgSamzGhI$Lc zugNG?Je_`>sEfoto>rN|>D0UL3 zArW5%dJuM^GOV@oWq0WuPEF9Kxbsymb%+s0uk3a;VSd#`5ZYo_4dBe3KT_s4fc6tf z&1wErRn)nlzXQ6tD^TapQ$0Hid^OPOKD<2={qCX3(W1&$B$9Xq`sE000uoPyY$LE0 z;C5NW<=uW6CvtGu6-nre*c{lhb9~5l`{i8Hpfrd?RvpDvD3zn>-f0Tt15?WB2HvC( zf@YgaNYdr>z;?>%ZKS*dC|gaVKe+HFNTsU&hvbO+44g-S9?H#?=rEr%M%jZa-pgj? zE4W_(E-Swf_$Odu4m8+sQPE#sn^2dmRCa9+MNyPA$*Q==2&iF)f`7j|B$D8Hj6fiwC^YNMa zxN%TL(@QfWD8r@L^j5w;!wZEV)Mx|}mqQv(MjC)Vw}2c>;6Nau?%^l`3xW90&A#JT z&T*aX&Xg#7Q&MGij$vM-j5Nczo+9n%W*CS6E}UWPY%L3zG38s+Kb&DC_c}G58_qV8 znr&oGP3MNErgOtn)5*O~P3MNQ4SuinAy4mLkEEs_nM2Z@pA})nRy^}c=_Q17!-LTS0u0>^?mn`K z_OB)>+ifNU`@&Qn_BlM@*%nNb{EWrOV?TZb7_W8KMS>rOV?H4~VXT6eP9x|7Y;oou$@$>z}7 zOP-M>?liIOGg8*}nkZ|-)5M|7wnM3j_6_FqY(X6;nf5$A`_94S$j+Un`9ueD8nH*v z&ZG8{!zd0rb_mX&SPG{ZuWb4i++wgpHi$s*;!McwvssqYV&IhZ;n5a%D zM>!xY%tm!UILZlOVO~@xgrgi07UoBFL^#SBVPQd3XN0315*8MT>X2}hQ^LZc(Z&1n zb!821H+Pxn#ysCxYEk1LZyO{%!x-4D$N|wm0-k_)*{FOU6(+lG;=^#7}MfGHp;YE zhoQSCE*$9Vb;pZ&CH8~HEv}<9h zo)a|UK1iFk_9OZO&;FHu!nZ%r`U86zZ8~CaqxDDa5_*D|y^3etmbo5cBa%t`G?F=X z*i02cH^Qlm=JR_q6xrZl46xtQn{uIm>w(5O{TJbaz;=P2wzm?iz>XzcXul!FB6|Xq zVtXQ1mDn9fR@*zVt;SvnrPlUELmRsZN_Tq_&mOh_dQbZ#lD%vJdV1Rtq}#_Hg;jm+ zw^+N6_34xP*}o9(Z?_R1U_T&V4Yro>FuMTxMw^DRul*ct!|nahC)oK=Cfaw%^(4EJ zxRY%oDbA!prp~d6W65H4CQ(!8*<1}ZCfcDZ*!f|F4x*O`yCB3O(Xx85watyLLf*R2 z%1?#T3rg~SPCiVnr+HMZ9F@3mcyF0{-eL%Nr zdpN|8O+$U&u5nHuce)ESAr=M4K2uPzt8oa9OkQ-5X0&zxpRhQt*kq%)5=&tH0Mw?3r z{42!I&Ei8%?Q=NVj`HM!VWJ0r$TBJBwli6Mt-lmX#D9(ho<%*#Uf#JyJE8d3q0khS zVSL^hMQ=1y;yOYWxy?1U-J^m>x2Xy$)S8m1^sWzD;&Xn8YPA(L}DIgIPY!kg!!UD3=}H2)i9 ze3x!q-vs9`bwW=y3+)Lh-@f_`_b~3Lc3dAx=Z|o4K5LGnkjcrz#`veSl*k6h&rK55 zdB$a>D04!qQe-_$j{3s*TG~P6QWs-fbBtyyov9gLXj+-BNr<;dl1`|dtlY)J#5XNN z(;t$`+y%{=T*&1&=VFMBah)oQT;kHZJ}bpfR4MLuSD1gvQe6Tjt}prXr@9Dli{<>H z2N!-(I-KED{(_vnS)t!TH+Q2Eo>(S-4Ma8V;8FsAB5-TS;tr1wqm(i z9nu=X8-SWCTJfO+5zVy};Ayt(M+!A^55%c(Cj*h~AhQS@288nWAn)CZ{Ayd)F)t&( z4EB<&{3!%Zl6-I{vR@~7^G41sWy{BuZ*+yJUTMns@&y5PoG`T;s}Cb_ZEOXdxA-Pl zjKFaSTo7uY^x;SRSDc>7b{`X*g@iiM8!{5^JVq#Cf{ifM1K-~qolh2^sShVjRWMVh zv#crWTHg8RvkeW6-{35uK-8X6wp@j@i40u;{wUekDey%Fh7s$2YjC4Ol1_EXJ3c8IgQU`qk_zIwU8&*)G%t`r7EXL8B z@B_g4G6G(J^&JQlFf%RFk&14%Rz3A5B3=d*KSqfaBV_fUfit;D{{=;nS7B^L;u-+U z@NSvJ^eBYV$EJUfSOJV3h};CUt^m1*z@HQ+k&Ec_q33>cn!+i&9iu%xsC4A0d;|tM zWseZ|;jFS(2s|TY#qVJbYSX?Rva_9StJBhvZ(;m^$oI`+41S>2*)vHGBLow)vW2Gs6g ztou-=tyF)1ZKawsi4?~JZ5NS8x@j-0PzxZ<75OB{uF3|sbgwEK%tzr9B$JCek_snM zG*qi^Cu|=YC<5z~lz3KPm&^-RX2|=5WcAvKQ=q9gkjZMt6KxMHGv$wB`8&JL<4BdW z+|o~1e+3HJyjMg8Uck3B%EYNydLl3)%k7~?_Tkv=rPyM7IA-yG$^i8+XeS6Akp{VQfsHwMD+AfW%((xDx2b`#P}F+DgJ}NcS4k+w-!l3 zP)xKon136QT%pM4_%q_iD-@XIKK0egr|OQXM?&6E6ephPg%Pj(58`qNzyCr3sNnY$ zmP*`DK294bc$i7*U)=;mvMmA5Pf=_sO&I>#R%KO;rD=dJ#TZo(*2Nj}UP?Yo@Ntxf zu{0>VSTA)|tj@$}uUM}kp?Q@lxPn-BxLDQDj)P>IjxNc>x}&3FH4;cL=r3cfm+8JF|GMrdL4u5Xd?z_wa>;0iLa323!o6|%iFJ-!|EW|0nB0%^G1 z{v_yQfb-LJ&QI@xz6JDNHg|=&-mM=LT}YZhu$|O2H%pLKb2VV|WTGm94gm*uA|YQ? zG)tJo1B!+36azn)^4l@Li2&V#%5G!U@}@djUQJ5nfV1gJXH$RBUNQi-t2(EJ>SM>4 z6{faL+R%qkRl>>{Ut!$nT8q*59>N&ts%0D_!V30rHo40xl-z9e9txxmpTEpp)>$t? z$AcaNBw7+lFAtQHa*4thF#SU3`CV*2bs)ZNx~eqe`3q~L@FHTK4>-?X*yS5Ye*nE! zBzgYA!OudvAM_r;<#L_N<*T62i)66+Vz(ObE9lQa@I9%i?yMm#{1{sqW;|n9*8PcJ z5&KVWU`6BHu$>_gy5Z%l)#tX8)dd%k2_XM9BvgW?eD+kPfCRV+OWBMPZ={;DJRQGM z1eXBq)x;&`4WOG|k$eN4`B#GF_xyI2&-&;Y$dt z2bc_a-|(_#L_v z*+05oHu;(rRb27C2(AO@yX5HQgeN=qcGUMge9j|8ld(?vnx}_1LY;@{Sk^!j3z?cY zIVNB7giL+O!-qVYw5t9&CZF+$IaZ(XMEQ(IOtZgAV+!tU1hGvTP$FfJ?!|w%0^{0& znASabegL`)2xcR$u74TAnNB2F3{4&EnITQDbjM}HHti*LJ~Z{IcW1@aR8~A5s85YI zn8XJ7>QhmR3bRjkOKYF(CYM=5Z>+to%cxns-QL#JIpN;cgR18I)t6h-C*0eLX>ThM z-U!SMVV}Z{X>ThM-Uyr%?rr6Sds{K>ZAHQxfpfyWt(gJf0zwzwky`& zyIcE&yITRfTd#=s-*&f35&^qghpB2VABWcL?Y9x_ZUx!vZzI~>3bOa#Mzp&XWG}#t zXm=~f-hdm??pBb!0ym=Ftsr{`ZbZ9VLG}{dh<3LEcDHV)eBxYzKL&J`v$k0Fl-Pic zqiYCNgd0baidV$dtr`T{fYW z%l^`ABHA?yvKPBXKBV^w*fmni@FLnZ3fMIg7DS$C;K{C$u&8ONU8CSjtJI36uhR3c z))zDdy4%&iy0ye;UdwQte|3*4IK^V;WHy&%P2rJ5F4Pw}m5F$_2l(%9?~V6xE(ve% zjrVkjjmKxh?j2ed|L|~-K8_Q_%Y^iGNF?4%NI!=})GvueG{85 zW2bvk5o$a12+9BCBtLbMkMZ>FbZko4Q_z#Nck;~1$X|S__(o}ROZAV{t#lp zaVGwVTX*D+J`;b`1#Q6zCjOWUdIie}KkmYQ!7`+uaN(d}8R9!#I8rcw)(R7U(k*dE z>o;>0LbFRo;VXH-VM#y9a1A!Z{h#T#jJBrxWkq5=*UWOUY958PAo|^JsJ`m; zUa6*@Pz9ZvlnGT##`dHdN{&OX@9ax$mgLL=S==WpX;PVu8KplxOZ8=%Z*6nbD~D14 zmqsOYPP5P+Cpb^Il=Ltu%}sJ@5>jxz#GR&gaQrWLn3Q%Yl4G5^XPVXRQ4*S~c}-50 zQ}RW#5*Knx3crCkIHkReWPZNH1cwTd^1k^Gj(N!v>G=|z~&1BoFBs6H!0D~Z{ngxM{>!;&^&Jslq8_$tw&H{b##cbDJqhx30!2(allRV~C~d0;z&|F^hd{DDZMHn5 zeFy%HXvbhvr7c!{4%V|0DO$lS+L(2-($>&g0m-|Ns|jgc!0UiEGF6FMJy1Y`?RR9& z9gDF4+Em_gDfU+ zlvE`iMOOVp=q-vr`~uR{eh*^+693BPePEc+c9Ruq()hlm2 z5!I)kli^TV^JYNP5OD3kOD8tKIb$!Q)3=Vs2d?){WBTo+Wt*n+3gnvQ-Q^;5#e%j# zFmp1pjgzQR2Z4?kNxL_9PgRF`D(Hzok#=hCFMJ--C7|m?QtN!!bun8&uM+7!>il1F zZb#~V(0fGEcFwbfD)rYup99JdzzJipE2f8P@(a0V=HZ;fp#O@%&p_RgAUT)NF#@K% zC)jwTeLWzU7yUmfN+a|NBw9@>1T~3V*&Eub_xf}XI+;zbpGL;8NQ2;AI5N=Sv8lb%n@d`= zfIuDBrv4(G1bQ5hf1KIuR>>{_xln}T&1Uy0%B>*VML5B19&jB|o&8gK{u~>1=1GK%YjxuQuCTx zYFg~A(@rNnN1^~1CAt>1@!`MN%D_ zGD!}Fc5lOY6)4yEqCcyL8sA|#<1oMt zFXfwWJ>u_P9EyqSlz>igB;FbR&3XT(e^bVS{bbDCkOIoV)mPJeG|C zoPQ2@0FffScugo!a4w8lK&&Nr zOSQMxyk>LM=V@_E!!!Aju^zlBL=Ki>BEAN0ru{OmuDMz2HkB1 z=~(x(YxeF&g7*6{sy4^*{Flks&#nc1JlUIx(cd1R7~N(<`VYqvGEyhoKT7KV+vVDf z?zQ$w>2|+sX0P9upbdZ5EW^LVel7lgThPr&U13Y{hn?M^eEjbv-Hg;Wd%dLoZ#c4$ zvFJ1VvMl;PFYD%CydUMZ+mrE`c;DH7D&F1;yZePlQMIt!hKlxI7j|ph!tRZTxJ5-R z?5Z+`tBP9K6&C)knHF}1g+FYjg<#!8FQF{=j&jSr9f-G2X1P~N_nAX?#o1X2nHsm;yA+Xr($D9rV^P6!uTv4vF88WY zdhzUXudpEgL<3Kjdxb?!U1qsgsg+4zYtOqnv57#f)_c9HTT71IXua3Fy2onCiQPKz zwj>^GmfMo~&9D55CCF{*af9T~GU&`MerV1$x&I>^~IC)`%?08*V-dk*@?=q zt~WMti%e9;nEtu`@OI4A+?6%{$Q)PFkt*IH{QVqa`^kpD44A?&;?H%dl_^HSpQs=O zC!;!aX`-WD4%tp$#KWFMzC3$AVc&kdP|p0=0{FsGMBi+xz|gUW71t>1TB+K5#dixs66=y$=&V3 z6_JPv^j;SsNP1MT`yHc0@@5zhxNzs>@kDq~VXsSaKf(_=dVMlY-X3=0Zpj*Q`-ls7 zPYxup$6UB~@?YqA!iD=L7m$OeUATWzC&Zq0;X%nqkblmF2S*C=RN}=PtDsf1!C+3Qu7 z7G0t-xAl?O<-A~%UoGHWO^hJD|AM0yn8bS_qa^ttd3oPOX_0)J@CPnj8aWjE6Cb%+ z=to9T_=%6hfhdxLuEZyq`uPWC;M1^vM$VJiXAVh4o{-q*4#|rY;HAWuxvE>Vif`nP zul*azT1}9M+r(pJB(A#*5=rX}15=Eg5VI|{kCRA+SS;PLrHsq7arNxBH2x>~B^`44 z>C=(o7T6Uit%)Y8Y+`l}>VKl>1?D z*tO)|+RG>%&)!L5zI}sdVEQ-MKF=dI=AYH>g-`I)4d~oNyRogq+dkU*^Y3|85B_!a(ImLiV|1TOS9LZ+ZM#Bu2!_$y~d;(jQHNlJDEuAtmQ8^I1WZIaBx{2i&4l5!7K zUsKRC%G$(AY1!Xt`Tc*;;*yp=lU{cul4rM2dXF?qI{r=Kx4B)KW=20~<~a+RAI9Cm zk*sprisoU;zh$e<2UM?|`O#YOTxMLTJ*X*=2?a_g{g{$Dqexkp*evP9-E_-kEj?4J z=0t@YkrguO;flK6MLoHh+NKF(*2TE`H>|*w zTxh*^G$Tu$kgh!pOJ|S6q$w0v9OEuyN!GZ6{!-#!h~G{RSAXjd!(%7=OVaEnXd%j; z?01%m7K4~YgN$$-Z3u!)RmmrQQoB3VFFA%diJnwMyV`eW`iC4fdzLxVe?>xRrYv@i zU+9n@=*PG}K1bEHS7ILJXq)^NVo|ngj0K0%Kh!^UG@pw4k2RYz+i$nWl-YiRObJt; zlS%!bEV0vR?7Cz_;Xi`PN=O()%$m^g&SV|RG&-5{Z^+uoc()b-n2 zytL{{uf&^@d%$a}4xhMMc1>KN;(OZbpz$VD^zz<{UJ2uxPOT+8Ub?^ZT5AGgIt>(Q zf~<}BRT{1nt^o4Mc(-kW!fE?B4qYz@-3xi*^6|Io;#zH+6_R)ZM5Xe^q zb_tmaGV4nEX22T)au0zUfI`KOE`yS|ifv;k(NiT0av0F=e2~8*(v5Y?=sJ*PP?rEP z?=mh!qB_eF$6{Ogj%v0wvB|n;9MVRw-6rCB_rh6CoK-;gCo*Dwv)FgO_bbE;;GPF~ zyFoS)xJ<|gAlnFR1-iTrf>CM=Ut-iOmNbjDf_U7Ldkg>XMCfLq=zd3R$dOI$Fw~lV zB7dLPPFteRo_7#?8z`1N67ii##+J|Ed;&OIejxC@5ZMyBnk)kuTZTPJO7%p?6J|Kd zqfbF7LLeXD>Ka%YRzolOe7wJIxX&KOF)-Vy1;?s*kx;x{AU%oG1t|I)#9P-;^b`O6 zb@!i|nuDH~J5gqcO4l(w*_T6=9mEH4|2vfirLt0~sI3=~%HS6KPk~@U>IPzH(D-LY z-@5%}TfABd`SGtfV_H?&dA58$k9O{mm+o%kfQ>cM0>GjANW1}*bAt1HAY`J zl>@Gnnh}*!Gol*P7m=QTNwq_by!cfnTYGu2(ZuG!)od%9D=w#Pz@Vq7)0)#{O*Q2U z>L_b6VBIr{=AUitc(uUO;fx}wk+SM|kjVrlD(zSkYBWE=krBU$87B@4XO?t3hmy0W zQPB1VM$u}|HTFY^HUmgKwJD5w9RmL$cI-9ywyiTT>`YWvD^2GwYMVP8Q@*qfHoG1} z&j5=aw_R#lV&-XZ7Ld*nK=E2-4FS(gq`@4N^lpG~9GsPacO}Rf1Xcr-jHVIAO5FSo z;ZiS=XpK;eUTG5omnlXu$aVtP3Hb^6CkZ?O6e>!z2KHaUUIn7{AfFKUNXS5te-QXa z$Via%HB6#_=wy&O0@Z+P;FFvQN1|_oABnaiA$2%?VfO}H1DA+zB$8?1BjD@{xT-Ue zzyU&3bq*yk1IRS+^69lmiy=VF@bIM5YUZ@Wsdp}SpM)Ywg&w)Jy6c0q5A_Zn0yt7++V?QVAKlYH!_!epoA_>6z zXm8{VkW#26;yedZOQ2fFUqHGN=nND}SrKobuERPX{c5^@M73Jtx{=iKumkLCV%Nac z>y|j2ND>G8Vkbb(|4oZN26Ac|6~Q9x`q`Zc4+nvCwS{TUKKAJ2e)M|l0WNRQgzfkc}M zxb`Oj&y1u?$h5zCaOME6{VgM~1i&t}>3b2jW)i}cUjBDkeP<(ZCeU5&St9(>rqkN2 z^HR7Q0H^aB0#^fMb5tAl$6a3aWb`(Ry~J3iNZuSccOi5K;2i|=7=cHC*d!!>lV8`h z)ww=yvK@@a-(|k1SD)D^+T)efCmFK7v)haO1s$V`@e! z4>R-z`IzHpdRbGclGCeV$Fh^al#qO-H-hHcg1W zOa5K}T4^bwtL-IP*R8A)0Il>vVOM*wUj0Uc4+Gk2>e(}#dL9kF0O%7z=}Mrj=ClKB z(RCi7m)$B;@k@S`xw-FVc!FUg>nNjp3zfvXtd4wv*c7Lk0bLa z;0on60wBqZ?s04~e}8M}_(us)=octU?XR zeBstWoftw|_o1QN`njAi%j`|9JGycnJiT(qP9dPz@;%Db>NVkE0-|%xIVwoL!op=e z2pwT#@9@v_X(z?lSqPZe5cs42O$)QRBNpm|#R5dbci$>ouXixh`={abd^UL#;UCtU z^nCu?rta058WXkUsvVtBT?@3*O$AZgxDT~s68IR=^sQUePL+lez?T6N^s$@einhBU zmbzD$BHKad|Ie7_eE_wI_?v-3F{0l2DY35*QEyK9g|9@}&fHD8COt5T*#C?^ z*Q{s^H4K@^T(*(tdI0NDs zkeMcIgnKCvP7?@R3-H%tDJ8v)7&Ilc?dX|@xo)ue1c8qLH`qwRGfyCq8En3X^DW>8 z2Ja7O5}0DCd(^3W8R6UaajJ^p6#`C`xSn}ukE&`om4H*#g+M2OztX1{;h^;`)eJOc zs&GzRKSWLp9d)U5lqsF3GQGeFYOWIsUNCfz;Ds5%+q9N(M$4UOd>O%9?Yr4C`e?o7 zKrKeuv)uxe>HDTia$(A9OwV=eTnlSmdAsG7g@e@aa$Nx~94mUYTjV;*EgV#9#lS9d zD+Z=C_XvFOm~~=OXzl*X=d$Jj2n~j1_&IOsLjsi~m%?}=JkjEw_re%&g_G8N zg6~h#_;&?*i6f&hcSnC~KFUvG!=IUIncl2;4rgOF4(UV>N-KSLELf4?xbLQ$( zDsN$QbHEn*UJ8n{Es^~uN^H|pHL03Y2~$A$BC;KN-i6diEgl4T zKY`39FdZn0QYe{@wW!dAH37P+z23qy^hR|}jVQG4nMCc1>Z>urz0ID3mb0Z+>mQd8 zSTE!QkZTBBE#!5O?F4QFOtH+Hf;PVCpv^5zc}nWfu>J?=BIBI7Z-f06D3nx{%&d}q zjjD@^?zty!HOD7=Dvz3w{z!y>0Ip$6Dlm0>8g~3T@&vesT};5;?`kS%BdEcgzn&*x z*9!2^d0Oo9&VGnX;RUjF^L~kUl&v%Ca(Yrxr5;zoSuSK(rRJk;si^lNDKh}s- zL#0?!=OKO$;8MAqz$TzdsZ>dQmDIYm1gYR|J94wck5nr9uhsOFNN-hidH+@dHw*ay zB~f!s}!72OSK4}#qX6sv<$oR~QZUS>FZ3C;_W7p+LIzEQtS z4T&7{n zDx>9ndphjw`!=u2jz#hOgrD52SPS?kGBh0MqEGhMO^9aSr&F9Uat-IijB3rj$El&tK<>^PB4jqW^%D`Q-IKUO$kzav-WJ2V&us1JQ_2IJ|Pe zU9(YgosUTq@oVi%gflk{^v>Qi&_dRB*Wr%;`n79RU%UE! zyzh{7;{ErNc(q)ol`-+rJQMOy~Bqmr}=cY(IM^bxf!BvsY5bbZ9?&BXvw? z_OlmK$8=;rdmnX7C-$?~QO9&(KYJT>Oy~7yhF8wUO&5LDIm^nd5?Rs4auxN{1nMrN zS}t}cpG}=UGdkLZy}IxkYE_27w25&Cbz4;w8K1p^+8Lj{fjX9GV3R3K&Wn9S5pe(X zRV3iY+K@EYPpbw6FbJgc8PiSb+v^?1osMchdMR&xqM3djf}AdiVG(To zj;!Q#jVr&V>(xZHalHrR^vaQ>7ym{4@XldB-Wd%!eZzdmcZjo(L!$8`NH1rAb5Feg zym=;PP-+UwatB<&yKv4>e>?hvYST6<4Z}RynA}Va$<=MF!L3Poe?ImEdYGh(y9u4a z9~|p~EGuv!NprtE#DTfGDK>X%R2kSVDVgmaCRca527h!4o@rL_nfOjYuD+tk9qXd% zT7W%K0~K>ds2kqMo#ce_7+m%UnOxlo8{Fdb*NNq9uh*5kqk9Y2!z5K>bJxxQztm|t zJS!SBo8poRTp84FDm3Qf<;~G^Yr&IEF6P=SHBdio2I;pAQ(YV@ciKe49bNcliMeua z`3_~Y(I%ZZF|B6O8%9nFmmyEUOaFT1-U1h_&! z+%~9HT?xKfG!^>ccA^USF7R7`p}K$0^3|Uj&hrqS1@cE^oeRymKxWQ%@Sd@WOQ@3#*wYDd$L7sAX{f9UAD&BzRK3;r1w7H zs=^do_$)GcH&NMu|6Mi{t^b*o-Hrbj$FU9U6aFC63CplLkIwRW=a2292 zf!+Yh*h6zg5mt!*UA~9f$V}-_`3@t>P{5_Rr+npz70B#ezUtYU9q}oRrop8CC1wR`2-;Nkz{qJOy9C0ZU8-V}d2v@1)h>_Os ziKuhL7G$pioFi@`@W*UqIU;n4awO|lh5~(^e73&Lcy(}V9d64N>ca0`>xqL)6i?1*xWD;%Z>f6i)8M_#5;kA z2EXrmtKWSM^d*rRMQRl3OVCe6(v;x4@ghaHlTje@d)Dc{ul@|(HK46Tno7j)d&s=~ zK!=K?LGk;M8cP;|&J{_6=Jy9m>N3#tfV`QIesD8_$3Pzh%3sMgtW-6;@=f^7`vBVe zF#is?il!kaTPMnAW@D5S<5&M>#W)?>S4e*Wc*lbLLf}Usi$KylNE-;1^=~dBb==$n zPRAW^xwhx_OERnZj4+2#_g-`(9x=@Tz&7dn=*Y~;F!mcqnYTe{Yanvt7)S?Shs-F@ z2B1Lu8!s+W_U)uR9mapTP_Y-nn+J5%NtRb!C$kFl1fZgV?pc4Xi&Wrmxtmhtp&t51 z1TF;TTR!K_lzWtf_5$3Ex<6*I~@;YJJ^kiV=A(d$UEY|Cuxf{F5=yY+y%He ze1vJ;*ay3y|2T4O%ldkXWjS$b2Ixubjjr= z-43E{TAh!Rb~ms;Uwbh@c0c6T2lkg=KP2Mcfyl(eAsr?s{tEgNP_U3X^uSWN+D>+U zeaQK>=w^68UNC||-jOOn%Yp76SFvD_uR3r5lYkQKE_H_9Ui@w3<_wJTzC-A#yaZz2 zUC@TW90Zu^M=}x-i9z73r}rYX(Qx;ZMChuM;95OId8~Sp6vxn}q!1guHQW2x^(v7G0cd>Sn?#c9$vA(4%fVDwh- zRH82j+@Y&YWAr+EE9i|tUVkd}|rD#M1LEXmQ!;i9mP2WoH8}I8l(`VowG%L>UW}Q<)K5Qlp1XLCnX|7*c4EQWCGaP> zMmVWpgOI}oAzBr`Ay22D|cHjd$WsO*xKq zm2RkeSG)%mcLIfLkkESxzl5`lxwwnP_qdtsKQu#3tODH})*9QLY1S&d5!~$t5e-{4 z^T67;cc&4$eKp|rRTZ1)o7;(AtlL+E&3#pCigo*Huz8%qrZSH-y&0V}Hmk}M_i^~> zkhxgMfsUyGHDn$*%4vzy$h-q*yo3@{*=`cZ#GYb&BSBr^>P?)cuu1C8wNfYaBg^a6 z=c;e7ISy=?u$toujZ?^^bz!TYxv^E_g!}zu2qQGRHtDhk*qJ+9)$4_9UE1o{+IjNX zc~Xg}{|MQ-wiWhBZ9MrL#uwM5ODShR*K_u$uP#zQ2jNilbo{*OcrbpPSrtwlwfk*m z2*X7%`+cF5_=Q3(!1*DMUng`t)3GBNWrg$8d8`t+70xr4GtLt2ms&-p@{HtmLM?3u z9ZP$H7lbGKbG5X|ZxoMkr1;1B7oP0T)zT)vQA`;^inZ0h@HBs}mNxl~;^Q4DR)#$V z;c5PY@HBtsM+ytVL;bm0;fxd)wnIEuE1djnaeu;fGCfy|oBV9?WWrrEnAPc#`y&s2 zyLgeP&x-mtQCDnbE*Bo}FUbCaU_p4izpc&+Yjhas&J=HHtyo0KoE5fk>clPx&j#me zK`R#iHrXJzpcU^EKM;Oe3tI7g3KgcAbmw2L7PR7n%LWl194=@j2Gy*Suokoug9~Oz zIIRV(M0P=Ih&s~5P=7wGAop3^>mShZ29QEg+Iq<){)+^^3{;wJY~$(`vpqM#vWRh#Tk`vne$lqn}Db4?bliH{GySM(CYBTE6n2|?N0C; z0q5|yLz;8=t}y&MyjOr&)!n~Tj1Gvj1ESAlq^NkIKRf5yPoVXJ*#od|fiw^p0{9a83Ww=h8cl3W zY+9x$yjwBx89(ncrLYv@IOIo5!4V*{2>cExl2mXql;vPc0SrAkV}jGJB7N46450w* zxiC&a<|H6`OGe5WN&%SedGo(OtfidJN)&K&GBlT~7J1Lo}yN=-vU@sL#y#G_d{vX!fJI<==`ujiooOAEod*|Ley)eu$g*Nn#G-Z$h z5$TE`A|ir-f(T*<#EyyvtVBnGHTEuIjU~ojqQsV1VvEKSOJYe(^1MIm++oIi^L?J* zAHR9M)|u7z+H0>}&MxPk^YfseOjK-VBnL3@^I)V*41($hw3*0$x*w4UY>0U9O0RId zx$+?K!p@qYr|e83#dsj0k#|inP{YX*=!HO@+QVZc^e&^M>w-Y9(zCX(7U@ZVwS}k9 zaJr}>a&2J)!ZQJD3m1c22m~*o^pmz=E$(IIpo?1E$wAN&JC@5f(rg7Rmse46y0pvX zCWJQtmdg&1?LhE0Nkg4h~fNK|3%#t9uyET{or0EM-E|(}5UE1X`65(*ba+v@!9tgJnk6aYS>y%y> zrC%Ndaf)rB+?O=d0jroBrKL-|P|ia*7fA9ujP@0CJEW(JEFPJwn58H#ZnbtdLZ?eR zYpW5ilC>T1qiXiDYv_ct1Kab!mhCONmOA$BsF>NoNL9=!q*)6jhA`Qj9qgm~_ZH}j z0D9-_V2*m{ZBRD>6 zIZ1?yatX)?@_Y3c*ZN_Enlo zAm)S26R{EE2#}>fFp*^SJ)#@wu_O=ngP~i6?yUCyKs_FAV|EsacOY(62fHbbaiff0q(=oWC*FQrw;M$!u0@-9bUQ!jqPBV$Hf{kD zi`PrH@Av5Z7W!F$w(19CK)lbnd;(aN$D+BCe?J1iLIuiCqzF|Q1bQ|y8by)j0~RVN z{O44s5@9(IjiMl(0qcQ39YqzYU4IG{&(VCOTokJQr0EM-sHF9u^OTVYhXZy;&xJ~Q z=g@z4y>l?CdY&cHYf~NlBdd>-e(Kv@f9E!@aIh@5G!|O$KJ_~(coVVO3|R0!^&1tu zCD0213)L6C^^Q}a*8>)+H!c`6ydam>UPrH3Phn&tMY!@svbaiACL^&TGjU$da~-Lp&~q$ zM{ClzYe?4~9UqU1!t;hdLg9G|OTPx}*@-v&W`*Y+=-&ghtv7siSMOV>uK}y~UzAx! z|8wNc>MVa}l;1OW6y=v-ZA@F<>04XQJb>qb<+szfw%i4}4j{jszKtLwp>_j;mof9- z^HcTzb5GVpQT1;?5sLEZN2ug?PgMQ;VPy(n`P~y$|0?KZfK~qkQT1 zZdCuhexP3=TlHUx^kTrO{~|P;F72xSDumkrtNzTS+Kdc;dQTj*xK%=Bp z|NW%d0a*1vhJw?j-JtRW!pDK+Z{SBgrS4`>Rew*cwC^oma6gi0;EaB*T>G!pOf-Em z^#)qB=9E~pw)!?(e-*gp ziCxPhuPd>>(hu@+#+FB&&@TsUc{B=S7*HZDTOLh;ngnobY#nyYx`KHXr(qg$4nRH& z_+N*dg$Ne_?S>pLJBaXXiCUD*cL7|>BTb9jY3Tgyk{>qY{LDagXus4!%fcbj}$N?hc@5vx1 z0s6~!q-QUS;xYmg-Qc;F*CUUYMLq38bbkg|KI7%_*Y(Uvb8)#5$#sC`^BBneB9za& zAb$YJ<&9=;w^1&=F~Hq}Tw)A2#AS|eYlFX{`K7e8da!3g6vPnaD2N&>P@dp-*5Iah zaO4TJRZu9GKEkDme(Ffnth)4wWhcPg8UZp;gxs19vLE18&7~DolGy2@CWZlbEX>0Z zFOmK-h+{yGmcG|5pI~+Ki!^W^c}4UMPS>KzFrIbud&{%a(Od`Eu++^Ts$usk=oWxs zu$#Y^Qa=K9zqA${Ba8F2#r6m2*8v--R%6~9Ntqh`U@;k3_xuX!UjXZ#>(Fqz$no5Y z^+$w%2dsN0e}yd|I1{CxbWhuQxLG;qqVxm&;6CM|{#8nvV!-;>?I<{1C|c{*LoLD@ zAbB_Z+(301sBY=+Vx|2+rI!syw{?EB>jl@N)_&Bg-?EB*4`&f|XOO=8VUT?k$Z{=3 zUUa)_(%bz=ut^GBxdQg0J5&KnX|wNl&i0^E+IxC6hp*@E__`~Wy#Wik*lypuu2l14 zZ@{tQyot(>uG}~cwjovO+tiq{-;GwcW#qFxa%@_QSJ=rBofZwnRP}aeRXvm#Gy*mO z+3u{WPk>$tP}SSr-tzdDP?t+f-foY+gZu{cZ^e_>+udQ(OFY8RDxONX-JPlu4uRJP zuwAqrQR(JD?+4h<*^?1(CG-lwy2BFO^**WNZsUsAR^qmH&ekA35wPxX7RVVQ)EzDW z*#vktXrD-8_kA5L)MX!0V(n>NjrelF2JI(79tTRKWrOw`P_F@)&<@llnFwjRPr9-% zWkNepA0vMcu=Rv{lmiV2ui|4g*;TbRG*)Q_uQFYRwR<;2tHlX%K5cP67tah2Y&A z;S&CDfN>^}rva#rF5&maK)vf$iwzrqE=GDGU<1$%Aio5>x@L5>d>V(IdfDcMtef&S z?-%Eh5q%Un*gQM#1^ef;&`50dU^Pst)=HYk^P}#FB@dn3YVj{;i8dFM=6JGf9|{k! zOp0*x+>3m=`*Q?Dxd$KRkpEN+Hcw)Ukk0cWy?U$5Xl;5kht`wexfX4i(s{PJZtC9m zQ=mHm>pWXs|L@Ux2l_Sf)K#`REjzvNaXPAa>MC2^e&Y3p*9EX{u`TKXQ=#_;tXte1 z@eYGt2w1n+fg|4bIvR#6zNjM(savc>x&p9nu?FNs5$YCaft&$E-QpRY$v;8j>s|IW zC04iCf_RhkwblC|$PS=HTGlOIfO-zdb&H*t2!D(4W>=O+0_zrUA%6|9Zt+);ua%%` z4UOb=^aEX()$^{S!2JT|zY+ga`WHf^e@$2bcQ!;lNG%Y2OcK=+m7}NpNL;^-X1p=_ zhI^nM${@Qj8p6sI>5XofqH06v`BCJ&`fo{dN-m8?>~fu0o#Hx5v-{G8$AkA0?sZ#- z=DcX6yo9{D0Z`eR+}MNK^IW6U`r=woV7!vLc~OpTdP46Xo9D($WgOx$K-n}59vb;E z7kW0Z*ELuUQA%~Br5=_W%Dwv6P@R$UQd0r*a)zsyJuBM`H^6YUo*8aW;VC`L#^Z@L z_Sd^(Sw-e7Xf!el%}#qCk%ea0XP1R$w})`A6FPVO$vxDy#h zqR9``5@3q^>$K)s_plXuZT4ef7V&Sy(f5FN38K=d1lewBJLgbRA9IW0tM9$;};(4?5140!@zgTbwe#ZsXcTcLMCJ|~t6y}}CpHRKn-kXLaaivx?v-U_{{wa_0R$qj%M zcbXNK7khE5oDm*lg^qvMnHdRcc9E6CW3G^5CVs=T7jPj&2}ltTRzuW*R0FIL^kV|o zY+F;?e$l#dtJP}H!@TA?-P=Z>I1s2@x}L$Mhq}(ekh8?nFxqU#W$Pi=h^2=Inyp1$ z3VESeI>>6Cqx8T*{vfFoMAKZE=!z}5v1qvLeZygs)s_#MJm z09zNl2l6fu{060;tP3oUr<8{-%45>|t$BP-icbN{<2l4mmv(u4kMLW-@`yc&eZfwY zewv3O#S7dx$I7LjIS7ueJPJvX1#IQ_9`AoE^xmW; z>>q6rG@{d`)zH6WNSAn`4$(U|)kzohzIY?SiqDe7~P z_O*55d&OO(t*5B`qx)*i(YZt^zvDmJ_Locf9skjj#rO8Hlbx+BsY&5l)Q#+jz63%Y>y$o4hXO(!?~DW4U4)K#mVhh(Y^56~H*c?c z8mJ4Vcg2ue^chG`1FW?bqv3Q(;9;&sZ$fxJV6E*6kjsIf3Z4Ul=qbw@LEd#W-z#rz!Q78@J78NdFM&KKLR&B&fxHKlD2Z*s{0r*uK$RvR zvKHu~5v6q-rub>kD+FwYSp(8hgl3qHAl(4|Dzp&TgOvW!SpK6++9F^u!hzD(E<`iP zo~GSdOWL#0+om!tg_sI|GLVrM>s2OQf*?@Vn2;@)^^5iIxBLOei zM!INyu3z@*P)6UOnh`tJTkSCk?5wr(g=GD5BUv8@v4&(P0=DwIPFZh5TAje5a#2EACmqX5O0J0LBxv?pMv~J#N!Yi z)3+Z*+y_wsQ6iAB@GCg|p&EhkpAeHkCW=UMpV7Nq4-!!ZaSq6tBI+UT0J#Df*axDT z0b@PcY*tD8!YF>0iUh(D5Dg&JKxe%N>^?GGEVaEL#=spdwS6HbgX{wgIv9dmP12}M>la>AM|}^@A*QUw-t=It*M80S0ac_t1HZl5_L|YJzWMO# zuBMY~H2f%>j-lasKSXv(z^Tt|<6cUcE(UC{pN)poB}60lgv(V3w*kqy@N;AIWIb)B zg(Nqp@s9N*x9X>kAlkzqYGyN;*n)w3$WwoJAH)lfq6Z{>Js|1#svHj6MV~%$(F2k$ zdMMIG4@LUlq2N!AKIbl0MY`yr$XN9Aau+=m>Ble|RF?Ensvo!n{Yz)^FTROO zUJDl&J>lrz&Y&C?m#>B8>pMWPrur+v6V3SSYLcge>n{bkmfk1?qma~QW#~Sla4!(_ zgH=}{)~_KS6RY!1LTaqvLB1l^N&Ok`^rI{9&yXJhUh>>J?3Ts%#Bg|3w5H^DInh&; z-gU7kl5>~Q6)loGbCG;27s;OUcSVvjM)LT7M>13-ga1n;t9}y6P>~FyNERs?p~4wP z;p})ZcrKEmA{mP!8Qw%9e^^IFvii{O#QiK+_Xb3bE}gu*50x%@w6y4L@ces7Jm5Vd zP$x;tMB?EemvOv?OlaYA)Bxc3J`Oeg!i=|FGmrp@#eEqWvT|esP4%sx+;fy|xw>hQenCkg7n$*s9UW}gF5AxB^U9epRx%e)Em3Dk_?#T9LT1xoq4 z4VUeYbOchG8ayk0S%Zo{gbe!u7U;4*x1h5x1n>n6-lC3VNj^d`AAe0aTTESArM6w)j|`Za&vi1tII__g};L%FdP@V>{&w*Y_X?UW#ylDDNORr24p$mx<#xrpWKQVc(pj{Or}@B%78 zc@j${AVomwNf1&Db)ijob*}7Kw9C&y&ze8btwCNgN{-3Q+*7*I&VbRVGkS&I%iGIE65P-Vkb9Eso0H@l2>p!R%33jR({NlHGYL&Z}3GI;R<%;H4GwO zjJkysUgsmaVEBXTK%uD|elnZT!{mWiF*r+gn>VV-E)w~#Mfn%j(;lBF+?3&tR(LJ8 zxA5&?a^{|QxqqiSBt-WT3xC`CUQop7;N}&oMgBBnkI2J^cTFz0duC9)t1T z{EHv2H0^F{48|+Pih91E8c7Ki~I-*WX1ntl&r7=PLLJSEi34$7SdnkLOLoJ(&HBY{}a;ePi}ZNUC4!$ z@5$o&|EG|~6t}_=lZj^-uc_D0U0gqQ=v1sAdU3Vj+N|t_UeUhPSG+E`TU7C{DX723 z#s2|i1D01ZQBgVF#SVv6Ow??~;sqT@t}#$ke(K>c1^E0Xcmsu=PFU9grF&pde|{eY zz9OdIPb4P8+={dX@X93qSeKX_4bCRAMWxhLG(vtuf^r#lMSI9HA5&J<6irsm+=_wg zfr~B zT2-W?;Xt^2v$mUSbZP6^>8MZdM;}lFoJA+HBRqp+Tgv)#CKi(POcoYBUK z^*RZ>sc^KU&0MPIaY-xRw9G}AjCrvEGBl=;5PI1aQayc_DoaDvett+1Nb2Tk>_A};v37|O6T%C6BWbaGCWZZE;7TK=g}s#KIwSTg zSh|ojH(8q5;e%4U-H5pb3s?2$GjgUjKingMItvoR=Hi_nwx<2>= zY%A;ZR@rE;jPI>`wMAp##DYf}yt=Xq7di+IU_Ba`wO$fh8xBdO%k=PX)Z8SRzN%gLKs=90pcQ%O@JSxnq(mSBYLrO_k00=Tq(?ZklqEfsU*IX%ElgFwW>Ud z_*YU%Wn=oj#`GYy_xM(?iedTxmRIY>UefB-^JqT{BqcDfeh>8qU|xL;@&RC8$v~Lx zW?n6n0eR*B7W;x-Dv2toZ0vDXt4bDeS}Li^RX!vV`u2Eu`nSATEKau(8=K$}WJZ?DCx8s#C!4@G>4R8lPVqF9X| z3t3T*uo0Hi1%`KOp|DYfOlW$7_{VsezWmqfynHZ-+V?Vmj^+A$>?*aGM}*1-V|t=@8F@JPY)@72;#k*@Zm3U~A0%2IgBxe=qg>r2+C0z+Z>A z$b5fcs{z+?6Jt*PZuq^weQ^Cpw7v!M_3+sK2dPI_zD(~2to!bNxVmpY$R2=o-?`R( z_kr9?EOp<5tozP~oGX^HoL8qA#&M7<#Zr$x*n0E@kmmz_uOfK`QmmN{m1FUUzeTCr^u(l-wiQ(wc z5BHY=HJp8r?hUl5q$fyaV~-PBRc0ZcDHRxM7eDETV)?V=)j?xB<>$OQ6zxNRqy*9E z0JQ=zug(NH71-rfcv$4sXRTRoL%J1cQ%S6fyed#0a{Ok*H%g_=tG0eeUXkw*yHD%&Xr({TeW@eh=~*(B{>7kyod-X8AXy-vDhYiJwPaUE8YScJj=PRNB0n zF-<8nlIqXDR$d)EX(H{=YA{2Jd>|=-dDRiB17KeD2k8y8d38tRRiz9l5PIF)1fWeN z@lfQ|$X1p85$`9JHm}-72YE$Pjs6ZbH*ItfBiKAY&TfK`x$#;<*zVU0j&$GE9hIlV z7V7OodRo&o8BolIjSwB)rl*ZoI@&+IPfY85qnn<9aTq?$2dt}&-uD|=XF{$6tgDT) zuJ%jFtHn}R8*g3hLC76q$^KrQwAlYG*g<$|UG48k zzXi-E zK$}W>n^ZRT_@Gtg62uotrLCgcZh5dh|2BCwe(c%VoL5(&y$wi8U|!u0bt_N~Xm1|%gg zuVSon^w~x8stTkWX!GjB$g9s=vmA_cAke0g_$u8x^`V{VQW{LA9XeQm)>Wjo@P7IdODAu7Br3OqE{FuU;i&1uIkUU{$9^< zhoq0v;mrKYkg?!VCiY&{V(v{1Ein3r^A>)M(AD8Dr7E4hK1BcggB+>&lO z`;_m1+X#Zc#8n3!XW>rRSgMso(PxJV@2aWEK(C?oV6b65YnWrTjyZ_|PWvjoS95Z1 z`zlv(`nCnhag8#|Q(NoYeQ z*`;)f@E^D&`SQxNxz(^1UZ{yekPs9Y0|MbO9%dVo=Wf%PmX~z-j|6==|nE9{kzn+?IraV61gBV zPA2~iCkW1%K^+IjPNyb=QZbQS_jMKqZ4YTvNd|GRY6lCXaN^^2MEq zLvZOnvOEN-3kG4w4{n8MV#hq3KrViu z#c~k5N2o%tr{4X%4ZYgv-Om|Sr|;Dsvzd94izvT#0;!M6QKZoup#MdhxZVKGD`wJ4 zVS7Zi*oT~6BI9jHiPkxDSg0Opv|SY-U1!)8t6OG4C8tYbijL{r5X47O;*BV zot&yvEP!lh4qhI zUV-q1&CJQ8a`3U*cU@9%i5Mx{Ui?$y7kt|4{h!bbK8rl`<0q+{pSSw^v>f~*qVV@k zx&IfZ%qnFMyVT|Aj?Z8<@vQJB?Iy768G?^7e*d4ZfsvVzPQj~NdZd@xyZBdfqi)49 ztG&!bBSNqL){~?*B|V^3ZEAb9X*spMyu!@bX2cIdt$qo1fd^V%Dx88aB0EZ_-w)2_ibyEhV@8hLx z7&GgYssKuCbb(i@N|XVkM@RHq&=b_FPtNk*Z8>#7pc2)$WY#1n#PPI-0WNb&)PWZ(rOriIm# zykf+DVUr}^88JIvwjQFRGYfO$k3S1F+L>&Ae3G&~G@=&9zm<)p5w#?Klp?tzqL#(q zlkCEXIx7BvWS2+O>b;LTZk3n0HlmJ?uaM1$BWg`Np>!`r)cW{=D$J`9b$VPIhnd%- zcM@-iYuhdJW#s2Zo^gRn_~z%PxOVe0brE$@T-$k>VZN1U3%`dVG>T%buDU7I{VtXl z!+m`vI?*Y`&2fEU9Fz6U1r^C5d4&AwVr~aj7Gy8{cPT_CBf{`8NgB+0BK)Hy-Hb?w zb42vcjw5|x_-Q4?0CTV|{8VX%m|BM1rLCETl9#e3O?816#7)-twRH1LIwNo$x9LHI4{V%`!IKGVK`t z^LB{+jHu?uZjUIGs9sB2usQKq<$Oq$hMJO*WWUdNE_osK8QmxRLFdB=o??jdg8K2g zPvni!J>Z8X7{T-0fx_Sk6**YCFN0w4Ia2OYGl*UA^Re8eyu@kb;qMv9a=r5>#qIzJ zy_GO0m+CeQJM^c=o)Y_322p>8eXbmK!apGPgV+kHKc`SGd!fDy^(SfGqU53i!qgU`|f_>xi ztk)~B_pjDK+^b{3vsd1^{t%{COW zH^hfa_C1U|YsjOtEgtWlsX0-tb4h&P)}-F<9mH82m)g=@+?o{i?BAAIFOFTzOv$CV zJxxy~6`tklelB4pvERe1sZiTq8oz0mh21r2EviqdZk`oaNM1L2^r1O=4IX8`jQ>e8 zb95<;=(Kj!Ao;{%<5eOtlrfGr2e_7oeA=C=W~e{71-UwJx1iquI{wfRiodYAk$rPN=Etjf0vO4cKw8X( zVmL(?bJ1UX8mu*)hLMMV9lZS4C<2fcKmSfRouO)h{D&Y$fD8kAcdCujC-jfu)*Dmw zIYsmJQ06!k#sXf^$eflx7i)W#7ATi};7vn1MH=0o&iP^Gh2f1&`5(bM5a|Ixp*}Uw zUt>*9F}?&-Yh#5yq0_?ihkzZ1>Ox@pn4B6zE)6R<$aK-e3- zJxgaRy#kqforVQOfxHL}Ul$myfh0{9AK9Y`ms(^3xZ#15!@8ivW9v=sfwr5C~; zK;bfo)OCnIq`wfYAphUr5ii$YNmcoZR8UINE`FZX`f!r%X0|hjPU6nwPeWrc>aL}v zAQ#I5zecefkJ_Gq#j?QfBi=#K2LK9R2fsq$TLpO(&{_G(TJSpkw!}|pU&Zpg0O=;c z>#UYG4;A+TD&>B?_EjuGS0KLJR8$FvN##paI{4Kup;D+epBBS{e?5xV0S#*FjcS`p z5R-gts!;9H!gv=dcgQBOIGsRADd`i78b9z`U_6ZQLBQV(@f^rAKVjjqB5nCaS2RRlUNS_D1syf8acK|C%al_7x+0XMncb{F;`UsznCc5ZO@VRT0mu^}YeH{67H&qgT zBU+-D?`G~|;r%K%9-fhqQprWx*4*Hfh-S!Vutjx^ozWQ0!&M{A0g zoQ-5|nwR;RnnHOF0qnqw(k zy&pd<^?WtQu28i=>L{#4t%7gkZedE&I=!`#1C@FKDnCg*fYeVCqSM?4L<=o% z-Q+Dqr#ahSI+m2HfT~TXXf9EH6^JGrdQ)_(Be7ubxQaDHuevP184caW7DpPcI~r zk`*DFfo#xHFLXBf_kWK8MCk@Z`*KTgd@5S^gw(Bho=w~2(rWVb_IrUbb}lXjx-bLt zobO6IepAh!Jq)iu7CQ0G8n1>-Fgp$K^eX@%E(!GLp72yja)?K_W=1B3C;$_420NE+(95W!TBZ7sJog>B@RRMZiCG# zo<{HlkQUEwZ0|t51=y_ObC6E}yTK`~>E$L~!5`RVL})ju}&H5;1tqXSe zNZrQPtS`j)X62@=e*toZ2xWZ}$PK`*tk>kS){nt<6?<3K=l{2?t6ruirqP(H6mjeD z*MR8zL0E_d>le8~T6Ju-cMK;JUdb&u*XKZb`-d$&oiGZ@wWuWz-rS85oqRhj^*%0Y zfqx&K-2-^3htZ5C+!)-^Ze$Kpk8pd-K8iW_M$e!LI~9kY1o2iz_)uPN{C2_jm>613 z_kXuWou5D3gOks>#b}>*G4SB)P)&b6EC6b-1s7=iX~Bfpo54#z?NNO*ln-wW^;Knw@jO~n2X<3PrWmtBh$j>9+5ECnZ#M?6BpH*XL2vu3yiSUauo?En0l;CKG005ndkv z?ACcAi$*2A59&5?dSQB+!u}1^UjRk>RGah{yv+g>=yc>U%e~W!)aK?u?k|=;?tMn- z<=lFXgghLu38@_LA0Q&9R_heThQL!0o(!bLw;}L+sB-`t0 z-*<|P2Cq<>y$d!f8sEYjfUqCne+ID!$SA-o8Ut0xEk1Y$^_dm7N__^r=}0H<(kMm4 z{}he=3tno~Scr6iG#Y2u(kao1eJ72;Uj)4Z$#S5o0fF{$_{)ZCX(A_PTn!FK?d(LG zd#OFGiP}>(kk0&!Q*esmyZM8y2OhZw{t-55(7>?F<_Opvz8?PgjMGif^v9ciOzq2! zZ)zdmihG{~-#ek9q@q!FW*T0-YSCivK%2IBeP^wMKiVc3PF*_kZ}cb`s8&N9V_Rp{ zYJhuYbx!8>eOYNn43~d_CL6`lb0cOeO|gB3e#8>f%;v2puD>e{G!n#YTkdx~r4_Rs z#ovv5Sh&6-@BePHMwbeGMc#j{Kznk$RdO)|-=^2SH%c9So8El%qi@s4USag}pIL5} zY!5Q}HhpCEnayohpUYW&dJPF4?HTB%8(DpHAM;7`75~vgHC>5PKf0nV_2aqJdn)yP zy#n1fqty3Ju++A7df!3XI*n4_x3n$w1G&_b6puT525Np$>N_oU@uH;*5zN!JZj}1Y zC2gtij#BqcoQ(9W4sQ^fKzkU)3ywJq#z2izUUuMGq^I@_v@BPPh@HAbH5Ait_G70W z^DsJIcD+m--!r(ORq6P}ZA!(kvDMu_IQ}+L@MweHpFB z*a2|R_s4Z~(6j6dB!Sk4#m7R9m9^r9U{lTRu!@z8N`7CBhZ=l_>pLZUrbMetZ`d`g zx%f(nVySUwxSjyuBPF7}VPCKg`O)=Pqf)OkAzvvmVOEFm@y60XH`|y_;p2^66}&yX zUEgmm=1h@$l#bueKY@|Wj^D?e5*@!E+e3LUy*tBseWK&{aP>9pA-q~K9CkeVX>B|@ zLyt#?+VSXo-hO{WS)^rG|mcyvA=>U=&qyaS>1;?enhJUXAZAEG9wcF@Tgw)In| zcyuryav$=NA6F^Yz9II$2C2M*OVJKp=+0h0`(bLTvScPi@l#wvozkbel&%1;d_#;M zxTN}*p3T4FKZ{EX@InSKFEyj=YW{VSzr*{HbAG@1p!s%qo^OZe`O)FIsf?K<6+1i6 zx3lwne>^u0FMM(gl{4O#h45W2d80d89y%AzYpVYTHbb3@=8Z9a$DgkuocR;dS0gXs zTr_|0;@O~HiOxmyCmIoY9qn8+e@gn9R<)_^)u!dt`g?`>W0Q64o4V^y#=mjp{lPtV zBbnsylQ#q+;dCyVKRs_8#QJJG7oBNJ)pjl_yvbGDx#%LP@Pn3}*pQ*L!k_0AD}%%u zJdq7!a?Gg$D6!E6_C5(u28F$D;YCWGw~@$|I+MHByDy&7R_(TE`*ri7Rl%iQ=8;;ESmp<5!0NG zMe|=VVn3&2(fsd>m>nxy&%T3G`nfS3ijH>5e|}6yqK6v3F!n8}mm0n#rsL2RhA)e~ z2meCDkBaFi^m4;j57a?uJ_n()bbM?DmL4|AnwXA3Uow1sOoyPa8h(0AN1(4eHOdV! z9e{pm9&L>2_%q?l&Zd|SKkE#?D5j&&VZOZH;w2>tY8k(!Ds$(KR6X@HR*I^ zDb3D3{3o;qn_r$|rSGMu8xgv10IcbWoaUh|)S8lxDgak#;&L&GgRxh4h6^2c?+-mS3IwRB48oS{J8-(#&up8l4VG zGowwdx6?ssrrC)8&Q69W88Mg@J(B&580PF;c&-tnoE-}r+2c;qcmpdqZktCtJlc;l0Dk9-> z2cPD>A|()g2jh|6D)4)$tKUC&PtN`!!>4D zxNvIsNRd}J^bK*&U3aMFU6B~rRW9~rKo>%7rTad8#p^`uuv z^^%86M0rec6O~8!E<0H0ce$LzAD|UoP~GiPya{fC-3OgsfY(L&N+~c+I13(>k}@8K z!cZw?zePcH@d_de9SiPaf$oj`J8Wg1We2oQk*5HXYk`+n1@AuQkvZBMReTE0c66DK zh+a3Wx|Xdu$2+>Ia(plH8UyTpCu5xBN8%c%8itariw+ySLy#Q|>~S5zlNEn36@p^j z3JeAJz+Hy;aKOv{6}jwh03sK7n+cn;c`2Nhpp7|z740GG*-BIkLOP#{})omZ$vdl5!*b&_p>r+T}-jh8nNUi*40)A95TM-jCp z=7i(0RZiS6MNZ7b^kg8ZyZ=oVgEf$=#8OypHP$a6FBj`?gyo*>Gq`#OoLejfYIt48`QQA>_M^bsVrAZJ|9MO!Hs)+EJ)>=@(ZMR4)Cf@CE1;5`G=G2rQl|1 z=J$$uKf7Rid#{&eO}*kv5`O_OnMXs> z_!Ln)D_-8VoS==VCU(?%mh*om;V`QCF#hwhyj(2LoUB-S?@^&xwkCGw0cv8^uquJ% zKh_hH;tydBfb1uh!h5cTw+V6tP<0&s?SXZ#oCs{_cp>J4P4H$RoCySHLL3Tm2;k+d zY1iJ4g;A!bCl0Q}``J*g6YwnfQV4cw&7CSO1^!1u2(c)x7vg2)>e41pE=lS?Hk zH%c(RRAGn& z<9kGcJV(WzR;_rawEoOHZLnrIsY7}R9~&v{l+p>+%XcZAFtAPOgfXTxMz0bmxRXc3 z?KOAd(HaRgh*TW!g-4GORdE8CPM_Ic&8>aa;neec=GMNVy&k!>ua;sOn@z~t*Mz+^ zQ_=gUdT9b;kD0IONB}(-{(dd@+hHWCIpIvrp4mn3DSHgkn|Zh}T5)EgwXH38`2=Pk zq{E^Wa3)&rW}@Y8s84+6^{6-mg-pApZ(c9GiV&84;xoKp16sRPo+VbhWpLi`4wo4# zudDvGTL$M%?QplTY#AJ$O`YW}uG|Y&xVZ>?X@_p$!$UIo8l>`fTw;IF`yMdhG48K{2INrg?VT2z)|6BI42dJiq46JU!i|O;nK5NJ{7)?^tfm_oj5h?cr)m-#a;x!~`ryoiey<$X$Pr@AL6}?#^N!BgD3dvh0 zDez*G$f2+LRoUQdd5FycSn(2HNm`CYd;s8{9udxmyQu)RHQaKU3USd3o z&WjxgXVmk5V)vnh&bTgyX~mk4Gmy(&z>SJ(^<*SeJW=F)(Ty*Lu>nS7Usm#lTwC5W26aL$>K z_Y|Fj&#|9zDas=rDxI%(<6Er4kjR!iQgoY??rv3jUP_Wjnj*c}2oi;VlFiqO-j@3N zt?G(Oo4OaaP>CgP6b85vOK_=?L%IB3r}9hwP*f{f7cSSm(>8gyp?ud$t$#u!KD)utMXU^9?vFr>Ex(qxhn`~=~Rnm=u};$(~XF^ z@fa!H*NC|FiPD)yqm9eY3Tt*q}_pJS~|ywtQ&JC#DPW> zx)lVrbgmJ_ZkVhcWJIZ(dIrQiYlD?;fZRDat1e#c?m8V}z7ciqW@@wa5F@&{m?Vc< zc^X|t`7AV|w_7O#i;U%=@ z)?ey*<-gB#hbZlE@Bp4P$nFMSp4#*|ZQ z%}YM3m9F)|lQv-OgFuC>6o2(amcP7E>RxJh?5wa7%ul3VggDAGrcB}nu27#xwAfzIv)e47;#D>HIX)Osu8CqQe%*uW;JzM zBK3PbI6dz`rsKZ*GPlgkCEUg35Jy?P6?!pw zRr5R--!7IomW7Tzq@)j?g7V5hS|y{Y@4{ehVb}cD%ueYpJeS#q^azO1-OO|^*l5+7 z%WRWnmSz~mOpUan%q(%Nr&3*^P;3sQQ1Up18Wvn$sHeAGLlc4)E4=5nGC>KprmHMq zOD}}@g%Jt&g(TaINW0}Ct}L8{TA@316U0^N!y!uDm-6juBPv}V8Mr3B0ZFw>UjT8f z5q0i*sa==80!bHF&MZ3krI~JYgJtdd^qok0yCKTw1|#~r30oj;G_}EAja;-sdNCEF zNFCFjdABGVrUvK5c5ju+TWf?~tX4er9yNw2RKmR2YlJ5@y;Z7q6G?@6vC#xFwgR+9 zj<=VbC#HOkm}*vD>?-K+wzKj2reGhER^AIE_BfZGr_z5b%x8X=!A@;Ywc!pOAv5o58GIMENCJ| zl$7TAo$sYHkMzaXS3leAd!64yGS5kJA6 zb7SC**t=ipD*@NC2F1MP=fWGJTAA@a58nV?zT-ID{yyu0+5@q;-otq$l4U?VfLI5z z24K_RGHl)>EV6kwHpg@l-ujmUaregJJz<_rnzJn3o(Is;+#SWL*8SN2qvr9b^f9{P zjd80U7+1gI<7h){X<|h$kYIycFOXQ9$1Qbl z{JU1dQoyw=X*G7O8QYGb+kre8yS9%qei`xwz${i0_nbv6bYjHaX6>aJmuWE=+$w{E zB(Rm`C#3ukD4v3bTAercXquU8NvR54>0fbYio8-{ylAij)#F3>yCqVeMF0W|`!&|S2z;xrR- zs#pr$MGM3_8ge<%7QZf(#9f>&#lFSwXGqVL#;*7cjiPZ!5#<(c@w*b0UjY9#e&eDP z7QZ`Cx(%@SJqU6?P%jOO-*ZsU02aT0fczjr@yjrbB!Twv>+-u2ippPV76x!To+Oz2 zp)~`D{}btHAg74<8sdDAjUqmRxC~?qU|ry+mEij8g%S3KmVNc?HI?u)+V`eim7td4 zT8gk@m9S};LVi8Qt^uq`ZSZaZNpD)NO86Y|6W}L~SnpOR zw|7_Yy9k;C)V_hwtJkg#yW!Hq41^nZxm0Z~DIn(3#(~N${1X>I`EP6%rv|D5u>3bp zSN0PL3o)<-P7Lt7di{{ZF%S9-fn?cSMp=jO$as%*R3K2!qN}?jnXe)wO z)lb95hIA92In_a#MhLe-2PZ8*a2u~kz=EQ}1Cz01JD zQI<+$i(5EdHDSgUE^ITlaAljZg=fiFw?(T~d2Ufs&NS!|c(=sx=7!f#gE%}R0den) zi}Paw=N#6oq1||OjHha4i=2NUeTIJty?@1Do7V3e zyiPS#)JXF88UfexPs|P0ZAE{ao-udMAQNp1lBkh4X;FiH*dlPcMhdJZ>l z3wOWXD${K^|4SgRk)g8R9%Ai;d`>JCv!Au|e?Wc(4B1?XLhB!K_Xfl+D5qOo0YAQ- zOT#A&ctHF{h&~{_0CR6O@u1W;Fb_Gny&a89gOYE`&JnV6I+tN28!9`;LyQF(^PhH9 zoVsB-JN|EbP`JTKee*s(9p)6&Cjk}B(iqnoE~UtWMgI_w$wyGro-%GM; z4FeGKZ5-%&6AdKb3wyiNz@_GOtwQ4e)~T|pUm-j2!J1B1t7SlpRTuEOmeX|nhn(6* zr1p>-CbjO`_k75W8;nwSJ(&2AJ3u|l>pJWVQrzY=^@vj378$k_x4AL9QrzZdT8gSQ z+%se6)ym^Qvx{;*gcdt*cXOa>H7zK%G7{=$TfQ1{thS0xZRJ#{bz42qi>uWVbwb@3YQX4kJWCx%qL<3if1(NFzM7^)lOnBjY<8rzks&|f zkcaib);rDrYRsE-Dyap#J_CcNPbVn6=fVrE$5O2|4d*d|!fI_V`H%Dp=LI@Y3wl%x zgw8!n8Uz8XUX|mFWd~}34%C9(Drbuo9jFC*t~40l;Rs{pb>&~sRjkRC>%@u<*MjfF zpW0!wv2xFt#vW25)45u(w8Kr3M2CRY(TQK~IoCjEYGG+HGbb;I;SwJ~87^GMX<=Q7 zRw;oVISsp%9xS}O@ZKe>g#W;WcgWM>z3h)-=p-#1Rr(9?+>^6`4$)$@#T>|b#ddzC z7~~b63>~xcvzVQqCG7kxVdrNFJ3mX<`B}ow&k}Zimay})gq@!yqVuzoQQTSh3DcKy zK{ji`l7CV~t6j&fP@V3hGIGz6Wv_-2Uce>ysBLYYQ}BxhXVY~1n4P-B?9?S@r!Fx& zb&1)jOUzDPVs`2hvs0Itow~&A)Fl?3x)j@~i)L^CELFezten66F zgU-J%`y51-m$VH!-qxWn7ug1#Kd-a!XwS@Foc;zP+Mx57nYn1s%s(n$FGnl%LV1=pWua?KvQzOz2sIg<#WVTv+}~np#yEu@iC2M zB(3A!x?cE!xHqX9hILG!m$a{Iq=qEQV$_B{0+HISSU9?0NLOFiNbO$rckt2=Hd5zd zer^3+DeJ2m`E})zchyrJM=bFlE`S)AQ4ffDWp9#wdgx-*f^O%tP_7?*J9z0La+r|F3`=y4=RC;_ zFH^JTV1n#2BT8@>gviMaL85VTkxQkKvYm8;<)IP3kV@}3Sfibu5VistES@`CY zyBL+)k}G_%SY5sF8x>@R%zQ2dyL=7ih4Lm;Au2DG&VhY}H;g0)H!ALG^4Pc3WYq0m zE<;`i?Xq@@-3fX#li3jpa?3qvbuq2(rln^){>i<*>xv^h*T+VO&ai5M%$=l?lbQQL zlraA>5S8OJh&)>mdHGMlQ-SrkX)Es~c#6zTZM@98@B(PB!;g4eYlWQ;ug?6+<4#_2 zz*y>jpi1R$J}Q3+!tcPp%o*Vso1#_lUV#^7l*gh6uGeiRq4!^Or9o%RbXW19MpzUY zmFIer^|pL^6he-obi;ru$+jS~3lkJ?RD3HIdP=EEE=lO?0`5&p>L)|J%D7A+^(3J8 zHe|U{dqvklC_FH^e|DX-NQt&=wYH%yN8Kl z(ZfWkb`KN9qKAo6(Qj%(&3$5%D{ryPVvo^8?e{gYsU04P^4ITc?7^Z~y9bM6(St=p z!`Me??M9Yg^S}O2Tw-5vu?LId?H(+OM-LX+Gez-s&lJUT&lG7A6z^SfrP68=6z^Yp zH~$(2D|bCw6dzXdq=cFf#YdICBK&r`L|$=ulW@(7@@k8xqhG(2%P>6x!^G51`8Zl^las_Llf!luD?$McA(S4 z#61nGA;LhXhl%YqdXOOzgr{-6w@d{p3?BUuVn?K<`mu_ z+d4f=%QvRKx>dJs z)z#o6xjvLYsSQq&moaiebz=*RR?9pKhtzHISE(Wxu~37P0u z%78v@prSlAhZ?A4#?)x`(-LZ+l9`Z}DHB5tR5BCG{tU9CS84;5O!sUrrKy2Rrnkv? zp$00Mp_XRMi)o;e85YX4CO+`$rMsvGm_IJ`v!iB16^w4dSUwiB4ilPg!BaE+Cqa(F zEv)2bPDv5%{1YMgb4lEnIbLRU8tUU4+Ndju>vbDPf194`M}0wV5>IaCjnUSe@HD^S zL6JU(GS(|TfOLvW;u7G*kDTk69~KW6tJGLu{fKoj9bj>}vC0$qSmvL_Uy;4y3S;%( zo|V~JP3QSui>T(DnYBC-$S$7IMkv07hF5g7MP4GRU7RDUVv6UKGDtnw_-Bc4m-U3a zNR=3=0d~KiGMVmQBfd(?>%N(rc;Np&Pw=gfG8@6u*J{s!bzevg_wwh7V0L#aov0#u#iy$tYfDs&_ll)kfR{N}Mfu57BB&I-%xDZuEqtwwP`x8P=Uo3k*W{1S zswrR=b1pSB*WXn-mN1-J1jN5ZL`ylm=B||oZeVM1g1!BB7%k1(L5iFUg7wFO4WdPdhrqb$Xm`mTbB|jP+K{{sJ z41cx~c$nDt0R_vjcZPqQeDf{vSAnwUPh@G&SCjKUU;zbE$HNcg8{jI+4p3@*HUF98Z}^aYZ^;VtrhSnkD#vrP#-% z*Z^J)l;6bYTv3CwDU7~;!G1)pQ8;@)oZS$a4$v3ffRJt$soxUNy~L|tO~M`gS>U5A z;XWBuETuVf2$=dz%T6cD&ORvF8?f{gBRGLH>ip72l%B%_zO|70PvEB!(D+D@l3lKVb+*D5rzz@%`sLXb2>D2wyx@UvicsK@W0FHC~rWQ z-@1%Dbdma@fA6GzXbmYW18R20t_sZyzNt|)T>|YQp#Bt0=}K&07yQrrE`3RcBD)y+ z9SGb8qKLcKU3)l#xeO>T+?}zkf z8Kh=Fe+P-TCDmVw7a?F5{LCx%yLKlprujdJd;yr|_{R*^058eg$ywc#Mj)3fkJM~v zx}~Mg$_3(E2khT9RPDbAXyGm1B6%MxSgoUI!GEs zeBnq@xCaC_h;Y4F&X^iPNO?$(A)v`tHixk=S@RP^8=0>qqNOa3SbAMAHP>M&$A>WHrfwTlk-KJNo0FoC%Q5Aja)CDU!ik*dKtEP!w>PFZa z3MTI*ph03ardoA2OKu=?()$ox4J?f_fN`nj2NS>Ar+i6T|Kvw|f*Y}uTUj%wCFi3U(ExLSNvM9XIRsSt8e*;*}KT6%wHziPL^xkzpUw=F;(vU53G9~DAEz= zXB?o3bNDHpmPl7W2I&|Lbvr}q09Zks=^8lba9{xU+}4cJm7aIlxfkX=fR}t0uI?jRdN$A5&5OSX zt^IwZ!xQUCcShP*_R{M7{29|!ggtFgYlY%MlAC660}l`>1kUavPZm?kbmWg}Spe(A(cN!sdG=v%!PbDz%nScfa)R z6iv`NTHJ<}%Lwl71ofUmFuGnysP1MkO2*jy-rMO;3<#s3&WxR$##{MBio>2pwC^J| zEH?k$O}9Get%L+`C42@4OA;eTD3sP)35k)DG;w2=$+bjpB_x`vMG4DjrxI=&Zq`hZ zM+_n7J(2cX)s-aHLHaxS{Tq-y3nciARtsW2A>r_Gd}3C?0g~3BqZ0yk0OzYCJ_ZSQ zfii3C>5|gavkwxzBxSvd; zJ@1LN_@&~w^PcQ^ba-&}I+5J7aog|8x;$w^N@zFE_UrPtzm>Ik^*(mw6YK9gDNIYy zn*09xI}=ZdHJ7baIJfkE8sXg1yFFxP>HTF$W&h&RG53&JZwqwdz$rUk#kP#ZckR>> z6Vmq3_txa$g#E@AMq!=xOwF_P=-V6haU8cCeMiU1gxzZNofXpU7NhUV+(y`~Mcz5@EbO=sh-DMdxAZoX|r-m(J;_Cc=|!-eJFvnJ>$JB`x$hU@pqbc@bgQWrsYYtGkN*ey9< zXELlf%Ph+k?UZ0r8EqlsE}DTH7%mwG*BN=z@56DR&n(JqP0 z8vVuqeyg4bCv~q_GD04*KRv18X^7}_MZT{JT@N?hhIX^v*wnlB+9S%vMyW0c=~7AnmbCcG@6yJ+-Uk?jq$pL0bcj%2k)pQgV*^`?h_vFT_?gZ&+#I;oKSZsxcrWAW^ zqg9P)i^@o4&V{5gBmU>>n89MF-zp6$75j{_vX9=j5s{fz;LW5w3@F)zWmed`H>$8F zLz@INzK0rEUZl03S)Ik(1NsagtBUvnzIQVcd!(%n4u)|MV0EyDz$!q$L?03zStAAO zh%*zC-+Ck6zZKocy=B_D$esd3)yR(OB<@zw+kkRLSvy%_z6bUWP_jrSD=TAaR3ZO{ z_9;+&67=JV8eMh|)36@WQt<_Jz)ZeNCSQb5i*uVM7`*{Ac@%*WK+ZGHLDpY`?3k`4 z`ZLd%3V&yy@_e{C&+r1}ETJdR{mtzc!gEh3Jc`LO*?&i6azA3u0a9}9{)^;|oM$Xs z2Xv9>8h9%JFAyuC$K8#laWWd+5O!u>W21T8g-D;3*VuSaJB?jT;~nsBlg5M|t5=$` zCX~79-W7Rel`S&wQ3UVHE34d3xyqSWWfk%Pymw5Q9^V(3vJ}c1(C@d(B`mK6qou6i z-w*-IYr#J4logt?KJa=0UX6xatyNDFRD-O|4Y*XVrEb7wy-$q>T%+q1?u%F#8*Uk= zt42@}Bd8hBOL<*%1dMPkAyk>uKwi|o|y0yo4 zb;nS;!AGD|Hev@?Gab(lK7#dRE9Tb3JG)igby4^%gj$VP3fy?5!>dRa9$q{7V*ZXuJc#}duOnZyU)}w1b}E$0 z)D8J=?jc4Ke7?_-f<^QX{^ZmF5K9#<>H%l`zq!ExiBe*HiavVY7u7d`1}iN_^bYte zWOf5eMJxIQ%Hd##0hQn6#3Ql7Sy2&c&x3ImkZ3^9DhP?*1db!1U&q3Wcq*q5*`_;w z7n8bvK|cHmeec8uZAbV@=-8A{{g6Pgquy9+{(x~rgW);=Bc)fPntQ2<-Aszt0ma=h zNm9YS%E55A@;MIT6L22`qM;yvBk(d%_9dc88`C7YiCC$#Ci)^b32_2lY??kIiav$- z5ph0{l7E1FPvBcA3CLhOC8|qotb6EehSGNXxfeA9%&@(@9x^-qAIb-)_$ztt zYwj3@gU9oN-uEQ%GSU3ql#e0NK#do4G;t5ay8%%eWCsF6fwI>S{fP;QC!yMd#ZHf3 zghBg)&Nnm8N4uF(H%MkoMnwx?cfq>7)FKW6JqYO0zlQX?WVRCTWbk8vVm&82M#lA$ zalN9aW!xbUH^TiD5X}X-nZS)e*@@d5C)ehg%xXkVmJ(f>Wmb<~r(;)iDvaL~?{2_+ zSOQ@)NrmU6x+77lu=(&ah&%-(PDdo?!{-zI9ME8*#fWYIe;t`uf#^z*_X)fQluDrJ zPAFf4eF+rZ50c>?lLCtV2+}~H4oF;z#?zb=Cl(Qo$t^o=q1viuf+C8O%5SV#t466< zrxS5!z>2kMp#~QRf$lGTdlBh7d3gC6s^&0X{gmpwKt6q#KV9){P3b03>rHy&g3$Y`dSuIiZC(<#~Mm$xkj_`KRIHBK@`EY^>saGq66;9~wcp7qr zZp<|hUe!u(j3wvw(vU08kZTV`SxIn&LcKNQisy!0F^#R#8gj+mkV{>bWOJjg>Qp@y z2vo0WVCV}}=eKTnTKv|4>;t-{78{T~-0B8o_xD39zukFPZd`7Ugw6%$ptRwTE8V+| zmG1dXW$s*X?d#y6v^f%R!?w7FZ5))g)JV3kBYytrkan==Kb7v?#<+%X9F%r}q;f+z zz1x_WR=wF0vv(Wgsum7SyW2=^Ux&tS9F(R(ZKWGFj*k`n6>LJKd#$nN6_BF8bE$ck zOI#Z~I5cg#!W!jqXxjc_eka0(SjM4gD;3tTk3-W=Q&=xJCY#DGRro6|9H90a{<;pr z#cRfJiE9AJp=nzsp*I@~N-I@Nag72C>Psgh(|?bXC~TFDJ1;G5`#sXO-=o&{d({4# z)Q+qD47p=#ZNEpY?f0m){T{Wp-=p@BU-0a;*6sI*zk%Muu^r3=og`M+(s_c+@oC$I zqnoRiKor-77*kL&}dU*;^3hVY$7 zL0T+MQ+OR(i*_<(NZ8C>rDzvBTWyqQ2f#^jsdDXmU6r5_m4Fcguj^b9W#)<7h&6{3 z?ka*^;!9~jMN`AKklNAnQ`H4~kZ9OL_sR}-Seh4JgMX(Q42gxOA)o4INHQEFq(?^8 zk_vU838%W<2a*l{Nttr0+e;wjVJOZpL#o4>Qa#d;y6_+=Xt6jA;en)_+R->&!-vRj zYG*@wh8jYob~U6aJXqS?5pM%RZ3{^4ZJZ(D?&9ocNOQPW3Jx@6RQR!OqKhn@mT)KK zXQ^=}hO?#ma6=}CJ4xFbL#BrFr0sZ%vs+wHmDG`C$5v3Az>UOR(c?6|T| z)oMnbO8EG)T52mE;_n=5r#g+FOZ(thyEBN~c^oyWW9?o533JEVT}c?R+_84|fYpdS zU?<|~SUVw|hrI#9v3B-`q8_<$tewJM_zj%=v36nZSi6gfk}S_1YbT^I{OV-Ho=xg~ z%#^*?%dvJs(&f2h?Sy2)+_82-ioK%G`5UfYkYnwBPipCbCxfIv!!kep{0WRE(?^_% z4Qbn8mA(jil(r34=}+J$(zd}WZ5yo8x1Ww3d{zEL7}8m`;ti>^4OVH}V3l?otok>c zk{7w+JBiq_c4>F4T~R>g?xZ7{>{z>Q3H2Eh(Z;cM67~x7$J)Jv@v*}Ev3A0e0}r-i z?G#QG=8v_Lifm#2Si7CU$_p1#Pde7_D6s0n{IPbw0;?;`A8RM9p|D(%`D5)0^T*oB z(|Z;ke+@j2wR;z{1{CIxwNrfz8JIiPPROvri*G@YW9_~mT61CkSUXk1m_ogStz+$k zjV+x1XE2Vni{Z#E19QjPi8a3P4N6?c+TDYaiC#Q+tldDcqG4RR-H4QO7szh{E30_y zG~#S6nJuAx@J`07?D)I5ILF$ZBJnfw;wp!2;$A#=tlf1Ix{1qV8I(&e zcdXqb;{B0}8KuH<3M^%L1xwXjR2;eHm{lH?X~QEgt2<o z<0u@CwG)yJmz@T(uOX#j?pQl<%ER2TcJjgMaG=bYmr)b13v%5k>r(^B@pwe;2+9~LT zI!A(I?Vc9B+#PH88sXY7cdVUyxlZ9kx;c)u`v^{bxjWWQ(ObgqPr-O2qdsp|xjWWQ z;n`vCSUW}EE6g2hmw_|K%c@gUdRCJ$hU3U6&3w&Dfl|uXy!hYe@p>}5=dE8opt1;?`do|)-cMOXgQkRa@_fhh0W4Ivil zWQ@vx8IlaUHG+KLZp&6OAEu=$8+N$_#z$$H)z1p!V+;2$U*%PPme4DieC|ZtTM1ew zI(qRItf~Awl$kZ6cfOH?r&fNIJ%`&&cr>%r%C9XgFC2IZ$TwzRjQzTm-&!#4YUI0| zbyg$aTaBb#CH`QQ*i^WuYLr2U?n#3R?~}2ap_pUlH-l>LgJWtGg|q(qXw4L)|+cI4pW zh!oDCS?I_?A(W+D;jaXzY5>N1-GKa&gV#fx_6?4Hb3wEu`whe2@NSAFTAGzO?**f0 znHBr|Wab%=wKFfD@7# zcjTau6O);7XLuYrDBnIQnRx{ZPEOZg!Bxr3Q}22lIoJ#2?PSIsIjGKUWx;eEIT&4F zb<2^1-MXWx7%_MLm_lArA^udPGBU4|603@_%*Er}zw|+#G908M2QSTv zJ19%_URL}9x&|GFzqFR9#0KvOYhnS@jjmq9;N3uWOh)0CT|o8$nN%2s--2X6All^+ zEX}=mYm#vH!*H$cey!-5uQ2pjhFA3TBia9FsDWLC1%Cncid3&fD%+BIxK|G+`Th2i zVtXaGVl5|qDsHDtUXz7%Jh)dRMv+Rqqyv%-PI5w;^Y zRJ%AuOzNDmW=_=ywDu?r8b!8?a?jUw(pYghJigZ|%1&+3l>NX=X&Q{$;OMzxNhWY5 z^Ed|9x>#qm#j?=PT)ZNgQSuR*YFwPHZE>vRe&*tpe5W45iND__ZYEgHkEEKNi6sw` zg(fGd&vLt*J3DtI%~Ho|Xk)4Jyru-+7hF70R4b)j^+30JdZ8w?yX{`?dsUBFsmziD zEzg_b4fzLE)><`DooAW9qD`TdRMj_>NoBo%Ql9KpU7##<@-J$ml$0Y=;q19DPqpL& z%aoP7SyNT5M9Tf=@=`3al9xe#T#3EgMy*a8;A_s(v7L z)Gg>P$~L*Gc``BUH;b&+=2aEYn?;#m*X;#|oJVn;IOGs~dR^0C+&6rBwIpUyT2>9N zE~+jdnaX1S?7TjA;AF)^D1F5oNX9e)e(P|a>)2}FD?vwDbk=|A>wx4dCfq}HeGB-t zK-ud3m!M#x)@Pip9lxX=0kid)z-%24J_0aXp9u!3q7DR~2bitT zIa`kdUk&`!*8Bb^TVMMhY@K=PFUiCog1FzKjG?BM>A||IG*ib=RUiY^>7~x3_CO}e z!8)njwmMt9zTY8s57SpoyO3!;5k*!j_XNGArxi;#0LfyKx+fSab+>}w1Xww$XedYR zpP?Z6o8dmm?bY9m5BfI-Y5$Hk<8BQ4NNM9LzMgSoFib^c=G>e!r+$s%TuGeQ+TvUp z^imv?`*lvPVg=T0Xse_;Gktz}&h!mI7sYrI6CaW38ozD`1}gLKgTD<}gWcLI0ZL7^M^ZWgbxB)ND=n!*DsxFK2|6jMEvVcG zBsB+E67=bd)KlOOi>86+l3=1b+K<5B7i}8NYDq9da^cs!qz`TPLk~KNJ!HWl66EZn zetXh;ED6@w{a}5ppXzN%u-jyeu|IhXV z6G(eoKfsZD?r0&^0Y?j2sjTO*Bd_#_>$SLjY%*M*)PE{mpNdmj6RF$TZKc(0rS)LG zv}On0R9ZV>+-SfmW_HkD6>}W;5}Km73sZ?7ON^6ijr0nohkQeI?f)4UfXzf}j4 zS^FI2>ftFw9|n@=nDE$El{xtPK-ocutwzBv&l5B84P`F5c{KP@!R&InlqP6h0V~Q0 zt|(`KPXYc9MY#|Yezqu2XkV0eFq79;$JKVW{^f16Ux#j){hfo(Dw!il>rlW-rgP9o zMQ{oDdeP`6ItN45OZ*P>P9Qn>ROuTpCwK+?8K7+w{2Y|UU<-dX`N!H)*p|HY7x$99vrBHe@}v^;%avEDM{3K( z_Rjxy2MUZr&qtdPrN) z)Lq6nvCV@Uu+nesT$}TN+F+nOU>!xU7D(z*XKm1;Zu(c?8-TL?7c79bi(KFy@H+tW z);i~{&x1b&wB_AQ)S^ZescbW572%mOsjY0hiW@FLf17P2ifw1-Z7Xx$`2o7$1I##@|x>UO#&ZH%GX=RM!%eVDA4)9x5G1d~k@f%bQ zI}pDwkbHcDga>FOy#Rb)!1DZ^Z)2Ua!A}5YE$8dZVPMlsKAPUWk~Cs@bbj}PL8Cmn zp!+Y#Z9I=I>OK^1B9AVqySS?v=J_Y~qtyguXJcFJZxC-Kp<961Ga&a9xKGFfAkPqZ zO33XXuM&7g$QF=)5%?!yWqn2;G;d!$$2Raj012pieljf6Ov5qMxYqBhdRsrA-Z)sl z0B7emu}D52tY3oX?o6iMv0_yh;Ko1i_;o7H)EIK;zvK5&Phn$+_gwLHqS!w6t<-v` z$ox-yiS$r;`JcM53d{e@g;i4i=N9&czD(8l&-*FWq<>CbKF#NS8*rr5Il&&(mgWmC zO|L?4o4{TDE2d%$l}A`RcuX#r(=PXB=4tlQ^M@PVS~ zIK~J3DVhpR2cHBaM_59;tHG=QKNK+MdB|C^9{d-;Pitfp*8FUZXtLH;BRX}@?vUIX zsgu>7)d_u|H{vx4?KaEe)2MQlahqSO%4j@rDI0}u^Lwda8kH50p~_36@&GbHtthqP zGLpK@pV3x+cjU^iZ(o#8Au=D}U4qgf-_jVf z=ssp3_3x;K?ck^VKOx#kZGwzdb$WeIVdT=ue1OMT_`rXl_LC2E@*Cv?yq{F@)TQ*c zZSBm-9oUfbl?uN}a(DiKzW~Gb%@t$VonrK>{ZwoTlqX?50rWgo{=hF9q*^&J725#e zWjHSa{Ca(eLH;Xg|JVi|V4Iiy!<@|9dspRRgLM;=V2+(KyNd>Q|w&t$r zLTwdOTj#?(4~TVWkAxtfh|CnH{nQ6^tmc^&7RWpEwnpe-X`gfK^`Em z6{wa_vHb37uqT0Gl^}{=AXYdbEQoc5@;6w21^5+Ag1Zm7CWroH^9XJSxP{AuxIt2_ zY2HxmvOK&`%=ZAxLmQ$z{0Hh6;wTS+PXd7DL3*NcHM=z(q(^zkz)S&_hgt&F0ts0j zx`TBEh7H1E#V-&m97i5npfIWC>6y#Jtaf?WseK+ss@aJf*hN(~KRR9psO^m>dJ8aG zZBGKRyi~sZO@}+x5-HdZzMhb^`I7Z4t(;<)NB<$K{6{1~OXD<(h~7LX2IMR`W+a z6`rGT$NiV^>ieq074~`!B$Z%sd8n+r*o#Lhw%6+f+ETEvJXAO7I15J@r}yua;sIq8 zgQxqSV;3-%(E?$AsmfoHnJ0hG5-gVB@k?yr?!N9H>!HkNvq7 zhGRp^ZT;7AkUApCOH#(F3x_z~Y21IpGI*+A$14kmI$n|D-5->P>NXwk{=mkTUj4I* zcNaX}FdXl$9B=3oGV98qT$Y5J#WzE*3>sY->n*qf-hz7q7KKwVa)d(7dJC>#4m)qUr8(XB$oJ zaG)EH=#e|SL^Yq(k5)pymgB&&^B^6L<%@yXa6# zlY5ckI!G^*z_Uv6Y>=-A{9DMSAf*9EECR7>Kz1O|AK3Rc5FUjU-_QRX2(y5?yl(Gc zy0qK;XtA_Qas}LFfay4vz|lga{d5AS3Q@Wj5Lhon7F|K$a-dquES>AXwgB5_Ulp$0 zY3|IS+Zym|3aw#3Ps#MOkmq7#*kb*pOjKNbG{x1g1@K$%?Tyu+L;4+Q-3r8XT>jex zUIvQOAmt(BAE2QIq@k-W19Tas%VaKfd6nJ~SpSY6T`8r~)1PR)083#Cft`SANtxzZ zV0=WxE0*Si2+S3t6wW7bmJp@%FoE9-QHoy@_)LgW?i^#}1#DkP>)TI`A|9WP<<2xS zNnl8~~l!7Nq#yI^YGQ92^=9r zM@(!aumLEp1-YNV?}56!8t=E10;>eerAXq>!+j1gMXwR~n-C@OPXg}()r!&}ZQJKp zi>=P(U7K(|ftf#_8;$G7u4!;D=Z?+4uIqh43)0KEchK=S+RM2EE@xPb@JIc*@cS1# zEt2lF*Q9$Pm*esN1taN>5smb!ZET0?=_0vTZIkZx+DNb0#->#-62~2z9{rbaZnqTL zbaRc`?UqWqSAC;)yQR9g_ktt6HXAjRjVFGjr%F*%*}e*YrHk7w)pe`F?Y2xs?Y2xM z-Rr}VUYw1W+Si7o`DC8$Q?C-O+qYbj?#01KJFtW14o^brz8f;J#L(nOOs&wVhKU_Y z6}B}&l3NZxF}k(^QV(~kVY0sSi4xYShRKFXal8thYMAVt-ak{ho)3ILrl0w+YkEg*l168ui>z&);B1`+UU|nKzT)Vid?DC03DqFytw81Bs>&Hc^ zK9)515N{N~(>`u|osKwYskg^q1=%toqx?NuWRyQ6rA}zi%vKOD^1bhIy+miMY5OU> zXNArQ^#>C!LZ|?UjRoP|6R#YIU!0496lDuE_!X-`Vw+)fMxq|@f`f8mnCq6iI{W@| zXiac?1HoN60fdPxAwT>>`$(b%cgxok-{B7WS(=Ohyg3Djpx7@*eg~8d1^gt)cmgdz zd|FPEl$ezqs5MDZ_JT1DiCuu;w>c?g!)z$qWdz^t`HAUs3(V{TiL*aoW*Fiid<_T68!+52! zHO;x!%_8a|(|2>OwG(l61kCK21aGKBC!u(W=kN_rJdPA6M5P; zv-!ekL!e7LvlpRfA;2$v5B<+5^D3cZ0KfG*5;w0JHC$eG6rw8t^QzJ2RhNNY0{pah z8eOq}0v+m|HY4zBz+C7S0yhCa+dGvL#a!rKB<=zJ=icd2xDNyWuX-oTvg)D5HrSgB z{Rw5y0#+BV5_kn@Yv$HD=ITN(-CA9|hr~NTTQkSEe$qQ3>}cESLKN#D+ttPA==l`j zZJ>Nd)Mn*`$SnLG_P2mpSdgI9fuFTd`_at8awJND{|yWIV2IZd;FrGSJRUNdw{*p& zW(b54Jze7eUCDBTKu8MH$I^P+wz^mM^< zya6@Z{9#^n0s_Ya=0)caI0G;*l5n6)t|OX56!W5uNc;+LUNi)WP?vTc(e-ez1$ zbhN?OMb(n)h=hiDTDy*Ds$_MM7Y$BNL#Nfz9VojEusXV*zE~(Ed6=j%D*G>24Gfx zNZ?<9St;R|E;%co&0F~;68{0rN(sbGbeokHDNoyG5O;;UizM3eek~GgNGc zd5XZ}fa(7T0>7UWLiH~x1f#aV<~5$;+!(objOyOsEpsp_S+`MV-9~vKof}Zn)?uzj zz;7(jm*}iD*2C=xn4kA1&=csFA902!A|5a%xLxvUibG)!2L3m?%NF#E0ceUp8M@ci z9G4+U-5hs8WC~#2+H3-|fSR#3iVCraRa_n5^WNZpKb*1 zgU8l@N`}dSu13KoDXHFaJ}v869!0bGh@9NVsMDI~2w$#J zdND)v5&lq3ZA&Rup^v6SUf(-fs{V%8gC5-fxlU0Nqf720tUNSC?kUQtE4R zXF{d^D4QzRU53KQ*Cfg4kw3xc4Tp9m_Sg( za=pX!aQS((pWDl?CczEmr93VYWSP?ZYm57>V$tdhyiL6!3IA zJZbc+pk7gKkG6Q~feUPpwz^K!;Pz;D)E;d~lxb&cc!Xk>X^(ce(kYRng!@?n>inc+ zzX_&9N$t0*q@-ltHYM}7DcRpC$!*k@$n_}US@al%IWP;1ecDeu&1}6n*lX1^| zV%mBg?^V?TH`DI3GVwmuyBo>2UdQx2D857WLXp~iRwh2Y<|rd2y6Mk753*0m#CNq# z*`%W9L3VUs{9xOZooRP;U)-IZGa~m59PP1Al$UZ(_Uz!kM0MFt3hOyhqM>Y#!rES) z=vuy1VLc~G46v=%y*?q_K?P#R`6ZgmE>&0$ixQ)3({*g+uW^wVtNKFEr%|^Fj_Xh!G%52rZcxknup5_5{jyR!M`v6Whe9;!n_LeC`g~obP&Gl(2uU9 zs3}}1@c~8s9+o%{VZEZ=GcWMR1DbN*D>}-MtUqH0oGUUP!)fqRQX!$VtO~teikwm+ z?{6b^_$%RFBE-fqS18&TUPO50d4ADV1=DFtrH3r@ihkWmLC@Fmdqq!JTAw6r+uxIw zUm))Ji5Hku6g_R&06#HC*t3SsXMChg?nhiRq@x$pr&5ZZ3pL}guWh8(W%U#&el(X+ zeHQ+TH%?I+to=23^7$*!pL_^nki39!EZK)^lG01}yBmShLl$`H{)GyXy(hUmPSBD{ zc(Idt%%2_*O4I0A#y!EyxPAE@UV|9_hb~`m857f9;LNdQQW1Mi;p57-Dy+T0nd8ge zR#vV)UTL43U+mmN}2Ll~;|0%wQU3S_F(M= zE@3aQkg8#Cz%9Ke`38ucl303gR$0sLntZ=F*zZY04vPH{&Pptla+5KSUMfttJpMX^t{o`-&#`<*?ac)mV`Mtox z8jA9JfmQxpi}HJc_kq{5D8Co@eRuc#gWQtaJR5r3)VTZ#K5V>(q1+r+(CZZB|W$nox6 zI?141dbz#8qs1G~#T2NpoB~T(PT{3go+=J&p>z()qcUxHRlJIkTfvp|+xxK(b3jN$(U?C|#w-;DQ z#?S2q7LxUIdx3?N`nkQpLdyNzUSRoPwV&GytR`OP=k@{%Y4C5LHrWd-gpF?}gB)l* zMNdDs7g(8V@^gEEg$(ejY|C%OU$S*clASkzvyL(fdcI!0uXrV`L;1@~+45WQx6CNQ zwZ2~WuXxoyYS_uwd;S%#rKiHFFJ;Sb#p@Qm#n-F)6>ntTM%AoRw)|GSY2n$vw)|H7 z-J>&EM zEY{6WRuuW!GeL{At+aw|r9!9+CD%%DyzXLEfj3y&N-NTSsB=0dxNW7COR~>!qxA1S zg-6m$vl3_71wEC^EDQ6K3GFMbT%M7(1<8aqmR25N%O{JH3GFPcTxq-|$%M9+R<0^~ z0e@MZOlV9{xw_~*)UQk?w7InM$ikQ49hppMcWLEX!;VTOw7s*b*}7!n9BDbhuoIFA?J=!9(XbPf32id1Jjp8Vq+~+7Oe;@L ze~2wtB@^l@D^D-|4(#n@;yp>8QKFW!vS6ZKd9J*`+=7j!Wp|V7w~z~zsX!qwzKBAK ztJLhCDJ@oEWBK57jBsIF1;(_|v~ojuEfM;J=n%YfK#|ehJcAA7l zl^rJ--kQ7;#BXeYaa-pv7@6U=R8)9-<4qv$0ORnEj_X0(3C7`_6&g3WBaFlL-_s5A z-_xyni!!VZ=VafOZrvxs{kkaZ`H!Cga&YQ<5OD^`Qi+9wbxE;bqy86ouc|0;B!+bi-ezCRu^$MC0%ZL)?+Z z;YLH;na1I!?2(AMLyf~LQx}7{Q;ox`3~|RAhrdqU2FIOi9A0fmgRf84g_~24!*M4Y zhu4^DceHW1CG{E{ceZhOts(Ak;ClEF>@V;)mq9verD) zi|-*l>*B&|PmrR^E7w*t&ReHLmV@ zAF=Z4^V_KXW+k+#YKsU1$waUiC0@UKXp_hK54KU&1Ot_y*KYwWIu>Y0;rci!sin&rfv(y_qDTT@+9-IN?cUDV; z-`4|>x+!`dHQ}QW2f^(J)XlAN0y4=SjzlM?jzX$%DU98am=2hXEcGg?^YU>fn#hKO zAk0T*KOpQ0vVy=eptB?jM?*OQ?0BG1pSZt{z!o7hK<*`Q7a+|&tMo^dQsQB2I1a*p zVg4Hkhk!Jse6JHwBC#mik>#QvL6QLJSep$XOey6gy zKGMsu;q?%AfxD9=+REYyB%*UtryuA#9Tx0-zdkVgJ$R`k|6Js*4%||X&0@pM_Jwqn`lBOB3}_mK_ATnw0xTua~@ptB^*NA3o@6EGk7JApTZ$Va{)@Cm@L z!q5B24aCFNuogo949~QIFb%R7f!V2R z>7CQlW zlsqyswI@%M+M9`gLtgF4GoD%1&1MS)t-vD}A5%O%Wv zRS~b~9UJ6Q?=gXX=D5O7B*IS_^IIPxZt;XB7z32jKSdRfsA z5~-{h6fieAK&_`*U*kR^-b86KIzaDBW$4w(kVo`U|K5ajccA=fs#Q|q@&SmgiUuMV zegJV2+=)Q=x+t@CeWrM>W7 zGYi(CDv}=4&f-wgxVrc+;5SQqt3HQl#d1h570X7HT?&-TkQg!j1uB-qqM68<5%<8o z3)p7FBVZ2!C7JDw_>L#aIV0+>Bx}%i!PJOtuUS=@-skqE6AG!UYEA&?X|fA zs`(zvPf%`#zC~RgI2DweAQ|~KpOFJcC?g-C;(efa*?EX9&@dw6tD5?iR zwT0aVEFxKVH|H*}bR*hkrv1hW?sW1Oe`b>uR!WgSa~~UWRO{e|Y1R_6mim08i}iJ( zX`?hGt|OUhB?XfM6`91fPor7~R7|qiRurxJ{)~w}TxnMM1F5YaNPDz3jt1;i^YmLo z_{I8S(dgb9XACBZ{y_O^9A8pF%K*g2MW3Uv=eZEW6S+)AWRk3DLPUcKWxQo#SM%UK zppp6@{_?4#qsM+5QE#b#OEtQF;f8$bgL^9V*{GZelwVF7k_rYY^&O&qob(Iq zy~fww(N1+Gypx>3J~#+6-$s&McBkVEFZFkA6T8$OvrX($e@`d2o|+7g_0>r@ZO8f( zO-wEYW3l;ESDj)T9_E+JJhc}m%R#o=WI4&!$?7EAaGsM@59VY!%yyeBr`bALon{;E z;$**WljT6$ZL*wbYXj}BOO&ILPF7uj(>v0ix=nVZzf`i5wRkepKkgGs*X#I>;{8x9 zL^nQbIN=YL%Stti@Q1xL_OF!hhCduG_wgFCiu7iAsN0^4@n(zC@fx;ng!6QHs8N;U zJZ;u`9kqlLon5bj)$p?xE26VUJ0rA&6P;u{4V`Kku|_A2);O1i65Wzk7*B)DT5d%v zCQN~48dm6gZ{9#H;Yf3%mT;mY6thuFIMGU{L`yi)ex^jDIVsuCDN$1U?J6lLnYT^J z{B271cS^K`6OA?{YPJJe!f|f03O5Ok3e=hkwEckaP!0AAZl$XLnPP+fE=N-~LFeGP zHnGmZq-|oIgE&HbJj61VWWgXmAQ=) zRseD3wqtIigedACCEGOI%3%jJr%^O@%87P+KiqI1NSD)EF9Dj>mBwxIbw$Y}yjX1qq~VFCSlhZ5f_1HuZBQ3RTSItgE=1a;}I7&Ft4aZBh13ht)Kg#c&r%yc@_`0!Iod0y&MqDZn%}NJWe3LWB0gQGSih zbIyl-9$@2napNY32y>mKSY+e*E0DMxsJRgdo8}BsQxz8IqI)^=Hq*HYx!(Xb)47+x zJ%CMeo+R*u5KVHvAn=(GO>*KmRA6q#a9SPX%P95tQZ4V7Zq~3aZu9snY*aTEN%apU zFCs;yu!#aMVwlQrdVV={SIzKe15|lEb2hDve%MOSU@M~^Z*(i88@U(h_ryCGthLaf zR~2^>ufVN^hB}5i=u^F;k!&qA)LLk;L-k%FxwX(RKz}g2=1?QqT4;e=3l0AZDcH4! zr$t_YTMI34>z@T~88-JSyq?NQpkA%8XqGi`usCCjB*vFi zqNng^GLTG6+C(^*el_%+3T6}b0`-oG$sG>^;RMRH{MAV47N7?ohUKqz-6ozk^bn=? z0)jJ3xp?6VXiV%=@-pPat6Vy~$0d3amREQk64}Ju9(1LFp7-@sH>4a7H$>uXq6DuVHUThsx6hF3x zOa`$vBpAkGh{a-u!i{39xyECEfRc!vO-&|a_d+R%Jwdq8D;)L)78cy|1M1Aef_t+H zd%-s_3hpyYVu2P83mz+w4auYy4h#NhNMWFb!-8j%s-sk(#i)Yk4M``pa9HryGI272 z77hzuHBPaYknt6#%Z$LU?2AC5t$Y>^?t}LPTKFs+;;O|9weVRuyru+BPpx@!K2o{F zdL{fFu`@Nqz5^1og~ymJJjQI{F=h*oF zZ!(wCgVy>jGKT}`6{*fIaaf74j{XQ)SLJw}N>(mCob@WJvj)Gj6n1b}SAUW)V(Ys& zJ^dS%az}^t_Iruf$w@Z(Ba}c7zhGw)7*MkGh$FmSzL_=1e`FJ^CMP(=UnxPp$*q># zTyn(zUOyLURLK#m38$rCOv&LZmw5vmqs8x}C*e}KbEW#V4`0>vBec>DU_D&7RA zbG|=EWiZiU2l%Hb-Xw=D@MFRzyFys#_ZG&%(yF#a{zk>y)k!Y)_xJ#8reF326}QB% z5pQ>gE%%>(4{Q&It@IcC18gtfn)#9bo^OHe!JI^1Z+^%rBz0lvH5FQylKk4saYaO=9KUC7)VM&c*r#btUsah0kU_LAZyC7UIAeO^-8+9v6RZ*N5C$dW%w=vgiu zR3=WqrT2nL;8fQ+dezxg;QC1acfJ3kO>_v=iYjrb^!Y7A$4VCXxaK~h1auj~Tnos3L5Kd2N)a0V{ zy@8Argnqo=9$1&UC{a-e>mt;d=Xm`O?7V;NI-7CrEMUkZFoxRUC3pHoisNM-A(pK2 z%JxF{g}#WnU99?Og{isNsnMi$9#F0+@h=^13HV|lz0%v@+qh^A*eXCX9?P#+rjKpS z_x&X#H5H=Y`g~sV0Zz+_$gcy2twdxPB05OAdyMr@$BStXO1`G&&2W@ecwNo)H+QDD^uNcQo8+==txVf(I2hEMmgCcT)*`(l%x-#=@#A%-a>-SN^}ka%1vC4sz2m;YMiHQn%#`nXxe|z{{R|u zBQ#9p5m=Rye6L0c9!T`LK)pQbeY;;D4|+6EEnEI&q>Dh$73n(+`k;$+JP7)GAoC@v zRlr4A838Asc48B`YbZv^og0vuWy!yZK<8?Vy0c2f@D>_g0XnNV?i{M}h?leP6p|Tv z=R_IV3sPsGdgPg$J7pD4N+lG-wL5{1ol z6%0NuQbD`j7S0wI^&m#HL z0c#w`s7NIGKdT!nRvo3*WZH`N1ihB{R{+KPgSSo93-0XOrIBs@a>So8KZgxDzy%?O%&4Rm2&dq|y#?rZ2 za9@aN_4v$!TNKXCeCH_q6&Gf{YCENF=3DF(nS=cc&a z>%8>g*Wx-8iZyj^O!&%ZV#skIkzSTbyj z9{3D^epJazNFG^oEjF$xx&AjSNR|{_=XtA2o`t@$KH7t4^smAC|!kOqYba>G(2vZn?F{xmA7$Vx32voNP z>kkC!umt|PAX-b}e)R2T-W2O_!AYKXBHiom7+SC;9En(6ZXWzL;ZQSm=E46Y?1i~` zu+oaz$8?wntH_fTxp}Y<_c0yj!74ZRF&*Z?Ledqvd9V=oF&*Z?LW;fmWu#E7OWin3 ziWLq{;x}P#{#%J&;^*eSA0bsQc1wN|ETrDv?CV6{i_Y<@yF(dp2$?E6*CAarjWy3m ztylyzvUzM|^VrDEW4q{OS|@VFDH5@_X(RVGZSfgU#@XAnskEPLjWMcH;qYM{$ufF7 ziLr&BmKCwA-leT{NdB`rVx+QqmA02(x=GQqdXttHX&(V8&n_fB-_-dxNOe~4(efH? zZA5uw^&0I&hcsk0k!9YaI_R3!OSIGdg87K`%<3IlKBw~`oB`SA&fqWt-)g7rYdWf( zVOhOF%g1z<6Q?<=7ij0Z);A`rM;5$3s|p#L)$6l-NoO5mZC}z6XM9#~&+_u@FgO#v zdKF7rZ_uW0FZm6&7yp(^FEtZoD<;Q@SplVExN~Z2$)6eYiBss$6<{gEsZIlJVm0#Kjb-sGI^zS)SmP zsW4R@<=qMJNLcw)#to0WvNyrc%j3Q`U@=W6b&X#syNl&%b+c(wvGmY;5i*}m4-0cX z`z@_LJ-XpaICVW~f92^Zd&ZHv7#-kMTiM0sL<1*98y@Jr$srW$ojV8J!*tMHs{ZVdL~r7kL9p5)H9*teJW&9dH7cS?k5cZbXa@SabIG}E-=J>i79)KAp^V# z|G^Q4_$6bLHx*C{e5tTxoYj^WzJl2$;|=k{uJ?jWFeC`yAx_CeLqaRKk{zv$#lk7n zeaR&A_oVxH+fL5;!wadClF2#e|FslMan2uJiC2~EY)E-{lsLN>QXO{L3^Fy8Wp&{< zR9(rm@IH{HaM{-&)5B*#mV}GG0NK?n_#kYe`IXEGUx)LF>pm32x{qRqE0W=39WGJB zk9YXTd3-|tUSD$HE`^>Kg?N$|jpXV_FVnn&XbJ{~(F!b!MXTshqNs>$#-nSv+a;o_ zpd_QAPzs_?D9pmB6qhZE4uz8Py7Y%_x46zm1rd|9ZS^<4iRLb?r4yTje@B9ui(s<7AaL%=!w@;$O z3|Rjx@9+lc-`ePPc^A|S@XxLu-EvU zz>2&8pY$0?g4d?^H-S}){A}0ZJO9)opit8-H6*TKzSt6t6Y@0YAeZv4B!7UQ;Tyy>FH5QKjqh za$fbBXpirlkX3s3Io3!rUhh5>L40arizs4w)u-G*%u_6tm-4aQeZ9>TS2mXQ;kQ!_ z1+~6*vO6j3^{ea7pelP6w4yPV20k?1my=q>K?&7$t*F*#R<9e6Y-j6QM~G?#$72#N zrs&>?{eQzaEL*vb@I*aRsyfYYm?Oatq3q}l`WO5%KcgGZT9Gxpwla@t!0Zj0ghzJs zPR(lqUG}*QLQ$%zj;|cy*_(j(2WU2|KNA|Ckycmo}z)|jfp-AAJ63Q zXkgNph*Tn4pj*T(iP9pN7sEIoAVCc|i**}pswe$R6UW@lQ$iSi>$%eSOA7zeL5HL|u>?Qt4 zP_dHOh@uiTme>_`_7>L?sM;R|IeN0S?}ysc3XSxa@N^< zAB{^FrUvOr=w9$Yi}vn#(Wa@m{{Vju2reP1{{486At5d~OLBADkshuTU3;6k38tFU zU5Urxge_O1&6EkA_k+K$B5VXXoWLPM zP6s)Sz)64?EJu;D%NUiAp2K0fWsXbp_}D>aUEl@l5SW5My%R{phB7R9;rWn9K@PSO zPzz3s5>QlH&*Bg9z3^W6>P?bJmO1BT9jU$pr$M{adY%ibSP z+G_H9*k1!?=1(N^GL5=gyd^;T9fq1Glh&A1!N-es;q@NZ_SlN&F!03yrt!3++yeGT zNwHbad&b3l2K)(N+IDFEh?HM{tCt_F>YYhtS>V$`+moqMc7bL`LEVPzTR^ry2%qZm zz6a?qspJ$W4N$6pq;_oXLtu=MMIcWQctFU(AYT*sT*w-b>Uxp`k|%(SC$N){^&ra# zED~})$Y}&l60#ZON&>$Xay`hi1fB+Vz7u5nU-|i#N(_61Kr;pVTLp!C668ZD$5paw|31G1UGIw7Bd%*Ba51W5iDwK7Y-=pV&&HbLVGxMKsXwXSyWI@NYmQG$jEs0DH*4K3#c z+|hq~6vrDjn6$=_^(RVr2uME??E-k2b7>^mGHJQ_xnRn^hP&=hck{eUNGP!121xx= zwlz5WGMt4Zu@8{k267;QWk9e6`H$&wd(h-cZL}BM1Zgv+KFCPs!_M3eZ96Hd7HgE( zr6ls0<)zNbq@~P%2_*WoCLNwc zEyW2!+I3k^+SiqhUf*MAC+HL)D23OK0+rHgQK2$T(2gP^cx=O@B+mH}S77>yuh88D z6gh)WOg)q6s2*CX(f64|e|52xCWF5v(wYoXd7dPnOW4?&I*{S~`6zr7J^$}f_zBhl zFGOK>^LQ`1aLo$urG$;ZsRS|qkw|SsEvbjE^}Ls(u)5+a3G2i=-AMa>nb>J5W6god zUDfI}toM`2%xA=^k>4og!l}c_FO0&ckXkyKwv>Ox_?}5-HIlST{q{?GP_j&8cwZ0j*u?6r@%pD{ToO!DXa&eljaTG;{#b*gYZ(R<@&^6sl`4t zd3|EKCa`v?-#^2OHIdsy{B~B*n-ir%YLqMCD79z-Z$umwwC}Ctve|N(!JIh& zlE0}OtFy^%bD~!HU5Ztl4cOegIniJFz6$<=XsX@j#8?&jd+;xT%-$rWk>7g5xj&Oj zz3&M$(?yoir?`xpEF(=omeECtI%U+<$fyNaMi(UpD5H7cGeuKI7bV6?ZWZ`pK<2+B zRm|uub4_FsP+57XP(uKcA+?(D=EHL2I(39Ru{i=!TAaZXKG!&sbC z6TOZl+tQgd@u`Usic`AIqD;5=ef|RSiv-UL(RRfqwwMi-A^#%LL5A$l99l)(UnF`+ zp6_MIGgU{4Tm(~nhwrxWax+P8`&r)+PXhiX zNm%s#5)F!eB~dT`$>?=&VP@RMnZMJ^-)C`mt&8H;B)Tf@y~Mj6u-UFQVYA&f@V9_^ zop7#8*fTccWz!T=Iha&Bl7=mHh9xT0jkhEFo#bV=!xPpOf(`pO?T`EfGo!C#JRu)GU->+&zh+pDQkGO}0W);iS6F_1>!bXxXp`TTHu+uECcmqT`CZc{ zzpZWZ`$OCOZZ724dph|YX8GlLo_Lue_?t9^m_Z*FuUAb+VjTSeGs@+z1P6gH6-_l? z;YxA>_%WhM11nvA7l5A!umn58m23;xWs;IcR=E;B4t_siCcE0j3^pul8bX=W3{SFW z*G%?USMbk}{SXMIARv>?BGATUN7DM7BM5ebts%8zk?jTZqbOsGG}&P&gTcy!<*+q4 z?$?%`-LN1T)1!T-bI9}*M2_x({TD@g97K08n_Lgi?7zrU>KJx#2^_Qkh$Cy|WiVf7 zDBAxTEO3kRcLTVhc|j8dndCN$7ky;WAL<1IV95MSXfD~SI#l!&;14$QU*?6pLCBBl zM>>7BVP~cBE`KbvvQ{qE%B67|^{Sc}>4CIf=H}z(e47A1Of=bgxoi0=z%K*p?>I>> z`^=Ze*QV-kI$mfy`8xUPRMX33)P;PvkWKnideN-7P2zVE^)|o@=OZzZqJ?V;f%Bt4 za32BH`Q@l;?)hYtmw5(8Yj3vtHb{+p0aE?_=gfAU=v>dl)Dv5HzL1Egwv2mQb3tl*Md$Tg*EB9AtL|f@2YoEx*vgY&nL_nPnD?`4spv z=8szWUhtbJQVFS|j$)*OIbQ}}<~(2rerAo=YR)$yB9q-^2NAQ`hhWKL^K-|t5w>Wp zM`Eo{DEYS5Iv0Xk?p%veu-0K-umpyz^^S<)mi_k3>JKbf>(>aGwbqSfaddo)Mr7}W zHDS+=Q4<~?>!T(-29+%btO-waO?VynRe+{-PxftrnqCxCl;Uzl2vcb#%auJ`9>;+D zn>IE@dF&ChA^s84x(}$A`R^GscS>x-O~+Yt&v(uJ4*WMHqvqbrHFs>o4abob@6Ukl zgsi;}bnX2;!e0W+)c9Ud)q~Vbmh2|Pu+ZFMtGWMCWVwbi|xzQS|_|i$&!r;iluv?idUeNv*lGEo&BAH;kj^{FURFWng_4 z)gPg}F%Qc_^QzZ-H6ws;z4C8Nu}Zup!&6uTSd+$FlkNw;r)cVxan~tN z0AB|L-d$c^j>rE-g$OBf9-3;?fyCV`j&9Ah5x@?sU~gBgdl698#_b?Chz;T}ROX;X zq8QPFNJ3hi4lP;{+UQ)j(;x6+=+p2#`~v=_#|o8tD`=LTZls{UQUzo~?*ul~+y;J& zRe&h6%6nZF3FP@RwaInr)&2Quo+txf)X{*ysaK~+XO9KuIeUm??gh+q_E=z^vk$>v z11udSZ;c;4BfIsHbm28u(kLr}l_Y5kn-wm}QazBZ2!?A#VvC$3T&Zgg^VS45?6pg= zwZ*$LD6>~z={6g>?3G=~&#oTwJgDuf!M~++L6w-9~0?LFP(i>VsDcGWCJ2 zr!Ad^NTyDk^uF``JO9j8v8IuWJJY}9F#3;sx8Ad}&xa%#gI5fKA+2*DMNa~&A?^q4 zu0p&;{J?&vDV1!H&fX9Ce)u;6$)`awU6>I-!p{+wB?QU8xX1Ft$un9ahB;_5iJ*dj zMvyaGnVBxoH2y@wWL3BIGF=Pj&%}~`PQ&_}24ZYhfxo*7OeNciK>wMA3cT!F1@?wG zALy*+z)US)w_2QqBu25l#+!jShCd<}W}h-Sq1f{&v}pR^Kfcq+_r9*v_Ju7d1Z z6Ww8kt3X5xw*IXmZpEf`Sv^dRsnc7TN}u5?=mkrI>LHG04@5f*ssofa0%~3&;3lH5 z8dWx0jKcKCuyh{`jhDAajJD4z#l_k@lC$ZLSwp?)81TS;TS)vPKb^%?vX{as>53l- zNd5t&mOu@VISY9`HmEqZc07q(Wt$y|7ZEdOK$DpkguD)m7zQ@_S~1CiWkbP6zx5gC zJiqlB=X}5Q8Rr7GVT5O#3*9!5)Vt$(UiMp`aW**#_l&c}kDhUwA7;2X!k1&t@;bt| zfzpPZBm9xYVQ00=*K7Xj8XSqf#$=Ok@7u^{!$OBhX4ZPfEI-C}&eA2!GM+EizTHpvUVgwqMmp*wOW zGP1HDO~S$Q@IK04>}oE*;IG(k$+JM=+!|*HzozZUMdVA&o_nRaeRJ#IBCJ(h(oG&bauoJYy(1F(|hvE>hnN~2lDYLU6 z%_Zw;D$7EU;|UxsM9)kY5x4-Dvl?V9F~<@!xd!BqP_F{Iod7Zo4ilC)mlTsHLU#6A_>Z?Wwdd<@C6Dc zS55e76!045X{x>1%YSa=m2Ww_0MdF2aSD(;5acET*8{^>fh5=Q^Dx+hVxI}}0)c0Q zoD1?DfiHlrmw{;Lzn1@_$zVMh+|`@-*FmW3!TS>+*bR=;)g1tA|PG_Tabu+1yAih#UQmE?^!ie9Nz6z|w5jX}mM=3baW&V{W; z-=i&i$7lYnh^T9stIum;Y3a5RBzjX3VJV3D_rsF_EUGXgR< zB6vX$2%12iw-}L6%OC6oBVcF(`7UC(=O-JYTA%hmMaU+QMlC9Gf8yE-TViPKmu-PG znzk4MBxiu^Phb%+d_G8W2|q`ItrmMZ$Vmj&2{{VnA_5zMuKIYNn)@vNk0OK3l=|Ji z#6KIt9Z1{^1T)~Mxi81gWR>=u*V^23VXL`sDYCs_Q55C*BF#qMLOU;mZSB0AfZF*R zlPkPGQY#-7rBF+8+GNVhQL~g23Mrf!rLdF9wN2sND22UuOrc;WSHqT_9MhJaIkL^O z^qok^OwKP#w7Q1wgC{e&vB;x>dSLg07hvf*`#HyQPw~Z-#u^OeRb^dbhGJ2?pbHdP zibvbZd~8L*jU2%c7_yYE5ySa~eqbpfQpJn|m7=2_Dwg7l{vv|;E z^7Y|-?rHlLS#;hyx_dghZ#ug6x}V!o9^HPOh&GmAs)XFe^29wi^Tc>|y9*)p zk0-RrJmHR7C-j_^a7V2RpDvrB0&2r~!X33Pe7fwHO3*ED^cgKLaWAPRZ>_ikdYFR{ zG6s4B654{ET3h*?lF=6Q)UlNhE37T(spIVZPfd&B|N3$W>ui%~LVMCv$5(!XU_%0b zC8-U41)-R28PD~;hWCUy+cKWBE#tX&e~Ak80^0zJHG21d8yXAT`5VI}gF}Gzr z5p5ZN&*BAYy!3{hiI;X;#$&c+JoY^{Gd>+{8BfgF3V%yX_rsSBdyS=0`u0Z%2ho;s zg}uVj=?4iHk4{T#VO6wcTuAZgGy_fR(P<$iRneAlA;qK9Ldv{w59K`mL{iQS)@zc& zY3YTqX_siX_>*vI#2#4KEiNR|PHxDaSWe7N3B>G_KW*AcAm7PeWhLV~0#tY?~Wt^y-vkeJc+2$A$cV(MvNYa&U4?{v%wt0qR zTygd^Bp3Wzna($)G#I6_?PW+l7^f=iZAe9sz7b>}L#l#%u*;GKhSUTvNNk}YwL!_B zKo%KN@0E>!wY6lM_In2}D4$Pi)QVp4juQB{A+=Qpaf0G23l9j^Jq_bKL#73%OKsb$ z)l!SwtzLpy%s19C?N%KCmU7rR-k@Vt?g4&{lvTa!35?1%_^sH7oMU!=AZF(WV($Dv zwVfX@k&AyJ5j#H+bLR)bwNM7z`2j8h49`kxc{zz*e=-?iy|m5U5AG zTevwuusPUr|h>EFx0f)akukEJOsw2FHP9U&;?B525A zGe1LAswh7lAt-&he1v#o_^|}$75H(>S;pWc9>b_gzbaMDYafIl<DiceGEA@L--Ix|h<`)Zr5~Wfc*mzNMdX!J z(rJ3a0jH(^Oy)~YOIN~Mepl$B6gU zY3Z5#^Z4ZMiTqFINB1Rj8$&r&tnxE%syt=CCBb<4PP&3RXpd<5=$OLPRMw#zr=yyd z4I=r5@_DaHawN4X-!mo=FSy}DkokrL!Rtz6ub9*l4_GgIY@HU8(362zzK@9|gFlmP z`GS~=5C+eRvoJOYq%_zl&LZPf1lNkQuW@R<>V3ehmzE#&9kQ{F!ej3fA@Hhg^YdiN zQ!%6>4byFY?y`{bOm0-|yCe~x+(*G`o^M=A{>(ik+?_PM*m_j$$F3np5bJ|ZW3k=& zjeBKlVAT5iT#sng3eVp!@8-V)*`wkgU>i*1fqK8c#QJ*}e5CZ3R;qfr;4>w=%=%Y_ z-BscL%z9CkSF6nL2296kuj@tRcW{I9NpSnK*VOd}2#40mDxJ4^Xir)p-NjFSfsFMD zuVXU>9^{v*OgeoS*P0-{vwp0YjlUs{s>LZaR&VjG)jCGIVl z+D$L3#c%C|hT4y%6iTCwyf5=Imn7BH8zruJIs3)~WKR6*Y( z&f7prO>|3qxH@ytlf8e?Mo3suWAg^nFt^7u-R^)=ejPu}$g~H_F9#V*U=&a?4dI6% zux{7J5*}6({OhduCQ*Plnih()F@iHRyut|9=6Hu4QdX#R zSHyQx=_>w1D_s%aTYB}HCSpJHEY4h9((bM3l{`;a9p}aC6?;#LHVa5CH{lVAxf1*^ z(Qd$?_l$QI?KJR{L<=yT`Hr?3{6e7lPsE)cA8-2E;5C0vw7r~2up!?3PeUVam{Jek zJ6<~j)jvh#M*zI~3*y!tz5sg<7-=tL7sk_SAzaH#R(gx#H7b0^UYsiil541wEb)F8 z`RLRii$?t!dc4wh*vfNZ%SMvFBT!A?4JRkxPV!D@xAK@1xTmXNRj6l2_cBiWha!IG z0>1)&Y(v~$&Pw3N4j#0r&V9`5$8& z79%&uJ}iz=#4^dyE2$uY?Akr|(IYgh)^A6-SHw(9C~6wo@;9yKk;dBiidci%xIgOZ z378#U5gV#@+6{aP(0&Ecr>p-S3-)s$(~Ab$601@wkAOcUnwsOPn6<|H;4g^wdu;9M zSW3@Y6MEy;0y6Eej%#A+S(M`!;H!ZALEhF_l?I>nV5b3{PNd7|-fG(Y^H_y4zX9?V zAk&9_`9&phjZCEZBm~K&_$vLxp)0iqtlX zNkc47I^w6*Xp)*LIdiYbqs9|@fv+Z-;P|dpBELog3G2I=)!wv5_QiJUoYQ`$ScX?{ zmYoKhg*(Q?a;%tQkzpZ0$X=*XzW#Vxv$oipRo0s4=cCrFjdf6Keu7Hg1!y@=T}gQz z`Y_f2*1ol|DQe$6z;^~R6Z?>EtX_Tic<|$Z&JQ#3wvXAw5^PwU@z8lgtXk2|hkXXn z>DM&TJaVS>hR15udQU=r7_iEzP$L1?3a<0Gx@|2OJiLNCeGL`du@%)8M_7F6)5Vmk z+oorYH=?Liuj!2&c_9)MZ2dPR>TkNDJkribK`&|N-<0re0PTDfjFon}^`$yM>OQLZ zQ7~I|84W%H=%Gc{1XLj;m zG~9kUr1q-ysg(3Mz{Y_Sf{I{s_=n%coNUTZUj0owa53c_u@ztRFsZpvQ&PDiD7=qt8DFv85EM{Bej~;Wh*1 z_kfHfFjUCRAae=K5ONjBFA1y$dMSSI7onU9b_Ou&O%VODm&E(L0`6N7&V#cNFm1|! z-h|U?M6O|0X^z!K=%V(l4GV**x?i!8vK06SjU-#`Xk@ch6VObo4RfOrNl`D{A?ejjF6LXdti`{*z-K2Vos7A~ z_&;HqsyoA(vYr!w6m2seDI`?+G1bI|8OhGHcKym5+4~V_0M_4Jz~6Lu6}EK{IN(DF-YAA-Ll+Mt_7+v`|pnf{!$0jPi*)V**O2%5vwRi?Tc# z{BY6!eUoS{O6OYe%K(PAT>_h~UIcp%C|W`_Vy%{7s#U9_a3BA)yLcm1o;_coumdQ6 zVLOOAffaN>&_xCPgk;}ynGFhTzRV7wIKWPdgvELpo#q`HWYn1&VKe}i33HiwhFw`Z&86N^x$x%zn3&wp(FcO`ae^`eGc-j@~yI?`z-g~ z^lj#4o%j#LRV`(~BA@^MrjF!miuL`jO0ypY>H(ybp6?G*dNaVMiDpkN{#2D?3HV|l z^Ud`<`ncSV0be89$42X}oGt}FPqfEpu_kwNe+PdMpivTz(marH0mvM}Si@CWin#!M zo@fbZY3FhHCHN7deM=LkeS7LWAN(xQnlb3K-&2nncYxmrbQ(RFT2MvPdk5e2{xOV~ z0A~VHe08M!)orFPZ;Y;p@*nW$vL2g@zWhxR9ea@HKV)q?Y7nnmfL{BP$2hgC|G1?; z7vfAHc`Pv%XH{$RC6_^S%K`=&oJn5G160qy%J0KMvWI1(jz6Akt}^%b!KAbVsBA$% z1Bo|5Pe-~l6}hwNU-IGix*D&h`S5qX#rg234ndT^+Z%TD;pf~P4Pv&L)e8A5T^TWs2R-!NGhmRjyNfS9geEhh|yA+n& zJ$}6T=kw+eP7EGKSXW2Y$*N_$hPXr_6z$ zG6#Oj9QY}7;HTO+@KcLRzoxv^&Ve89Rl(>JHwS*)9Qbi_;K$8@A8+Hp50}T@QMprr zS~1)(g?L?@13zvK{J1&ryR>!Shg)Keh~>T*v zL+LoVgq3pOhmRWK9Qff=A#R??fge6=NJ*s}_~A>H;y4F>_=<7Lyv%HJh-#T0(ttnq z|G?Fy30+;99ua#?wKAuCrsXM;Hm7`Md|qXD&hE?vLxM`2@|lSic24=sBtx82J~P=6 z=akP(F~m9LGgA$5PWj9aZdTn3`1(X{E3YG4Vjr| zGc>qz&N5C^&e?`Ir+j9PAJEv}MNK7&(U2^>=;r+fydys&e)uAccUgHvA0 z>ME!FWO7;2D}nX=_-fj&a>+~J;>i*)hkV>Q8qZ@sM zG$l2O;E=zZJi8>L8+{sijOme#ZuEH_&Vc08XYkzTTX!2$C5L<#hrFzLSTefOryr3< zB%>>R)ZfM?HJ{^<7cwpxUFkCxv6d=1=W_})$@${5H7sTc0j{?*RTS`q*G@Cc zZUr2Fldkj0a-EOrmG5~gKe_3Df^P$1Zbps5UN8aYM{c(o%@y$=jZ|)CjZzMS>%^ID zNIE!mGsxT;HB6>*^$|h0IS^ zv2GLloz|FIG}_9Fane_n|IX!b%cVLUsXxw*5PYYx*VlYLn9)KN0&zd+*YD@|Fo)7DY3Ui9dpC zn_;N&U7_d;ucPIRbkp-@TIlUSrsw0I>9yQzl5TrRe?w(`_Nl73gBcc9yS*JOR=f3H zxu3T!P#mwFY^$75)Ww^6ljg(0P$*?;)rW(gYSl6ytB0)C^qQVV=B8k;g3L`pSCe5A z59EPPW*HGK3f4+SIbResC}&IaqF|T}1bsfg6lYuTH5FVyvi_zphl@+nCkEw`eu)-( zUaiyz&6cP*rv$Z%`XR*kfo7GV>0ZoWCnU}cvf*+FU%~kT2$z5aL#QB7ItejZcWdKH z#k2h>s#5(KlzpTL``< z&|`I8iSgG&=@tcBsa|*zv^6kS0^x5!&LD6K&{0BtH$nLw*o8pfD?x4|a6N!!DJ6aJ z+w;GR-bSc}xeaVY|A9odP}q=%<3= zYWC_@EHcp(b-4jif!G2?#5sJ+qcr45569-wtCmMw)!jh9l$tQy#6fJDg`n@Y9^_MGvNFakyn7Q1>^$)?*TN0 z8+)W_OK!)%;txb|^0$<;=*f}D~Z9MLRU+g)f$NPKFmxEX*((IRt6E7LS9 zrt(`wQF~rMFY0b>DpRrXvAf?a{n_}~-QP)rTyJ%vo+dUSAco(|>BO5jR`vhfw?UNj z76bk!m3F{E%Xn2}DJ@28^MUsJJ%b;3gc{;x(6vB?P1k1rTR|@q>1%ZUm64tXeH^f= zDAA#SQS~;DPB?-G5T4WM^r>UD*(jIgrE8*lYnS1(olnuJdUtbQk0S*{1&3RtViY95X9bX|2d zy-1~WCZ=|Bds+u#rt8ShU+Le8Vwx2T!{f#ya5Dy0L>ahB^p#A`b3bhp>sDl(1e0v~DfG zfq)I2_?-70$0g5zr?U`p%e{DQ!7VrEHs_X0(wh2vpl9GE+ib1PI=5W1&DPqibIWC& zTMi!tgT=@?IdrnlEthp}x#U-ng5B%1XwEvfT-LeevOBot;K?nQjJDHmlz72Kmu&O3 zqNLtjMPDmQ%0l2(uP&byY{>qX`NfA3vOYI|&I zdF&4s&%A4?4JAw^oqp_H>lAs{lG+}d+7f%4IHkj0c}CZ zpHg#)hJ$ZV_8P~+A@*4cbRm~$II`}1I5lFMOEis3R7j+v%#bFThV7C4|MXR%q+D~E z5wWL8yVP8B*%o~+$Xs68@p*d=w*9i%35EoDTyxop7Iv<=>?A{+Yc4z45a*i9PBFx} z=CV@_ajv=SG(((gF1xcK&NY{vZb(I5b5?d2L#k}QY<7krHD0N?=CU)-ixJ~!c-%Wh+Aa;~}TCpCRgyK~KD|7}QZ9@kv< zD+@c&N(6D!pJ!{2{E@@HivUgtO?<3$D4ER zTM9JEOKPJmcWti#%dFw2y#`R#DW)MMX6i|5qbzrApDUq@3PLwYNPH(L)XV&tNJ(v! z<*x1fp=2K6$I_GnTE)F&bl3L#68eOn5h_rWpPX~twVkB&nJhn+fb`@Nu$*NEUZXTA zU3An;#OL8vMOE7HgxB~w_}l`{$|&-e9R{i3FKed46gu*kNw_q+Sv$?#97H#3D`B3a zujCnW*O(ALh;G(ay9D{@W^EyK+2atKW1hHV5Z$b;IAQR|58>=%38aJQW^KjE5CkJlU7LxaBj#8PTo3#&8nWCGut#N|rW^Ex1`d1-(M6IO4Ai7yw>F0vzW^EaA zK8SAC7E zSKSUW-b}Q?K6F+#!K|&(9GGPj4e97*jv|!~@3M@UtkkCJ`$zG8i0j3N@JsuAK&qj? ze-D;;K`)UGFze#%))gR2Or`PsQa(@QFLnC$I#(dKvV#i9<+-E1rp~>{;D}OHI}wYw zcuiH0BGKe0)dWjP*%|C6Fs~}QFjvB7h-E*rDofpdyo_ers>n^LZgHI?HPbsG&E1|| z9$W4%k9|^nOJu!LvYcw=U(B4H68UZMH4S>BnkgDbQj`A?$-10=ysE!Zhfc1@wLJ5+ zDRQm+p%v3pD)L~lK2sjTyjpF%tz2xZoy9V0mpv{e=Z&ewq9|7@npYKhPozZGbhIq9$5c*B2xQytIT-Ihacr`n&x;`mIUyGHCDGVHs+ZWcuyW4!wR zKf(S1q~4-rT$`bI-+}*2v<=Wc3@Vgr_fb6l0V&z*M~=1>d{3bIux0yu9|vU(l;OAF z7fJ5%PuPSJm?>Wmz6GfK1#v$K%B0Qe!ZTEZChm2aH|wZFz1 z!9D(CMql~0qF;?F&j6}ddf)hFApJ)3kOrhKLFwQ6W*{@crvTLlEnmsSAvVyR0KP_Y zFCq86-(DVo>%p%TO_yE%$4$p~f!_w$2TQnKLlMuxS6Fk9f`~wt!y(^mvG}T&JrqP5S6Z;A@LFJM zDdUKS;oX9)it!0iJ_5X6@9`X}4;~qJKgazZ&ez8M3T{goT<$>i4i4%yjP@Aodrg4F zIMl_M1U>=Ktm~=uZzf6CB6`w3l1pufP|N+m}GuM)4KFT~xc$F4v{ zGsr#!_5%7ysB9#ZpMxy{EJF?D=eP`Uq8MokGS{^&Lu@VEfQr)h7NxCVd!j29>_|K! z?w%pLufF%L##QNVCF6O)AMs~Ytb%wJS)T$_90-yd$7N7L7JwWLayZaOG0N6KxeM$n zpzKT#?PTIJnO@oXAoB@K5V9HMUIJT$Tno~FJUcjnvfDux6IdYR0g#mhmJ4|X}vh}Tb@eZD_g)?Rldy=lI`r-qC=b-elh{*tRy z=il3P{>nc=-`lru%~zgl;l3IanpSxGxS^#|!@>eLEHvq9dx0AcD%Ir|x-MU-VP}yW zb}H5F_jTRg8#kUL`EH%>%Vw=`WBdVDxQpP7@uw^7_5GZZ*7yp`2J4hujo(kxT%AUn z8h}pozHwP&0F1%5n2sC#fjW@?gb_M96K*LII zvsQkmf}9AHJdVt^29YiXy+9-taa&iB?f|_-q%o4}BhoXVkBRgbq~5bp?laK$Mfy;r zTIE-TcfA5AIi6CzZ&IB>I{?nZ;GoA#<=_)>lS&BK)4Bw~yP znpLRHGeuenx(u)qTwxRY)u6u`3C~E};_YIEiNn$ijW< zVzylvOJ9PaHCVkdif0bI#A`5=e!n8aOKgLt^e42^%D;qG=nB@QwA^{I)5%D z8em$yhd4C#3D(q8slj-_+Vuo$>Ysrw1ST9tlp3NmXeIM&g=ZaNcp=hv$b40Zl%LE<2b8ZN zf^>+I6S2Ws?|9`0L(}3Hnm?4n=l~T?cr8`6;c-CWJ_GL<(w2iYeX#sc$K@i;CTI|5^;{#if;&KJ#xsF@zb^7czsyn zk>geSAq$Sz*A>?F1c`O#b1nE^KZ4#dF-Y8@e<2~~e$ANsHDm7AjJaPk=6=n*ekC(m zX4n=sH)hQJnlbll#@w$NbH8TH{hBfNYsTEK8FRm8%>A0#(f!&$mIaq+3%#)55>>e9 z5~X3I4TrcywI4Ywi(H~YiY`&DoQf_{AthyzOH@eFB`T!M%RVYvK5*1Q(i3%yYM1>SxqC$!;Q6WW_sF0#dR7lY!Dx~NV6;gDG3Mslo zg%n+)LRwv-H>e8Qt%yrhtypx43aKq~E>VSxE>R&xm#A9G?N*daR4lh!Q7%zo=XkXR zm#CE0dWAr4MeBucQ8Kf#5xkXoj)TSf1=mj7R>BucAq$wS_Mb$~W zq$9WJKjHL9M{dysdLEFD+@eyt+p{RQsIXz_$SrD)#B}5qRWBWzj@+U`#-$^-=yuX} zdluyu6>CEJwd2h#dNZs^UWGJM@QwC?lpV-VokllRET*v~CVhGZ-{>p}%_|5UE+O%q zq);z=2$2fD(RC6(xgahrw2BvfqraEX)%^5OsiOQM-{?K!J;09@O3HExSkAHruR-dR zLONVZfR&BvshS&}@ESDym+>ea@oNvhg2uekuTi;chY~w?jYA4v(}@TdyrwNAMs*^u zX-_x>uj#9jioB-EvgkDxQuLat*@CjjYbvDZH5F3ynkr7wYbvDZHI-PVEb^MFWJRy3 zki1v1yUG-KO~5fsrC;=#%Fc^kQz2DeR`u)|c}?FWT>Tm< zv&#a?h9^%ZsrYuaK>RHp0Q~p@X3`-3JmFZp9rSqoZ~P{_QrjV#pZ=OkXq|6Hjl!Po z5Y6vaqshYU5Y5jtXM)=ynxAcm+aa2tTjSKB9isVp#>rt{q*L9sP^$95rD+~!fEPr$|P6L9fQe$S4;_=;;d z@e{XCz}2`Bvn2B2O#wGo)gMXyv6KQxMM(z^_T{+-d?*KC|=pD)am}z1@{cY-aMM9e7^5PPA^jT`T_e19Cg0YcH<|vu#uI>YcAyS$8UOT+OEv zp?s%G+0B?D%Q{eA{f+(g}8yAp(n2`GWkVSvheld zE3K#%Fb}}8Yb9`7pJN8oP*cCUWVxJ|Q_Q`jm7pb2L{ zS5Pc_pn2FFxFRQbRJq-e^=!qX5-v|3cJy%Rd?j`ZKyU?aiU#}O&t=Ot&X-C z{CA@LV;dg1SO+!jgWz`oIr;Jrk5#DjpM!r0^qs8%ZF#KJ7UCP0G|uB0ZYu)0W^DMF zSXK#io5qeEAom%xV;$`<@FhUv5wxQ2-GfNdtNFmCy2NX64y6Sq8V84WPA+skOD8^s zrQ1mNE3jsYl{nH{<287R|3*n3)iz0glGnb=16(OfUhU@*kX5%oFbb4kK|o!j*tGV{ zo_GxMHoD;xZIg=bh%iT4zxabJ+;lit_eMl}pN!*WH5FEJ@wvCq+W#mdJE3EL(=+%g z=>ZF4O=|yhP{VHkYyX9@p=#@Ez^??X{TIe&h;}ddpCzaEUlglVyS@nioY83iMX^qz zeFpv^VC}!JldIU7Q2R;)hpIgw+|E3BvO_bq!{4A_|sA*$_8hsV-0HYm85zYVA>cO8>rk)2R|7wZ48Y~6YUc4O_Gx~hQ+E>%Ui&2G#c6%7HhPc zgFgb8HikR7Pr5 z?kwu~7-xIIN03h+Af*kukNKAWA>jJ~Hj+Hy*J|Z=7WjJ6RL&>eBhYo=my7l&s(i{l zY`hHql4w1lJ?&`kfxj!-M2hpQZ)bbI1^-O69CFY5)tW>*&cLY&H15RcbOG+KoKDvC z4a`5#2SzWzYup*`E#lrs)B}SKs!$7@(c+>$zN*Fu(YpK5YcHC{5o2ol{FvyiLx@JP zLbM=qO0J4%8f+RPnvHq!4U6?oupmF^2l7WCKh@D%J@ofc!UaDhs*uZn5L<#LM}oTA z)Uwe6!d+u9t2If*zV-*PwFtTQ2Q;l&UMbS#@GHKK(L(3z9ay@nrI=+2Ws!Wb99on0 zG-5QZ#@B`gRcHxU@U7aE>kn$x(Y#_LN7KSee^;UneqXcQpU&&6MSQQurhGufKtl0?%)=!8PgpuYQ{iuF1&%>U^$# zn+>i>=W|UupR4~B=|vk{lg{UwbUxRl^SL&;bLa3nQj?_fvo^(~pDg1O- zsiOSk8_T?0zEHgV`LP6~DwlxeEIaU0m-8ciWHu6DZJ>Ip;)W;K_yK-R0q0c3Dr(n1 z5epCY^YzCO9>C5r!aekWpFNcgPRc~>(9`RsZ;R)arqm}t64^Ru`yPMB)8;>ii2l|C z9O+2&mM z0N}t+!$F6wVW(TDggLjFUAf$A_R~tGc~@TL1KItSv#%_zr=$Zx7m2iT>7ia{*VgO7 z&lK%2uZyEx0(QPA2k}sC_V66oqoSzWvsFw5O76yn5@^g`xC$89Eii?E)8$tb$aEWc z?aR2P#ze$=HNqR$ph9g$3RSGIwnbA!sLzdkgIzo|BbCJ$KdZKzk19Y{VifV^5_LoYF(1bq;wUbElN zy|Ycb+d=;Yl>g>M&pXEyF=lt3JAvv0yp5qOW-Z8S5z|!BKR4Zhq=F6etCuhL&dc-# zxg6#NfN4iIW3~CKtBtD$rmNA~%tukI8Zj?k2C=MxbdOd@e>H%==|p5ym!s=cmnTX5 zQJ|j+?yoIXQo)8*mW`Cssx+u1_&b!dP{yynVSvBs9TLoIG+WrHoZca|H-Pf}db44{ zR1uqr^@%i`;w&~&KS;d*%SaWAG9nAPghmyz7-d5;2F1`h__i!WZZfp6r4e=qW;hDjRdL*UBHm^_k#XyZj9X7++-?m*=|_cVifeI^ zSZjCJ#H07Ne}oa&;vzaQ6K``?rd{-|_9Dua`2Xi3ns}R|GC5mdq;#i{=W9OY_=>`w zuLVZo_=>LuM&bBMN%XEZPl+?WRv3ljE52Uu6ppWyv^~D!Yl%@jzLLI@sJZbcqLpy) zPRcoYSF5+j5Tkds&2Y-aZq~|4?`nm#i{8v`A)FXU?q1?E*nZ;Kf*`mWLu58g^6<4Lo^Y4DS7_PkL@s_i^ zi+9P)AnSPHE*T+VDGN`%mlaaHOGfdFcgciI0>!&zhJzIElHp;z^)4A9#k*u!W3=8S za~YiCT{7DGQM^k=y>m#ZR-VPEBAfrgO4)Dw@6t5iWw*YRUQgCr!rlN9Qur%Hp-ag~V@ zpH>i;0$RnrxR#x{7xM>7=um#Ts6bJET6S_=@Ih0-zga~hiN(NNbm5%(B0)8y1U#%cb9wU?s5;^UGAZ~ z%RO{=xrgp9_ppYZcGhWODXDBeEp&Iehwd)-(B0)8K1N^q>a;Mr%ROgzxtESUl+10! zEFBY5`57fup4{F{u%)Flt`J-9g3_5W(Y+GALn)nQNYd}r0%x`zM#y=!?tXNoSnKXb zSFlb=j7!8OvZ${6BjJ`rYz*P9T43i-^_#Xq3uJEH-21rb)IrEvA&^!B&5Xe&e!Ob; zK2ExIH{QrHjAJj1D%|-9tug|ctXJ(`7)gFt5p6Q+{sl^^TAEx^pt!cq%imZzH6^pt z1t)FHuG+muQ!*D6IWF6gucEL%I5p5;33b&bc2KY3f=Xz-V1mFLZ0%ot3Lz$`^j}I!Qk7;@M z$+EXXRf}BcsCc1c?0FvRWuJi2#PaO+h_Olx?e34UXdmWfUx@fG75FgBj~DT`!T%c; z@Gr+t#B$h%*GokqcU}h|Za(j{j47?p4fNhc<(*|ZMV;Pbrc)Jy`z-xg9i+blsn-Ia zue9vX>L)F420sUAkY47PTHXMCRisWWygIb)qF;l42J|~txy&3dH{GpaE3|lxKi_UF7S@TL?KE69xP^6v7S@U0wJVKe8zt)%uF!7D#PHfPM0YFg3azxcPVu)! zvXyp4SCMwD#b(JdaW8tU(1JIydmUv}A?hJDxaD?5ojBX-RmNT74Q{1e|4*>|JN#5= zshzBzZXG!CX-E-$11F~cd|>>28FvT+^3S-vvZZ7sh$=TJc8N7PlLV7dyIFVxb(m_6-yaq~(&+O1L_9W)hda^mLY4fSPdu;j) zxwTEHlUYhM&4+Sy(+P+i)$}i7MtCrZ?dp=~cW&DyebpEx$(sMsxesbV29_$9rrZaLGt|Vo98RkZI|>ypcySED z=6wfvFEJgdO6$&}7yN^RnGD&@`wsM8E?r2lKDPk_OTSX0Hg3#K67p)vp>R4j?>or* zr$uhbb$cB8Yo&GMGPil(!QSf@oR^z<3iLND^8DQ04CLuIOG*&h+pALhD>Kt}+^bRs z%F*zISEaO+kKsJ+i@&yjcl0WbrWWb9Vz;1_-4>)jOhhDlu$m``2y%4 zTaEfj1D{y1fAebZv()KiJHVB+JHl4-4qinImrgMI&5bR6()?JSy)YIAp-tcnSRf*po z+N?$QC~7>@FR!I_ZV;(v`e$)rfW-d-GSE~J&mDX>$e>6sm);LD*cv03+x-EMA%>LX z`buo5A*H#xdqIYoV)MDKe+3zyxgHa$$kmf=W`rS?v+M2y8D+*DugZO>v`3eyI6ZpR zfQ&8C8n;K-YZ2vXv9iqwdkrIniKX-5%nW<2CGAN$4fONFUQbYj$yQLlAz_xR_*VPv zDMwH=Gnmd!Jz69i&P_}Es%TSU^UzMbD)hO%tPuO1z^h*kGJYhb%4TZBa4xW_Uy}9p zpmU|;zpLZd|5lP0pn;sBMd#RpO z+5gaC@svgl|0CZ_FiagF>|@{5TbgC>0?UyL?5vd7Oo;!*x&1tDE%KZz6O;7zEL-xOPY0gM#eBqPCHo)wb+VTL{ z*RBK1Om(LP{BNA(tkf51i#3MTXl|;Da{tcp=BG}j;r#FY(y8RWz}>$6AIDpq`qvV8 z|Mg4ugtuSnKBc+cm2*kzcBSG4R?bzaZYrlASPs7!FlV>fY`?aG9pjo?sax}wx#m`i zhSNJV(*3M}(>az&AF<#iTCDfZlsvaI2)Dye-SQxeWiCrE)u;;p%wa*QaX8q4fvG#5 znxrHSa#$jDzp#THmP~C`!4Gj*D%D-7{M=z-YLT!*9hP?0KP)JTvx3Zc^+!+!D{K{b zWUIY1q?Ug;26*T)Uk2@^KQ61v;X5Wt&FO7wl zgE;ZBnAOHhjbKT^(#|kHHT4Uya)$+}tdgp5Sj?+mNbG98EiGwIYY2G=Jgz{zn|{$|D;-U&sl%0RUrn>va=o;}=FH`4kg zy_1q0DM`h5KbB$jL^AY8WfW~M@$IKgBC>!!w_Z%C)~*uY$|@nR`YrTZdbAbd0rb3YV8N0fDWJ=eL1E+KgnGW(3AkG_k3ndxpA5avqno1xp z8c#xGUad#JlE##Hr%BRMX-%s78!D2SVP(5P{2%DVl5^U7n(Q+3O;TGUekkdx`maAD zG}pBE)sKa|>gQm_8x9@&=}e}uoekXBqFj*`bIj2>D_I$B#iT;#V=pe}Im z$7ED;Z5@l-kM$Cf;#Q;l*Kpm6pJlzP*}DsZm`zso7M2tZ8}v zJ`8@MH?~uk?xJwhY#srD^s^_BP`W}XC%o`7!`5ADZ%YA?!#t-+79u3t3-0 zt?rX3(`dlz{!M6gKNx(8XsY`+;TWZM8u$r-)&1Mh8e$9hC4lAs`fSTzJ6zc4Qmjy7 z;N||TF6H+OhReF3=0;lmmDWO?X@$Bz9~J7Au(ulI84`U6NF2i`@k%&Sd~YsqJ4O2y zL(MDU3@N%3v_`-R^{Ok>Snwf$HOOnBHORr>OC)y$z3iRPX4(G%KN%=}c^4Ar&+jpk zw^m`|0W=i*7sPAeUIoP70lAI9%|L4dZquw{j*zzXZQFni6uY>A$QruXf@7=&-Icy_ zqL^8z2?s=R)B?pBfhwR?K4?Jx z-Y|VaLB1Jw$AWx+0=*?~&99Dn4RS@xEcVq_?VI4|*u*1|pu06hV^9#bxO8MPAGT#j z-`|UEpnWX?tq-<42{!IoqswNC8FQDl#=?+W>AwytxeDTj93?iiN&bRdgdf5 zGeNae&zwzQH`T7SC({YNEn(s}1^J)BURsbpg1`#NTNzc08<10>elQddaS|%>Tam<% zhhq1|rs7a+X{v)2wm=s8_B(@_%cZ%dp>9$j{*d7ZUE4E>N z>xT0nY-+8`aXSb^pC@Zg<71pX*ZpKM^zkstaU`1#C@N#M<#}&+dVgDae>b(6?RRf2 zv`k9dAAh29e65d9d(BN2`gJkYo^9oW@G$HB2p2{vDQsq2nO22OabjjrDqu0&AXMqN zFWr*yYT7f|oY6XjP!EQXFGaOX;il${Jk<9qRLU7nktg7Xw~VNbR>UMJykQER)n@}8$w!r02`Jo!XX-37lF?c zO~Z0UxU0t3Gr`x1rXjc@+*@+@gWm(#I9w5~bmOqseoq>+B3$Rj;dpzsRz-NBST(Vxbg0K*4k6~eYFG^#PjzeZ`A<}vRXDCu}+6Xq2!SFDBdO`kj*q0XM zuOsjWlP^}{dgKoX)3-@pOP;%6-ywMotd9_QXb1W5UgVdA>GulqFTj4jApbUjH+PUP zdjk2TVY;p^O8?)m|5cFp_QDW%kgs_O`DI~x=Yo7GB00dy)1E*b;6^5m56h7&cK+7! zfo~qjR*OT;`EA95@D%JhvDyo_*SC?=5cY6exz^<9+;ifqy#f7p7{e6d>;FAMkly|y z@gDU*SzM(b%bZrZgS_UY8BRX7;lpEX;m00l-6HnZv2EtpeVq*Rt5sK%)md$``KdY9 z9q4JRp__MzGD#iY2GKT3d|?L>hG4GoZ=*kr!~bb3;>Hb|Q;UruyKC3pDZ!3CurhV! zR&_@?PHffIJk^bFc zxvd~_$#JG{9qQ7nQq!zv&i9>wtyNneae@$SFv)E@wlH z^o$F)q;R{dr4?GW6w8(##V!zpe7Bj;Qx?|-+!3ay>xVDklfJFR zTxG?)voV?rzDRY`eDfQ!J`E^aekj5t#r_lM^+2L#lM;iO9l<;OK^TFl;tt-oouo_c|_d7%b+5vF)18jggoWP-g)3mx`2XZYA zP-=3mpZ8F=8KS9My+cRqR=bgYhi7<~$k#J@A>K9-*CyrrP`W|~mdug=4`eR--({@r zl}@p+JLco%HL=!wjG;Z!+TOQHznlIq(%u8gsw#Q=KJkX86LcUobkj}FIZ0?T5(EJg zCKL>)C}M+IK~xk)#T;4@kui^B&I;z7vm@p>jtOzcnw4i;Eit!q5*peDIEira3kbSH3v)|t<@kXa3pQ@r$d}m-3{sOD^(EO( zL2Jb!w%aTP}!r6*8=HICk&)6@t-ziuHK9KOngm>Z1-h*~N@qs60j zC|dt3(W$=l9gk2I&S_&f8xO?&PL;HEl_x_V2Uu#y zxYYg?`f9*ZJIH7AWzONNhEdcBLI)QWm zyu$4@$KdjJ8N`|OUr&ZtnujHfQ|l*VRgL%A+5r>QRauZ^V| zDzf#BTL`|sO+lLo%|lld-0XV%92>ea)JlJy*D? ziCL>iPRm(qWa9P+3dROtZ z;ai@ZEZ#BDOMqB@mnU}y*LfVJ}GF2al6V#_NZN6&O^oLgEf43&;@8ie&s*T(i#=vm@?6ewD-&s?Op(=N+T&|d=9GhG+k zbi3yqx*H(cRXkTh*8_P+9OErd*jT+0@&TalvxuGV%=8`fi03`%@J>yh;N{7Ly;Z`uUu_rB zT|Lz`v&Vi*+)UZ~G5VW;bRK%|#kTKWxDU|)ZBIqv_bxUE*bp~U+4g|l0cdkRL2Tw9 z;BAb{WoHkVy8>1umr&+kq1RB?Srh9_=7dt38UNVP%=B1~A>I_foVcs#55cnEuf4W*D7TP!yD^V~M% zD!1_GoBt+Z<*B%~F6|=p<<3a9S(P!ZfCb8!T3Y6Z32T{WlPPCpGe&Ps%s`;QkY#lL zKUdPsVc-3!qtht5COvu1K94cPOEy;*$LF~=I}DQrs&E)ROM6!AgtuE%N zMNO@mb7luf>z3CVyFpju%0+90AF{f;YQ`fAQnXCii;R@-8oCMEwb67doJ-}qA#TwN zPjl0)SWK_5Om{B-8ITo;_%39^?%+4#^YuVj1#vgXoj@B&r3Q0*1ZpGDZ!CnBz%2!aPtAm+b^z%Or#q0E z4KW2|JYZ>3c^!jJm(4X zz74mU^kni=mOtAfZq*fb(`NW%wqewD%-NSW#%$ZBT1qWB+u+I;t+H|BJ>dTk%k0>u zcc98_Dc1B(szY{psPJpH2=BW^_zi?Vu~m3oBmMiw^XgCI@HoG?*0UOAPm21vLXub+ z!(T2@asJrGVi|8&OyPak#$vX|}Uh+pbmXGs)`z?tm#mWa5 z{!BNm-a<#NT)mYJFVm{b$N14eb^~Zbu7cm#1TJeb)3D+j_Q*p*ICo!L9ba7*e zY=zL0Xk%mJxs{34-Yu6fUu;t_weaBwS zV~;Zjj8BDQ^YbfXn_1gz|H`=bADC{gS3|Fir_kei%{AMwxUDiSa`tVNadF0e&*O;rtQa%iSirAW_i1Z{v*O;0X%RixK>+K4MF@^oj2A+m z>v)I2o30pcfW8K>HNsi(UgB+lz8|nP!r3nN*Pve#Pq}iA^WtmhF9GW*^`h!&I6*aR zco9Hd*maJXSxj&u6ODn=c3N6(JmCa5T5qwowA{N#R=WSS(+rlx*1x%(ZTmABujU7` zWbasY&$4{)xQjBPNfBAQcRWIq{w8-)M0>|Os7Nhq_sJC9NJ?vN+-wN^_9chyzrQyx zZYrVnmgxt$xqU(NyV)Rfb9%yNkG+W0j)@a~y`t3Xgk$0k+G=dlnkmMZxSzHY3$$(< z>(((|&AAA5h&NNvl5h;M-c(>(48)!bU&1r6ic@rRqJ@pu8BcKk*CLfs&s9^@DCCXJ!B0CkxPT96r zpy6sKFjGAw_3eK#osqPP^1rOrbRxZ9MLUv}RyV$ix?A1Yne6&18mKHR(CHuljBF)X zqLtX!4)0Oa(`_;mJMTwht-xjH!;Eg_KGcMlqkKi+zmv7_a?~Ri z`^(WF1)7DIqj5P4uQc-HwXC(%NyU?q+oiHgs>_y1D{d_M1TC0b8 zAet>*9-P=x{lUnV>YWI#0TS{k(|j|pcqDmUrBD05JPw}`3+>mzF_Kce;pU`^!>QgJuEOm3`pQ+WNMw}rQ%zCY)}?FF}% znD_dQ$+QN&R{dp8+iB>1>_0LZd7p=Fkv|4AUg4{?(&lQ9(^p3EQ}`XW8^!C4`}2we z5SBr70_h+k4KWC$kBHxESqyZ#ncdPYhYatSW?vW zuO~*02X&9~L%;52`+ln)lTm5N2+brI7mBS`u>a(B%x)H&Iccno%74P*nCynJb&?9$ z-5Zt_4*TKKRZ)J!GDi${T3TGhd#t807SgX*QCP!R9@*Q#f5Y+X0jtd?yW0FL^pn8u zvY=-P+o=|vnl1K)_Oj24Y_Zo_v7hFO{S(yQ19HWFGx0T~_IOJz2lf29grCg`HY!Yx z1lzz{(xLSv^5$+|iMVA%rd9kL+WeyU0A771R;%qlhocpK5WIZ>Yso){JKhQJJm?ib zdgbH1$?EF(6VMNdcPPEg?vD3Q=uZGk*};)Ll;BjQD?w1jK5wNV$s{1K~8?r{5j?9)_7t(ldNIU#4$i>rw zcq)gx{h`Rlt52}{4q(+wJ6AcYHq~c!;}veeU0wc0#+4JI{OQo)kK8)X_r3N&_yxpp zkRc-8g_r{}UBpWee+9V;Xe0fUwimvJ+644p3GoWtn{g_22E^cl*r)|k7eOoqsS~jd z;%Sga0dJ22C|%{i^HOXE<0FDTP;mcBs86w3Ow_6N5I@7-45WHPv^bcjQ9x=ti2fjb zMNEJg12P=&hR=ffLB8$=vJBRVlGzX99FUbF4u`k{Ufju_ZB`!b-Q5Wb?kD4)za;y>?=3`ixWcIDD-+M zI|`b@nH_e$6TD>pJa0~Duiq8?`aaDiESGhg_#GUUs)P4>sbmX2-oSb=?0KIl)$Q*c z8#e7oplO}hNNZ_EtG#KQ?KDj4yhc*zXQaGheKl9CFVl+kRayD(7qglTbHn(qMB&%J zP@Czk%EHbX#=}E=?^g<_Xg-dVg#+YBS9n!`HU6@2lw98hdYX6|>dL|yTELtPT?fQN zEv7v*=hz5+A7H&-d1zz#2heYcrwpwOtK>s!0dLd6vohCLJ7>bAR@ey6wv+3{Rnoaf z|C2{~-YrflGdXtBLo{qR*AtP=!9>H=S8onxDI2WbYz_{zMSzC+&A}4M6zIF_pWP>ZR&Ra} zDrDa)*4KWWZ-0o-_g%E`yxRf4z6Zmx&Bu=otWFLfOL_n{6FD}hmEGN;X989f#|Bg7 z!|~8Zi>IPEHrQRY>>}v1fwVrFygjhB<2}%Kh^K77E2vO>FG4>LwDlOwz8_70`ppKG zTY>FLzem7ZK*5RdPItVv`3OEK!R1u-GXi_4@Ebxu0XBI#FR;3uoxGeMShZ&+VtxGu zfz|D@LpjO@$UV4?T448#pz>%;=Z4sXn664_RK0|-Tu0F`!TIw@cV|w}RRYarRF^c5 z@y2FH^Z?ryep=9GTSI?C57mU6%0--gcCOFZ8kqKwP^XIPz;TLMUyF8L_$d8l(B?0i z7;t?I`1PW!_{IbyRebHqhPHqe-7_Dx|_~Z{mVviub5<0w- zTXYx=QK||^m5yUC8cr)9RRu8!q@RfH5K}=Wh!_lU5Xd|cV#&V2M;?5HSt@J7O#^3T6yRVw)*72R*< zsJ!0$9&vhN8)7f zz@|R!3$}Zd@4*5aN(vqzpvK|Uq>Z>uZ2lc@EAT=(`S2dy3ZK9q3z!(?oAD9q3y})1)5`9q3yJ(`0*7 zn%xo0P1YK|XadG;C_Biv&ZS`40{*|lePiD1I1HEU>mBX4P`_C470w^yTbEMMW&>SG z20!x^>aK5#nO=vXQV={sZ{}Nhz0 z?3L(9qZ?eDEVS#qJDqLxd+tiv@U|Y8X50LW#e_^>JKMKitslsouK;^7k;s6#2Q$-eCdNW|rs1Z{Mh?A!Yb)A4O0 zU^zC~AKizXI1ze*c*?QK{xtPDuR=cy(EA_Y?c^%Rzo5SZ3KNqR0UpdF$9D2dU!O>h z)xa!X#GCU#I258INVSNb5Fa%QMMK=XzZaOfz&a%QMMwhyxP&=&#?b>u(Hd~5ym z!(^*fiw6n48?b8eF339~R4u*$`AmeWQZ7Vw9=^2ul*tY`U^2)`von1djWYJNm~Qh zjJdUMGv<4t?^Kf8qV{`cHp7Qgm^<%My!C(MShETK zSK&LF*?edA1x!8%c;n99$io?ZyE8zO$UVDj5;EW@Z_lBY=yAJm;B9iflWD=bW`lQi z!FztenBdRKjX>q*h^AS4$(lcFpoW3J6VaQBZ2YbCFM)0HjgNX#14k*6YB{c}81U=$ zjBIax#>2EtpZ07<^BZYbYh=@PBjDHTNnrRotin372M9le=m*kG#Mcn}f=m~Y7|%lk zkhMUn8N{0)j{|esLezHAGrIm=K~JKF?lqOpu@}Vb#lANKNDYBF732gF;~;JY`KyQ> zA-)Cq5*V(L>^uyl7J@WeLO%v1 zA$|b)8tC^tL>E2CE!3X1uHY|Z)hkiiLRt9=X1gQ#^cQe$Yn(otpoTtOOTa%p_jhAr zHpr{ie!Q+j0KfjnY1rNaR&VTf1;PU%rhrTYQcEHB1KAtsq6eip=lnZx?!%}o#=rzQ z=bTcV>jW$36zj?zw|M@nnbqXR5^gB6M~r^v;j)r;(6(e;BruS#8__yExpGZ>otx#BcrH4*_Mo}r?N`gG<&Gl28}KrmXnkE#v(it*7@YsN+4Vg z@gT^ZKkt82!ILKKqMrw0Yn+W7q z+9}~Y68l;P6lV*R%K`JIJxDdsPY#UDMjS~`eeA3_ZISjuq=$4A>2@GPfNexhy4})3 zN56R0dhb~m8A}%E!EiVR))bV-%GxxD1t9Z*)BzADgPb7Z2#EC{Yk@BM<|X${hc}tp z)F~O)$(s7Ndl0z`u=koD19=2+C8`IYrz1!1*aJx`X6kx|CZJ~| z?`8xvS#<9fWna2q>>hKnE5g%}?21+$yoz8639Z&MZCzslzh0jUhJ9eYj$6;m&*2ci zfczw4dx)k-Glu}eogjLEbOBNeAV!0X5OFlbZXmk=UG$x{d8+iy$G)X+PUho4J+N5i zm^{C=PZDxT#J^k~{ME^19|F(G=7AM!<~dQL-J#6;z;PY_wpMMcb@Ik#fmf}E_PVHJ zBw0Beu7-6G-tG&8mqVNZvO>gl5LbfKi?{>g4v<@b)N>Hef;=wbEr@@Bd;xUX2$4(j z9y2pZ=G@?1a*lUQ=dtUN8$Kb_2zi+k-~&)4AoEPy)D?Q43r#Loj@85#J}=?wcs4U! zWzc>__T}ihwB-byXeK8nW{>@x*znIgqnV|6e)RLk?CGEFpJcotr<$?fpzF&;{858D z<+E6)f2Ln=-Vt_7&3ZDYg0^<2f3|j~e-`hV&*p?X{j;^7_y=;uI{h=xo&MR{9jo8k z9rjtQ!#?wdv^*23*6vvS*6x7M;(x))o7VC#3ULQ~wsr@67HfYX@AFo2V{(MO??H4V z9-sc{_9nL}ZFDczS)WbZS)aw)ZD``o`fT~70(Iz2llG-c!CU?+#?RcE^e$!Q<+aJD znYL`9o3P^63Yt-NyTr8rnZJiEVLLQF;~?IdXijFU04f|YPayPg(Siv^ z^bZF!LKIAPCvbYrlpYx_QAV?KqzH|v2#gtcZF-Bj2FaZom@UVFw-Li`#S7@I3#Np3 zAvMVJ3tMO}C+vjhg{=#vO3zJSQCMX}6s|zLu!9k)aD<3Xg(`&nuq(YsVfR8gRvdn@ z9KxMMS{jB58EBrj2xrLjc1Bc$`^iA9=~RVtiMeo`g|rVJCAEcBq zG-67)x2&CLI@80ClMu@-WL7v?AuB8ob`85Lo->TtBU~fmY}1(&Zm&qsGh$wNwBotQ zhy%k-61&WZL&9!~bd3=U!>6UQ&WO4&Pa)Tt>7&B2GH|`+^>Ja9GVz9{DyyYlvw0Ne zAka)*uyfA}Zwwd0?si;J^Zf`4FTik7YcuS%n}3*B)VXjm{K!=rp{Cu&Ya{Vuov>Nd zB^<+#)v61#0-@LDR54XG^v^q{#gl6ND^D9SIuzh&(qBZ)NzP8=XWWCE7jK6He*7Qu zF^Hc)E{yfZXi=>Haf##C;3VQR$k=3jACjr~0Pg8{Bso>-O+BtFvyZ0Di}%A+n1pCr z;gS-b*#)AT5m9(!XNW;Yq(W`1H63QTmmeJ@L6(o|0TA`{2@ zO{bkh#MTU(?qnifm?~#eYEQEigCWEJQ4#fWo6nXi}5MH_*baGOP}I-v0r9$Zcp%}$%enjUS=@v867FGq8-h{1 zt_^|l>)?s_vMMFK4|pn`$UPkohm+@Zt1W3hHjU2F&rp)BtS)%rCC@>$H6jW>c^0DD zh*VhlJj6gF^1~0GfEa2-aky9pMi@~VULXUbjc5_>C7tm`RD?YhGRcUl@B^9N!HD+Z zXc?GcMCb5R5jz{vJ-k_BvyJE-P7tw|5&gq|$b)^27##j0o&Aj%<`s{78tQ;h`7~%^ zR5E{jp69ijd!ScxP`OaAK!aGxA%#1O2(1m39B#^9WNoNqiBVBxZK&i}qf(Kzp^~LW zChGiz-=RVWm-lT2#rIMzx3vtVyjlssfu=6LyJp8dXujP-;iX6&BVz zDp;dX>_(#oM+JFG)?Y2YVNpTi1*kh*XAu=VBE5S}ax5LZ%2lbe2HJ#k zh^bZkXX%k%@wbZfzHmBX9R?AJYhS@B7a|jHdXj93Z-DK`D=EOh>lOuP+(?l1k-?ef z0zKXr2nMS{DYaB^GgaQ_KrGtGYxw~9kXbldCT^ZTr?zZg$_bPG5no1mQ562XTWfc=%%kJPqil62|o4AE8y3v0d zeWgGB6tBlx0;2h*KV(M|w`^;l{sS{Q(*#<(L(QkVe5vSP_@4aebFwn#|IZ%`bl9^n<_~C8SS5sIaxr^!by?5ipW%kuW-RN~WCMDu*Fs*h69ij3^8>PcIu-X!Gq*M^~2(%3DEVn}w}5 zLJT&-9bH{Ev`{WbrJ;_lE*n-LcRCm7=<2c&1$hM!sREr{T~=$}O-U6Dl#MZktq7Z* zD$wcGW!dAa3!ax7ubZOo`IO=`r7d7=OCsVkqGanC-HYQA{m}7VuleZ zulQH0KX0NB!gTK+WNoJsMdKcn_SEvNyfRHXyl3I2grr{4tp_)+=gd;yYyM(h(%Qj1@I5JyGrb-alRpFA~46vF8zPS0JcXi^Vz<{h7+irbv7#@l(u5E6Bq zU)58~#qxF*@i+xjb_E zV3%opbFAAgV4xkVfc?(FOyLyNjk-mUtKw`b{Xk?dVymx?s%+^Z^QZ4}TPyq`V!wGX zzVKfVgSrk~k9W zay9z$pTOGcNaj!dTrsFS=IiQa*<$$AuTe34Mk?O}R1BZ`eUSG%BTKp8K)RJkA8uuKKDzj(d(=-@xO2nA;v0rpourr4fj$EqfBqUx3oaH6h2DQ@jMHp*)@JH3S1b)8+AklE^s+rG5X^ENeP zHr*_lU0ssR>`i_LW%if2^(mmt-sJaJzWT>;PN`UW(6`ASC0+}7rGTAhx`}=mUN7iw zfH^a{)DpxN|8$(uPCwr8GlMF^&rBuGUMOq(8Y9fxTl;le&ab!qj`C|fhDR$x{Ce9T zp!oKL+)XU`^|n7+ygKNG;_2bz+x~QogJ(dm0RD$xIfwqeLH$OqR=SK*dR*u5x^w6% zEMB3QaOidC&^?fMh$V+!cMiP>{j7L$=yk>@ocs*>BjA5Hv{gn8n@8{9-|v^GX6l*+ z`1SM3vX0&F_fby$2g|=GMjX4}w+^c8cp?MLvHSh0a-utQXYu6N{r>Laje{Nu?5fAO zM75uKT$)Q?wVnrj8~20N3tby|*0qs2$nOO-Y9lk$MjrGF$KaZ^k%I}J4_F&H8f38u zwUM(x&J>|GatX*qBGg8*gv%v$IjYpF7gCMP{1Z5b1({qv zgx;;nhdcbj$+%+qkdI6rVENDjq+EpZp$4R#2<1ahknSRs4_U%X3>m0WX9?(S%otuM z!`s8IMS3vMAjA`D3Ek-zu0p6#LXC4$FNmsPZaYJDjQ>py8On5qiq@Mk#bCu z5#bs@8G4g%!{fb>cZ#J9y~$O+m!O{mthRS-@!z`zzYo3C9^ zpZBriA?oW~S^fd}t5}NqI#-tEC$i%K{O_py617hBU+>!_P1)>HEr(sy>;0~3UOlka z1yI!M{UK^LVw!{h#%KDws~K;AaX+xz0?lyFc9k~K>0M?N z=lF$+>McTF0lL`R2dn);4VM3c@g2}fBj&koz${(LKL`V^AGp|=>H(u0(CMaw+4S*k z9WWSrAdqVlzBgR8@;twI0ugRC&#<~b2JumV)%|H8QvsKYt`Er8TsO<?1$DQB1Y z<1DwKR{+)#oU~O(aEi-_D+#{>$R#@PRx8mb`-NkP);fY42)_pvCqOx?DW6kQ@`H{hew(?+C&V2Qu?Ttv&a}GV?`$teY2#wZyT4)Gw~A zwIG$qL`pz^;xgTQ8;TW{It-_Y2A}s*3C#3kzfH#9WyE$OVE(QGIRoe?F?0G7sEdHE zbMa1B>?tfc3WpD?<%|Ks)&pFLKcIC5-a&}?v;25u8-DXgvE_`&ZGcrxEhXjd1V$yl zkLo4k__p$OS3kZ+7L>0W(S8UpKc5461~3=j0(k>y(cq%IuzbzB`5ED#0I;+5B=DBV z%ia9Ape?_ujXxr>8L&FypTsB+(NAJlQ3~KR0UFgth2?5vYr`o_@SoF)1}& z5bFe3Y6gJx11vS8Kt=-pS8ApaJ{4$G>s4Eo^Vr|ZkKfIvXiube2P{SNK@I>cF^fTt z0CKfn`Q12s7+?RUyvR z@85@4$h7o+&lVvUVg77jT-{OLdqcH!ei-V0p#LO>q4&o1K>Gv8cO_R=2Kr%e?{8zfo++bMRv(SHj)Qs+Z7`bK_*_B=bkbsUPWfcgJQPpIN&Blxa_ z&yd3H5J!Lj~isaNU>5=XD83p%y1iqCoCIvkga4%M>`!@cHX^H}BM&YGxmbieSP!xe@G2TS7y{q_BmI|b^nWA# zuToI-4}#n;LeW13@&w=|&Kl{GA9&-W?fL1rhTkh-zly-iz<~ENGLgxouFCgQwX9_c z`ULQQBls7Pe~b9G5kY^Hb&jaGlu3$WqM}d+B~IZxcECJr3Q{CO9#(*~0=(wm4>4U7 zvlqiv`UIJ<@4pf1AT51+-4CRXv=YlQ)hG6LRJsy=`T=R&0DBAqqolD0Vj9R)5$8h8 z2H6$x61xv_kpFSO#$h$O;j9L2@0) zTA=U%h(u53TDl@n#Twkr!_W2@p9T9igl>`61c-+~9*~v}PU`xL25_#Vce1or`02tt z5bXVeQC)#|p+fHQ&I_OO|NZ!htxMx zdk^AwkYAGEfD8h1wJh*rvPHG*eYvGtHjeNyQcx}15oDSO)v|dY`vSSz#y{;! zo7(29wk;&=P=JhTsC8A6pw?9?5vp~^A#n^~wQeQIsUlSC)`6@AyygwHPkCq6h#I)B zOsEFljL=QeQVqNhc=K)@#VQRF8Y*hQ{Z?RE0O_G`utwm}L&}dF{AcC3`J)p=mC%TF78vvUV z-4Ajv@PE#UUP9o7tj7Bwo220-8s`V*O;=Kc z#PjEAk>Alz|Dkv^Et!hcWT|QV+7)DH5t^3F1=$B^82Me}(!|K`M3>)XCPFi#EYT=`h>AVOXhnGZCKT;Q3DzZp&E zx^>U%DXT;M^p9DqOVF#6Az3{MWT^;QT?KLm;07m+a7`IQ{@V!G!NT<6O2c3_q=9Fn zl-?H5PS8X>@9AS3lxzxB)v=P-<(y_Z<9!w%L4d!EfJ^bmv(x*v4+Sl z1A5>34551#DVUQ$daWd<_R7=ap$7=P1u!oUv@H4x@^i6v8^i8$iQa^5x{9S8P_Y~X zx>#k=%lk_z&g;jIzTaF$@aaH51+-cNXFb#!Dd{nYuE;x$uxLs=NlJIX{e|Fv1OBxT z@mYKt1o)Rj6oV83-hj;+?R@WiX-|#)Jknf6SX&8~Lv#n}Dx$hE;Xw?BI}qTiXgNwh z#N%Bl-;a*}BR59CoruJE>Gy3+bcEOm?o41ncAJddYm^gLxE-?n2%0NJ?WrvUITUCV zRp4z@RL94M^v^`K6oC_@p{R0%qB;}qN?>?HRPt6mPvQ!jt=1EIsdN?FH6ZH&V$)FU zuICin%J_Q4wh8WC2;3o!mm!`2c}&D(5HEwg2zV9Q-MKVduBe?Jza#CliQ-+t-;sjm zhu?sFA%)zgmy1%Z_S{$pM7x>G+00x3>uFknl#5VLGZ3UN;QBJXv^5ANTa3)J7gw@t z9tG{_f_QO==8;)=Y&ZZjcDOsC*CT5+cUNO7Gm<@I`zT9KH z89x1e?n&a}Mjh>Q&QNZg()jRIj+Y%Ia<1texrAC*_GO-2$VNh1x{&PKQDUjrrh9It zR~+>$&t8w@`TuWEl9QvV^2w-Ku*>#=ve$9EqKj$7t%j9`$B4gh{-F@vza;yugK9Nw zh;VQG&vb{adY6XXXFfr5nbbz@R|~;p@rk0Rsnzd2*NY}w%l0O;!Riw>zLlcx*EeOB zRjR*14xR``NO%VdZ4!`Bh%VpTo|+Oo8RY+rUB4RkT*CKJ;cjE`8$2Cw(67EB3mync z)r)GS8(9<&1U(dmH{mY4C^9dq6hpnHjn0drpqoUF!1`f|A%Ewmv2=%jXU@nSelJNx z>aPfxVIg_}9%BA|64R^k!JYodjUx0md~jDrXQJG?%O7ihe=JE{)%_)BiH}db6 z=sI7U9nRl%{s4>WNf$6d#T1#1b^dN)3KBsfO-`{l1qx1bK=8@@~@9*h! z#y*eEDZVz>oX#nJKhrVCPw{s&$4%!He;=n)BNrC?7v^*p`@I{oVX;5cvcYr~`*TdE z=25CdaFBb%s~rQEWe54wCF>2lfw~t=^sDtiM3<`&yRm?9MKRGIuNYQR45tEJ=6b>Q zehW#jg}fX{97N5~mGJga9hvIKT~YU!LA*)$>wteG#77_>0AAN?3D?!sTObV{6#5Ur z+DzbglD-|{50Kv_?d9LE((mP;05?tiz5IznqZb@|x}~#RF6DQA0m&L)_9a>4k2cBI zBw6E6a=Cbua=z5pVV@Ez^|v>n4UWB|6S_u~B=EHtEup|4XF~Tn_EZxpid4sbC=JU= zMHx~*jFM2Yxv{r*GJjXxAD4#XGcq67nv5Q_2Om$AO!8XEe>_Y1>=j+8@_Ml}RIbYA zi#wRS-tP!rT)2o-dPOM}+QX%xc336z@K}>+ZR{z|&KpY3?WN(Z8JXK%ybr0W-agUE z9HsiSwlvg+rtGYpY<4OkgS9iA|Boug7nX+Fjh4)XlNw|$oMAHEmng2`?Q~GAAZhJ< z_)v?aTpu(PohR4&l!n^Dalw6DaQ@Fs>f?2hmi}qI0uJ77fBLU9-%5d7+w<}-!_)Ya zP@70j>XWc0C-q5aJxVm-ViOvw7V70cM@r*mp*97a%CfL?PGwoxSKdWE75lPqJ0o^r zFo2k9e&_Gq8EQtT9T=xSBW$13pAq&n6@96O&>*Mshg1#?v@zsV4h?$dR1OUWJE>>b zUXI5GTFyDCu|cPt)YzbplbYTMsp>$FHJns+(2y_Hf$Nh-yl6rrtQczUQi>n+OJzV4 z1gH0)-yvuH!Auu8dZ9@UHog4$ifXm5^|Vu2?RU+otj=_0>S+<0Dk(ZlN~lKrkZ%QOK`7fI*lXVP#X4P-YNMF zLrnftV~>)}CH(0NdJXz*9xQ@A~3ymhewKSZW(YAouYTdmXeiki`%#aEYx zM`mQMcJ|MBQf#wNhao%XmxkA5WX`utO1>#O=Z`iYetlH5$^(rQsVH`Q=Xj zd6`-6Tb;vGCuW!tB3;$ zjK(;|fM)1LT3ZoXYwpyP;%92HlifEbyVy6`v|gzvbgC4+nxDHNJITrFIi|Ba$;n1% z$?l|#-R_T5(Nb%zE!==;QtvFK)^@f?yLXX4dt0EMbtX4alT&+7csK!WzV5xBVzgOS zYVU5NVY%`m01+N{!yF{acTz?NNx{IoaISPLq#|_F!Tc3@gp`EG=R!(Cdq3LCpS6;ZuL5l? zxOlz_suhprHUT{v;`wKgiKmI;*%&;Nv$iqdYaEY;_oCvtJNP6Qa(5=AXz3G#d|n#< zK~T~X^tsE^qQOtYd95_mn#+Z}W-0ZG&LJxkmsf<76{2!TTt3k7rWRnY+a=Fnw;^%) z&K7_9d3aGYDFtU$MX1$^Q(M*7nIN|ktL)`;ujo}o6GvBs^*O1d8%Z7Qr1F1m!+R?K z_U}X}8d7QaAd70^X7q3MC*FLN4)fbr`v|(K0KZ-zRJ6JkR?#_}@d?b;M#Q`d#ifhq zmW+!2y>TIe{UfKeWz^TT1TpRu?$A zN|TF<1B>Z6b)nqTK2aSYDucc3YuQps9Yf z&{Uw$UIz-z5A@ONP@%v^3BMucL*w2=uw@c%c=6K6afXv?|c2t~&^AALv8Z z8A3Y;pMvfzw0oeBTxSdI9q1F+y@d7;^nvTXLI(%>ymfz}!}w}hE#!c(InGy3jFR)y zx0Bo|zHUt(R4&xBBN`5Q)X-4hhaWCYFADW__!8j}XF7D_WL)8?DAbqXONHl0cI3cG zmaS2!Z^T!KUmAt_p7l)OEuv6gv#u6ift{;aC4VdrqEKJ5ULk((C|r)m*9z|+h5Cy1 zM&W~_Fc0tlD*MBtP+zd#(S&r=M&TpK-zyouUTvy^k^jw9giWCNc{NLq^qNXeaawrj zl_@ONC#}i*!gtXvKb$60+VnBRs7ke7Rrz;BRp#mvb&Cn+KKx8b^x-Z@4%Th6LK5!F z&%zCoS`2$wd=lvX60n=eOVs3(H-mYFs--RNz>OW3<^;`Li*I4}zH|$w(`lkl?zX>@ zUAa9__Uriz9xtUi@Aj3_+==$TBT%xG4(wW_yoYG8Q@YW?MOVW*h_C~J=wgWDK$eI& z6XG(EOMsSlLfk4%-N3!zis*TM|3cu^l71NC7Lc0(HWKvt-o1zh&k)lNI`Sdv0_%Q4 z@0EBPh^Ijw2im;@@t}-r1`yT+>1Z>Y_Xv7dvY$bG3Gz9B>4A_>%JfG_PrpW{N5T4q z(0@y!<=1rLk4iu{f_Yah(ueP<)vOJH=w}2L0b{MeMY;v*G-bJJ@YpJ4`6xuU1M(!%oFe0-B=^;n4*0QS0E?Q@d)8WwkWdxi z*Iy|!uT##o?NmAT#Kdk{GsB%3c7t@L7=K7N)9>f=; zIp=39i6zv9l;$*@s?;@nhMf<9R)3>%wVv;FmY>17JV4DxAO+H`tu?Y-AHP4O!keflWRnpBQhm{;bRTQ_R~oJ^anjN4V)AuGdHnq<8EI&{M!r8<>4y~*&wE5)3)I9idz(*SzB=VK*Kd_3oak0{7P%q7F@owaIa9Ed%k9E!KwebjS%E-N@3>&Qgu0Z|Ph8ijc!G7&DkJ z)iX{twfRyFb~InA8!7i_-WLXxoz0hgH%H>b;4d&>bEIHM%Lxei?&vJP(Htq5)^Z<( zxTCXtH%Ic_9I2U`BN3)~QT+Z@WZ>#nOAwEB#8>!w^W&xJ&hsjXY(5mVFIB%`^P#AB z=}zEH9+s3lf2&k@6UIcZ$(!8D;_XgF_{5U+5OH`qw`C=_fah=8pMEU84z!rK6G9TN z=ynb_FTd?W%t!g8l;=?jW`dKsx!{VGp4TNUT+fj#*egGUEb})(^TGz;*SDkH2l~!u zQ_}}vtfe|%1O&S-gjFT&XCNOD>(R$x^-z4@Kz;^9`tbPuv=m!2r7r@ax&;fp4~#Vd za*SAqdLJgGHXmYdz*uA{&~q>E9Ky~5m?AI$QS%H5DR-|xtnYx3zT!yk z`c^jdXQXwET?Jp(Rx|1!N#gERM7l-;e*IHQ-U9JkD}Qdn`Z^$3BvucxzJ~l5Nb8I5 zdxt8;ea`0%R3Mt$$Gblz&z3_SZJfT|{rTeD3Uxh@r@#J4U4^-ajlT)r+u|Q6em?xi z3nl+OysrVS*eF2ZK0rT^s?qcl$IRlVWmzYzRK%Hlt zzTPDk`MprL0(m2{POUNir|>=$e`?mLb>`GB@O}cglApiGR8u9XYZ&0y2WtHDm%_Kq ztGtkz3lP-f|I%J^Y9!3CK-%}pE0Qm%f zkMoBq{_i2a0`T!*^Re(EvIa084>2FxL$(ESKAuiIjeS&$+@_D0U&D&w6QT*8%1oE) zUqqMKXEzgjI97)MUh2lg<|DV;AE zl{V`EGo@Kg)S{$TxE7Ffn6rid%#9ASj-MjeS5|)jp8vUSihW4xBYL&?_!3ou)F$C4 zSYMgS^r7liQ<*;WHSkta?MEIC^{PAb)Ae*T^Tt<*RT0~{!-)ZRLnQY2E0THLZr}{} zyp7-|ka?tyf=_MD(|}MSk33%a1-;vy!7>+ zw>a-b_;q=|QbI&kTQy3}!q_6Bx?)I(XZ;8~v#Cu3p zC+-3-OkAddPMi)-n)=~Va$)$W=>;mB~PV<59Q+<;6u2<6(+b}E=8$+ z>W)L(sq3GvAQGZE_Y`hJTHZ`Z_q&*dC`-}<{{@-&^i}Z0kK7Z9M;Q2edfQDP`_di# zQW>h2(6F{-O!_RJ#cwW0oAlRmFkxo`CG1R~#4F3Fx``vsAo|1~*oYDraE}vvQiT$U zZwXB%)-&{`5@+FQI&sHodTpiq)RUY;`G=n-i*_PV!cGKAxD$a`m!q_R@-LWLdKu_Ss5|Tki76znpswzaEYZZuw_ukNMeWL}U^gp~;;`g14D4=2+AK^cp54pj zQfc@$^`~G?q4KpwIF~#vm}@!}p-(yr_A{bQxRMG|aA?sgOjm_nCAQG2PJ6FwJ|$E* z+sYyJ0-aIe0mV8oGyi68Js#y2{1aDQHYjVn<~N~{UvxmX7&G(dc|`|?mObHP3ebkqCbjvA~E__?*NJH6qVz{vqZf{{bC!8CKWQ zOg2~skitWFRcNCTf!Dk<{YAe2#CbWfryGm8b`V%b`_EeCjjV%+noJZ@4-T% zpL(CfA$a8{3c-WKJ-88i!z*ENiuK=9lM*Cb<>tTZ+Cq5XyGU;;P%VhU;iSQT&)E)3 zmqWatwz3Z2rj_^~7}2DlZowkY|Imp1a4Zq|9~n^)c9(&VjVKIn6Y;5Qm*EZ~J~s!7 zy;dLK=xlsx(-GtkulbvV=KGt^f)(ojN&Fwnub}k2f_)YppfBGtJ%vJkHiIdzm8#km zSsS6(Vkcbe=vT@{9R9tBSJmQrtakP*l>+tt)UwWSx;EytQpSDU$VxMdOJ-{RAgN=ko)TYIyc3t!FHmwMfjIxQD2%*$81Z}ufwQE-}hr2|s8*>|;m7olE$ zQm$ViA?w@BiH4MqoP|(wxSzN$Ct-n>jMn4nHahqT5ie!Kz1A;MWqLZh-(|TjaZ>e~ zX|_~6$8tQGCSJ$YwtCZcmL;9UwIWakxGZV?4|?Vjzfew2Q24jm(g`$pdd;**YT6~O z{L#OmS(bS{Z=-mQULaZ};MMMfmD1w!rQoCHc0z51U$rVLKH6*l2g$8YC`)wB!LnaJ zKc6n}#A_7LS!Hk}Gr1#xLJfb_iQx)g3w^qHYG>7noz>0?E@r9<6i!^r6R||KQd9$7 z33S+ldQp=YpseF-*p_QC)gh55@5c~40O;7HoN0Nj=S@!}56vU-eW6P_>eh-|se(F< z0E;GZI~I+_KoczRN8b4DJ|tnoi1iiQ7k12(*D)^O{Ae^6C-Sz#?~=jLCEaza(yf$R zslubNVAo>sTp-#3!n=fhL=m$gY9QJG(f$yVKt=$a7C}TOa9ay?iGo)`d30<@74EQ56F`U@U3`DDUwe_dzsWD7%FznKxPNN~F5PS3t>QLK%MbA=@tKjHS z!Br=$f)^wz{|V;_^5hY~DtJMnzbg19=(ojF1usZURR#YM`aAJd!3z^DRl)NwW4a1h zR;p#mjdlKXw{f{6DTbQC7A-&eJ7Z7p@OfqPX%36xyQvE6aHgrowMB7DInz{4V^Q2u zO{1wIUlfm5}g=%Bz4Y$#7^e2A(kY-GuG@P!F zimiQ<^h%&=;oN=Ubx^Of9rPgM!5O3uY$nt+z%qD!G+E=tq0svS9d`XvQS4&f>}s#~ zeD9h_Zd^*(IY3KIC$5cbI`J~}^WuGiTh}?>PtYF&UG&eh*GJ84zP5ULmwkAf`i7`X zbEjbS9$gM!bhLM4RH_+UuzF(4BQbiDGcdfK9eSYUWHS4v$Yzz(peF!hhQsssjVUKK zqaI}s;$Ka9u%OI+D5_NE9)naJFisM4fJ=**A?$^JZR55Yn}XF-#w*uyS6?u{V_Y&5 z!Sd;ZY(V`%pnNREGayd^(H;R+___7iDGoU1g2`seqj_Nms9biQAtrJU19%ykCyQTA#sDw71)n^1+Zw9Kl15eJwnkzug{pqfXSuEl`n_F{y6KM_1vPk=b2B4|18op) z?5BH(H4FzZmy@@QQ(eu9vbVYTH9qBv=A++k{=B0=TdSXFr-jJLQO64M$9la}BkT3N zKKH#!7Z}Mo`pcsu>o2{|hrLW)i=KSiD<+s8P32HEA6B`n4I-QS0m=OqE%LfYY4y<7 z+newYGKV>kjzW4Xg`d;$zKcVGe-`mJi zFY-Dsf5r1QhADOnuY}>(Yf@9CqS+XhDKq0WyfF({x4$v$pmDVlx+OqA|EMjE$3qMT zCiTS5U@VZTeEu7;*l!#5XVs%WN>SA;K8kQnL%gzjyt>GgH6_BaOPpg##eJ#6y|S4| zEemB^J11nvxY&5Z6VY-@!H%;6svaMXh&J{slvojGpR|MN- z>|B|#Glhn^*4e2{&h>5y3NAoxvbyi&-g_VA-4PT_f#FqVs7^*vkpINoL6+G&DNfCT z4hmW*PMZZC6m+mz&^{(+>kgaC91^&>%zSS_;97OR%5@xb;cuY6SD@|JzlptG>MFzv zd)IQvqaT*)H>!hs3l;7fAbyfy^$=GgPsO9r#Ls6~w`Ev;yqF_#P3rLstFPDO?F>sw z{fN?QKOgUp_f;yoS^$21f|go%>B|ZzRULYZI9~(2eoJrSfq;J{R;o;LL{@UXll&H` zuYeA(P^R)OV zALGV6sQ*j$yKD3=zoQ5p4n&_p>;W=E#Ab+-L6(a61LAU!i$pY`K<@;(RYY@$mqDHs z(GDVSEi+*t>H*OXq!QR+2t?ajZhF-*fp5_$h#>?G0;Wxc7!XHviiZ-`hg?&qW`Fq2 zP6v}0PTuGBo??x8aa$0ryLZcoY3$0Z_K=Im609L(K`z*fcZH|L{)!yWR8I8bd4y=M z;BSpX!qwBY0Et%5I-mb8c0=M(852)87PP^V_f^frH(P|P-ZeMyY8~@egk}+s;+4ZQ zgVX@h!prN{HMb$zBsmWE;P81bejT=Y-XV@1t)60&Jv6%TVrCJQohKt_b8<2f_&zp-6dhT-Ci;Tg8sVZ$czV4p8Bt}t>xNe|{hwdRu zka@^51a{~iNQdqrOOScUGE*V$Axr2UvIPHv#Y2__3ULovLidm*bPrkDx`!+Q?t6iI zX%D$dTnXK?mdYs5GBR{;=>>Ye61o@kf}ds7y`UH9wY<>1mWOZOL#1EimiW7F|KL^? z=vhm2ygipre+4JdLzd`7d*G7(U5xN_7|ZNwOu7&kf*Y_Attfelz_NkwGv37aYQ#eC} zK3{@#c!w-{cs*r$N-apJ#A&)k2L-(Jw-j|$U}4Z50l)PmqPcsG3c9MKOBkC60L6Xx z+YcuX)8aSazZUHgDTQ z2*yb=#;cP2unWN)helS?UlYX`v?qV}kk7Mz6t0ZowA&l#kvKsxBw1W2AyqeaasyRWAZRUo@%uls{hSZvbB_npAz-?=IS7;12_)>eGIUBv({@ z+TYEgku~RfPHQ5!PvL$Is8&bg7-iA!pnu&2bd2n=0=Zwe(4>BBBKSK*tOsHvK(@Y` z)2)D5Kag1jb`a7TNHxp;G$p)RbO~A>Y@r&UE*V-&XUp3+G7*x;o4%Aia!md(>glpdDaNOB*&_y zAcIu(1y%WZ{s>ihK~;U8KS|YEP!*r=_g1({W8r*%lq#z6Fpi;B!Wwn`3w`VQHFpxe z$hS$rOJ4?Zyk!-%_4XLOf%ZP$w?Xy|h5aXB?R~u8N15lZ;e|e6?R~u8tc-hscLNgY zhRgjP>UU$oM*-Fsm;0m3T{Dv336! z<{)(^z_c3a_mfr!ga1M_Rn16$q_jF2{MUeKwYA?{UF>(@zXeRIt^IN3UTEEp6CG4@ zj}m<|VBL-*9Yj0(T8>!(I!cq@qnH0di^pfCWBT~fT|`_3#101WuEPOO$UY!-AXPw2 z&US+d^aUD}G)L|8>I#=dhsBKdiTX^|( zdWaf`tO6B74~qO=Z9ORR2etK}$RE?zYa)O9a<7SR=`{)0YrI}>&{O;eOy)*bbr+G1 z-?|&O>)x6e{Rg^#0OeOGe=N{P6QlpYR+?*9gRca#OBZ?%6_ny#u#HAJ!h5*L7f`&| zT8`?1(wFD#N33h|A(Ev_ygwE9C3b6K2Lah5jy%MB)EZ+6=AePYwMf5Q zw8(qh`uc64Hvpc!42h={YT)9X&$!YuBh9k4Xv>UOD8wbi9C2&l1!aGZ{@}5nFEz#) z$^1EDKVNF>rWm)>i2Z!2ahPJVIE=0^@gNuWiZe94epO3RVthHAy+eXU25 zZ(2;jOUx#RnuM=b$u{RZ>o#p(36XgvL@%9$l972OMCO$cnO8z&UJ23X#3my1N{GxW zA-eMnZh>AwUI`L;*mw!t#2UskQys$<^Tlu+wctflVPl@z8%pi7A96rK zD(5GcG6|ZyK+!LW7Z1{tiT87(Q9KH-dXxFVA<677j`ljZa5jAIetZl4DkU$5zkEP% z1glqp)P##k-|TmI45U7MpT*<^zwu*`#>%7-$^QWG}R5`c~;Z!)?!I<>05biZGRj zda|GG7hgx2A>m)>9CLkZf#&QX%Z~KsIb>vb@vZE}@RJirGb%ipOc(f8>Eq2gWuZeR z*sJbEesU++TC#^SJb&S0CWV`*-Cy~QF=8fr!S1KALb|iG98D7^aY;|50#u^7I!WB> zCWxrW)WfCKV!F1%^pKbo?>L2eiDnW7A4=w{r5D8h*9yDpVhcO3DQVKw>&36c^gWk4 zDOAqywH3r|ER~=n>bRIvswF4Da#k1ca_YRQiu`W~Fj=cFs?3JRyqt#KJ{6n?%w4ai zdDA0~g=7ONJu)m0s2>@W>2XbBPWHWp7ERBnVKVYBz83oSp#*z=Gi{XK!4Tg+kB6A_ zPN9ZOklF`7j`S=;BENuTBt6FvwlUodGT+i9{acyf(|Z__@;_qcPVZ%GY1We#;6*UuA?S!xKwm{Meps25k#U&ENr9A}*< z>(3Y4a_iqk|6m~}7*gXURL&0Lc{!aqv7sa3`eT(zOLZ({GuE4Ha>QRG(|qv)^Ti9y7cVehyuf_%f_LbB#|P$% z7nmP`QioUix-$LUSPg>f%)PE=8G4YFJ9n$@wyzc{~=!7-wRJ~22r(c3j6r^ zpHRcA{@s0^x35Ej>f@N;_VbfcGxECXubu==s`#oFuiLA11OIs6my}qT+=#XH@O=;Q z{1g4WY6z3%SR7y;gKLFfv$HYPL#a|x>+gVkjX%hdFQT9IkgXxr&7O`=hdIB7Z1P9x zay}QYr=C#Lr~6I#cY5+H@_KnSU6Jx(C{F$Q0)A^BW|NHe%zhYlP@&#oq47G9x%)}c z`iU0%1GZ%#xzzhOv@9FJ>Vd?^i2NipXV_-&fdG~S-ZmpvP37&8(w#!K^IF--Yk4bu zB;=a28I==Em+8-Y#cv_`t@<8qW;7BfI9+x{+KxbS>9WJUiJ?{cN#I8ViGRU2F|3w; z*MYAQO*&5uJBs!I_`N_<%{M75sOtU-{;c@wU&He|tQGBB@UMYBf0#(m)!eb)k%xO% zhaD7|xSoOosR@)KdV$5VE^)-)7FPdA5&a#BXo8~=@CxfFidw@<_keyBn0Fas7l*}u zNcM+891i19F`LYDVDWWPq65O*&SI0y@vw|-W0Txa7oxp0!>XezY%^e)Cbpt9d_~f9 zfy=uf%$cOQM9&e6SMw!Rc7LGupZT0u{E>gZbqS@(+-wm=#Vmt$Zy*y;NB0NaRF}_z zKLJ?%J`h+tdMH7^%S6mz;nbTG$y|cic+ED4Qw0$(yEVV zVDeYc06zqU>orTOW_uCa18`OLfmn1QEf)TSu?!)4uvlC>t{^%(0x|Cdseed}+HoB5 zqs3$Gcoi&xT}bqgAYD(bny6W@>?Af*C{Ei1=OU>?nBAtrvM15Ii^U{yc1h9KMG7^A ziG>xmU%;}z*b36edRfN-*I};?=J6c*CET2|(9 z3;7L5a3hbGLM{bq0T~I{xRIRLOloOBkl$B=RNto%y8>_(c`hv8JXi(>=~Kj_ zmOYQ?--yKq!}(&d3n~o?(#CQb(U*wDOY8gOPrwr_Ld@DA)B~LV6PG^{zXs^1h+G=M zFMvG<gpM*%4!cDLPjxACL(?!GlpMHAl3R?p#^Y3rEH-#{OZ6>D%%h>+LRh_ zHj?}ecu8o=GetJ|^=*o5^lfyTB5%5|S9dWx-?osX+?#@xt z%>SrwcP4LO#lD{Lyw7QLEwjFTg;8S5tY1*WKXEGVAA7_3kXvxGj{e>QOtZy1uL9VM*80s%%Nmuwd}gk8z30kGhvCTzC~cvXtxu8)deE6vQ>C_-C>VTX>sG#=t1dt3kUi0 zU&jR`#jxMmXtZmhhK;PNF0+rqzs|l~QLyO0mjNv?OPq;nMSM8ZkDm zw>ZjQ+SM8|d00F_hY0K$Hn3;dz&*ppB)J1|CJ!Iyj;PjO%&~Cqm%OI<>%uMP@M@M# z{wVb9ul!=+=S%#erQfZR{tM540tE(7v-CA@kbZ)2mwuhn-%9$yF8zCz^q0V%Re45+ zo}Yzbn8s)<-0)Wfe1d>sPQWb^a3Kl}a{^wg2zafcz`LBhN&4YWS^95YCjEoLUHUte z-sAarxJ&;`C4EP_oGB2nv+-*ZG$*0N!qV#q_yGl)oq&5JU}xb@z{3>*^I^9dyvp;B zBmLMJmi{lQ!OrlHb?MhC{VR%h>F=nd*OmrLzrypcq<{<0wDcn;k^VN)FLdcIQTkzu zcj?!X-d_j4*zqq@f%ixLV#j}j_}>@q_**OarCI;D0{fo-2?9?2&NAHNMFcDn?gX?- zz+NbDsuOU2MZoqI0au;Jn_d!}HU>&8yhj@MBFEF5fGZ_nlH#3!QxMSm6}pcb!Ag&ADdf?W$F=Ym+mmz7W#2v{+E zM{0mW%n=8QHPxy1WJw)uQLHZ&>o&rqy z3;kv(|1a=wfR19;&;MW|?s;X!JKT&<6_AkPy$Lh{4dSp;w1ABVOsO^r-WSAE0!y?5 z(K7%m$wC4PfCh1FDUPbjQ*rFqe-*{>N$+a~H9-1<4Nw6Fs@6famgb!_^Bw5heAh`! z%!B-nw#01Q^(x-B_~N;mdTQj~Z@o!%(Y-|xHEPITqQ=3%AW89e^;2R$1;PrT>ORul z%8klvTtW2KCJU_MuRx5|>(+jMskMqEzX7y_vT}SuX4W(!xJ7}aZPkH`UVdTv`n9tC z$^`pkAP=>2el5qj5{souFyIIUb8l2v>>L* z#1wjf4kV&4kQ@w>P_f2?jRlJH;B4!f9bMO~uV#pH&#$LkTiHGTZ6?D@khkL`F8Y5I z(@NRwJq$eO%q*4r{}dyc**oXVES3BJK8kT>mR#A)@(m>3upg@!XL89olS|H-T!y%{ z0C9S&9+k~3tHkciEJLHHyqi%qXX^q?E~6FJx`5q`X59HsgdsJD@R$973-(ssksB4x z{*8+*4$7MuqjsAaZK1%1aLqZ9?BHw&*MokK@|*36s8uY#+3rLbuJW7hK46WC9#(m? zEu>Lq=+4?GmtdpZJ|I0~s>I}o_Xx+#+LAPDOY#wzPDq-yC27`{q*+^%W^GBDwIylR zmZVu*l4fm5nzbcq)|RAMTaspNNt(4K>8vf0jPc0@`H(DojNC*CQupo0-LR-tNorkD zVZQ24M5??Su_$AF>Zw$L6v$!IXT@xt6?5yX z-ZI2X;$gba$7~T3vqenIEn<4h5HE%+{wW4C#K)W=KDuxtOQS!Q{!N5!BCJ(gRCBWn zbn&wFT!)*XK10Xp&+HdhO<}0F_;}e+ucnRSWkbD?WEW?sS2!Cl8|sz37%v;@Wf-oB zmksqNfYis!hWa%ijq$RfUPx2C=45ONzT4v$FB|GVCZ=z^Y^Yb49uhAb>eW2WUCM@f zAtU2uL;ZK885J)Z>eW8u<7zkz^+G1Z<+X;PUWYuibSWF^6*DQm=_E7MKZJnEY$G|1 zYP+*E5-ht77ppdvC{PD-br;D{pLw{nhnN;rm}FA6c*iN!%kF@Vkqq^jS4(G!{k#gh ziob>3i)5(Jyk5LnOm}c;mO|zHWT?+(u6*N8AtcM~7rJjQfc7uvqvQiPF6ptd#_bL} zT2$4(mCo%BEB%=Yt(|6SU7+|aU8uDEgFLcMvZxz>9<{aBg&j`!n;sEe-G7uhk_uaT^UQA)E)KNaQV~ zI(Wq%ETjL_eML5ZvTWERTkL7s97Hx9RP(yt!C?HN0TW%#>zH`P|{t$08Hmf__t!@=Nv0TZt3 zN4Q%rjk%uw;-4A!)y4E95}`6jB~;yK#(Sx8wj=RWV4J049NOU23Y-Sj1Gsv>XVz8lC1%s*+x?x4{ysu zj*VX74fRXQ!jh0&4cZ<@W~4O zw9rbHS+_vst*k8z4^u6_u-y8R#BZ%bODoVX!bVBCgu+|^j3w5JP%aEYU11#V3gY#h zi7KGti24>tsEc10Y^^TdaGSOuLDQn)x?q-QgTea)9auZ84Z4do33NQr z@ipr0wm_0Q-bKaVZo&T8Q1D2fji$lMMFTGV02iYmaV|>KJd*RgE72&>Ma6g_NaRQz zeniABNSqCX8$lKj*jva8AO{mT5b$d9VAqp2p^F5(5+rt%fDuF-1*><@o;+=VfOjq3|39U12>;-N$d0N;Yg( zxE|*3teRR8*cRV2!)IQ&}nWYg2jGz?$q`_%;F7WPc~{sSq{UcLcrxQ2Cc+-()I(RZ+Pq z=qZ&m>Sj&BI8#}DsVSJ{RNkA2l&P$N=eN#cl-V#&1x-pBzuor&z&dX#7%d5%!8-!h z|1#zNx6DSGT3mOSl}voyI+M``U;R-d+^TSc?`A9wg$@2#(?`8{gTIsXX&Eq*`h3SP z%(e>XHvw$Df45SLYrQ`}3zLkP)^lb)VXrQUsII&+8f^zv zO3}^ltb7-O?=G6^rkiiW@>K9&0qR)Y{Mlk#3wkAx*CM=!U$W)PN)FlhozUKTrU+I> zd9Cq#_}gfWAFNDHoHz+beUzwLgW4DQHsL*sl*fUpXQ8d~Q>vJ6!2bv6F5R`padS?Q zXYp%EZiAz5+raThxoFL`&sL&glC!94U7HQ&ge&pyBYVawKD+O;^VV6qSFHN`DmCQc+X|yQu0p;idGrPxjgE^Lv*tyqSZS^P)*&*neLKacH$enSntS6M|gn_{1#*x;q!dktDI zJc#t0fWZeI3Tc3f5Z%cv3#qLpZSvNN@_ka0wX$-tT84Vt{*l7_>-;6mLrA3Popitb z6wAn1L)DeTn;?xt@=zeW59Ck+i-8(3*OAsP8vUn*{^3d@uJhqIS4ouq_XJvjRCn05 zLa)?+`dcznqn~M`1}ou@GR34MR_k`hr{-Not#;DT>`T;SQ*UJzc`bl+BciWUUQ0mM z6L?(6F(4lk*bGcQ1!NQ{hmms1sUX41B~vvfTOdZ*kvWNk&*e&@Zn?R;u=@g`Zn>ig zYz?F*!>e1bb^uE=w`FDJ5-&ZI7~Om4{AWyR7h-;P^Ce@t_yWkPzmv-ev~iM;)O+;@ z5mBifuT$kFt=jclZ-9B4ZqJzJI_U@=@KiO*knqpxH-v27dvkamlLc1rf}KZ z788Hj{i#H_Tg)FubbQ43APKXW70hB*FpF8iEM^6>m=(-oRxpcM!7OG4vzQgkVpcGV zS-~u31+$nH%wkqBi&?=eW(8+4i^*cfSz+5L|Aeo0Ow1p~gpshb!V-2?Si;TgS8llJQT7r#xA!6qgBGCT*py=W{EWh9Dp-WZ4) zB^l|wu`-gX(|KcMBweTN;$3Iowe>v^Z>+aG}Gh zBy(Q4Na-fIxIM!km2O)nb3wSf>R__N7KW!P-BgDy3L|0DT_r3I`wPPytY$kPyi)0Q za-0W+b3X-}?N@Kd?QBWdQE_t|wlsY1Be1y+TNW;QA8ej)lgcsSZkxgO@Ec?RS{}Zp zxCMUU3A*WtcHCTkpYC$GKaN>a#YM86lVC$i?1VwpE=t2AAJoRRgEF$zd9ConNDZ8uM>!Sh?Zq&)l`QXc-BL$zOd_-}4M{5Q8B{+ms7dH8QG5B~$-L)Q;WniuQ6*m3G( z&)KBexf^v+EPSsnWwT7-2kTy5-BPdcqxGN2_KX((WnD69&i{pkpVADG4o{@g3wgi# zG16!8i&QUmRy_ z*}9_-UE~$V8YOUJ9Lee$wV4_lD^oGkxFgbHTCCVEC`6cplkL0%>^-Y>o|4&3+F4DUe*TNy)d_62LV>UsE9&ofC9ryK~jiohUIxgfbj)izLpdb=3NuB;k%Bw`+#0+ zcn+OJX5JsR#UVac6Fd#!Nn#!cf(JleA@HJ*+d%$C;A5ac?3uqpu>&yfp*nX&%7+lB zPM*7Y@^^mebO{~xcuq_YCHnOQ{8m}LDAqZ#o~o7t0y2OV>zvpi6{|ORcfg8pZn+3Y zQH1kcRgNQWG+^!c9~sLApKYY+j*F=_^iwzRTYK|(OSZ?kMw~_R9RSPrIMx+|j@dFD#(|c}D`b)!b(11G=(*u6lAZ=6ySIqe zSI-2i!7m3;W^`;DrN0mC4uBGF;~METuop$q=`Ukrc1QaR{BM9g$bQ<1B^_CMyVdZ1 zid@|&RaZWe(X1FvFHqgvNc3%?QaZQk+ZPVMRcCpjN9S0hmE&HlD&$}#=p5^>67+)B z89=wLPPZ9gQvl0ewK~bHPP24^gPNWeu>5PVF*&WsTxVE*6X`~|=@kx@w9H?nVbTka zTuekKWxp3f=L1P?AN?j8s8Mwc_);J(XM}Gen;k9%UnM?`gm0p$>N2;0-vIRdh+h9) zBvP<)F-m_QS+9SdxJQBB9(}c$?2jPx{Qt~kI*c;n{*K6h0{NE^@b9Q3E5{0u5rf!FW8_u|WI_r2NO2IGXY@ z45m=btPcHLZw+x`TSI6ju!dM4)vF;cK+Y+EHN^U;pBiF4_#=Qd#QJEI>g;RqPl4Q0 z?^##PUGMk3PC))M%&gBv>4(X8IQUkgNr!gt1_FNo8CwMy^)lC7v-xDWb$>oceqK@cGO+^b&v(;-l$nD9rbm%`y-o* zy`o}goP|FA6_KxLh~pNE4Jhlk?o&l&An%IE=BJa;=vP2ea<7O6E9E8N7XjNzJ`!4# zfj>LH1BF=~*}dszqW=ic1Fv$KJ__~_;AKxH)vSmCVL#oe{MKI8HV|h;eWlGC@Vx{i z4?IzMiX%X#93} zT32h_c8^-5h21#2N82mhajDnSX;SsSwC`RpRIpNh` z3{kzA(*LX91OlcV6&H@GOYY4Itr$AJ8N60ZvFq5m!L*8scE z*f^BD%51K-?|<1Q&pRosp=8WwWOJIbIRH{eW&a(CzXHLK>X0JV)I5%ZD2 zmQvU)qdQTzII?iBx!Zl*-9nM74Z1@HXud0h*WB+eZF75BoJ+OeP4PXd zD(wP%!%=&5l#AS_L9G&-R(}gRxg}BdQM$xc zf%Mg{8Q>Lu2ee|^2)c^CKe_JADnh zlSFPp+-pGc00z;8K|h&fk`HqMdg&M{{eoWHvQ`D@K&MX)B&IJAYzCQ1V7!pmK@KIb z7#L7VXNjfT!GZra*;@MZ;W$@Gl>YYwE)$~kcM`Z2XkQu)n(~D9Wk;27Hm@NVn7>8c zGykJx%9fIy8Q9|c1tdKMSjo-|dZ=XIf`1NdDOnvQJG)%6#zz=IfN3_8z+fTLY;OX) z0{^vS_rhQ$I}wf(ltd*vm%v#Qn5tAYQYk`19`BVMLE9Bd_1gVJjccD<^DTIk@Q zugcNk{r(D1w&ilu%Z!s5mSPN5M2ZP6?K;J1n!;r)Xy68;H7KBx%qAM}-Q|4)4NT*6uT6#u($s%pd>inq~M9c;%sfO2p2 zdsw+uQycw35@j{D(Vt-hStj?loL$c9<86OSeQa`cum7EEnUj4?8^z^PrS)rMqwWR1 z&BqO>Rs$qso5a>rV|xtvFhFy(v)AnnwmXn-go`)H;#vlNC{Xo0+Fk5uBTuFKZ6<@< z;odsGO3MERmNS9)-e@2rg&WcseU?Me++KeH0nLM6wuy;sny+N%Q&Xc%Up;2n;bGJK z#+RU6hp@|mWWR^RJV3hq1^j8zy0?fnPR}^sf&T+whMM6@(dkj#2!H`|yWreH2EH!3 zea!L0$H^vGNknfrdIG`eAj1d@5waX)9D!|w9Nr!|0AxDUsfyVLWDbE@fLFT~@hag) zWK--|*!2+B=kc2$%gO@Dr;OYG&y9pPS+U2y{%>Z&_&ewaK*L-byU%kp*%xNF%RSC3XJBS4s-K2@ zUl&ag{#TigdBWKG+H!LBFhiEUU;WM-)svFkuGSg7)Vtl*t9><%4%V>ht2cY&G?+$fy?nbZ zQ~P#rVdJJcS6{u+TWs_5s41km{C33j7^4Nwm6ws6%^EjgF!fLL51@CuC;RVV8Km=K zS5(VN_%BNJ9We5TNfeVfOMSAXu3teanHarJnje#33qY{cbfscL3fSQZhB6T3KxPma zEu1uxd#&1Ux?%%PvBU9mZ~F{wz^(nb=^rfJN;S!zjevr z5x4~?bpt64;xf3B%uCR*W(59pB^2*J;QLq!C8hQ$5&;e3$|!X|uwFn$QpOS(1C$pU z|EZe#|I4U+fT@=1Mh-n7?LdktKxq(2X|yiea@k7k&E)fHU~I?2atP2MT1LEUz%Bi=G@y!tA7tjyZ=eF@0)tzRcCzSl9* znn3*4qonNpkeZ%G17PRJLHjU~+}ApSCuZ58vn zwVBsR&jlNaaCe?>mDx&2b4aig5d02g34z5x<{FT52%G|Jqm(}>KV6jHZlNVzOXRhH zCB2ittw2dh<9z65iw6Hw)<93WJ+V3LjtGw8?T!Y`ke(scQxekx@*#n@h0Fv={+YAo zfM6a-R|1`Y(jt(thjJ+$r_gC!wvyWgKGgGwQm%E*3*5FPAIsj&28bV+&pbGYWZee0!JsbHlsq423z_)jK5)Nu1O(fB1 zAm|FRkigzT27nw(;7B1OLCz&`7LaKHxrV@MAu~Z9CU6f>+7)Cg<#H$Wb8oCs$r>f7 zQKB1_S%acX#5<&Tvm)Xv0{;*q5!xRe1GZiOq8~Ggm)RGjC)Dmh=3tPm2x#}86Pn)^5jiMeqC*N_7L$^*gX75E_l(gSemvW9n z?Kjn>%4Zj~a~w+je1qM=$V#~lcB!9lusc;TZi8LQIS!?q<4_;xI7D1m)T(T-TP=3y zAk_E&-e7mp8KiIyLY2*S`;ajDPM0Ay$4ZEE3Mz?|^pr#Se50quQ+5J+Kw)jjXP+I_ z;zeaApuZ|yb^`hv;f@J^3V-qDixKqyV9!`2r<3@oa4O=m6Hg|y#BeM^UMQ!NM008k zVTf`%NsR7z6zkEDcoBqhuvDPbN-3G+xwwA;g%T7W}FTg9a3pRN4O zBPnJcNip+CikU}J%y}e5@<>WA4flbyqw`2guY3rk+mc&&%^$?fBPnJcN!`jGNzt4e zNV7KlEo|A5o3I$C?`sLEsEPF6^g7TyRovv+stt@^j+xW!mRkrb|MccOV2}yRw518}z6mHwbx0>W_+xVUU zY1_v46-e7QzJ?fzSGMs9X{v1FQ$6*pY~x!%OxrfT82Pkq<5LYbcP?+^6VkSgZz*Zo zw(+Ub+P3itY1_tkB5W<4%iH)AGpVwTZzM63y^^Y>vX}2hbWh&KrAl2{#q!m-zEx0V zFW-w|dbPszxtJ91IE8X-Bl%SJ^7&+wjB_!Ws)H@;US%&|Z!zgxHUp$pIluB=zDbIk z#>E7vs+<7JSv|q)qRLc#bX`q=Clr-a1vfnAbUf6sc$PR}1p-$e*?i8wlf}Bp?%g!<+ z3U%^cc8($OP$%zY=UbX&cY}ko#wB{X#(4s_d(o`FVy^J2$313p$sn#=e@F-`l3Fdatn;1)74Eh2i<9 z&^+er#uOXK)sGEdN5gv2$@~>Yg(}#fecvHsQoU4(g+0gODlb>zVmA{PPgW}EGKBb4 zF$)1XZp1H4sNNbCulpEJt*fD~N(`@1tX{nu*_G3Ln@`oF553#)@@iy;OLuo<9SY?} z-CD`t>atD5_4VT?w9(ZtUX4r{X+FIt>z_!E9BX{-JqSS=LPWv<#)E&5{b)ebI5tYP<2E$25NiAdBIG> zX4Qu8u+9#w<4kAiHW}~=cR@TZPz&m(hZ`($NGf)3QAC{-+!M}uK=C$)>v2Ih(T)KB zB~Yj5=;co88Q`Y@osi;5h*!8~6Hh5^;)g)uYZl~UqUHp7iCRUHl@(EQov53@*8=vm zrJl4Mp+I&7_q}$R4M4HM2ii*!V6L9YTJ=RrGc-VE<%PlRB+E#}p+TbxxgMF10=3Vg z*l?HEC*U6e7|vapF_^Hw#r`U_H1=6yD#28wyS}67P8*0e-7en8sK8J(R)Li0THA!PWi-?0mEj@=|pzbhl zt#6B%!C<|C+80Um2j6DP9l@uIOMbT3`!uH|wPGJ2E4h-o7715+akU8zGlvWN zTkIOyHE9oBmQX{nfBS^~WG7MMcl&ZgvO87B!vz9EeF?)-YT)l*W>A#el(r~yZu^+B zGI%qgNW086-CWhi=n`w1xxY+veQR>LU(lWD7cuHpzrrQd{ld1UI{=d3x{~K0Yr2KL zb+!|zpThx~ZlOO|O?NlgH9%3@z83nE)FeNE{|&HnkQe!O=NkSzmQA2mO}D>aBffpW z=L0snG^bcSs6QS-zHNhn_tI39-a}iwCalxT@zB~5dkqIsf*pMuD;oWN>x-~;*I3!n zx30|uq7N+Z=nv4Xf}P3w!t##(*7u8hw%0Hl0hsl`FfT~JHx&Ux{3dl>-Y6BGfT^yn zo-nS#H#}dir#ip0_jPQ7#MlgWUQO$Qhx!ZyTNA8jnH2a z`!}1|M_*9GdgUMd2b%2GTQHAGV!nLr9E}MzU0#I7lu91 z>m!gM1O@`G7wKl@jb4s2{uFon)1*AcnrBKMm3bSL!k;qKZgOKQyNECbJjv7}W58uJ zUeb&KZzARr!AK#9zEQ{~3S(4~`U$eaOAMzU3@5@JD^*c@ym; z4W6&jHOaz3eDTrVwib;1hv1%U;kaM8l?9oFlm5APVym=p+8+abnuW9ecJNQPaNb{Y z8`fD17ySd_-_F8San1SLTe!xbNZOeeuJd9ilb~^DZL~4fW*Ob7Hrv91=`+W|9HLFy zT`U|oedby?Y5MGH;k4*m!onAE9yfZ%hWK@=l&s}44A1Czi`SIv z_b&O2@GoM~MI@7h*Li^J%FAfi$<~!Sz2~~}hH_Uv@}JzY+HHudb=^8$J}gpPwXTb& z+u5~hU3X8H4~{%oT&}ywOiL0g-O1hn$ zE8Wh{m2PL}O1HCf4YQ+>;?38PHe-9MGPbuW^U_HaI%9jQGPbuWV|%MIwzn$tIkAb1 z?XAk3dos4SjN4n4E}OaZ7AdW5P>B(RVT1=%wm~IE6==_lZG+0#HmHnkgUZ-8sEloc z%GfrjjBSI;*fyw)ZG+0#HmHo-1~sgFl+_A}Gc#Dp%wQ!mgO$t-Rx&eK$;@CSGlP}P z3|2BTSjo&_B{PGS%nVjCGg!&YU?nqymCOuQa%Qk}`6#R26sX(CP27xA_o;80Wrw4z z6!zjj5W!Jax$$>N`pg@2;H7Th_LN7op`XYdR~kM$ywN`__ci4Cm5Or-5ZS4NSM# z0Tm-x_ONB38QaO0v7Kxgx07u^#m1Gr;(T$Ki7VqyvdXT4GQ&(Yiahn8gdw8Utz#z4ohWcjv)u%TD> zqM5q_om!Qh>sw1Scaps;%LgXZE+Ye-Tb1Pt6X%g`RB*CnF7U1X#|L@?n&s#!HO+)T zNBm?tyXp!!TRO?;mE|iFiklQ{I*B+wGclLA$zF}BDy<`|vUirAp;+0!aA{Q6RUt!l zoY3klts|_m510NSrmrhZ1*BNK;}q&;2TP`ou*$w#YJ!sO#l>W*I<~NTX&qseeZ4qE zOxtl8F0IP>$?TQgSlU-{i@BHp)tM7uIjeIxvzIER>uNB}UMi@HZg|=3b#n#B(@s4s zt-Xr5silXZXCLQc;@=_=s+B?usT#cOW{BM$zlP_m+!tH3;E8Wi(l0~x5HCKKh%yqz zwO0{D3MAv&t5`--9kf@mjHEm08LEtAY>4K*whXiJ=@bD(DiqB`3WDn-W>xJ~1d-_4 zxb`Z7s9)5@m>CyUUNU>SF!MK2((u*$6iGxY7Dej5v(MvbD+J7Irb_F>(WVk z6?1G>)NpMIx=A9N6@~Q-rV3-T;;mqP18r8!u~|`A|3I4+b8J===fGf$a$vLKc(5Uz zv{^C7ZbfN1EO=ryaqLzUXLF$4iaB;G3LDkwh<&{r+ZB~;Y$vuWg5-pZ@1*^TIW{Z` zYYDVrF~^2Q={zaWhQ%Bk7KLpaXv1QT4U3XEIT)chHY`fZ>A@6XY*-YwUGVH`Fg7fT zb7t^_(y?Jt*v^4AEaup-C~TKN8y3N;gv|>Utp;PmqOd&!ZCK2)VNo&{1iPyq*sv&U zVQ{L_v0+izqCguKb8J{tJuD8iVKK*CAnbtPN~L4NqBsu=CJ2B7#lg*!nv0$eJ z+OU{o!{QrYX9U`?m}A4@DzI~c#mbKji*{y1Fn%={8x~dCivn#}%&}on*d>8BEaup- zD6BQmhQ%Bk7S#?{2HLQgW5c4b)qyrF=Gd?(?5f~nVQg3ww#KX39Ag|lE!ynTbX3Uh zz{SR)RBty9Z5Fb@nAWbv+=9~4Vqacim;UY8RkdEap9C){trq9C6;73H3#XTU?@E}C zDLo;k^<0LlVjP3Z@2{(2IL%EHpAy&2b}i=K)&O%8!8`3I0*90*f_K_a1P&=r1P&=r z1P&=r1e-%OVtFFiY?_oOg3awGg3awGg3aZLK)V)mAC~T*TI;>^aq4K#*&3&t?OM!# zufAjRP5uY#M_vcMr}(3FqR7?&`F~lzOxpb<&#pzaR6013O3$-v@xTnKdD+#7>2^A_ zn!+fNI@osflBtgf;^u7EPKPRoXy9Fd- zqi|v!DmD)!(F`|2ntxB4?fhz`_c~rA0W-_e`bzW;e$y(Fbky$1Ji8+;pFTonIiyQE zOG?0QFd-icRK19;CI+?RNQs>5H;KjG!3?bMroEa*!rdPwpYt0;j)jQwy7%AAEi12% z8w;DNyr!n(5qVW27Tz+!YwFSs`qGMwtXH!@GM*yInre|_;e^BeqH$eZ;fi}Tr-^G4 zwQy~<$gyw~TurKtKbB(Q)d+5S8sx@~vG4{VuYlY_%#}hmgWLvkhmZov@2ro7eI?)w zV(yK{!d{JjQ};utmUUL&v9PxYr&0C?%7i`;dYw3lTbX+sFc#a88(YjfUbt2zA0g-T zR8N0L#c7;-z2q@a>}rdpL)%gmr~;RwbE{hUbw8m2da4+#AxB{kDzLYX-Nf z{4Q1EyRnVh`AxOX2ABNl3fVfC*ZBrUQ2q@Ux2Y26b?zfU&p7gr6|#*$uUFZ~uQgH? z_NCC4K%Hge&tl{kxu3}Dl3uS}uVMhYS058Z)w7Ma^{O@4Z2WjUhC_Ofh!R7__lx@6g;u9nKX! ztCh{jxvSA{RbrD8NjGaPZ~Mx-i7!RhLUpFM!@f7t-HUanQh>ZR-R_ZUdL8#gP>g#R zijpz{L6owy|AOZwkQfZhS8_fpE}%*$rfiM{9cIaXTS+!C)nCaDC&@uT?!ZsQJY2n| z75oCx^n5WfHAQLGgFgZc)FUM{h<+*|(BMK<=pp z)|aIJ9AKk6P1iFu@C`oiY<$~d(aPza3Pi0U3olX-Ag4DgJyX*}YX%<(#7=r2*Orvs zi06XO0;0)?l8|A5Tx6Ef$~%^6W!&rWCwg9#It!M*$}37WOK#r-XyhohqiVx!i}93A zTchgqJX4eEpol~lgk9ZTB`bbLt3R0>Mmaux&28lKTgR0sz>g^QWU`B54o0c{fm|(l zKA9Y$K6)nj$)aiYelod(GXDekY9My~yPUw8v^&GI;758QS5H&q}#Hyq9RiWZMc$ZJ1e;yeJ%p^Tf0+7a+yQ;P*aPF&3cRc}W{`9})Qh;3dw0Ls>>w6ENBESDJPsG>zU$ z(~dqH5%ZEGVd)7^MlDBnK>GFoN=MXe$>cFhBX2CGTvNJ~>?nB)VA~Z)%Gy{;_S1svT<|l1 z|El22?^DtQvb4_=fxoE;{3c~q1#()}ev=rWrQw_4ul`>G*HE0z?F7D65xCh2 z{5J`|l0dDDHzx*YVLb4!yzv75tA-y@D{%1LWXDu@=ffa7vuQ z%_$Mrfo;wLnI`Jl1U`ZC5n$D{UoR6d=+d&J(3=b2Hi_6GNm96Q zHBsNd|4*QB3rOJ=iVYOjfow&f4`9;V%r+=yFD=wJ_d~!AiOh=#t1d#F4d;$PgCYuz zP!0fF1Qhy$oIv0hAk5_7S8kXpr0KiujcjEO|)i*glgFC z3msh}y8A+7qSp1j9{+;t$G9>#uAk!8&FYS&kNgz3&RaJhmVd|XQO@ge77-ics_MQq zCo9-h_eM+mR=c!swM+YUC9S?Fa8rB-rBzqEDQ;F@OM6SZw70ZNd#g)Zw-)}};`Ug` z;U!F$m&CO)_+X>^$d}*xAyShXWS7KiHOMy8YHtHJ^IQ_Q)k5?tU)M7lTw}F#ngC@u zU~|zW@hOtI6nrrdeUI?vUAeI#nzqwxdD`VouQ-iHc+(Met4?I0_3lNc#hIwNBCdxh z{kTyww2o&rlRRSoUl7qnF;^ga6%Z>j4V@CV$E+v8A5or4ru)VO5|O97fovXddy0&hbzImXu1(dya0(^s%)79t&SF}#>=dt6Wbrj#^#X~Hh?LHd=Al@^8oq`qr|J<} zjgHpH3D?MdNYfE$IES%brF%?uJfn7<4{;6Ln^q;oSQlCIm1D1Ixz?Vz~ zH$>4}UhyNU&2PP^bGZOFMOJ|5b-qnU7BRiwzA3WF{`;5}a z?q*xVF%)RHMYXVmVexKMx{SKp8RASJ+WBod8T30yS*eBHp{Zt`+Cobm1x=5HZM9JU zFqHm?DzZ3!{MLqRIp2kErLjc4fY| z*<`E8CdVd9Rs?eL0NE-UuBVLMdy{hPc=0AhO2 zG%T_gOS^+l2dd=FG2HdxYrroTO^+_kk=P%evX!S@}p--shYq*)^*$J6uQO|VuPLNq;SKJRE@ zx}I}sDyNaF!-zrFkB{0C5novX$^P+UB_eWJsa`El88!abjMo2Bn&KO0W|1Pd0jdt=^8;2LQ^CfHqUG@qp-nj_f}a2kzMazlE0mhv=-~)|CcFo6 z_H^}3Xpc4h^hWcUu#Z}=?k~(d&xKa=byKgQ;GxY-9J@>PUu!mzCT>HtEsAw+D)*6V z!@jzKt|Y@Vf!H!KTI;0T1AY_G&}|AWkR#%rFsDb-+}n710g2s_r;*@!#ly&bmb2M_ zt_A$oZ=1@Q%nFAplisAM19HD(ikTH|qr2A<@CAUaUS@^cE6r`-R{{2LHYYSY!}s8y z0(80~yj?<@IEQXxArB0`JH>6rYRdYRdd-u_v0igV7*pPp;hO|(S%++ZgU;d)cO=an ze|IF^KiV4F%W8BL&qn1jZRO+MPWk3`E0=Ff*iU)PLjDebm2XTqT;)3ed=X&%MYT?r z@{!aMX9(|>c4hv{gp~ozw1eFBlB;!KChVZe^4Fw49!}|DGiCWZ=QQAd3`Q&F6J)*% z@P%7M7vH9-FAgdypJD_dQ+=Vyb`%YX4ck3zwh8!9IQyjRid zgrJkE?Jd%608&4~qR6)9&|%bG{`_~bGz3LOTDk7-SuWS`z~<8MU91(P&pn7f!-L*- z1BNypi0L)Jh`>hRW#H$Erndnj0<+}23cg;n#n846>7}4JV52%4t^_8&le$W`MR-3 zc~Hy^QmT!Ih5(mJcC352MN?>_85M4|_cius0L2cP8aF$M-rwfNG7uZ>OZTDdv z?5?|H)JiH1sflf=yjg3Z&2zXrWY2ENsaGJ&6lOhDW_iuiS{O%tiP8LWrb`qH@0T$x zYAz?ZwnCQqzMLpEhDc@XRHeH<`99{{w(h#CHLIR85K2~PpJ71U@L^ieH0 zyvJ=5$bD+GX3@3>p8zBXd-l|zz{f~y%P#&NhbHF_^ZuVxggs4*6S28YrhoXY>-vd#-($>uBx;RypJ7 zoO0wJE0OI+PU>Xn92S9hYaOy*=rj@ zy%gUfL;nwxWE|Z^D-{1T%ASa2Uzo z)L@*X)Ngi^OmFVXvbuuM}c)|A&QR81`WokoY3YJgU0*89j}1(asc&Y6x44l;J3=mSp71j8;Sh`P}l_W z7=ed{d_AHpDC@Av

vOyk1uSxvNamQA#CmQD0Qjc8!?;Rs25#|6jPQzg(j&Nh^&i&Q@BU&!kFEs*Wjb=_A4`swF=m&(`>e!Wig1DxR(JQQC-_G|$$g zdA26avo(42YVPSt^K4C;XKV7PYe=3n&(@@QwkFp>NhO_U>mc)NO^nzkK%9BDX3VoS zW1g)U^K8w0NP^`V^K8wSXKThhTQla_nlaDTjCr}RTimyf>}}I^a$WHe!fw-b@}bm|gx#j=lIT%*mHdqE{x(n>lIT%t`ZR zPMSA!@^fMnN%Lk-nm2ROc{AIdtb*++$hQ0&nV~inWG5EY@Sbh&%uX^S$g-^`K!w=<+F ztH-VE_J-7i+Fy{JX-J({unh*;o&OY7^qgfeWj$vb5;)!F7{Y#G3E0JuxYKQ}AxWp( zu7;$YI=dN?4YkoAJI|1OsGSDc`GyojZ8ga5Zb((Ay$0Dm45&g&#=3KMkqRvgIKAjfIDV+H;Wo!I0^p zHXUUDU8|N_P_11D+0eJB<<-mf14}sUBCnHn9%R{hpvvk|af8kswmTUo%?&!aH=WH- zIydMZ6*uVI6-SA~+@O=r4LWr^lnLerox=@!H8&DFvOb3!w3xj}ZqWGZfw#tjSN zGGYq0`#(QprzBk3{h#07w&;7d`=4Fu%F6Bj&+lZX2LxH|{?E@c#O?mi&oRX9{?E_1 zG;a5Qeh)+3?*IH=#+J^?sW89K|Hs~YfZ0(Td*3~0=H%V8XQOskEA1+v3@8T>LJ~q` zkdOe0Bmoi`ycm&WlEGMDlVpUAu?Qj?gTW@63?|xOW0P%6FgY0z7?W(i-@kg!>=Bml zwZD7sd*AnYywB5TyQ-_JtE+o@YN~5`LP_S|{x2;wpzPZ3l1x`#fimh2xJEJ!L#Dce z{j9dP|LeL9@NfUu9oi}?|Mq{~QkzHq?f<%?ZG!u^|Lcx5pvmRcL*zwY?q=~)wU;Z%ECFbnK{}}Ku z{sTyN{>A?o$k!-XJO&Ci3Kow6|Kfl7qfiajgbEf1kO<{a`?Uav!>uXQmLGsvH;3|t z0O-!p5@rys{E4Zc)eZ|Ne^y#m%S|epdJ!cAi>p#cq+oHNdO>|61&fyn78lgFQNiM6 zg2gpax*`ROmkAaZG%%8XwM?-1{y;+_1&eb@8#F9Zuy~nZaZ!$l6f9mQSbQeX$VLT= zmkAb^l%u2jS5Zc=xG2X)OGHVqxS)xR1dEpm7FV^&jRcDW5Npjnw^703WrD>8O^y1h z7Qy0@d3vN^@iM{Uf;Nd1EM6v9TpVXa3KlODEH0Thk2V!Vu(+TtBL$0>2^JUS*3tc{ zN3gh{S&@Rp%TqlxH&U=TP=m_mMT=B#x-Z)`Qm}ZLU~%zW80{=Q5G*ce&*&u8BUoI} zB35A_g2knWy(0ySmsv3d?HgUFdIXD$a{oxd;$?!xKV$R`j1(+hCRkihcl4{*fe02C zv?N;e3J}5KTE&ixc6tejVDS%_okvGct88IVr*AkMA1NfJOtARoK;MY8+fgQ1{57DH zBSj&V2^L=kbZR6|U729<`+?4krmO-YSX_Ny5h+-_Ot841b0P(cmkAaZw32Td0ud~( zakwy=`9~mv#RaX36f9mQSX|IW(HnvY78i7}YuAO9eMq?N>*vyFem*~T9ZK}7>(JI} zyBMy61!$w9{Q=?$&L<3 zs_%La5w~rEu2o{K`0#q-!;SS|0mO$3$m^%{$Jbduda3(*Py`{xY}G0q#E8eC*t(<% z7$bH9u}w8%BM{q`^vn=bTm@pgY6|IWmUSqmkltoBtA{aS$2Zu2Y0;VyBZk9c`)VGt zn&y}uVv00Xc8C$ZJA$s#Q6P3~)|KTcrZ1%z!93!_ufW0FtWc2pp9L9xX*Q*K<63l{ zIH!YU)jOU0meP;Q>(Q-6aWwU}2KAy`M`c!}SqGZu1_zmqgtDtxKYU!2n@IgUTUY0( z$cCc%hAW_M4>AWN)OIEJyBSe;`dSa2qA%-j3^J!DsHV{L*a_i<9DS>;+3j$8k{*Fsx8^(3P= z++>NlCPj}oPOFpYxW3BGa@^!>W=cH~;Vp`dt$!-WYB;x3x%ItCF@E*iH3(QNtTooG zi0}GGgUok@vL99RUnEv*Df=-AOjUW=C(VD6G9C*u5381$u>WzbmKo@!OgOsw`%)rP zi^8_>Hkump4e)w^{&_vwSlSBNtX-(`6G20VD6BL6k^GUBbNf4YCAH+l zJ;IGT8!3AVe*UF`w7R3IJ`jKrR_R`>;cUPyOpCF+L$;7T1W zS*~p+LVYGO1=+ol?jy3}AUTR;3S0!$^OAbWLEY{x&*ujee!s#;Q{UQFhPla35g8p} zi-On!PRh9E38kV{DeiFcNr`2&Mkg58wgZCclMn^%8?T$`Ey1p!%}dtWZc@<%(4Am2 z>iQA#Ty?`psMZi=38Gk63GQ}3CO*$}@g3jf12lIlsi1JR?_~N*jE{i-L~7dy86U04 zcwVNT3Y*`;#ZIy&O1`)L<`=h8P|wwhI(B_#fGTxSq3=Ja)OIMXY+b2vudlE!#6wBe zqx+eG)^9a89ZLEgH)-Y4Y){`4$^+LGOZoQZmWbm?dj6(5P>ODym04nUhk@ZoV*9jSY}Qi|O5vuW_Yp6KOo8 zQCl&$iH2(789IsuVw-4+%7(sf`MFwkhYlvcZ8TK)Ub=#2MP~E%+Ln96?8sJCH?j=T zkccsG*OP*kC$#CM9!7tN>TSU=ZbTZb`qsjUK!=bD0}yDK=Xfjd&q$^!UGBqR@}+T3 zI{Q5K)MmbXjX_KFyeKZ@Dm0v~$|Jv2!Dh{n3lX7LsGG2k9yguz3T-j&bsgPm3w?j@ zgseUEcN95vdxv?|8S@yGdg)!5)nUIA35hsx?% z{5Jc5q;a}W9cf}*4|p!AOH0O)ZIW!*J48N^y0ra!lszDPAMg~RHb9(XO>@ryK1muU zd5<&M`~Ha#1k(5iq1qY|oEx7<*JCVes}_B5JN9M`(Id@8Mco@tp~fx;Deu}fv z9gJtpj%Pu+OEqqS)16jh1=Qam*%hVfWz#};lNAv5RG-mPa7}eVxP0r3Z%%czqt0UC z+FqfhH=!$h7x5nq>LuJNnmLa&L7j>B-rZK3UHY?r`B=ZPL2)8IZ1{qr8>sLTl8GhT zbv;Uaq^kZ|gpA29bChG@q!j*A?sOzLnm5k-z^E74U&7=*(r^{j4gm8m&?}_c^#SVN z#WWz*ZV1qqOgm}fOaT2!-`DapVlxm`@+$;9|3$ny%HB3HCz5$YVp@ogSFMb7E1Zgs z-|Q(goGksn#W>VwI6WD(BD|O=%G^$8vl2Z|jEYMv%s-g!M?eoAzD=|nE}tRlVOn$a z7q}nL@f(BUiEMN?EC)NC9jChZD6w;)-0e%Vn z^$1XVKfvW+FDAK3y1<{J=+`QG72s!}Z&J}jtp@tTICpsehDW!eKjJUB1R`%)DwkZI6arP_Ta2f$y8E>aXp1e zg)P2>6WwlK!in)AJvc;UWT1-$il_7^T+_x@k4hKDDVM1jY*}`jP z#9&RDgry$X%3X;#CWCI-1AA~*Q*v462lT+kWu{RO4!7D%t_Q`PV;lybani%&!9AP| zr$^8ezJ${~=es?)q{Xcre=KxAwK9vaGajP9zlYv%T9#S-2? zI?^9D553SMRl_1syTX4*(sq?{Bl2(e&PxSGb2#NoNH)&v@hc_e-|rdc=`oIRwzf6S z$%LMzr%L@@MG96n90PbF+>RqPoC0tjnX?6~0=S#Z&q%d;*XR{8&kNAk#J(W&8L2_f ze+{d-zmsgJwbw73$LDLtS!Jp)O56)FoFH>eA#xU7CD&OYSf5j?aQ?@@K&{`S6w| zAKo&>hqvUkcBfu%znXv0b+TaRszP0we5lLDQLZY~C8yzzLtSz!n6UBp4sunYF1b%& z7@rH5!&Gq5_RXvK$Br@$`FNKuZM>&FNGskaUm5f>ZM>&F9nNwDOl7?!J=LY z7WGo_Q7?o1cMY=R6a-TEKXag4E)IK{L>C764?g7PAE);1y9NdOu0i3ZYq6LTm)oxvo2DxmG{TQ{IMS z?)Ak<^KX``nt!KmFcl)#JncmO<;NT+vORu_Gi_{sH%h4cos)njwTVHOil905s0j(`@|97p8r$I9j9oNb>!P9kzdmPF(TNFs6sBoR3Rl877uNkoo-BqB#Z z5|JYyiO3OyLcpE{vmN?!?TNRMYR9%z;%x-=#M}ItdOh(rx^jEsZ3Oki+oW@>?Jbpf8!x z+KdLOoxo3Tt*z=G@73^Q>dHmSD7~wGClT#hAv#P%D)*EEUG2A}!Z_6Cnqg#w2R@ikQkQ37EkCb;T=xNfq>uG<7v)te^-;Yx zIPKQeeXh9zV`!Ww`4mJ_npr;xeC=?4jQtEUeyhZCQiH4A0%Y@jm$E%oT76!TDgA<~ ze&`QI^k0wgfZsc&L;}QLkMKagQ9&eeNug0eBrysKK4f?&~Qgsjsz}MmCgGd0x z+6R#UXiE4XlF}!(;`<BB*bRf=EgPk!aoa zK_n%DNCf#Hk`h5AhXMH@k`h5Af_xB3i69bD`XG`LK_s(*Mz$!3q(l&jr1U`~C4xvq z>4Qj01d#}u*mCF|j*wETHo1i$5`bFqn9`ykk`h5Af_xB3i69cm?1M;31d#~xK_n%D zNW{?xk(3A`k(54&q(l&jARk0hB8WtkK8U155Q!ikL{ggSAs<8n)SxmSL{cJ%M34_6 z;oLLh>4Qi(_{<<5L{cJ%MD6(?5>7rdJ@_CJPB=4YUkf5B5kw+NA4J0LapTT7Fnth7 zi69a|K8S>4%nb5DBqf4Kbbb0Dk`h5A+c4@rh@?ai$#0me$6F9di6D}TfP4^1i6D|` zQ2HQ}5qH*v+Bqf4K z1g)|lk`h5Af_xB3i69a|7rQQ9SUClel(w(`F(TAn$B$iy620m=v{lG1#+-skN(<}% zAo4#}$R&Rjxh5PReHG&a>$CKxwuT>LtiJV7y4=ebLUd%k&VH*M#m`tN#uNDVo>&FJ zH~liPJ!Q=nL{fTQ7nolNUaVdSJPIfpyNckX=I)X?Zr+$s=%JQ#PKg||NQl2P$qasOQWy-fmlJW)y_(+oS zhM{JQk0dEiHo!-cls7W6nnp#El&2WrBT32|8{i{J_!fp(H@Mmbv^GMKBy~iRXxSX0 zNRm1tNz_80_}efVzQNkBw#j363;R)zQawL*Z|kEiIAx4PM{O|0-?p+4Zh(DCTe?dW74L$xxRz1 z1UodkO1>t;CiHS}L@J zb%W#hk>$czTl#T*E3p8QB@Ij&r7b)LOi%loffS8hRRJD zdj9aC0h?&+zIj>D^;Z?jjN&UHIzMn(P7`6#JG_bmn_%U|_%2G?RallAthqA@|H8T? z3z$D8XRj9Q1H4$cZcZq(tK(>(Zc_gEi}`4J&Mt&2fG-i1&YL+kXBX6Mz&8u07adN^ z*~Ro2@UKbvo8ROWxtuM2e*ykLIE65tk+X%g_yI7f`KWY}a z+j7Nv`qmCv6R9|wVoe_TYK~}27)}CDqVZ^A2rzI4@#lR)E%Mrtcv0+)!@3 zzTCel8y)UO4K8npKLQ7C`q`LvD^C(k!&Yx zj4Z!t|6H*H(sO&66uuSzKJE4f@X}$#R?|x6*&a4Z18H=sjnWzTmTZ*v$aQLzHm0*< zNH$7)`BB;zcyHml-6B6qM*$r|G7T>F8cdIbsg%(MOH)RdDPtmN>&D@2J_vljaNTaG@9Q%_zad#)hxxvCT*C|-mLoV9bMFQ6!($!XOJmYOpNhNiu){PV zh+*(LAoR_2Fw>X+oetilTsqjF@_*F(kD&RFdq3naOzZ}F$a9R1@{gN<^@P@t>!XG7 z6Z-Q3slh@IbHlWj_4<$vH&TN|Am%0rHx77x;be$6=DM`-&H>&=xXG6ax1n%{0v{lp zVy>HV&03+p54>Es40KJo!NT1Qd=qI?iN-o3HTTL970H`$pkE;&9lJ=V;9JPdG|~Z8 zTy*@~UOOV%_?V-eBu;sWmPad6+C7Vw=T@Z3k2mXza9AijQW4ca<-iUOtF9yGG{&`J z##U!fMw24}gOztt*QUnmY^U;HAju~rQ_$+HDX7n%`LGqq6tp^P3fd5OoN!Xm2ibNh zV?OX4;iRAsvg3q13iuG=q@WM8W-D9({5|2MpbxYCq@V|YZzrLbkFvHPz6U~>wkQ7p8dJQLX#X`NSeICaw_ zq0!>8vtP&4;RBpI?9zvW{s3O5tZjL>DO3hsL+Wh$3)=xCQ|C9c>q>Ro0#6lA>ilMQ6X8w< zUP{VKohN6_<8uq}^`wE{7{Xh!G@5c_Hs`@7TRf0N_*S9) zRjnfgnshMTg1Ols=*=zJ=KS33`cg`3x0{=tCS}xVy`P)iLStU1^?q)4p7NctQg+Om zmC~t@!JV=Nap|1@7SFMMZo67tCj-WVnP!*P{*`8?WrylERHw;5Ej!jOm6b*|-SSxk zo1X1dbuOD3{<3icKA`=+#_2sc*~Qp5JIF3Zaq62LlW^*rotALw^qlJEQoSqNY54Fl z<=3~oqM^I8Q`D_iU7B6lt%SEO_V-;xiUF|{LlkfPne7)XvK4e1yI(e=KFjnobB`fh zpOmK5X|P5@V1p%uU!_&2GEIApM)tch_AE&GIiz5v4h=A-cV#-nbRQV*LNZJ6o{U+7 zX91r<${&jAex7Mkoy&nQCMAtuy+-4Pp3ME{?pT1s;vH4lDb^=tT&)cHA&QT_#*kem z(-<~+Or~oxU6Sc;+PSH^tu_dHI%+ky1y!WBQ{_sJH`mGC!MPllqGFqP=Vr`QcD;0j z_gpTCFm`uS*Y~1L)wNVpPc9A2=TJwh9921vsv!8D|dnU38v+415A9zZ+uwK5A3%t_8kObh;9rjqI`EBj7hhr$>orBYOtE=TlA!AejmI zhsb*U2=FgSwjw?k*^2l_;3rArmea;*>7(D|AegTrrDn%mB1!VPjW(xSw4yeA#%3(Z z4ZUr1JV`3m)IK!bp{d=El0Kx&gKx*9^>Uo?%k4b4I(HT|OX=e8scg&bIBJX{*>bxr znVAB#+;(FHY|RoI&O^ z0j~i3fXw$v<5i_C&j4NybSbH=8Q`a6t`*P^-~lqXlD1qI;2P+^O-MZ-u?K{BP+-^<%81O-)yzYtR$ZWQAfX@_8H=uftyB+ujQvZWl!G$J^&8W=Q5Xfobdg)66 z?}S%Z1h@oP($~WpTsoYfrMAdHqGc^V>W2lwh`84uQ1=v*sSC^GWO^U0e7k=v)0A+K zWZI18HX=0~g&0%9QCcMr0p5>fBQZ6!h3j14?~qKXQ^PJP^*-R+Mc3`7h5i8o=p|8U zY^I0a+wnJ^XGu1On|Ry|;3>kDX?2Fj9R$3GaC@-;ZR&A10{>XJUoq=vhPJpr5B!vH zI{kh#kE{8D2w>7yI#eNeCgjZ)dThhIl#GUXHXWCGY?w1##fQ88$v~e2kvuMojYy}= zy3AGJ?Bacuj4r42N5U{2R(V#HgFSutT;(xw(F(@TF}E}?G96^(8BC8RBW@4*y3z7o zSEO8KMul!xoGGp#Q?aOzV2bow#>_t@sF*5cyVLx5P&|mI1idwg>(ljqq>_&9J0%z) z586S%`w6G};wixd4eW`)$B`N~L+z&o(`0|G0{$MU<4qd+w%>cOIeDtzmH3FVr%5&$ zP7Q`=;J@io?m$w0SNNP7j1%s2;5UW)3PW&eu$gc>2Prp`RMX94%xQjiEwA6K1Y=*u}C zXLrl<1G`(!2~(W>NS(#VeSt6EA9#1tI8B{S)XTka*5))bkZW^2){++jGab%{=3LeN z8tuL4aSsFEOL9Y(P@~AGa4F1BnUCQ!@E?f&k#|u<%6N1{DYlcrT{WNcp*?O>;Ay1J zOW?b!$4yvGpV6~mGS5Y@(+C$I0XI9#g|>Wi-p$f!eX}yYTvtZrEI6(-tD`yp5`7Y5aMqBn zHNjeTXM=@Fw0z-;K+CUXQ2gG=I~BoE{4c%YUq#M8R%DeZcJsCa1Eb})9hV^*c@`CT zzIfeNa07Kc=`VB}!|u8u|1A*Nhxqv$j6No1ZwKf~Gkm0sXtlU_(dAt~pJIuMaqmS3 z2OLbqu5Dmo$J!OFQ8Zh2Y|vlVZL6-$vBA1#noc^8N&B*fdvp5TZ{m-E`pRM6Z|I$5 zhl{A+w(xp+l4W%*ywWb(Ve*~4vVk5W`{~MlWri;7eqSN`YOAtace~(qTcEc&IZrg> z8@7(akMLS%sG$L}ot$iY#A7=Ia6!S$+wb z3k4{${0=fV3s7YFi)5Y>@CZOTi_%DK&j3syGfse_%(o;nl{EY$fb@+L1U>DF7@D@c zQc(62yCSTr0*F1RnUk${x>|x@l($$c?N17;(#_4ZBpOdV?nj9Y#CXEtXm!1k6 zDdtqFBQ4+Jk|U@%7qq5;+2~WtQZJ5Sw~oAC`%>0qy^u3C`#7lHFl-jnj{rucpq^Y( z>)L7=2Yw7`xHejbYtyB;ByQ9i+)53)b@aO6(ctGA=MRQc`vp+jQF9Yg_HBR@$Q&&| zU(&dU%(()h7QBRH?hzm#;(KJ?6wm?Clux-Fsci_r3^G$lvquA5eb=#*r|>^3xA!h! z=aVwuiDk>2PsR+S>&ZwLk0Fz$l`Y)zi_hsXnoUnL_|1jIbuX;wt9Tn#HPpUZS*oIX zyz@k-<;-ww#c*R}dD60;od)U<1lfjKBXE0*)rKboF_H>-`+4zP|-O{N1=+=+ado#zh}u zoURHnF8UDTbXACP(T5nPt3r&6KE$}_LyXfj=;9FLq7N}H`Vixy4>4ZfhZs}ViCF14 ztauf*iaxA(WR$K7D^90bt>dubbX8b!x+<(V{Ry?>uwrCh4b&=B&Z&hse)u5}={SD) zcID&v;TM&Udo3=c3C^jE^CL`Wna6L`J8?6a)sTG zXL($jwZrVPc9>n(4ztVJVRl(N%r0w(*=6l8yR02%m$k#}vi>l;^cl+-)P;mZ(Y}xB z&CX|2)@WS9 z9)UgyoqaS{fLBeRC*|y82Ka;XvcGFoNhvsp+kW;BR#NA3qiLZu?L>N)8*{%}R-|rj ztbdu(r4^~0o78p{C9Nv%xQXIT5h_3a6Ts-z$H_;3<~I}l9RKWkZj@qq^PH+D@>UV` z)kmZAd^9@4OzOKIJQ7AA)4z^-IbzQw6SBRZvX_lnc(^>P>J{G8%+1MJ+r;wF}l z0-d{8oMAvF(AjpyO%2EeI(M%)(||%CJHNP@0X2cn-79WxKq=6Hjl`P7)_`1Fe9Vp7T_-@PB83GsR+`Zxl2H3fK#lKj7WT12Rik}&@^V!s37<9|xSf6wGM3f;X?>+`U^^@a?0kgaM1zWpwNwr|#J-&nOC* zAYcKxw)orQ0%|fkbdNLl?xcP>qcit7a_?n;rp(?j;KaSgESEt>C+>0J-b8?o%nrZj z_UM5w`+hWWf3R@_GdgaM)Ao*qY)Iy~%eke*-yF~AuszP&QwYo0w#p~R1&z<>tUZp} zJDo}sGdgN-VPIGHl#CVu4%*Xozi~zf?QzcD`H)R*t9));Mbk4nXOCm{=2A4nwMsMT z_-o@jSTFY|KYg?Ut79pxNh#A&I$DMb?y7%JL^>43h)Qs=a!)DH<$g=0v|@kx+IT0J z+(3SeTq@}ycWK4`^0o09BHDtVfs!h2PqDvzZG5517V~2aq%6V1(zS{V zXE~^!>bb#b*QvYHk1H^rA<)uPvSapY$2|hxmciQbc1jVF>zKXTjk>O*q-4kJ)o!tG z4k{h9SG!dx?k*U6Ilwjs1i=||0JgI;o%}I-wX+T2;>GJ!JI8=bkhun6zSYSEKfyw% z-Nk@>@cI(~yBV23X0LWZD9LI9ef_a^p#f#r`ix|{@(Lzd>3|0%(=cQz9qeauP@qiuedg98K{Ye19Bsh{iUn7z{R?FW%BeeE`? z*Ntn>Ba0qY>c*Rp&g80_U_iz<`z)8_>t@H06Wqq^ho9n8>>Qh3?il0`sPPXscT7c!9oeN?+A8b>SIO(u|gX)Sr+_soiP=DqhT z&%4(^*kqrlO^=d1!K|k7&x&SigJ#zq&(z7JZNgv8GtCc4uHjqs?wv@}QGZ{G#N$69Wns`ikt z_6k*=C*_}pL=$ua2twPVsDBxhKIsU^6I_V@Wn@VBPi_c4x9hIN?-~W?Kr+!7UqZcF zF}@(`u+^iGa-YJu?vWR8P5Z|Bf$JpI|CDN)?Y<%6C4WfdRur5H8Z2VI0=ItR_N}O0 z+|Zq@#cxH!bqxozn{*L>E1IAyG}zv?@B5D8^HGgG^TD7{iW%%5b$JG^;dd;^Vd>1r^!AcRC4q7T*D9B7| zi6&{Xz7MZANUq`2EAc9YYGWbcoLp4Y{VtEj)~!oI(_fz=Et9NUmxLqLt=Yia2&Zmc z5>8RK4g}tlWZk+fw3&52@CxCM#-zDCv?cXH;5$egtYm(iwgpW-5!P&|%-}1*tfuHq z(%|a=M%1L-K+@zp0IoztBy2e8Dm=?63ElCo4(*iC*Ve~E-1k zb@!sIhftvG73+p7{VhZ;n)#u)GWi4>YYzU@>itvgup|&P*&bj>F zFwtbt*%zWaoL_m-UH(W)w03{wOG2D+x=bg!{I@94ir+%tR43Qp3b=m5!tq@0D=F74 zWK>*k*SG4s{1p^w-P_z3rNiA7kz2kNwAS1FZEu;w+Sf5=DdR4pu} zTtKQ{LHoLzY&g&o;%jffHM|MGoQZf9Bqy7QBO7B8b17Q{Tj5YcLd0BZJ&8CMXe!A> z%%}ROt(CxM3MUcsso@gwSHSm@EJ&s$p$-Ov4-_D{*{>`S%G|&JZ7l-uXs=G&ITyF3_fK_2=x4WlR zY)*p3F{Gh7Yv`V#8km~^FDLcV)q1a8tRDitM>1#qeYQxo5iOV{_0sV}_qAz$bOY`# z)KIRw`;F>W!0Sln+JC?d%0B=;BP#oryV-Fc1Fjb8kgGV*#4hsIdiFL*y_Vg;l3}PR zfTKxM78C3f{5UX$Z7gp^@Y5ies&3iezFUCF28A1%oa=uE*kh=47^(j^04^nSo`9nO z9wKu$$=}3v4bly+Q8K@!wub1ixKQ?t7E&{Tl8ljSImy7ylk2jd=K09T>Rh8>qMIfj ztR>S7uSk`6df3j~Jhrxtr);+!lB#}`W#RR-F$PEX7!-Yi3>4iJM(Fl^!eEWW2#w|m z8)!7AOQ*pJGeqTvZ$X7cn(hx!Vcmn>-Zmubs^&g6V4LXUg~5J-8$$HH+i3=Oj}9tg zAW)&aC7{ePH$ztT;Up&Trd+IY_&)d<`ZkB}NmM-ts&%&Hhri1ggf6Ob_!hjwH>z^@ z7QDl^;GMit?BrcQ<$`ze7QB-;ik-Yisl+>Z3*O0F@J`+V-pNauoV-!&t7^Kz#cymVx1^<@A8P?qS(F5WOPyN-hD{< z*rodf`Id@HcO`;l%%z(*mu}u%x_NWy=FO#>HE_L)n>Uwk-dwtQbLr+E z{Sjwq=gp;?H?Z~ZhP#~jbfMX3)Cr&e}U!iofbB+ymy@zW*FdIr-e-o@UGLs zOar{@w6K{0-gR2o+yL)7Eo@a5)V1Rd>7IrkiyG{!`8Q@)~g?R>e*J)wC0p4|5*x3N@ zIxXyCfOnl1b~V7eP7Avk;9aMM-3@5xND7_`uPVHLfw~~qY2n?LUor&Vbz1nq0CSxd z{$hFWIxT!=fOnl1zG&7+Eo_kMw1DeW432J)>$HIDRL}}O3U&j`ah*z8y(*5;;sp-^ zW|l6a#Z2rNeFV%9bBq>ojQ)|uGppSQ9HXLj+1N392W+Ek>=+f0YrrvDeMg??bn=t!vjOr2@n2jBy`n1WAZ0s0i zd37VRv13&8b8LegqeVVKB4~Uzc8uOgrHR?tF{*21N;Y;Xbs-bT8mrhw7(#ZgASQz6kte1tx&`bF`eRnbr$?G3Y;)o=y){ z#RY%cA7B#$0(0=y%m}6SRGtF(nPM0SI`m0w9XEs%UzC0-!o538t3(LBDTE%xIH!92cvSjFo=9$!AJBEWlm`LK%V zpz>iA0p8=whgAf4k1roqQ62B`<-;lhyvLUhtB5T5u!v z`C571%G2t^@;%_tW^U=`=dh%Ltfqf6#+IMdmQxGX4VTlMuU4;Km$x*^Z4*kHllG(D zn+p7ob)&ZPChkmIX2ohh)mbefL9X;OTqMJM!{12QsbM!<&a#GOLDxCLYke5uO7iL9 z(o-wfCFCoCaH3<>HFnw(^O%Zsarl<3yd+;Gu1a0lAE;a=g9#DJ2yi92D)Cf`b%{q$ zuL56H-aMRnDjHZRan3weD2K^-4pRwKFC-v?>m1RL}iVZxLkb3JX9V^TLpia_yhqz$JpsZ>e15O|{ zpL;VlZqOj6y8`bl+=pmyUeL4}+&;jIN$c-%1#Qm{O0p4B%NI54Cb6@>Ei9qDTlHR| z-Y$Lt{wDA@Na<~nTl(D)W+@&fa{W^{5|)tnUV-%P5NIg3_XO$iR6Y8qj|Hs>w=}MI z7&Qo^pPQj#w48^8R4@mpL;76keh1y@G2QY-F8xz*nru4XLTxU=I)5CT{CLk+^Wz}| zc60}3oGY60k=guHeD^t4*{J8Ei##py7#nbS3x(>mGl8OqxvcpU;g5dn&-~*`<~}FHt5or-9ybg zJioEQcrB{W06igos`4d%JRFU@9DczpW7q|QVC6(8`*gcmZQ}PSHQy%n(WBC=VY>Fl zH!@2|<^EF{5xWuY0l1S;PcXVWwu!@Xz;6qcW^(RiE6g>3KNM;pP0q7*=9hpEk@{+* zXnwOU_vZkgC3R{~-7mJCzlW_J$GDoJEzxp`IDxOaRV|Y6eP~}Jl{b8W(X7)F(13AU zCUN)0XTX4-R%=5OOi5;xN;F{ls7pL(M!gZD-)1;@vP3T5lND*rcq$>cnN}&%3iN(; zk*1R=yfP_(*>pkn!;yW|R~Hkw^jMvi#gOy11|xeWCi!Gu+S?wkpE|0g#JZrB=B${hCcFwI;pJb#X)(Jy!O^%Tbwd3_QsUX` z%CtgN`y?q`Lqk$tBO0lQy(UL}VAGfUz1DIvEk;)&r*CBS_U=F|P=@BYbCb*X$zO)5C_<49Jl{ImLzrn$mR}mdS1HtX#rwDOVQvX+) z9eut^(IpSBi7Y=Q`t!qn{CjQ9qCUR`chcu;B6F|7I5;lc9nDJc7RjIt2ZyQTsPJ-1 zB+tl-bZ+P$Rk9!yc4mUjt$;9?AAUl2#9(0$Co7o~o?Iz^na*>w;t^iCH3wbPr>J79Q&9Sg;3^r%qFa{GR07lwbcqx{`XhXjeg`X{A5EWv5xu`8Z0t zGZ-xmZo$&EDQV>IrSH2uGMHUE2O;kb8Z_Z{p?E%t&mO}j()`okll%`>YL<*zuwbbR z`UV?}hG939i%6Z{XXbSVooa9u@b^izYNTJ#Ta_LFzEij>pzH5(e+GU>xVP!R0FN7h z8hevU3l<#Z1_o`?$}YfLc-)cLV}`pN_$*TGozxxVai0ReO=>!YHRg}p1z~c8J0$23 zlW|PL;Uv~L9!XiQu7N?-x0+h?^+7&R8@` zfsxjlZ++m(_lwU;eT1~|7PI*0Fyn;3YlJb+C8e<-Djv-pf)EJ zG+XW;r^#{@;31?gO_m33uAB$>eNyv0dee0gq;GX-u3ZQ28dB3@@K@1(izdmtT`GGJ z{Jo_7?~qW#wSsbKQw9R|CNcb(KT%Xs@(~HzH6H>yn{VmBcs&cBr^T!Mp|9}5-}4$s zQDs(C@j^{nclBrLUa9s>C%2E0nD4{(9a2HPy`xQ6My{3Do=CLeCni$Iwxo7H;HX7< zF0!u&L9p^HIQEm4FPSKg!7Sr-X25G65o`pEO|X+DR0;OYb;Ro%@Hv`ff}L!FT?Tjw z$@SO$V>*>t)Q;rFG1Bf8k!IcrF!$mv<)4Xr)G*Dh>!^4QDRVLuDvOoI!f7{^s}pt$ z*0-zwLJ++)UG^5}23Y1o#Dw-!B0~p|TzU z>|UfR%J*lo3E&%?=^LzhkxHSiOCt%7Z9i0OYAzCb>jd5H(c{Hle?v%|az%MI&Cgpj z{|C~9O1aybiOj9fN(Z*3TsvuEJ)|nAZ%_uz3=)5nq_z)vei?0Sv)=$bl%jn|8=MJH zLbV0To}*s<*&xoRhxRK%?lO{{wmBRW}08fH_RF(M?tZkOP zQoM!u)jwl*-1QONV=H17mlfutd!RdXjsAX{*S<&U$zGE{r{j2cfA3BEdvEPHIHdLo zJVhLU9|zr60`2V{pN@m;{XIVI@A3J^Idv;suf!9g%l{BD!X=h(io#37dqI}ghyCR> z+ba9nht6HmD6Grw$*@2Oys=oVUx2K16$Q206d)@bY*TwKS`syh}aGO(B|{7jS&t z-(WFE;=7>kSg3YXo^7J6wu+8`#JbeUC)QwpYP9psVrL56r9pX@+EGI6no<9v)D3EA zxBTs@n0iCN?p==ooa{m|%Ra)7Qp`2{E&0|^dMebxCl@XKf_&h7 z_6@jjPf*1ggn93%V9N-xpCf-v;HOM5>T?#ppm;`xD#2-=2xt;l~xLE(LXA;B-{^>SZnM392r3J;77zDdd1zM-)}fs*e9jUQ2GVsJTqI43B71~573 zPs#T^+0@`0l&lPDid^+G0*%3iL8J7(dGIb`uL>HZ)~$oD!1|J)yd%API+zP^saL|w z!Cr8?Ea=q?gV%!=fXhAWx3QpE%?m@2y*s*PIla#;pi{RtnAS53zUm@QlhUYWumq#q zEuTx>^$M6f^7~OxlREfQfIAH+WfttYw~Owoe;R?xsa9l&?zTFusj=q(+}ohx>PYRQ zk_QW#UtOtpy8(XD=Pp_wm|E|v01x+h9bic6V&sZ`U0b9_BU0D&pMBsP5@Ya=~lJwpY-kDm5bqbDzyX1cW)!?n#REN16WmCZgFMg_ECo0?$fP?@zU6_z z1&Gn@$%X_Y01olM$l!EE<6Qe>v7ig?nh}TL?}I! zwU*e3y6{yYWs--N(5bSPf_VI8-|?9aeuhKSF`15J1_wD!!3{-a6LMWt8|laO*%pFm zGSP*Mc;5j}LA|rB^A*b>SlM~73r3Yi{Wt85k4arOJ%IK`=Y{LlPM{H~-_DpCYN7w0 zWZKEpn?JkWBAg(64YNl^%1lJ*Wk$;9XirAUA}X8oDF+C(M90F`huR2^YUUWt6QGpq-it(}!VteBy8WLOvfmtsR=8FJtzC>%-FA)Ze zU1=`VqzlE>8!*v~;3IL61ruSy2=FFMgbgFe+b|JE%w80EBPPO%IT8pfM#v0z;x(+8 zXtzL)EHh)GHSCyZ4MQec!;*r>8#9g6T(cDc%t$eCqI!N?OTq2bp1q%Z2-HS&C};BN=JLg{F-g$jQ_@7{@_mrrvBC`#NdR zlF$X-bPK#oDex{O)V>b20`F1^yh|zYeyPBFmT))8G^9-7yO^}LQFH>e4ku-toh|@Z z?F6O1#!vPXVsuh7J5(Hs?h;aNH-22;QfKimzlrL>VBlK$0 z-{_$_cqJWZ@Phou&NC_EUp7(;vGa_l8&`;(XUaFqD!rLZ>^z&UthY*qb=e*Hd61M- zv!QE}Rr)sBwK~tvp&)XF*ms#Kd{_007Q2G0Wb~k5bGv zyq|opP|&Pvf5Lh8 zDC>DwYsDIU0w{5wX_MriaGt55#Ci56brR>?BaJ{b^eN&zxskmJ<6@Kw^JB4A-?g&oo?# z{i*qt*q`zwB=+aC0Ezwi1wdkdDi$}fKh;j+Jd@08cb+M9H?cq01xV~qF<86v?095L z>`yH#iSta0)WWqm&!o{v{fpGE$iPA5TzCZ~vHjVmd?-zu(fHJwbqw@%Aa=!hb}Z!;=b7?rcb?f5 zY z66cw!U@Zw(ah~bRa~0>AMkaBdX*3h(nSjK3CLnR1ss7rXXCh0SX95!EnSjK3CLnR1 z3BbzKT=*r7t;bo{ZdRrcq4Z#z%Qm7eRGeaXGRRQ3n6j3Fc>E(S>hMDq>pYI$72lX$ zXR(F1F(egZAXq7=PxNOt?Z|k`5671`A{ONWH{6Vf)42ykpCKBA6S+w4<6wa}`lVR4 z8<+Q%P2O8Qd2itKUBheTO{cs!o$}sv%6ro(?@cF|DB>pXZKh(?Zd|cyH*Vd^Zd_;2 zZd_;8Zd}ctbmwtW?IiWft@lst#uck}16H`Xa4J7Lzt8HvyOkjBacedw7CKkq# zk|DM*lus-S0mpY$dA_=;Jzq8Q@tzEcb*a;pVhiITv5PGX<=1Xu{ECvq!gv|rWEY89 z&2#)H#ayG8$d8Jor&4TT==j`QX*rAI*jCTbEf?@TpU>NTT?#GhQHM(Nh=%s;y zVZ1ANEWnVkdRH*4-W3evT|qT8HjH-#Po&PoFy0kB8DMf4?+S`+Y8dYdogvm3yep_Dyw}5cS5U0qcG0P*vQ;`P#nw$<@HULM zRt;mkHE6^5pKcBMVZ5t)81Jqg#(VuRu61j08(L4So5KJS>*gGQ#Jc$jz{qU8HK^$_ z7QnU!HT5O~{QcJ8jnql3oBIJa%f?%SVz74W=2Yf)V%;cSFtKiAyL`#IX&3}fY7L~% zK-X+wpztn|caP;=&#JprGhFtp#o30R3yquF+C(M zIuF=Ze0A8ab6%C-6T&AeFndE4@7lA7-4bsNDoi=l(t>YIc^6i14Tka7pj}oj(v*wD zu_fLb+*7q<>qdDO##@5|GGX=BV7SKCAjcB3p$1VbYfHQ}sH3RDcx&)N6w9ri9khx^ zEsVDYRgw$itwB|(ad@H;E8ZHM%LNd|TZ0-I7glc#hSghxVfEHv7;g=#en(inH5gWJ z4TjZQgJJd7U|7917_PB3SfjbH2*%dqtQ#ZiCK4i&9{OoPu@QCAp+fcp8R_=cPwPQE z{^zOWH2vI6apMr8AEI9e{k0@FeuKD(=+PMX99t#&O$=-$U~JguDaO6{vw4in^s+{= zzb44IV0~OfnOCUoG6PxSgUlWLrZSEEhM5Db?u_l`x^(71Xfm0z!DKU=O=So&jR=tU ze5MDdh|lhny37iGgUmSSQ<>-a4Kr8p8)asKPiGdwIg{Cr-)yEEOfEB)(tM^CZiURx ze}j~nC&1LWw#(^jI{f^Ipxk!7WuH~{Zp+?AwzL>7#|KCLhPG2FcDsY4%9^Dv^%V+& zrMcfjT6T@+N+1qgm5DN76~M?qUW&%UgdY{-j|LcJ`0^sM*<0!c!Ks6YFMp{i$H4Gw z*WgGM=*LBBWn9J9)T+>aAI(qRUKDD_wciB8F?%L(c?0^Fz1|u)M%ZL2apf-5kiD*~ z%l@J@ih`b%pnSFJU)v=CA6S#9XIUwqEutS8(c5bh^{iLr*&@2tB*_*lk|^h*8h)*- zT}grUci?JzlQ}0ytNF=mmbJeLzu{X8sUL^ao)OTA0=a&9t(AwU$QDi24$R#+P<~lX z*R)OU(-MYO*0eFI+&5sGx!kG>D<7sjw;td)`cyZTOhD!yu<2lSIy?#!-Q^~NKBflx zrcID%VNg!0XTj!L09Pv0PDXqRU1Y?^cmyx|3ac1E3w$z2vKa&8C8Nv}L@F zm2F%p+a_qVvZi+_n;Co#6SyGp?rJIeh@)3%z%>n{cxv!=QY<-h9|CH=xTZsBbpwSg z#kEb&mjQk48z~+eJe(BYs@jiNYWLoq;^^wS8d_UojXzV1ckod6=Qd5TU*HD5hcy1# zI-CKbA?YED^da@yyW5?e7vWYwn+kKV`>q*L2LS9L#6IqOc4s~tU^!{xsgKe0mBIC}&YjGU z=11K*WHb}*M_%>zaB%m4)7ANVj|-PPt-gZPgsXdw%xp?^E`}su@&f<#f|Jxf(bauK zxrFZH%XwkYCIW#eTq$;G4S9xT;8J)qWSi zEhIYi^>&dy5AY1B?jks7WjNipCOy(zc-ZlLz~pAiB&m&JSyGHd#_+KB;22%W%HJ`U z(Ktj?vyX=A5PunVyoz{xXrdc-j~Lqq?Jk+IN%m-c_)Epy&I|ts}dXP|CCn1MiDq{6Tsfn&9r#AwxRpp|4H<$f*u39ZzR z1~rj-qe;V5zAxqWL!L#(2}VDy{}?q}0Z)hW~#XDYdby;lFJor8ago z{MR;8YGYT!{|g%_U2ATnG-y+Hts5x~|8OIv5W5YuwbiI6#z``G4#yJMfd9eD8+ib3 zlI=CAuNKbRFe`2*HBZE5*x=U`J`D6ADUZcFx#1UJo&|bZn1kI$WpR5K;58w1&cH^E zLY4aRJ{c*$50N&SKSKZpl3K2$>5z9AOIWVFuUhgi`}?gwaraw)%5nH4zo8^-)MI_8 z7|Vtk&;MYh4nZ)0Z$WZA2-k>{|Ug4NG-hUQ;}Tf6L^u;P~@eRK<*`4m-Y3hT0X>VJ5V>H$-_yX z9nG6nK71wPcbhVPw<+Uyn-Z&Q9oTR#&s+8{_lExY-KLD+ZOZuFCYWfqDdTsWD&Z@8 zL0$=8QNBf1*R^C~t4pIE2UQE}vfJ`=7b&M^Lp~@^_{z&rC=J;VX9m zwI){A{y>%Rl@ z7jG^p?<((psomt=uOF&n<=wA40SI3av+U3KQHr^ScaU!nrKd{x%3I_sn@h?kn@iS! z3pI7}@#fN=crw#|bIC~4esjqv(|&VF`DAlR0in@g&bY%X2R zW!~XR??F(Bnh~lJH6vPAdFAXctT{>4jDRF+MnDoZqdLheXT2y%qGqh+$}49Al2^`V zXo2ZnG4{3qN}^`w10+#1s+7EPCLnp`ObsPbGrLnKiJI99Ac>k0SrRoP-*OT)qv1}X zW;B{f)XW{!Nup-d)g)@>7#Ji`Gh$8D3ih#>wW=EP!Nl=}>@VbLmuok?DAI zN$rdUu+1gOJQ=_?mn8Jm%6n(asgrCjtpeCA9d9m)L9)4|I>~!yM*<`kpO&;_b4d&2 z!b<3j>g?-k^-pSz)W1mmiVPHH;jJwo!B7%)33dERBVuczxMv`*WNYr{;AjA`~3U0 z_kX|kZtvRv{cG=i&HVT;z4qR@&R;R|M%RwQLZ~_ep-X`RnPDZx59sZ$o|obI2Kb+W zTru3z;eo07Gv{1~p7M@S71LLp9#zapcT-kaigqXwLD z8BMKYP01SZZ0bK=Ojw4!OaC_2Ulog+D=h9HBY`U{+)3JtmVLu1BYn)isk|}&D5N7< z@wYlIbTuzr#GPz;JA2)(ueWt-;-KP9L9KOj?O)zc>x>#J`*C7g6NeSEPwZ;quwv!A zWbOQxOfMf+e44U8tXNoA*n^)xl8WLIx_+{D6p34L^r#bwqvxmOBUclL6{}iJ98`P^ z`EtCurr=@!meST>p^4o*@{X5dH_s2$gn22(H!5FwOG(WoZXN-Nn@2$6<`Gai;^#uD zS~AufNMbk7=oGDOr~s`gc~wo^JOUCokATF@BOr0}2uR#K0uncmfW+1j zkk~o`x?KOn);Ux%#4*ImC$^4&<6A9;Sm8`AXtfw(<(b)qZ-Y7!66;c@E61B_dOoeV zd6ZAwJZd*_^C;Xjaq~P6fSX6m3eWJP6mt!qBR?RNp33p&S`lNv;^t94ar0OMF5Cl@ z-(2JE`GYIQj^3UZfwy+__WVs5^+WNzdV5|_&)f5YdfuK_J@0jicza%NDEGWQuQGqs zkKUda+O|dtOgxJ#Wvep7*^(yge_-J74tnyxQw|dwwkSdfuL& z^#8HUq0u3&U4Or z9-zYOdB)TNm=N!lDCsG@o)@u!X#L^qd3Lpy!Gw4{&)c3_2*cO&Ym|-R zCxY38(wzt7)>1BiE8^pa0eo;qRj9)M-f?0%W z>q9rZp1%VT-0OJ)Erj9gd6ucAFnm2PUz!Ry=>q1e58m*4-ly2)9E!Q|dY+*0dY-88 zdj4nx6<*Ju1(a8563Y?IR9c_D;r09!=1O4v^KW z>v^KW>vy|CKe`;J*!uHwCPc_lz(7ro5Yop4BMy$`H}}jYdgtXNEneQPz8kVb5!n z_eK%Dpi!llCwft%TJKS&+o(~acO%hD8Z~=&Gv;qKYEe1+u75a=vD~}<9nhW1z3V3m ztIWH8#!FV2cl`tyUAC%XPjGsC*H2o-*(|bKLO^;PD0ARicW17iDjAE=of7$jK#PLr z3e{ZF3zfPlQGF^RL_s4d0}$tCOL?Onl+}oHTcU&$CJJg9=LArGWaHE}fbten{n%0( zNg0ng_athkpo&rO7V@bkrwSp?M<~7URjchTLBzzjO1OMf<8qY_Y6Vi&$05aDUarlO zRrLd)jPr6-d9J5I8yQ`%E|p?>%Pe}!Uc~*adeJ_>#i6DNw-Mp$M|~BOm)*Jt(2j7W z6Omy{DmMz1IurP4(q^GXy;Bv8_X_YMaAk96ouFD%InMX9n_)!}u58BK1!}ugj@?|- z1N!LUN*}|dY}5J820o0mLs3SbRE})p)xe8M+Xz};o!==veRTp{>7|I!FI9Fb{`&^- z1*FBOOMe~jLEwAf%H|wDOAXLvyb1gQX)|WdQv)?^XfI#2!j&DP2Bk8r-DyAzNLesL z4b~028}Kf;KJ2MGJ_LWD#_o-ttV~B2fzt3E{yd2ARd5Zj0z3`RI=H@!7W-h>-vRmq zTwDs!+5$EIaB%~`f$;23upPja@LWo;J-~zT+)JKoyI$agfDr8|)R(u})7cm|s;PSVB4(eo7Tcqgs zzs5hy@F$&lVGh>yW>GX^tK%&T_DAi8<*E7uBR>UTc*!>jCT9CQfd58_^0r!N*-XQQ zvlcB@JEpJ>s40N^kwohhqvY%B1UwTCH>SC6p(E}?N9chd+*XvpZbiR^ zyG}JgFE^sa7X_v$Q}Jt!K^#_$5CqG z=%3Nt(Lc4{xTAmeyF2=4x4NVMgA;bwiA^V)>W==oZ+1uj%oW0Jr5FgzwsIIk{?0w_8r8IYQq7V~>VxpH`S5 zkilB-h1qg8QU^xBp3XAtl`Yc<)M-{T-ouP{A>y$Mit;AOC`@?UX2p&vL{UK%uqeo2 zgXLQTcfv1cKZ~&sv0KhbsJ1=z=XsSq^{3yR`nR%Ft8G@kC>3zF13Bxm{Wg-xKn>7!8U|6d+PrP zb1_d!IWq3lpQGtc{R!NuKY=^-XL@()&ywA#Kcl%*e*$;vPvB1d3EZha0mSZ{3(p~A zX>qK&$;Og|fc=o?S|TH=g4ap>7Kj0VV)9%H%=pVbl$+n69dWvMf*bH!JpSG_U7`K_ zkt~zZZkjmf0GF`3jiCevh= zg8l2rj3Ia4o=g_qo(u<;oP`j%JsB<*|8`-xJa`_&W-U}dm|iVZClxyY{P`nXf>j7q zTQa;Zg(Cya+=RuN^TV5?RfuD5PlmUMIlw+)-zlR&%qz;a`u!faGrMt=l;{MDs->!0 zg-4>tRD`5XP>CK5`!b5YR2lWEp*&n`?1+Xw0Kfb~N5d=VS1DYojEWWNN5u;Dqhf{n zkx{6h!llY+WM&PLSE^_Z{)<_=^>ETmlqM`rGo}S*0D(R9+&}eR#0G1Sj_@qhg)<(IF|`LeyMNbZBz|zd+}zh?&Kh z2Am2u*N7%%`bX?4t+XRLi6%va%ZW}dqhE75k=3amaZ=To*DR;vtLjpF#zR;Woc0U? zr#*w9YwZ~{p1Td&GpLZUc>u-i5p?QP?V;12u^eCSXE0ia z)t>PHLY(#tj)Bvj!ESZhGtNWnoc0Vh)oIW81u}5jGnn-onEB{ltvDlExdx;ZuBb-$ zmP@ava78sTiZfEUq8b$|&WP?$Q9Pmr>(K)ON>aR{8m%s)j9YU#QL*BTXiYhXOLIBV z+BD~v7OY1PcY6n=Yc3~xq+0{(t+|}&@f?4qHJ1}Tk@^xqdy01(qo<^tp#Z4!da3hh z093kIr+&1dY#P#NE+=}XY(BuADc)_2o|6nTmlGB1)Q>i%m!ol-%ZdJw<;tSDoaogO zE??7y%ZaQ`{d_B8vqwX=FJ!wyfuyVG4+z1!`!@Uo>5tgclBOD!DM}+yr+Jg{K484t zk&InX6ptkRD;G5*M6zPX6r!kTH(*(Q*+BN1i%PNFh z#ToQ>tvExzC>3$G;lo5~^O_~e-($+uAyTK`Db65piZf0{K-MbGxEcUl4r#TF#GeYh zq&2TuzRV2G-9}llyHuRP5T`hUNwO*;t;W1&+00xFm&1`!R&fSLGqj2`2(ngj20^7& zoWb;6E6!lFHmf*;pxr9YAQ)*CXApE)#Tf+PayS>#_$Z~tvFbrCXTBHT!S%&|3-aIi z&dg+prJ!p9(!Thv%*6m3{VF7n@6Ox@u*pAC0o;>rMXXo+?U`m}M!s$T1u!}Bz2&qC z1k+qhvnul-(zJQi?=tBA%#%QUz3NRw4+t6$Arfm8aUgnfF_S5!qAN-KIR~3Rb3M5h znF+XtAtHP^6lv10WAu`34NZuZo{FFD)WF)u5JR5Xq{ieqRg&6r9+(sua8qf#eOKwp zmF$yn)<}W1}A)t>xnP8-VzWxuG z!43lY`Ij(cM*;o)lNd5ezyKc>PgQ2LfPsEbM%ziiApb&wodvY}OPFRC0fYVS4CxRs z#6N&wR{`7mw=mim0Ym*Ane}c0hUvLAA3Z2@DK*vsH#9f|_dA7VoE znybEELW+tnz@IYsOnTA1QIbMCr{~r_1G>+b>A8nRd4TfwKyJBT3JCq(2_6xU^zqJJ z!{Xs|?v7Jr=YORxY7$jp);R37mN0t5LDXYi7o4&*|3n!l}}#(kt)fbEYhfMEAX8y zXVn*fqVklLd&`a}$GFnC{PHILEY@!awE}Quzd-&sbYsH~0^Ap_J6@pOm}kXL1Uin9 zc1Bm;RLbUF1b9AN(_stM&CSfz?^Ly17``u`=yeFY8m@K`lKddeDY_Ey4!DZ3Al)Vd z>USPou`kdaGCF?ewAv8WxKq&Ui24kpH)A&Z*hH9KH*=x7TS_>v4NvFbS{A4k5?b*M zq+Mwu&Z^~%x>rhh4YAh24IYo2ydIuc`BxZS+km=yb3L#0;JtB%0G$;%A2k`Swao0^ z$5*?;Wj6l}Jk#+IrB4VuSDc>kXkz$2{(pdfT)hX&*@N*IVIFcg+UBr}&S5fAPht*J zl$ZCH{DU0MMh+`VQHSBE!|q-Q7l9c_eJEV%HxO9Hz)ujkhqgF%JOYkk;Bo}MZp$`- zoe20ETqf`RkKwDB&KbBV3QcwLE`P{uW^#KQ<&$Ut_X349a* zzhotT&;0*E7iLCot)>T}YWT5eWq6mB3_8bQI1UUt_rWJr`YY6Av#rTAFW}_=HEQuI z*5n#y@(*gV{e6hUR2>i#NPFh!0euNMyvST0-da^LCF;zSs5}QB96#*I$i?=os=NeL zt_kxrl~q^S$3Pra2_6TBnfbBw;21c+FFchkn5bNgRutueDTs%hoPeFPP@0~Ou(uv` zb|AAcNWsi1FNa4}U@$r1lBCWz6@F(&4;lC`tJNzfz>z`WbcTNYY_1abC z2gu_neA>-AkKni`q};_2wJha#fp@dTxtnhT2B#1>8I>r%Nyj>-i&$tt6zqPKhbhXB zsC=!Cx~%J{#e-a4ttafyyN`HgzjpZ)SkWVNyxqHw zSDa<`6hvh|WG-Zy&(2Qn7DYdx z`F+H2XX`QFzJhvY`@?etJgVC&L{Wj$JZadE;tyZnIhzLvpZJHCd#}W6|bLe0FVUF}{V6YX&}-pc6`9 z<$K{5lE?R_vKJvLhd8^zcvRJ!D4edUADTs1^*Aa=SCz#dx~hsNamxg*>Zu>%@)w*M zjzx<-xdT>~oSQ zP@b{Rc{}_@$_V?MOx7dpDN@E9c0=GyDP`nt1eGu+tCzxW73S=R5J(wewsR7rxTo6` zp;?7FKZ0LhO&eZ8zepKjwo}+=?=;L}nC&D;dM{)6V78MW>lw411bIpsVYYJxlH(wi z5{Q_!TMH-6L}}(Abv$-ap1IS@q{=f-w+TXT{JZ$uA^cy`GiEz=amH+?6z3VUodlKM zLP&yPwv(XNGiEyp8a-pSlc2d^w(}xZ!JMPguRLS5lR%%Nh6kouf1H_6${0=-L@6V? z`f5azRy8TBGv`HSY0gsVSKegy+q49W4n1SJa}z?6p0V7y831Rg%q)Hvf9OoE!H4j- z1nerSGp7|oD(~WFklD#)^efL;?vw&lz)6)iQpRIKtOG_zFN2kDboBl>f%Lx7(Mtfq zIv)DL9u`5?pNKlc92V2$eWRoIX)G$0KGfjRawkJ-eWRn7pwTxvde6c#*WBA)=H;nF zi*I!FehZ+@H#&NmsK0M?^b)lD=b(pik(UJx^^K0+tC41;Z*=s27htq+bo4S>hkq7^ z9G7^1gpjd5uU22W`G9-Xend3TFkA& zEHP)(gSsC*W4V*V)#x40khN*fuV&9!?&O}U#WR*WOHuDO&sgpp0?^+Z#6q7)@sY8X zGQx7_-_UR^WrXEU)>%s#VY!nP?eNC3oDF4sk3H7AoL|l}Wzzw)lo6IYnZY>ESngz+ z37)as`7MA+p0V7?m1T-&EO&DGn(pnvmmjamcZjo8CS{L?Y+uNBg#t-e!EX>^q>Qcf z2kdD{lSXBV(g@UP_=^<0!FbD&1-qaq9!c7|P*8~w$x2>dyW&+a0s*r8vcdALVPnfL zXQ9PK*LRno+Ib^oydB{_KX0h#rC<3*JufR3`bIskd{HXkYzvrU-bfigW@;m4q+j_) zJugARH|lxMLO|9x>UmoMAY~L91XYO+rc!w$W#nUG-$)r{#rBPQUR@n?mdcQ%Z`AWL z3C>bU%Nr@Umjmi*MBPGFqE& z)bkRw`$j!4!ARez=OyUyV@ya~(j|bDk#pg%$XHq&;+y# zd6Y6H?#i42u+gKGF>!b1hX9*AN*NRP$lm%Dk5b0O%8Y#59))#@d&@%z0p2R5lrga? zb0^ZYd8L#xChpIy0qX0OQp%WkKoF#i0c#Xw@u!xHnanyBTm)}$FNQGS&s;6nA~OM3 zFytowIRI%y${4pbR3Mf}8IuERA3|XIY%nsZy=ythB5_QP$#dES?;~(KD`{lEWQ>rJ z4fl+YQAW%&LPq(pJR@WzNP2V7ZU`9(vYrt#668H2WF)BcjF6F_)-ysz0{nI|gQ1c^ zvuA{i3~BL;8sPL zY(&dq>MJ86#O&Hz!0db66J#Hj1zUN0phekV3J5)l5VMa6NO}|@W*-%hm0R7}#{_5* zV)k(Xl^z8?*(an+YCVb&vrh`B^C&{ht`nd|h}ox-tU!ZD5n^_IawWiS9z}@Rr>oh3 zaUMm8*PGoE0qw8YO^oKS5uP?wT!a>BkDNR-kYmH8N?`T;&}YakM&bPGy6h>4B`IufoAg=O9`(j;tTN~WO>$7Z-3 zFGuKQa3z<33tJ=+>IY&?hAUs777Jl_fZa%#xlkP^pU&w(`@)q>Mn+47G+~ghI^e42 zg7n(0k(aMp^HbcCZVusF4BGb~?aTK)V)hBjyT)4&e?4V#n;YKW8(O?jdl-3sA;+0| zBXU^|*Y7%H!k(pSR;?hm9iQ;;L1oQPMVb;ypx&2C-i{PMge!X&;SiZ1QP4RdK|QaX zlkndG{*t;#OYr)y4ZM6ic3=bMqZ$eH(~pr?Apt~SjNds6@g=dyTc#vb*(1z*aZyy8 z_wlGu@CQt#fFfb}tT-b2^W$)Z?z6&CIdH%enL3J_2M<76?)qN9|K2jzOXkAhX3m9G zXwp4!G8cx_a4xI^e3&E->h{UsqSQ|S{{+YBF*L>Uc4)_*7j7V@hc_(6+CXNDF&!!0 zH5p-hz{wyS(YOF}u{+9Nht7~rohXL?zK$4|!j+wia2W$ph$fvnOFDJ2?bL=hFpiX4 zO7c1K`Co^m%b0xSR+HD8F)16(D0~+7{Z)%8T#n{L|Xa&O%vs=S=^nch0<@ zv&GK&Xb@h46Z@B4?3_8-w_)d8vbCM_1xTJXuVD*2=Y5&$7CYyxc@0Z$s;iwd>k-juC2?RGmHLvJLhnVowLa`l$~?P zopaVah~4VWSqe}gCskKFX9l~S^XddDV|UI3Zs$zkcFs)G_0E|gZs$zkcFtrY3p?k_ zfZWcR8(+6`W+Jz9Cg^(SOt#bQoWBpy_0E|a-)-1A|4*W5=gg+Mo%7F;!KZf4A$QJM z^YC>mJ7-qh?wsj&J7;dgvUcZ8(DlxlX=?xR&Y8PJw{xyTz1_}vG=SSVQ`gou?3`Js z+c{4~8n<&k5}@myGt+$Doio!MfioTa$Dj9rKWhPZ&VfMERk#r$mBdB?St|)4yIT@c zOi+|ipiW3>LM3tdXGUI*%-9)4kx7!1AzUv-h~&pEDnwCYS4VE*{p1hh`F(xGCO4f52S+7kg-?cYA1-{6*}cIU$nxJf+34s<3-# zt~7QJy*GFvw}(Cp!0n-L2XK36R;lYfbb@>6oY_PF7-`zPoY_PF45+V{Gka(v?4d)} zDC9uYa9NWnrNS#n{3*sckfv$DEp6$sMzZ znkqj=jI8XP(|y@s**mBE3m1;ZvS13+0|bP!cTNu!p!d${;=OaaT|)HUIXzf_-aDs< z2+(`y^!5Vu-Z@>ocTNwJ5WRO!4^MK4^xio=LV(^or$-9Vd*}2H0`%TFy`uoVcTSHI zp!d${(E{||IlYqry?0LUEI{v_)4K@Jd*^hA0KIok?-h3Rz^9m|`Y`RS2{PQH7$!e5F0KCh z`hFjgyxtxwYc~ttvR`3CQF}roUN3iNqF-UZ@>954ZoXT)F|>IwAY2`GS0!x5M1Y-0 zz(%{_S;V*<;99u)nW~R;Z3yKh?~OXk}Xi%`|52(E_n>3p+edNq~UNS=nOS9&sgUJo8wSae$v^`=C z&vLAK4aEU4TuBBb{Z-BbJcOj3LDJvmgMin<4LA%WZ@o7#_VNSg9F5nt>%3X;51Nzm z@^>P;5vXZ9`oU}UN;puHhWTm&+~Ai`32!?u%bFbr!clN#S0fdN@)y{Bx?Ow}96G!@zSb%5<|6gE-`B=P_UGdw`|}Mv9A1GOw_-LWIT>MV z;p7x0P>nnsegpXLyswRm?9X=#yUXElQqF{%csR`0d01A9p55BR;bG{gVzczIQTW6g z;r4L&O8A9qgIRj|{}-=pzk}pB9NrcGCCSwO5Kfwj(##eY>wtcO0)q~!R7QTtJhmM z$(#(YMTmQ4`vL$?hM8HCFK+2ft^r><_6XQd_GCDXO_zOTOMh3dY_sNM_@EHgF1Frk z6>NVe!A6*qVFLHcmZ0lbwkxq%Z^J9wH^9C%_p~R&e+F`|Y(0F&+wjVk1-VzY38Zna zY%>5(!8W70SGElZaj$II@9vc?yVbq2orBhC-A;IA%ci3EX!gTDNLKGD=1Iq%;R?7#6Qvxo?U$z*( zcXn$#6?M;=;I~h0>32_U z3I5(w+vF@n{tF_Rx@OJs@Nj%%_NlF`*zgGC&X~p&M7w-8nS+ldnavD(5982(4nzqH#0V--_RHg7jUqIcH z);J6ONpntd4gB_;f_`h9g*DjLa|&aeWjT_AiQ5zZW%xS%E;wl*N;6CxE!x`~e!7k3 zhMz9Z-0&m#qR%PJJK}Kvjx%|nPte((V1KW{*d+z*iT7wNI{j6_Ie-v z%3kl20#q;qq@*#jS#rA5rVGIMtBp;-6~{mU7wB2!eZ6j z%kqwMf!x{1i2&PhHo}73twI|2c4s4J0=TmgM(eP*3V8h30cqT= zLN?W%jc}=VXCurSyyJ!F%A`3PsRKzy@ZR#m2%5Lc#x6@M`ox`$6pi2m#Ur@7tY`$y z+huz;!r^ka3OTLatwJibbY~;HaOBQLE(369Bew!LyDTin*=1p!on4kzRMee~@NS$t z8+j1G*=1n{?p7hwxU&&*X6{xYRWP|*gspQ{SkM*6!x5s@znS0RvDz#J{xNClMkM1+2KB0}I!L>3~z z-6}jAAg?l{9fe4yu9j{50W&lwBJwL?Zxyy8e(0MM5r(*1g-imrku=LT?vJ@|PeeE} z%HAsEXu4a41nyQLfxA`6^j)8bFq*qnNZ@W261ZE11nyQL!8p8OMMb`XjHShvZ6qOJ zKh$t7kr7qF0umcR4EW1d!==ECKaVPcbNS~-2rkujS-2LLYO^fj)mB;PwWj(wWXTIL zQIm1)dr0k_41Zi#Lcj9PBB&Q`HdMh!p!H5(23j_5YzMdGwKBY08U4!RuT$JTA;aMf zBxsV9NfkVfl&zLa<)@LSrkH4SZW2<8?RQl>k|}zLzM{pX$`>TQ6PbPR6XX%_$Rtm# zGST+AOI+H#;bE_{=~OKrY9{qV%@w5bi&ER=AI02zUO3xH8P8~x`2^u*i`40rjPqx3 zhp)r6O+)xFgp|*Khfz{S<9nY)sA%Fz&4`lU+rY*zYXeVMMrL%Zm{2bt4vl+o$awcE zW;_aD5M15&=V8p{=jNO=`xBUS0o8ZdZP>c?@H zNsY;RE&ODf!xm4K3)6fhDomY%vyiS5wVQZ-pei)eoLYQ6+WT}3dDAZCpH9D^#L%x| zuq}U;@wGahNUP(Cv^pMSQjbbR`XP?hFGxn&>KCNH(lX84XvL?>GR zBf}#@tJ1$o&{^XIorkjyhDWB~2|5Y>Bdqw;{@=6WQ)ijg|61|+uN5EuQg4$LpL*)D z3p(*fex6^3r(kU*6v({r+<@_@VljIKU(jfM1kB3IG%xsJHR80 z60YwMQ|4(FDW^`5O5m(I!SfMrWt{YPE#thHxj?fg{tK9+RVVl>_^phSekbE3a57F| zRz33s=4`~m^&QfFhe)QbR-IrgcrYvDl;yfh87D)WjFU;gtdeHc3I3e9nCm+nC@142 z-{@qV1WuhGfm0{Q^j*t18O^B^Byj2k37k4Xf)39-fg$*;6`ux?asC=51?-1BPf%pg zaf6z~uY(xyCnnF+5HtQF-lPuFfJzh_9|0qf*imfg?8rzoa;7&=Jl#~?Eaymi_mwwc zNQOyd%Q$$;sL#SH$s-@N0gTT&xaJRLqr*yt1^qMd>u^05fYo3TJ(s{!4^NqJb!FgS z$RDXD9$|w?`9p6{H3*YpP4S$71e3rxU$q>^o|;L?6)`EXzLXs6d&sfY85nE6B-VUM ztof2y^Chw7OOTFyNv!#jZedyR)#aQyraclh%b8oov+fXWqYJ5F^>8) zJn16Y9wo?KvMDzpAXGVXOv_|Ba~gXL{8}Mk)Pqb)Ql9E|fQmRpOo~Z z`ZV?+kV@q=7Up+m;B%AXSeoDA7%DlBrTLxjB`~7S{0>pU{0>pU{0`F<%70mAt70mCjyn^|iHl!<<-x&Z@Fu%i? z`gk_P%iWz2RxrQAq0k4kG{3{HE|}k0kg!LzG{3{P7tHTaDQUs{4oiTfjS7UdmcVf3 z%^)T9`&}80q<+84HiSw2ewTh{erFnhGrvPnk`zPMtIIZ^QeB_YaunSu?deFekzCk?y z;um$8#rVCklD5N9?NT|Qh54Nu5J3y@A!{Sh>OcM5zA&F{1# zN$64PM)NxbPKM@pn9Q&;rE**g^E)3hEAleokzR@;rI{I;-{J5U%njc_#1$PH0gVT{}`Ub4a%xgkIw z(&%8BHF85*nKg1lkh%_kR>QUMhaUGFd(+5`H!+d_A&8a6=FBGei{@$l3v*CIKbCI> z;u`(&@X@h(ADn`>wUWA;VSc8Obbe#1lDe2-erBMf)YJS7Y$hSVa;1vAvfbTvs= z0e%}UdLGGso6b>b?2mxIOIi;1t6$df;vIbTH`1y=`<;%rD`-t{QD%cuzt{0L0k0tq zml4$;(m7V-<{f=?B3!iVSXf%oX%~$0)eN}kwr3@EfH4 z8S(z8KQZVske2!?*ey{M$k`|;=Y5oJmYs{y?kaD$O2m+or{ua$>EtCdu!TGF!TYJnS{U`17AnA5XiAufq-Rj z(XR`%y>^DA5>Dku=Da*7PXdy{CHOm$@xHjTbyPV0+_&8Q&j^HzcA>eCltOc0@&wm$iD zKxEN{%FDpZQ&49crn${iWwJ%W(@(Voidr5)vKCB`$8HT&YU6caF15AN^1pMB^}rb?+bxpFYnqg7 zk!rS0jw=PIU2HYZivmMRQ^GZ^#jTQDwx6cWH@qE&|+E zh`?DQ-GJn7E5!89EDVRsZH4fISJ(=zM(J)VMEfXiE0jSa+*XLJp2%_O{nyKJS&F->DqqyURgSBxV=f&Oc0bts{Hx`-(%qg> zWyI<5#mI5%Kc5_zwJ_IIogBAe;D=ZNYh^w*PTmpUaD|uRXI9uEb)&t@_*){qwd{ho zth-#|>|e+4^Iq^&cfmC^Ap>tfz7^%H1AYvynHNsIK`GAe-vV!h>%oG&b}2`6tTTb? z`5btWRxCNaz<+($n+Vb`;V9be1<``P7g&~VwB5EEp0^MeQPqSW1Q5@NalbFdpr5hi z7cOGa;Ys+5<8M9>goVH=eEbQ%pY!p4?ra3vT6oLisSpu)$vW;sK0p)Sg@fqTOD7o* zeY6@O_mF8repjJ6`U%lcG>3OkKR|O%K*T?yIe+g7QQnH02O#nn|AeSa-#ZwoVFku}uEOXYsYSaj^a@(GbWS^v*}LR2odPxTX`a=CrF zl_x}LbNlosn8~^Wzu+fC)=(cGgIJ-pJZABYa!G#bxR*2;|JiGxya#SMGFb^MM|ORJ zzaQoa5rKO`MBq3wrg0n@-xWBHj3JIABXArUkGu*`h{#a6Cq#S>^m(5Uk=1e>85btU zk+D9GBWp&8VEbc1GcmP)Nqn2qS%j$c0dLQ6Y*7 zdIQV5AvRrBVe^jYP>b;iSTS|+J0iXivS;k{cYVe#-r2=JEGfhUXXw1yQh`RQ8WD{3ko_vIIV3zlyD$G?G$*X z!;_(CZR2Sf9N|+s*=IKD9lxlrXOa~fDb*<@i#f(`*{?SiL=fcZQSd zjWyLfL04}NsoqS49tOwi?P;s`F{?MuR&VL)wY9ERoJuyrjIsYy%9NdP8p-P$y2Tay2OqweP zyccP&9LNpDqALeUbLD`xCGC}iZ?h1?z0t4Y&wu40)>jU$LGnr!j=_H^UcI~xPTGUg z%$0*7_@+30sX8-e55cn8w)Y-a=DMgeJmMkG^LeWTzIZwS69%d^RH-6hY) z5XZAI3DlaArY{p5?mfj^%)Lksl;hbrnvQ29a6B7<qlkzA5=Uyk#8uCM2Ko9U=2ORf^4f`7F|U%ld=$%aGqXwVsta z5lqu@aM>f!Bd3)x?Zto>z~%6qWoe4>mjhi3SCK|GV^JCv>wtkmYk8rf9QJI~Tz)C* z!65aQVxG0d%&lWF_agP(a8k^XQp`HQhe^sqU^Y*_y*~lIPSW?#w)xU~{#alA6(m+> zK{+c^2TB=Sj?C%N73`6rfJ5LaHllp?s;M6|9HE*AP{Htby#rCv@1sA)vp<$0qUJrX z#3LH%kMYtUyCR!Wa8l8|rJ_>-C&6WCDQBNbt{jU1k0NP-+P4SuyAa?UI979ispfK^ z?~ro5nvkKeb0xqExRw>BlBc3%R8-XQLK72pEe%l>k0F#(#)aT;A3;zHjQXF7e%Y1f zU4dBWR*dJH$R&GC4)jKL^cs|~8m>3T(;FiV@Fv!>>bsTjbMy|Voj-el8Y|UCr?h^9 za^W5xb0vS$F^pK%@8o8~5lOE|Q8NLCy2~K*Xmt>pV-B%$TdZb0Nt_P@wV~?~- zkF*1|k-~x7u9AH+9&j97#VIJ6Q++D~r$h=0p1g4okg6kyiiS<*}Bj_$FizBUL= zSnAJ#cTkQ2flDx!364X8X3$HHLX4sWe1|ru2Ll52EZR-3e?Affa&rECM9%&Vn&lCp zCqmaCm(ZM+7jgYxs5Cl3v2q-qgTKk{58zwxCr|cl6})BsqQPoJ^#ur@g?^g`=Pw$f zMwXCr0npi`EKobh=JbaEH^SiyY0|Cx9a=X;T343Q@4F_Tbwi;(>&-g@Tv!yzcZt65 zT%xZ_m*~sW+v}F++4A7&8YsI^-Kpd`fI)Twq|KwG?%eJKhkFvCL|?Hk(O0ZX^cCw8 zeZ@N88(OTxeQU2~T7BI*kNavW+`o=?i%@Dk)}s7*d5{jT9STyOd!cAx2~*^`7m5~( zzb%ZG2UvkrAHDyXORwJlkg77L;!hTtWm(SvHzcF$QtiM2jV49c$72{PpwXo0=IA;2 zLzUU$S7q1)B}Pc8VL%f}i4hrAAsNs_Qes3UK{lX?q{N5@f_xb^L5Y!>Cy~5T z#f$J?W;gtK2~HY?(qt2q7(LTRX`@(+ol{Jz0xD2Q>>?lxs6ZjnAs`vhL{ef`0oj0x zo)cpP!;;2tP3Ax%FN z>%0RnF-5Sno)YZDfoawsxj7#R~u*I{jJ9>IN30*2Uc1Zs(liKM#$+9G2j ziHZ70#zYc9dvp%^116GK(9p=3NV*ScMn=X&(t`k_BV!_o(K@2DFtE5+@FYUUMjV4{ zybAXFxX74DVz=%S852olP&Y)zL=v02DKaLKeuE5NiHwOPX8neW$D(^HM43TiCAsc0 z?1NxeMS8sq`=G>q`qL=GJ}9wD{K;VT?=Twor_Mr)vH?vbB_0q^QpSByVs%+9a?J-c zk(78)($oetk(5|d&f#hd4rj>PH0M`yz$?~?hr20MwI!g5q{JiL1^~1LG?A2eJU0QL ze=vxJK9QOW&|b!UP~s^mXD9&byk6=&8UU64l@!_$@QQU}LmBS?j}2%dDe+9%X#jhc zaUYa;PBIu5&_q(=MM*Oupoyf!#`GFAZc;!KNr^vXxw1?NXd)@`Y6%ys=>e};Ctj1U z?Fd!P!DWy7Y@g3|`2tB-5cpvU)mN;m=#Sacl7?5Oi_!?xX+A=fCgM24pXw)&5Bs4g zGD*IUObbeqAA6?|MaATSWyNKy<%0uLz!mr+i}54D%}@f?*e^!i8;l~X#}OX!8^ zsK_Y7;*f@sv6DoQjf|Zng38F)Nn-lO$k<6@$t{t&T)=2;k+G9R&>k5(NdzM!V<(BA zBZ^UV+@>agMgvX=Zf2y#vFgjs(0tFogNsZ+J4ybXnJd6n;&yc&;4U$kzA>PkB>(Qr zUlFn?pq(WDo;0iUNqGe-~n|e`}dZYf>nR3o;sfWRhb~eom)M1Jp1=&DuDWW z_0;j~KOks4q{6IG%z@~~6-}m;if<+H84fmo>-up)G86D=hWw0w79vf)7ut|aH?j#a z)gv^$fj=XwT2a3eeXO7Fj!6d<&+LQ>qu6;8+7i$x5)?bj@B~J&GeH>8C=wJq6C?u~ zMS@~yf^0yeNKoudkPm1S35uNwDgzotf?{Wa+JHuppxBuJzm^0;1vCdViUh^Z3~32y z6bXu*MHCY(B^V)~Pe7wcQ0&Z*z5$IQL9sJIzu*#v>?ojrK%+=d?97k>0gWO-u`|KI zpeLj4Bw$cLqexKf%#ikgMvghJ_>;N6f}YRqioeadCqZw|y#snjF2vuZYSbPR z_EMGE9lY@n00c`Bp50N{8U;Ob0HX{OwTL031tf#Zky&;p0a;kw0oYkUURAN81DR)b zmyrId{gH2mtz8I@bZ)4sro-R<)e28tSw(UbEQL1WG_Ta;aHZyB#J&n-U*^kbJ|Rtv z4l4LlmcA2}%FOf9?DYp3haQzam*i7Cd13TC$?lJeXQLYFm5gwbC)NDxmJ!l>GVDYz z!!&$Fs^?W9hxA4?K6AW|(6MC%E^#Vd$sCT=5f0lj0<%%+M;T#}j&R175p)ja=*7%2 zI>Oa1f({$Vuq8TdjSFMLeS!P~g@X9gV|pW+kmB$CD~z}^JpP~2oj&KhN}t1q9Hny# zv8~fB)usHBVGDKGAQvVd3?sI+}K(}KemsN4XrlvUV+QDva8_#lU`={`Q3Wcf3n zzGLtQDq<4&!-*C%pY#bV@dO?JQWu}!v+BX^Z9f^U+ZiI&kU!Fp!O$tK7I?|E3=ae@i=?Ya8T6YFWb2p;bP-D!UnCW{^8qg=j z(nm6mw76#0Xh=4{8*{>L=;q~bMX0yz0BlN27qz#m>ZqCT%3j^wS1-erE}E@sqRKBJ zIJpP*;c%5p4x6v)BALy-fqTH!&PO8}qZBh81H3a_&r`eO+8j!-e59?Hjx8DK3 z1Q(99Ju$}ggpY!Ydjhu5AwpB(ezrfR!NdOODG^NBX1Y5YCiqlKf)wAmTH{O!>3z1z*pUk5J{mz_AznXaswqeowR(PG&$o zQi3FZQRgWABr=d0KpM0WnGhAy$ATMM;Nc7?ZZig@5p%5ccB#$>jb6T1sx!ab49dr$ z49X5DcY8Qi=i^WYWeVT{Bymta4rNe|2R;Ta3~iw$T@-3MTGi0PKNa}IO!ec<}3b1mg>DQ{U@|X zdWW>og{a22fOV&cpc;Jx3GhUG8k7g4cN)+;-a8`nTnYi$5$H&7*|)plu$!Xsccg|- zqu6zD-K2&iSV4ar1fN2ht=`#>qjxqaUxn+&?s~U`Q+PSxWpH%|!{H>|1$Zr7a<}#M&^>T<`=gxyV@*GdI6-T;gSpH zsLd^m)HKmo0bFvyNosQ&Dfa?>Q&W&knmXwK*x!Sz+XR+&^I*oh7Vu)Y@jItf&X_S6u;zJ8;N7O6Xt>H5vq0)b(n7#Vn$!+j zAJYB={F2ZXfi#GuabJe2GPv3=0Vr=2Y0m+#hO69X(G2B#QmI3x`f4Iv?Vs^W>wBfF z*D~NsNt11qCtbP*_#x5`Bfp@3kY50P7_Jg{H}6&{Poa3 z7NGn^WIxZlv>e_aA<8M6A_sJ{!B(R&c6clssO@Rou4Ot7IA-Ylfs ztHN;&UcUEz`#`u|gKgHFg>$h9tvncwi-IX&M_Xo}un>l4lN+Uby1~nuCbiy!zQ56{(p@kgU68oH!pko~;$eu5 z45UI6qhJ8SRN`p_lKY#oWgruh%jldAU6GYK{c&4H=`HE2P2id1#tHiB_dVLX9Ds#o@36;3hgg*4?P*yQ< zp9$Ug>Ciiwc8v-B>!(A{MQHdQLZzZT@tuh0QtMd@PjA-v1$ek)_;P(=DoNdLG987S zFh`}sI7`FMWh^*f1Et#7i5y*&OeOk)N^>-wnwscD1AAqWU7{1!?UltL1Y&R-bXQS2 zJ^A?!gfh7%AP)CZPZY<&&-h@K_$z|A5BtlOLArLl(AR;wmDJ+GBO+Bae5y&(q1_S6 zA?i~Uic=O)nel!_R69hNFG1&6WV|0DaUXeX*O73fs}gfeoGU&Z2ZhVT!vut8LB!&2 z^~YPp!nBkbaS=j)i_rBpRK@_4R~qoJDdBw^suz{8Q(_&!ZdzwDr~*4G>%$fqRM+Wd zY;Qv)0~CG}C(T6&W1WyK4zRnr&$OO9@ z9&YHbwWSr;CA<}(!cjj0k9^I~!6S3E8s9e`T8G`?5lSmOQuYLRIEH_;d7=d>F~v|b zsI*-b?HH=WbQ9X=)1lI-N0`t(KOKtNVpTw>)Sw+Jj8u0tJOj}U;U4gC2}zs+5374F zb4X0MESz{*nCQIb^c%nthvymAn+MInWMkCsJ2Ke{VPScOi{E#!uv4(;bvr?=NRhi(iFI=Y+#X~^y?Z3x zFM)pwmpo40D{RR|fEP#rqjI0zl=>sk>!i$8t8y&sV}K9f!l@`n2I3@m*b24hmrx7; z2+unK1qb{y?o!H(kMR0Z6suwi`S$vNkzVmczC8XCRK{PY0ryhP@~t#qmWKy;}G@rN!o9tF{*9*5MDE_ELeUFtmKL6>SmM7mT6 zGF@sY$aE{Yd0dXV2FOjMlO=1>Iq~@hXsl>+q*hOYfsQ z+K{DKXpHX63_!1A?qMXNyE1bCHhPraM|Wo~1JD*4qkGab5ldTWj8 zZ}}@2jkofY-bbtCETGNHzssQeGdCfJzTjqv9uPDhv35b}+rzc0T2{oU_o*ETf4B2i zfuY)ip>_6lz>z39&GY=kz>+=b=Xri&vG}(O6Uzg>pYN{E^Ld!wU7zQZszfEk_3$N_ zO8{YQ;=0sYU@?x6xISjHl*jY@#LdxS1Q_E8iCaV|Odo9=A+E055An3k=46k}h=+H4 z$sP@q7^6l!%8z^1{1$X=vpF966|i!0UoReBK|j<(%~SCRDNx%&h(}~ty0+OIkEkTj zHk;!S4Fq|rP>V-qW+6HBye9Bp^fZcC43D%2@#QE#9{nCjVhbVOS#$tto6Yeq0<_KM zxI=)pg%Iy5K-+AN#|Y3io8#RCXq(OPSOMB*bG*9%ZL>MvLqM}?)JOU8{yPS!0*~_J z32FM3$D{msVv1mCo=5rdfoaxXK_xNcO%{Zs{AfL>;}K0-Woaw$nIDj|OTZ9k zmw>?8Z048S+>b~3F^=-Tix17&CHN75vrE84&So=#v)RmooLzzyNaO4htO9U$2^g)z z+9jaI5NDTw{qF1%uv?v7f}UudvrE9HI=ckFMh4C=%VdpydIAMQq*zuGQA{7APu0kmC$`0?DY0kmC$_=(h80PUhJEq+SM(c04D z^-^c8EiL|)6x!kOC_mm%_7|klb_wEV$|7`$)|M7OCmCqF1o4ZKM%yKbH>RhdZrUzE z{D&-87HyXxezk<_)O3$W`SEM=wH={KW}++DqaoWDvR$D-(pA7EG+^&ayj!-6Cs4=Z z3fx2-T*$~r0J7~xnUWOh$oDV`z3h=f6cs!NEDJ1KDjyj%>+lDy%3`eIJid={eBTrG zEi=dWlM(Kl<9qs@K?0WIOf<`sF%EZLc8W;ADzfWR3fAaDi=2s(Uod`~b=MVt^^Hl)Qd zE_k8d&0IQU993`=yuox31OBKq^UF7*zK$Ue@z47Rwl6jqvnFDbGXX%*0Svn?gmW~OWrDK9-&m4#oI7`QDsk3xU;4B>zI7`O_&eAb~ zvvf@0EFBX#OUDGx(lLRvbWGqZ9TPZ9#{|yOF@dvmOfXE3%x>sG8JUFq#akYZJ53qu z&x{QWPX$TL8{>oHa4?a?yU4{8pM2iO6e2TSFb{EL5|9&3~z=s@5VG7T&N9p8c>dE|?xT4t_a*Q2|@t#A52d2_E`x7Jt1f z{`b20mwU4K(~;?ka8mrsBUt>^fLFjt@h^9<6{`U6W-N-{H|07(dKU0$xT@Q1jaF{8 zMgzZ(J(|83UQfHmx3WUZ5FG=8ozyW1Ev3QY4GrwWw~*@_aHZ#df;UxltYzX59Pz=G zo{Q!@E1lE`SW6N+={M3zLjVWDHC*RvB1aPFA|6S=JOhs;&`G)~JuXLP-WjZm7oaDr zS%ovC3e_z7jFBw5nnj*j!;YzDQD^pIhxBAecxMh_PgE>YXE!s0io<5kgcORbZpBRX zKc$S=>l!3KSJM{EK3ttA)QZCvoT$#Ll?WFj!g<~3Rl!jF8N@AI^on;C3GLj%Me8&e zf-<^s3m2`wj?sIJK~jH_{19;}^!&Mi>wHdnc?g0v6%XDnRq zLVzXk%p&+Ez#4c~5L^fFAv}M8%iIGn>`)wC!Bsv4Q28kTJdHm?Ucw($`3CX(_>lL*X(kZY4Z-5U|*n z;dzFD#h2sPBMp~fHHO2}PQcnshG#qhYjrj}XTl9*@7;tB@%V>bluy z{#8AVu%F`ds;b5mVy7YJU0{?3PTiQoVxYY6tP!57mJRA1=znS&S&zu$5#!=t2CBwf zTh~{)p@5M4&q&|c{?`~QuKk?Git9e7vEur$p~zTqRR&@(aBXjVp;oho#2f)2mr78mVR+U*BO(Xv` zR*XB^;ftb6`JdA?Qo=8eJz7xk5eg)I3uDF2&RDUe*;Zr4B^M%}1`K9V0VEkE6Q7`H z$#3WuQB=?j{9j|mR>=s>W7r3)93J%_XsoygrM&-oW5qp-?GrD?!k{OX*tiqLB1QIz z8Qja*cB8s$t@EVCnggLOkKQ+e7m5F-)qQLRKhnb9UDg9UOO88>0iyBaRZ0Q`9vF2!5|)j($L zO?a&akwf8k8hNjTKU5i`L4?UNMt{g&@LTO~)DxnO5l;XWag6>DJn2+c``elDi%bdH z-{@D7)*r&+oIYLxr;nGw>Ek8H8{5O@B01#keeqv%Gw4^qBdtMcB5w~z*W<_2>JMR3 zr;nGw>Ek7E`gjSPK3)Q+kC&j*@?->#CnIn?89}p^x5M@@PT3q!M!)092$oh*;C>*h zue=J;{zgB9?YPW@H`ItCO=?nB``fL|jzYQc;BxwvKN&fM(-JJ#>Epc}Ax?kD&jBE8 zXJ*L<@rTaj8vG3YZUOtrYJYnNeycx(ey2Y~3edv#w6Q&WWWWK00*UXGOH^ZfSYjI6 z!}J?_8rP+`?=(tezbnAm9)1KR8KoD?W2P}mFK#Tq3#(3}s{8;EtkOA>tkOBgRaWU7 zwKX}lB?L}w34v2v!Zc3lTs=aZ+7c<*Gtc!1oYFZeL~8DCS;2jP94j~tz_Ef%#QyQynX~6d5>HkXeHj zJQ|~BmCk*P<+aE%^8|8V@=g=^EC z)=q6nKUB!6EjbXtsV!Lo;MA5}4B%`Jvm9r8n00oxhgs1MpE7<}MEN?>IJG6$1325m z%)qHFVH(E@o&n(0mT)z5YD>5>PWLI}heZ^ofsCL3u}4ErN6|SN3M5?xO$ae+ODgFP z*wd0`zb(@U)M;87uN{9%EvJ%y{wugBlV%3(=uRQZokEJ*@z?@ky=f>FTSDN}mJoDUb8ZAsHOILy1{q6> zW7Q;FAPE8cp^9sXj3{oxlK40FHGkQvxD=T2Kbax(_~&w@F}8=f78~2c;?=f?>CI4= zNn%W%L)L7WIZoOhy|Xy3|F##gaeUaT=MsG?pzemAFO%DA$uj(-EyFFJm;M9f|PVOf|KJ!%N@br7pM#+Ry+xmt_t!1R&lY-wO)jzum(>UBgW3poVue=3B9+yO16d54dYpbd3=^zi_Oaz#z@KQz

pqegCJy3^KS0;P8NL$vD8jCDzDY}jlpIs0E$PQl#JEHxs_CRj1=ey6voowE{f@O{xsJ8`1wtHa`62*V%QNv`{0#ok znOuVx;I9kVPnNaJU@@|+CH;=Ilmb*R10-weftqhDkH=ugz)*Dj~((A_51N*_6dZ6F&cyj@|HubOx zgZZyiO_wNEO$Sg=O$V?os_7D6tZF*ZSH;N_ayo|mZbE_VFBPmth|wwBK!3oVmNa}x zSCmGePD9mn0aZ7M$zH0aD~fjoay61Zs-}~y$PX5xsDP^JWRaz6I{DU&$zG~yFpE?v zuXDigdp%XtS(Ck&Bi!;qe&acswQnk4Ks{+54ZUnl9#Cpe8zL zajfri1|$URhjOZ>lMz(`FQ^39fEe&6ro0BsfEj;Yo(-rgBA{xzZUa9=Z&k{K=q~C_ zs=PXO)PXidC_eJ~DwqOdQ!};F#ab<$WhD&5)JOE9)g1;cU2r*=!|N-rS%(1iCxyDj z`js=sy#aS8Y372(s=pXGn+13%Tn~BRGcbESiaZhcc(|VV9$ub&bBVSCQ6fj;2b9Q> z_<@Lc6?iPNJ9)fv))KQNV0U=9*@BcC5o7$5U%14~aYeI{zuZv`29}JWzblEEVQeTd zGmOnjcvWmAW_Uh_KHesYS-MDKmM)T*r9|0O)Z^0k$fX|~2l%wj7slO{E(l(Cm^D}J;rTSLENYq$Y$Y|Yjr zX7PhaLT7RVGFOv)t5wqQoq=5;JM>XC!77Ta}nqY*k`b(gyL$;~r&WC1-)LdO~{(60>xX z#H?~I7?gO$S~6N(Mnn3vc&wQQf0J!q;&(2Pzd@=}pP{~Isj5e@)J=qHUJsFzS*FKZ zRz*oxk8UjCGB8pXz*RwT)w7nx{TS#rxL(5{raBHRREvnIT18CtI0AkF*Lxs1D3)10 z8Xi_DXXI6_7lOb`!{;F>iAxaa|6}h>z_To__VJl#dG|MYvnP;{03n311qhogMnFKM z3ZiIT0YN|z5o8fJYOTesilTKv{i?WDYir%=f=jg`qP1GB3$8`QrPiu#wOak(_nCPn zZ!lWyuiy9k|E}xHbm@eP+qkJD4#(yawi^qphkH|nqSMH{rhsKyd%vv294d=F@x5? z0PlZF?o{FAPTzc_S(taES(tyM8UF;;l~YJIX(t#ow(naoXeL)-&?@Cf^ItM(Qh@R~ zbs|n_bRMT9{TrPvem{oFL?5&waB?RC$0;$5)MY;jU7?`)Axb!UtG zTDv=2WY#!aD|ZsM_+QDL4nd2Y+=;+_Vw6XA9m}0KT<((yoL}y2@m7@X z&K9=VQC0gV@XvK2e2d!9V_lZ&Vc58IDSc5d~Y_TtZ`=AvwaA%85us+=>2< z!Fd{N%qqn z%AFYE2Bs?t$=c5+}R>W)1566xU)q9cecp%?rgCEA?|FE(cIZ0fje6y zaA%7I?rf1@qKb1aJcf*=#c|bH&K61V*$+9cB{HJQe}Tj`Aj;Wdj!S`+I|X>C{f`-3 zi=XN|xl>L5H_+orW3O)jqL~z3_+5m!`7lDnBIxx+WM_Jnar%A?-sF9_A}41`&!Wf@ z-y9VQQXkRB>b@lU%PPZ?q;MY7AS}rnU`ZOG9Nmbxo3cu+dIn!W zHUYxI`c4`X z=gB;?=KkJQmzzRp);wu+w#1@&&`*rFi$(L`Sn)Ro!PWjYMDJ|ams#{0_JvfH0!yZ# zxuDXlq_27H3il6h%FY)!*Z!ukqDV$ zU3uBM0LI3nj%_X=DuP(>nS3R`YvNj&-qhm_E-3UGE74wX`kT2?qT%_&d$PC0p{#1+)aQvI}67MFlT4sSOMnjEF34moSlWc3ovJA;dlW~RX*JN99Drx zXW^6-{YEP*oSGz9T}l=voF?^$*p*C7I9(8q&r5i{Jj(Gsv?myg{yi-$7kX3 zMf98Fv+x8{fJ$%*mDy|1O9E8cUW1k{jx3trfrs8%G$(Kt%?X@Ea~aXdqB&n9&Z0R( zoJDg2XVIJ=tE=lnHYUV1=re$vMe|DloJDgcau&@AoJDgMTTGV@VD7P0EUeTpG-~$XfELKS@^V+(*l4x z|6b}m5&)HcMha~eHYR+oXe!beHYR+&XePjf0v?}*TO|X-#)Pj(8pFnfucmH9;|v=U zzLnw1VpOEUw_%t^SvDqoN1nEMs)U2f9`)HipU;gikaU$GQ-)RcL-?!cPq3#YO&XQS zOC!*v`6J`;Gw3DU^|1@`;*sQ=cx4EYtk^MaQB-0Wuq?K0usmzH-o+>9m3+1t?nWNORC(61t6<^;}|`KbtS z#>}q<$f*=*S-gsEUCZok=)FLSjG4=d9T_t>)v?EC3~|QHnIxkUq?Os*(A*tF#>_b~ zDl%ry(R9Yl37j!=0%y#e>76limh6m~GnzAIPT-806F6h$1kRW_!9P!gj^Jf|pQuAm`D5d2)b&QjZ4AlLG}*dNg33 z93%iQM}igsbsq0)CkG3t_h`U8IYge(MsGF2PyxL>8Zb`|6VT+*fO&GbfZiSrm?w7; z(8r?z^W+EteLWg5PmUDO&+Eo$qXhK#Xuv!=E>az z4Dx8eJUK={i$??I$*}?ko4KPq39oWryzdJ8Au)-G&d567ipI@3Jy z@kb??y_lCy*Cx689?D1!@c5J}`fQdeyc%Yyjy9QmzkMd`HZz?IX^I<`xJkL3k=hC= zd=>YIVP~6^jbBZ#3YQ@NW3{|Se$Q|+g{qL&w_$vnsXlI>N~&H+)E~o*Ce1ZH?3FgvFW7R2GtLDYw zw!+nbLh$FAUNK%X_T78Q_y|?kbFRU9y%4rEl=?Lz^#xH49EHh{t=9?8y>Z=PQ5ivc z{ihY+rMOeNrHbtvfc;NjxXQz3t6z#D*?6EaaNP!<4kcbz?E656kcxw~gX&&_s12Th_ET5zFoksD1+5YHKc3@+DZy6@xIiRlwphTNi?|lQpD*&%4Ycha81ZgQ;e5HCl%}476fageUJSCt2eWp|BIJY99xh;JTqw#n^?(IblPXwy*2!29Ivsm;|X{F zJ`%kNSN<}Lu(gjLTZg=kMHYUM6mGH!J^^)76#XVeCeDxcL7gzb!b3T7g~{i}$fR5rZ#{ zF2!w~0ke-LMzHo=^lmP5tr&bg39rQHH=H^Jp)4WQrXK&!rsy#qh`=p9>F%=f(CV*;ZX=LqFXyl(soz zKewS}r8^G43IbRxl$n-+N6K!1M`mmvc%-7kqM#}8NVR4}l!X!HG)??LFM&rgyfTXOGk7HV zW_Tp$XW@}LzX^{#`=7wWu52i4*Bxf22jj3TN^z6np*iB%MeuNzPir3^vpjeriu?jR zlKEX&c{#t%X&*V7_j)kqm$AY75Mpwk-W0`bH&4Gn=oer#9_ui)8p|?E`6vqgnpxb8 zc%u<7TP{uYj-{nxZw0Ij?}Cua5z^0u$oj}I`Ah~M;C&E*6_^}FXji>M5z5LRxnrnI zxFZo-h0q^Gp;7hl2y#tYfnGfUaX1P$w2#9>_1GB*W91%iA0{J&^sL@_wgT@)QQB4S zIvc9d0I_q6P!+qy7FiQfO|_)RG5t-C?%qDk6&bAy(`~$?c8n)Bd-riG!x9_sf`1Wj zwT*Xo`*=I7GnXS4JLKi|v0Uv2;K~f5a73c!%A$t;1}9E#Vc5%f>+5<=wu$ooYP@*$ z`rR?VD`%fM&S(BGn*V(p-SU;WCHe?cGy&sj~r>G0t(S zXYrZH{LcXIGR|1UX%t>6xzbbrWSnDEBc5-FDnMv~iyyaCHI|WbBG58YX024cGOX5P zK)*DUIjUC?N%M~L)C{=zQbejCWj)ZThJr}dBz+F}HSiO`x!K5e zZng`WPnW$JKXlp1^lmn?xSNga>t-WkyxAs1q|2_TgUNh2^)@(IYLXndyH=g#*yam_ zQ`Pqaj5yC~-`@^3T5}#_ZRN(zv5d8hTO1wB^hMx(gJ(Ro(!vyDd-PZp#z6+wug_ZTX9l9Jl31 z;Gf)>j_cy`mbONGC zlOof!!GZTOJA0*xesd;++w!Id`IXt=kmQ31aaWq21HhFgW|nvgKXf)%{}1rj`RpfS znl@M!K%^h({?fnWm8R(+WvuS+@d&rK<~x8?KnA+Ab_K19fagkVF_ zOQ?anEzdOWw)}4(MyOV0Nfec}M?oY-y1$I8B8`?b1d~pqg}`aF5Ol23(mRG}r0vIT zrR3^ z?zTKf)7_ST3TfPJc{bH)w5&x2PNRicL!)Iiy3$z04erW}zakRJP8_*5z zCRN@D-j_du_veq`1Crj3;6ueSg3)bxPHU&pG7_abjh5K}PNRjka-BvCuamgj@|-E| zwmj?XZp$|y>()r4hM)-&2`w209n_GrNN8I2Z! ztcJPtZVil=@xqhOo|ZI+wNE3^q#4S1yD{Eb$bwyvmp4gPqhUUyGyt<>+M*~isw;~< z8!V4FZp-t5eK^8O6-OE^kD=OGdlVGIoQZBy(ciH~i#$=v=WO$tW7Zx8O=W6(6hyz% zXd(C}jh4i0M4pLAwys%w6m%ssw72EuEzzMy3qzbn3zI;jg|w_a3L1;KA8E93WWKFN z3)BCnHChs!3%rITEsm>hqR~Qv&weQ9S|TH={8=RCK=k=$E9X*R$NwyboWP%J5u7u+ zzg&xRM)y~|M)#NA=(aqEtb3%l%Sl^t%%|9W>%u>PiwXN@-)0HCz@sW|M?fE4A87+8 zpkmG ziZ+4vBxp+AlE#RE+5LEeR-Mf?evCSq-R+381=D2HyE}eW;+uI`u>@s5C{euwlPpS0 zHGxxGnu8idiqm80&%4*wC9(unY1rLm2(L8k?p^R2WwFihh(!t?AJX{OmY^cVX(r3R z*Ovaedu=;1yZL(5X?xL)i&00+E-w{1W|zP*y9AEeCHO{Wmz{*iy8~vINu3@wfxEv? z;O_4excmDA?*2Z3yT4ChbdZAG#a4{Fzt505RkxGOZdINhbydC|wU~wyW|vK>RcU+C zjT}#h%r47yder}#*)_Qev)fge-L$>vM*g8gW>*R@M_uV}W_Bg!w=)ez4#Y9LOuqxO zTS8_xG7ZHACt`LP*DzG}>w;Z#}XpY(CYi%c(-9I3WV|Lk8$LwB+3>>q| ztSz%!!aj^lg%*R}0msYQe@pvNdBeDaeJGaabhwuyXUFl9yK@{b`8db%@`DJDY0cVkymtX~%<(df)8Re^!0B+e<9KP@XGX;FGR-`dO(lzZO`OgV|tf zb4l>#2wUYR+75UU!xGttA}|W4bN-*dxBGG@oTuti7vl! z1fA_qKBGORg3nFdUC5?>$&*a7!}fD&a8!^eO)_1eaP4w?D&#!!5NO?rv=q z%i&Io(yIpY({bFcTM&`N$eQZ86r5G;ez62~)<9z;Nw43GNR41obr)U5lJ^A1xf@*J zdPLcVO8gu|FpZ&~1VQz>62D~U%C3Wli6fS{Dc>ko0)eNZ8G8NMVEb}Z)%Z-f;?>A{ z30w|EeqPA}?+3aQu81eoUx)>~*8pFFEB`sz;>pOsu*EqoeDNm;`2eo05rwcLBEGnA z5(w<8nMe}x#fAHT$Vwb0g7O4e2IO0D6xR``v)xvrb9s;-@uK0mBaF8m- z0G|hZ8m|0OH25O0#KrSblT#9m{%6qt#OSL)I!*5Deh&CIM!y=-4`lS4AfUZWn5L2w zF?MjO@3;Z@MDz-^1mUKKVsg+~_#@CcTTXKUs^2A`wM7~L-Jn-Z>WH`xWa3EgujR6; zM&cNUT>E{KBCh@OzhfG~-HJZVp!7%n?5p&vSAy?Z+i4(DSWY~B>;{mYt=JtTXP?#D zZWZSI+t_>+X?0DTT~}rr39pyaZ@GE;g`0m0o>IfjpG~jf=1EnFnfQ4fF3DUhH&5|$ zWY?9AaOSsefxpeJE0aZ{>l5KGu-rV2Z$Z5z?Am!UsEA`PLGnp1u*^GcvP8@~{ZP3O zNi~ae%sYW&-U%G@PLPX##rRetGQK6PL1~tGABd5OB-Kpnn0Erlyc0O)oxm~g1de$p zaLhY_W8MiI^G;Bg$Gk)9#Yw8^camy?)n$3cx5|Whx5l>;XCmtN5k;DWZ^>BZ{UK&& zCDrshNj1xL%=@DVagyph<6DX65kO~i72{i7#rRf%W!}Hm_?8r){Fx}naM8hWdJz^0 zVWWc+b(|3lA03>c)6{S_j5JUwk>R9)x)2#wIyhA)n9lIh!D%}Abck*i$#Jm8fi!Xp5dv3AM279 zq%%x)aFNap2QplBaIuML*y>=t&g_9O!&e9YrAs&zMv5H#L>F`1j2JoCpmVFxTEkig zSDSt@ymfGmuAq#{FxSDgrUY=;G|E+A%}Csa?ugTL?%l;=l#41#!9CK~K^(UVf_ug9 zM9K3wJl-ORih}!+1O;(947k5&8!F{4N3zeID4C<^7;DZu$5?Me>5j3^pdF5}?hoJ? z>xlr(@qD9P0BuIO0K_O43vG=U>+c|qW2_GWm=N#CC>PT>#`+Qf$5?Z@aiU}{T{9xa znrY^#V*cZ73fR7Y?Fs~vuKec^Vhyi$qu*ywOPV+;lb1%IN%IQhz0G*nAPaUuUObWl z6R!v%k`+6qEsFA6fMw}rgXI~7D49>xQ4xloW+X~pifS9iI%w3lAcAn#&}S(kFsyaZ z+stRfTL*p2{DSdSPCB2t8s<6}r#tX^UP!8~^H6p`b2NQJh(FigOb}&iT zp9%yHo5W&7vz0a$Sc60K0nC*`Sv;7Ic*7)Co-pbI#>hSLrf8e~}Q;3$I(uN^=Smzfx5J2=`@!EoCF%&{^T z!)^!17-abEV2MG7;SQD>WH|2NScAZFbC#4Ld+CC>GAuUYy1$s~ zD(6yRX9i8g`=j}D2z%h5FIc1JybnRq2Y`>&&wF+qy^iPwg92TIi26l?5_&Ylwi=Yt zPc!T#gK~NV(aQ#vLc;~<6@x1E<4pIeLDl+NqSp+n(|0iD>ju@U%%3rAIsJAp1e}w8 z8bH4rlnlotQ2LHX@bjKQK?!ba>OTdQjF%{xwLt0j4Z!HKRYenUHl_a(bYX;|AF#-p zn1IAYP>z7B-<`Q?l^ci9sj=LCpyj%wI-6qUCn6}<7xYK1|9;S)h!yZb&P{^hfkYVpk3pw+N94glTok-0OW==4 zy8^U*4QvT(Azab7*ce{V6`cAZe_%*Vp)c^h#ox2Aw=3XEF`_}C2 zUc>G$GIq-`2j#}hwdI$54=Ix?m0E)=W#$gH*tBl<^RDk}qQh&Q~U~z8a zK;SkG1a9L%5N#Zcic2^GxhK>3;X$CZ2BrN!BlWM4jRUK%bcJjj=nrtmi9?OevT4$P zK=A{|w$LaMlQ4XNU?lT!b%FX~lbbxroha?zpqeH~t!PW(>b#P0+hi{EL% zV<*J#ui=H;CVqbt$cf+o2Cx(2cNXNt@1G%!6TidUeVh25(VY05mj`x2{C*Hx=fv-9 zsuRC+m*d3m%=$eQ@+2dYyk7{C-5`jriQOQ`b740K=CQc{4Rr0s{BLX6FEd0NgqJXw zZiB!yZiB$#avKEBFSkK>7^S-n0`J?p4MGl$a2teP0B(c8a$2Gdg6Nt=8w3{G8f_5z zA&uK0j0SKU1ZLoLO_;`Q5Y7j18-#X}cP>#gq74Gm%u^zuWRLo6pU-yr0vW7A-ZHiu zgzof*>}g5EyViMW1e!GWGu~##y8>CT3-aQThQ}9@ z@;iuR>snxSO?u<$_?D7)CdsIf()a?aYqEv8SnDYq87Fz?XgbL|fs?!wILSNHcPx2l zG$(l{aFTZdCwV7ul6QiMD#^L96&Xv59eq$C*qYnH}sB&KVDV90Og%Z&?&hPeu(AH z2g<~&Db4p97*bP2zw*)qUF;Ws`VrJhngq;uAVO{yE&?WMB!j;*{A7ffTqFaL%qJn4F9d^>H_MB+pf1T?I>GqO?ZQmS zxf#$aNz_WlQyBg|X57poOwIa%D^E6<3>LZ!BrKQrEs7tyAgOfEVJKHOi@ZBxy!856 z8L+98*f)1!`$nwxRDZY<$h-$sFx_IHS)?qRf3zA{$N1L)u7}GmoU=%^l(68p0e?%< zVl}vuOTvQhd1?>1?EIsbt0A2^B$-oiFOQ@ZYN*J@j|btqaM`75XiqK;8lt0rlCWr@ z8kXdoF9W5B?qjfw!{xl78L)w*dq|QGR2%@fFI?lCCD69P9fYPKI@jwF$ji&q;8K^O zd8fcM9!%gM(n6-a4QanGBJ|q;Zz3rTy_z$H^b+7RaEUr(!x8vB_67k|Z=fR{$h|6+ z7=s`V9`&~aUU-72JaGw#9PI$5y7+P*qUst1ah6yz26*IPbG9--B0~ZFU}P>Ax)PHR z#5p-RKObJ+P>F+W(A=*EorEAxhf}^1)N})aF3u-Y!mkpGQ7Inp+$uq?3Jlt8gMRzf zplt|Z?cT}HP-@rva|F%B4C#~_isOjo;CNh%rIQXuC-p(lg-FglgY*X5Jyq|*#;-uq z$xOOT?GXjD&(Xg~T6HjjSYO1q-DQp_LM{@0p1v6pFF18Pu1WF0;>5kR>LF@I1%<{G z(h105GFPxqebr#pg$nGBf%{o&3aKpL6jHLC4J5aVkm&7fAeB={)ZP$ML61T_wBM<` zK=KYB#5#x~@(dvra32CgNQ_XxeFzL8(chDXkY0zU*6c$LqSx$0NL6W;^&wn}_3%|A z4Iz~ydwmu&*lM^>L+k=>M_>qvJN}$CgoI6+%7`H( zJU;j<;C2LtkOqUEvxbmvVM!Fj!w?evxG^GzkQ(3(^hqcOhL8vn`i}~FfI~|OGI{}v z8`_y5mobKr?m+TV6?_-}(!KEW2%IzuQDi$3j@$zbj~>BVjF#)(N?SunrnpHAX_b(K zev~EbCLp8d{}o`2fSmp=!B_#Mn%@kDAtYu{sYBLxcLCLUJwwI|s8d~y5>mML*{p&! zghap6{A4f;ArY)D=57RrkXV1Ei>)CfBCNP+cJyV4CatPfIco^%Wo9XTcu+C@N>67l zR_R_-=^loV{)mu-ew*OXx=#VtsDPQJKf({4%{BN0{-%Ikm9vJBdSJcN=RA*;#~0DB z^zDxToDh?4Qvs(?iQSPbCJSf{Au(9_13t$>qSLp<&uP`!T;vcvhsMF5Td zV`w#wFPNy0?_v0GdO^_apN0?|Ua+7RKZOvSU0jAV!~AP8d^oze5@4j?4IwzWV6;~M zRD|H*;ueIA^En1Mw_v|d^#6=%x2=gcx=t{=NV>v|v-W`G+GnoLSt1 z47U5_064N>*6*pH3Ei8shLG+6DPs&FNv~&&AtY8j$QVON^d~fTBrt?@JU~YC$O49t z2nsUR5YiVMOkIgOzz`DCRO*(C03Isla8>KM4B3?8{HoJ`UJS6g=1r7dulel*7(yyQ zy&LsaoL0Zh4glz*`?Js|lam0NGu99i%V_}+LrARiNB}W}#6ny3IF|EV(cVZiPG899 zIQ&)^#!cKTN$n_2k2&kw+pyf&Cs;x z2t!CrGfx%qAA8he`#iSG6G*xWUOP_$*6#|61yYe z$9{afBjLy>e;k^Q6AF%I;Qs{)aX>+k@o&dO!TAJ1slN&U#}iCn?RN&i=>$uz_pd-T za5%wejeZ{hoJ|lk`#%D}(FDOT{}Vi;IGG@5_2US^!34oXmF8UF$3mpVan+SOl7%{c z3)dHI4I!NXE)9&KF@$s*z^mFCLZYJbHf;?du}a&uHH0M3wzh_lXqo7PVrvNLEu?AG z#nuqg-+`KRu{DH51U-pBK3~Ft=*GoNrj!cKhBvqiLm2Qi*NtnDoq%^R}nIW)pJO;!!a&*4E;Y^u4wgj|c*7Eglgh^bs`u(_dDnjJ6h!7?RW0;t@fqwib^F zDz&wEM1Z#-GiZ?v>a?|Z#E^PzEgrGc8}(|u++p#EpqI85j|iHywRl9(TU(1q1bwu% zctp@wTZ=~o{d70xHcE2qudT%+hBRwy@rYo6wib^F25M{Zh+vSm7LN#8w6%CdFgP-M zX$?vRP3X(II{fr0=zu&JyNkGM9;!4mTyyiFS0g;Li*OxEk3odY2*ZNtr3@Jg}GWsoo z(E@U+KeNm18nC|Q%u?#VTP(m1A$AZrdlj3EUmaVIUoUn$etp%6o9NmkUn1QR&#Q;W z>%pF7R~pMjX)H-27%1->`czPY{41=nCQ@d!3pY<|MTjC!)WYu_&v40vLyWKW;KB*) zI1#L6P%o6L#2!*Xuh=c5xYv{M$qcKo)|i;llxlIi01=N|8 zBNoqB=MK+;v;c4}Npn^%R%;W*Ae{_&JY45lpj1?V;;mJKXh})0t!0T9Bk&wXSa|f| zYHhyNJ~uXDyorz`T>;uK#DJIR_kg>*%Ooza4?XwuAYRu z04@~50JW}>lxe4VY64v0-k4JtNC%w>crr;p!vI~7Wn~@(yc;e)f5~!nK{-kFKZG(J z9IPQ-AbXKx0S+W#k-DG@VID!AId?DUO48FHJq#BIn{+`VDP^ZaPyttXJqznY z(pbR3a4(-7yvEGNT8z#AE7rMj@PE85ZP3{UxR@j2?paX!8;0z4vw z0qVyoQbwQYsa@a-k3=>XNtf*n_#Kj#qT?@-@t+B}KS`fMxN&KY5BZsZr^B_ZKtg@L z*DxGkC)mJeP*2-mF5(ZZU&jj`6{{94XhqRc}Nx&Rrb)iDefx zqyZIw8OiXd?S;8DNhf;3dQasTkbjF5kHA$91^57-_uz&yTGgJQq|frOOT{_qz5v7F z8ANa>z(Mfr4>xQcKn>!5jOtX)2Ur5?k#N~3P!T>>)ni8PP@}{QP`Dx#pdLJ)T$aJv zFDzoH>Ujv^8enTLWb}>79*IYT&s26DJh}wqejPk~{thvj1Z(d(IfnTD+I{g4LWprO zmA%JC&OQ}+K8%tpRFBCoiRyqd+b1qX43?Cg7~N1fw*OdiY9JH43>O|jbTeZ z3D><5(u$CicFZ3=Bvos|ykOGx`AK8!$^q3XF$AHk-W@w8SBXV7;qUSjQYMtR2qA3k z8!kj8&cd*g_JyON4X_=Oy%hoMNEL9I3|_Ru%9;9KQ8Y%-lJeRLzWP zxHit|%(by*mO4Tft1c_myfmNEE-UA#d4=MeH9*amz+Fc0S<$D;TL#;v-T9DB&=fM= zh*H2sVWd0HQWJ`$j47oH)I?dQF2h_t2M%k%B+30nfJcNdKuwZTnjl%|1{X)UlS*0c zoH)Si;?}okQOFL3lpS;3DUv@X<>r2FhN?FAZ?hSLScfu;d)P$5a)|z z7rr7?oGj1?dV@F_ppo<@;$(kD(VK~r`58@bPUV=1w`;&!CYVtXM;6MUg{=Nk5Q^zh zCBu;^W)pM_o?OdeU8!j1TNs)eV^T)d6o zlI+j@D@Zy6@HDv85oq_pXg3}su6x1SDL70^odGJ1RorN(kfECul#A6ebk=4Y&R50` zVJgO&#`Z^^F}A$yVLny6Y0lz$V7!^XE7fC>2UnR(x)DY z1vvDKy$df6fZygn^8m)o0~j+8AQW!+0LILN8#B*gnR%$KGEOQ_8K)qUsmmj39`k~H zm7K4;nOn}AxxYg#>=!4`qSuJRNmcS4ve)1VnX|7dcr!Od%|sOLZ;&%1C8BWu`tTQs z6R7BBE|XQdPa5$_iau#Xv;PUv=AQy8wp3Orrxx_+lSW+0j8f{568crbX!G+V%Sge4 zp=kmm1rLUn5*R6XFtjs4E@8C!e}d$&J2Mvl;wAX`1)Q`8rCFt%K^Q%ef(N7JkjhBG z@hNRn9Hrnvs{kVf4|Wq^q~O6A0Y(ZQj1^#{;K4WnMhYHX#T6-dFkV9HR8e#l7dD=Z z6g-%cq8|(AM<{h_l3;a)Qt$v;XsEl=8A`!}>4G2yk3;6Gz)_o4wSCoS6SJh4EI6o` zej^2k=^4{1YkKB!gcvD!aA+Mx;xIkK%;MCApp(9;RsQSnSNZI!=&MGBctk}C9vojp zzmbAN;wA-{+qjVpm;*8WJu3xgu=1=F{E8SV=vgT^LBg|AaDt3yrQl4H^Q;v7K5WKI zJu3xgNTp|`-~`p4m4eeaL!JAY_7b3a&q~2h0ciBB6r73rcvcEd(Ck?$I16g=tQ4FU z9fo;U3eL-JBRwkxXS7z&O2OA7WSnQE;OzH_o|S^LTPJ%~3VsAy_nc>?;B4wP&q~3s zK?d7BD+OoPP~0y?_eNhe`Uyx0qqr}!ctsW+ zBLxp$O*seeztD*dd5MuRm zis|>+(~{<+_Gtu~G>?!A|nNl-NN-nq~Nhz)3n}hq~NjJ(yIWB6g+lE z`dR=Z1&{qI#VQ#ocR!UN$WFkYFodci{s<&YQ8pW&Udk3GMGBs1 z`aFpiPzs*tla#&}*=(Y(03(}C^b=sD;EDbMj1)Z4EWk*?69WVoDR^R_03!uY3=&|Z z;E5IiMhc!7EWk*?6GIa0bRz{%3>9Fc;E7=Zj1)XET!4{+Cw38Fq~M7W0*n+qF;ak$ zf+t1^FjDZuXaPnFp4e4@k%A{$1sExKVmARs3Z57vz(~OpV+BA8E&}e@+-8iGbYg6N zA(sgw;Eo+Bz;t44fq;Z6W{-EKfIGIN8xzV*+aDg8X)*bQo-HR0EzFo@Ll&%+AO)l; z|EC;NCX#qpx_IJ~m1<#IWTx{^MjR=M6H5vK6T$x865(1^y*t=eU7O`h4E@FmRaY|@ zUfs2G=#M*2=ek_X@V=t)ggk}2)$41y-_?D4^U2r`Jn>Yx!o7YEG5)TsiJn>*AVR+! zS6;nO;a&s{5;Cn$>}fa4>aM4BU38Sv11i`--LlNnOd=Gt5+VgM*$+&QG~PENoJ{uY z(K_tnn+^*JZ!@uB)8mFsj~g}}Ig(Ac zCUPPs`&2}a%-_&o6EWGvZTcp~c}#Xl*}-dYF&68qE;};W4IqC5lU?hWZ0^M)&G$AY z8-fJ<kN_LLP&bDK+v+bGekW-cnoV2P<`JD`2hfFq$ z4n)-i_8mK5vIF7RBPQGC8j#7Z3&>`?)g)4W&u6k3{B432*vMW0611WYzT$4oZU7*&)1 zK_;7pep@D+X}&F!%{24Ow>$Zg@;M!SJ~zHV2CIPY8EbZ?l>UG{onaW?19@o#nlxmx z12Wl}s}YY(c3wP^d=rmMwq!*nyDf?e$YjepOD0>MHGF=9>n>ShyH4fune0gU{cD-* z1|;5r$qvY52h1^2e&0DJn-}pMlYJgQPKBhAx3hJPl;6LW$u`ybdL}#IS|2ID|3{f@ zmi!-JvO~@Vvb56TxGL$0$tFACm~65mj>(<{;FxSy=^L2rtYxz2B2A;tS|)o1P?OGD zCYuOMcEB119EdV9*)pY6KqfmNlO2%BE+dm|Cm@;ZfJ}CxQV29P zI6r?FVO&$=nnbmdZmN{z^3(6dPHH?U71dbtejaB%LQ2I{#r-&S_^3p-kbWPq($1 zhB#{IH_hQ`ThC8$P7vF!xo`0s&*hHnDFezmcCp`c>>y}DlezaOho(=72>1^`g}L|G zgq+!-yQczGY6SJkJmq&Qw0DAfa{5lXFXnojyk3I7#Swwn?n&A^x7=?e?VVft%c8wU zVcXuLFmLY>kM)vgP|BL?*>UfY%oFgZtht{5_}*g& z0YBS=8vS42d*pU*@3E5tezvMsrL4uCe|zt-gMi=UDgypW5%8z1#h!n$_wYG;Iuh`6 z0r(%=dsIbsdj4PDdx(HPWi9jk@809z-FwKz7`|%SB+ZJ|@UxU1_8$MPfWL#iM?BhlNZp_q zX4TyP?Y+l;pMako@gLZGveMX*az7?cE_8vwy&qNZBjJt^^ zK3QbA_pp(f&gb4kisCGgLac0_n+#iM=h5Ig6VnPW1L^l*Ji)Yr&lXeu)dxVGJ~2^( zwzwd&$~A*=zex|NCBOYw@X&vOQ(ewRPPo*|ob+e-F#`Npy&Ro$+UP_P1EC9rm>-i| zOkR0AeO>bz<-XvJyBTJ=TDaxzER}pQ3PknlUk8kz2gMn<9`6HG!BYkYvrEW~eDxj& zMSS&DC~Y||!)-PN&;ASz`y3k4eP~4Yp%LAOMs$x% zD7p`gYE2}%Ux37s=$?LIpYMdn>c@Blfxg%jN`0gCivXw@<%`Y}ALZxh{9Q7zJs`9Az|_!|r zzshGnManTB!5^8br@y1`GNtVm(b0HBBBM2IH;%r{718g<*a)i}L*R_o5ICbXOyg|E zUjyaC{h)-aK?8BgGB#>8Vz;^vB=M@CGg`x@I-@m7EEUdZ4YP)F4DaVg$}v9x zDQ1*oq}O9cIffMvVn#WJerMJ45CCV@lAs`Fm1DLbS7)?_X`Im-4wo}p!};Zm*3hhi zGg`yXu{)zRUjjIzHI-;lbIdBou$&eEQI27qM*@g)3=3_IjMmg3jWb%)7hponD#tJb zXS9ZCoY9)q0M2L)mlbE#l8e*~Z#*s)LOF(MtlXYG8nAul14#lIto-W`f)$mTzn$s# z+0!Da;WrZV(g-wZZe~1MHOZWXWbA^xcq9cT-fN6PFFU3!it+w(ArQaE?X<(_^D#yqZrF_mdpE;)O712lGkBrvP?~K+E zIHNVQ5#Y?l9|r*C7}B0cBwN?C<()fW+DArfWV!C}14#^VA4p;nD94bNwpT>&W-eAa zh9jf2RgU3kI-@lN&S(vRGg`y+&S*^oLW}`RToGk7XS9aE8Lc63Mr#P1(Ha6M$8at@ zhK!}faaB#;*(bqgKNNE5fGWQwO8V`7++UNO2jPa^;upw=+%i6c{n(XL2y}^lWY?C=srM` zNm+dKQq?=llnVgoz}5W}x#>O-GWo657uyz^$FD^wa`e zMY&4vQ-FIcSLtcU@bHY`Xoei3RkcV8zk@5>w96OlYQAwaD!Wsvz&@1kmA7}*e)!j+ zTCg93LYB9w%fX0HVeIQmx3{f;h#o- zH{-YVGlbqq`mjPWB>toHkF2B~nExV%C)m~aZz6q9T9IL{NHr5`8hlCC-B)$A!?6N5vcthv8odbE;pmQlK>5}V2b1}K zVI6*F>SK*@uosP#GS>B%h=WTav96ujb%;+XC5&;tL;M&~NmR zVU2^pSmT(+>RVeJ)9DABl~@lF2FWxj5>bW+?goHvt&ifZ@|pjXv869L;;$WJ2 zs(}C4qaoWDvR$D-(p5k<#Ofdy(jTy=CC$S2X#|=y;}}nj?p2^Xc0pd=B!wp4@+d2I zOj{HcTnsGlZ#Gz-H5lmPlk-%BF-BywXo=%FR6Ei^F2S7ftPV2$P6wF=1#bdXuH6Hzjn(?KS1I>-c02bsX> zAQQkuIOoC)WGpSVwgCeY0`@}**Af{~D1?z%17gq@jVj?%V8{PrhMdlyTM_Kf$K}p= zQ}L0gVQLiKmAOR!XA!7p;mrK*^bxgyyzY~i71L;}-$eRPihoP`WAtBL{387?G0yeHZ_%G5{oZ28nsD?@|AQjY z@M*d*H73UilcN2t1Ja#~AT`qOB5k@R6%$>MOOYVmCG|e)>gj&p1Fu}0YC=e$&tphk zTC9ib@dRB{#Ry61*9p3%x&UPK+XUSuw*q}Kp5%0W>L180r|THfRB|&wrG9~+w}3|d zN7kT^fMNPdhV(6Z9nmK04;j)g!)~0c?_)@Fl9iqUqjqQ?KTIhDi2Gr`L+Cl29lL^P z9!8>&5Kl8IS9%+wtR<1+!nP=?$7NuU3+^a9IwGqEnk~#WXn75v8Ii-&kyiC=MmBmc z&5ZOb2rDCVyjK@4KV>jQxOalY@&gv5nyGE{evVd5jnn#GV`rw_H_Ib|UQ3Tv`p`nw zOySNGewe-7`E8n?L9_-v1HA27EN1=B(~xeloCYc9Ht@_pg{we$Ju6t=D?rb{^@bKe zuVSu({`sEz5|lmSxVMh*sbUCk3qr;rB*WY6$h9vsAZvcGR6o5Qus;g!2`3u- z`@l1a;1>v44$qMURG|JZcrJqL_XvPW^nV)v{IwUI+{`S?k)>+EeR~W5l^zCM3!>zH z50cy&mZYSe*30+TvrXac7UP2iNF37j%Cfm4PiaLUjGP8piODMJ&~sp3eY`pq{E zzfl>w?ZzQnwG+zFEc%<2p?6S7Fu96CLT6D(_?ODiQh*YLgpQP<8SJ=y(cFu;eFDer z6F6?4X&krDGiAr^GsJQG1diLM3PN3Vq>w;8LC5X$_MqeTnaFYb1diKhL5|z!B}2#U zQ?1Z(`;6weeV+U|Zl6jaj@xf{<8VPNkK1Qc9k)*vImhiYYkTAHUnoPf;*l~m{ohs@ znrXhRGBl6b-Hk)4^|~8}!vS{U#vuze+&*p`(iXP6aYzoj;~R%e^KF%(nFc~t{$r2k zDHjMNz1@w&8mEvTX*yC!FlnfeP{Lrjb|@Or?1#Jpu13~@iR>Xn@?-C`MNxhaV9`Qg zt7WmZS_y|n7_&c;tn%7nq!G;vg%Qh7zhn8wv()I?p*&W~=aloAW26!N4*U_zPrqaN z2^`DMciRpc(V~^`4@9zcjWnXEXB)Bn)G1RD%RgSK(~(9rlh|vAkw!F)Y)33Vhet&$ zKkvsmmY=|}`~;5WXL`r-vt-BeGn!-h2^`B$;8=bF$MO@{YlrV4V`*_*6-QbLTx6na zhnkFm7~jLSL!KQwjp&5{P9vIC>R2QC=g91XNF(|fq-oQL{vJ@9Ml{hRTsvfqd=5k@ zS2USY%6#1ZdJyH>VX3G=vrOglGP6&U#C|Ih8ZGE}(_g_p$}PEg{#C z$XbyxF2#Sn{@12f>CUXxg@|_^oYX4QeJ=994sZiWOI5ZzZ@S+Fa61W$RDslL3&1A0 zu2QQ)sTB;ib^8Qmz~V`v91ct=l*56kg>pEsPa(eji8F#iFz~YT=x$Yy`BeM$R--~d zkNZXSxSCHK#tMr9S^fH1P(~M4e>57^1-j$c6so#%#HcIAiGpF}<5ud=F40C`0v|BD z7g=a?2A~Z?uZ@aCf^ulSl?g@F7A|H1HqPB+1f8#q0Hu z11s+UY~*(!vTiE!RQo%GXeK#>ftV?Kb}E+KnI&{EBy{K&YF%w${dQUi4;rNm08nkS<`D-(_vZDVOgVCQq1!jfA6ZR z7~OPU)^uL6Jx@6oA;tC_g#IBs2YDNwdUFmkmtJ!YLaIt1kDpKBGOU8HhVmSwhFxv# zk+afDluU3A@+ka)Dz@h!Og1d&(F?JQ?GXqoR%Y#y!%mGVlp~Puf{Hly2xKJaV%4%T zZ21*SvPU5Ft3q=G!cvW<3G9&*7)=w{BPTGLCa_0NkSjFy$TuQ+sfx|OzjQNxo`91^ zp)`90G6h{OnkF~`VN#=Mf+G+DqiKR85CWrV0(;~HM$-iL$O(+53G9&*7)=w{BPTGL zCO85iFq$T?M@~?u8qB^Z+#B=LD4K**QuG@|6P$n$tnNfb6WAkX{gv)y?U55<%8Qlt z4TvVK!fI&kk-xz#r4J7(rr#)=;1q;Kn@_9a6yzO*7-bXKBd45xjfyd|^gr-JXLF5x z3IFgIyQ<9EBkzOQqHF?tNu1J))EUtDg$eYg`hgHmRQcf;#RjybP93~P<>!6v0MSr z7+6azOw=c^mRJay18a$e1+@g$63Ygp85USeEY|~!46G#-SV_0J^u#+9TfxQlU8okzOw} zry#6&P-sp;=r_tHut$ChfKfJqJ#vDALTitl7ln+n3G9(GjZrp%J#r40Q8s}+az4mL z*#xH`{3w!9Hi13zGSu5Bo4_79rPfB-1op_M0yGy|d*m#q1wibPv(6&{#2z^dZ53q` z*dw2gG)CD3_Q-jyaYCWBN6rk4vI*>wGmTL;fjx4Xe=^D@ut(07#VDJ=9yu4Q86K5Q za0Nqxe~djXX>zDcUK)WW&34A)=Z`AxMKU>3 zY0I0W(8S|`ie$x(Y0FB*L<59R3L7lX8s1&RJU6lHR84dWassN|*(#gxqr-tc1)(2< zkG8@dISUK|t85}ql!|e-#h7Dft8Btgqz3jBL_VGxSW7JO?bN_pVmTdIWddu7F++O_A}e-aEwPyD*ewx55`neE!Xz0LBdxPlHlaF3V3kccGAgjj zCLGNmu$EW|GJ&)*iWN-g?#^`F!wkuX@%V`Go-6JZq1fRod=Z zd*t$Ld(?N0-(CDJGW(#DwMTv_(lqK$)*ks!ftqwDYmb}=TOwFy#*lI#dU7$7DWzgO zcZof~!RBkOC)Xl70XH(_XZ$$;X<|>o*JBfYMwB+7PFZ6`v6%YXVDj1UGSS~oHnC-% zHB&A_;?a0^vTu?g@T{3~f`n(yloMn;Yo?qa=UFr51f`xeQ%+FnSu^DXcsVlb7RkEK zvu4T}Qtw$aS~YS{ zDru*7kG}|7<7_oS^o<(ltBD1qsPvEV^KKMhs~X;!OSS6C8JG;|r%@*#TbEI)^b^GC zdK}o^^E4@4F9UykzVY4&PI{eqCBbk6OKmDuX)pM@b-~ZAzE67SZ^yk!i8dpO25svp zj7F2)_xc5-hyMMD)-3_={SoCNPKe3(&<9*M;;(^DrH zVKXC07fQ$RN9|e&#x~n4_AbNRf^K|-s@FN!Acuuy2?Wk1I({tEObp)iugnYCvraz5e^G!R+~S5m53SQ1(a6 z@4)%X)f2wV&mRDt2v<2BiEhH~OBJlaMcFeYqgN;D+`f|0m;z)p6J!~Ihmc?+9LD5K zzm^q$1L!5VqS-UmkNk2z7DcmX!P|*me}Ov3m-lA&BA94^t6ne@q!jCflfCK%vw#W= znw@+f#ok_sdkiR4<0x-Aey1WDz7>T^GGv$ySz$tEtI9qMk?QxuGxDLwO4T8s`=$E7 zK$Q$iUNLc`iG&FfJCK@R#)n{IYqdOLq zp>Wm5fl|mh#jaTeP;9{Ls;hB!crvP1LNm%KU!I+_kYp8HvJaZOAD-I%5CPo=dBha- z8|*tLMk0jID5#-79Zxstek$c_oH#Iu5DS7@1p2FO_#%lmxGePGrl0H8J`C-ajqu^I@1G#E`ihq4y0z#ir6cs0G~kG3Q)?~5mx|RM#^!ZRFU!vpleB41xht3&jUR} z$^v!08I$*cw!>ivZ!kkR=04O~zv<~`QRl>!_+g7U;f_TE3U0+?uu|GI5kalerkB_z zYS^NCt%n(1ILx?4)82i6 z#*wmOCP?z6oeuZ|AJU0&ifn<3K4UrSLLLFE|cWlNqXs zfWr)F4rnq|rvv{`XtO}7;OJchc%C6KS~Y360RLQQhlA9Oq~8JFP0}hb5>kn!mwW0c zxTJlV6DM|zhJl`?*Bf*_; zm1B^IPeWpM`_!N`g2DkYlYrT+Kz0RpVccRKm#0^E*SR71uh)+%k?9>X)B7!C{1P0- zDCX60j4H3dTLX@LmN0!b6mXCsHG?L7HW_%l&}M-oeRc%kEV!bTvlvbK4C9(K<9aee zmNCJRpvbU32y_>mDtHyIpv{`4Cs5Dlq@F)1wexGUuHyXq6JovrhnjBIjf`9RU!Kaq z;eEPU_h&0d1GT`R)GcPea}>~AQWgvVNs2uS@Kll(fg+RX7N8r1!bnBTX&c~HxFVQ< ze_YFYi3RToEel@pPw@D_`LO@|gqAnlY`{rEngdc9=fU8&7C?+z$i#E?m{g z80OQ_KA9WO8(!oT1T2S3_CptNZXAXPoF8jv;8Ti|K>X@T_`K#yxD3(UN|^W!Vs7i~ zl5#G{vhXFXRbCqQ+$=D3gG<3gFz}{x+cJGhQw&)r0oSfk+k{vx|+Oijs}_oSG~A-Fg~(Y zdIIVb`fISzcUg`~a$Vk3hSx9z89&oLYj`zcUj^4?9m2uXskQCHZ${Wna8PVQ1oChj z5CPq&TUCN-zS@b{8L<0qGcS_Gh;w`=NVrTgJV)$7zRC9~T&4zf8c;p3UTWA4Pwh0_ z47=t?F%1iF87j}`Pg3})V=$DP5cEBe2j>Tw%s42?rx4Du+Ixp^mDp}mx(pHDy!Dhy z?~8V`tAvFH8^vKPD8=|rknw$Q3@i`I8qI16`!GSv8htl<<_R`YFgmgGa z#hg6H04{(l8H;6mPc3rS%YoN0+Hs%=$54JXmLNDhIeY3dz7~4}^&n*>G}+`CTmp1} zP-cQ8&){o-&lu7i(BvU3zs6HJIDh3VkUI0Z+y$_oAu(DVX$yhp3GHx@8b~@H@I*su z2CX+~_1EH32AscYpxVpSemLMDxUuD9bq?Kap6NrhEZqkoU~jm}P6*^Po#+S8SEt}1 ze2)FK6FH?KmPU;$21BSvY8g{a=B76}LE!^?&sVkV&!Smsv>Bv6yUQ0Ua36;6jKps+ z2cj2@NxdimV8BDfSzzwv$2qmMWy?)^PiBe-wX6{aLLQjEDk{f!p&o>5z^ru+& z;m}bR%R|`$(1(QM)Wxz9*dJg&i7{VYDo^|2K!=gCN?j^ZmH{j!0q>K`q;lT_IuWi* zKlB4yt8PJSq=#>lZT%$(I~OiF4B_nI)1%kjY`iHag1AE$PxTVFaq;BJ?7BO703x1_ z7sM8m+FOy4cV$K;W+249LT3wi##iVBo(JkRTC>c4oTh7JRqeN2t&zpFPk+3q&fsfm zVi!blNF_I7WcV_|XK^@qd>K6f(pT$wM&7$f)t-h&WF|+JhlplmXVut|omt6(euIA4 z2$x%+W_IO3z6J0K9LD5u88`1nJZx~OCCk-p>E9es0!*=3&juRb3l3+p%1{79}VytJb!?zTLF;13G)?h!1n--=Bj}-b*BJSfm#Bm_GG4; zk*WMh=~(wG-y>I$@9e&Ea*z9A4w3??JxA%z<^n99XCGjEbf6jEdDqI=mI; z!1^F`M1?u9Zm+{Drt^H&V@Dlca+y2m@TT*OiZuk4P$E%14;TTdcA@GIf8(22c1gsz z<{2EzSc7BJ5Rw#&349>KW2kpX3H>UWXE8y(tBo&;ux3ubm%!=w z66BJ`V#2*hUaG>w@Gs8VJq{;rMSQE@yEmp+^hFWV+ zJANA>?u#N{0<2LXGmC$UA3EtPm{9xz{$3%wDq{_f^~P+Ez9>S!`=SW@Fi>K$waA`h z^TUfBepmbM7~)3X)h2M?)h6ipyV@^8LcbH=)#l}yx~53K_eVhPyV|@lw-evhWytN0PefmjMf@`SNl$cxbJGS-`#h$*{zeK?`ofd*17L$v#IX8+7BWF_g!sf z{hkV&(Y+aKaO_@?lE!F)^m-Dnr{Es37ZD`$j3&r;wedxf6z;apu#ApKRJQASIXoB44gMROR zNaOT-=KxGdTB8ZfzPV#l;aQQ=5nQSD`edZzR3pxWMt;O?{(9h@%%G?opWE^%$sXu zL}X-SWQO;v{Zf4JezjkZ04_~nTrU%0A1J|M#qDDs$pYOzws7p0ezp0<`_*QaT2f|Q zuiMA|4NGzR*c_R}{A$z6*8A0F!28u^!28u^{?>lAnaumuX2AQ^X2AQ^X2AQ^W&ozW z#DyY=QhMB;jGAdL`HPwM9)Rr-Z`ykm0*{JcZFm&94FPZ3JAqW*v{z``Jc<-LAVT!G z%Z@*cJoC~XciHj12+fDcjSX*j6k+HfTX%!0_uRI zxELA_wXaBEApO(X`0}6tcqE-tK%R#rFq%HU z8-cG%U`oenFFrG=eXYUI(lis(Ol4C5qp}+x7`o4cA zY8;pEPw~6Vj*>{eFPig5=*Q-zZM|LAAf`yBK7bM5C*}Ln%okTI?G3tSNU?|WJ620D z{$brx>{OnGosjHj`|R>%@ddoy<>6HNcKbm%APFo=cb$tZ#xdTG_i#Fmv-oLP>YajT z8V;*Il6DhFmm_!)p0TG;+1Jwn!t54=-^ygqyCC^S+C$iV4Z*MA=|A(YE>6Cc_L1Bg zAH?1~KAva!o<&w=nuJi|K2k~IWH!+^?EPVKov}eXA zpxt=8yjK4e-6!;Jtb-Kk(et-2Yb!zTUYSg)15odN6U*CA<-WZHDd~o|lpa;O@o8ME zR6QIii6jqeO8ItVx+9322U>Ma-Vx(qi2LfN)Dss01L{Vl$2 z)Nj5`FP3^)J9J6E!lJl@-R2@XnhZRMEF_G$3%gIAEd3#%nf^`@;6N<=fja4~uc5DX zYL|W|<9|9p{9HVBjQ{WJGW-Z##F!VKb$;@n<4pe^1mB9M``qWll%${dbw7glG3q7B zf5}eDFA(?J;E{Fg1`nm%btJXg$cLeUyp$q|Hh$! zK5FT|2(9W*`zhg`h*U@58TuGpkPoC4BF^;)U&Xl2Z&JFJxSJ7vJD%!7H^djAAi#&) zS{&gQL%*~ZpGaG;)lWKZ#T!q;kY0~ZB*^#2xzwL4n?^!*g+WL<6EWYC7`Wm-1I3G% z>ZDB0zkD;WGX0RinwpGz(B5>H!1+UCq_fYWk)OgtINvUCei)$#7(+nwkiv~ z3lY--ddV7W7*iv3^4ZW6Wi&!R1-jpgo?Nx81bfQzS?67x#2TThYJ>*jqYYKn2vt=h zG!P$WsH#S&sv4oHYJ{q)5vr<22qp6TM|IB{p*f}zni4cZQzDH}g{zMr;Ay9XUrZ*R zrABCOX`U#9>JVC?GT5^+=ujll>oX5QWe`Ar@?QYw%+V7NUtWzL(+=_7v_qfAyJ?5` zjynX;NlI&Ee)gxoi648=4!Qd@??-lMht9#j3Y+^aJkoE}=Cng6a^B%ZPw+R(LjCD) z2K?!7t&SHx!QU(c{`5Bk{`5Bk{`5Bk{`5Bk{`5BkFf~^=Gh=GfUIp#YFIlA14)MLUcIbEb;4_g31W+Qk^{@zUEri0^U_$w17noA27a^~dY9O!|N-0+4l~NPPb1iVt}E(E+%>T3x2n><;MzsZwr&fer{N~v!mk5@|l6ajye zCkxmMr4$vjd zDW&+{S}7$Im6VBXWtQ0Qlv39+_w`UU?4S1W-7BRS*ppJKLZ#FjkjS;Q-zlYdQLZVa zWTI%Pl;Rh!lwuYrr5M-mlv0;qv0zFmj?A-FN-_UmS}9c_E?kd-rN`~bR8vZkznD_$ z#}MqiQfdYSTCbEk7=hMGDWPpsO1%q({j$#~rH(+Jd1;?hN<9yu`Dve1N-=aGlu~R_ znFBG6%uG-!DG%YbydNUVoL#4p7dZr+!V;dP^f^PWzUucVv|2Csc8NgmYKr?I*A zki44Kifc&ITAhR3rnMq2mEVAfmI^CE!xUCBjHa++z$>g6@CqviyuykBudrgkE36ps z3M&S@!ioW}uwuX~tT=vNVa0$~STW!gRt$KB6$4&j#ei2>G2j(e40weV172apfLB;C z;1yO3c!d=MUSY++szmVZX+Ti$txbMsDD#+tu~+874i+YXa|OmFg6n9}AHR&0P*SbZ1)udsRujrIzwd+{Zwuo3_= zhX8c00+i__49?DazG~sNq&HGnJ&kA`TzN~eS}L^hXCM4PSB0v}*Kn9S5td=*2hAag z{V?Ms3DWgO3ajIM%2s9fMhdG-nUZ5%m_V(nIU4#Wt`s(Qy^`O!j7WMP!!>rDv*jw{ zTYTAUMKbgWFp=_#u21;HL#Kelly2+3-x4N^4uvwXw6WOFd3f;>9O18QEtFZ|e_9%? zUP|m;3*owRmQ*$jy-Cz%29q+;v-bk5sylvLIS~;XeWFQ(3Y-Iz>Ax$Ymj6tpmMbPb&9T%HG)sNS45p~8@$2I#1tov2R#n;j5Vc7G6E@@;4fc;5YWXJDA*`LDG^FzRf zV~4f9nr{CI5gg-JA_o`zmp~;@?>j8*Av)Zwkw{4u$|d-+9bbq=w*E;|y06ro)ek>hKaHve#(!Fo)W6_9tBtiBc**n`V8gLJs(Xhf256)dVR@>;)K3CYqUfQ*%Y6EK02H_d z51aUgw9Y2J0Kw-nij47%+QjP+zLIfNJiRFu&C@P~-;8G_O!P#rHTs7`A?l)nnHMB) zOF0SktVhLT(n1K*YBgucuebmEoTi9aCtOFWG_s`@&5l`MZgOFv0VKLN4lN$FDZNm}yoC!mkS z!*Wj6a+V`F!6+&_Pf5qgd(J`lxp=y$VLMgT*zZL6&3IOv|6*85zdTJZMGd2W20-RP zf7L~u=hNCuJL2^#oNho~-p@$fAR&s7C`#irw=ogG3xX(>R-|EQJ;}r#8u#o~ zhH9&4?N!E{GV)-EIc1dh&wUI$?51IkxpRCq zNlOniw4**noQD}UKY>dLXbg_wJBFgY2mh}@66um%eO@}@^DNG(!}y-G^e}TjGn$8) ze?tHsW>{GJxA4Qqm0J8h-bagslX+*P^2|KU@LezcC|#lZrb+QMM45+~W5D=YdYE}D zsK$GkVZeKsVW72#nNML`YcD*^{1oy?@G$dpguI8DKO(Rf9%fjP_b^icX?qVd?Fe`e zGfXyV9%hE|#e0|`+`Wexg4KJNISsw@9%k58?_s8a0=$PA7LCggshBbEjBi7f(@P1| zpUK0_Sr`WIVTJ+kVdil(sI`X~4wv^ZL;M;q{Ne%()IU#q0JVD$GrvW^dzcwUC%lK5 zr3iSv6zlPNDYiMQmy%0AU@Wx?dAx_2{SokbDHhP$!_2GEAMas?Y{h$+A(J|_u$=;M z#={IDT4Mi7>{m&G6DTDq-h(gZVTSKTLRzHZUu5%0Q1g6|=^kRbH=_uGAS#TFt|Z zP!vcJ35qPyJk0z6@8)5K@7}`<1Kz_7h8!g5F8#O;0T@d$?pH|U+G-wVmV=_q!;G-& zmL6vK#e0}x7Tkl#IP);`HJ0Lxr8qK)d6?m7dJi)Ucn>oScn>qo-`c|rlX(v_40sPS z40sPS4B$i!*efpmU;xHa#D&LDu=LnG%rK%zIP{U1$cQGzUo-NZh%9o7=_4y}<3EPi zVvRp*kS60{hJ@ADmyS-LyGL0LMb1TtN@m

Nz)do$imh%gT`qeSExcVZcXCwQ1y zi_mh$P@Y^+BcdOH;6aQ!9eZ{QyIAts2%dpwTpi5RSizMDzZ6g7W{4}x(VE>kn3)P4 z2nC(v&QFtJ*(3ZHC+MIQj4>`nSkLR=+UW#lM7IjF9;f{U&+K@cZUw^gz!MDVR$!ZM z1>#P*dr^q@J|iBdYtA?v!g^A3#^HP)V$1T;}!B0^GUGlO4We*cH%R z#~<+j9JF7$6mECM$%@1T8oqmhhV|+#W~GxmuvZ@hnlB>YT;_Fr4)1(isp2wkT9I(F z+ns-dcN1v%?gbjDASn`c%$EyYJDEVk&&jiNna4b>UFPwNcbUgP)@9yw+i2Up%RFZC zF7p`p-{~^XZg-|5H~MlZeX38OPG2st{$|5V^yN~zTi*BJGOxXr%RJ`)3%ksN$ClHQ z(${()0CK1=m(s)1X7%M#dPEvJX#&kO%miMbS%iT4aw&aR3h)9A8~SWr<}nX^x$s{r zmwAj&#ATlIuFF`g4F7p~kLK$6JQ5+^)oVgf! z=yXb%3CqRtsqjBVOUpJ`TJDcr5wgtwC}f7x>LSN0`42qluDhU$8=$sq;W*2B3uKWS z@eEEJhAlJXo^w``uBou-!6k^g2T?=!p_CDh#GOd_aXdp55oR*x3kcnV2U|ExF0|B@=Hs|Un2%f4B5r4kxRYDNy{JXpbuHrF65=M< zkN1bLbd*rFp3nU+fGcePIM|B8lkO6DH>MNbj{;WT#xt(~2&OX!NQh4%{2M&dOP175 z*-s&q17lh3`>^MUf+-%p?L}!)*ojjI)4EaMJ$Shjf@KX~7i@xyHI)nZ;)dY8xE$DB z4P3g2RhKSf&vd^FR}K$?VYi+4yz{Wpl6I4eSu4_A?I&PCn$8-%60u{Sg#H&#<wBR$WS537G+!rM&?R2@`+0PUiqreiCFjc|R_!?)pcFiJ(&Iyhq=Ggh98*Y*R`d(OF2- z?X3Y~0e%pL4?&us+v7UGbbGug->lu_()`M^w|1-OS;%*xD2T%Q;a@v9(eJ<`{XuO` z6kdVB|DUmT>o-yOC2WFI?eX1PyD@N8&7Fm0`;)Zhtlb!bG#q@LPy-v(dtYLaPQAzX z*4A!c#usnx_80ALr6N@^xbBJ>Fn$)^2>yS-Xj^6O)E{gSmM&6s#$@ zJALV)!Fx7j!23F3!23F3p4Prj_{IA=VZi%3p$GWj>*PX&yswk15%9iFn92J(VW73I z6M7TyzE0@)q_wY;UHGyWzD~|;gL<#v?(}6>y{{8GBxvR9#MFE5!sJ|0X;`3MiOxb+ z_UbHT#Yw|I#qhR13(4VXeHQXT)b7pBc;~z~JDZA5c(b#W2<(NglLUtdfcA$o7oxpi9}4%acm%@}v^GJb^n#c1LZ+DzVFxO6>Ba61zO9#4b-NvCET6?DC`%yF97HE>9}4 z%acm%@}v^GJgLMkPb#s?lS=IJq!PP4sl+Z%DzVFxO6>BaVlGd_?MNSnMv$aUexaBm z3i489rFh{rlZYzG70|_h- z{|`Z(oA#%y`(X&4D#Ftwt&XEQ;^AaHMA+4M>K7#gBW%?{2<(ri`wB>`gRJU#2%X57 zforgUVtX$|=wdw6UrNb;YLx~)uSWQKJjvjNi0rsf3@s?__TXc>>uN~EsI)2$Ox}ZZ z@4$mfJEhW(A#evCskFvQzlhL%jA5l+tn^z5J%VS(11J>hvL0-t29v&mrptV?EP*Sg53=50L#=i~ISI>5`pNDWC9l7Du_gd}1HpRf`Q@9IV&- z;`k1}cwZd9LI83*3+wn9e)zaji#+)-yGS_cDV6eN(;%yxFAlz|78|}eq=H1`c0Hw1 ze)}8ny-WuZ@92}HWeA&PcS@xUVYBQ`sTA({5fZvnDuwfaCuMg^r7R94Ztnd(THqW= zxKk>HmDv9*zpwA#Ak~Z|BQsHzEf*MN%5%2LE6-Kojr1um)g7-WuRl$m6X6UWb6U24FI84e(BU@zwww zZf_01(e%~;KSLgG4ZyB?Yk+@10p1#bMZ+54EdZsSQYqgxfhZZlPemi>PN~QU-Yq9i zybF*^02A*5gn_z_;63pOx>G7Tf}htBEWCisz@1VNYXG zm*OSLBf$yD!<$fwCotVD2onTRIz~BZ?P?~OK$w6DNs{6%2n(}khlRwUJSX%2zJ)<$ zTrSWN`r~M}Ef;10XH0p{cdtC3V6A2iAQY7piETxeXv>AOncFGP`R~U|>hmL0mW&1xt^e3y>lsiiE=`d5Mf@ zQoNjz`yjH&nQfG;z>WVc{PITr+=I`(dPs!4xK|H}$g3U_;cJCgm=w15aL6i=Xx~SJ z@A7Tk^cSvm&ZWV383x}(={}m1w{7eih2&r2WS{iWX1r}h7f;n`%sd)}7o1V}!HgDS zm_XtZgGup06u!?#AV0OABWm|cd?F#1Nv336Qv5Db&VLHhX=UFs3+Vr6=K7JCir;%= z+C$sIbk_oieVs2kJ^4uQB*Om(!ryQ3bi)4gqZQWJxC^%v;FgQwDm();guOuwMUF=BU_6Wd9cf3Sic@Ny{wf57KA;^js>^)r!=c*h>WR@QYinffPm=5oZ>wfDF zurT=6C1#!b5c1PHx92GJ6?ykoZ=LJZ_E}ARmucz=s=d(E7qLB%z#Sj0U$X`*#kLLj z@}=o3nV<)@oTcgYbNGHe-)HK(TQ5lbJjSo>KACCm=ljNyGx+`;D7s2p^!+x*AEfUz zbuFC$d_V~3#V)*Z|?jQg$FiifmCZVeJFf!iAIMk*N2w3*>d(JeV%iFn;D zD6eeCd@pkwmK=N+!&qJBzG$s|56HJUjsMi=K^# z2S5h&Y&<*wGN5PU;Q^3=@npm=IcSF~+XZj|$amc?z>$!RBL@mn8?^!4WGL z;Qud>M7m^K1?3Z#Vh&LNp4i8C-72sphg_Qo_kXK6)1*&O$~$HJAOvnmN-V6hKi>Jc zQcDNoeY8Y4=~hAcvX>x6whG|>kMFuw;FlaFqLEnw-wWDoxmD1PsnBl~FyOZe7-+p! zFt-ixEyS{a!MXnv_!gY|zoRh?s3mauHEG}R2>Gpovk=&etpZl$-J+j|JbtU-A_V+a z0h3J@ocq6P@WpQx5boYBI>CBy!MXpVsOPr|*j2w(@ER20w+dMFlS%0cl%rb(<-0l% zMZ=l$r}_lyG@L0r*`J0pWheW~33a&tBkRy>6XE`kfw~yZl<(<19Hr`30o?yh;EUcd z0QY|!F5N1C>`(j}Pie3S*?%o+*R2A$|2q`{-70|lKiX*MRsr1q@kI7gF`R+y&wA8w zru?w9Sq*2(k4UAuRRG!lUC5(b1#tg&2Lft1Q~s_LpeNMf{%-;e)vbc^qgC>@qtiE% zR)10>ThXloxc?)=IyI#wu$TSCs+SNgvwvmwt1LklnUogdi`y!g%J&i>EqPAFOO!`~ z6Ov~I)6vGI21-l_f+!uML?%i~&u5YeWFcTelB9G4!oqObVWBl_M3ZtpXJJUjCi{O8 z%{EJ5`spi7Zle~tR~+~iVoPA#DiDfFO2oDjOEgR1Lzvsi{(Sda1q}GDf-~^Jdqlqu zfgU&|!M~G{$hFlhf#1#oo$N2{+B~99AbqLewhH*AQgH77n570|FT|N8@D|{{Z5422 z65A@^X!@-J2E0df2E0df=5M`Kz+~PdIs@J#Is@J#Is=o1cCbTO0yD59sSpYvn(zO@_gnhD#P{zp&HMWv=6eU@@9uk&@4w;uz5N%W&()5hG&!z1 z^|z4A(w`xHby}5oC}Pe>qU!YO_Yf$gi(ihUGpe%CNMFw{e%=8&l75?k1rnH-KE@U-l)&2b-Tbns zmqtN5(qHq-;u=ABaQaz(S=zxyAD&bQwGsqB88jH8sCAN%;PiHMuX>A&3|9#9Qs!Gy zT87*+9zsc-e=BKCLQHq{a%He|keuVAkZeDQr}xY=l4W8}^<{*Fq4i4PTfas4*LY^mgyh+SM17+AKB7-l-$$Ya^ioS<^$VA#NuOx3hfpMi)s;?I z{l{&kq+hkzEsu|7gwjAT{ZWbEvM6z4B8O&Q)lMkq} zy7>MwvA6`Z0^ctFLy_5rO4Z21y2D+uO$%#1GDd+J*b-S-ckIr>I=)2d*&P{+EUeqH ziWUoN=@0Ozg@v_tiGpG&)=ih3pje16Q7TYSEIC23a6AJ}P%K;kd9vgL#X^~-IYF_o zi(gDo95%C(XRxqVL6OZjL6PqzEO^NmXkjf~nvrz4`?Ys#Va@(MqlI<5Sy;PL#lm_- zEUY`+{o1>=u$Btc!rBDI*uq-i`z$T2nWwddHNUi05ByJ}ilXK(IYH5`GNR>k>my?vE`MZ<_~nm`eH69(BV+V%>W_^5 z83BJ}Y@`ifY>O?d5s>?}+2+X>B!ST+!op-1;YDZ-HYH@bls+Ak z5lF15$m*E-T1~Fp_N^huSf;K(UsUpccE;AF@!_X3%z#fOR+mK@M_Le5F z@y0qlqwa2Fz3_r`m^<9<&vs+|8BJi_X)tO}-Dxmxw0Mb9*ft3F$t%Fno!w20k79$ptW9$Mmu|<*P_vDFoC6YnAdC3oOLhsTCB+HwP^L~^;$G0^Li~N z^Lj1Xnt8nz$H42gI7VKtbq;#x^;+zz*K5%*%ImdQH1@Oyyk4tx*Z-^u>?3H9H-V*L zr#FEeM<=`q>^cOVtqJUAHX1ZGtBpjl2jB*>B1$>dB2%V55Db7Jym@RuPWQ?hZ%=Z)vLsE$C zVC(MsMOwI;a*OY+?O=thk|I&A$P(-B`o(`|ZYQ(w-7B{k@XD>1;)7Ri>Be>&)V!$i681Tw1 z2E1~MfgMR3ap6f6EIn>d`pgcNOvdbBQ>sSNHth7YeXMf}0^SbxT&%YfdQ2s>B?^v*=s!7`wCCc+Mu z0lhO3cCZZSor$o6WkBytgdHpcdS@c+U>VRm6JZC-fZmx1J6Hzv&P3S3GN5-R!VZ=J zy)zMZuneqHBpC(-1xd^fRw$lU(Ms{ce1++s6swD62%x?OO`*>~^&2%~4Sm}?=8j^IC}Ur4N-7bOd((u(#V zNVWUp;r95#Dl0hyp;H)h!9~fU5t`q=6rq>knejT5!J5YZ9xp7WTdw@-7Q=yVcjeb0 z4I|EBl@x#%N|oMygHKE&SI7{T%6-9 zW+gCjk6O%DUQYqg=t@_4+tNHOO_;LOS%e;)R z(l_)*ra2X9Dl_`{x$ztPtbK44>i3SDdZwZOT^A-DZ>aMP)+S7{2(MF_4_Ct84A^wM zu?R(4Qm<4O^QOkGv(8AWOR92dV={%UJjF7!C*^C`LKI(GT!*Ogqxk9EGF6)VFMOYD zdXRib22U7hxq#JuHh;ehYVQP zm{bj`5SWp7&5=N<_-Y0gOQ2GGd?q@*Tmm&2*RC}Z=qa8KJnh;d0fl1M0TLJ~ZUm}# z=@5<;UyG$z*Aen%JSm^VvX3mjn#i~v?~?#yefaHYQ2N&>uRmQj75fqCEPU!sKLl@E zJ?Ytq=}zb4y`H{<+0%B!)Y7klA9tp0sH>Wuh_4;#7)rpV5MtWX?;@rx{VdX#(_4`e zx3 zKQj5+ZUpv~j^Uai6j!^=%*#eG*POk}N38!Q#n8E3Gv7)svhid5z@KD{EM~(^ zV0+z%R$1r9_n?94qO?k;$Uks>%z-~cVsr)4018SrZAS}IoW*C%5T10`e7tWyntA7? z(;2ATT}TRed@lczjIp;{e$CPOPpNd?32D!hh)Z|91M^PLmr?qkr`?Kj%f-jhzsXOq zI?Q3rSGe)G;V&|rb`b(IQN=i(;kV5rH>>^xajOts#JD>E%6eL7SB^pWXgvGA3FDs* zr+uvH_N%YD>ZQXkSWJqPRL?_-=Q8KN0p{aroe;SY;j{5{+>9J6(bAMZkK;@FbjQ8e z;akAT63uG68~;Cql(*nn@N>&UWYHQ#glaW9^HBrnG5{E=Olfi<0f{o2;t+cNb(ju zrN{A+xS#a@32!$5Oz%UQcE~q39+xbxoCsMA$q`nHYll#F<8kfq-!zFT{tQ~EAxX*~ zRGy^2EuV`~E)1bN??dso;3-rQ_%L2>$J2Kx0!&@x4_j5-kd}EpL*aOQxfe<9!Gpa} zO;%ipi59^kw1b#BkAB-kR=6$ zzK5#6gGW&4=Xm)U9zh`{FZ0JxXgcx;3jF~|evd~{=n9t2AHvn4Q1P>cB*h~rbS=K6 z{E1MA!J@?xh59%|4=^QvWQb;^kyl~u3)(q(~?Ay9;rSmM&$MHhkzQ&iDEdD&=9Bxbb5n_*xVyvg1 z367Y4s4HdZox)ac7p~e#_L<%x>~rfC!flJUX&(7NlYoIx+a_Y3e0z6_rJ-9s>&z!e2{&LiI z<22T`8F4G|46=7`nZoJfRS3RDc|xmWu4)85(TDCa(; z_#7UgoNwUeAw0{-e3`m*8)^pMJs!#D@Lee9H%Rg;JV`P^?t2Up7C(uPj%@yfPfz0! zvN;JKQ~pF`!(h?kNH!hapy(Tzl0QN=@0xumKvWpVhdMUiYj`>?ajA+-#qvtm)_#wc zwY>r#W+KHnp3PV z2wZ`e%NRHdf!E^Ym3XjtB$59!icJ3roxZi}Q8tw1{Y8BK93CO>AK~TS@GK(>X6oX@ zNDc1$IVLA%ci)RX;h7-!Ws34+NYS5eV?i%D>fd~EK zSW(6*eFiUcK+mP8@p2iV0O-CR&7VLxvv; z_VTjKUdQ0`(RfO~##foWlG^bQfz$JaOj45i&<9Aq=P&pQiWh=or-7tqNT}61K&ZKS0Z%1#4Jlr z7FzlMLO0{-g+L<7ZfCOdknDxi zHdwNsBFT^O6qxL{c=7~im zrOZ1E70tjiep#}gfMh=eHsL89Xmy_AUXr=XkaK;?DRh)9V|}`cJY)3OZoY4m!CBFc zzTsHxI738PNjW2(WXhG~Dv-Z~cP4YYuxRK@N&1qgFWtyQ$=tW1ymI<7i!Z19Nqp@K zTx9&mYzB%%)u1W3l09NS~{YZ|}jf?P4+3(NzB*{)WjL8NrUY?YmJIE3`U-vC! zI8_Fra|cU)p1dcum$0NwS`uk+03~gfJjseKz^d?rbc`^#1K(DD0eDgPp{^2==})4Z z%7%gBBiewV#99$B6@P~@~b^yHZg z%;CIpK(gc1G4MJ(J;|!8k&Dl&zr)1C2mA#|leBdF%dvP}i@>y3g4*AVmL7OGe(=|J zbP21Rwx8h@_fkEeq1JDIF`iTd~?7eK$aOPTmL{)Rg63RR*cY!$?&gQ0&oF?|Nnef(54Ol~EHgZm&9IRfzJ?5s zBYq%P!(TDOkNBaOKqQhToxuzfK#V^izL3js4Kl2MiXRF$`qz;6mCSnq@;;3uBe}fq zV1_^PLxDJ?uf-&topg3??ks{33tdUEzP@uq=ekCHXFmnb;*iC3?gWaK%E_|+!tf`y z4x_E*%%`@+smt3rcXYf_Op&}DHwlQaL-7pGfBL(RQuU)$u!Wuq*+ zJ70DuW1(GjH8QQ#iH`Pm0}3p!Z?Sf(ypH|AmkfZ)QfF~zQW$yJ2;h+gkAkF;qQ5B1 z!KrOW`qK1Dl-wQxuY&3tCDzyB+ON6hj_&M_yHJh4HrnQn#veOVMz%d zs7g{L!>h6Zm;;g@_O>k2wa>%wjGifRD6m!PD& zqItK1q(_@t-r#!MtHaQjMGNgge-^gHy|*id4JZ-}3aA<^tTEsj#ZU}D1>dkQDTCZ2 z9)*20WSkgWf{!toOv$mFsh;-6Rt9!9jrA#6kdhk0ou(^{2%H&84CBJm9P)7>8^SXi zH4fAe#un^rW(lltbECbp0l=V-{Lcj+o!g4DfK`+Th z#=u_ckWg^NalmD0RR!ISXL!!+t!V$)nc6U}pD;yx))-p9~K zATfq@-F)ATsN2}o@SWE2kS;HjM&KW~MqwLU1m$)Lw2i3)KnKSCpgeMra#e!-;21v% z%|qhhBkGvUerWuG4D&Fg&M{1nGKzBrPKTIwGyKzoU(z@kuiPT1biFM*+)C1cuSU2n ztToG(JAzDAH58BeYp0QQ%}~Xpx~#0<ZKiQFTI6c~(2OnOx@ua@|MCb-r@k1$l~FNUn23s_S7v#6_AU6PFXg zY_YW@ng`q(OxR*pf+M~z^C=xS=ajKLCTWu7iokSNW--yt_p2NbrM zS^LJ(^Xk+v?1ki`16|JJXe-%=oy$>ar(*_{9F1mrtMpwpx(w^+z${pFEkFdu8HNc& zs=6nbZX>mx7*|Y)X-%Di`yPY(JuWI$6^Zd+X9Iz)3>sz%l$}&PD&pMOF844ou!39z6fxQ4p|~;zxkH#$ z9)I>YmiO8@)#=_yWt8b$+=puR%Nne{>*8nk@ z9X2bAgeL=CgHFnK)gVpZ*{{OJzAKXhu#%QZX_(AvtMy)%x?bwqPpcFmz9$cpZ2}Vm zGj_DBj8=2qb}LDMOMsb#azK{Q<4-#lI~{_h-Pt@l92jPYgH&2O*vp6QfVq z9*X`Zhj||EMw>kRa3ARiiIGRRp%C05td1m$f}<QSz2fm-L%nK5L5;sB81b6R|0eH$Z`cYw?u3CPEWn;gDIS` z#umB*P&lJtv&kuhO`)yWo>Tdn5SVMe*Zua|oYt31!4Ar>!it#!5^I!n zm|mMWUPf{2`B+wWtK#ptGO~uv6fn3(STlte$%n6Spm9)~#iRKV<_goJ^ z8FJIU&hydMF;4Wls`m20{FqLCM=%8$nX^W?V@DfG#VoZ6C07{0>y<~hA#dzXb3UnkvnQ5Zs1cqQ9dENJwm$1D%@nJ+dw_+(i9bBr`nW~ z;Rd!@vopCW?dJ|0ZZ9MNWEZKQ;{b{elLgBgk63Y|nM`H|GMT0G@oeP}bAq5Vfr=8- zmpKNY@@!_5m7T7w zsH@)X`YJaxHrtgvjmnUjmPESZ*|%a~e$y#eqMv|r6QdXV9i3Hk`8;zEyHQF`UHSDN zb}0SUbGM%?vFh4A*1FXf1yGq|b!#^(tpn`?u(SG@0pC_~Yv04cFbg(mOR@#nl1wl` zr*o(<9VD=46<6%&VM>ffI1eC+(Bg~;y}JcjgiK+Qh2kXQ5TK7{5*QC8&`=VXIRR9f zr8D1bFOLG1Nl^e>365O`m)x#O zz^`r(UfqN2@yKp`og63(a8UNO#@7t*RzPBJ#nTclu4OleO&S_eX$aekUW`NQs~&H? z(m)uSpy=)?a4fSEs_iCrObaAIA(VVP5HhOENxd_C&unU;##flTjf1qtkruY&LzCQW zBde2{z8p98Qv8~gpD?g1%WbbYK5@((Cj!y|$(w0uUZ5pY{y9m&@Y?OUBG%&yaM_`@ zBqBT(v!1{pxUdTfKSwu=#6E~i=OWoyo3{77@hUKItAZ86B}|*IET1|AuY}+XmQes| zJu2(vm4JE3i3(?}Zz;wqFO;lv^~b}=jS&wbZUtwR3;@!`Fr`wh;1fGMuU6B5f%k6R7-JGI!A((#}UD1-S**ruk3KyWrrch&Ko$?>$YK?X>9mm9K zo+Wj~q?RY!y79X1W;*E!bYk`-%82^2gu#_*7*~urb)g|bG1XL|iakgab}CH9#!5Ah zm9ixlG^2sa$yjvL!jCukTxMYrttSeuD^PFe2hqX)7K7XND_k?tF*y5l=#9XlZbX0u9#gK6U4ANBK4>-MhS;CL!A&73bK&U zW@C$q)@rhBi1+0EPz6Mxyd4I=kX`Z>b@CVMA4fN(J&heu!!v_6X|=AF*jBjU%o{|S zTmpm04jo{lTy&Kf+-Z=l8DzV52PC!rlZB1vB)KK0TN`9{IdmkvDWT!D*mKX2<~YxXLVh1%nNz&Z9vo)Lz^ ztQnJS4q*a%+8ja%wE3wIQ*9WfCV|GZLTGjvD>q436)8Hy5K#!$sZ919fq({z%(6Gf z6`WzN(?tQT>t0%W08m#A-RfqL zZ)=(|u?}k<9Lh8()7u=F_RR^|dF`7nnDN=UOmKjrVb|jeYOrW$m zG_NujV$NvHz51CX4hr!+7_H3d&w)>~n%YB(nH^TmUWwjPF*%|9XD+J3&^pyNm(lZr zm``1K6E4ly#yMnQ4k!k_|^c5oIB6t5xgfhVG!a^*O#$f@a`+Yk+hQ&hIPG6sCB;y|Kfus1v7nTIR)koSBuaxk=DT0`t9iXlNVT)yDX*n}ONf*jWfL zjEQiuGLx9ekqa(Ell15p(G*SEt$}_ld2w)rvq@fI5jI}fAGAoWU{>d~Bd`>U>905G z8Gg<%Pkcc_1)ELMy@?5QmS21+ngmMCj*bmPq(nitbs*a_l;Q@X5~iRIqa0`KNyP{< zW5LzTm}`MCbAu1Cs@tlp+g4@N?@In&D&4V1;n=6}G9snP7BawD(Rl!E^#XxwYP>(; zQ7A^2*6W3Md~{ex!w8vv{l7OR#x@~t6JF(KF(wWwV0w))7yCJb7S4O*`aTAvMCKL-se_IS`@a^o?E{0I&GzZn)ZqkGQ; zV*M>TqOJlFP0d~i4R zE)GqkocyFW=G!a%)af2tDxIOC?GfP%*?Bc@V5x#)Bj(i51!EEJCh&%-0A~qy`hKY> zF|WH)kCMDni-}$)$rH3HQ0UCM zFyfPqDlvep()QEQc-=+H!fCP0N%9dG@A&1OO*6eDL=mj)jM0~6Ae60RdEh^~sgi^4 zN?k>+lEG1}DprEvxE!F>&D>~B;6}Jjj@)RS7t($Ibw(I7j#<~$oG zhP9lIOv;vdCPuh@rRSzJLYZ5IWTObqMuAl!#kPE{Rvy$+x;L9efEq~TG*ng<;VzR{md`b>vXr?LDv7EXJ4cYQ=&BQYHULxQqEg^^WzP?}p%%Cj zcGR+*)Nd&}OF1nGDs|5ub!$;A=hE})Y&XpUfPXytg38x6uneNP6RNQ&OhVo~Ku*ZC zX~A_{mUY|A*rR;U?3Wm1Y{#qR*jQKA??ca7>QH_oqwIMd{Yv=0Zua!v^0Q=a$(798___t&+Nv+n6J= z|1nywXIV;jmKPcr-SDz^M(hrFN>BbynYc4h2O32Y9ClVk01KH1DqFj1Map8~LxBqp zD{tYRny|pQWE*VomR8F}SfXQ)vuK4&55ll^b)ExgU|@A&%bGE`{O2te%PK86Na~qo z84H=p1yl342dONmr&3V7-&Ko71-oj}EV)NV3h`o(_K#wZ5+=9PzzN)VYm4WZC+AB32n0T0Gq>Z`xZ|N7#mw=VPh@8%4taURgo@pnsjRhy-@(MOK);cWQSzlJ9^&*Q- zX+=Mi1xB6MElVSSXR5PN^lR7YhILl-RZPJATt_WP5PL)oqA_xUqNZBzX!g>%p`M{J zV4=XfJIV>QrgBcK+G82t<~5tlq`9i5j1jiaZ{^!wj!zgT8&IAuQaHOf7+N4As6TEZ zOLQ+Y<&@J3sS!h)oPlfDMs8uqZ>SwDGxhEx8wN~vf(k;G(k79B-B>rO8@LR3hAmg6 zH{6ltcUm2>&C1f=Y~%fN+*~7k2=iLttT@UaFH3pU#H(b8xBJ*UH{VnSc8pSx3iQiV z3rV3c1>sN-?9>u_$&m>%r>~rZm0Og@!??_d-LAA0o~?Hg`FTg@H)@F8Vu7DLW=38I~ zt{FoPX&lxKE0MX|AC$^l3yapLm?3#0iaUyP&3@GEtX4~c*PFyVU!Cp|o$4$Qk~Yn; zKu+$wT`*c9G-6B(-PS8_T(R!L8zTU0?gWXi3CeR+W(-HV44}@4ESzgrvDQV;%g!Z= z+mI~@d;x64P;jM&k7g$qsNl3PGYp_dqyELp6lq2+bhJbhO4zvaQloRdH^aCUX?MAa za3V;6XQ~|N&9ijekWg>T@L83MW~E9f$pqQ`fJHV8>l?ko{MI%L8|#9wv0j>67akO#$ zSKLX$@BkSyS1Kcd8J3AN+@pyFTB#7KEvW({CkTK_4vK4~5mt`j9YWG!YxcnH6oImW zft`<$;pDszm6xZ%ys{$$B%}@e&iF-4&35xJcwMa}<1!_e04Q)#r{*H$xdG6`BTbZ0 zlw-bl66r-F{UpQ=(c(b2rg?)y6IZk26j|n$G3*TtB5whrE6$M|`|;=hl;L6A^>iv4 z+_<_JnX_f=P=kQ6ds9>;;Sv|!Ub33*S`P6`7Aj zaRZHrA#U)H32aY|8>8RgPB99^S0BQJe~hx#Qkz3{u?&M#psEm;jv==IfEyA`?z$op z#c@Y1i&)vrp;iSBwOTpUnr05QHp`*b8H2{|b56(KV(&R(Lz~EkHhVeRwLk9o7UNNq zwphe5Jwk0O6*Bt){XJ!f9zV}y_Rlhzh?PW4A#BU45M>-hkX<-PG>f}+2UZ<2_K{4b z3R4$>`;`?p#EKJGqvC|O;|%Lza)ta3Vp!X_1qlj})x0p%?yM|k+#|GNSGka-3AQ%IV8=x`)clG+uKBRRFg@ z_Qrjn7vu0P@QXUwUkXj@*n0*7;#NM5I&n{{+qdvkt#b@&SlR>@85_Th2m{7yv5v^D z5mt~Wym2`-nN4EdDkG@OZ7nLMtx}kjeT;-ES#FS33B-ntG7d7E zHO2#5)D1tAtC)up#AYF4!~!!+BVQX`2xGWuc?a|*xCwW{IFkOci;@o zjBfwH=(a1PJD{1-?Z`5^ou<+|(8W7J^q?5;Aj-r+C5=PK>0nk8W21_n)OZnR9kCrA zGb~C!M|cz#c*M-{NdHO1s`%4U*-y5EbaXyC&hs4C5}o6f4D8acIPO>(Fi)b#1wfNU zp`T%Ox+f;9(^FP<%U>;`22!1u7|coR_I}sY6Frza0DxRcA4#2YCPEUb*hI{S_W5d z=2a^KuUe_RDzeznKCW)DC|r}}QfrlqM_0^3aLdk@>jlCNzno5c16dcY-fCuDn~e9W zcFSp6HaEqBr8|}pqrzl7<__jy?UaRKL>SjbxY<1x``P+_o6W)d$JnQnMdsiT7OgoF z6&@9_rl3SKMRLZ_*~UI@eC`Tb8@q4=tq!OI3CzoyNg?dDW(WnkH3_>xfNU5~v`t3P zVI^lKe61M)*PUJ=3Y)%opvgyj9g0ExiLJ)qjIm|`Y2xw&Cq za?4K3 zs7=NWbv9K=Gc3a6@yl&vXhwh3yWPutt z1pWa_7m|n^>5i^PG3!iJVHZQ2b#E3BK%2bNBr%bVR_sv+M6?;SJzoDoZww!bgcnuu z={{W~pXsrcuzd%T-isR{JiY?c#V}Th1cHokg*p3^rx)rRZ^D@6bB0U2k4t_$~uovy4x#eseQ5Sp<$Rg=V@Q zXRaD>cc);d%*&RTw=Iv14j5K$vffi~_k_W%@3Qdl(fbv|C=YW6g@AS)#f&w)ZP&x{ z56x`CBJFX&qFM`Ve};o~%3pd~2(Z2J&)^_&F*fC!VuE3MJdk>?3BO_+=7b88jW_LB?}MCFE5wnO(7z>Zhbm6u-Oik z-sJ3pp=M6@g5HtjBsUR?iAiLYnV)=njGOA()?q!wMK1`sBMK&=5154R1xDrf0CjwQ zbdH0O<6$|NjOct5+2u8}XgwXS(nd}u$x4bUD~*}@W}38)rd@dap+0?9GYg&V#sd@S97XgAH7}YQY!~L~nr@%$>`Cij=og8L zY!x>T^2~H$E7o*{`frOFCiO^*n-CAy3_dPkJeH?%O?JA#5gZRgEhm$YOphb%4#qr9 zcpOt3gbMdvF@b(V8NAq}hQwF}I77;j}8;cL#E@J6$|X zytqp6=Z}ecE;?Z7K4|D3BX>Ls0jDG74#`N3jHVcU<@eBJ zQ?9nZvb*hBP5J>C-{>lu9YQ+*?M^`3Ys1MGcz27}Tj=4MgN%(IoYij~;_|ws)uBY8 z%*ybvn7N2JakvMFNDlr^nd=pt{$D8!DMlmB+qdTR~m8JbXyc2 z+iVWeLX9q%=jK_$BIv0imYerxq3FuS*}3Vqz~jQ^rE#s+r#uA5{0!e|iiB`|pvnz7 zy9VLZ@tV$b<03da%jRfXQs=||c-YuYRX2I^QqW~D!pkxCVA~L}8*&5n5a~N&GKCDN zU^fI`C#DCt!5O}feaozCJhl2)7k`c)O!LfBC7|gMe;1ae4BjckodBV@tY?A%I9jha zI!Ncr$|GGA)h$`YfUcL6JYmV|dXV>ICiBMZCf?I{q@eCU=0vQrH(y1t`yx2noKTjz zYfm&+u{Nu*IO0>z=F1&Q^ja=w^W~TD3t}m%N2I8Q&1_{+U@ME2tt_G52FyC?AvA z8*F}8XGl(%KJy8~bG{t7}()g=Wv`WhC9xYkt0b7 zW~q(uNRD5^2ugMQ0td_w%0^)#VXFUl`KW6oHM#Z^4O$#LOao{lRB|brzn0IRTL;G= z#;j>(SZf2rTBi(aJsFl9j1KDSpw9-$u+OT`reNeE!krv~>5<4p`%aI%V&Cc6g-n7@ zA<=X(pD`R~Az{LmaBhs^HcF)Xdma-PrGC(4d~EXtXN7`>8oKVh!g{9&Dgf+(Y@8t? zdkT-RjL2QS*Fu%;c#0qo(G2c;$inkC343-`Hf|J)J*LD`Rt09#k!KuLBiHzXsK9Z8 zuLc!b;zNz3X~j0kJAU6%y@jP?t z*)WXP5_$O_CIE5J$vw2+@|57>bUV&ZfW$a5HkRaOS8T$?sEbvo*Coi#KiF3!WiKS3 z2LVHsN9+rdcpg3T;<(4laFB1oG)lq28wo)rx0P_p%V`e7Xshzjm!PA)EIXelGl3o@ zJ7Zb2DpNdA_s&RJwG24CYv^lN_pCEkgquqIF*EQ>0#BynjEZ2R$)B4{o0l_B_RD}R z08ai|EM=?^zWprV1s89p=xt>%0sH>j%t#yN3<1VNZCB(9vv+)Md!)C4Doj0_h75)tx@&R9a+x_AmU+CuqDUdgNEtT$`=nw&l&Vwyw7 zg~b&nrrWS6z$8mPBr70csJau8_wBXkIkg$7r|UE;S0ow2Dxw3Cp^9U&t*_`xh)_tOwt>mm|IzzYF0!v&u?V4Z3yErD04C~R!$}KDGDP` z8)G*odJf9{RzK5=p_HGva_FFggx!D`I!*&6SV2?>Hl0R)f*^)QGH8s6SDuO}at#+W zRW`cd*LHIsGvuZ`;AYTJxvJ>Mo`M?YA#WuvVwxVH#f3DAeBrhc2Xn51!~u=#nNAeA zqh^l;X4?gV#mo{Tz@BD4C2P5d0QNk=(nE@>^o zMA#C8=f-5<*k9OC2)NDxP~}qwbye}?kvp@0#g3_u7WbW4jNNmOU1g*2yn%9{bkD*> zzI5#i*2zvzl#eVuIzXG1OS?=;s4EY4>O!vYaB;V9QMiZJ#(jvAtug_EpwA{S-kH+0 zH!*<1JteU{k$%E9P{Mm)0vJ>2()wCSX>vYdn=LPW;aF$9(x(g7xd{sG~PWwb`NmW&4% zm}V#5c>gvCeAvQLIZ!0w9IfW=EkzTTv|dv#bxhd7fZJFYh)7@KcCj+*Xoz0sTwQda zD;<%l7Fz~8=ljj}(N=q!6~Kt@*>7ycvpNvjcrwXuT`Sd(=~2P03>n>#nGL?0EWtyk zYA}oSJbH;muu~41{JE2o$~ZiB;`j3**fq1ceFK}@s?+a&Ds*o1>VFX`dDTj!r`b-u z54OA93JSwPdfH*~%+Bl{)`5;s2*jWzk$jOp=wMTEt84hEoigfCjgs$s3NXqR7 zS{QTbO(fAgIppO!?6#4l%}HBJS)=70Bsfm26DdR+ll|NZUevk4n9?oXMIISsWm%uL z#K*8$M_2XcOvqYx-Ik!e69l2#wIN_pGn;9CR-k#CEmSPS36rc!1ow|LsqE&(C?)&N zkV~A)IE9HG13+f*@z><1iOy;L=@}Q>Rd_*CVZ1 zZpm4dGAe%R6#Bh z)*?)bWD4Qk@HAo-(`^cAy@wR%(V=eIKvE(%Yg=8zIMT4SpW%uwTm4B{<;}n}(^(16 z@WS9TsH})R5Svt!u9iNMUk>{(5OF5H#!ok#cq>R&fKkOSz!>A zfoTjdUDwQqvR<8H@nWOOAe&So*-T+$OS7VD(z7cJC{b$PykN1_1dILr7Ys6!Zp)Aj z$anuNV=^YT-7n|_X+%-Rvsbxg9@nosK=+&D$)e!dog5?6*0bE2z4 z6zqq1I(392spYt>EvH2q%3eg~*pf7Y9H#je@tA*OL1-&8=r1^5v>B_5jv-`Vg)%#W zdIJ~d`YA(i-VU4LSs)QaT_ObmlcafWIT^g@Mhw_)%vJiRYXu3PLpYIqsF}5B}vXvjut%C7};)Jga_*N zH-$IeU7%_b)4c&Iu1{xsrNcDaU7hrEjedryUx{mulA4(~(uTxlc!$XQG*jMuo2_8K zn>9CquH7O?_2JG;6vhq3a3zQn3seHYEFOyxULU;_W$@n2SY|NNw40BF;!M6+;nPZm z*=+^bE|T_PBNG!U%oRys{IZ5)A|~Uupo1epp=h3>0%GJ2L!%~gybAi<6~qGqqhj8k@H8Bz91HAp{R0@q`mxZOo^lL_>iCdS-zr4|*G@DrpvAqK(5x!>(u}8P(cA>1gCGMFWmbl?GuN8EfK)D(47~YJh5KGbUIF z{bU$Y4%iHpmw-ZsjCccEhZ|pcGOD3V|%gyS#C;e#(-p_ahKv4o;oZ z$RZ=lMm*urGxB3zKm zh8-F+MIPli%nwN5V@Yzjj}02QBVx&l8-mdBSSLBaG2R_zXbv4uP=%31(6?~Wypx(_ zwk3lJM?O?4${$z?tQ4oq46%c_Q1QI0!x#gWfz9c3JqR;d89r8AGtL%{Vg_NWyNS8L z$|2%tPFTTFCa*ej$`B`UflC_mZq}8zW+6k$m3T*o7jD_m5o5QbCJVrnP**9U-xO9C zj|3gn2j=UV3gIZ)zE)l~EpQs}$W}AIKl+}dX)hqP;v`-~5?B*~u|=roq|_WIrf$bL z`&EsqyrsoDk${FeJX3D$rjY&@Xw8CSQ;}WyToEdm|Z;C+NXKZ z_R6U1qXHBzfqWJz<>8D3dU3vr;BN_GsLjXUZ z5Dml=QtZxKIZzCQ=5q>pLZ|lm$6 z9Z4*vLIjPBcPnsg6HGQ%g?e*}rFdM#&Z$Y8WGNtF<(CN1DUkrqtJBfXp2U|ty9$ga zzt=Av6Re5E7iDLW6s=+mOpGJG737j&uxX{m$Ww1(NtrEw$8RKutnIX|vXA4jHnPn` zGygApZv&&(b)Jdc@0-iZ%i(Z191cgL;gFme4k?PFD3YQnie~5$O;Z%Z$fFTOGYq3} z6;{uM|H(WNL@D@DqhDB48s+?ZeloUstt@l8+Z*NPy-_kTp=|A z!*E?~U@QW`u=+gj&-uCc8;bg|x6SStrp|ZHx##!&Kks>u_^1f4z&p1YX3<9_@=62g z1x1(~+JfdMJLpS-Q=A?IP^>%ptWkc4)w*1hQ3*nWDr9S&TCQ_yso^AIZ$V5+mvGvp z$RMd`DZtC)T?@py%eMPs25OK~TZ;snvmEs##uroH6Cz_X*_3K1lqgZqO-D;TLP3~_8fau z=d7|UxmIqFB&AdD58xyq8R*nr(y3pF$`VMCGaZ<9oUHiKbbjkex&3XSWsD&wbBGvA zdLbk!Hz!D7ABJ*JojzQ(dT+>vbBPpGdOHiXXi2||Mv1qO(~Y#b^a54b9G7bNcttpj zCfP`DDI}~mUQ$qDBC{E{fy}ic83&t%^phJ_1U5z;9}$Hnm01-K)L3l7paKjYVxyEo zxC&|#Nf*rnPIp$jYBu3SVvQ4t7|}s!k%%5bRK)m05|Ri{05`mh?0jO+)M~+%t1||Z zg>TGRxSat<7QV?@xZZI$R;TlfrlA}MZXgc0j3O)Jq$;{%n_*=uk%Jed64c1amtU7M zl9v~5&-kz6k2(d}K#i_NLvahIXakCx1xMb=O_i!1ATC(|lV~ppa=o9YL^iqD_q833 z#}$u$-|?l`(-tEeP#9hofhp<%28as~PkrrH3L~3ek;9Fym7XW3bEB(W>nLT!fi-Yk zE0ki&8dzFZ2oOup%u~x z%4mU>5+O0_yiOjM1Z+s}{6t}Npamz(nsl8Gqd|@*MP44Ee<7N$Xfo`u1c;}>&qS~u z=L8N)O^VF$k1Zs`LyOqi1_`$FL3^3jXnq2+*Kjv_N2qlqR6x~@B=jZ}T{G9T!E`qY>#K#bl2R8|77Y*MQ!f9A6*h9tw|} zmALz1fwhx=vc(`fB`CQwkgf+|IUpfzOE+0x_>g^VQ#g}YKb$qSrk3G1!Xg~{gSydt zWHjBIc;!tb8^bn2Cc^cF7J8qJVZ<$X%I!a}09&&%eKyNO^GJVj|0C$HbOj4H(&#PJ zYJ4al;EHgPGn_Lss#ftks8-IU+<7`|l5Tf+q)XI?roBC!p39QKOzaFTdI>3Z28)lb zEzrX+Ttc;#r$pff=LTB!k_PQYW%j7YtdlNCP6>@j`3P=Z=F+hG14#=>toj++9q}d* zMQ9S@hL3(+T=kgN0jNa)P#<=sxd_)2l;k;!&9a#u!IW-dHyGw=TkJH7MI=!{E^?wI z{4IFo=mDe#{Ry*iive51*%<$`O_xMgOj&EZu12uw{_@oSQGA5=HFiV=PtXS5(ll!0 ztlZDHc=#m{A|Q#QFQ0P;N+uYmoX}%?db>J-hiv#_JLJ{m!@sC6RUJWi?DT#=FC^z>gk_5|pQK zH&UE$V9U`>$4zo^hf+y=xk%!7wCVWaNXLIs>G%<0UeWF< z0t4Km)92vs%)P8XoDvS4oXIXFUe^^L75t#vBv3@j zC$KY83OGa%5tpaypbIvX?vQzc(j|1*N%u;px{Nx+M$>^XUPw@#;rba^Ln%qqN2>6?icmMxX5AG+^MD1Z&s1b8RD^RPi^o-X-l!@s_9JaHL}Zi6XV(2(N(|Rud>|TN zb6-kt)$)Nr*&NIYG9X-cB5F0gCR*GGW;Hz;hNVAIGaGCe*P6W$(~>YXDJ#~i&5cEk z%mNTf=Y`t^WHr)F;~iiy4~|@(hVUTESI0d_l=U)A@-V`kAR7tdf7sZ#fG;WTTw7(_%{FLhINI)+*o?AGn!vByp_+vGTw(F{-YF^i{ief1o`VC)L{_v+VDb$FgTC^C=kq0 zQ+Z9y0_0`)FVnSxLLI3mxQuZZ?thMzdVM%>py+Rx0b>JF2Qnt2R8gaA#2AZ7l-#tb z7WZ}6TxT}%PNq{nIsi!A1HF=H7m5XpqtvuYc|i{cT<@K)088&?R!#FGO>5k}(VLJ^ zww17jtD3qiMlL7XBG{TJg2k8mMCw`>h@1RuM;T40Z86iPLmml&iVr+v4)CnFUtE3s zc&FS7@yd;wUI+>`i+!DXpQH2+D(@69ZN6WZFfr46%MwB%QtarfLk2rsgYha@Bhvdk>J<_k+Ep?HNu}F{5Svt19CsuS=GMl6YflF*mp-AtyABD@ z4ESX@l%-wpz%yO>X|)e56s6ZeP}JhqA>oF6sWB~4>6ISYjWGyzT)sqsZ+fJvSQj=7 zt!NlHBf4rryFowzBz=q98K?4KayPn3EnMG`aJ$2<;m2q*VR-7(YO66-2Vj9T=X=Ak z+72h0JDo@UL_@~ioDyFD1vFqL?~CZji_=t>ceRo7mPieED^lJ{Y}~`@{`#c>Y3ALo zOA`aWft(OO;d>#s0`LjPfMd^88c?X74I)CI`V9G))eP3i{b;55U~XGPkT;dt?4e(F ze6R-{WS*y?3TTlb+GZ}v30bsE$5((Hx@9)`se(0v z=L9&x454*1m%9iO14#)%)PAtS8CK~s+hg6TT_=X-BwB4RVzbK0AVfQ-4VmC_r2{tW zhD;>8pwnb`;}Jmaxn@O&K;p(J0Lg>`$r^=3i2HrDm}d+U);S>Rd)#30`bvg@liEFb zs74SM>c{c818GB8ix`fY$>oX-M97UQiQ*{OdDo^W)WXqOJ2EprR>mBG1HckJWnx)mN-BBCibP`91*(H}p&>M0EMKG*GqVK~52VY|&l zKxLeV=sMZ-vY=JH5J3HzF)(4WIOU4W8QcxxT}teGUj%JKcN(rrp&M7injQ#QoKY3k znif$Z9&lw&$(_3~3$Q03yh&+?dnq&_k{$}d_6#xESd<`4bWKqFQIHVVAAPO$reM#3 zw~sVqoKT@X^YXzNmUX3K3xEZOSpHEEqIaee8o8lE)>XuRaI7(>2Sa;uHa!qEysp6E>#AJZ`xU4^o?*~bEcQe#|9T*1n39~8*_1m%cw47wrT_(c9 znMT*R0ARVQd}>`h&cFt6KM3&c-~r_7LA<6G1Ir@NC~e7iC^+CM;wTp0)TS=mj9Gwp zZddBE!z4$;<}2JI$}kZ_-xVNJxR*lPm7gU*6Oq;GAaQu$#HD$D^!}94aIyBf4u`{I z0yCj_pOWAwkKfkl*v*h7*Cn=FcOK5S0PI&sejvcj5$YkN@@OI&y z7*Bd83?ONcqQGC>h9yf(_$o!z5-e5eyeVBeu~A1Xe9_w@SIKtoL&`+ggUvW6I63Ul zEu|%<4rXv^D8Jk#?qmSOKy#)tL()O4hwc!SpifGdXMIuC(% zL%`@D*Mq`D01n5KDe8hF>q1QZYoVYxp;S@Kod~syhKv!s_fuyFE;L!Ttn1WkDM98r zrL1b&brzi|swZOP@)^)dwM~ElLLmdy1o1$HksTQUtbNjGJ&g8&&GC8mYCOotR^Bto(;c#~uvmW?*HN$C5< z&=QuQSvx-1E22S&=oACi2-&m4`aAQcQmN&`Y9GeQqwffz4%fR04yn7IQmm_wPk#k* z&1q3`MLQCihLjdbhf%Vt@mF=6QNb2#*%I7xIvQNF^#f&Z{*-Q{6AdBFEk&+u8$5V6 zy|N=kw9)6`FDz4{JJWe2oCu^?4S(!JiBRGdE-;9~6L}%`F5Y2ip|WTeYgz(Yj~h`~ z!4`R$a_xN#87MCBKb6~bsJXWrl!w{Rj~gDvnMJ*D)t?d-FcLk}Wg5zKEy5H-GUtmGAGwQ4rtC^UAO(d%13t-a z+8{E!OtWH6%wk|3$GViN$-$-39Y5ra8y-9X^`pvatM4qT- zquPh#`6@)Tlp69p^DeFzadDmikSe-&2Z-?87+~4f;+}wsvZ2a8j)m_8l7d_*Zeop_ ztne0#Vq!*cRaSK6S^7(r=Rg-?^!rGP7w6P7hI9?ovv(LD7b^8oDb%a?&`A-(oNt&C#O)OM|adTZmRHu#~0 zKAF{|1UPPKIe-L1APH-fos$EYoFd+!$1{-kNab$qMdh|SmAgr)99>YsEuaKDbiL=<*>b^Om$fL)wS?OD2?7f(iXZH15^jlcD3nt93!B3Us5|Pw zu$J?k_qS=(-bkZ7L~Bl-KF}mjvj#W<`pU0wYf>!4*ho(uqQwo1rqtd2Z4H2fG^~Nj zf-olaeNElLHUPaBaNbcjmi3f6VW|)2G%Ee>7n_vIT#Js7lo&txB};>_I=fjQ#96xH z?~s(CTRk_aTujVP>T{4K`B0a0^rV5wlK| zATx67M|c6ql;D!!rIf@U3G@|^*-9KT0v7?YAw&k66y80}X%M8z99eM$(bCt`WC_?Dw*jweJOvZ3Nk&kS6y=gQicp6k?it5aX-w7vjsnUs-+WOb%~KeaAKu~7pr zOyyp6H@hJqMk;GkI8kG9CrwEu{QXIwRbdt4s6%m~&|yPnXy6#^d*S8@-nJLQ3vai# zZ{f>{<&i? z|BI%xFN1rhkQ0dMR>TQ-*w)1|yi77USt=A*opssD+zpAI3_oDF#v`miV^NJR|9u#H4kk*lQQub>|iam~E^JT^q zVciRqdA(zLyqlgvr_!8wcS~SY>8^PA+O8#Z4(y|G@)30Cbd`AA+LEo*Q7eaN-e^W)YPL^igNdsfxyG48oEu z8$n5=Kw>z~J5r5K!ZeDq?2%p5V^q)*(-~G*(5}3YR_Fv?45iSW3<_SkxL0 z^L8^r9;j8~k;0za{V~j-igT3t!Ki`uNJO{Z_WmBI3+K9?Y<0|ecMRw1=ofD4PraH3 z3dB=3s-rnoOSwZ(1=Gm|eK5^j*W}({T54FDa#8l3hc0Rpp-o{!ffd{*iEGV7FBku? zwK)oH0SeN!!YN#S2I4VRguL2T-IR`ms(&=>3)G}*$Ai(pS!v~OAwu&wEON4PYv=YX z{xO`#)5c=(iiFVCVVW4rL-58?D%y*IraMPJrby~+qHr3x-A)5w`%nN+7lIA~QQWqV z7|aX&*`ACfybt9=(gCfYC}E!rt3hJrko!)_Z5Zz3D%HyaS4@XYQ-=+CY7G_fv0DQL zf?6ODkKV_Hkob6@6WoN)SUrdNzPMJ<3mloJ`gF8>%~ajG_>@gc{OE1>$d{B1k?YB6 zsh>cbn{2oh-m5AFvYPrJ#T(87<1vI67K62%DGD*wSpXBFu;(BEw*idYNG@5#4d~6- zI@{S2S=o(NVm)l#gHXRbKOaLihkn@#z`m?UBFWO5FOWOi;P`Bf8xh&z&EzRWmgrWq zGtYtvS>=B4zg#!ECFe&t$TBMknH$uDSQ{LW;xhYTr$HM~{|K>5!glOcsIn^nmulZ3 z0JkFu2XOG04Ixv`Cb@V6EO6~UY`go7c{ z#}6)t2eF|t6+`@(vyTqA5%{<=^r>DM_kSc0MgjNwG*ktH3}99C9$NCg-K z=wY(EeWjk{|2&9I5RzQ#?a#^2(w`ZziA&@(CcPh=L&r!C9jg?CH1=QuB-bdAXt2Qq zf&Eoqhno2QG`5&@gHRI*PlK2cw%53X$_qi1585=rF-o9@l&uVWV3EU2yo78BD&&ck z<5N44S;Pzf`JVK6O0cz!*|luf83T?8wNK>2^r%u`kl<_S7@FnX6#9>0<-7?X?O*fo{7P+!jC`((QW$$e0`c#)IG zb-Gu98uFq)#5M_8VoY($nIhld@z?w$2KCf6>>-3_rk#fX(YXENd<%A49iQ8S%ov%w z0l*0$h%CegJzLk{4KBgSY}z)ZaE65iSP@P%;#H!gIjHS7w6QLg>~gHznq!^6HzBZ= zVBL1bx*Z160se1xblVAOyXHZ%+(;G{oZwyiLlIr|faN7`K0jkOwv>AMx6_r>k7hYky|b;fR%LHUchgWT&b^fvqi{)! ztS+#R37v!En9`DjfTm%5RZ@62`{=}SBrZOMj8##{7|j#pBh@ zg`e;h_vbkjuxT0j2dxc7*pCb=UQKj)aKuq_Roo62Xh!3fT$69fSiU7L6F0YHwQk8o zb4$W~R=^r%m&R2E<(hs`!N{a@B#9W_B*HL0m|eL=Qr+n`G~@I(?0+I@wZ)~R`WdUnld&=*s==E5*Ix1-sJT=PJ<4ql>=4rKI-F)(? z=JoTai1VTGOb2tP91){}@t(eq(IN&rmHtj;5eX^J&f>MX|8Y3cz+kow*0KqQ%Or|{ zgJX{v!Z}pJ`7tFF(@k((ui!YNG;D*@g^jMe#Per?B8NDaV0!9f*Sp}Oq36uK!XL*n ztCWZf456m?R1Dw>c{x0+ag2E_dqwb!vUE4VA&wAq;{zEheUCLqnH;^+Bdj* z(AUp-1)PYR?qf<)m*~Ru(~WOwj!}`>;u@%oK=3K>)PLBd)Yd{Bxr10A0)#-izysEX zgYn(E_742)c%1Is8V6}V)D(zNEl6EFY}e%Fsf8$Jv_A+Mr1a8>TANNP+Dm{$3&^30 z=Ar<&FdZP$E|4JF3?qEE<8b6eQG9*mz1#K^J}GJIarEt{G-4-I_v#S7D#aL~islj( zV!dbu$O@Y1aeRPP1G9&jnJ4g4FUG;v){w{g^! z((UV&8pWF{auRR@A&j8469U5)rQ|otC=&j?Rq^1a;IW6{k@LhuEFr~C*|*12V5(&r zrb?QF0YAEn;t*Q|4x6ibFFO5;a-`)@ELZ#xu^KDMoW6huE=V{oy*s=J!a^@iEN2yV zfkGw|wp}yTtnL$_QQg{2Gy`$-6%^!U*tpqF_i{k(t&jN;Dm6H+IQ`>N=^-_{E5wP9 zFSqboC&Imh1&*gp;~>njKK1%-!(=K_oaSKF*n7A3UF#`dY=?0gIwzwVd#z>BMH9q_Jrj$MzWA?4>4Vy}; zdl~#9g^pC)>G)gH>?ln3zK$41O}ZI`T){E}Dlr3cg%*NG^(FO(0!(mP*`iw`w}{m< z`Xyz{--1G?a$~&^=vpVHQ`aRzZ1B!ZhaWE)rd#qBqV3Nb4qe)fu$a+A50a8f2T}Ut zUNEGC0Vkv$Kr1~gLk6T;qpDa50xvJ*B(RLI|CA`$5Mx2JBxT_ADIi>=c{>Q~L0wC! zYFiFzk=Y2r?ZeAl#;9F0i-CfiM*A@W(Z~#5Z33B^Nn~bCBAZjlt1*5l*sgSVY!Fo} z{VKAb#Didpx<2ykvMg6w;+XK>EW-6PRf6%zlUL_(2fJ3vlh-IuW(2B1&1chMh<2U~ ziixtsusWp#ak|N**DFDsaba~sI0OrT2={=Xe}qi-*ig|_`iYQiXzd~^zqsB>rbiYK z*vd~^82~5%u#ujtBAhK~v$+ZpXxitTZq{)T4VacVoHgxp4v|hj6Ly?JTVw`i7LcR$ zX@9*c^HK3bi4Z6)C0J$|XxjxEe456A#)*T!UFono7B$O+pRR*O2ABUIchC^72!4{X#mcG1;>hC|S2a*F5}+l%|NTyW zmbz#>5Xpvn-3U@b7Hd(ccmdFr+9CZKZZ|nwOV46$FfwQkCOe4@Cd6<`Gxfi(N+hbl z)zUe?Epubk7&0ERy3GguMJJfXoYP&Im@LHWl(nsQ);8n9)`nE9F^6!{l}JKth$-vR z7j1=ZP>}kEZDVV1%FoZA!Zt^sUpFV(Su)UZJBz4OxeTE;7Spp#hERXXJdf^_0Yj}` z!{X-V3Asf|$!)!3dS()Cub79*1Q?eJi8Q~7EvE|XxB+M$7%(5DhIX|)zJc=I17FUD zdI;YwBDB<(;Vr}=S>Zq|Avg4XaW1D@=28}%D)_u;L&RCB;<$LTlX(Z<5zxeSDtC`k z9uK}E$X^@`!~cJm!!vdn>6T?@bn7iepR0tYtFlWpIbQQYgf;_o1zzyoP*4vw8X6lN z!&`=~g_&a_ou|fTXG4uwLXyi?G>4_sguu1Z`RhmyrzUy_I5p!%df;|Vkiqkr0yf_> z9Wc@J)~N*T&y9e-sL69mNzk-2L+E`l6i1;$pFnWBgTY0euK`p97sf^gkS*tl7Svc+ zjJkZJ$*FA>{{+NB7BM-tS$7mzMV4Nm=GI2kj8_qiU247g~x%pZ^8H6HYF}lYIiI z37z_YOfRemLq;Ska+}#Z(FP%Zf7t!>dI)Y(V}+y%KCr|g9l$mQi#V=Rr!{iZf?u%K z)zuT6+f!Eq4|8_Nnv_LiT*c4>F^LWd2pthS)p0Cn_>%j93!P>;Es3XDk%Y9BQm27U zdspH><1!xCNWm1r*#oW(lEo>72$3Ap<;cTK1K(FTzRT0ua_b~HzXyFa3dED&$nv4G za!3&MoG3FQdjxIBdK?sttV+19&3Se32j)2`BO2uUxY}8K>O`n>jlODA6OL63@rtf3 z4n3@|MuME%gZ|iFsx+b7=@$lMbrQ#4`#sY}!3_}w;Ti+_lGBp~PHPn{c}i;tq>v)f z{$*GJrwZIi^hfqE3a$#Bz_x}695}$TiAW*g6bHDT<-iS+5-&m#f$(OeK42qvuLRpH z1|XgY=GCe2Oe7FfE@sKis$D6o{EwjKI4)e>8AC?v4Q5kh$N})3oH0ZJ%_14&fT0Z} z*F+#0%i#l#nd!;FxRPz>w?Jp^6 zpBkQL0?dWF;Hpi@h=4IWrf*kYK^)bX#>N3`7lOg}oxzaJRnW3|a^N6xRZ6l!fZ?~3 z(L^`lBNvgx^?)H^Z~8$zLvUKvH1}~M!;M%7dipz6M?8R{(<$-4)`Q!(aKKj3d52f6 zn!wZJ(p3TpF1$5(e}u3=sjdKFnGo+(9iBM&|JII01rh&EfgoxRJL>l1E~K^=nm5l5n3VB}vyPT)~MsKd`)3$i5oe*9PB{jA}I8@ zm7r39JuP70N*rl_QJT9Mh!@8e;>Y*r3iMDelDH}siB4iJ5}jEHfNFPqFe_-qG~D=e zc!_^)#QhxH=)Tnwbo?@{BOC7vL4cvaBDT8;)v8jNR8_LIF2AT)I@RxASbz*pI+{SD zJYg`PG=bWfsgF}tP&(HqxjZm{!6aCKY*>1L7|cG(|C5051TkKtN&~{@Oz`@g32s(O zc!To1Ew-0{W7XSkB>Kap%^sX>W7F5l9Ba)M?k`Z}BFyy43&IoXMnv?#>u+^)#T6Ns??6O!dt zfDu`1jPk%$c;~vr<9E{rak6ErDA2)XdRRS_2>Ka_;?#oF*3WmAMatac4A&u5IG_Qg z5nJm=LB47KhzR1Lfu#iw+{kSpzrDOB9W4EvOE`QC9YM+~@+ihqvi3vz{(T!JXJ3YQi_HDib4p7Oxvnb`ZK`Vkp4@bF{ z?$f-f>oAiNG6$`Mr!S8%(s0FfPao1r6AR-}ggXc{Oj04jV%n=;aLDOm>taKjF2?&c z4nG1&hU7m>SZWbV1+J#wZ4brz%ET}i5MzL7&QEBbQ^w>W;s9gD*M)ke=kua%m}uPV zo{S%yGc;05<){-Vi@+EiGF^sjN9^>W4(6;oT>ef$z^}+e@p46kJN0Jr*#X)7Kt55U z8n+9Ss;+84lx|X>Rt?w$xe7;gIEN4Ea1gePN|T=Wa4#6KGg&SO{0khyBL+^kvUc|% z(c30fZ%h5VRd16g4A~jq84jUvKNVykFxFF=)VY z`JOwg$Bu|gh?IFd?^s&CS0c*fW z0?gJ;H|(|}1O2cwNTF>dfs_@25!<3EBgRoTeT_UcUf8P?H0*{mEG!FclfFi7kW1~{ z$v~^Up7hk2kL(=RtbHfe9g$LT(5YkFi=f4yo5t%%|43Q`-0uec>!o_h1^pa^Pdu& zvGx)1H5~!tV+9RBfM0lMd(TZy3%In%_xIg-jZKHY#Im=GshT(-YOV zkl1o#46gH~#+Y?#j9Jk3LgU~1UYhKT%PH|HUxW9+xl?Fsu4-P_cJzP}5D}H0A6Erb z0h;`B{o5lXhWG-uh|tr5rKRtVkSG!a_)tMDB^x5BaYu(`LBz$!e0Zk%K(^aV<87aH zDiv8Ud~Mj(*1pA?5RD>^m(kM$Sv4lwqB6?2v%3&D6b&cws7xBl)U!< zRAl6dH_p%CSUgB64VVI4^nj?0@7Q8BPsxodB}^wd66?zmJW=438>Qj~kTu9tBG@^9 ziWdIX-Xp+#0KNgYKm-XR27*bA`^plU9LD*jzy;`m{+4i}7TL3PI4(h0rUs%?m7kA; z+sKkSu!+lJTgnZt)C!T{_QqX^=FzsK-jHu`4_Dd9x}4WE18Ov(?5*$N=0LN6g=qnE zsgjgUDM`_=8)2{E7@c>J%Eo!f1GC|$jTuzpsfCn4Z55A1NSlZ&4*gU1ndeNT+C>SwIrQ4K%31B+XVTQd#D#wK0KpyzvZ~_Y2QR|{rzB9QL z^j6QBHa1*%j>a}VftpyCbWeKRdWoDryoJL-weMtk zTzc6MGKV1_ic(GOAsl*{+Te$>QU}tU(2a(s;XaZr)&k-kSc}~2Qn!dPm$*4q@QwCT0Nlg4$e*FQ`8m9^m(yblRv*!TJ}U|_f;nz*%+#u-vBjkiv@uy?pAFZ0$v ztgJG;YwCpvyh&n{Apvr-OLnP3P&#u;4vJi9jG?X~WoQSxigaedlSgNqX{?qEz>Ij& zo*$vkG8ewW5`8h_5mAN%;S!7DfRd$X-^+1cjS&G+wQ?)Yf}&>{bXi$-JXg1^lt<2| z>Iil?+9P$y$$WTrD;=Rmtqe5*A6IyDOKFY-gNx{!Jiz7lw)GL;W^#PnkmK7%#kb@M zB0?dlPPnLWz2f5LCNAEfjB<;Z_X9`^@+nc;nrG$$41`0W+_Ds@vETMIMMy?0BnF`_ z@h^H;HR^%_SxpqM=DS1rn!o}#+p z>xve+L^=(pT@iJf*Qynsa=$7Mc`Plt`!Q~Owc$CaPwC(ryg7NMtHtFe6oS?`vx`O) zG)P=Zfk0)?6i+6FEK80CR*dfg#Z{deA_H6BW=S&9^u5iEb@{;6qn@5gkvhE-_mTEyrv@S){#$9! zBJyBz5H?ySBB#khw@t2y4_+zBgIv6aWZjD2;{HTVAKv3PF;tN-aZwfC?2t)MMdI~7 zL1`ry4cE_<1W=6*QYQ`~xUgjH4L1`1q_>M_rg*nW=vzkKF{Yi8^0yax$GI7WTHkWa zU)k}yJxP5_y7V>=KzhMla-KRh7Qk)D@vP}rr*jNOq8^88&MR9{U419H$v+3{kf4!m zk0H@I!kE~3@WPu=GLz4Eq80CHWA~WRfN?TKr&);+`zn}GQ%dXUv7YaB54zQB^LmJD zPQ4QIwv((>RI}~`RB;VoX^wmo?v^&R7)9tS`zi=ZL*B^HdWa*-Ana2A%}H8{DFlh4rPjeq+$c)64bHZBkxMfWApYKV z&^>%RA_dFAGO<{`M@KYma81qGIh5KxwP2jGS4UImiLZ|KLYHBuYVXC-Z4)xylk>Q+ z;e_ZbNmjO%DWYA?dEDESwxXfs=WzJibF%}dvCU2es<+teHunF+yp$+N`%dK$KSsS` zu+p3e^w5ubAzO;a*${tT$5OZ}MN3~Q+x?tGk3hdcM^#Y*GW*d$yjR*oLZQqNgklo+ z^<;27glfqvxToSGjLIt-g318F&!vKoWx|E85Zf%@=_)x*SnRa3jznQe;5?M=@T9gK zoc8DWQ+>a@=p#6EE0(4+#*0O923#dIGcNP8K&?IR-u2)DN3zB9YCYmSscnjf9TolbM>pSo}>TpZ@VPkP#1 z;)CGk%@v%I+o3qY*AsZ0{m^k4(u|+haGY|RiJ?|+Qpv<5OITxjQJn3qvC1aLm*69m z!pvlgX((z_@Hb^_ljLbpKO5T>8Ol9S$LTeCOB5$}n*lA7Dn3>>-_`%}3?R@agd)~HNHO44=e*q5&fm#GX{Kxn)An!Kat zd*K$L9tY<6lKQIQP#QBf3&0&K)m8Srj%WEU+k0nGG>>C(7ZoM`g;k=cj~p+C>hAW- z$Z4mmf#RiN_Hxlz)JIWo!0ItwrfILY7X-)KmJW)F|3TB8xw2l`xvN|{QvR#X++``O zzQ%TnA(RbG#%%Zv=tsjS7`_G{T{EMl7zRuFJ9GHgl6Nzw8@`c_20BN}!L^;E7>hrGzjS=d(ABarA4vTLj1FVddS0=_n96GL*_YmY^Z&eXxvau;WH^JU zjy`)==4!Js43P_Z5zSW^5*Dm}g6YoPe1;`mzfL;3ah(q^qZ9IFMkAQf$Y|e3KXJJn z9k+?uhl?@V#r-}bjH^Du6<>+$m7|)CK{0cHBk{DZ?;x@{DC8!|5w>8JC5_71UrpYP znTI6jTK({s*`ci3gm%~|>Nk+t?W+M;{$l_@v14Zar!M}Bi=~W%ANQ9>ZksVsd0N`3 zFz_nu5SrKQer#Mnv+vT{VFQ+;{?buE!|1lS2uUg7v2&~(VX1vWUoK_#Je!n# zo2~{<-PXaN{dd0Bi!g{qGo51`IsVce7{&;OH|hv@t`|!Cmz^(e-hhd}_Q`*aiI@FD zgII_(XNX{oRpLioG#-*inS;OTY+M$|HT)holY}>6NN2abJK!lmAM-JUFv##1P(>JlVn4GT8 z7USElmrd(r3p0+s#;4KOw4#0qX=JY4x)+O~f400OV86Vk`$$nvT#tX{&x)4dgC%Q| zk+QJF;|f>|X6K8s1p6)7vfscl-@qlEyUQgL=w^Z+-5mhzd0CTn=w#hSlx{o_d%^;E z>0RZzEuD{)TUhEHdf9xrj@b%ee~RWtWOns8kp#qGw33{ZT}PX&QWgSc)18k168IN# z=gLJSZ3ELf4l8|GzNz{@DqwcLmm6si}fUYzP)I$3o4xUxkT^xE4h zNW)6O(Y1Z&>&xZj9JYOKzVCeJayfs>Hr)1f2*^4-j|D*kX(L1UWOzUR*?&O3J20Pr zCj;ISz?0)Nq7>+N7?9Aa6p6I9(3pTkf{(*}HHaqv92yrrT$kj?pOj)ar zx#R)-^A7<=mTpe6li^+c z0*;jZg{@#*3asH?TSKtd3bVvdG%vFlx$4!tsvYD2`T|OG4gd=bV0S(M{QQ{>;LtA^ zi_2DEHXi_f{_F;DN3Q`K$p?U+S2=(Yp*R8qO1kkKrl#2fxy*K2sM!M`z5~owS~!j- zM!S1;Un>5>uJoS+g?YHRd1eYiTz_Yt!;y*#5t~q})?7_Ge#POW`1Ptto)Fi{!7WNK z(cE7lbF{C1Nv3K)gxzEO{8<(w80g4o6Y}ftqp*ggBs1lYvZzqAs+%>#9s`cc5nCUV zYKKH15*q4cp;~$tlQyXcgd1%R4yAcTJ&*~E{-H?0Hs7*eFsE>e^ZLCUp9tNX!qm%O zBm1#6`)jGuXoH!d4NkPA9Ij&59JGhnOIg=_*K{OAfT@8&q=uLp971Y@si9${#+Vu&L281jkr|{Wk-}m({=7%Z*XRSp5$%I`q3!O? zm(gx_=Vi3necxrY*WGm)o7%kv;`2;*H#Wa4mAA~us38KE)iE%hW5*YrEw%&vjz8N0 z3tC*%tgs2xmes3WQu_dS=D|-Y&#Vt2>ul#F7OTF1({0u4&iVUGiZwKwNh?^qqLiB$Wze^VZ9KJ*jAHc#41nwk2HfTtIet-O{1Tz7m zfZl);{#n^DB(dQ@4C;Ov6Y*MP1lD`{B-@w;n9V-jg>dt9_qV$OvgL1gzs8KOb-&j& zsO5LzlMkZl4?f-P{$?THbT1v3FZf$N!Il;Em(lvmU5X_tOI2T&?!MoF9PxwB>-^8( zbw1N|N#Z+F`eFydP5I}YAM(HQUG=w8a0U?aQs=vb3`#dDo?t+KC#Ay##Nk~S)}cfE z=P1_h=)FjNt@C0>_%*+=al9d)bb;;Ne$?yVT%9kL{B-qy{y26!XTub?XO_S9Ff)e-}Sm%-%M$S~NNq4D~%yiozRz02;TT z1QR7xdlDUV^oIa$y-Ql1C+vO+$#H21_2UnYsQN0(N<4OduGqeT$WDgPskuQI5-QX` z;?h!k#kbs<8oS%qtqEuo4)mQ81nTpwh>sz;{)NFv%{=7rTP6dR;Cla`Ns%fi)$5{U zUk|Xo{<%Jpg*i6Qy-RaR6+-SXR(ANgKIMSaw|}J=`XoLzb!rQKmQep7b$<_oIj(S0 zRGR;Chj9Hewy}F@4xouDzbTEg{k`((azNU_{{?_nexvgp!dn+Kx;i3dMZL86{majE zpXo1)ZL2NaUE29yk+rYC4F5cKp?b79OK`uyG1$^!WuB8xCI|aFhcMIr zi??$P>T+^+Jk7cLneMT;1m*1E)oJOuGA}-Jw$U8uK>a0jRFQ%bJzl^Mz>xlT@go5} zFd!CTmj^X-eRuoJ$2jcn(CEjCXS@AxzB&G(8Df){V9xc|@D0>Hq04W-0YJe^91l0t z(|zZFp>Qt6qa_M;Wv0`H91Q5HfmoFFHy&6)KNx&%ut)ZAdv~8tBpg9hJ+cehVRI zpXl{D{#H9<-FNmZbcCTeDqGh@Sl2~CFO*qPVropVIwVbrfSj5dFG{uuG=oXgnk}Yn zW}9Mz5lyy66vS;Av6hcuokm6>SUy6_32UGQtio1&P4?wUUmz?6ivp}+S$DG|RQ=V& zc#Q0)`-;h}WPsiJB9cRZF*NoBlDm~HGFc#rCYgk8#tNU8q;#ywyI6rq;s)A%9!YkG zx-TFJ;VvenE^}#ZK;5rfT_o>EauoCz!#Ree4d*11lg#bZOd2*Z$>Ct1&majwGbZQR zE_12vA$cCjQYthoLO4`72?q|w!=ydh3`u?E15gdq8 zx0db#57~Vbq=VeW@@BxSHr|R}F)Y@qsz-|Y&GBFnv6W!a00xg$W71ZFNv@g!n@&G8 zjeRP&eUQbDy|OL*i0go9GRY1+**(umXb((VzI1_KGVDL;VrdFda(4q0ckj`a*mIOv zjlaq&_(}{O%~s-D^7&@0#Fm4;65o})G4R##8+0?jjhrx>SEYCw#WU~IU1g5#Dw76e zKaixTBAS%xG6}tzb9o&}?kbXhZ*@a*o)c%T)%~f}l{xuliS>6Q_J3p0?`6vT$Be*Y zwq>c}>=LIEiytnYzw!Bvm&--f;*V-F>`OKGOnDbYp(V2PMX2BzUZJ)M>$HVGC^k+H ze_><&rv80mbmYcOonmyQ2*VuHn15I;UTmK(jh|lD-rlk?wiJNsKQ94{{Wt^I4Jg>1 z^C+&8L4jZfOB+xCx=e$5-1%eAlpjfUo=ns>sHTvhB-Sx!3Zhif=l3~I1Onn!I*q0Ck?g)u0tOCSyOSc13Hur2`>;UN+S7>ICgxC>-ymx@*8fjK2EpGUEs@roW%Juda9QGa?< z_mQ&Py${LR0}vB%c2QJMN%0Kn$`10AZp{`7=+nXp@cV+a2;gA#PfGQzsJ=~(t~xby z3M!q2B>ROF*Iz&`4y`e2OA6&eabCIm0Qv$~pGPs*L?%2dbtlmYp4E{FZ?j^V;4UfN%rOAX zh%C&p2{LJC^+%Dk32IVi#iUK}B$75k472*%4u?2HMzXDYw#2>}GeG_h@=55(_#$P& z{B0~)lfr_TG!{H6U5K56Hr__Wo=mVO_d;)IE{e}v>-_TQ1D ziBHV!=k&SfU%-#DAnVx#>6lIZA#yMkLdzGC93tLeOOf2l+>RuTNivr}feJ54Qno~s z!X%kA#`kAPmbz!(igh(9b(yrfe_?g8a-B|5?SQ?PN4;}z6T{taN_dHV`B^hQ*W6}~VfMplNiYxg8e94uRj$V;w1WQue|MQZ)#7DPeQyATn z`YSA}&;hz(dtYUH&YD5@^tY9V-zF4*_(}Q1ACw!f$naUK@>YfH%XhVXclm0Xkr@uj zRMz`c)_=AW=EC(EmEt`{x68dS9~!HY1!9#+sWNC&hJknp3=4wF8z!m105P=9OLsik z@wE{FbDMm;){Cbfi>39aQMQ(t(ybpyk^}`XeG$n`ia$&m{xE5T;wdDF#XxXP3ZY=q z2*tBVij>=_cOn@#r?lU`IsV%=2Y5J-`XdB03`EjCT&_m-Jpp<-xN>I^8Ui&Na%SCMl@of? zhh_7nYN3YhF{;t>XYA)XjQP3;p*lQxK2R2)Ge(QO1rVzUoeZ0aUeF%9`Zx(P;9 z`GpbUxICOZs1edS7WWSEw;{^kg_9lnH(-Sp}J~LqW{m04UgCP>?h? zh3qL)B)W@KR44!Rfv%Gock%t8*67aEd0xCH6GGGQRy=%o6rVOjz z@nmqDs+66w?@CU4n8IK6%6()rV#m4Ag4GGD9er4d+zmnLM}G3eiq*hwR4=^flNJx8bz`| zM05Gd>l9rAN5y)e4M|N{_4+T(eX$ny3eGeZD0oL&2;2a4@rRiG5a}YD`a4;QS-{Kw zui9BEv+OLDNu`jeIxW2hu;f~VJOfJsL9LgAH7-Uck(Hd}+n?U;e>P%C&1F-MAK;F@h& zzld)WBQ8HMDQqvA+M9KRuC!bz?P8$bVqrkLbf74+a*^Wp0eSXi-&?5+14KeggK0E; z-DrKMwO$qfh|?74q_O=J`l|<#_c{+_7vmSf8?B5BPZD33G{bQ-XCpt^$=$K6FH9*7~CQY@F_HZ zy8KM%H58o2+SEIc{VjLq^8r-{r1BV;)z}tHX3K2%(xLL3oqxw;!GG8JOHS}FJAaL~ z4zZ{EPk8F{7AfW*cUXX7g_m{yJJn5VrAs(_TO zy>!T^)q>VP*6a80L>Z7T`@@%)udXTV*_~(#r>5LKO+tAr>!TbrvA~lM`WDp>O0I0G zCPjNEih%uyWt_t0IDSLYz_(mzEcLXk6%MS*;xhtve+w50uKBCo9|-ti%~^*>T3AOW zMfmLsQ0hTf{RDCcWl7m2f6W-ln!7u0c`w=CWDZ~8dCx) zs!vN3bmgAl>DuW>Q44s*>_OTl_*XqEm3YWK3}ZZ7VYxLZNvWzW{+?8Zb)~Fn$eFv3 zqs@zsu?TJ)kb^Le`c8a7MFP`1iX=s7T!y(9Nk|LaAm*~SkR)}&xXufM60VSn&ze07 zs1Zke;{;Y4IH|f7y#GXQX*U8$VkS?ZLJ};qtREMq26fSri3EK_hB9fGRl>-qh6#?D zWfP8bXiAj3vtc|#~V0IK6Usw z5bwmjOx}Bn+=Ab|BpnT;Y?VxiJRpiG(xn8`32jBW%C z*gz%e4Pc=Boep#YzoSK%!^WO%LwjW*COv>;c}lGd<@u-St@m{2i$?mt2n~#jmVDx* zf7wfc^ov*ss#_hFRz;gSc!B`^AOZTprzlHGBj|ab)R}W~a{oW})Mq=N>o_S9aYAdJ zUQC}U*f+}izuNJ%Adq!;%;sL6c&g*e0B|p=d!?uSWU2=r3taMyL z9CzFUr4;j0Ph_Dx*~Gj^hlC%Nm?*?#x-C!R_Yk|n7D?I%gni*}x*IqEeGb1H47qyt zes0SaEZvrjJe@<%Irt4aIh763$~OVsZ@LdiEowImHK*@K&i$wyCcQ^NW`%a&!$z9Q8Qf&U*C=UbS__~odNTQ=tNQVFN}gtC($nB}QQ`!1Zl zTt4~<5>KmTbq)~-51qggo%}eHAAgQ(Bhx)7jnI?y@IN8j>eM@sLm>~C$sXuQY{UV5 z?vd(8QT^C|t<{-hA{vun-k97RD`QBFHx2PPeD#Mh}@yRltU^qVK7GhAq)nMeH~u%0RBF8G^s!e3Q#u^~yqnQ{!=)c>jn zBwvhIv&m z%))2iQji`*gQp@6YVZ9-ykp1v&f+rK@q00pdmlg!%7l;N;M|im#sg#c)u1AeByEgf zG8oLG|Crz@!f|rwR*pZE(?_ia@uwW(u^dR__#OChhlyy%AM$PaU1@JU#=hf_5GwTX zyyQXUDmU&KdZhbo2j|j{7HdCROy4{q%d&r4I{zmCbWm^u7j|El|>f^hL*s)r=RKPv<1 zm9<*%HT!<~WDvxV22qYl8WDt|=2Q(y1#z8Btm68ymdT3FM*s<*%$L_NTi~wVgm(6z z*>Z6`jif2gJ0%HYBFuP_#8k`r&R9W{l6%4`NZ&>EGUXVYy3CaW2Y~?QkER3DvKukk z8|kJ7yb$vKH}c6!WUt(;+2Ab9T@L#fg2p6!%f`i4R`U^#u_LXyi}zk*!u5&tUw zFegbpjF(*gV_=C>Zd{8&m%bZM$QME=c51c^@OLD;3-PGzmVJ+OaI{d?Uq)u3mGJ91 z{vw=MGB%2VXqQ5tHe*XSCxkeZ3dx}NnUpq3#&Qt(3R8zO zE#51E08*ZnO5g#gq*7!+9`H;m_t+P~N&RjsV0GJ^YSGLICm>q98^wE0u-NrU@vdf} znMRrHE;-+?HxA^iT(Sf=gue|423Rs^kEZytZixy3(PENrs-R=6QDrWxyfG!VKr z4zA7GY=M7aC2$-x}GNlZ zdLBYCc1Elc>?m=&f9v%Gv+VdBy65}L8e#~oZ)}G`gh?4!bzmRXJ5sX+*PBX&t#?c= zxZY76v$0aR=s$_|K6$UM_q`vt^$r!_Eb;N6xpF!xmG^(VwZ5|e$o*n<^dVgp!1Ue? zSdVa)eHGAM_kiwvH*hYy&~C^H9w$Y=bX&;=^oRAmYIwG#lM}IiSyuLdzv_DsC(PtA ziAA5Z01sKIKsV$7Esea=znw3a(Y!0)Ivw}2yUS&4(jr^fI7CS035&rX_PqG@-eexq zVmZ1u8#2dM7IMsi)3xt3Clt?LI6T3%2tFUIPJ zi-XtG^RgUUQ=j$pn!QWVpB5BVj6*TbkH&W`J%0h8Y~P|Dn+kRa@KM0n&BiIT@XuD_ zMoi#FlYNqGu?REU`990aViJ6RlG(n>ntdatBaLt-$g;MFI3RdQIf_}f$coDs$#H+V zJoGK2TMU>3HDj|iE-?rAD`y!c!J)Alci!{FqCbTvYVw$ z($&B=DNFhi3DK_2B8E=G2>(V?1e=bDB{^c&OEN!dAEa@o4K~ z8AAOaXC+pHAF5qZmH{iKC9p`8)35Q&=`~yjPC!A6A&ZwauL;{tPtE1ki7~0I2-m5` zr5m`kmAJdvy(E2juG~HUbGFUeotkx7Nt*OZqSxRKFWH&Ycv);{G{uv_Y?Jm60E`cS z@s}sgAa&+z?&4DImSXsa9K}uGFLiL~AS^3)Z5GAmKy!>WaebcIk_Mu50AkfCX=0?W zehp&Ez5EaI`6nar@~XOYvU(rFN>s8kBmVR7oTujIu?X|`+RvFx&Fu7tPRpk+-sCS<-sE?z{Zsz-6rmX-DcgnE?cAd!j_a&8s{i?ZGf2^%85P z*Sou1jvL^|&hoXcaexX*AQnYDD@u2_!msZ}GGv8&7n8P+boUS`t4;YMuqD|P=O?36ghN4uJdVb}UjTGkw zp!W@|gxy3X2{p$$gSfj44uQGKFAV)+IO}1K>4oOu$sB7{jE~F?96Tu$W-x>8n2Gu^ zZdsg0bu%F(l{aGi8(9zI-~1u`_z>%%S*#4J4d@X4mk-gIST*pIH#?#VOKmWjx?ngq ztKTh;9K;0umw#=)%SE%lII}Jk<71t_HI68Q9D&bS#Sfi?H;^?SzCVDE5^NxTwDZK&a5~3vXZ&$?w@NCUL9*57x>m?B=Q{Tmi{L0qhQ2f#O?DxUykR zMwt}xH82ugD+n4GgQV>Uh@<3Tz5xWBIz4H|e^$`*4=l@f2*ky5jApssr(`MqLIDWQ z9uSBMUu_!G_@K2c3j;fcLuMWaPx_=*QuIw!9L*0cIV=?(`j78-|&|es8OiW<_*5Qq! zn6jEz>27DVK1>8nZ?K4O6^ zdBoxXp!sE?fFWgAx#%9c4AI2W2eIEesL9?PTj@qA6?>Tk{;PG-Ff5iV&WBZ5?PMTb z*lpM=ON#CR>{w}OjOM=|%8&zH8uW_jw7Ku$2S5mBl?E83PN?9>(J|CZBo6AwCyQgk zCF_u9#ySc;%&%ttD{iu!u$_@9m1hubBH<)j;TW*=*onS}AA>=F^|0Bj=cLt|xetW( zJ{E(fvRGw~(91^9zl|&gV`Q;tg%4l=n;-|{Pr&$T{GP0y`{VC&cz|X3jgCT+j({~s zH9)|}21pt;LUImN0|MPHnHqu#;o`V-N}B;Q;a?MztX$6_*IXhrDV;DmYV;6&%Fm?_ z7l+m&Ovd_Gbh!7UPS@&Si1IV5gQ4KBI){1~AeONnkYyY&R>5*B74vamEcK)K1Tkau zd;TyXdjyjK(?D;ZX6N{Yokch!`2{5Nq*g+&2zI5{vFOrF9VPO%s;z+#61OoPpo#Zf@PIYcg*FB!R{@7zDVTt3x7MUz0a(lKlc zzg8(Ee2W9~f`O>c!_)g&m-4;gagd7f`+53gL>y`OahfB0Im-xf{wwUkx3Ev0rAjQQ zp)Kl>E)h86a;sFI|}54y-M%0~{^)&FKQq zT?o=kQVG63cQRPbopTJyGu?^cMX~Wa+^_JOO#13)4AQva=P$^<2vw^os_A#vJv6DGzV!*U6_cE<0 z0d(OB4tj&^AYPVz^(1`asBvuG2h67}$_7HYtSoV709mqX03^XLE3X%wD?SX=LXgJ9 zlnW}&t?5-K;EvRhCKKH0^@U>xX}_nlWlxVNd~Ixpg~u3zbTf46F2gDwT8j$P>kVI` zI4{Rjn?c|<=k~ZMOuidUjB1yJD?@>EPs|r&OpO*yRktpg#T2&6csZH(rmT*b}WG}0!{S@e_Hc?@)~e#7p48avq7J_-3ptfmWf{NtX9MkD zdA>k2&uw!wXd{^Nvr`C=4VU=k=ZkGw*5KL^z-X%~+L8W-`?pIpf|>1b_-H|4^<>wE;d-tAFuX1MmLHxb`;PL6DX~ zW@FJM%h#bAI2+f2(K}(-mj!^4R8JO0eATVl0aND)08f^-dMJzwbP+hZsAhLXgw~y*0uZ+6x@nCb z>t>%`Vc#v8i$FX@6RbuYZ7I9P22D?h26cZe#z*=7*uYpqu)#cG%~P+DY_O@^D>X`FF*0kJP=^;pQh~%@&WIDo>ArJE z^&>Q_h1UbOu0M$J9yEio3`Wb~kbw|xF2Gi=OKW3*@UfZhIamTgo~#w=VwQBITYnAJ z_Nv+O+x$W$s8^80dk;>N{!-e4O9w;Beze$w)f_O+_g5%dwCpU-H2Uux)I$tHon()( z>hl}Z!dT-^@F9XRcMx^nbW-L(QtLYl(g}MJBB2j5jgi-!%qXWuLBXb0VHqk#r!>32 z@B9{!-cc9%e=4m?$kw12l@@dX>D{XDVWXSyyT0Oo-XXTXE0apyrrY6C_3#_r=&*N{SfGh9N6@W??FFLHBRD|c-9RY zb=TLp?l$@8^&c(?78Err ze-Q4?uO($+jik(n>gPayVId6NBj^0bo=P&EVeIVUH8oa4(E>%_me>^@jk{k_?orWP$i7o<13j2 zQolw0{srr!dmFFlVdH%teK;GFAQV)N;H6Vhtbkx^J&V-t2Y$g0L(fe8t4?1a-pOK! zc8oh^Vs=Hbm5CRDgqc9usr)9aasNsQg%i8G07(r}CGp1V*^y4#z<^MTS0H%k>22G z4WiO_?mS44L_FRCNpyb6PsTyHr}xT*3mN}Dsjbo>)}lX^=DZBAZn-pvZ>n~-w8VdK zRPR{6^klrIl$K*$OF^H@`I9`D|DjJB!~Q;Y%8z|=yZxZz7J2Z{Nc>Z4i;wa*YVcDx5(@ob%`ycFI?x;MjTi9T;-f@RJ`W z>WezI(XTN`@N z=n`gwj2SWJw-CaX0SN^p5R(M}dZ8Yk|g7TCQFY0N4ZZ{B^kUl(WCvu_Oxd$2I?)RH3U2 z`~wjK;Ar1R@v6j8;p*&{b^b=`R9KIVoAA%3&3)%lXEU@E5`~K>t*aIP+yC_cd`#4; z-oH)TLH#FDf4Ca>=_mGrpMpB^cisM7yhQB?l<^BFAE*Wp>;rHQ!vKFn@^Aju`ka>S zzAVyi-M?(31ffT0SbYsvfsw6nXP#TXjz46j?en35?PrVkZMbE8rhfA}_z`bjzFq2t ztbzOJP`W;q@D*J(}~M)5r@h?f}1_g#mc=bbKgE03sFtdNRgybeMP&v(33-2-I&iPUJR-~ z0mxaRymfTZd9lj$EmDOA3*-UEoxINdH{5rTq$bc75gdP&X6sE}?;>W?hJ|j*{t2;R zX^*iO)+pG5P|DaEv8h~XlGyp5^H2@ab06Zy6{h|z@wF8>n+5yY<{+l~s z#l3cbMb^J3n^1OLx&s_s33R`!yw0FZhU?k$n(d(P*>`I;m~L_ee4P*XxkcLR#UdN7CuO+j<9=ns)%@0QJ-abn&u$FYvKJbz755r0i)^@_Zefnu zBGoV(7%$7EwQKLcp2?TXimm^8#+Qq4s9R6x3zo)NurE%Cf7O=Wv(W6;EG&DWSy*xJSy<$p$m z7iD-z;T^u8pyVTK?AIETGa+oqYvmL8mld+O(4IBxL@d(ZfV93J>MY;Bf({nF?X_;R%8^SAo z%odrrW?h6i;{ZI(fOsOUk^fj*BGJR|pj>+Z{~S0dua6%*0tROb^kZ95D7!l_n4NNd z*R4lo8{{}{5=lsG6qr1jOk4IM;XW+F9ACm~0d#A?`Ne58ds-c0%KH)e?I=RO{k2|; zkhPw_;PtZejZ`*Fx+-%k@^| zU=Nsl6v+{3$GWVT1EL2}!V(75U!A?`w3L3 zS^pqTTf)iFrYFOs%<-4K@Wci_k*v)-w@}0{Vx&H6`=tobtysh$Zb0bqzDLhcl&YUa z9_>q5P8QonNUl_Y9`GXa7x7*!(%<&9!naS)z+El>jUv{mMn5If@4IyBayfGyCVSl` zNpC$N|3P52`SSedI`ZRloqq|h)bd~AX-E0}Lg!C3@h6>s1Ao-=-*o;|e}A*{XI-iB zXWf6x6N7)-{d4{Ot?t)KDfn9XM>KN%QTb#gzn`pri)O6fs(z@ye^~u{{{HvXA1;>i zKV1CBjPm-&i(i%BIxSxA!klalh|yebJ%xYHe}#A6Ucg}RpKo^l9Dzp5Z*^Z?>_(gW zWXj^SxwLzpQf7UQS!&lig`@?FMAP4ux{vo=dhrwGr#dfS7B7B+AN&~k@az$?Q+5A2 z*KkfMoq9^^i1ug&=pWhazEk(3?r!M`t?!Z#Nes8()kA6m+@fl~WJ`!F1id;^PBNCG z8ZN8*q-?Oe9hm!NWY6jlE=cxCwDiDl+ws(s$a(@b)c*_3G6Pa0Nn-)Mq`ZKTv;w4T z(~g$TAjx?_Ydp*9NCE&ua#4NW>SCPGm{>*e`QxIr)XyR3q3)#vGAgO_qSPtbYss_F zO?&XqzFAmU(8u>sI9#8{`92@~L|6J(4L-q!_sZ7q{Qv;v1GAFeuK*_%twe(B;&zCy?x`P^Mq8`GR(EqS9 zwG50#H(Z}UE(Cd2_(LSYR!BC!5p(ZFlI{~wm+nKdzk3#urxr=N=sVjL1Ar9B5015} zgrv!l(=r8cWR6Ova3-96a`8*#D5UeF<5CW1uyO|=NP`D^CSIr%-3cX@6kW}W7d zRZL2|)sS#+(La9ISt?NnVa%mOfE>{y!AiCeuZsF4^1&s5Vf98N>#FYnTEpt$nFjnG zsQR9RYO9hBR%1*!6+JE{Ch^bY7BP{cpq2uWjfeWqJ|;Y~A9*DG=th$glZZ*4XLG;# zk?!{iBxy;;tWF`xJN%#uOxnFCCZR#;JfFl56DN);a}yNlR#rf)s%Yt3yI-gIEIuF% zq4_T($>ZydAVsP1gDqDt{I_gaqQ|I#2QN@zp0i)@)r^%y`jdQ@HuPh;J0|(ci#_@>^`l;P;9W)AcO`h!TSl7DCMAYZ{_ZCB|A{* z^B{WFljB;GW~q5L$^gf8G+pTi?R-Uwl>UwNExCyJom;tWTlet?da8d9HS}?H{{fT8 z*}_g|sv^!b(ZxXGGQCZqqM^eXq^EL;-6keSsIT%^HUpSS2$L}m?FZ+sEQ z(U*(gY#d5UOXX*{Svd46*E*!^#gD!Dm2(V7D!+ z9=rg!xF8b?lD&Q#zJ%(hnh3wVtK7ve0Vof~C21^l_!7Dyzr>2+%X$40KOX!9etg0f z69-}{=(5-9Yckrhdn*JF!H-=_K1Me-gqnkw<3Ruvp4_~rykAVTiv*m$E}zKBiB&$& z%KOfPa*$zSncx@CFv*8Fab%HdHC76FqmViOV!&B(iUFOy~(b|1T^TJIo~HMh@jaAZbJSi6zmPC)s&*68UC6;JFKSrv!Pj>}f*T z^fuXkYS6F$7AqfS?%^}c1=a3U)6xW7f9iEasV*GJwP3RpK;40B&7!{7fpFxp%&pKw zNLPKY5f_WTPQ8s~@_D_BA4|1D(@A#K_hb1&X25?;(j3znNcPJzR^bq7_M~KsQpn{M zXsluZypOF0PnEpSN}ik?*it6h z5^Rmx2E~=umP0>ggSd%aV2un(l#paFc*=^t#f=dHV_!h8!y;j0H`$@Bg`e*+%L@j9 z_%=Bz_Xv179CNf{Et6<1n`R3`;cEIMUK4gLwKw@{qBqT!DKk5-Enbhz4)nbGzBH4J zr5qNAiLq>S_1~jfjb}?qyKEm`jsr+{nR79hsYEge>mdH8(gRCJ#Y)*>{vJ4XbUKDPsqj9LPD3!Z+_kHy2|I6O{0Qp&* zd49j&`|El2(=ZI9VGx5Xi$M%RmSycA%Q{)Bm1SAhX>~ewGz>z^DY`kGLI_21MT}W7B`TD&M`Ffm2*fIlh8=(Lx9zr75>>4nYFQZMs7D#OptQ1TROJ0I6 zhL?&{Mf9I4-s`|KB|?|KG9jA>;0O0CGx;$3t=kZxk{UOX}z?a()j zYw1dtxJWCJxetCniY;<-Q;H*O@Qk1Xju`sY|DyXqK_B zw{67qJi!b^%oWw!D8{3Pix)>NRRb-ZV3#sXY#;~bhT9Z9AZjD27io>{yaqbmEwv}o z^EuF$+4P~?qT~IJS0UYgoR>s^mFkXUuUQA!ZZBqLJz*$%LxB~Be&?4xw1UZh->o1u z_2o>4x!1)|O&{D&tU_HrrCvwk4PfH7y~Zp*lrXU4A9+I<-N|s;`D{a)b6(uQT4lyb z^eZ_L5c}1rrPODACy}Z&f_cywiAPO$g2Wt~wx!xm+)EbC#^VWf_wmxAT<2W6BECBU z@nXyI=5r+zzv3YC654dhva`4^LA{6Pk+||#)y-i+L*ZN~T4EA&vRj!NSt4By5_KOA zP9026_h)&uQoMo#NhL>yFTN}FkW-f5Srf+lYSS1?lgJ+u{D<+DJXcZ`ygLS011&|Y zK-yaIhdL$hREeRaNE@sPnb%6fmm|>Evk=#_B&+vF-Mw?GA<*b^ztE5n4~@z#=wRq9 zKsE586zgK(A?OjHyN2!>+Ny$tJmo&3M^Q!=3wklo1BMV*N9_B9GkFQO1)mXimK?XZtwIdcy7Hep3RfH0zWY%kWk6Z9e zTx-6;kTQ6xm|SeA>K~d%l?9pk!B!^SG7sAK=qWgrA>qD&2D{*v$h+qh3eAVMa3E~w zKD253ueHas4lFE}Vt_M6HR}ii7tq8P>>FT(Qcp+wZ|U)i0V*$8>9@=c?TIWYg~QS_ zP_MLTO~9skrSmB{PQY;z-YR-%0^*bw5?Wr`@9qQ<8;u$%gE%g(p(LiG@!o z;HiZl#(*u6RPdWtrq;pq@0e6M_HK*Jk-bev&gnyxce-TclfK%Zfy_J4XpBo4q zZlK+{fe1Ld;7%-+!=15#2za9VthUIXjSWP=Tis6-@JVbSC0Y0n^-SqMj15GvrshY}E5pZ6ht9F9?sA_3*>kNuhmWY8 zUuplu?fiNB{@Bh>7SFkz-z^?+J3rWY)W45*o>Y6&nbg8>(jGw#Ot#%q1dQbNL5zPF ze;2w~E7&RNJG(pGjkTv(>snxeT#o$b?x+h6$CZ0nGF~~yS1!CM-wZ}K>#hJap|>-k zw>zVc5ea>{-pGr-D}E4u5HNZ!aqtKr>nZC~4mx_p$PYRbkNu#{|Da#H3U2gU^n=a@ z`NLX=Uh#v1u|3=ycvJrmGyoWx?;4rc9jp`BuPX{#rffZ=@+}{qc?Egwm;oxvxpBx{ZRAS}J6x*hlw`|3a0IGjzAn%&or85ZyqUUwezcW-YMYXE`b< zIcT>LlAeGE9-t$T&2Ml?T?wODjQ!p^MLxy3R-VP+P)2sv@wyI z#6;>vb)re;Ep|i*c)R^x3V5&m547$24~nNH8s&vmL}k^G!y9r(%Eq?~a zki)uj(Ntb%Vo+7N+QQmB*|qn{p1xqC-F{y{WoIHvgYM(Yo8 z59QuOYuHZ%!ht^|iY^ixin_Bu4w*NJ!pcdbHacwrv;vX4N|39v{Nx9!M=xjwW33H- zlPdbAmK>>qOm&9Sy%>X_gVo!Ej{26ft@)dW?_ zBb@^miEfRUD9U;QxrfL!mLHfvNiTjZr$LkHy2a5}0Imc9t-jJr$(_-|P08Gdx7QxC z0`iPWRunKlj#BXI+FqP`Yfcg7YtGr|j~cxf&ts#YzxaIfvJK;MFOG`4$HLfpmR{?( zo*95W;VZ-~oI~f(V%_Ofe~F?oMfed<;Z{K$uy!Z*t`68a<$$TZDL@SPNeFBehX%xb zqdRh6ySs-566*!>)dpmAM@YLHkfy5~yI&3SZK~(n+hSF2n-z zp{tacLvc5)z2Z38-NSKImU1@cML`Ff_7OQ^xVVft61kbflYO17V!-s!M@V$RMV$e> zWoMKAE*<9b-R0dai%0bPH6Es0d@hA6x_1Lw4PlhG_A^e4ww~%r2WblT8ZGB4w+5&81ol*^9ll^swoEKq$K{Zo~3(gLD@hY8{{E@!rtY1;Mrr zal9)h!ju=>)VjHK+7gB(9zi-ni?!)w*t{Rt{)4yv8$Gl;sSxlQ|u zuKbwOG$zeAO`JE+7irRD4opDR9I3)E^Trhc@h)6FN6K5xkyMbVXkmm&L0n<>yTaH{ zT*BBGOqGl|kG<-(+3lG>dnB>KS~rkp++91m&+hB2RrknIz1kCW-XS#h+A0MT43$G< zTa$jRI|G0wM8j1t_dUGgmo3Wn)2^9#0TODsyg5rw&bkFD{M z#C1q_ucNziBjZUEY_773687 z`xh^rMV)b`c6%w&>14y9(?D z+<03UVK2>f)>Cn5XMx=WL7{5~s@8p{R%8F6Yh2z}09H`3!)A;%Bu}i9>wxif*`Cy% z!jh%Jy_8hEx!%m*TX<_avnV#!OnB;N3Qb36G57}5*~pwiU)A;4$LSWcqg8xocEC&R zX0NeaMYrWRtE)K-Zk*qsKI!5=YdSaZ^vT+d`iUzm<(L@MMr52geiq(B}A z!s;WAd#Vi2#x1dqw`|3;b;h3FB+Kd9%Og(+YiH6-9YM-5BVC51xor7TNrZh3Q8YwR z^temf8^sCfr@V^x6eG)_$BRa+_nET}3~`3_67WVnU0KTPCut*-_y zbs2#y%~wnhfpG2m*h@bJM;CbttlgjE9*_>oS(NhX3LUNn(pz9ii-n1aT{_jk-3GE9 z;dW?9&rF6LyYTFqY)}g+5!R-JzEx|7`-fn8KWj4fgO|Y9FM25O6LOm#D-7gK^!OA? zyZag;Tuc?o)!%rfHxGilmTI1l9WuMMdeDvgjWRn)BSK7C57#%bXb7hFNTK@s`igWzUhOU8PP4T^ZxCTaDYOG9H);yS(t(SM{;9-<^_iT?4#_s$fF60?RF2 zTe&Qa0asxbmmlS%xp`4aCTr*=G9;0J(!*~G*ql0EznpI&vJW3pUbO$}oS~C?( ztR&&<2}}5T!sg?HNBEv3cub>?Fn!~|4}X?&_oBkn*Q`RFw7z^Y*5l+}T4XPGdDWdS zfx2g3j(*Ib^lbE1D9Wg{d=JPb)#RkRNxQeobwq=M3m6mc;1A8iIg9T_dU^r%Nbst) z{MojTKl^5in_GGdyr(kNILqcVgep$Bo0ZPJXbOvF)2R^J?I29-&ph@ldRgMJT@Qfd zVY`h1S@j29n8_|JFHM7o(AeBg((3LtN>fnrDqJYC(x_wX=@4BX{JS4PY z%mZn2+fPl$B{o(2B}|fO1{(5+vuQR~lt6m3|4Sx%@xKx)u;hcV!$H7mOts1wXNyb) zTOR5Dm;|g%Rs7d*R+TD`s)c(0Db7^yKWl=>lWOjx+Ib3Rti> zHxetjSAIh?8-wG7ty1Zbl6X>PcLs@irQYEBUDqCHvX63&khRL|Au&Ay)TAm0&!H*@ z_fVz4L9P0nPXnY$RSup*RSxc@%9M3YnL8O`d;RR>!K%kYegtxFlUab@ri2Nx+_tW7 zFE|Foj#Sj;Mz|HWwoRuM>5Cf(Vg7+zX#@kZ&L9Xn(E^eiExGfOU3iba6s!C0*2)r$ zVVw~qr;JG}r}%1j5QM4YkKn92nmnnaU7eiJvmfU?*5Dctm)zK}G=NqS99XAtvBnw* z&MyKfIK}xnVkN2=6It0gpJTmsq8e6fA#3frx;K+`jCG5wfUFgY zjZENE(xv?0!I`S%J)Bkk@}&GfOHSqAsFqYTfVelc&bSKZWU7LDhmrQX9h{dzuY)|@ z=+i`!gXbX0!M#W*>s?0U2HHYR__#}2(N?i_O(bnDz2Zlt<5)3O+`SiPs)+}1Ry83{ zs)?79lbZN3&eTDg7s{G~)ljf{jjKd6kh`B6@wZK8L^r1u_O*0(i%Y9(^!sV%jLXO<|92}|yplJL@Hqz=yEra;rSHVH*Wlui;d&C{ex%aj=^ zBgx-U&mA+k-oX+pN0xeONg2d&XQ1hkL;F|@B7($dIHA*d#XQXZ!zB9;Ah1j@OO%eH zMFwX$6~OovrZ1(h3Q*(kNyQdNL`sT{#^f5(qAcq|wpSUj=a}ULz+<>G=%)a~sf|(% z#aO8aNkzMfq}9e`JzJCKhdSS8#SK;Y_EuaBKTW}$M^2Rs*6EIdr=^O^PA#eo`@KJ| zIEN&@bPsWF?668;hNk_BG>$1tOpCTOoUcyKF3Or6NgS=>t_bHVk+mA#Su(>=Up(%1 zoYlyZCylI=$qC5QIBV9MNa8AuN2)${8}rL;ccg8zJ9H3r4+l}7NdeEav31=Oo^3zc z*hh1rBMR$nk0L;aqirK$mbwGrRD?MhZlRb6q*sI;w^2`bv^i5e74Fm_+bhC7N|k#p z6%+AK5Hn%KY!%VM@LWfpHd3n~PJy|;5 zfTiP*E?FFUloPH}_kfV+o?J&m8dDNUXEZ@mqYn^_$_j|?wKzS`W~Z0gF;s^(6BD}C zh}_Wz+>AWiO);+4l8r)0NmE7`Uit`onefGmj**HjOh*H7pOL7~Z{NY6ox4(06|p;T zV@0jjFGXi)t!wWKJ9hJD-!=UC-uJN#hqvW2xSSDC2M~6=qtoC$ft-6HP&&Q*CB%Ar zeaAKYx#oKm1O4Fl4&gau zon_Av^uzg3^M zU7G!O<76wK1_zCpyv3||c*xdm46JQZ5Jb@cLy#)R6|}$#F-S(#N;S;Z?KDTL(-Fvz zO_bMJ;#jL??n#;7CO92seSWUfQ%MYMbo$qgNY^ry5=EeC-1gwg7@FMaBMg^Sgz=Rs zbi4agQc3-Xfs?A}EhCX+%K8!Q#kiu%u7b6%Oi#{)xzoy%-gQiCjs&5Tjz;*PAuLxc zhLAip#b7_&q~I)0J#1)M9uIOVO9j=7-`T&K?QK2MDxx9kWhbHtxBe=4@fO+7yS?lVs!ifuORLfcBt>f>7>@o)Sc) zwj6QnBElBws{3TMLTo1PU)XShZh9 zZl15;JXci_nwxk*k8OZ{uKR}^&f!8&5^7(25t8sv>8h&%#eq<&O8PvOjS zfB7+?$-kJm!NI&9-mYbIPHHxms*G0 zj!J;Qd$j#zTLDkDA4xXJk91CS2x)u?m(AoaCmGCw6F$@7z>`9PPf6@*W^E&QhgY>5 zahBsQ$SU<3-fRt<597KWA!QP3?vTjwiR`4^og%^&PQbHFVbg8=5$sjr?iT7;T z#-F`xy@cxy!Llfi;v|c3#Og@CQNf8`bs_{1POh+PhaKUwk`lsC+doUv0+?Sn5F30* zDL*B6my+r;Cy7qL-ZYr>*M;SgmAfQ~Ou+@X0qlvn^2iU{CnfTp#NbUCzQ}O_y76o6 z*XIJhuHyriN+%fC*GIX-|l4km8?l7(eBYamNFN;Nu1!f{wEcXygnCXTchr`XURPzBZgM&9)Em{HxxvY`Jr z=fKSAkPcXQsI}>mc(B*TB?_c-@#xAfcD@Sc#nv}q@ij^TlcpwtKQOToK zEO!c9#*vvu)Z%D98jNr@(=DC2MpMOceX4@vT28O#1D1t*{aI3hT?b3k1`BZbg!629jxIuC`Kw z1gxur`>|UH8>4=$Gs_jTn>Krdt9<1iXJ?)521=Js94m^iilx0*f@G!6Bi9SooEBZ_ z28!XdSzx-xcv-cCVx?9w!nVa>(kpbEB3BId@=?Lyr`=ZrJ4lJLvwSqHZnxf~*&WrN z{lu>qT7hDSi*qcnO`~pPy9a%vW7dVIxaPM4!V*O)=Q)`G-H{$Z0c4TNl79UYW$NTxoF6 z$nLHJ1hFn)nM3_1L)w(2v6xUrevg=e0;a$hJIN=yWe<@ERTb=ZUpRDod3;}aF@5Cr zC*U%^%eV>4RWdL%2?2{ zdP_W%=Pf)^9a!kEL9mg}ubqeUxJ@K^w15$gmR>mT_9wUA8b^2_>w(b!UHC8-67uyy zuW_a-tnq}uHOW$54j9V3&kGndfR1`VVfCoxjRWTepzQhnvy?mccx zaZmO0MsSBq#@Y9bdYvG zR9@i9&N|8sO*rH3eEQ1y2WagBvymPJC(SB`j^X^-)VX~$xG2ypADrJ1oTA1s#gvS zCU@*e3h%FarF?yLKCyQykOAI6ntP{Waz~2p8Yx|UivE)d_iqVl-Q|^C=k$~o4N7yD zkJQCMSy5_7?ghRdQ0tx`2U05=ez%Ycb|XBKx)p^ zsnOuv@wowdzrJRpN7IyMuASVrCunfkF_C>j;cvcV6Ffj|%D1S`Zja zrftapPfn&Fv@t?=(6InijNx#+3PX{acwQ}iey|)m&g7@Vw7z)eH$q$#+J~uEy2CCpw#(k1^O=vI>UI z_?0n2I>F&D(Otfz*gW0EIKO(#-*?s!R5NMywb3;!bwg%QO63$lLg@N;1epXmkvqtRr(Zc3oQjJA?M(LwV0dT zzA#Y>$0`Nq4j!U!A#Ql(!wD&SBZ&Sc<<|g6a}U^S5-fo?gYR-M3*4~aV218qUben--~LVLmU#pTJJ*!7 z)%wa09H=La2aq#hW#;!Wv;{fR!tYUBymGgZ;>s{E#ZrC`w-lk2{{K<^j<>7k4z?S2>y4QUm8sxRQ@C?B*E5VLXR>(%)y?DgEx4K2hTm6r*r?Z#w z;PzWHbBuWEH1ss3fv0G`RSGzyFbNPFt=j3Ww?8M8%~o|FIfv&{O9OsP4AWF3V#LhJ z8pdr=*6gk)$m-!fBVk9A1s3d97+WlUqngeAa;Q!n(rH5>6jO$BInO@#hL%VDr4lg* zh&#IavDUMs?h$pmU3G9z3KN+}QiV$$T$DGm5Ym2cSZLS9C(7JC$`2SQJDK}v^uH+v8sDf}dH9J89BQ1Yn zs;uuD2gP`0xYGSKF&aL!m4M=Yf0gy4PG{TfRis-b;f6hv)trI|>oEq&fLy+oAi0)K zK=gMuS9gaAZH>8Sb6rV%LLsIppK*eC`54$n^=Jn~2v6#7o-fMJJjhRp;I z6^DGJ#_m)gN<9h%fj1y{;ycQU+W1Z5KgM~xUc0%us$(!Ra#)%+d1DVwxFolP0nrI2 z2655ds8Ys`S~)T1p{4uTw;1>Ibs8U&*~@yyjcR@Y*ue@`zOvVsVgGcFGBK@1`twtY z{iD@Wig9(&mmh?L@2D1~hDuJ;YREgioFVJ8e%0B#|MPD z;tUk|A;CG13oCB!!^8Q_ z*XBfiF|k~bUosn>hv6}Uw!SFpp2AOtbN(Gw6jha~m}lq1!XX5hGgTN-XR5DDZf^aX zRo9}q2vTi*LB#20xix=Da5zd%sUBCmXH@%j-=q3RPt$#O$KcE`lth*+^i)CTC0h=r ziz+znd#6gTZm+H6tQ2AWy*2aNm`GVvB-unqdh+uW+nZCV`}WGA+$EKLmCn{OI>E9? zwl<_oEKMLXtH9jRc~-kSRZ0`u+zX0HyeQKGb1wa61=V?g)6$QwGur=G!@0`Mtbt=` z7`z*I*kI!=<;hp^1R7vHquxNw%>YFMj~*bJgHv!32(tu$8WX%A)n+u#GUmVy8~L+w z8+oQ?YG86vr^s$)>Jj%pT#-ExKMHepPEt>UbYVxAv(p5`)sxxd&{S zE-+iRuDFbQ@z=?{PRHh^W$bg{8in#U7DuzL@67(uV}bjzSjp9RQdZX3t`aZ@wUnWp z*Iv(GCRxkN$`WCd18ynb*bNuNbBmGrPNi12sf&8*6g{~JxgbJaZL@CzeyT`lMwLjKKX7!psIAJ2AbW1K(xRHf*# z0N*Pt#8?jpOT$T9lyILhZTEGsN`Q1THNZH>sPglbZ~fMcW9*qSK4aSMFPj-Rz#19< z`nP5rW6zZF8Pj(A|Jz218(@u$M*vA{tJ73v_Dg-C`m z$DD@QDGZ=c3Af%A&n09kVzd>>(@Yi9j<$r*{hX9(u6qqD zX>(L8zaXTqbK^DUkUVc;#%5EA4md(5Z7sIY3;XT{>b^dems3h z`C)F_NTy3s;#aNMHvzP zA7E@ucu~C~8q%4%9`(v*%1wt+^xAqw481Xd-e+7XW0!mvMuy4$;wGof@UoZW0u3`B zVQ6LeO3y#?r{dhMhX&`?T|HF;j8z~b-hsP7+63Vmcf=qxjdBKwknYca*cw`y^Pu|W zUzNd6;Zau8A&l!Sfuj3sLK-9`e_94R5C18TI;Gi86y?*aB1^%wG#Sywc8iH}f&vZ5 z;8Oivx`v@Kv4cN5xadLVqbfu9hai^9)Q$I$bD2owhl!2N6$(}!k2qe;X=F8j(8jqC z&lB7%MD*uEw7WuE$CGP$jS;!ddnT6hT1R;E%rz}D*!-0{9O+7ks*1q#JKV`z4cqQ6 zAh^aorl6mdtLu!^6Uwr4<1K8FG`K3%tThmwguB*NHjMFeo~?4gk>-?IkTLp(t(L50 zsqS#fbW5|Fx4Xk9Rq8y~fUs0ZXq}xkKp5AhSkDJ%jJ1$^#@I+{`H_2~7eI^Y6N?jh z$exPfWxY2SN%mA9X~Ig70Ok{5*f#nw!9;)E|6eq6Gazemlir!`{WdXFYD~zmwZBS8 zUi+NXbjfnk2V|(jl`{#b0>CPArpaJQd!5s|y+;{hOTJ9we3{)Cv9;S`#<5gnY(F^Z z$3=O}2`zw2&_FP_mk=y4qoBZ@a`N*su{e#KLyf2(3bg;xN|glb>V<(5MFc~OZffdO z$`#8W>&{E9_9>^pIbXuBf_F!&1tymxXZNs5H*Vs5u0y@1occTZZnGT2WOio}vzm`~ zvrb!G>13fpusXhvk*Q91rAbRb^H$|)c4F1zX_`(IGvaTBhGY1Db%H7^5F^d~d=>xX7BFoyhPiwbk(ZYZC2W<01+lZGCpcTt6?GMWhvrJCU%85S z#@DLZ`F+EBTRqTgAo2$&HhU_F^B63_f}~RsxKin zqvxDk=#SDKHH2qHR2)^nwIe0-4#PO8IpW4asFk=@GMDOIBPJj3@<@5W?Fv2BC`LZI zs>#EJ8O96j*_e58-Yr(rcs^K`^0TP7x2Zp=B9QWyQ*%yPypmomX~SsB4IkvSk02{3E7p?sjkXk2ROeI>Xw^Q52Yr+2lD1T0i=g};X|IAf(#p$*4&(Cv2I-Ymo1Qs^!p=Mu)^GtMrl z|0GJ>cWiz=MrFwiA*|ksYv*;E_tMpH;rR7z_}0E_dwd6bd^0`1efaX1a11B0@tW{VlTK?V2|Spw<@PcMSiuOXj>)3SO+YEfc+mV@9pF0`6cvVyqOJqa zN{GJ#X|5>z*xtPinQ(90ccD}L_qE^Dn`84JcZWqlUYQ{oMuwDt@kMb;ZmycL19R$Z z2jLw$dvC!bMmMEEg*2o<4#o9|foG0xC_5_|vXNQ|t3J!6nFF!6A>BDf2FPhItdyHC zDR)yMS6sD7rq&ko-eUODZLT=u(Dry*nhg|x-P@r;GZ40Xhpp2T({03bV@%Gfe8>W@ zC+?n%ICLOHeC29`SPb7o8}7NjDurUapN;f4-yKV*@F7+^Drs~Rj%}gcai5kQq=t{$ z*-n~4r2%hrU)FF_OmHc@TM%Bk2?wvkV|!f%xa58H&LdPgL{ICZl_32 z<&YsnQVNFTc%v;#Y9;hn)zf4{prbo4?=hE4dIJu#^ccth9KsrLO0y0YrJf z*MnUDmk_2rSxu=>JeOECkSQHk&Y4oKHJFo%6Xf6G>feEpz8mZq@xxl7#RND`extowXY?D+F4-2LWu)8I=38Z!kT?(CUVa`V##HwTTiX1L+$jv5|Vq$P>6`Bkd zaHjFBL6(v+&DBod)-7c02j@_>pR)4{!791F@|J#?$k+xdZ@O-#H*Ve@nI!q&1H{^_ z0O4$;6AUc4v9)D<%L;Xw1vh>_I>*-JP?hmE0A=V#8SlWkNhsQO>S`X!s8E(60(cZB zmp9Z-8)7Sz9c2~lNt_`9JYB;^r(xwxu+JyhSi-6UuAx|!#gz-ZxhkVTSBtS)e=?`bwS_ zwzF!jECOZgl?osSWPoh`b792rC#}E0?q@V7tnGfzs*@%YmcJ0$oI*0QAhLuFnjTJD z1wQ>-PaahjFg5fIh>c}~r>v2R#!#|StqPo?a)B?2R3~#MbWOk2+-YT2Xw}6&jk3zc z`htk*CIaX7hs+2$?N>Xi!NhtgGdFd#`Ga(wLNovTD-Tl9k~*E&1Zk^*P^o?2MD|M8 zR9Zt`X^2Ub#7cro4CVy``F7nq3XoBxVbOp zHm(42KnBQ-{ug%4B+)O)3G3$mEA;YYT(#sc%ryZ<$*s{6u9!`%fBYJD92r%`z#2Q2 zO8;H={Z;?g`+h3#sxLTHGI(PB|9`*9wwOKrrhE5~*b|PT*^$awRhHE;Bh~n-hdZ-V zK55h#zUqbZPjFS(JTWbYXIq2UyL7S|v*sU}t@MdmD|jySR1B^ZKjmtuPu#{^nKDkJ z^CJ!@hP{{WuvU8B;cdXCy_XHZu=nyw-g~j1u7l9ERms!R)b6@R{rbOCo;H;5Y@Bqd zaOog?O4Ls7h-+|8HuficQ3Vwtq@)36h6Cg);T+V zfBeF7;wu*}d~*qh##K@DlLXPZk;CJ~S&MpMF6JNxUljH3GOi2YXBS)!ud6OSzdo){ zT4e^<9WIdig8oBO{E$>Da&L-0;Avz>)O{rSJKeQbLO2q*u+ZT=c}Y0a$&bKRZ!Rv3 zen&Eu^h7e1*uM->sekgHKlNJ#2f=lFW)i3DuTnnt#ZXb&w?U=-wTtQWc~ym={px=o zcbn6?OB>J0se7YHr&{)@t)e>%ETXhRuvftoS~_dFVqIK?JU|F4RwBC(;~c8i;?tn7rl~PBL&4mF+bZ2YVQ7=GZGs@l@H9HP4{#&d+$e4~@e3(Ds^T$D z%67TK1ee8S>^93jU~sr|6AyoI3#%8gD$_@d$YcT0+*Kv2RetI?53yKChlYrho>zAJ z54Sp}F6PXK9-caj!-i${!gvgQX8f^e57l{Cm%K)=y{}0NmL`bzMc7B=zTo1+k%v$r3^^f&FE&f797 zm%2{80mU9=SnP4>`s`Vt2uFhTbpqDTW5*FLKsgh}>*b07`6}3{a2{7t3NMe1kK;0| znSXaZd6&GE$*lm1i>x*^Q6i-inX|;OIGs=}Jz<(lsLgB6Z4MLljXzW0Fyl*%(#bw? zu*_G(VqZGEG7@{+(*n0rYCLJ$${03A5yyIO8j2Av6~;cRcdZOu0qU|rbdq88tJJ_(KZ~Z$R80A)$!#&~ar~95DWGfp(gt1SVFTEd zfIHm6;3bsflArkL2~qO6qtV$<2ky&lhuM2?r$Oo9<;rK>5XD+X*=X@~g?5(^=Hs5( z-RZ_>_#6>tPqhInb#k{<2*Xi?wYp*k-9b>bcrZ2`BO zOZkI<{PmS9|0kiflH|kqyn8bo4jI-tJc}+7-cA1Dg5vnLCbWB#q4T+i31k12E-3zW z`@IE?CL`F3wswLZ;Z z>C0Jmj=%W*aNYO(b7%XxK099Md(DnmA17TlZq3^jZuy|pt#eshO=Ugm$bnAx6jo)N z+}fr2OdDd3AShDa^>b*rr0qWks511On;o_1@`x73o5JcSNbKhuBadA zJHD;FShp&fB>dlMTk=0WL5I&+!aAKW`N8=;xQkDg7Mn+{s0t;pq--d?juC znyv-ycydknquUn==N$E$=pI#GqnDEQ(sgpKlTf;Ezns1a{7MS(pon--Rl{+O7kH#x z-r}TwPV#f^O|4pUy|^+I?>ob}D{wtn7bc*Y2=cuu?^ z=~#CS*tr14so*yV-e$&>oZhQ=lhA7GikC+;Eiq&4@{}KEv^Y5rTHqb-9O43s;Uyj2 z7`9|t=THYDuoZsvj{CwAy)m)nx@g)E2HEeL8;eL6EgTdZxhP8@_r~&+1)VcyKjQ31 z#++|aXOktTr&D@3~-`y#PG^F{Ma)=!c{)*2#bU0;kZn8 z(QH+?*yiK^gKE@5AzV?jYkC=%x_#F*YPgthx!KU=0Q%4s-Azxe_|j7?NoRpO5tuzL z=nY@-*LwXs{;=2oAW~URNUXfo&f`f{-c#+js@D6!!EA(tfu+Ul(z+tHSR8Xj=tleS z5=|Zl&&#U&WDU37P&|b`4IBDt#M=F(0+|DJ2~GKcA);7UuRP0Z9PA2uNEP(3#E+_i zuXAjy;B$3b@3{wQsb9Z!DeLRo`AVV$O`OE09nJngBr2$azJXswr!qsY&rUJ|b^Zdw^uZ|Xyz zcQH$?SU(AMO8n!OG$;Mu9I=IktQU*LSw#+Wz~vet$o%{eK77-;ur6>Av!H z<3j%-V@eDpzfv3`dp4Z0apV+I*zmgw*!*q%-RbK$_b7PJ9}>`z(=zVz1LJd5+2R9* zeY(YC9M|}z5OXQ*9yWao*SB^+RyBub9Ne9gkX#W4&QZqkA(>^$c-ch?7{641C)Pve z`b`Sn^exe&uiQ%`N=0?X`2#d4j6D5i~o?PygfdTCK($x4lLVM-ChV!TJ<^jmCvo_8!Mu zVBy_0PI`2X=mp+5v+Z!CS=gG+O~_C1SSx20G1lMx_N=e+sTg&6%n7c5QCxw#z_szH z`lI$f^(BBwh?qP=@f-a4`EBw-xzQjVD#!AnZQOOV0Kw7Xj)FRxWI<9qLI4dy4UHP=SEBag_I<1| zMD3>v%tQGRL*$|C$yo{4JJ%zj-ikbbO+)PggKQB=;tp$Uj*)N7J_Y zWf5yr$7&LB3&scxD?wG5tR)H)|^| zf?r$zX{%Nk$3{#Ny%U-JH_$C%k5Xx z`SHJ^&X2aEeM0?}3;?GEg5b-wH)x18zcw8)<+a7@!)*usBgQKQbSqlUt$E+28(R{4HCNN{C%tNlqF;4n8JDi{`~VMLGma2XTkvwsKI z!COJp04bH}`l}(qp^X@G$7fZg&+=XqRXX`tc&?4=qE}u?1t(fBNuDZZP|Az-TKnoDb4L4rWXBBxk+MnvvCc|9EqgL8fE+(6h{+^qk38mT}#9i zih_mA{17+fz)S^}T;blhJ$58RPx1S=yX53{t|;1;-DThg)Akb+q2s$KhJPAqP5_ zoP|_=D_2V^s4s{8+2auvnGV2QOL6~!p!lolnvE@mr0^pdU88{{t`@wMrBL*znAeqklm7_y1b zPZzRVsCPAa(;4wIK4k`VppM!L67?qGMME#9Y~1Tbh^T>NlBiczg&iYvp8fI|5a(C+ zsSq~aO;e%wCQ_WZMt3=A^586P8c`HqO73axnALX2PgG)z zvJ&*($Uif-WyMA`S3jW(O@}ub%@m*OPB1@} zccj)Rm+d#xDegl9$&Y3ig}sSBLBDUce<`uf3!}u^g(?-yHn z?`w*9zx@koGk+l@TvDu*`6l~F`c?+d_G1!?jIkFl*G%pU+g0>^r;C1rx|vCJGm`-3 zP>eST!N%#D?O=+rl9hO;c!)PqYK zv_6HX+HxS$T0UhA?q???2cKZeAr804YyFL26Qui`?`<+1a-lK=`B6jK=*wbrSEK9wPOj!?ETM$D>Xl z7aYJ=4XX0CY*W>Q zCM5SdZOuzv*LcD!rZ-ldKbxeL+%*`uhKheGSoY2Ja+%MnQ2=1C(lx+&g;!C_^B${hh!B_nCCL)D@D5>RA^kUv!tIr66^KIEs%Q)8;fp&xxiHKEY)jZ zr~`PnfnCS$5vd?v2h+N`zicw>nW-80ND=Q(7A+&DE;gb3&BQ$i0H>gEiuMZAGm)^w z6H@|9f>jl(+NPj#YNk=6u&r6E34>KGTftx;>J%VjN_15jVHUKo zbLdw1uIgd!X8vr^(2Bzz=+M&Td7JXNSoBg_s}+=#uN;1* z(oxt-%2lUJe7CZHWo8rs1^c8)^2X;9ZHq0rm|=ABv!L7-o-Lj$6!u*4O!*5FqH#8O9e=*Z;GGU1SwE0-d($A8ZE&H$ zQ6^gr+q=Qyg~b61{iXA6ULRkR`p(j*@cXI`+DWj792;kXbX=Zy`;V$yLy7)7+o0q1bssI zS?3+uvix$vztVBwf3@Ioa;e4px?F|k_)>QdOtP1D6&rFt?(p+!=ix3tC%SL*L!Fpo zMCL)otCB+N?#@}qcd3RiT=I1u!+NT7vL_(cWSx^F(BY$O{?CMC;cZN_X2Q?A4=!x# zu}D(Gf9{3O9i3n3)z$FJ&PNOM`_Y1rRiIB6Jl~b~`R+?nu)os%OkRmq%Jw`S!+fCq zttD$YHq8YKT(W@plJ8C!P>Jut{6xR66(4ts%N`3KckT}I-yL2I_~+98aJ&Eb`385>$c>s)6jT`EJh7TyT^|#Rw2C&easLKj_kODkxEPYlHA` z2aBwx{}*!#es^(ary2iZ=he{k|GMwjeGPxiPo&by{(5p|T-?C}q5Ql~zHxZiTx(DG z6&c5XyNh?lx8B9JCkC9-bGLiKr;ri@L_~Bcd%I$Oa|%jLsC@jWSp29o{3ty?N=y|c z-V_N=WT&dyj_&Vr7HU_pQ2SBadzgWz+$q5o;b-mV)MheBN)ay>KUK(Goi{rCywUlj z11JBab4<1d^_Ng1F7g~>aRWxW(~-4@nd_3{n1rC_PNJtey1sr>`Wf}*nOn)>4sF|O zfegc*qKH3~wa-sP%XIi@@eBD*$pUE#j&Y|fX&wkCWsQ9@Jl{iEZn3KEQceYvV6jw_ zWxPZNOETPdX(7w+Nw!J!drA|=68V zhub95#+S0?e^uj?;c^>{xtb@b=2tX9zpC;~QnwFwvS6hujkXlS2sD{7d|A(`CB~3O zC71Sc>os2#wCi$KB~>IuenH*tqi)%_*~e?T@0*vn8|@39)0@mn^ghl$?7L2x z$DS%s7w*Fv?G82k9WqMW7w+UourGGty8AFrdqt72bUv2v$&pYjB45~uc*R_67GSs#NHMp@$=5^dl6BdXTQ z8(vtP6L;i~=)FBB+jEkv?@0)2GKI1qI``O=5Y#5Jl1gdESfX4mBiw(t^Z_QKv0y&t zm9{rn?@+<-Xdg>l;#m95TyQ9kB5s5prGue<=0Zsfvcd%E#C4nw3C`)frK!uRqYRnS ziSDKQ^>_aaRL_v|O5oYJxH3Gi>}tuaeBXqrOY)vH=8BWJw5SutI9glfGltRK-5aL) zv*!?h4&6xW-}pGqb5N~-_-7zV(g(lKkYIZ2N48m~DY?^v#B!fS9hMVe)Qa^l>(SOi z79d{GmeY>!itMh1YAf|EaZW%n$75!J!0gNU;3@!xI@GA0$et;e0!zqj9iMk9G*Xqis?AuC`_oNetorAl z1y_Ou?wcMENoT^CRW{Re#ElwmDqP5dLtsZwzZ*lXFd=wbJoUk~~)1kz(`!}pD!eO91zr>Cv;G`oS>>LU{%tE_foJ^i$FP{Bh zBp`bRM}vbUY;26}CovSI<(uq_N{G-~XofA@#bLKk;+%ZcJo(Y~XC9+-7CpD|rH605SYr0=`*e`NpviLVAc4Y&?%Xvd`55+1M zxa+);PjS4<8d*ngjLpJSPc(bFMDy&YQhQG~*7 zFk)kSm1Cy<>+r0vZ}6aqWX52uV8fV#^WI2?o{G?!`W$>k46dn<5s~@<(KWE4hx#fW z>WN27u|!ZyfU2mkV4xnDu5nbot%@CR?0{qI&X&pt1w$@7U2UkixfO=UVJHf?tpwx3 zX14qFBubTgPv5#Zcuwo);5n_EgXgtwj5u@aR`I{3bt{;8ty>L?#7f;q(OHJI*47|W zPa{(Q6zMPgwDUysXht;?e3>5b$lw137 zp`SM-|ML4}=NbJ1AULreDeU z66hdxGk7UwzI0tIP=9Kt4WcMOWjK$_tteS$t6y7g48z3ZXURjE@_MHF{hY9ruNCd??8Ec zvb>C^*seK5TO7L852fFFl+{-p4LxW))r4uf$@HGiEC)r|X_yYz04?#@HGGYPVu`lY1J!)^q$R**`r#37``Y4G)eN}z@pQtj*c&^ zLUs!ilbu7<1UFSnI(2y5!`Nf@o_#i}^l6>__p}XrPt?QT%Yhg9V|M&a{lSJBKhvD{ zGq&Vnv%lTu7);(o%Lx+v5*2)j3|lvD;m?*G^6%J-^V)x+RrHVB|0!$cMsvpWDfMD) zAG2}K6Ea)mB>5JSvp(EIO17!@g!kHiZUMizOA})3X4T-?E`jA*{>;XOGIczq3|w(l znacKm5Xxhcl#X!=L~4s&&to1IOY%b0sKgZY-zqJ~(ygf9Nu%$)QwzR3H6VAhnG7Z^|BQ*^8dJ|| zVJ&U;y_?i#V%wP>c8J0?Z29kD^?Q<^)_a%sRD6cB&MxlmcoZa(n!$}y#s#MaZ(WFt z31c_)9o|{o7H)o#VPCBrSe#bi3BPyqwn3eND3{g^bAimht2GD(&Gh0VVM_3+FW9&#VghjvrJSi* zgJNFQexbY)U9mND-ENoOV?L+Tt)^Nl4_H{(AqggF)Q2UPNFqw;x?%Qz zDVV4%P$@ICwN45~`c^3tlDW`Mk|SL>l&F|@u+J5aJWpNP<=*=o#}n&TPWar$ZxwTt zTkfX{J!t$1_De9#FDdjiMo)i*teNAkV%_z6k!m;=C6~o4+V@wpd!y#Hz`<*Sxq4Zl zia|J7?++GHx!n`x+q3CbB3u!qj%ro!PMn46S%4 zZC#NHO%>#OnSJlZB8j()w1M5*d~*}0gw6N-8jalyZe-&fdYyt~z&4OgBJb>im}t13nBJ+%?r{7m1TqwQLOOJI2F@=e$KY`MBtR(% zXUCzqF{nd0{^9L1nx&7XTvHEp>i%&2m%6s0w2!CGe^YzH@%upBJ-ZQ=J>mERM4dCz zh{~RD{2`(ir*3M5*%OXGLR9=xWqK5ukL@~bk2N#(*!6)I0nuT5PO47B6$>5)TcepWxWJdH4ojRJ388(k8`1)gye}zYK*pDz?%uRPox} zT(B1k_U?@o?7coxkQ!t~r+cMFifeNP-6Xdrwigt}!DIBA)W+KEtlVkr_tc2%3vpI^ z%8#_e&3^`))$Z~FT|Kg$HP54xapp+~R-^Bu82jquIlv(#B|^h2uChuYlt?>g1J300lyphs1wsdw+7KkeAjxtaRku~Ww>)^Zvu zwc_H)Igw6H&TO^MAthwH*Mvv_BZSUGUyj&=^dLkn3?{WVQyx&<5RVe4HMk5V2f z2g^j*n1z*`)|F(pzUQoKg0c+a?E}T82~&u^2$lq6Gn4gamLvut0xeWMC@bvlc@JxD ze7JZRp-E&u%w}tB@JE;h=g*QhW3r8$;g};0*RU4JwErcrr;^;S$@hM2)wAIFK*5Hs zmyH=|;7G)w7K|pac&vJMoLnM1qvGebw%cNyVvdi;UOld>-{$gZw}tFR9h>-cqRgie zlxQx4K9^2;?l@#SQDV?3k*z0qb&+$M$p)#>vKEJY0(dM|_t+^^{gLv-6cZY+l9xz7 zH1;f)r|b&P_UW#ey$HB{&+FcuSNl$(Nv*GjsnSh`Me}o@2lwK)nsVd_+#wu!p%2~> zUg&$hPu|!2xO3(*@s+B}yweH&E$*=Rv~#S_E)VgP<2xO$(dUcN$=yu-MyFi#^56UH zKY1*C)cH6hx3y?h2L0v0Kjv&P$2xXqm&i%(CbFM${oYHDh4;f}eR8xq@x|aQ{kBws z)>z-ho77z%={wPvoG1F8=x_b}G-So!9aFOUKM5>{;DLa|Xi3Dhy9_o~qHw zzUoZq9_&0Mbh#f?bh+bzt2#%beg-XV z3b)jW9ZJ}Lu))RZc%MA8;OILJ1f+?jnERK)U1E&VvWKyHK7^VktHqXN%&VMV) z?v^7OU@O*^-EYa2dqbXa64hRZEvX4k!CvbtIPu%6=4}A((^HC_%Xa-F;rUu=p08;5 zZeuk#H!C$k%Fglu$~c|uNIMt^I~dYtT}y(qYI+6ze#L8&Wabj*Ghp8;X4i#pIldyV zk(C$2o-L(~&-oz-IzI%dMpJ0qadnxkY$|ajk>bfqhx(!+-g;c?w?f(0c<-Y}-j=v+ znBAg6UsY&q-d&;#9SKo#;wrZ3OMc&7DJM!Litlz}PKr#hla? zIFsR*?T_^H=em|)lFGr{ZjxjFpXldPZj$8Z^Y&2@MQ`lMBjLY=UUZY!G&1YsQL&FRD|Ig?g9<4%G zuBx0b6(1JaerVo*O)k`Rx8c3*-dKWrF;T>O z0^Pq$_=fHW+(QTZ$bQQuxu#Nvobe2k``yX*Uz2*}+v=5Xv)kn0chwBKS~{nUjhNE^ z8&H!vLoT{iA^m3^S>VmzBij7!UwiiK@7O!rT7EH2cKM#(fQ-VwiK3PCi5Zy`q8xxLMW0A7 z`_IFF@yd7%fN*>&6XVy&Fqw<(obw&*9x7aiZ1Y>Kx3~((X;@UmG}W{T0XI|xa8Ypd zIRBwVvng`|W4owUJVFxv<{i~G$|McJ{Z0Z(UjmzeX-#aW)3H9Isd#00Dte~&LJ(gQ zr#B6(1XBua&7e`r2&>DIJqs)3hR2Lg%LSG?(6IS;_@5xF>kVf=jsMo=dP7TGuk{ zuFX>e+LXF@38m$bYw4ASqSmehs%Pcty~t-PZHKZ+X}K36EV>q|ot6qv+8#~G*MRui z#!{D`3{+|w)Oz$wao2>$;x|({*YD^sODaf;?0}-PUfPe1NRYbK)P0hn-3w=ll`D?^ z2-~d>qUt6ARQXsaIe^%C;Gp;H55mflaF1aQqcf|fQGnFA0ex}d2%%#dIF4b0NN`+OU+Yv8QDOA zhGBF$e_cm)IIT45n-Z8Dn$_E+Ek?P^v%ePu_cm~vJ*BU* z^tRC#uUnt|9HKgXf)XAvY#V`#$oHZZIbRk+f2q24DXL0~bsPCkMW)4Qou$(|cg?CC zQdKTpk*hM*%Mca0REMulS6@RFol7r+fNhqdue zJewC=>U6=~&oDv3zN*=qrGFZjZw%yW)s1o0613_TR?DF4-j{5$Fepr1#q{WpUZ>j~ z)&n#npxt3gKr@P(^QCI`deHk#o8w5|JV}F-6g#>-xc2M~H~l@h^I2iJ9P%IseDt|n};_{cvhEh26hKhi?#v>OgwEE#FU+#6xMSKG*Gnb(NR*ZJqR z`+VD#u~)R{=oybUFqI!^aO6a&Ovg*Bmo|20w_qZ}iO?SQp;unQ5E6$kNp~r8i@-y; zz<3I|cERB^X$-A8>qx7bGpyT8&_fH@KDk*UHMdo0Vu-^ycJP`-STEDORHRW<@5ag! zC-(C?QL$k5=zA}}%-#%#;%AQ@LNUB#5U|VEY#P5f#a#9-JLO9g zF?-1tnjpUj&crU8d-(&%9HdQrZJI%EXIH`5J)auOiBc;KV>p$~yP8C}g0|Ock5oMp zrq-?vH@||4e(k!`s4XpgOz7IiOq409SuLBi zaEVaw%=|^lR@anH{N*ntj#4x|XY_JvCmCfKroz5EoGa$r8#v{_nchH@zT$-rtVs8! z-}+dO>upgPH;GKqI%e;`xwzNHPsvl}zC;A7>x&oe$xE6Ff_n>P2R7qet5B}4QfQ{7 z!su1qDvIi>91z`BgYh&Xo(&sE%bPn3KZ9A1E?J12cX9MA@l0`R=cd~v#rJT`7A?e` zFx>E|n+)l4je8}iX_KfwiA>fsp=;gsOdL`($8zx+P(HRG00gm_YZy+~q+@w=(OFq5 zK!hs*rxIX8XPffHPAc?Uu`XyTLHX8mTO)6;!u^Puio@C;Ye{MH#?^31_0Uq%sD)^0 zU6h?Hzmu~-KB?Ru!&Mbn+!=7`U7SRrvs7?mT2=5=Sg7FM5nwq>!M)p(|8K?pdsOi6 zP0y>7=oY&tMyGTW+Pq6?j7%1ZAWJq= zn6y+*H)IWcF@#<$-X3M-jKusuvHV6~^1bK^?rl6Bt_}*W36%8T=`(>XUXG~T^sXE% zqA~=%E1tEj_8$k%KivA=@qyMSzd2{g4Xs_{7cDw=^ytys5Jv`vMj_zzaYLgQG~%e| zWF% zZ@JuG6x>@b+XN{%4af>xzw|o&tBRXiVU>;>^{!3&z1iQtis@+8TDhAQjv-fAu|`X- z%f7OXC0CkfVM!Hl!P$=ctu6J`%H7LyE}^KGG;CB-*SE4L8K*Sb*(Fr4OXxlcQ>-L0 zbBwvCXY~(Z8$Y-!8pX5t4l!B}BQSC=MOTC4dVNRE4 zs)Nv|kDxS3q6;xis*mKWa5wY${boMj?J1jlDIeEiaOtgT!R{M zDTBdyBB%16bwg{%vP0~TyopepD>=brZx2jEny;J{CG3o6O1jXO5TGBbofT|RQ;i)( zPNq{*2`_u0wX;IT+2t{AfK8~mL92E)kW^%x9!VMcx70{v+?4Q@HPvC^&3zBFcZ}~? zQT4df1*sh?g3pv~#n&1%=i=!M8 zp)=A{LhhTLwFtCIAzUOmBahGcJ} zA!E%n8?tKr8dbk)C56u$=W6&=A3V<##=eGyv!_!x>MZLWMTV#pDd#Uw;p0jg6x<1F0Dv_oG<`vKTx5ff1h9jMA%C(0D)~63@ zz9LO=g6&~}jnD=QtgU50dqQrcN(^+j$0L} z!2^4UKm7>(=2y%E^Z2GSH3oI%ys|YI+jPaEn_Ao?FgCe{qvBsjZwa%=QRRtDU1orQkWtvVKJ7mLI{=####kq852w} zCfa%^{> zqkA588_`va5P6abUf>DE=w9GBW|RLa8^5Nl3mm2~sR~*a9^?mvT?t(kk4*3de9%6Z z_GCSQ?Ew(Y(6B{ggN9+4bc}P-QRp(` zqABr|Pm*X!oOlc0YJCeM=g#inBr?a67qH*-GdK4y>#r*$Bj^74XGJ8hg^1;Ya=f;? z*y6JcirCFDgUZhuJz)Arj@Dc*nwHl7cQDxIX2=x~FSK}^{)%Dd(Gp6Hqn-{A=r%S! zyB^r4`mun#mN~grD}<(dKKP*q_R!Ez)UPu)BdIZj$8@3BwUjDEMo-%K{+Z(3tV4OB z+H5XYo@e#OuXNyk*jzh?M)k7To7&)9_rahO+1t9e?I zi>P=wu32vCYM3zwiZ|uUHAXi#z~m;iT%4U2Zzu;_?0g;?P`l)v89VSNACx!ZfK=~> zwO3a%acU$u4S7dYQ>Pyc%|m|4oz^d;du(uzqblQ; z#~M}+5ZDZT-}m%|5DGzki#7O?y&`PEzs+=Y;^gMH>jSLu?h2D07s6c3Z=ak#S@@|he9L{1WJ37rzrj(16066L*=V?jqaK2MdI_-%{rR_G7AYd!kCQ$%#Ki_y8X^d6$?(q*Oh5;m*3b(zX! z)<~|NwFJv?-3BvRc0s-ls&IhT;MNpIvzs~De<$m*m4%BaV$s`BJqQV-hP+#t)zb3P z*fHbj-2B4ql*6d8F@4uB!y4JwmP?1srq7I_v*u-?0$>%&kT4ZvQ~Hhvz{a?_0)P+- zfEX$OVH+_A0t!x6b=MZK_n^Ad>%2!;Up>V_T zbnlC)BO%RzzoTq8x{ir;=J>%F^q4-((g)B@G~5_}7&WUv!dkM@{<3T}QIPokbG*t{ zOKlt3TI$-Ox6)BDm#W+`F@{c>l7$LDEwz#D;7F0$4ILR>1;C2t9-Jvzr~vQ_s7pZ7 zMdv)?f(;5N_}FR!I}|x8&|%b=j1FVRJ&O)YT`LbcsawVZ5?%y)4jrnAP{1-Np$~4! zsd0r#z|w|sD^zavmn*nYRWq(E36@?m{~4C)cC+j-BULi)m4+M%g(i+AVmb+w{VzmS z@$uH2AvOc}G(Md3tOYTYQSb2)h+1vB4)jexlB~^9#RsD*i%OF}(v;&P{CuJC^oemz z3l6Hve>?a!I;C@k@lxpnSB3_UH5f|n}vM9 z*F|peBEe2f`+bOv`xSCLIiuSP$#jPMT@`Y+bV5dfgq+|hc|z6g7*;Ftp>530 zZNhb>Pb~cN@y4OWB74s3661@-hx$AzUP<`uD(%sg#+$g+R}Ep;PKDAYL+oi>p~JIw z+Vt=+J-Z17Kc)8D?Jh(RDTlbk^WN@u<`y?kMlY zS)!xKK@MD)RZ1Rt_3hS~{8^{txIE*|fzj9|0Z*>CTjtjFvB$m4;tfg|=>ip!`NL0b zL)UU#tT?vRF~#2hY8y9n?Z^3mbsr8&!OIfXR-bVBv)UuBa{^eYw%n-A#YQZBXOAu2 z<>hg7Q(GZ&ZOFso`b1I;KX7A`wr>EU2WQ8O(Vww)4td&aL7jbyI_cRUU4p#a9Y_u* zxtFC)TGRr(oC*qP`8sE(-2?)u3mZb4o;{)y%hThuAWV%uyEJDrLQZ4ila1VxIU|(!DA?{izJ9eZX;HGMh8$ z+||feiL-FEm_=kw7jnEx-IbxXx9SkvwE19Ql&!*PqpOaQc(+qGtuJwxl{4$OG70b* z0&qLjH&Iu0PMnnVW>s)jwH$hC*U5AEb0_(l8AdVo3t%)5D^n?Ms<3^iJL&Cpw0KCQ zc`!*h+b}o?DV$%HLmhCs=M=N02+%LRa8Wa#jmfLkvjAEYT(X#C=;|5wr;$Hh?R`m^!fnmta0=y7x@CY1iZn7SZ~p z5397}7W!cPY_v(oS^LQXwnN5!ui7hIys^p3>Gl1^(tCvfVuqy~rrp<3JcofaeXud^aoZ2F3LoVmR432&AqfHtWYNM~NnSXj6=u%E`zmInwdt*mjomDO{$6OR0VRQH+@dJ7 zHvO?WkeQP=dMpGkjlo^6tl-+o%+87o%cWKpS1>tS!GlvvwkEh%thS5C6da6H0*<{k*7vL7^kj?&7CgB_l^v<>DyAY=e zZp1qll?x@s>d!WFK!}X zu>u9i#EIxEY;`+L!+Z8ZdRg~}{P_?WrPJ9RlQptirtfHBqM5diKOZ93F}G22C~u+^ zFw=H1HdhV`Ug3jR2*YZ6rZSiK`w|uJdm8i5;1u*^qUp+Bc_kpB#KZ{In1wuilv?dTVWh~397H&}W9pSpGEwNH2J5J9D^-|IW5 zTU$pD;q>ljcI)S+sdj4)k@;?&)g$ZHZ6)9aDMy6k12VXVa;f zv8DiL%9Pl%XD%Swf`vpZ;s~l+!R1W;2)BpCdAyZw=1TQeJJ_9tuCUM*g<`p^uIR%H zfGJF|mL)ptt1()vcqWGf&}`>3sejTdmMSjj4{q3GY|6#{YESWkh5qtC^=a&$vo^bg zxotjU{_WNLS-pvSfGfHOm{n^RtHEvf6ForQuPe}k8q))?E4aqk8h8vG7tkh!TUqHN z!^8B{t#)v;U6cN*Rr<5e0`y3w8bD$QO^`NO186FnWg@|Xk{*g!u&}fmeDrvAwXv+l z^e4S-#Y_+(CQPGwroY0US6*e9F6_kB{W{=Qyvd)HtMIB&izv$s1ANh68k7}k z#W!_I;0JK>H+AzyVI2%3r$M%Y19xZwYLi#Z+k@-u6y`>zQU+dHJt-0yi)Rw*rr{Sr z8tc`YX$^Lup{g~frVIX&SU?+vw#6G^C*YazsM^XA*m_Gk10rzIY_|^RzL&TUKf<|N zvR_!=9<@}dbT?RYMt#jv3)RF2fkZ3+OSfA1BuF&H>oe3dR=@u#+7WJPP)#alNHV6X z6uWIX+UP~Byu0iTB^!CEyP}%dos%fzY%gvdX;C3dX4-<2*EHb9l~aOXnu}89bKGW{ z9xiiJbUfal@Z6kU*$Yy- z+hbQsWY7cTY1CkvfT7=-F&oe9C!%}cw?1{+ACTY(s8q5X%Abjp*fHk?iptLED`;6S znycOo#VnBlNS9iEu^?z)?Hr0sw_2RdKix@h!cFnW9J*noGkQe2%qC$|97-(gWM4$9>Glbw)xEHYv&GU{+Wc(s zL3PxW(p8q}kQPUWpq@AYtpsDLY$gV-Z=5IHYRSelaK;P~$|^tRZNxp_wDJcIm2R_? zEe$MKW6G8pjcd6qF7wY>P~&GSF#JlX3gxYPBOjfm*#xa^#psvDi=!-^T)UvYq#G@V z;tlOB#LIPtI7js1uN9#k4s{4GW|~6MFw|G+ycJa_m-=TE+NE<_%*#Fe=`l7aSlC_M zP@>v;8m^@@rC~Jcy1DO%eFqZ)+s8F{ROC}TeG|(sRGc-WwO)rcy503Vi3B1tX{RVH z7h$o-uSqk{dDAn-HjL{|t}d*-yZERXL4~X z>%_=P#%7Do*d_q3MS9*Swt@T%%} z?bdkhflT%SrAnw`ZQ1M~Mpaxfx&};|Awl!&ZLI9rAD7`WvKVW!&d_QFFF!facio2i2X8GC@*pi-inq?xm) zP*+21w$TyB&!vvZ_A&(dZ|IisuRZAWQd??ASV8bC2xg>~sqqMpmW&3g54sMp@zO+zOS}vW_48e}=VmJ90`7@(e9NQ<7YBhG` z)HuiY>bQ4+35repX_<4zjH+{HT|?0)nAsac4Ol49=$5--AcNmTRh#^^?TXI$bjWA? zW_YswZ8u!eVcnbMHhUnVSNrIoHS)Fae*>HvMrlJLO8Vnzj`0)x(3tQ&Jm2$*%sh}t zjGAd+JeXTXL`X7r`HWcw7(5z2ca0(X;^_sAR>BNiytni2uMWPMmx}oeH6={|_yp~V z100Up%E<6@5jc9E?@XwE(up=)Z7C;Jpq)+jde~}gEAU#glgl3CYOE>G<{>#+UMTL> zg@K%N4Sop-rAlf0+e{;d>M(N;v+F2ZD9QF(0Hs6nBu#NRB*R@A`ge(C>@|RGO zFAMA@kV2vYMj&0mcIyx4(kcs-Bnp#>E{A}lkANW5*zeO z=l-vn+Dx(Pk*p2wazhmy>+4h7ZDk4uL;A`hK+xSKLd?V2SlYhI?@VOCfzsrmXu~24 z?)1UxIz@vLrH@cEyS^qr;R-ibu+E_1h?Nf(7ewx@VWl>AdZFIe%O^FFO~F72q7i~Y zK7|n^Co%?%%!o$8q3Ep9j3l-cQtV(BV&^?gB=>THH9;&<#b)4<7HiDQ5ETrqTq2tX zWHkm)puSzMEitv0f689Ty1RZaRvGOQ1uMhM{!P#v&69c+&e`PXJmw2ge=8yJm%t?Wn@2ok@R_sy1})Z zw@p{No)xvzcPxXokjlUeki^_XBk*`gE}nw$IAF+3qi8M-^;eOnM=h+vz^|~kWf-LE zEzI;YtqbWop-~DUqE!GY=(`I-F^0MS6VjU4WWzwML^p3S#yiVA?uwEa)dx=NA^}VUeWU^ual7ShgB;#I}7U=cm(0Ta>a(>Vs zAOZ^SC9Vb4SD^UPBu0x)LuAzV)-`xl2czF!q;O4Maic$Q3<+cR`5E%Q>f2Nybq2LN@mg}clIc@&GaiZq*(rsJCK*N+(rGB9ir zld~mq>|@Qz57_UTslPK}CBF78R(qQus`He@ju^qc0(NdUOjpW9?18K5ddB9Ppf~kg z919CkY7wU;rJtM07P~rO>2&&pp9iYJ%mE4xV_d8wpTn#XZ4a0l8y3ZQA_T3t8#kFh zlP6Ou=minusi`aXjFD>^0Ujf2nkFmIrdcmBC>=M^1i3x8XlN82n_BssjmUtm_fCropQ-0Ql{yC3UZVjnldY%Q;>IMX53RurPs7#6+wvt&5DRIjg-S

~FT73uowSd^9*+YI?2*RVpitrZ!SOq)3f zEuZp5FnLjnawf4+_T;Y81+)ycn6BHWWBwu?uM8`l&0m$nl&J}oUU?MfurS2TZBx7t z2KktR*(P&l=*Mal(%Jt+EijJijngDT@1Hya&kT_d&#c*aW>>d1jui19VQ#VL3`}$c za3+Wf95tOhooY{ytuY7B90Nzxp5h;BkMIvYxEvt{fwTKO1rCBtw#z#O4$myT9qYm2 z+ryoA`1gBoqF0c3(v?<8$uq5DS~J%1XQwX0&lALW+$)w+f*w4KXJDuC2ZoL?%+U#^ zMNEMhc{@~+&zr8d9K%RA>h%cEX2kRZi!rv$u9j;@JB5%%!Z)~%Hdc|B#Vy$wI$b-R zj$<6j>WW+TX6%2*EZUY76O+}tjj^Jj=Fsxyb`9%;{xr=cZ_X$8J;G8)%v6Z=*?PyM*i(=Hmw7w#!XEVCu2svza zj}r)LJ4~2-*KD`mC}Eq<$R2!`Tc-8PvpS+L+YIytiQd*^7cvVHp7xn^yqSW8XVFqT zO9d&&oDrwA-D+U3erb*%ZNGjWUA!jJbH`Dr01F zz9dPxl?A3}tIVM6X_d8&W)K!w;VXuZ)TwRkuu@uOG9kLcw)zVk{W)ZxJBaKd_47$? z++c1MQxz04u^~~dp0(4&YPyidYBVv(Hz5o`otxHJYXHiGjcB{AxiP(Jbu{!%_4f)e z={2vuW#3Rw&nVJcmR2G|qwbX*_6xYC&%`xb527!4J(CPmXX8TMux&hlCd|y}kbZ4I zbV#ISGJmE3B<(}T+GK- zqk^*)9Fp)1D@_N(D^fI%`X&CnvOs*v|FQ&2U1ctfgFTk->oV@lB3VSY(k>hr>QM^c zI63G`TxAZNdY()hL(l24f^~3-vu7-;N5cX}PtsQPpn~&x6&3oh$&HmNfwEx8so*%S zl|@wU_Q75#P@vi&{z7K!Agv(E33L`HJx@WONMl)WEp*ezN=0Gt0x;7!3IycN3Ep`S zetnZw>CY_Q&QbBg3&lWO6{da4B`%d#!~a64rq40sXpM0ldZ3;-8|SDIq7(EmZK_e` zGP9bpNWCFtXTl%`fHo;-Cvr2CYcFoIG9q0=MjHrItCY;L+9sbAuVZpjVyu;Q|B+C8 zq{KhC&D)WI*0+Ec=?A|)da7KSZT?oYtbq__aR%_Sz+={50ODVeG5@P7gE31PU9QJ(`r%p*s2&fh zx|R+AY{Gk$2DQ9QfeR_ni$fuW?IL}ZnQ3N4OMY9`%OBpPkE1q=w1qyaY`4&?u-?+p zw53r1Ix(5g?Zq?oclPNbAF5;xJkpcDs>D#Wv7Vru=2_HYmelMt*=(Igd1D2^E8g-f zA*-M;8-m|~w8(OE}^6c%)gQVnwePNb=obr!b1*WS&a+;8&AdWUk1vM>*Rw6(!yEu|lOa(*{ zR{T0k>nkO-Ux>7OP3n?0&ee_OPFpv9>7bi!$4TM!W_E}?WD|dUQ-{z0QELq!guH3{ z|E9^=n3ru0w^*N!<;F&`b{^xq`o!mC( zm7K23*$p<5<7#eN=z3YzIU3TKA?JI>-c@`8tv?}G-piB z*5?u&s(74~#p0!05 z+wF!cmVQQFy-QLviPwOtDaZ>eZuLE``)~C_;9Clo?MLI|I+?B-AsWtF?~8HLzfTDLd@J=10vjb4(amipyrmqs8+)6h^Yo zi?^aQk;CR-@gMk5Lxz=>(J~~^n(CwNSkp{-7TrSvvve|Tw5DIi&RE+m ziz~HBP=l7RvNI_nWVPGkO(0cP1_W8V-FGLdMpJSVeuj))A+NNY{3Y#T(s~ccJ=TVL zY!A;hsAQuJBpy(46U5cCE)>XXg0W3HEFA?w^U;|q+Z_c$w)C@%#9g;I$#ZCSj8EJq zq~e*qN5TH4E&oh3ghjaamuZBTyMdH##x5rq%R{&h5@X1f&a@ojYIYuD&Vmq?c38w5 z&8zd5Yvp6gKp!gef&eqd)ZSUO<&EtKA31;;Y4S(LrMG+aW-a4u+! ztHP`{zITO7J`|dc`9hU5R;m+Ct=ecBH-|rS=Hs0o1nh6LU-(UNuZ|<`P0w+Yn>&|Y zmG5f$NgcjV>UPv6?>4#}b%*3VRQGr5XxYD8cdSl#1{|xqLa6ExWgH1hz9)IMKFZLj zXfW`S88%*xQaNMqMGh-6icXt21Q&BZ727oV zrQYXf&M?su+8VQvuCz)|Rz)Wtr%KD*@#2M&ycbGWxou*Z+mi0p?U(LQdOTJ5@$_Pv z{D3#4(<|n`l5VQQZ_FpqQh8-y!A#`(mmi61(lN3Epng5-5A6-Uq$~nj6tkt z+?e%VcDKh6IzM$Aiq{ozU2EA+7N9rfyQ$YJJ9)kGiI+R_u%M2-t}q@BGTy+zWj7Rm zOEbuC0S%5ufC20>fIh%rb{R|ysD+6y1IxW71{Mx%V7nt&0t{?-1WSN{?T%ngyHkZ6 zK-$Z4)cZBoECv~VZS{W5!&?kIY8v0TtLD#;nxHO(%97K&AJNM;@HntSwiN%C==8UW z*e@(GSPB(N`WpFSU&}yg#X06j{Q1$V_X^*4R}3MRT-qr-wNv&+!hw?QP>Y6xJx*8)ZW}ceONg z(`RMQS+lVr^`WmUi=mWiQVCB<83Ou~w%e3swXsLuX3^%IEU!5smL($D6iYU)fm;QT z@a+Q7aT6QYhF31lKY2<%cFMHc*lF{I#?)&&bZarAU;#k$=7h1pP(PFJ*U-z?^m?Rv zH>%Iu0ohKZop9EQ7i&A&w&DUB&8XF1fMU9-jiIw!-Y(1QJNs5Wc-v*!zqPZA^^9CY z>l!X}XW_Ec{@OlnpFS*Ner-7rf!zZA}@5~X8t;99dGv^9e%?+UjP=8H$nH|gzw`yM9e3UX8ylAZxu-75Cr(oTb8 zJHk!LYIaop)7{I#YWYVB_~@@|g#Gp6J|KBfRtGES26HTDyT(bo_OsvKW|Kf)}*HVGT*l}db7B-fYnxzA_zYrEe=sZj!F%{J> zk?EHfPz%E>~g)v`5o z0gzQmklqs)3Xa;(q?^e4ZgfZs{Z`2fnSJOMf1nw6PQ z$DCp*i;Pq@^k;-opY~XomO&jfFO-*6UkEKgah^k7TbS0tNyn5FnVS~Ml4*0C%%-~e zv6WX#g4Ee0+XxXG?TmAcQrYG)-*OTn1h&c2OHN6$&B2!G_}DLoq2nNKMg^TYQH&qmP2w--{D%>MUE0PE-AT%tWwe zAU6=5!XS)%seHAYx+G~M5E-3I)A@xVX`Od=75fk@44S7x1e=dzV!wpc%YkEOQ|cf^ zPK@n#W6@K%sk7+}4cv#GJH{6QaSG72=}1{BMzx`uEMr_F+kw_Mq9mkP1J0&_h0!L@6oJsmhA*8SL+a*FamOo()8=6j~W?;Gib5e}xWU`@D_g)9P>QHY3*@ocpjZ1(4 zxtaQMc7*u&;#)Q8mO0&%L0BixyFZqVSO{VjusqO*dx)kFS*W3GVXeETdbJA zuegRVNd}PYqxQJ3irWS=>k!Rmwwv+Gl=sVK-6i$V>tASr^+j=Cytd6IXJ70XP0q7T zMd06{4T(a@##t<-F`0~L4G^>eOBF?Bzkq@9%3+j?X)_jZQ*ce0>ihLnAs^HGL1ey= z(=%9b9cCw_^2f}eJ$ zW94ciB-b{%iiApZsFV&prRHYNmzy&+oo-9=$aGatTwj@j`pWBhOKO=rklqsPTj`h5 z7Jiv-lO%qk?yNrB>MwELVVS$svI#}IFDO^htl_xqO6T?NmiG(B{`6of9pgciUwEIS zkEQ5)T=zFBrQRn6x2@$;IFn}p1CT$*i0CivD)HG<+N;mr(!NsN>cZ^rP7C^@YDM$4 z5BZZ){ryiZk1Bksbh@PPMJ{&KcVl@|*}~J)n#|nh%9e`0TPnNkd$n@izSk>Xs2kp^ zte2Ylbp089Zr0!CL+OLZoa|C^LsfP%bN?c>h_&i&S}t}EB<3v z2v4e2%SNzmzS={%cBbIh0Q74Y{OB}1exY{2s}1!Or{|w>b`Nkvu}$UDfnVX!ZId9r zdPRNtv*LaAx(9BH`oz}q5q(aScS>cvEB#!bYv~rWb#80rdOe*lLJlB}mo$}n?-pF! z%b>7;WtfR?`5I+)8Y`N=ddx#MT$RpI)obbVF4#Zx|CKP%Ki&-nsczMvJ# zcMK_4-_LZggzuf=W-E8I+vY&{6ZbqcE*d%)%a_X}`@D<-mb-eNgOo4`MaxoeQIE|t z)=r$jAkv&(6@ibVHn~2c9>*prJ15rW*}9~Yb;%}MnA?~O@C&3aw32$%D&woUPMP5# zChF7~{4dv5O;S(H`BfhU61k{G+nt?nJW@ic^1`|dL`Y_{${|}tddOLcrb^J9(kgSC zO?nqSn@3_HwnA-T`fSmG4OU&Pq|ywPqs0U&w#w93XobQ~y^8V|Agn{pnGMAK#q{xi zKT4N6y#HdYG)Q{CUS0XGC9VegvLJ&bZrBO+`x9KtVl`!V@TTFKRK|Rro%M^oypWzT z5H?Y2BS^N|o$k$EIeXXPT(`lKgBY%%>W2Q#g^}Cx^T$)6 z!{Ah@U@Mzx5Mi3^66j^qS#!_|m8B%4dnvaUs^(ixb^Nl9@o?b=@D zDjWP7-Hf-)s5~SgAOznyc>1~J6zk%hEu;$D*%Vjh2k!aKnHh0p>#q=NrYGY8G2R`a3NjA(p5OetJGM?uPJbTk#I{I(pgKPQ&bofPB$5qjMI8y%UUe}53xpt z??8p`NRrD$lMriEFp*8Mo(fgSMukiY%u~Ua{4^D&)=(i!HHZqNs-Z%b?wM2|b)dq* zYJbw<+}d9{>R+h01x+AaZ~~Q{AoJTf^JwOI_E3{oedjWUTtVf>2D8a|rX^L{j9#?7 zhyNmT`HNg)u~NsA(LiXxM~eFtX5{u02Io%%!KhYwAKd)G>dG>l|AlA$uj6dCid1Id zY^lnge*9dytr{6`LcHUaTx!&23w&v(Gz)ZAnW<#~O`pkzy!L}zUZ(OdXH$n1VZTJk zFQL+kWEh;2*V;ivIlGnfHLrb>GVGTKA!jBc56;Px?#9MnW~w76Htj-`Z6|UrR?fKW zNbg(KG{8rVS(9&7O+ZhTddcLQ~ucTlsn$P9OjYEQY_{&0Lmf7Vx@@t1R*{! zklZB)WC!W|c(R>ysTf{*0~)`v(kL5AVTCS=Vj@`hmDmY&YKMMw>SOk?e{-0U8S3oRip4@^5VRv2?oMUNp`%CM2 zErTy6tP=7S4HLrc0P8hZ(fQLR$o87sS47feUFKNzEaeY7*_h8Y07BqZ!YP%3x{W0`?ehxkC7;u&pIA5l-k)SCsz2Os17cs*i_-=7ExsyT~E z<=~ydunj_qo*q0l5~7<_#IyrkFAN z^qK*aHcCf1UB?e|vrXD)<507%juPqc2XY^W;j7D=G!&Ce)z!!P+peu_;j$F%WEc$3 zNK{^j(i@YHdqwZE>ZPl!Kr{BmBsNyrtIP)mF$J~@+}LhNnAtb2^o%}94+bzjJd0f& zoPbN)|E2FGXv*7Z^7amOt&RyeCv2*HaKxuHv8lt;ucMRMq;r#hqNTbB^a-!o!s=Qy zvbZ4La5(`c%Qg6h{X*$2B2!B{P1kWrMnOtOPl{85mX0Cia;02u()KO!kIPcez2>eZ zHxtEtsf>|hq;FZ(u!~-fc7;bu`0hr}7`n88zF{dg6SUH8OZM9LKyp#vfMLM%s3mOB zlS97(gK22wdR}ui%JgTsJH>8bj68#7VT?Y9jibu5E-$9<0W}KQMxDPnMPhj@p*`nE zi9&6am1x%??JL&tg7CXiZ}#!NOXeAn{!^T`vYx~vhw8>2><4=J1kG`^5@BwV!fDP) zE$2^`&xGg6&y+7J;9~h!2)I?gE$RMtc^fNz0}*oDal36uet{<_F6^6a(}_bbLk4wT z$ir5UYu5GxlECCQ>b9@!FaF?V?!7%#&fI4xIeH2uD*yan0BYUf&A7$S{w^kCMYM~r z*-;fw&#mehTOm=heLgy38Wl2MOM))(6k4zO?v%Tr>F0twgw|`mJ5oMnUm+y_Ehs=P zkJGnlDLp=CLQ8&O-!F=^4rEKlGBm=@%bdTxv_PE0;=rBcTV4tC`ihc^VAco(!Ko>cob+wSwGGL8B zFF4T0EA*FSMHsKjP*)kxEZ~t5?GcX&!BeV46WR-MbfUewGSD930B&5eeW9Cnkn{_w z?iGE*Op_&`;!42B640`h+TNC%nVy5Dzv9H+i0XC^i;vLLeO2JGD0MRiRYv_Y@Xj9h zs3iP*4F6&`jjeu$uGsn+!Pd`uvij85ViVfqIhfQCObz27t;xFE8UJ`qwTl_))JB$2 zWt$^*1@1Yt0!#IOnyCsbAdt`OPk2jezMH)ho;IH=fU)`F+n->T$aja^tFN)`kZ0JC z?eqH+Zs@bkuP5y8?TsNghfBR&gw|%atpHE>z(L~t$6x1!2D6n*oQaaOC0=CSw<7hf`-TA4T z8{Q(jIcRNBlgoB4$HA$_eV>;5{w!Rxlpo1z?gw~2u-utsMQwa(V;Kr&EWxsptljSW zmM}A949RRQ-H@zZ=^AcQwUxf?2&AGbmnuYak*}gdET8l(tCQFskG8U*Wpa@=X)I0p zW~ef9@uF-YoNi$e9_+;T+MPptv4fLrt6zvUL;C~XP{P8q7&|Ao9Im(AqC-_eHe_Dc zXyKU}CB~={js6ZPl@@^7r<#PrPX6?Ii*!mYt*UdYlIPh)HF?F7SLj_*EsgQFQYksz zx>&hDJ>RVM0m&pMtm@WNw4U}?C9K1>?!%mvO<3KK zq;&ZX;UV%ETJ>zyckp~i>5Pb#9?E3R&B(7T!&!lQXYMSK#blLA-^$@h8v1i%0HK(c z^zjAL5NGJ(NI$eZwyu^UnmnzHPRQpyV_(Mea*ugJzL3TE;w<{vEXC$4=RumiW7KV% zT1Dxy&Yl&`5mPr(=@67!O^Kp()gI%ad9_;uJk>QY?(88)@kOBb9Pwt3p~| zmiuLL#eS0>w@RBTS0kkXC6kD&qI%NDS4T>Z9)D>er!fXIQPpe=wHWBMMoCFw0@HlD zT8$+}!+nh|J6AX8khK-=_i-u7I4^QiC^WtPZ=<%*{WHvuOF2;b zMCNBFjH4-|#*GzdhyE5qEZ80oP4Fy?N zV_}cP+7Q_SB9)-x$W#i43_FgIxl!5n1t?B^pVoih1_9frHmEa>kk!oRwV7%P?Q8}x z;5yZWQd^7v8twXPD~Mb1F0Oaq$Mrt&tSTA2G{Rvf%Qk1I)zs-U`SkZ`HRXvFROwlc z#eT1bN^+~zVmIx5YjsPnDp%Klmg|z$)h6VolHRcy)~3PJK91Utn=I$#scMX+axPt# zYser#nq7K}Z#Tb@*H+VRDn<9ecDdn71ufW!i0ua2KHd=6t+yg~^IWcnwx_g(wV~qm ztCB`O?bL7y?I?)HeQ22Jn&_z>Ljm(p;VgBVJRtlA$m^3sai43LTu;tR)l=8dpf!Qt zJI`zE3#u~QaE$LE<|aFC%cGW?)D^Gi1#X)tVt~Xk}XQFB&W0(l?7!I8zMk4 z%8Z(&I?dZ`3-Hanz*Jf1Ql1C=9w*3(urMO;ChJRl4LAJ>**mnDoil9Sr}M&Ug+vHNI~db;+nn>%rS&LO(KP*Kqn zl7*f$=~otS;)=IKGm3>^o4FMnWW-SMr&23VnCGjha|)D@ZypHG<7j6OM?3qZmFY`v zpfz=0ly2#BtMsTuibthAOu~kS{)D`C-Qg|u8lSGq(p5WAE~#v{hc&yk1Dttpeu>v~ zQ+K#@tVHOs(uopG$3SXwQ6^XTF)h3f6Y`}@JvXZD9Adv##8nwevQbpp#HJ6KOz8Wj zRADnmMyECh2^e}CO^M?Ud6xcl68watA4}Y&BF0Ti z3V(O-1whIcb`Qq-c|{?t1oX*%p#s+ScHXEL>hib}fHxG`iPPDm&;2{OK2OMCt-c0^ zWyhW1XT79~D(Vc&r1TElJ6TnFkI$;rybaVf9@py6N(zZ2h%_cO&kHFvpO6}trLN?( z>p}!e=h8ckJ~f|^8kePR^w+MFF5}P{P8p?J+o)X|)=REu71dp}8t>{pam~J>Y;Q19 zwHJa}R;aDwOl+P&1ux#Q-;Je+7)raY4u3;^MSzwXAca3lzERgWiKQNW_;l$UeRO3` zT2ze!$Y!NSuEe@%s+?0-;S{tUpkaSQ&<5dE?fh9*Gi7JH4G9>Q+sOgj|A}KYjqbEK zQ?$y+&v34z-0fBQp-q~4R>vxK^wt>rt(dq&jQ?6vE~tdZ>0 zhL(}}1$d8vF$tsH3l~U6Ttnkcc`2x}loXR|C*A*;0w(;K1x(Bru-=kCw*U;PvV}0n z`9|iGaS|+|?1nYx#ZsqDR#lzTK?i4?)Ml`Bl!Yhc zN&F%f7k5KYkjJFW;@RDm0%J9q;X;L3z|4yQ;%YgaKvr#%DT4QsG(j|biM6naAyb=M z$?W)+7G99A=dV%TU$c{aC^GWDAgL-Hted;by4>q)yl2e^cs>Zn0rPnPZdVy86Qiid zj@&5|9x`=@Obn?ovkC375GxRX8b_dR2GV;9w}{xH?8sEp*_ zE=Etlz>VplE{fozjA2Al#H59ky>L;z&#eJ#$v8yi?{%pCE2O4O2gvjpwz8NptE3k) zxh!lkijLB1W{|nBmR1kLboW()UR_jL%Y?P4$6mhMRNMsW#OZ<0(rUK$x9arZ;==uB zwZ(?yZ>mH5&18pG=sS`DEp=&@f#eYZP>F5cf087|Y0;TL;tHnGHr>^NDokBR$3ZHE1Td~Jh9)1Qkc@%5 zWp4rYtzUPm4^Wd|UtP@)u3Qnr}W=(GNmHm*tV{!%?4gE}WDp8~lw7 zU1ac{pZo@%-#Ah+pGPE|x}7x%%<#DO zrn&b?79oqxBBYK8er{g zbP!p0g*#X}TmqlNkWAiv!tyn)km0HryqoH{u;(>@VbAsz9*G*v+<;2t=7eN-!e=)m z8nU+d!;aFZ5ruZn4H}iY-8L1vltK@bP*WVBFq-9%s=eG=CyW+%K?LW0lJsV(j{MwK zs%bJjC`V|pE{@xie+k$eNbns1o5s*!dZQztqy7G`wSxV;bfd(1OHd>%;uE9ZTz3_TeV9+86 z%o2A&U^?B`>HRcJv4LZ#wm|BbR9fqAcWH(mKS3 zK5m#YPADxT7JyWZrrl81&7wOXvu1*7APma_J+sQl;5K5g15&4S8m`CfsXHV4$1`=; zbaT|Ty4&*I23W@GDdecTCJUcy?z${huDcuZ-Edzxt)0~js+RpH@kx$`QI(7Q8>(*D z@TV`djTzt9t|McAEW?vOcAp8%XXF>3|3Zi?@ntS4q+tn7#XhrWOZEdUApub(7m9rC z6a%GQ7BCd`0*3wB7w#5b>q=a?b<(<_-3D_~_3SRxN18!bQ3rCG>Qj{n#DqauS$wb6 z-8F`Bx9+zjXa5#Q+v*uDv&YmwG6f5Hs&u_u`dZ!f>(WKT%(nx4UjAqqKClt>Cg8~`zu>*P99d^5@vK#X=aSKuhE(5 z=9U=9@}-*x&h5e2_6ZOdT6h@DwWiIMf!|tXYHY5Ui??S5AcSiDqgg*>Qni&)_geBo zam;A0kTHZxeNM@B?-Y>90N*|#It!C)>r~(*2;HM4CkX`6C5Qn3H~N+w4TOXJ;7NbLneLc*&zxD8L5M1?IJ73;JBHPgK%CL z;L5QfVI|?ybdyGzPx;I~aIpo-3PnG(#{Wim{2LNtgkxbA{wUdBB7A>Ic0&s(V~57U z4vLV?R+Oc(^aZ5&2PF-l2c^yAm`{!yW%+NEzZU2Fy1bDs@A+%1m3EAC5G}< z<)O|NT&cfRZ+xAYhn1}Yf2)3jz(?-lw$|^cuiHMKhxeFdcGT~djrs0+AosW}4M4VH z57uAtaNPZdEkpcFv1`cbAr>2o7D`vOThqxd%PCD^r;^iQsdzfUzL;4nxuPC-MW#|- z6J>dAdM59e5=p+aL-?5c4k+n>bm<)Nhz%yoW4(WYQ zcvw@P_5w*NPuQYk306iOge zcN;FWkczg?*`%}<>{SqcRl7tc52DaT1-q`+E&~f~Y4^|E;-5L!zPXt8{LC%Exdmbb zcO+?HmW-cfZI)oHXy3)4rXDfm{`5B~?#-(x54{PNd-Fq(+^vL53n!jteK}6763|J1 zqW1kH*~unYr`yS98QxuX+?{O^w<8!k?PIF0h07Ng=!H_JxprbvG>J zM%@7|hq7*A#n2(UpkaR*^!m#NmZj8=@&V1z{GLXPZrDwC(7}65L_H>SDUV4{#6%&6 z31_Z7CWLrQ7||XRzp8(_ga=x5Jg^d$#S++3_9ZNfB`Cy7SQbkl#FwxvmLQ9RAl*Vz zp^U(0B$MDKLKQ-mr>hEi4xl25ec(vxLaF?B+=TBS36<_=!S_oKN@?fMTo>KsL1}}N zTU};@+v-B{eaLSSiZ0cR?ytGovbI+VRd)jEJDG+09|-y$BfI8-E$Qwwnak}E=_7rW zbW?dNJRaA7?9YA81xYmH29#Es#CFin=*T-0HmAGY=duGP^qO|Mm?o016#7+ijWr#i z)RIs`5ARmZf2`OHOJeCo#O^TL;Dy)*V~o#bkLC5ydZAliw*g_$ZKzYPUFchK-9IeE zmR#st(n9ueo2$|ssynPKhwVDoh3+C0))X&;uMDmL1CMOD6!(i?Rl9Yl4f>&_vU%eB6;FN)@_Fq^?R8$)?%fWjD2 zV3(WCx{;+Qt5`3294>MXil414sr?B;9-B`~-TLBYC1r4Imdb1?Dl^MVz+t`KwUkBd z7d}PEYdUnwM$MyH%Fk4u9=yXK3F4L47(dHZ}L zOKVx~3%*S^9s@77Qeo|m37RkrXuuM_c$#+^UizcsTIjCp{ zu45MPsOu);EOf`~P6r-!x{gaL5TD{NXs#)_2eb?lY-vkzS8RirFn*=|>UIrbi^wuS zLKO|}p=1KCr+Zn+xxKz%0#0lF#cpriR`EsxwsL)jXMGX0eOe=qbOaC7XTLJEThwzW~Qg^H5N|!XJzMaIN_m^rMKEmW{I_ zcrUP0RX4uuzBIqk!Oyq>8gK%Pqb#2*$a&j)G+<6@sov%8Qjsjs?~W>0#&y)?tMyn3 z3MVLIC7Ff)O7OpH-@B4$Uvrzi`s;Mv=Ww=_?sIiLPah3tZ(kE@DA41C_c+_8+6bMv zk{OXp-#r}mqKbQIDS0o@MEY9Q5IDFcTP0kMGQ-U>Hg;I@{wl@eC@ z{Uu$UgJ0xfxiiG_0!5I5Th8c?P&p|K%!lGHkBXNi#a`3;XbE$t>0IjPEgVI%ZL{n%h?HObSb2 zxqH1-ihU$@kh!&hCA7O)&EnUR!5H^)4<=CeafqZu4@Q4^%}+oc^rqq-f!zbxOkB{7 zIUKnBW%WcIK2aCcPj5{cC<^xLAZj{i5L){@TK{P~n}3@=Rwc9*9%z+y+nThR$Dqv=PAXv#f+EO*Zu;X<$pxBJ7uW``aNxjcl8Di0 z-0FYEb+U}8aL=mfv)ZXyLc^TZ=d89sU&Ds%xVX#lcsz2CSjV37G0kJg%IC_qEqzWL zr5pXoRqwx6zApcD^d%O*G2NDy)}bWcmi_}D@(FRFl^ zuH1*J=ZB1?E{6D);_&wh+n1v_w0$1ASWDaKspU`^Vs{#`#o0Hqa#mhdP+wI|-wW<5 zH{{)1{s-=NVWqi%J>@f^s8JtC5D)>b<~P`16Io!*3~84_Qy6!rdtBP+O7GIuH@g9; zy#~~w<=^f0$gcyN=0EIyU;f_*Rr6nPx8=X>=-^8Kz^#{hYP~wR{F};~<=?ChF8@IJ zcjf=x@*eL$sJ#(Rf~pml(u!B*yC&rprfW16fodpxY9<7@Fi}}!xHtPG`S!sE>paax zX)Y`CVsI9=k!vXlJ8SzNkq#xdrmtAHHf+Y}pxV%UyRr2Eq%2-yb#1)OpDe9HM^$Hx z$Q20wDyj4Br8)QyOPS|v>6@x&GlYyW0WVGjawxyc-7Eh4V(A_F>Ax>NE~2xO(mkSH zz!LQ-GlZi<4Z;({jz%Kc1O(m zlQ^qZxBEjFNJzqfHqj~nS1ibwkg3)n=v7wASd$_&Fj9Ds{C^}0T)FQr8>5AxQ zvobgaaA0|&edSW`Ftiog!0cffVLp-nK`e|av6Om8vBLC!0kNX&(eb-KJod?PL++HK}vaBRgv z^|msH8m%;yl4rLVkZ8Bt?Z-i7_A{#*?KHVQpLR5-GlV)lLZaQ*;9<0T9Jw6`>0p8( zBm*KtNVMAwCPurhoQ5~r?Gi%VYbk_8J3~mc+b=w-S{klzyeG2Va}OffaKY`mjoW3E zWD2B9=Nmry7}gqSJ^Z;wRl)BXl7rFdme?%4ka@xPLW;472b2*Uk8n`gM~E0kISCo$ z*(6phN^UA|!vQ6?A#@leC3c9C&qc{2#Fc_VNR+$=3ceQ#A@O|>5+%P9LZYN0BuYL2 z6QkrKuCz4D>1Ipv7($|?AtXv}6CPDcsxz{S@>ryMj0hCR__p-0j3N%F$FiVfnj5-p zZpa86$vK$B3NN^uQNp?-3F}VzZrO~S?;>%T{qiG~+eNwG_=s;LILNShn*;~%=*Iyu z`jN{@?@(1qW=7(DawtSXTIn5VeSix_jpzr#nvMEz8Syt!WkDW8NhG}sCPvc7LWw(p zg_1_Rp`;OSD2eFXQc#ldTR(b8GjZE1VG#=zAtaNxed!S#Aaq1{EH3;A8s~&`TlSbG zkbegjkuvC$UBPbB^>?eNVTN_kRBg4{5k92HPJ$l#uMUo#xrEpyIyGca-HP`^bGw3F z1m|sw$>o1iIPs2kTWR~fk6hb#v`hFMB{2gsJy_04j4_nMpQ~DP?$Bhq zgR7Bzeytdv4pm~e@;5;8H?~!?`-(*j}b7>o@P~! zO#AL8+gYtQkd7@!hK+j`DAL3>nK%g)?3v4~4-6q>NVXUbQ1f@qv9Yp-G-I?U-q^-&JZ^&+LkqvyIv5SN>80(uqHX(2dtZV8dtW+M zb4!_z?jm~MODt0M`RHf>x$mVjFU8%0vqa^03*6P0z7XIq2#;%b=yYTBpU5`&Pewl) zO>vJ#Z+a=~9MHr^cM<(~G{rsk(V;leEGFqDNx$p>``ZSzRz@*8&~`)tN7@WzY^}$m zceF(m2Z*Xc@nG9A9lkh5cn-xgqyI=K{?X{GLh4GbwCFA$y(C6wD7piqe_y$O zfAnePK0W$OZElP1^3h9T^q|~`EXut!M#s7gjQ&)hKOKD_2h&+-R}76!W1-zKG(wm< zpZxO&Mwhlf_(;T5=aF10Zla&u;pe8>Va!b^Y@U3CM)?Fr()24`;!4Y$;T=VbxKrGV zI7h@8E{QV7%>;8q<+)h8Bw_7R=}MjXKd;+YZ;m7N_q^j#{pkh^dDyTXYX|b|YTVZ- zhan*py4|k{-6J1IymDVRRi;rh_G<;P-#?;_I{Qp~f9y+fKmxu5S5n+5-jo7`fScTu zLO@?>Ky+jj%X%yR+}D+T^-^q}1xtNTH$03;9%@v;H;r4G4B2B%Ld}q^=Fi}qZa7Q6 z10TC%O&6MUhscGdN961K*ga}`tULN1H*I{u5^Q{7Ky%Z;3p-z+zB^wyKForT4nH;A z(w`cB8OH&U0LCh~0;kfwF-R;tUk#yQNolNOO(#KsYnqzQH{m@GK6R)T&4A}Z(*uP) zYU+Q1&%g`&hx0i){Gd$yFE(G+r*FiW5qxfpxTVjX5vO$d<@uIteDWC04;an2z)-s3 zf1zoUugKBiSIi;gzU>z(#B&4tOKGp)cGzD!sowM%3$M7TaFau@F?x&Jr={H?=~UQA zcigwmKAslsi&?aD#WriI@=5tlVpbR-oGza&*R#$Hdl~21L?FeZ@@B~#o4F{lw3Y_n zio{g6eb2|~csv8?zgFaqy1%Da9B;|A1FJ(}><5wY<5)S@bF!!|qduwcmy8zkql4CW zzm}29Sw{9bdHX;v`2p(vGW!(Tw4o@rF4>>Pw@)Q@Q{rz{!m)h>-je_C%XY_yozO1O ziD3t=zqrf8w=`Q<+S0tGSp{ruKI#LG;!wcF=6xe9#r_e;yyG~{Y$10>sCU!rV)vp_ zRcBUBtAjwDEFVwxJ&swXHTxMXGR>h1C}tl|U0T5B?D(7GR^1)%xPw6*nBT2CTq$ke z!kDS_F?ewFHS{-BaL~@oW&I61Flli+uxx2m;Pyu!rQ?2uh}{iBcFVK41U)f>{)Z*WRBFIg%454+4@KFdv=8XVZ$|SW894)hjb(3vBu*=`D|%AhKYDa0@&M4Yr~Ve zZi?DrG9*Q&wHCrdAXWTC%0+|G*h8{}F(9Yzf~mo5k)(@Q9CTuFfRP27QW!0t&oH-C zU%AfGs$p$Gl(30^GcR)F{hweoQR(&ZvQgMs=Jh+D8rztiJYtzo{Y_J=EE&qr;Eu1pV>hCx+JzNuC&2I|1u_MiG~XA8jVb#pWHl_4@dTv-%icgUBQ9 z%Qw(+5xc(w7;pL^6T#ue$eq3zY7KSHyx1wz34xv9tSgPy4=J&O`;fy zE;oIyz|Wg*G}S}A5PGBO6U`l(GO(Mf{@fEr6usqG<&Hi_^tysNI#zTtRXZ&Mu{imM zT&5q+b=z#DD;`~XpY{4asbscq`q+kliS7Xtd+0+RN;$#wR_ezYI4H$l^kWus zmR@Ti>bxYq<5+ad4(hR%*h;z)&TUCIM;87GYerJ2JA=CVaj6&o&hkMYA?|KD;P0>w zU_5L%KGYll1JKxJs7dQ>sUip~}EZ+Xt`$rMBu1 zzOn?UvI;oMNVOE7xvQ${RjVQiR7EAw>|_a40|odBkiu60hsS9EoYXGW_JaRE1Gk@N z&f$fP4B=q)t+t`8vl-s!9pmA=G&x=Td5l^lv=IIpS3eU}UgVINuU=PIQ zuVL4GFLsmBeWmWRY&ZQz-4~hrP~})9rjd1Qbnn9|HoC9X-^|?inEYe-W(14qKHhLX zb6;W&5W^p1LL1#%hxBLeJwpyBV z_eN}Ki7*FR_GRw#Eq5~awvnet#x##c?re?jldZQi_qi7jjEdpsN70vjJ7!JoS1f93 z%m=q>glskGagRpGUPcIxy%K-1=N`U)c>Q|?&ZFM@82Mtyh}|Q~Yy0{zINUvA{|IvK zA8|N_93F9;km|5{MlZ`vWSRkXY3y!fmcX&4=?m}ZM@XjRi_Lu__?&7v-NNT|%lVce zbp149a&Y8fT`qTcl-sQuPk=l3;$^*TaQQ_InO&JU9s74ii@d`}=5TzX z?c;As++(ZrS9&qtxFnxjn&4UEv1;X`r8S>N_21}Y6Z{ft_Koi4IxLHC&PxrsrOz$o zllpfudhTjGCPmcOt&duBRDRU@(-%qmQ+Puz^!AJQUraGIJ@6yUn_v8QI#ziJhEPpm zRdHutxTw3ZF23*?%Um6U5My}G&&`Vbdv91Eoo*1n)?ybJXKf80rbLCG9eQb~iXEz@ zc$gs-eyr&Zg%NP)g?lRe-V1#!rt$X;+bCgi<1n=XGifdPvAh4WqWt^nkJzGLOu?70 z#s9I7-L|1D0+1Q4K>U8~f9%_9MYn!#y#zN1DJtmr(Df#xxb;n2bOC`T5MQB7@?L5> zLcK_Ts)wZW99lEc{aH960%;cWIElIhRFOGI zaReM3_6I8N4~Bi?{of4xP2F|%o5Qv6B>pIZwmB{~i{406d9lS>)yBpJmI7MD+-o{Y zMh1%nSOuIKesH7(?1Y=xuwfDoeaCkSEMizr2+gmXP+Ii(tawii{~Qw<(z*pa;PuS@ z=6cYk`?t7_dZse!^ok-RBdLcvndBwmLR(2n=Gg0W>n|Z*I#p|wkDI(|rC_a`TcCxR zUok{*27rBMy8|6t2c3dIF^09jOdqalLFe}_Nr^gbJLgVJorWVq-kYR*ZvF;FiWU>x zw6c4`d|uIDoPOZ@O3f7wVU|`_i8kEX(CzB=M#iM6=)0r~EONpy%*jjP z9n_TM-jn>Efd3wESOQ$fp20k5@ndwCkH(P3M^}Mc?rtBg`vfg_)PY*$Vj?XR?Vq7L zko>L+{9TS|R7;}82v^a;5BYUCZQLwj7kYxS5|z)bQ%|GavA%xXF6ZCV#0zMgR}h73>_|BKA!H z*6q4V-Ju)*9%3+}k=eZ@5XAE=!#kzG|2cY*J(3%2cF$fW1_z<$(Zn3rd zB&@pJqziuPl!bvLef&Q%Lm~|#xVye$Ur}cRuukDHjEa-llyy%Di!kG&<2?xOJDEmv zbIyA$x``Q!aPt~Lk9+gS7VzUf>2U|*1v_WC9h{ZNS;4ebtcSCsIAEgwfGim`sP99y z6`UaT1cBBNXAsP>Z$;|7vZy>VPD-Mmn#<4(Bm_@-*^S2nYevC<)i| zkVN*PH~GW}-*QB7iq9?$_)pz9|1ozw=O|O)?AI|d&|}Gkmoh~xfqy@V=hgl`G3ozM z`a8)4&vJztKdYN}*8U~)dAM7FCy$O`R9L{)=u1q%v5L{TRL)a#N=Dv$eDU5Ze}*Ap z!F?usG1M$vJR$F0Zk|x$^qzU|apE5DeY^01^Xr`2!F!Bj(Mo)w?xMUG(NoKN;H3-f z3wo@;<_-`X02LT}PA$sM_Hl;vyf8e^xnNt-oJlWu#|0frpuF@Z!XQhXn+>;gO5|3< z7pM~P?`qtwecj!SmyyHpZ+>ATVik@p&1b#i?uaL7>j^p5a=XPGw_E;S=H3R(%ImuC zeb1RaXCH=PI1B?CktsRBV=@n+3L#U4>T=b26si)H$^#xDtPqu`Tt#sSMHpkE5P6I# z!Gw@8p2!#zgb5)NLb-%Y2vH{rA%qajrIZj#3FcCjQY=p}Q3;n2tlZy!?RUTD9gyAT zem(b{XU^K+d+oi~Ui)*ceO=3x>n*o~{jCW@OrQucH1Tbz34VLx*yf*UK=!9vZ?^(&x87^@6s7bb*z3L4-8zdMc=Vva;G-u5u0Hyfl*PO?>Fr5%t3C}6 zo^(le)d8sub0i#kkMbQsqmh{hgs|b8oxF_*nTEj4rmh5HFvJl7FfOMq;HOvjLVHVJ z(J{|gxMAZyb%H-KEd>e_H(UROJ?L zN~BiZBDl>Kd&4Ia^Ok+nxGgq4-!kstxV-zpaYx5-Zy`-ar%id=_U3%p%gvj|>j*+w zD$UKTM-$&l!@(bJ^N^*jvg{3u0DEb(nyy>lSa5OKRGn%@T3M5 zIT+&D4?{sC;v|w@4&)NZg!bB1F3#klRe5*0_=C({%Ex)2nMycbzM%biYe)P~jkz$! z+%I6jT`z0Po)S`x1Z@`e0D(ebMrNsBphEFU*blFdz#(r0!!VR(F6%tnQP8X653%J! zJst9ggU3mo*eT9gzY7+H*FeKY_Q^499J6H%akh-A`0Q+W z;iT(;?lpXrO$f~^Hh!9sLY)-DK*Kf89x6`~OG+zs+T-V0jQ184Uz9Nr% z))6pV=3Ehv%T1f;rr1M&C8?pYyXhFX>~0=rFvn$h{7ubWZ(2XaKG-ruk0HbmyxBtB zYuO5)#bxV+e$CVSC+rONoz|0yqn>ObLRZG6_mM+%H{u+6WbhHAQg!N(uJvld?AC2G zE`@&A0CP>Q2HEhMV|VoPAx`!QIW+2R9az6TN*x}1=g zoR*fvDCQWWP-t;p!Lwdj%rRWzV4^(SVGeI?)^@z%vhGA&ZP=#E3OgE)Xu!A(&je_| z1H3n3x8_De+KH~6_u5n>B*R4Oc*9wA(1eJgQ>r^KP>P?Dz(kf}u|l#!)(k1#n!Xgp zILYJf)&Wdz34sYCQaZ%Z(navbaIxW%CcBqxvWtCp<5hSuhR`$^!n6^?@c3Z}N`{ti zYViMN%Q2`1`>~0~G^aggb6V`oX_?Am2vb?QU7(7G5oa2EPMzl*vstjvWL7fZr%S9N zK>u9nw$$Z7FXGPgQtmu2<<9fK=*9%O-XWB@EGhi4d4A4Lf5HZwdqiLnPT@6RGL#ctLbJ=0indWoZ z;n48-1KEMi$(Hvr^IJ4*JeV1LqesSJ6j`fN3yjZ7_;b!w+>c+)i+5%u(+R5ah`I~Lb?_{c$?a1f)u;t4Xd54{% z?_`#&y)R9TRa-|&oDX1Ee-_*{mWe5FczhqvI4!0#-!`annq3nEQ+VcfYPy|m1Sy+b zbA;07f89Dzpa?s_ppG+603zjV{D6ts50nnceyFsakI;%X+w*F}=8w7u7Y!i)cd*sV{zWvJ@iNj(%POn9K-*!IQA8#(9-w4%4?zpiHwkYn8e}8;*eBb69I0hDiA+QkkEmR?Cm5gXwIgY5R z;QIk{`HUBY5cbO(Df`jg@|&iQMFNGTx_|sr(&KW)-_e}-j!icDHQ6|&qn1;nE;Eo} z*CdKTbQ3Ebv)>uJqhhL$ba9Pi*~%6Uy$Gk(H1>nz2FKNX^3&{Bz(%oex0R66VZ{tt zY#!gQbMAiD$JkDeAJ%o;uu3A(V9TKH<%;oHqN*M2_gdc20QCklFKntQ;=VOufCeSf z04=LXObpC^*S3Q2*xh=N3GDzEYaSg86YJB#e)`c%ViT7hy&5Lk8|aG!+rV1b*v3$> z4~c(pzg?Ru3+b5%7ogRI`5KPuo~610RcF>J-@YzIY5f|<-M-=h&c?V6#Lo1o;<;eX zcWKUPmpo3FdHf)U1dF&;WZ~w+%hM z_k6h7$!SbRw2Xt9nNZKZrW1$PUaw!7bWKHW2lf8*d46F-A$8D(HZFS$k(OFI*j4xpY4_x_bB#7w0MbCVMs6e-LPIifH~q!1sT z(gRn#cR)KakrI7}iIeJ<^OTLcS9dyIue(?n3l3c$rWLwA+_qwbZ1=(?gj~{BD6U;= z?FK=p#fq=4C8aRab01$z7&U7BilhrY&&Q!z!kr>q$ zrF|RE{qQ_;I)LDRh;*p<`*Q#Npwjs!FGmIUb;xXIhh;JTeBvJzMOm!*#FBmx%fj6( z-cv&NNP&29;vGW%chZmB*x@}DbZ_hRpKEH7Yv_r>wyC%|MR&8*9;Rn_Su|siL_-mz zqRkJ{P_GoC!7VLXis%`=^0hEH)flavAVTSv@fB0rT$FaDrD#_o!}KzRy${9=PEK*c z?@D@NK?=}}jIRRJ+>f198;8$5`J*Jfc()2PXnHQ-Ypmwp=1CXZ4AtqI7~VZ|dhnu-0mv%Uz(@DdmD9V{;n>ddCo^vzxq|ys3sFf8wWf%Q`yg)*%jv19t zqTF_V+lRjS-LpUZ18uY0d3AdU9!pj{?6HEJ(^`CD4y9T6veg4!BGiYm6y8GkH5K*O z3h%2)^xRb-soo-Q%+&}pgqu$|lK^`QU6Ce6e7>+bD3LK-sak{;<~xfVISR-hu=j8{ zxJ2h9FQ=ZT;p-_zXB#2c7jeo;%6mb#)HuB;C;)8K>k)bm3uHpOlG@E8&)A`UvTnD) zHTlH`#`lQ0lip}NUl`5q=Bp^MhczRrK&InxuzX9C0H&I|*VLM3`ODyj^i~mf?1(X8 zWQ@+Xp!L2t_RQl&y`*wd*I>du7p%F&><%*6TtbbVN<6F0Xq8dFALXd2i(&_38Z*pR zEfR6JON}arKBjBb-AAiU!-~QWwlj1|%gq~NEDJ*|NUuno>4w(AP=YSAmb@BrfSn9yO-n1}UN)t8EhQ|~+7%XxLh%g(` zD`#OMdPC?8@ra0gN`a5nolrMAQFqQ1^qe&bjGhwUDym8ne&4C}FQHreT*q``PM^!Y zw36ya^O%!VjG!_%_l-p^@#CP(&EZ}V`6L`n#DgM)H&3*VY^kgj>qoUs`;Gb^%{gQ(22f~Yx#d7 ziHp-}81^~%^Q)whkm|VaeqOtOTcoy%b-Vy8D@k%iHDila(4_>-xecQVg5Y;?wfiHX zG%ARj+k;2Xu7WzuuJG>JSqiO&u_S&VtaX@DZdC(*QqpW&70yPTTwMf3Eig6F8k;o5 z&xpl+CcY@Kv#z+Rg0{MMYIO2*k~G`HllYV^xrK~ zYzPfY5r1$wCtAbhsyp3aE|x?{VF4*9{jTVS($9~g6IX6a%q{#7S{XUAQSy$&Pt$0Q z9o%Cm26XNOC#k?(hi5zDx|;2}yR5C%%cXa;U-wSwrevUc8%|3GD($8jQNo;utXB<* z>YfXaL2xah*rz#MU)@&m(5-r?2$^}_76EKwvy$c(nprZkFrscj%X5+C1alO1$kKPII~Ypm^)xF@`W?1-a0<-Lb2@g5PET<9*L=wYXBL}{7cue1U4z#VaaAX%$(5G-JK{Slo^9FbhxYIcPVMHMl}(DH`;9e+>i zIq&)Yvf2B~UoO|Ziih&Y;$y^nh{sgSaIAD(`5Z58Lp+!svrUP8)P1>pnv*KJ zomCS}@Aj18F(7zGJO+3{w>FT)M6178jvGlH{krZ=C=Fbq13f4s7^n+XreYY_1C`CC z_ViTA+|bJ{sa#ENh!sU)YxTs*0~Dn%Hkd(*y4`AWJL>3^#h^qBxmWU*DjfNKN-pa$ zSfMa{r}VaDNKTYb3Y^j-1y*|@SuvOgGN|PSikdj^GYs+^z_|BJYn1ftzvphNi{Azv zDK(PQMi9_#k1M9Gmj|6`dea4@GLg(ZV*rc6@G5OS*IgB}CiN2H8CdU^cj!2G2QNaH zGNRswjk@o&kvA92zN_J&><4Lo*%`+Ixra${_=Q34GJYbytbXm6b)LB6;-Tmlq>BNrbLvWNSL)O8 z?J8=e=9cE5L560tmV+7G)%~IaqlPu;4Ub~%V>BDptFccZEPzfh58$Rzo|>!09p;h} z+f2hs1WBh+2h<1$5S6i}J2>hv_LQ%nK7&B>@#WxsJ_qkNM~&h#*Id*{(jFpHB*w35 z7xtiF}hio})?}Gz{(BUb*))}Oae$MCJtZq?W_d<*dH`~0qkNefQg?&Kf z8t6CFMbc~vq*@;{FsqwnUivuQs;{t98x1=Py9;%zp;c*}#lBZSo2vt1=WM{<-U>;p z=3;WQEV=HN3`l)un3*M-rR~>;#y54 zW3h~jUnJ&>=sss=*GEi2y$6<`C$S1=#ni18Q@T$*6nB6xWZPd%;(6}jqsem*Eacog z_W1P5)5P15%FhT~Z-LOy6Z%Y1 zUD$S#RRBF;w+#i5!O7y)gg4xVuqmt8K(*r9Qa}$Evc}c`K?%P#j7lhex3O@6`i5Tt_=`Ch6_5zUbmf&I=pVFCV74bCO;HOa#$&!bo(mqSY=I;Tc=NKW7BtlrCYKN<<#^H!F*Z|hw%|<( z`1B-CK7fI9S{RiY^XX}fDmu5K@AWsW;Zcz1R@`F7Uu5Kg>_?P=9wnI(()fQ_K4LDN zcx2tFp4{SP)EhG)Dkn=;xuuDM)I;zM= z3xCY><%&fPdNl&K%_OMtC4L%_cm+Dh&bX=HhvoYuXeHuGKQ$K5pFT_Xe>Oe{x;Pyo zYGEXA+&mSurgmWJkOY*4rpdY&(`4~eY9CcO z0n8Zv5yK9NV@rVOPv`&CAiZyH?JkKcejEhqV%*1OH8o6k1ay$ahp+q_{sjcCN;E@1&-N*juH39KlZkTCE* zx7irum1Vx~U2Yz3rtXJ@>&i-LrZ(br40~VUJ_;rq#^>E*m5Yq}xaAJAdz$wO>}@`v zj1EXEm!tp=arcFc(!n)^ZrE843EcWeL>p+%+XtF|vpK5dP~5x}FAX>}?oV_%?@z|P zI}Wb%?zq0@8j&ka0vwm>q~qf@H8aK7gxH2v4L7m+a0uB7>)Ye*E8P8Yz0EB!wGUNF zpF*DQAG9OW za!^qZR&MLMp~O(I-KpG@?Ox@+Z1;(qZ$+8Qz4C6wee$;uqj{Ies7{x1CFo0` z1Mf59zFc{yLZ!S@8LntUb;Gz#CfKrR+-~X$dI*K5jt&zd=FM^q0T^ss#_bsAR!CN7 z$GA7gl|P@br-v=a$cU*j*kVAXumzOLVJ<3(xu`7WqSDxsHD+9cZc}BeP}o}eq7FO0 zSlOmp_`B8++PCiN0?XZ|!(;1Kb4UO1*!yE^%@VRB(6^+b>sw8Iy1Ujl_K1QoIv$bQ zf#*>>U~$xYLf5Wg$vQQvHQc3JPrJtM9b5OwwTk+->~D`fHns%0=)~&S*c)=XF&1SF z3i9sQVcFj!^=z1S!yrlv9R>$DVYfQi5e3kGx7$1R0CSpJGbwj4=UQabzOmHKk+By9 zhR43AsgEU`j_Svy7~=Wh6z9-xgOX#pH1@Q>X=M`!cee+viLsMOb)x7sVe{%FO3g-e zIB3QlY&xv#^M{*`G`UaE5!{icV@+V7z+q@iR~_!X(eG<8dw=wvMh%2}8ux{Hm)qBP z-dxT%?rF-kPh<*Kt-S8WuNjbdFmBADWB zX&PON7v=-R3HqY=1zCzj#Kv`F3X9#kG3&?FeFBPKKW6ioy0sWKkD+E+V+k`#4yap= z^W8C&b|L(P1gH$Q#MzJu>8;oOev7}#;_t`K>s4vMNVd5RU86Xw9NI>RG_JHuPP`ahVSTFy7d})Ga&P3r;PM7oj*N9`%=Iy&K9O*awOSQ%eatP%lc<7ou6M_5Xc`>@ zX)&ux&H4AKO|yAn|CsGcV_nlG^ennfRBg-Z^a7Z*3H99d;rMt&5wXT?qM2mK30}unaAV>3qC&@1i^1+FByyO&Tcp^C->jkeK z@VX}Su952KRcmcUYJ%+VjvgM}6h>m$GvhIJYl+m3KS<(?gsskiaPifOVa(MlCxms? z;6oKYJ*mi8yfcNw9V~p*e~n;h9P7imMDnzFoK~r5S8+y_6oPXqX$$q3=RXM zhg2f_Vo3B4EpYFTI;)e9vkgRe-Xdt;tU0Yk5&IQ8arZ}kPRp5oX{cYV88JZyMk_;^m0@sBIhdt;UmKbCDUUde z3Z%^k1;t+DFQEe+Z#dOZ_X#@8sfKrj?Yj*(u`@lq*>F$x0iqk&H`<){sa9&GNO@IY z{~^WxhV3fQcI{qErTwmkUu~#ciQ!kN2zzp1KSgGDX=XdGrl_y(Z#Y!5^YXwUYAWx4 zg}NDSZ(*|`rOELXkjxx3eHOAfgbgi)5ZbM(Fa1|PGIi3-c31)adZ-28eWNFR8((dI zsgMuE4pFsTW-aK>G<-$WZ!I22Y->a{^_7O}YRp?SX07)I8tT(S%DmV^r4U_J!a%WK zr1YFM6@HdxT-Uq(<*$};{Aw8;rFvKS+NiAO#t~wFnS%~?rOWJKBVa9MPwbu^wC9m6 zMv4S!9nr4R5v7%`m#Sg^)rpCP6RPHI^6lniw-@AiL$5~AtLiyRWwUWt8HDIPY0C*Sb_rrTZuWbn0&Oq% zz3V?=7e}*aSPw>*gWLk26bFzM$>g7H3zvzfK-ju!ddMGF8mD>XQ0;cnU)OQ!bxu|5 zS6Y(ye6QMMU3p7Zwd?#zT`)i8w?k>di4QDzt(-$A@@xGz`7uE1v^MUI5G#}fJ`iUy zwbRZW(*3+6ynAt1PgP1f@E)qD*K#zf>SmYQZ_(lB7OKIf3wu?Tg`q4k@QV_2=6uKB zLRgnxdW+XXvx&7K&C5XHx#eHr%Xh8wg{ zER@an0kSy;X^{Cj3p0l>?J%N9(BPrKiCel1kv&q8X|L;i-TG^b5IDiId!ZiAH7yFAqlx( zr@}G^aZ6QP=AaPU4R17?QX?FnUQ$!tFF_4)-enH~Lp2xBY^`Fe=5vF9qTQ`ur#;ej zrA-uPF8zl3;@r!MqX&Lz;aKtNO~e@Dzz?_MJSb(;gmB)=nQMCd$I&YkJnU{cDOtLO zcHA0uzRe9R5V@qoWmwNurIAO74x*xI?lZ;?L}dxG-l=rw{UsX@)1IyjZ-V z-R3Jr?n6J%vjJz)tIcP0%PB6^A~jgW1U&2+Xf6@kcdd@Ss1Qi93)euT=5H8;A5i~>E?#{@ zZ_(+QKSP~8+cSEpjXQxvgcZmANDKW@LWgTv>H}#yeMlNn1^erMvkpFexbCuSm+StM zY}Zu{>HIE6p#to2tl~eEF8RSap4dfJqU}SYRN%vzm3<18nDVQn3aqkWy;gUf>fyw~ z5|2kwZkVgLYS~-Gzt&dhCfx~2&t8UgP{TH+oZ@6Ng#UpwJc{$>IfBOS7uTyK>+3eC zBpd2JS4VC2sfiFuQRN3_%5!ii!lJ|lJ@9Rez?vB1I4iA1^W9bS_tH{B=z)bs-j*Ug z4gz@(yq3Zj)DmC7saE4LKFTk3x0o9g1tO+*`c;QlNL>ZKT1c<4-!}zO?mkzylyV@n zD+O|8Cj-4icFF04vbR0==zo}P zvx;np!|J}Gnb242Pu6Go$OoM9+o`$GPV|S9*FF?E5`^*}<`O6lL&PbrXwls2FvgU; zsFvMQx4JmNqV->sifpn99PF;;ScQ{)2HIe_<>h2<}7M^1XSRd6B zgRFDv&S*k%2HEd`*;#)VhZKJSXGts|iD7l-VJ@8z61MZ6-oIPuHn_WrYHSA#kJgSGA3Qb@Z@VuV==6+0Ry(UTP(P)CL&+|Hk zvU$S{q`ys*O4hZ0!0UFe8}R!u;IYpiQ$(wO>pSU;L{$?$s`_|P4SE~}?;2;%J5<_B zSLiKw+Z9)^hwk1F4)1djP7dqphiG_03@Lep5B=$2S3dHHiL>|Renms^uRwhE*1+C+ z1?9P%5R?~aau|hMP8>La16W@L15)2zzgIWNj4aux(`_q+f9ltlMy*Kd4!>5Yu-Ln% z$tEitDIGvqoJTq!dn1cj%=4sEsyj$<#v86|M)URh^}b}uuzN(cMR(O)bQi9v*^=X6 z^^%yurNYtdo{2nyJM>?8M_k|?SaP8MYXnStb{Y<$M%E_^$92aL4(hjX&x5%1ZgG3z zva$Ae;k@;dmvan5ye&S%I;v4UdG?CUQd!~B^}F1SrM`zXYB9^!ZH>52A?zt#KamU^ zG6E|T^5<=rPcc2Ua%iJYeNB!GDA&lfj$DOs`Z0d|u^9Lt7cVKxOGs7d1Y#SvuyNg4 zMt#>f-s5@3OARjk@1Jk?T2tmk7a&T}nRn3Dy1bFQ`cYT32^i0Rhz;rn`qBk z!4R^7Bw7MC&m}z%uvq2CSp3&Y{;vyfX`FnEYu!*&H>ava*gz;j3^hN5LbyPFHC&?q z0{pqw1G7fWp``=04e1?KIo%>sj@w@4k`qmLv-n=||01^?$#1Wckmd89iDkLXZmToK zx)pH;W2F6>f5X3+dYgwP@O5IG`?y(*#}Ve+7Vs^1RQ97h?qL2Wc(B%3;VDTl@ zoOF=cy_oND#3Rh%9p<;zj8=5V`?K|@gvlL6#0WXWed*R89g>oZoG>Sq}3 zHpUBk4kDMg4UIHAcjJZOxge9#Pgt|-ZagX9aPJA|jx%77RQoZ()m7#Pc$PaUM72d8`hNYMQgm00n7@aHi|6M58S73N>~ z$7v_}s!4qYSCw3srmu1RM5K=f7w&V!Puh;V-J~goy_@o3EFYeh6~#j7;@EsQSwYB% zAoD|zbn{+e6l6gNLfEkSYL51fWb91_Z<_QS26Asz7-c()Y22rQ0LN@4KTIJk*Vu7*lssg z+E!Zieq?r0E9g8fNwu7LKpWrYjo9>>-0zM=l6PfWNV#QNwgA>cv-8objO)~C*(r~! zw9%?MSgvI$3YB)Q@aLkbKM!)(_Yn)WERbVj;h9ySg_<8ip=wWlS--tf__|W~x>Art zF@E8|i_|~R&oWNjT4ovCbKuf4)jx#HW36n&T>C{e;}@l)g2{OB&AP7naydf2J<&HU zGjWGZj+-0Lc(Wg40>YuRiB5#atgTHf2#wo(H|Axsd3iY~z$})p%}O5p7q~IY$Y`1T zX+Zq55>BqFD^}++-N0EB(a_!949-0m`7sZO;(v;>tLAWW>Q+VZp^J$~CvcJN|Dz zsQh4epg7Zih>U;eDbRXq&Iq*dm@kj#f=8__@mL@abbTvEtr-(8*|~{RNowl!T2d}) zA)ywzWJR-!lyb>M)~<0$*B~u&+P|0;tGQaIQ}&-?o}Q~yYSR0r%7P2+rWUJWn z^dBu$xNxn5!tf;}Ik}`+={0v0e}G%W&&d1?mqmX-BUSlD0>F5ZVxhbdBN7YNu=*(t zS>$58YEpFmXOl0u`KUp1Q_3=aeh%g-i^`wx3TDY0#hg1|P|h=y+l;x&dG3oczxcY$ zuU{)*ft!>M5$xsCPB){FoR$4J_MUV+F3q+yd_6O1Gv z*9;%>IxV~P=U|L!6I5RLyv}2H`Nl1OOzmSAYp*k=E<&0%Ws$pB*+qfJ(sT<}elJsrIEY%Gs?z`dhg>>eA|792;}-w(Je9oh-Cs082J~lPRoG zV}hcdLy}MCGLzH^adc(lZ>iHzTqXZiyx9YJ9c8yu%~AVGPlj^DYktKs4GX^D>NZbG zs*v!QgN5?v7em8Kut-op@A-Qyn=)Uq&ZIQY65Cx!>l?H#N3)HPr6m?12tVwUZVu$k zi^a0ywZuj$h=!BWLJOKus$`qOxdDa(g@+X7hmV?G#)d5FsPaZdqmCQ0G8W346+Cv4 z!l+=+hly@6OgRnH#`Uo$2BuDF-ZQoQx8eJA_TVLb$WkiDSS9b%c;z(Sn<1<3oJ?WV zXlk!?N{G{WDQUtrq8``zluA3&H&$%Y6iuB^#lqK(8bgJ|bfSL}iQRS1jvfs?(U=#_#4f{(8-J^_4bTh?OGQ=O7ra z!32}}T8KUiVOrzFE~`&URh&#KJ`qi;*TniP)RlJ-J}LeX45Y4n(9Cmd=9oHuC*@aH z{;+wPB~8w6vM9Y7m?Bo1W&X`k`CW5c3^{d1L?&q?a5~GgX!8~&mCiH) z0o6e<`L_fKy}lQJ#nIQo{|@ZjHMcLq$*H{^IEa5WwJUu5Zeu7W|2sO!Lb`HS`16FH zF3ZP~io&-5<*u)4zuz9_@lwzS?J<7DV>V%Ck^U?N=2PcdfxQas1FAd&z&SvDv0NL2 zHJJe%#$WlAUq~twQ}@_OWB##TKD^sBlYwRbVf$3D^g$0C%Mj zqt(Mf>|L_(3BOy|cfqat7AKXZz}r7ot2g1%`Xc_oBfwan%I`9E)yFNM@X#0QN9N7^ z7n586Fyh<#&y$MQBQsODt&mio!hQ+JIaM;Pm{f(&a-i&Q1ABn_9^=2IE~$3O!e{La zTxzx?=}Mv8dk80d)&iA&{H|drCU;2EnbSP*P`FhX8|z76S?+u)hrT>Ki~srH%pFGZ`4>s$P9H_570Q(L3uHBQ*SLx`B2NSOaYohwUMmkec zd+dLISE%Sq`7b8F_1pP;)lTJ)CzW9Z;8QtnW4{f&@h_7~qa67noD-~x>O)_IqObU= zti@!~AH{rblaAU$Uw*T`2YWH`e-gv>EerfW;ac>=R|z2NN0B}v9?`#=h7(ZR6qEWh zG2LCHt8(fSZu(+6GKcV||6L4!GR5N}Q1ziNU%n82#-GLT)t?G@&q!exaB7HVzx(+u zCjaDO4F3xLO7|deeHu<_>Qg&+E)VqA1B~@s#eF08X+VAR_#ea`@v36Kl?xx^y^OoQ zNKb2nHR%Vo|10=IYVS&+z+(Q3$)Y)26}HJMBN*p4y&gD|$&gYeshQ@W~~VuDhYG@qjlfp1qvC)IiQEe5s+ z6f*jb=~;YuXEFKfEWX^Lzu+S9?gd^1E(6Y48OqTERQZ>r_7y4YP2D#E+wj+?@(f^~ z1-uH3^d|R?Pt^EfEO(@1*}ER_UxZzB*ZY7wPL|KMZ{vRO1Ke8_iEnxU8QhiHMI-tm zUJpX~sf`d3#4em)N)V^c z$d6YC=S247YXYA>2h?~z3|s+R{L`cZJOUKm&V8-cf7W5wSGC_7---1Q-G_@Iz$+<~ zZ92FVlRa5E)|0N<@ieeI1kd=G=%VdsYV@vh>XZ9)++#h){xipXljPYHMtma7)1!hs zXpi9{tfuKi82ME6|L?&VuRTpC!WpT3UJ7G658@;5Ko@_U)z=)#9qCE_N~4(k(@~Kw zcHuu=9(=JrHU?`(e=*;fPQ*vSLVnA$^iGrB%rw40C;!D{Yv#`+Amc|WUj@6$!5zqK zJj9xu=D(Qyb{4M#f0cVSP~`DsE_@aHGuY!eAInk3U7zq?jDOxP_qF=ri{@*u4q5nOdpu}Yx#Bk+Loqp5jrHD6dZN$H6wU$8j)8&eE&Q=5 zF}%EH@!v~0)y=%u6RnSvZeYYG!kA7Ke|-w4uf%^Z;RQDWRj#32eBnEcJ&$)gZpEaB zeYZ4~8DSoK9=Hp?_|3skOg@!`<3uvl_or+1uKF*h_R0h9F&*JlOn%~rviz{C+^vLP z1LWNRgBX+8o-#KYpZLh^7_ZzL>bDixh5sVpMBs9u_|`^X4^Uq$uiE1>?t;T9lz*(( zHd*)t@8hp_uY9I9|Egj?T9;HW1NFu5t(f-{PG!3aoCln~E{ylxDO?4di@QF-A?%8O z5jY#z^4S2pfpT94>|oncUyLWb!W{T7$1g#)=xec@^1%r6Lu9)<=F^S zee?sB&q3fGVEkk*Cja`UW4b+?lFC!KZ3D)7Qabt+U!UwJ@mD=u1$F?-KVRd=RqR#l zYk=E;O6O$G-{N6ki~Hiu!GAMw7xwADkW?-L-Im%s8>_9Miph`nM?B>=TR(itM_;V3 z2xkT7WLgSe1l}TD;qQJi%sVQ;LF~tYSE0E*pAUGYQPTO>U;KK^x4JdZ*{T$t1Rf;t znlIGG>nirM*p<(<6y62Cf_+Ipwski;1j*; zi~A3%_f7bB11|v|2UfnERF(i&0ONS|1a^H31IWgO#i>2=_tmLg?GwM-7>dcUuSdMz zAYI|HA1J!N3tR;3-jP%$Q?BK|oK&8{egrrdnCuMu5xd?D^J2Fv(93k7<{wW0h3Asg zT~XTg!za8p;x2kT1#FNbpWu1yon{MkQ2t6te;LsF1Ac<9V}BAj1bjLTuXfQFVPCM? zxRM$Thhp;0W*sr>bGvKfT*O1}bNDYN|F9*7YayKKZ#q!vcL7yj3xR5fKHvi2JHRS1 ze(GDr&Z_h;$VCsp;oi@+7YUcz4l&MhU?9nis|J+*O1 z`7OmB>s$4sufqQt+yyrRm&%b(B~`U|D{v8T1@IN%ef+Kb z*cC2*`!N)g)jt;Vo3*!A53zk_rGZzaup@+g)_#m(fJfFhbDQx-m;NA&TeJuv69BY7z zzaF>|7{4A2#bocch-c%z5Pv#Q@#X@B*ULcV+Y3~`JP+&ww){rm8yHPJk)S@+VKJHT zm6+}V!l_(~flGixz!|_{U=^s(1wcILX@AXK&X@TI&wVjHxvkX?Uta*mi>4EA8TM_! zS*d&D1Mn>UPG9to?bcR+GeMPGz6 zFXq3P{P2ZXzO&#T$FGtC@OAOu&VGa1OkbD%*3uFGUW5PBsr&2{3hd{(N>;!HEE(7X|qNA`sN0Z*=1eIe=&Kko(sX|yN!4~n1+EffNlS4ji1GG3Xi$C$9(0!4EsEwKDEOU z?6E!McANiVvW9K;kk3{8RjymWDv(KwrPm2;#Xb+H{MQ0SH%EY~m-gRGDwl!Dp-^9) zz;3MTfk%OJek-Zm2X+kx{@?oBVL!C-F!c^ScKigG0gK5WJr&D6{r7A2(n9=)Cp5f7C| zpV~oRFX5&i4e@$_(Y-HtCv)-Fr}W~t9z!wt+zT<^0pcm2-aiQSIRvbxfgb~2#@?3N zTT-|rg=%koG5w9fnk-4-<`gak-X)#Isa;?W{~Wa}k9hPP3+=idcs32U2iWt6!Cg*Q z9qoyIX|6m5^WkE; zl{665VBgXdUVFekJGDo+Keb0XT88~T`L+RDPp0D?<{4?YBWZc&r1rrSE=u9a6ly%u z7sExq8~I;!?+(F|d1<;4uN7&3JD>U=N#Uv(K82gpc;c7(gtxwy0Fs{6zcsaQPGKx> z%)dEx7Z~EdnEVV}$7Qb7)D+Xr+pE-*>P_FAG{0(!|GeOw(M_a}n13v93M}Kln0)oAJpQr#8n-rsZ!AX~$EvvNi|#Rev{%hH`0pbA;?yoMkN;xw zH~%!|cOQR^GsQm%`#}oxlz#ZcH}pk&EdTQ0Y`;tS<&M$(m|mH5cHuSvtWv)xPu0#X z6Y6=#SHu3>E?|{#`h@>c>}_UaZASmr7wb>vfOqf5V?LJ&-;eu>(@AA3u=u~#=DnvC zfv>`UQ_lTaa}7VLt77tBSH|?Bm&yn|t%>e!#FyJ5;BDZ%GhzIh`|py<-85394_O1A z?|df4?>ZaGxdfabJS{Y6|5Q+fDfEi}fKo z?D`KidhapcFb|QjE42%(<-eGG-yg*Kk=t?o@Wt{fJ$;cMM7!uh-;Dqg)rY=Vf2s$4 zGXgO8CEyj^1lA9*XUV$%M%`F4o;4k`fO#sIQ$eSd22ODnFG zf;YZXqknmy=AV6+De*RN8~!TiEZ|jO>wgY-ZUzou@4Oc3^A%tV_O(Fab{431)mMS< zSN{v^Wy(EpJ@n6Q|26Et+y`zB!IEt$TngNHqc&fB9QzUMO1JUr@L`SDe^KK%RjlpU zyMRl9SAp?U+Qnq$v#~sLZr13s5yD=AeTXn^-(-CQey`jL`%wFVvHnDd`b58-e_7+7 z>W`bTt6jGN#ZS%xW4}~2-@@JrjGxTKo# z7*FmU{NE;==yvLV3v|?zLisCyeS+(7&)cJWgq!d`Aq(FH>Oo&Dhs>gZVsh$dWB%Q@ zYx9zt|G(N0{g>juT^{Mz0xTvk^hN*Z9?~8E`RM*W@gklI6Z{u_Df*ZHih9m5q~O1J zU-a+#KWghW#Si&j`mN|MH+>=A9}GqJgT$+vPxuM`U-_fxe-{54t`;EpPy5s8-#a$! zk~(Z7oSvGhDfX@vMc_LtHBTA@(scqsobG8YJrjio}R?IHg! zjE(*s4P1DS$Ytp-cr^O2#s9`b{y*0q{g;mBPVqzj)Bk?-UxPn)=dv&0|B)x6|LLYe zHa}3H;O~Dp`rpF;;dZ}}`J=)!JGZOF|H40u@mGv3WcQeA{@?qt=-*iRAp93){#E?r zcu|Z0xy=7D{HMqx{Q~|!@j^_$8~@H+0>S^ypN{_PCl@N+X}?ku!M|%`^gsXI1v|$W znf^CEAN{Mk^f^mqW^vTJ7VN4{lE9C(ZBtB3M2Sp$p7sF(cew^p!S*nJJG)b z|C3{C8HD)de;@sCeSaaF4=Ysg|EoWb{x@b6DyJVR|8M-)=s!3U8H0!V^*8=o^gr5J zs0=;izc}$J{jdF@LS^1V{pZieNB@(vp^u01U-L-x7tXovlj8riDbauFlZEWOpjN(* zeSh>niT}g><2Rp({+IE8xP3nR!_nXUqYvtT?|vlu596=#C4QlP|LjMj|6ce{oF6Jo z@c%E1qknrB_0I!m@eBS3ekS_g`Vrdiq5gaH7oz`-e^#grJmmj3yP|*J{0}PMwO^0^ z$~UezWDfb)4MzVX#Ltg+!T&<$e;og5ikN=EzxQa2e+&QWL+$&e)6u{3(GQ~Ur~gCr z@BBdj|Hwu0KoyJdpA$0&%3MqieIxqoPQ2#9y4JrQD7hEm(}DQTaEe!KpNIL}e|kTr z)3W%3>hXIR!vh{ev~!#flTBKW3o`$+AL#$t%>Nqx57X&j=6@IeTsKS8zm@sl$G=q> zr{DJi;}})1OZ-eoU8$VZcbmEBTqW`0a{tfegX%uNo>aiQKAI7)vL1{mswJT;D7ABq zu4!`gB1*|2kCKJN?3F^B-W5+;yh#R_xz&Cr+i$xcBuq7gu_9(z$81VvR|cC)5i_!B zM3O71pY*YSYibSQ!GrKE5s$y4wMY%cbc$pe%}TR5T0=!jQb4s(EG6~P+|riR_oVKS zVZEdUVwmG*p5!J~llseMF1mbnF3TEOwk0vIX4kejn#-aZ+1ThaWZEY4JVnj=#GIO0w6@+-2wiNKnV)gXRwVWN%xwKj9r&PGX*8nr zr74%8yUg5#%yv@0)4YfU+WXUBN`n;6nDs<~Cvol+z~RS)-Zb~bS|ptZahPfjMOPx3 zXUzPRTLcv@P2K6}qNJCjl^#bu?K3MmOiJn{U81I->o!nTlg#Q|1F`0&ULyCN)ZEnM zI+oU~GQSXm(Xf(H5&LrVc~L@aWXY;TbI#q1C_21J(D)^otG<`tCf~yvYHW+-7Ur!}!K5|S|nTXGFF-)XZ>bJL%uX1RxE9HkAV5IJk; z>yyowdY|Z8A&F2akZVY%X03VExX$BlR!_~n7}BprFSF376#G0$OTHM9z>h;OO=Mi*8y)eaxzfPN*<3ncOrn5|LyYtibG`XMu0 z7iy$JkC~MolyUe(`!)3~OCmurlDVb|($x@ebSzu=6=q%IUhku)Y%I`5kKY4^-q1e)?MetpzLVe6j5E~l z<~naeUfx8!EYzG4zb4uh#-z30?TjmS=C%_`i!K0LmE*nu7HNvSgGgTd$Cb(zj%$=D9x&}lEtG4lx+wRsaS^Cn#8 zO|;CLU|GS>ApfHUudG8y?m|6Ij$?+r!-&!3(BPe7mbpxI%QD9Xr(P_Pv%oQPz4h_v z7<%j0Xl-(nAj)W+#26KG)ByR81q;O2{F6#nb6M-}oo0nzsc8wR#m;vqHMh-VKuyiG zhSkhkFWjoWo8QO1iNbjkgfrj3)SA7Czdf5mKk}RW z?!yJ(1xaf0>5r%FMiW7eOUz2$)8AX%Gtanr&${jxllo=mUUttcNb0wzVH$G`Tj4W8 zRrFYrL|w~J?C>V07y9sAZ!&rXZz6i;-)O&~*LRvZ{LW7P=RERrmPJAX`Dg}{h0$zX z%$vww$g7lmGM_-GVFux>Q35j$?o17yjJOvO7LR6TuT6>XBa<*)3B4|u!;lylPryH& z(j?!N%h;O~pB1d#ep{30bKdn5+KY1z3GRuuwb*+<=bqu1@n}_i;!WVso4B7PJv&*M zPg?SQO1i{ckq(x((r8o7mqvrBO9D_CYpoK^Hg!zuyHYPrBb#_IF7ZmI;!SAK%Xez> zefcSXqy$3;wQ?LYEBFS6@vd2CxEW96tJtxBSTFHGMI>Vf8?H-XO3YXW1O;?)>cuQmwXvFc5V)5vU|AH;pOnXBHUH_aSEzHH{e zvDTWozu-+|Gvv^fd=m^Zwkjdblw2CRlKQu6R?+OO)T*YX>ZuwDbE>6PYrD*>rgDpW z8Ep5Ze)Ns{{m~4Q7>Z`v>OwSAG4Gf;ust%16;mS|O%ZDDusSbvmwJ;Z^(Ig1O`5de zO_C;vECWN&h#xu79J_zmnN|2x9h&b4CQ`J)mH^(GeTB^0`+oKH3R zdOlMXE+%CHpapO8pWdWDy~%$1B`ejnP43h8Vs7vz^J%HJdXx9`S8<=4x|pPAYE}jv zso5kvQ?p5TdXw$Ug>3aE)j7h&ptP!zv1FfBOpw_8rM!~~ zX?hdU^b*j#T=bI91ekbcoh7+9fF`r7w%;aiVwwKj8V=pPiDY^c$n++TS@0%}X+hTo z?5bwTj~BsZxZXUFH2L#9VkULzP3AHevB8_P

v(vox1LTw&08)?7keh2PlBb7S(opc`qWe(ukPCY(4U@g~>lO{&uena;QKK_$Lv zD^^(c#+-SZnagg$BKPvgllnok7B#TWe#Sl9!yuEo(9YWGxtfOWSQcy1h5^HUmNy~M zf;SmaZxW)pLd`aF=qt|5C2vxp-ef|(NrakvqYu)ckK{_=xqVbQ&ms@7tC0NtyqC#* z`sCBx0I>LFZ_=LLWIcn+$a$rNIn!~qX`bt5zOl<(X1lIullp^Zp6+Ha(>-G5cGp1_ zlVvi?n?R^HanLkrWUp#%vavTL?b_L5`Ap1)nWLE*siEYa=svktiP}~uIqjWIbnAIf zoUJpnIk$2()t<&+&8MjvdtdXC`rGEn$p08`1G~;yNqu#lG9(jdeC=mbGnw2?%_!)c z{Ir|*I{T>a`K12rdIc$?c6X4)$tAPB&XWU!MJA2^T7KPb$!081nI&;mPGajfnq{7z zQD&^DA2Mr$>*!*FV&eGDOul5b+&txkhPTNdXtXzCL8NbGS+ufwQXKfu>)b?nQK8S z$&Y|W)>C(GObcmKXWx%?kvEZ8pL|Z4m^iFAVOVdXu-*h=y@|o1N-xjFCGx6j<#-E` zi28%6Rg1T2o8=VPwXz*F7?ajoouZ-r`Y@g{)luM&pU?$0B{VPUG?1aG~G-Fg$cHTPD3l`w0) ziQ9S;wk>#*wJmrPwJjuP@)fJb7742&mi}TWBo6i4Q?oWtu9%rhX>kh{LfL%^_L!Ub zG-pp{*3yF0#MG?AiLGYVdM2sAlM6HJ^C1f@FqL)SX=}_}$^FhU^ECT?(VHx*mz0JrXtbzcy}teLB>+71`lrZ6wK#mne;W~Na%Y}Inz5DkSM zObe!I+mUFlCf-EB{VH0v$D0^ z?8^2~c@D}eemR)6Ng{D>5l6Z=@MP*Wk$K+A)Xeq9%sgTzfSOWYN{LuoZaHgy3$4^_ zyPUz-vCv1eZQ@M=-JATmm1v^4%rosb zEOAiPlWEwZb)qXghC$y*-DbiW7o_H%Q+Vt(OUcb!zfQ1PIclhlKlcUAS1Tu)--@DzKXDQDHyR9BQ>UZIx^+m%}_r#NlZ^7E?O}BtI z%>v%^3V72h;Db(q{6;WONhv-%R}8E{rGPGNWyveYuzb;w>`keFHsQi5MO;_Y zz-5ZCG@`-r2Q(<{6&gjxw7?vv)Z~8yHY5xc;$D8I4ubQj+c7Ds=bbfeMK&Mwx zrd!Bv`zy^^-6G_H&r6u6p46KBjQboh`&fW z^OA-6rRc*IEh_&uZIFO#Y@5aIrS;4uLVPwadfZDdyOlMkvMmo{^2~b>QqaAE%tad^ z(Hc(iAcKrkCahRo^J6gp(<837wdbtR8B0_@LWlYQEy7&cr6n zwC|)}lex>y*-MQ|pNV-;)zWDqvmH-T+JWfh%2QcfW>%KVIrCs@7GF4@GvCgcrRBs@ zCX6(lSdMhmm&^f%kMi#LTX-qg8xQ|97Lm5Vn;E=Dd-CYwknV->3{vq0nIvEHm;3C)U5ph zDRohk2q!6WvF3pwn#~L&Y)!l=gz=^h#+x!2Z>nGn182WQAC$oC&l6rKV%Ql8=8@f9 z%!wM38kj&7+NNp>E1|q2EfA(NT^5q!K{ARvX6jCoHrmP)8Fj@%anzazOV`oLLX1jzFf;GFRUWx96$tL_3ot2kW(OUaW=gRF~ z1zhG$^^JLi?jL^7hU2rqN5aap%L0X4EP;=NxyrRL_g-Y)Awpn0Vd@=@q{9AMU`1i) zak_<{o=6-oqn=P0Dv(WL2s~PAR}6}7#^baXr={8y({e6^fsv17xtiZWPcenR+Z9Vw zr(^h)?6=FeOOZ}$R+<6(C%q}qG56WYzsysfH07kDn%&s=H>nkzq$I}%LI!}d(JXd< zAPvLZND6XdpIDumH6CrsnM2v2j;x#_l~`s*5pKt4bi@P;x~N9q&?B?jVO}-zj%$T^ z^%?(jjq&qwm@cK47f zzS*^QFjNhOMzA@8O;9_c3)Q^&cjWslw@UA@pLf`7j%V3+VY_)merw#ZA}W;X&zWE1 z*7Lq1FRbn-z>?onfNAcr%lPj%%f5m;P&ioNEvut&f|GA60H-HQ6K`6Eyy+P7reVmN zej#t#g}mt&@}^nHn_eOMBZcVnrc}tAN}+-`jY0))3WW;Z^a&Nb)Cuh(5a`pm4`D9*X*kOSf(FU zA=P);S~N49wZqM16DK3hvU_^2o3}E$EO0Np9?jgvTVLP==wKo7rjf{S=r4LxM-sh7R0Y=ap}V@8LH%r7ZDeF-^eqUuF1L{yy_o0+kIo)pYwGY52=Y%}zp zg<;7~A9^9FkJhQrBz}M_nZx%I;t4;*Z(yO1`OBCCk8CjX;$^#v?0~`>K`K5-MW%Nmr&hyOt=#n>UK~W3dV#;Q&9YlEE(=SP=C`xeTFEc z%*vlZBv?xjVl+GV7!Lz)D{zLBVR@u*ui&=u5^;2@x-GopUbE>)HzdX7_?~EH20t&F z^Or9`nEBQ-(MuH)&68dGl4z!*XBdjVMt6lDxgu+DEvtEh_Ee5IcNh;1I5oQ+JoWB& z)$hpykVcC;>DW$5@owfR+>?%HaL;5;58NMYamVV;u>l>@1O+)9uX88rPK|WkQ@1lq z!-DOp+gs-b>QI4|MQ)kqW^}s8XSpY`nk({TWOQ5W>O*x>vFkm^m;fj%bzgI6zm;L5vIU zaJ*FusZF8~%kZ)O6#84335I$4QgcryjlnY8oWk$^&@}_wUgq!984(#e881uBu%Ji6 z>~xM<21AT6|2!EilguahhY9G@IhQaRoDLizWP2;jJh-x<5*!I&m09N5FY*oY2@~Ho zGY3w6J|xo`LWPL=L8m$Cd6<>3x0_WKO_Ei2zPE(N%dI4ISRfp1#LVV-w0AcDv&Ig$ zE_CP^0?V;xwqrO;gdSMt-BO;Ttodq34F;5v0@nQ2uzIEr6e=*RjQ&6%+sPoWtX!m@ zr9-)LIA}4L;npO6r&E>aGPMJ74L7Un0hf_hT_TAt+A@gdd|{O-cj7ta$xVF0O7eCi z>R;#PA$P3@Z84WC5nHMpY@xn3!_Zvv)@WArXeOhqz5bu7#s^E6%PXtWlx!$q?)VW= z0X3@%g7`~&t}IOSTUxDvh{a5IkL4KBNUvI6!F~Gl=#nQ|Dj=&&Ve1+)8o-v`+jebP zbA#2ym`;As%BPc0U*_EA1;HRlZ9TebHKxOnVy-qA9(BwY+qcF~i#aryskOSvSqfM) z@`hBnhtwWZz-rqA*4@MGE%1S8uEML9neXwy8FmHM64*$O`Gko{;1YrVgo$(hH*mT} z3!nd8A6N_<316a24@^-YKx#Bw^kvookg~CW)_BXzB1x`5MR&;dXlh3K)iMnnZL&Ar zeC85PsbfJ^qan=53fM(Di<6&x7&+Rd&CUT7Qw!i4pTTQNZZIrqbJUyCK5r`fEc>VI z_pzKg)ZOxgcMxhdaraMDR&IR#pX{9rU|m&}_wUKR``jc=+NQZlUukl0l9oPi(o!Bm zQYr#MTM&`KmO*RjgI4LoJ`j|b=s1YTpfbuRA~Fm*C=A2+KxG_81(88ykPlHAMMOs( zR8&M%M!(;G?Q>4S?X}lhd#$w}U?n}~-}Jy#$jITtc@AHH z5_UKL-i%>@gq@nd-hHEL4IhzE`}!7lN0xa>{+YVpWZcsP&P)WDR&T&oHY7ri=jIpi zD%@WgVL&p(G_dKKP0EG&W!H$~zBbBV7hRvR0}HDdF6MwSFa--lh?5+BzOJrdVF&|$ zTpSlH2w}lO5E{%T6)gOq-9MJMOOr*f&yZ;QeS%g#KO2Sj6a1*TMf=IKrr4 z(Fmi01tYX#;F{H|@db-RX!j@Ot|uicx$9>6Id z?of1l{&4s^`ywt_aKnOyHY`|RLrY(1zhPp9dO8Xg&d|~?4KyXNRe>x7G7_f6xt6Kk zenU!_t@QnoVSl*gkS$vRku9SR zyg3&>9GWUgi6 zTFPAe4dd8r_u~r|Nzv}Zk`YMVVmnPBn^gg+y7OmlO2?u%zi?sx2n7t{?+XFRt9kH1 z!pGa|urB=|WLj@Y0TKZP!vfS;2(c4uoH9bVM4YLqmRZf8KmL(qv{+$^-wgLdd|qSz zR?})JtH$(}=(8DlVaqtWH+yPCgC@J3C6B6%V!m=jde0hxDGQHN{zI>h&z}TFU1s+z z<*&~91>aWs;rT_&bAGYim-79f$L)_P{f3CcfQc3C-}{|V@)SfgD1@4{ykLPH3l`R~ zkf$qQ<|S)w0M~~Dpc)Gn%(1YATqoPty#)*7Sg;_DmJ%jl7}ju~&ScdV?t>&zvivg( z7O>IoAyCQ`=JtYuMQSWqoW_DhX^aXMq%kTy{f!iJDG-RyEm(9$`+C5B6Ma^S-WQVz zp2T7@7QPRBi46ewwihfKqkVB&!6Gph3Qq#0l7))SMp&(qz4xRH*{biEW$RNU9G}0n z?lzad40UIkgy^5qi|eEOC3W)R4<+XF>#wQHKT!8|O)ttO;Oj`B}fRD;l77DSlumZ7eYkKV`%QM zw$08D;5H7q31jif{3b%bJP z)bjd*#mcNn3F#IiGxXx&p!Dd>O{;2uzOz$!d};LFD3`CC!p%FQTx)fPd+P41%ik|E zp_=5!-J5;>-G$5Rb8oNC{o%q*h5W6BPZaX^$>1aZ?)s~7@~FSDK7UjFqxJcp)IU|9 zzoFsAhFt#9`k&P2pQ^v1A%A1TwT;>H#SQrf8h*q3C&PQ5AGhZ#8Z7Gr4f)F(FK^6W z(WsBEPZM+bpEq7UCV$nKtHLq{ImJ| zyZy6q{<-*Cj2sJ(7A*8;iX!!9}qudvs zZ%?1U<=(>nQT`LW`hK{*h1+|`P4=fm*RG?Y2dbX0=J^r-mN^3O$=QO0MZ z?DjTn((;$M8(gltx|#2-W2yN>-H+<>zp1;{<*#+ux%`9fDVKXub*|f^PYVHx z8KX!>mCOwo@U8mC>hq7+KU<%_rQzbn{56f&fl~J7j)sRCYI{FnM*evGwa&Uz5FGKWF_l^mvUwZGb<*S^u`KjA+C;NIMLneg|@#{5-{ zH&WxJP48{WU)ywTQ!f8re)G3C-OufFapHL_Uvum zywe^`3Rwupc_`rxtpVt*2J9Yz2crrLhgh&+h*3eY5Rt(x6k?#8f$^@d!Qes&eF$Ra zT&}=xUG&?r&AEs_puxYWZ~f+tYx~x&+Isfdz87v?vtz@i&3)@vZC&%aRa@8gZP~DT zbKll23;GxK+x@(4YhKg0ZR={Ktz5l%}>IS8ZFn59Mz=Z`<~@8~avm-8gU4=1ptotzC8IhG9=><2SBay?(={wY%T; zJt&*3yI-!xvw93QuIXT}+_rt|j@6@pyf1mN_tm7RqUu*}IeXRib(^E`dYQyEJZ@XLan+VBYuAtl2CrPRcHOESXK!D*{k$z}w~@v)rtNDsY}(EP ze3D99kM+t>N!+Kk@Fw@S6%rS_ zQmK?DJ$6@Jr1YY@H_=lNecQ$WE%n{9-Y>t3r>D*zuSh-=sW#;6rE?ucEtebwP^1JivwGwCHtaKFt} zC?eAQnG?I;U!YQb6whauj?WP;L3j{^)``%`zXs_kYEBExYfitXu zetJCK`))tI(?>ntw=jDL>%20~PBYH2VjCjLo6Y;NWj~<|$*IdnahLs8eAE^J#7>9+ z&`8ocxz-)&J9Hs=x~?Vrsf$$pL23E(hamN7(lr2r6kR{aea^Z*=ss&buX!%*dW;Nu z*I!toUk1Q$M=ACCpaHNijM*Go@-YGMFze}@xWzY>{hWC|>h?`7OMH~%%OG;3wb;)F zbWPoUwt=ompzFh6BZ_|4EW-Enfn`w6+OlEu?h__W-|Dq8UBuFvx3Xrkr>Xm1z7dji zxylIZJ`j^X6oC?Wv-a*eJpSYtf`m^_d;SODr?RRxY<=xW$mcX5VPzP>M?r8?6od3L z?N)8uwsxx+C>96%&RD4t>j<3G&^iJmm98Uv1^=~n>lR8N68knPwwo=h)@(a-)uz|< zhsO<@s~@($medAuV_J4>34kbuC7{E7C$Lvh?5;J2tJOW88!+d^{no)-w;VQQHey|O#vkItA-?3oTvYq>8K;U#YF)-)gJ)cv6KWhbnGQs<>xoRUALO7hkKb;`6mt z{Bu%;C5I{&Yk0i7b7wW2oYe5b6i&im-~=Pks&Q|16D#0by<1-*X}&Na;ZVS}P{ozOi=J|1L&*oL(TI5a(NG6%a7>3Ow z27F!8kAu_lewoyHaEj$U{@`(j1SWQU#UIh>>$@44K4aRNJPN&JZe`o zeRuCr?VqyRsXLD#=&nCsZDCZ;<35V4A)l!eB)Z()7gT)zfIqK`to80&7Y?Wv<`-YY z?r$w~hr8X16I#UXOBaL!K52ZrclW@zcXxT;XTP*CiU$K&PE5h_fHlmY2s7u)qEy~c z$5_vk$)x!IE^y|p{^WQ(M6B2Q@uj%WKzVaDD7)Q*7Yz7lML^EO_*&-%xW|$Kf*h)X zsV)AnlJ6_|StVbhxTPWcv1Hc)1MVM`z0FF0Fzws1vAZeh+rtK&^$$%t@2r_n{BmkXL^6h-q91lu2!AR&Ua4lR+GAa3%cW*fj(x~6(mK7-HGuybSbL)_^QE~V9TS1WkEd7kJH3&buZI`|9m6! z&0H9ozhn7L$A+|kMu##uI*!8qBn(bQW#4*HAhXXv(Nj8mB_&jk`BO>BN>51bQ@MoJ zPNiU-aN&L#1`!l{J@zJ#9pO=Ev@pTztPS6LV zC?P(>kx?bHy;chTf%WxSFLtJTq<6zrkC`BeP+28nGOtGnlPDjDgh?dJRG5@FI$ZIO ztf|U^bh-M>AULL~%SOqNXF!y7c#N9`o`oD}B z%}4I9SrEi*UmjNC4)=2Vc4sO^Enl!*Ghs{Jhi%<3PAqcwUKj=aSQm}a88+?^71U}= zEc{M;i`bmbiXRKJldxZhlT`=ZxFf7i=^$B?{35&d>Dn!=nskNS+cp8qEoxeQ(;te5 z*Y}mVei}K;)m&SNd{-*pUDnf9e-s(Xa#V{yf))hb8*9C<)4@9KH%YEe_rb6l3V4&; zw^$~7-Svo|cF%|9u)s(=Cpx@mAPunVxfSIUsRJLu=)w`dA-3@WSRm%L;i!cYRCI*sv zTHIp2&>uB6#P0KeLZaRj_xg$-HzT|Dxz8|7I=g*er?2$;ab&E}6m$i4ubSTB+uWzE z9=?YO7IWI>-Vth^6-Pjj3ceUckc~8_SGtn#CK-%(pCbEA_XYae6ZiOrmxysg^A-2| zgW@(nt;e4($i-5DcS;Gs*be8?loz@lzlwqO|#k6=l-5-^Z;7L z{$=3#WA`ZCZV@Nwq;2!MGsbZEkMGkfh=Iuki-OcqLCvR6|AS_j7}6CI%1PG&vN1M1kJ@|CN!)lwVE(AUj6M8Wvx_7e$E0t(gVioy*9kbV6`9zW+T@gJLGgm zxZQ2Cj<-P|oRm)9p@M>9HLMGxA`O;6)ahOii#$VD5NL+)W33>;{TH1G_W?+)?uY8u zEZ;gk`E8E7TN$?&vb`&VWym(G9~X3nT?z>uS?1oObtjM$2u^Fw6gwi8LP_hBcZ-Eg z^Fej@lG5H!vDd3xmjr}c7`y+bCB5!V%&vvpi`47B)$TQ4G#gAD6b3G1`XsYNl%t91 zA;2H(OPYAieZJJiV|mah)z7UC$Z0dAy@KYV!`)0}3`d{oTNp4+b7+MITACNg(k~F^ z0YO5D$@2C(aK6p`1R39`@C2zAb2Yv~2P`8B=;bl0Xj=!{5-{uE^C zM|~t3+VAJ7mD7-TD)wTbpUc&|Z(j(G&vhT9ag&8p?nePS8Jf6;<¨nldQ6LKQ7! zW#tk2QCkCed8kd_IeJFVOVM+~EqXCOvtp^VU%9`3VKy^`NLvIW6e`a%G5g#mqb$^x zOiGFBb?!zQt*ynnczPn988ioi$Uhj;x{@qq%V;xyGF2AiB~&?uxphWK%fQP}D$Hf? zw*(kmqo~E_3=qKdAlf|+k#@5C6crxi?gB^DTCcv10|)HUh~n63eq4_dqOw?q&$9JIcWos+anV#YMN2GRZqJNsJe#tCCO7^vGdP&a9yiU3;*FZ96;LDdq?_hZLF z6F{0QZB{(5=Bf7GK0Uz?2CY_4ihy?n1e)Z&Y06s~4{f@}5~Cu7oP?epUz+B{r=;6b z(#7ZyO3=*4ZIb)iPQRXh5Uas?49iT=H(}VdtFGfK2^o-l|5f`Q8t6Vk(zvppJ&#{a z?m)k_KuZxRz)SI?r90xCEF#PZ19yoqqwY8#8B z9n#x=(%@9Q< zMwPb@Wme%rraaNOZOsNQP0r;u?%2Ne+~MkzDwPQnNuQ$X*c0UmijuQ8uYL`RuC4l% z&G=A{-C9$E?j+~CnDRQ^)ioFq>9Vbhas^@>j1(6b-Iw??WXi>&$Wr(0g_T6@D~VWV z!-_$NIXgHjqm@F~Mv4!%LOwD|A(vc~7IGAYTpi^~u7g4*!v(VWZ&ZldV3n?g5FI5F z*me*FE*0r#Gej$G?0yZaQq3=qzSL^jeqPOhM617GnPpjpelIn)5iZu+{*K+$2~o$0 zg^#u1E{bK@kkr^|^zYNe36TRg61b+kFLsg*r2%vje7uAk& zPuSK$n|r_UZG$yXd~*Lm@tt&6=+iXdyS2syAx&&J@RY<|^6dGhuzk~R!a@T$8gRdQ zA*^^5Po%(U2Ha$GV^>_t$nr)5?n?l!jyZNm0o+Ng{v{~1z{o?W3DkRJ{{Ss^Hv+Oo z0K^V6Oqz{h!c~M_=@$2e^TUqd9mbWmyU(9r@z(z5%|i?(}WlrEsCTGE+F2 ztXL%OkI9NWJOr_M0m;POO6n6xTH>Pb>hu!@PE&LEH~{G@`vRoDWahywRRam(#@MK? zS}3gmN;(l6gCfHlgVOH}(;;XpAX?`$7iDGemo}a&NJyV6iSqG{@affb?mhblbU?)Y zC%_AIZbc29v%U6KXzwm`-=m-q)6abf_%H%+gRCdU1w*l0H1Zwpqay!%Su_Io-(M6V zr=r@K)F1Hh6+qa;zXt_jqyqm61j)u;|B4RZxVU;E-JBvPIWA0GtM z+}76iR^J^vR4rrI@ln%kz8KqUcRt#Ijcm#_o37P5^UUzNC5)-=PZ`lq>OMTweSB77 zr(nxpJL)QxkNB>-+ylZWX2lR4|@F7zN8t>SmX`T<*mMGJaI$yiN`aA*f!g`%#O(nOPJnxD69dRfZ|0U& zO4+?+GGq5QQW1r$ql$G?# zKp+2;!variC|$`h~ec}Jla^8WN%=WpaZr?3(t1~99kZW zUM}^#*99I{mqaNov1hx=`$8zs_qgrGnj-Q{fr~x2gsHIht8t#QZS*db14qjL7C!gL zihlvDPxKD|0!mHHOHQFg7qL2z6;7Xf)Rk<1M!9fQk2pP8yl5v10D*2+E2 zy)bJ61v697<1E6tw7MQK-ayX%8MUSWkwti`>#_wA%2a4Poog%wb2XX&=T-rK z<8h1ZjE^7it=;~xBj`tu_WJWNoxLN-xl2us<@3+6(XKyJ_u4$UT2)kW;wSB$m66)^ zeS}Zcku-F?o2!}J<4!FJ=CNb{UbY{kk&m$t+LA$X{9|aLMsJ-Y%KO2m7IMZ6qH7WL zz`!zXtM1pTeifW%+Dklqo8r_ zNbN$8WezmNK}-ID0FFJL=4N8{*I9lLUjxX!vMktKwCfAcAxR(n{K)QqiS#8JsDlIu13pg{iUW8wDma_^)v=&fV6Yku}Dv9=kSUL6K2(f4%P$eF%p ztn@w08GZBtc$tArMPxA{lQ|fr>(w;(Q+gbR`*8PH>QlTvwK+peMs;$7fCdUJDeI$D zILW;`R4e;M40V2xt1O`_lbCITrLZSmVwPQgCbR6zqH^*fSfy&TzD$*oz*-pupwB|^ zTtDdjiF{fF`+c-5tWMejzDM87%1dn)YNTuNQcYq0+&_geSZeF&Og~2?duf-SgNr*> zXR_JgPMi62`uzCt$dvF04f@vbBtw!ZqM_x%rJ@yyPsNF81;IH>UP!i3&jF^TJuf>L z_ACKqtqQaHn3q-|qX|rewPwr%AUJigQDwG+BH7a!v3_~?GYWl62M1NeU=%DskEe(S z1f$0T7>8CE>g7nkOh zAc^j)+Lvlgh@FtsOvReJ&B6+Tu)t_UF+PgjBx zk%1&QJZzFOV;HYG!-kBZNjCV7L*v5$9@k~RM`nYWF=-9^WgulRt0mymG(Fg6FcS>0 zCAE03Mlp7WYNwRJi)LzbO-@~t+=sFOY;#`|y2dN^pq|mjPxYjn#bQiOJ*>bK_hG9i zj2v^JNtFeq+KZVjH>_s1+z|NP7i&&WrPn1NW3q$h-js#5w7+iuKzA~jL#ak;i~uh- zs0!oo@CL_9?h@cMEq2cZ3p`#NPEzDc%jIka-YKpRq)&i^3>d1q?G@TO$!T{p5bjCt zNxoTV#%fKF;zna#W7jH?p~L#J$ICJ(9J_~eTBIU2nixks7DP(}G!IY7*FOhnYR!Z^ zn|o#@efO^;-(3@>FTWmMUK4@p^?m-D2unE$a~kVDSf18$moIjUP#4R795zcxH0*h3 zKK*SNK2gIjKsu+4q2j+>Y*h&NuSy^l8cdrUT4pP;y2V}7E(QlO^B7iv-Y zzBQ~>jG-S3U)ZVHS6^l{`fP_lx>B*nLOAGof?hI%vNh?apXhQoNUh*vy6Ffn=lh#d|%{P+OM%L`s!G*!VR}l>b&w#QFquI>vhMMpU)81c^EaTN@`1=10mc`G9!}MJa(?Z_QUl9B=ou*slnh8OeS|mQ8;y-Fz zixdy7DKioAyRo=8HXo0n5l<-Bt=0%r3seG}BY#Yc6iAYH3vAPcVK~N}$msTK&a*`+ zAvSucXwjC624;%8a_8f<-9k{1SAHUao9{KK-es6U;mz(2R2MM}AzlUPus{5U&>S1~ z4*#7!qE+Q7eZQ*AtIAH5pet*1i)re>TC zKt&PC%HKB!#NAhq_Wgeqo$U{y;T{beZRVt#3R&pJ{fLe`^YjcFZ&Q9(nJBXS4(Y!~ zXr>_|!Dka4_z36ExLWgF6-h|iZuI3+XA>GIy+!ezI(wq;&Y1(`%(c*0-1H&xW@Yk| zz(hdsaQV9eTF)Uba+-Onu0$XXX=NJSUx_B7xy087Ho<%+s=0((o?uVC3%?El7MD_# zblWeQKS?}@g@shLW1;9!`R!ch+tNB0B?Nva=9?oJk+jkQQxWf`_pvdviua*~`TE$syyska6Bn#wx#7;}1JS#(pvqe6D|Z z@HumUwTx1fw)%efNJ514kBDYBktRN=CISEyEK(AihPa`~!YlTw*ES=x0ilIhaX#Tz z!$!m`zRj)UTltm3Zw3DaM0m@}Cx*k?={O7l0QiiH-K}72#{$CsNz+=v8N$@C(E@6k zR`c1t_F1Ti`2Tesswi>SoFSpB4F!dG{LthO>2UlCk`~br+F0#0td??o%6Ke81P!^c z87n?N=^Sbv>6uZA;dZA@n@LD>=;nO`mR~4@qhe@?#E$hU=l@ub1O9a-Y`yZSAD!_! zMaVJMN>*4`>4SHPO~HWbH2Lnu3&UJ}v+*uNiWESEDHb|oNnD;?r{OI9o=#txBh}L! z2_2}cn3Ym?AGLIuyv8(}QJ(`v3k)l50|*QtxxYEjf!8b;_sQ$A6mpoy?D1SV=8oszl1D#6g8`=W!z88id z+h7`9aUO8wd0djzXN*|b=VG8vRly0i%CbSkp>u{w^UYONdtbW(xf)A z4d}M%*|CA9y{gAT+ja#t+jgm@Jc#RxI3x5mrN;*8u23aQJM`+*32+%~_KCO|QpX8$ z6b91MG3Jx@x7(W77WbH*;NLg_!5=D_*|H^hLf6|5=P_gAz6PgAW?~zPfwx8*O1w6w;vl?W0#l z0)H5gDWFXVgq&dwkm-{zuJvovzV>Sw+E)O~b`}^Lx{?gSu25mLu1Jq*V%A$tPj1nh zHLHF_RKGmon@JAVQNPNCE}sRb;d1Yw*9X8|X+N3Q?5o|*ADn&PzqT-Y(0sD)J{P?E zA&4X~WqZou~r8Fk41BMDT_tzs}MG$!0{W}3nMz?nNXoV|VChE0n! z2Xp={naU1lW9G>8#U!CsoZegFW-M1tfpLM#qnoI(Qo$TJ)BMiSU5FyA73C-xi)rrF zVTsVPJ*{GjPKQ~i-n_;FF+q;oWJJpQ;3EiyX6Hk;6$)7}4klm%4*Krg0aFw3WwVx_ z_0YisyLnGdXHe70s_D5v>CO;GgWggMjhI?p;jAmk2HOgM27E(=s!Z$YG&A)MTGCDm zdW#C0B51(F5X7^~cXsv2;5ckg$%A)%Ow@ zKlvbXpVsP#3CjvqZSYNFVe0)sw&gl&i9e`>uQo{`Vqkhb?ThZP30AYRgp#-LQ=0VwcWvs#_RP zuh?+y#4u4~N<(D~x>qXeS(e^4ls-#QZ18NKg)n5GZVjMT=!i4b&#+|jSr;*5^&OQE zGJ;KN)yh6`8pu*nF^&MQh}qaSUa>5N8zLjZDRyB^Z}~!sJx9fwZ+nsOI|L;lBRe+A zsM!WAtTyv*v5m-*=*f8E=xPE?Q>S9~*R3anA=Idg>|pW{Mv=E$gW-Rh5V2lfeTF33 ziA-~6S+OA-$JaDKe0i{yk&YD2Za3+@J-&OIhXKTpB=B>Ke6O}{v8&LOX|24J=o%AFO7s9et&H zHG!V(0l!i`kgSD$k~>>@MfNe2>Z3xKDoSgcLZM|7J}<>alpK35u}PhhdE&4`1*2u= zAaWlRt=H1f45e<8CNy}(zS$JKyR1uqsZ~*`uAyy0aR4YmKW2f(I@~3DTWTmqW->H9 z473a$Y;721plL?ttZw7_?fo~dA4tX(*Etz$wuuALGG>E1MZGUNwux;}XKGM+Xm&Hh zpq@VZpo%L_hxM7z)O{XS_^e%x>d(V6x~r;ob5xI$a-zdMwYP2u9U9{k{D(Xe)O;Xy4ge_>MXiUmgZ6 zDAe|1euqK(RrR2)Wze1wBWu!;Uu#U-L4GZE74VK_=8Vj6n@{xZFv4Zu99TwXP&1Nl z)E%btv~=XL#(~I%xXQ-W8MC|~eVu497leI-2<<;*Bw|{oSbM^_a};Q{xlo&FURqKJ z-Vf6`N~UZTN(Ao1$mC((%hk$zd36{CvW+qMbc~WIYxvWlO=|e?lHSHXo6B9oa=M?? zW20?nu2!g$Jy6{2lF8i9j!dcZ-~O;P7?pt?)zj#Ix6()KaPPk}2s3#k;NFOuc3+FQ zOJv+P(~DgezmMlF?XvtWXAk*|rcm3D(0Sde?W@ZFxJ7hAuXQKgFB4{9k1cL~qjO36dGy~xsN zaN-Fyoz&@Dq@|oLW+_$C=+=@#{AF!mO7+%C80nw@J35^0utRIk)aQ(y2t^p1&Lxm;9 zPlpS8c9YQ4bY}Uvu?=1oI1`Ij^ovBzqf0aaq2x8{N_s#j%`{EA%=xGc^`N-%1=>0* zx(}LpAf+5eC}{$|c%qTcm(1kd^-ju9qEVkO9bJdp_YMUuxEm8%XG%AVUb~n$t|iXM zlJbGL z6tz(Y7-Go57)1`dU)zD5MB|m3En*0n1< z;-P1$U1n3kNHxrtHZf?F8JW+k;8zq{6Zr&?DG(YBe{@yx+;4g^<&$x z91KO4V?kW*ig%nBAF3_kSDpXXH(XX%)`qfTsQutIbmyMHR8u8J6^Re*3)6x4a(KxM z9(p-5efglhY_rXRnG*VXb@uESpeEs8w^H;T%s6dS14)~uy@sg@Da#$(^AqO#mVg%8 z@)3Hp#EHX>6yHivQ9=|cb5*p|vSZZsgQe;4V_W=0MyYK3L&W+__|W%Dyq;vb*dyg? z+2+QSq;{8j#Eqp{D1#GoC?B7=xXmCAjj}l8%hOUmu2QfFSsphNg_yD9<3@Z+b=RI4 z$mpz@U?8K*jPRtr5RG+odU&@iTx=5uo?lOK*w<+zARbQu!4iASxmmj{PJ^^2ZOIdA z3C;kGD3NiWYH#yvu+s;1A~&Vv*SK|%0v$K7M#lSg*DQOhHOJ9YjJ+D=2d&;0-9MUr zt~?kYs>2qh-sWf7-G=2_y}KX1N|PL4qqD35KZFr?x%>B@3VAekoRw%lF7V+X=L5OC z?<2SWza07KC%gYo8Mhu7hVyx3H)FkQYd_#B>=xYL2##3yH=FhU3qv z3obC{Pld2NE$ZI{U1{~FN>Rai!KZ2qX>mISd(v2Fi)?Y*Q2tCzh-kl7bg zEC$Z`OOEQYr;?wcM7)#wJthMS=lQOF`KosjX<;7UF7zBAW`r(}Qy7PtlRMA)8j{4o z$ks4#2chc*mPi-dQEj(3uM!2#OP6hL*vbsgX{p)>&kF7xQSj_E#UC9C*00#RogAKS znP4`kPoa$SvBSw#H^%ts#wtwSy1QWjtza=eVg&N;pHMK1vgc8@TX!=6^eEL1nX`daVPLEkr_l$N9iF`(dMo=Cw zV1)E3YLsnofhg$)7q{t1AJ<45YCoV0< z-I19pQyo&_xNk73k%rcn5nm#@+vB6bkpAZ-slQ015~>r9gd%+HJX*kdWa$QL=D9Zv0dDxDtqdsOfMhBAW*?xM7> zcd58G4rm(Zr@=Y)`)RV*D8u6>2cf?x&3T_y9K<0rucYo5$<#&dI@%ppF>4C?^AdGO zO%BJ6meDGk^{+>uCbevV0Lqe%%2|?L`FJMPmV;85w_>_UuNx!MlMUeGYDTeoh?BE7 zGpEY`w1yh4z}F)p9449<gpY2Bjq zBk>Tm?a)++O-$Q(V8yhx=dND6W&4KBoA!R}(~XT(ue)E}9IH)6YFGlX;=AAGKY8(N zG!eT79x3#9A11q0+Gn_t(TIJoWDf~N)`Xy7PwaMB9jcFp9KqJWz6`N7%%Tyz5Zd*j zl1-Ps&CY>DrpnnV!}o}y^lJKZ>Z9AN8w-#%Ne3&>M1F&@z;W~?d~ z!jk)YmPkH_;%p>d^o6!2d;Dwc+(D+h(xlLnHZ6F#U`Vo(C;4+7OHe4de}V>0w7RpS z1Sg>_(yX)Bgw8@@Rl&EZpxIRRd*4iSVBffqmYBk3 zdsGqil3LW)Np-wxB5)ROf?#bYkS$hSZK_L$Nx=#XKoutT`^K<2V7&7Jn`|%+9mW7p zklev>^<#wsKy;|Xeb++6 zj&&cnAZQo9Q&%#F6{YYkB0Lhf@9y^HPW_HGYqL~aVa^E>^A*kWMT8`j>k^BxN$zq# zz@zmL&a|r}asK2Eb*q|{Na(mjDf1S#!*J$F0(5aiB-L7zzYvTTEk}EblS}tlatA@Xm356hSS5I<8<^U_4Coe%<&EFL?$Rog(Bzh zQeC6e7MT$paADywZ>&Bk$}xQ{n;>R;cWl+;(5ep&rWUr8H07u}!M6A60H^%p>ZHD| zOPpS$9b32wfX)~i=U)wtbF5PnHOw4*MQk8>as5RC!rvz29N7tsy;#w~d8Nv-`4oGq zik(Zb;xCKtXVs-%k(T;%D|NnmTT<#TlTuqOTm{RLn9Z;YyI#j_s>4#+v31;43b4(z zHiry#;Rn@~y(g{ghgR8acU4l^lUWz8X4q$AcUaYh7t)1G)rAMN__pE>1kj`D{)Npl znrzQJ%Q#_Eh9QHTZ2$}gWo9g2sC3oMwsA3(L>*`SSx(M2nUwdzcJ2@ho!~B^ra9$S znQG8CFaw{t0Q?3mZPwkzk+H(pDulLKH`CogSH@BX4(d&2vNFkzI!ufk2Iu{8L*ulZc>eR7G)P=I5 zg~3lGPIAislxqJAPm(di?AeJW50UJL&jSWBwd-19BU!NGVqWkNb`8?nKFd51B zBqOO5MvK;G+Q+$R8Y#Yc%N{2hsFj9LgAOZT)PB}8Ni3SQvPuioh0^2qb^QDe1zlg0edxJlC z(cNfW2Ahh+im{@Ka!aFsvUnoMDy25C%Ovmd8QMJ>{wzw5toMx9M^ufroGh*G|Ga() zZzj5rKnwIuObXQq4&ouX!UdaqC1<8HjcMHE@qS8KL1+a6*(ImO!!J+A?H_}z*6Lpl zr5roI*8RNV>nB-(DiWTk&^I=69n3h@JSg?SoVEA%Z2@pL+t*d&{Bkfv9{zDbU zMv>!|hSm&1cIgLZ3>tSiLmme0o>=xc!7N7CO*D2kz64cHWwx0-DpaXpaqPYWDQO5$ z{lG=IB9DM#VpH`)CWB%}aKdPi6HZTo!C|ri|vFG}r}k1>L&nU8_!Wr+Xfw!7%GSj7((cFx`DUH{dz38Pv0VUpvT45XvKaeVwLR z3?i1CJbs@{1-nzsX3EoEbKbp)8JN6q|9zqANz(`LlzKU5GvhHOgj^`Js>t5#7|xN_ zOb!(O$7)(Kg;G!`xo>nL}uO_;0!r9u3za-MLrTp5fX^Y+8y*`CzuoEo0a86kQfJ@I80IFL4 zR;&p{g{}?Lyy)09B!?*aXh@*WMD8EJ0Z?I6DXgy7R*#d9cNhf}YXj*Ewvm}J?q68H zjY!Qq!Otp-YnfHSNS00`fw(nR;yHh& z&gKCA?E0+9eTmNq*A)(OD!O|}OecvLD-U1%3B(ka`vRJq1866(W7XE}`>te5wG9V6 z-r<3_Iuk%Lu{iD5euU7z#`ybRHOe2CS=#|~G*3K=DMb=k$_K-nHx4wZ$Ld##Fg@t2JL`WNmW}iI4@z{Do zj#nuRgz}b?Yp+)zw^EOvAZC`MZA$hU8}|v=g0vmsCv=yIh$At`RNM`!qQg#BQKj%o zE0r?Im9-RmP6gtr)AiC^T49fRsCG$^VZK_(TD%EcZ0duon`_2&08!imAU+=eAtB|@ z)IB&HYMM= zc*<~$f~$7MF*)qu76?f8Z9W zZ1;mfZpFZ;?CXim*qceJQg&J1Pl$g~-uYE|{g6NGK$`JiEh7kEJX;VeuDdAM^ykgU zQ;IIEFgxv?JqQ{L^a$YfnZ43rD9wHh_brDkoGkBHvsKD32pA}pmNoQC#^@3IZ<2e4 z(KFidLUet`L-w+XRI<2$e|2F910K7}_yEr#F_=$iP&s8f<<%5hryS3>!hU9j$s>x! zcDO4LyqRB3Xn@K@PUt9^bkWYfsL$nd6`E2PMZX=}%os)_=J>}=m$h-w-gecEt9zT? z*bmJ=Uc=lImCNO6;XvfHOY=#aYeyufDTj?n861)Fg&axt*Igz;PR;k2$>~kEeulq$ zEEka){=lo6?|z(%hBpOe+wdfgr!A*{_(fO=e@D-E4Vm|4koln?V?Xry&PGmfW#B2) zHI?`+FDmy=*OkAX{_frteeT5NX-mhCA@_Ar#Jgd+$-027CudpDP}Xl+R&vijtIxGu z!cB7Dc1gLr8z3$1Te`HzfMoz9vAd+6p zBKdDFs`R@b5IAOJ1lz`%4oAeG-=1=gB)=G+g{yD|O=@xUf2!LcD(x9~r(GlJ zFET`3teI^;X=yeisJo_$|IS4u4J9tuWGDPTO>8Z_%QanTZyBnq$}4D}8(8kHx#&ta zzLH|~Bl-Y^uH~~4OZ(0>xvjc0#7%R!ld@ut*-A0rq!?h(oi*`PrLwU=YTD{oDT$4Z z+KgM2`n$TQyXNzYmHIZP)b#VqlysF#n;S+ZeF^Y#?n9hOk#_FG%FW3OWb07}(}wGw zKYXqZO|w3xtY5AwIAp2%H5^beHPt;^Ro%>Ol<~W&1Z&VG`Jo0`!dvpu)$ZIY)0!>q zvZ_prRm{7p5-i8nRSCyjC-&ZSMeSQ$Q6^@SDjso@F#T$OOOKKa+G1pDN! z;R#==O1M>@JYJPxpL~CK!jII@o<1y#`)d09Oz1$j8+)a&0i8#JA-`PI{&SNRJ>l=jp~<%Cwv(VkQ`9kP`J3Gtb@+hhjgEfVkUM0;6gZ z{x|Mgje)}fvinGlCTtiJORh}uq{Q7&HD;IF%;Zc`t`h^lmM-oIOYjo01olIB zOWWygDazQHKnC?YEv0MAlm#2rgsP=$!x>7xJ&L;Pchv7l*TnF7`5?a6pFO4*Tlkcc zq;e-R37OTUJCIBz=qdTfC8URMhP@KUNfe5V-rv51COzh&@-O(W+*4ofuJ10_QwI6$ zqVI?PhT36i*1oJ2YJwiz%QAvpd>zIAIv;gE6Usrucg)}*|jSr2Ht*SsJz&q>04{?-h`N#Jaq5whtc6TpOzU)uM%*dY7 zCWnO38G}-mV`g}yr5_+o(5RoU1|}nk1Y02}DkAE`=_lk1Ef2pbuGmudllmxRt4Vz} zq)xAGP53-yKWOK#YD)TIL&Rr8Jl+@1Ww`!*SmJ|9{H78Sl0w00Ay4YnkM(M%im|r> zvBqhrJ=_gpQF=!rQPI)~bH;fT^e>H3XnxIaw}#XHrO7tFW%rWo>)ZA9uN!Gbxi|b< zz{Q#nkVGXU3A%;?lr?LZCDSA#lOWWk%{u<|6#V#@NVBz8UjOBoNCok4r+>-Iq{CU( z6aX2=Xd``R6FgPQHl^UTH}~6{5Tq;>NFKJd{@TRv?zD*C=#7n@T5PBodagzp16Q8e zTd&a#f6Tn02bom#xo_sKwE?z1TVJfCGm?P zmPtlZ`uj}czAUQr)m;)nz*9h6KTbUp<|SVyBWfjuR84B`W+YwGeV;qF(ud+Mk;udM zHZIxVgt}FNB?*nXGlHXJ{!~;zC41yS3@`r^67%4?%hb+Wc1!kL!}3yxDrsEZty*a8 zhaSFJ*hgG>3LIBD$~6s84gB#@E087+TMiW;sA7%pQ|9kSWGjyF*Jr$)_qcb&w<;h%riQq#}p>hnkWJpCJ1*-yf&G`k@_ zmVM+-2)Dko#?ui|1YO*j*+jJukUy2J<}Y+O>3u?>YHE4NMVF-0-AZ|6c*3JDT2hna zJHr#cH$35o!xMfyywINwPk4sLtC{Zg+iS(6H|Fid1qau(;c`;#uL}2T`gMJNSif!@ zp74?33I8xW;S0kP?p0fk0`!LE+iJo89cxmzYX(ng6+$H|T}`8Zx62&w^^t&(jF&62 zj;N?r6*r}}sJp%TFEW$Ph_TB<-W3(1)ewTJrsik;FlapIhYjk*iPb=h$&9BRIGJ(X z*_&7Ghkg406&d?>Ush7q-Iu}s9~K!6`Tl1m#x9nfW3(KwS!}z76W!aZCB`oIQzXWT z-M%51St_`JLfIw4U0lMfS6j?PNWdXbo5NE_N|Q&`NR#%2G&#$pN#C%*pTK8?TSjag zQ)(YBN={AdYGohL-0|PRvb<|~acCL;td?>6p|jVivs0f}UbKa0QIv8`y~dg*L{QXF z^tO9W4MoG*E39phz+r!U*b|bn94aeK9!F0G5~Rmew~X(LETnxjOuPXB5dkk9Gkp}(-`b0V1=6KMM@ zsAAWH@?geWb)yf7?1w?QFJRzM@wIohlwP@86}*6A1M~Kms=$84S)I?Q&xt5@*xuiO z(#nbS%80v7*-|xL-*B#Ym9WvFr2iO7`p~!>D$UoTzc@fD&5b+G-j2p<>;BSeX65ar zLac@uS2;hW_FM%G@*$Z;yb0Lc2MusZIc&h*t38OXxK-n=`qF|QqyCNm+ADe#YnA938cO+T*miXg z{LS*=$8F24`Fszk{D-m^s8IY1sCJQ(Es*lWB1a+|%Ko(AV$MEZis4 z&b}YhGWGWH&|33?r@JIue|hE_!pwyZQ6pAlA4T~t)sR14Tmpa2EU|)7dyCbk=)auk zqFNDwDf90ys&M-?Gdyb|R&v~BH78y&Y0YN%Nfa$qp}6GhT2;U!NMT~LHp=WNZ(q>YdGr` z*<%ro;2SwP3v%4qr_4A{)|V%+O%w6f+p#rNO*Xc4WG*kqE6R=kG4W_QHp<5&xqGl5 z)0t^wN_wVW395b4tn-R#d@w<~OAbj*?q-0cShryS=3Bo$XJdqYC;DCOObJBiR$3{t z=)Pd@tN}D7F_FYQV455pgNf$i#6)u@eLX{1ac3CwnKZenoY~f8BN~ci6jN9%8Uc#q z<4FdH*Rwk{0uWsl87m%~fa1&q6mtZLCWAv+J&oO|0Rw~0r25+g2;85^`1N2DjfhLD z9)%uHHBi{(4Yo! z#C$#Q*5NV1p!9xB80(=zw_T{(25sIUl9HSRsXWVEtALdDFewNR?FNyKQaX z+yGr5E9y*6-Yn4@U;=T$n>F}mF4C~bovMRVwB7ASU2L{Dxi1=tgm#@J^WhG6Dj$pR zG$_n@oJ23T;Dlyn-H1t+a;QKfo8P1Bvl7Sc(7k}3tPTBaR!4)Ha9~eM$p&kddks^= zsQD)P{DAuWw4ety*~E~{#DxyCY4*OuS!A1L`3Z_61g>c`4`MeQ=ONj1^Q?Ra6Jn5r z65$2(n+8o21OjhsQCuLkY0NOzA1i`^zCSFY$y!J990+Ipk4%TCzwkXSlKr`W~jN0Y{C^YRS`E>V&?m%e+ z)}6g-+xo2VRBFNpD8-o|zl;zzz}6vQ0|d^54GA(s$72r_V@G6LZ9$Y7ZXmRbxzsDt zrHHmu@G;hT#U96mMPVu*#ruVNFGjo7AH`H_w&~u?L`s-(k(^_cXPWXr{T8vHH1+xg zD1J+RM#)dEFc$r~gvzLd=s*(B{Y&I_zxlh5D7#PM=J4j=B3Q9X}wyavS z?aWo1Ueh1avwkSgd7E@r8LGi*eISayR9{)G1HojG&eih_NL9)}B@ZJ0x*QLd>1x zDt_Kvf&`Uxo>Os#pP+1IgvmBPVUCY_gZrR@LSHPN!BjsJkp_!IdY4yVl>;u4;beD0 zg~Y|~Fw-m{@~kk2-HB=D%psK`+TCf&d^DcDik>mjJ(U6{I9zls1UmwwKU(^yqB~2B zi`AVKH{{<+P%cl@rKZ$>aVoCA$I|DCI(F$;d~(IL3=;HG65>qh%3y&2(ZS+bDAH{)H@nS?`9$f4`jzX-_ZY41i{Np9|pfGKi zWrrjLUbJ-MP=hpe_;J1ZMXT6qsu`1y-7A$75gN(6H&QyRm6hOn2=r84)(Q5I6kk`8 zMEO#NYT1Ph)yLHv71SP%jxwF7p56P?H?6iQZRhNrtWW+$FAN~+;5@eOr%RQR0HEKL zph44A^kWpwFC2;nY?>;W#!I^2@i@tpf_CMs6j>j&!u?rDm%d&+WZ4u=-^vtI(k#U8 zIqv=B?J7M)j3 z&wwShyv!mVcUy=wE7U^w`plX4$11bkzWcZE9UtM?`wtQAP?$nqdH2N&2>@p09p`T2 zi+1U@x=qU?9Yj!=ra{bL!Z{Y*X@F*>P5*Uhx?a@j#j)v&L>C~18q%-5o5;J1HAI&L z`FNrU(G`8Bcu1G()m!Zq34#UT=ostzCHh&epIA!4`t}f6@Fje6hrYQj6!#Jp*T+Z) zrPkusxVtm%CZ3^R93t%dWPP8P~>Wt4!`d)sa_VF z|HWNoKa_cAKV^P97nSwr=9l_OS{2>@+aaXv18!snXx?jtsT}_fe_K1~)tfi1+aQ(%U!R=U9C%i9K!SOz*AyU7TpG}> zz}wtKylshsoG!C1+XTXFtE`P1Vo;WRUnOWiW8T&)`@|&sViLwHfo-Rw6;3YlOH2Ob zs_a(Sw2=KTX_3n$;*jF5kz z6g67JRGeXgkC3F8`r*tygr@97zD$q^l2igfNEaeh_6|8HZ5(e9g>syRmr$wkM$|eW zYHU8T6~<=XTaSXHd3|62mXdFh$Wx!?TN=Z7H4a)>8@RkncfeV|GDF{RSd^Abp zxRj0BW&z@?)vJdwMu8biiQn#nC8K%6;Jfc7^kFo$ZCl^^J=vGrS!OhRj2eGxZ?aVbnkG6X225g8|oxO6~S_}IRbrxe9bWgCQnh7h_WnM^; z#+R9148mj20nN!k!ie>SRbgm-2@19~YuAyP>*Bv`=)6XX)d%tsZ(t4+gx4o>9DI z-t?&2YPDxMlwrq1p6f4WQMt<&6_iIE?iVZ@aOfTGSOYRfacG;;BwHFw4xHXuXv|BVajB=!>=x`rN0kBe~!~|<2qO5E} z=tw!pb>Ej%hyus9qSz{`ygeJB6E{y#Sn}xRqk7GN#Pw4#;5RB z>WP*zm3Nyd1jdBYchyNhQKv0KExGgU+QFf*dPe)AD_fJ{QvHMmuK5V>2zI+-MZ6rN zo+#*@)Krs-?nf(;HmvL$Gm8R@I+7fCS1N~0{GzgNwXM>;R4dBys5*avMs*MeqY8#Gt$uzhFF6Qc0ovLH?(+nPcEzQpGaKhVO_=381NRJJmeGg0%NSo5 zm!qiNGXK;v_l4YJ+}qV60`3zYQ&UYoOd7A20gSq|6&(q)X%5_;4iw3d%7Wq5p~w=@ zQtawC2sT@M48hHwL-Y(9QT+sVxntla$4{g7p1wuQ9ED4a+^kYvTMei`7XT8$0XB4d zP}s%&bY!;st~xTAE{=)ayRFZS?nf8cd8bYZLZl3~cRC`j-B!;RVRA9rC0~eN2TRMG zE)bfYo2qLc##kVf;!qZ1w_}N^9f_~s01+awg5t}#<^sF@)|#8orDc4F<0{@rRyIzZ{mLIjfdW^4b)Mz)_JDrFrI+&NPw z=>fEGMnx)L=-<7Ca75eCy#HkeXYV<_mT2%jqPQW<2Uk~aW#DqphQKU&1&tOYIr%;&cR$qQpQ|2Q>Um`}iZr=zMh`ZG|unWLOy%cSz zsdLB!wi;=S2lQ++-qg5t>{wX7Dq8oLs(53lqM*elg3ONL$d0b$*lv*x8HF~w2{u!< zREkkNAcgigNS)0OJkH2eO^>Ylb*ihFjv>nLFn`?7>A1C5W6tOT=X%|_%Q+pQzzo$g z*rIiZ6PwkEbdN}#xI<&{PIL*bH4N~Rn24r$^DfXwc=NrgwD$oQ zY*w}G&1zY~sZ`0inJVlN6?RQkVUJgR`2M7@Z&szJ(yl zcI>Xd0F)?BhJ>%xNDVDeQ_=-$1@AW4C_?ooic^K|xPNCQ_3?}R$zPXkbF*8b99V&C zrCJzH)hGb#a!+`DOx0_+XDwhNx==*FaIr7LthU>#dguZ_jcr6i^#*o zznS936j!jS{yw+diYWk|F+Y-_`ZC*cU~`mu#t?a0tkewDXRe0?}lqjd@QOcpt<5L;T7>CW8;aK!($!BlecNbD{_ zKpE3!wU5E*9|AgF{bxwX1wZ(KsMKbZ{Wjw#4OyCX#D}l%@y*lpTZsE@P0|fn4{8Ew;7cV0ut5!darL1Tn)?nNsIO39y z!O+4eDe3SEA<2&to(cKJa4Um+0&6p_&20V$rfbY}9Y53zo7Xr%pN}%A`h!?CAt?=U zxAk%&-@8rgSU@JDrW`XrUe_uNfHu!yRPB!A<>czMI`E1w0GoN{7i?IrF}{-%Y#FHE zYM_e#B)SK}#qNXDGK6tp=VRdwFNBIhdV;Tu-z z*x2289w|HuvTh@@LBKr<%z+GmWwPd|U%&&l8u5T7m8kU4*m3YGl_ESW;cPoSFm4umLO$bu2K{C-=_-IY)4Iq7Jjcf8sh0j4VvStH2W*Qz2cY3e5H&sVX|TDI7U@-WWro7{l58- zB=w~_V7{UrU{cWL$4vvn52t+g30h+J+9koeCTvE{f0Ajs#SK|{Rc1b2S5y7lV7MOKNpt--1zP6fz0W5Pp5W+>0zztG2S1sHR zGI=!G%$)?!Z9)melILeK9HK112%$#51NwEWYqm1MtIXlG1OH^bQm7GxAG1cZ^QKwb zMX0u%X;ftVawGadm-`@!nLnoekP)ig%^Npv-n9F=>)qGu{_*T@kJ{$_yD2bg70;vY zW}|cyXPciL)ZVpv>r~C0?tSt+LXV9ud`ORtCY-(EpvMO3YBkT9iaJvt$0O9oHmk0> z6ed_dptZ(E%31)R3?W8Wu7G0Jyzq+)>Fe4jh`sP!~7p7WK8b`HEUYoAXl&%B5 z*kJ`x2n8hW#FAQaZzbowLw)E_9}beMTu0foC2Y2KASly{j@jK*8Yq0V;M1!jelV;E z-+|T_Xmp_Wl^!{6MK=jACk2(RaKZ+olYx+5%PK3tbciWY6$va@P*AZLkwrwM+jW!l zgB%pQ25GhbFMIDDSoc-l|Lf}bd?eXgwytE^maKa%uXt$K&Xyb}1PHbh0tB#~fJq$N zF(kI*k%R=C$t)vDNgDzUP{InMw2acS!YW~wvI>;8lvOAJ!Yoh--`D$jKA*cR*|IJ7 zM}I_r=zhleobjA8a4#>{CBpEEdJIV<^WYrwP5Jp==uO^Hu0iy^x(MiK8ne zJdDg|RV7|tuErp;Aok!O%19g>#IRR<@pgS-Ol(KzlmOy1m9eQGK*Vo=W}eL)_N4!l z`H*WS8fHO*ag|MHNg$ukL&+I&z46_RBHhDKpL3~dxFGO^$Lo7j|64T(=Xjr5UG~2t zu3~j`vWA$tJ{?Ny|Djtwb2Nr7gYTJYNRt0>ms!ZIC0yTf;o1%6H5`)*Z7nt=izF4m z3C5&5XGxlVgmER*oy9gf4w%|)dPihC8`q|H)K>6g#ros+=*Udd6UUN&RK%kMU3of; z6@xHYjs>cJlAIwXK9yC5O!N9ljiDKxD;aFZG4O74b1QF+PG)3LBoLZ+F=?kNZNO!+ z2%RgDMVWftij1MR(!7fuHZ$*X$u@O+ZI$g6`)&nIrQ0P^iq*Ep5*u4U%NM*56siNY zr2%e1OzlSgUdn&*m8%fEBwB4i1TgZk8U$uI6ona#u+-FN8#SQNkT~_Sh4D^R{1dAf zdZQD`Tq1yi^r9!JN8!DNGqII>qAT>FWd|!FJm~DOr|G#u2SmwnoOWH(O2s!Ec!J6= zC@bU4p7!5rro*%#IgW>itW?;=ti*4<1V+x-;`Ff`fVr{8lyIYyARTQ*ZF8$@yI;f7 z;Y+k9i7R)yannxTD=bFeP`Q_uh}lY@xzs%7M@G0TLL=I-H9(-@)C*-pQ{$iT*`FW2 zdK=U$OVzKS&SlKO#WenWZm)8MwyzGzs68}cjKl-!2f4)%vR?5eWJoD% z`|ni$UT^&q|Ip6qb}@Gj{|B&C(N{VG>jq(Fi3Rz$0We7|#x&fokH6@HJJfs_z`lC; za^FyW|Ka7dTExqQS-_0&mgKV70Efte&*yEiDdmr;dKPjH?X?9|sQtPSZ7;&FxE84Y z8CRh~T@k*5N(|)%nq`yn5>L+o_}dai%>=vx;7U2tJ$yoo6)9aDEVG1m(kl38tKi_T zt*|zzIJx>gz`7;+z12~%C@Td{g3}?E(9eO;|8A*c~l1|x&o26%vX>CX;X-*8v zeUO@+P*|$(tc%~nvz_MZlIPg_2pIJ4wD9X^YZ1aYQLJOYG%7#Uc%0qi_+-Fyl1gZ$ ztg-h$xA%Mv6koz2w@EC9pQ5z!Cx2p3PE!NY1yVFIoV7z>`M*1&A|Z!*dLcoZt#R6c(rA^igEe!#UC; zNi}5zA}*p)#}85nHza4;cMZwe_Dd;tdNY!Ue{-U6eiD9!rU^eCPIN~%gu#r>=H%f= zB;VPTqln%&g*$maXDNp_#^#m!5^b7+8nqKyH1tXMAuBAUC_KHRo|SoCJ~r7|9+_tl z1+TVlN*hPT<}eigqF&1&w~bDBS!bKm0Q~trXz7dHwP*wvCyg?_AMjhE^7XV(+LKdW z0;FGKwwOH1YC|l-fZ-}hWK$uoN(F@x#Z3HUyW&dF9@2I~bQl;Z0C`ERtia}x^y&=M zpkX_Bd0t$k?Iz-?H8wSLvR#V>S9gUc7GjsWGtci`&4qT>XKA%wZHTAoM+&zgcl9}i zdzQZb18BWe7~@PYrNVL&idkR!^<0R1waq3T$_+qFiOfjZv_vma%jqNH!t^7R<&de{ zo7bw%`Yy27UAUKpIu`u#lXxb_i}C+6iD%;c?H`q>GI6j}`8OVp?LRDIk8ECM?9p+R z7<-s}R+=;IRSuQoGwsL%wM@HEv@tWEF_yLig*<5bv^ZTlqCv5Bd8nD;Cu6P`E-}`+ zv1r(*5pI^P)~JF#{VDss#5QAa$H*{Jqc~PxztGWP3_(i_xI~_8|Iuiy1V!<)pn_~+ zLDg2KPsa5v@LL_rJ7nk=-of=wMp~1wGnaBw8#fyM3du><_uOs5YRcv|5SnYg*`Ma@ zD}mxi)a_9MC!(ajaG;&L$+RhprA-GHaLGY+;= zNl53zU8Pz!@MQr5RCf{1IJcZ%Y5Mrj*UgPH{PT5X_nZesVBTS$i>^QopyZUE&Y;q? zGwSP$KoB|g3*t+ z%iS&1*h1Nitvjyl>nOPvTKg;f7F)OV=0a7itMD0BuPgJQa>EjQfRze=ZG5PC42tj( zrXps^cqwbjI9aPEEoo0}i)^#RF)D~reRLSX}T~_7B4@lNi?q6yiZ-c(Hz=La-evQ z6JJ^S*0u2S18G-fAY+`Lg9;A6Sct*7!c`q}n5F9$r0; zZ*$?h2Mny53-K&DD*$(4t?X0vHmg3R#@EYB@O=m1NQAfG!Ty07CFzQb6I&t&o~F^b z$nqyLUDLuBz!;56E+9+2u+?yEYIHsl=0&|Uh`AkE6NS-$aaO$G8Hc8ml?`uzQT081 z>VWCvDaq3g9t{M=$UDkZ@$hDHLk0{QUpio%EhX8xoz&A7Tl?M3bE#W4hhepbYzgIu z=W^~gw?$Jpw}8sn9`vVQcHXtIgJsemJ9>FCC|hR}=3)1Ks05h%?DF06uxJD}EnGNY z#3vi<+vuqI9?VX{mw?{zpbhEXQb)g#4&Do9{xXa}^7}BTloVIPm<5*8kD`tJou#ph zTu|~KDJg%9lQlD#vo(`4X|G1Nf}ukrl)aac$yH{mviQQ~pU14)Q=b(iJntxuDhPkp z%exK?XtDH|Gzb{1m6qfTTOr%r!i-AfDQQK+=Bd||JT|Mi>b?~=S7cdyGtMQEOrQl$ zwJ*kkEJww(?jh6Yn-=4q+t`;kl_UYo;c~`uN#N8>5^(k(?+`?;1p{pHr7!DY4b4HgZ2fcL`G}WHyPf^&YO^D$1oK%nB|@SQ%&9|YHj0Y;!Arq z**ED_0Sg=d3k4i!>RaK?3mxLlTaPDqK1p#wM`%1QDY|Rz5l71APn->Xm^&ZG3SALx zWZd~dHfT2-vk0r0bJ*kxT{v$K(!n2!Ri{yB)k_+5nDL69T&7s6)I31lwQRa{>xJ9d z)!!FinaA^7c&TMhoVh5roEvA(i7gBCUtFe~?uI}RGmYtVA4Hs@5bBL>&6B1!7L#_g zpUG;u(mnrr*BZ^STr_(naku60zI=*Wg0bhw_L7ccDn6M!x;o4hdNTzA%v3TTQr`(% z)$4j6^>&|n`yX`0dMk}V3pj;rt?m5es%J_*2&J;9X_wdb#ZlR=mi@9W2Kib#HXqrHtCnBi+I4j3=ej%2ekQAT8HzN zhaQT(@ESUg!c`9R3>q!geuljW-d%oPdKlh>FLigg&)T&y^jLf1Ly~Z*HAl`~DUHqu zcgGQH?wi*9)Ntv*2!tqnh$=#|#J+wj6_p|IWdTQ&ij=uTNRza=H#RS#;MVXatD`ym zvs@7~OZ_MWoKtA?;Z<_sXW@iB>P@;{n2i6LqRIHP>zIrfzBgrnn>(-5I9xRyzDqyp z_cX=^w#Sb);_WqUsdyQv;*#*7O|G;z0~=yk1&f4oTc8p9rlp(yT3m%dN*DeFS2-qa zq^wcA=1-Y4<-bLY1bCOLk2ZRrE0IIxyDm)!ys4;8ayQjkDkHN41SUc97ESE%Xd>vK zX_1ofhRg%Y>J@KbTR;~g;J(D<#gUVXa;sf@u1<^LYP%+?8?xx09bEDV$*z=!N#B1?KsUcpF%r({7i*m|zO6zxh*@W5WO~U2L}a?b zve@t|6??9Vx#~aD2*cOpl)T^gi*UIFohjnG6SMy$k`NMUu`NE*17%#Iaxu^!r=PRf zDOrygqo1T-|0T}3L}qpeJxafK;X~WZ+kOy#^(iidgvh}~;yU6tNP@pk zp&Y}kt>xkE8K>EngwMli*2Chz&G})LF;84EDn0lL`0iy2_duG-%ZD0)Mm~v_2%P;e ztj^x9&UVT*67{Qg;ymj({(SAe7U+JVTVmYH=_$(h_3VFY!q2x{(+Z4C=)-;7+GtDH zlH-Q|l2O2#S`*aW*(O?@mY~8@PR0jlY9Q;YO1igQ#webqhto~sUf)qn*+vRnh>9>gxu-D9QXVTF^n zH7DuST-@GJCc%ys_By3E4{u~q$ z=amm%ldE|xMIEv&$7k%HuSr@9oKVLt9eNEorXhSJS8&xU@sS;5Nns5Z;-!W7IHky! z;Rw)?*f3ekY|Ui0a1NB~y%q)5cP6T)7w;OU7xefG0oTRpkfb`ReUMiF)9m{@T- z*jd}V7Wq<$3B_`&ol&2h#AKL;C;WUKWw}5|$7vnl>cCT-tccfNEd3W+X0K%zZJv zr|Zi!h&~O%u1t-|aWMO|R+2Q&flz@sz7ofY03d;9Jf{D@jOqV9h(72@ zr~w#!p`2Q#|0b%;hi_4MYPgZW4l&x{A@TIW(4=t9%Z#wznpzEZhjo{tHwuM^fAh{( zv+zSoUK!p>jk59*2xSwbB_@=i2@#*rSFr7dyXomXE5?QuFz>AYH(o0SsUdtNN@du_ zy#}p&SG@ZOMTj3@WjzFZ~p$9=7 zVCVNg3pCslJ_4fHhR^OCUiBkDyhjMELMDw@o5r>|{1vk&oUgzXU9C3syauSW2!Bmu zVpE$ut#@p*aW)Nj;KkbbWXd;nTfPh^#Iy}YFy$SQc@_w5ndYC(O9^6)MN$VVOQ`cW z-2(a-TPLkV$^vfFN8e*C`buHdRrLx}hdzXteE6XYULr*Z%Naiw2-E;Rg|%pzIUn6D z*yo`nn0%kziAO_>tI#?!zu0lB`C~}gR2uyMA@A2xpT|*Tn$FB)J1SEaA%9jW(^$QB zzpdKCwbCK>@ai>pYfY-%TBTM?4-(|k8YyQdqS*=^9uBdo#*M2w)0|&(7yLN8*u(VO zh^~U)hUf;Vgt)3O$=;-*qZCaepWB6vPlV0vs4?4`J1p)|B8ei0aq3E$O)>Er8djXX zwEI&Fg_;k)W(pU{5B}VtQe5i-Z- zvV5^XSx?Dy%4uT_Tpp557)9NdIvwrkb*WXt(-#pTW))HS}s~_=xptM);s&^P#2F zZRChB@C;X}qszm$jTthU+ZgVWi~{9UE|;~GZ;*j;d3bkP#-eF88Y|u!K1*@ZMZ&m^ zBG|*SQ~Jd4B`aNu!mil?nE0ei!qXFbB%ThjSz${OOwh=&P3hU?-m@>4d)6G@NK;LE zJ~MpU2Gtba$)MypsWz3tI_0+nM-mp<7iSs8T$k2UWNg?Md*nv5A_-r`2A(ZE!jWv{ zecjbOImIVoTGV3v`hgKoO^%F$6_I zI=A*K=00$kQ_TwbmO9TkQMWQnVm4D>Nw$OCSTm+*63j4MdoS^D_t&vszZib>BZa0^ zS1jz$q7hNioV1_N2d3UN#&2i4$&QO#yf90ySP_6>i}t^*OX^X{S%|6#>=-eSJ_k!u zHArn_gl(t?8BAUBr=&ex?+zX`XWbNLAfFhN615@$8{cE!rWOq#cNdZB{Jf~#&a&|1 zx&exA4d2H%S7!ZYR5)y4J^CCj*@h&f)M0jRk`1G>Gx;o-KwUu}J}aA|JIgIZT*%Ue zM|@??9Nh_1?=D%E3A}H9oY`jPg(5kbq(GMkSL;k!wV!cZIQBHE>3^MZf7lM4rMVpx zORV5E9gb9DkN*#`^b?=TN~V1b(>WIG8lL|k9-ci=_GZOiUh-y@XX`}y`E4#V&|Jxw z4g+6nGMAO*&&21D(}ly6wTH#m6w#Lu5GKqgTrAw4#Q-Ka3R}8| zeZ&jtbnc31^(AoRpx*RguQ-)~0Ik%BQIi>dzUXeAwubq3cuz~XP(@*_$_B#oUrE>A zU4s4yUaA27cAJ170d&8f0qVC2c+uDs@MFg2YB={ZaOki1zGR&T`mtqUY<7Rgswr4Z z$u4y3u$)21hBF_fdH5K0w}jXFL@Z$SU|L^5n8<)GSY+Z@VQ`w~kzkC+f~zHf;@6zy zR1)=|xO8+>DH|W>ao<$HSS&;6$6)jX!$*%Xi&9nUWZny7!&6FMlbv9pSsyN5D-|ha zigrFT|Cdv~IH&|hk{3LaBT6#YqffliD|62PIIQwAlh8{O^) z-GpXd(CL zP1`q~@{Elmw4zKXoTP+NKuS|-zz?%;q#Q5p8h?5U{@Nz`_D@Phb_0Z}Cvj`YqT|(?IfxX4xQm<*U$) z6~+doH-ghO*ncuUob?)h>MMV$@Cy4vdVI^NY3NTLC31pUCQL~CFESZsAl#1BWD9Ls z622)OO)Kc`0~Qw797vn%4?M;S!R!@2GHq27Icdjq0+<*3@bvWH3Ddp_zHc5WClpDj z+5TE>dUMB-{I%hf;pz>=8*+Fv=T;3QYhuH-^qg;5U%df30p8d$ViuGpPS9qp9u7Oa zo>iA&2NY5^MX$epWFKp?EBs6P;B|^MHNz!O%%~t0yo?Fp4k_|+9-lW~_DTFzg$3-* zl{v#DDAR*qN>M*-om<))XY{KuDTrF}Pn{o^3acPal+gy3+fxkD`9dPGUYUNs`c>?V zk7|=DMNup8!Y&GVo4dy8@oE;*Q^(%;m8fK|`N54}F7-3oPnNqRze(D{j$Yw<-~aq7 z-!#rLiZ>8OaFnx=i}5iIipC{jL)NAiD1-=6jMW~VETu+@@^DP343MAlYDRoNlaP}0 z#pGsTeS+@_c9DeNAWE^$D=1&TAcv6k2BQE<-@^A(!#@WyVivW+Z$uNpLL4cJ)yve( z*Sr~-)oR1^zH<1Im!%sH$-@6Dfu&K&5iwEwn^4pE{@+ z6MOH(T$O_L;Gx`m&`{{Xs-T4Axxu&!$QUU9dhDw2E>%rujn=(j9D=0jPS=~JS!k() zNLD$yD2|l@|3E#d<}7&-Zlfp7;ir08$z_rNo)=5Pi_B1L%VJD?`ca(T1e>4u04g}h z=W7Z`G*?5cEn%<`Ykc?k@E4c`t7_IrGGhHrh9bhuT4kU6TIB*2>^SuLM{Z;s8~sC9 zsIQt{e^R~tVyTxE`4uX{k!+g3dYD3AR82o96{43mVej)E!7O};chKoWjrR_UEMdGS z+IaD7@C%vvme`kvzznzXZS~l!+c!~NHM{h>Qjfl3J$fT)_*>d}MNqgxLJqmRkPtu8gr^ALYOfKnvP#kP|4 zrh_ZPzd>PVhQGuD%pUj`aR((vUF#Mm2tM|EvWMqw*Wh6|*Zti{8BJ*?rZ1;o#vX5y zzcZSfghbK=rxs z%lZo9WwZK~?2}(O1HmV9n@Mo4@lReDDn2=&R=(q(xW3Sq=7-1WdIc_dDIYBfA3A)& z+bC%Ak!4gBjZ38^``m^#-lp_6?i;6#l+(VI`m0y>`!uNE9yF*odp!W;^Snc5;eOoJ z{d$Tl3HOfEbOjvVNI@gf!VsUmSuPsmQ|i|pvhH+PZ=g{1uxxr?-ayqRc;k?> z7$VUZq1bH*x=1D@C9977eA^L~{;*1Gk);wSIqzp6n3!Oi@|BWlf1A39&_RjDkXHy7 zbn*9~(2Q6v317$AVJsMApko4lK@C&G2aJw5p99yLR>?*902MZekC~@jqFq!q}I4Y>$#?|1Zd7+%Jt0`lZL zY~-b%0%v~?y9dCzOu&IfCJh(#XBwmrUDKkRRU862gD=m{;)CjU`|26M>Gf| zzD0%Q;lGBD<;~wq5jiktC4KCB@COKW-Ta>fAC?+bt5mR?vqSDCt{0!U7W5A%u&PSi zT$$di>WE2|nm8P)>KrR2TUFhe61?JAK~oGLr1)j3%ZgvLz*#OcbiiXBZ|KJoPWej+ zfHa9_locc0K0P)=FVkRxe(6B?lLH-&1oA&5DO9U+X(}~0hGXe6dFZR|PiZXFU3FYm zT?UBFWIfz*#Uz6J7&G8KysQsxn5n`R*^zi=#?h&nOr`rWrM3yJ;@Zr6wI+>hWn`d3Ck2O@>ri|P0waUBY78;FG!1foFlyE;_uuHDFv%))gSsCFJboYKRf5D)CDxO zOq+*X7uHmdOSp$W5zQ2KC>$zIL{rW8aw1y5lt~(fSieR!W1yhtC)@6dJvzxfo?y<* z{D+Uo)B)#G{z>I+e6DQSoud)uQ>T*!$hrj?<8i*8Go@$@7NHFvkvNE!8H$EeXLedo zDzNRM&RbRIT=YnS%TU}!uu&)e^hWSdJz5TK@eIqANl=J^96&AT;7{aoIp=_KFq@J0 zUY%kvD#j0w6h9eV!9b`Gv{Xq6v~VBBMq8I}z4($HrR@z;JW7~U zg0_kf9s`lBtg{N+Tb&g-JB_j)9VV(w{As9Y1*>+-YaJDl8KRyveczIvrvuU3JnvZI zuRI|A;Ar?Zx_YU1JHsnb6s8%I&js&=x@#U@wN)$Yii@{gwqxfJ9M^jU^!fkPsy*mD z(_>h?2i295(W~MYe{&Ua^KP1IMiJm#kUH01f@@0B>Vs@`M3+qLkxWY;bZHn^fhWsa=sBR~XyFi2+1K2PrP5(47#y_Y`2 z&O%R}tg^L$K)GlCmVJ9m5YJu=rZ4L1Y`r@RU%`yCfe#Wo*>@a4y>*X{Ek;gECzBia z_=9+UNN8D_CCs4Y#)Kcz-n~2cip{)Z*OhyBr`NU4N$bEOubjduphck$(`^yw-H1ks zWFA;$;WFhhvci5*Bc zGynoa5_Z9Vcf>Vl+3elrInS%TDZ`knsX31uYM$iBDv5cXf}27Y7UFqv(_CIPhNsJg zg%jO)gO+L*j?J(q5##m8tdB4uJ9&d%N@sv^N071K;aWm0kdMRY`qTT@^k-R@Fxi-?4G4N{9L0v?_~CKXk9i@WmKy zblI5RcYUry2?Bb;E3&2V-Dl?p2a|0{u_!Sk%{y>qHW6P^k9{W2=PH|tD+4l7&+2%k z&%_fX1C?fiEV0>4$npNrot(f#obSL}e%QLkg`F+QBs|V5!VTy!of@~IbQ17#(8^eP z*owxOf+yrUhHM6&lg+?yH3J(R{OJL%+kpSCwB7#4R*bbq?E9g+%|6(sDW`NFF`&BD zb>6Pz=A6gct+j3syr8Z3gVyVnK0fDej%wkjfZF2~5fy#tuA>}2Xszzeby%{{K&CW4 z2W!Cy6^BNps+&Os1Fmw#g|hk;i#m_69put7vf9DOatymMQL-;_u~HHvUASMJ@`AA4 zExm`wbt0up;8z~V7V;eQ#aVh#jf)l5U&HHnx z$|SIPwLy5hckS7C@g2eB3t@AR0=(U>X8{%{NmWA^#@GIX2=rgPW^OK`86)9mTQ z!CqQ)saZ%~`B^Q8XBa0>dfBn(%41kOwWG+Oq~|5$R;hkHoj8QXoa8YVW?dbr@HRWw z?M$?%#)E$zGn&_@67Cmf+P~UNfGzjAYUbLu)={w5nQDD3qY(_Zx5ddcz@FNPlg}FB zSq1ygp;x8AftIlY2VNN=)87HzW0pppJR4pYS~S;u2$jP}hG=8TNiVG2FeJM2$3;^; z2grc)?!8`&icX{oJcV01jZ5lg^a)d?P|rbJzM|INX9ST#)8h;>TlB?N4yNaSk)utE zkVlW;2yNIXE_ zZHWk`TUM#Iq!pfG`gw3K_zo){o3iPW#lg}yV1ej!hsG>5n{npT>10cK2(Sm6<>Oj< zMONR-X+T#>c&iRIx#a`{bTZh!YI#br(nH{+p0 z7x7H^fIS%se{ZF9sH>PBUVIE6nNvM$p9BMp{ltv63CcPIZMq`3+uXyyouQG!6hA@v zVk#el4DE8o*00Rn82k~Du-ThK^AJXS7z25WpKX!K`Yf}9^GYU%Vf!u@NMenIu|=Lh z=_hMyJ|Q(;Z16-AJ!WYE-khE*1CQNv0AP5TprO3f0|9~Q0!$o?u`!&b>}8jP)y4vH zTj`nLfvECSU}X&q_7!0ZXNOY+oDRhgAWG&XM9m5-RJZzP)d0Em;^k(AVLhj%L_FKw z^Z?Ed@l5>X?C>9W`6hJXRo82^xkRuf@i6(gnZ7@w5I39a7_gaf4$Tc|p&@4~2&TS0 zTju8^Ec0LZtc!_bbP8@oAbmakwYAP_dj5KpCvuJqo z>saxTc!vGb3G%Gq&derhLxdDyd&0--q#g%ee+yjLHH?Ahk>~p=%IRL^>^sc_Oztd8 zS4LrW8f5*DzbnUw`{CdUiMU_mK$07!8Lx1MU5DRqm5u(pIx)~Oh7)%ZDS z=DG}15X#6IxIN+D4GDlfO8Y|?gMeWzdTV-%n(hi%!d4KTI-&0RA$A zYTMYli1Xm;L>V`M?++1nSl|{E(4CG;p6Vn+Qd5NSQC8Y4fT-P*^rXN@L1g{-ROPpCP2@96H%OJ8etJeF6e~ac=$Ie=ed)t(I{Bk#08!eAgQQ8~a)=B!63*V~4MmQ^5{TuE9=e<#C8zw{4B$8vX7-cv` z162t3xf?fLxFSW%E3J$2OI25ibs?NUbXa!O zrVPr~&o5gG+431GO`D_n$MZ!;`N+2i)TbY&Up$hU*>z`;m;w<|=R07m%?-J_Or(0s z>nQzeN;8X4rvWLU(i8_dXrI(!Qz3n+^ioc>|wh zsYH}lqhd)c)BERZ8K)~}YIw)9YMYe~DDTuzHZ1JAR~Sw&-O z$f+`hR+3R|n%}W^L9;hsZ)@szbpr$o=ulJva7xzw^VPkVTKAoZqb75Q4d`^OEe0q zXf54?j&y3c8!mxIG!B)tm%>D3PQYO{W}Uu8oqjdXIZ4}~@>JC+GGb+W6&m+V^B-@5`A zV|VyNOnpn(LJM6+AK3>a$jyaMkuk9`ybDL?xFXK!q4(~cjdq1gLie3Gi^a{dx~+vK zC#SKkdhjn4+cR6F2@U~bmkS?YnAK;C%PF)ngRF0blP&Mn1MvR;=M*Q$r0=LOGnM4n zW7SQJCtj8s*t2!-)-en#6BjZM+rlx5`C|&PldGv1vxza~@~BiYn14Z)Rzg||>F``1VXsOG3f|Q!D16CNcr5J#>e`ZxFB!uihz+o85cIra z)Pzo=R4dn6Z@4V!AF4GIptxE~p_q-vh}& zH`Jm#yjDzRCXE%t*U2dpurl037Apyw|4LWLB`i4_>~ATob5ALw_ES{zb77|4)g5Ve ztCBatVZjYZ+)ctWly!`N(R99TY*Ga>4UaSSb^C3l$D=}h{L-kmS`;eTK7W4Fx;zabB64nqP;7KD? z&hFC;=_SVfZjFz0){GBwJ`jH6(gXsAMig!qMHcP`KC0G+^_5u^wm|P`0Fk ztK@1jN}G%pdXYeqe6B3%yj?7q*bI0%^bTTb5c+$hqhOU`MmD&eGs43)C^OUpM!wFJ z6v~T~7I)+JSrku@VxLr?_*r2I#S<1qcv8-C&tYQjM@g1dLR@bSE+pV7o@{@*ErJE` zcVcUsGY+x23BaJg(0bMC$jy(ft@J=g@oG_ZqMqw7kEUD2|J{l!^rkJgFUT}Vk}(N@ zE=Q6K(ISk}a+?hYlAn`_T1r`1hZzj{-pQ&CLo4Z`I+t2g_z9ffMU+)=_*FJQJG=w+ zVrbcBDx5X8TEnkH zvIyLRBw!sP5d%YgWFmY+KR>PHQ}mN5S{UA;7&nRcsN&8vG}UrmABce*e=+IzMA;!( ztZv$dc)RISq$|SWCk@RW*1xSraGmQE;Ae#gOrKQ7aBl|TIEM3$LkVTO%Z2v{QK2GG zvQ}LU>bK$`!ryA;d2YG9GFEgl8@aFt&*acrC|c|d_H8~D0`Xt%c6lB&h8ZmHOar45 z=Nfx#eC?1UZtWaqxE*X%n=b4e{rm6>8nyz-yMpl${=vL3@}zuA0kAP*+JKDs}7&u(Up^>du}Xef`IYr7wX-tK{;lckDKgyB#~X zT)zL(t@hyPyPRzqTh(P;F_~+7Ou38@o)Thm`=#B(nZy5A;f7R3NW}#t0PQ^<9x30S zStt~&F)L~Z!4AFr4qETbL+kx z>C;Ou+p^o=U$OOy^vc0-`QE8So|18{5a+HkV{OUaAjt>guge| z!Zd)3C}7H|xhjC^A@y$3vEesCy_>^B&~+5ja1t;jkuNv8@^x|cWxs#97@c??WfGot zX++TII*TDyN=gw#-Y9uhE?Mt-G5LR6)8>%YK^k`go+FAsv&uXKcR-KD>dZvx1P5&V zmh6`#Hi1JBN{1Jc@`S?DT6a+xi(siRWdbqyR_rejj06MYMgCLjx9L3Z2zLc> zrxC@P7^2d>G;PvIej8qi+Ql5l@CpH99hunL#A%kmcbbX_eBvP~4ESV+BQKJH@74MW zo~k|BXxu02I0h@_^r!=4cLt2F`uDqarf&1O7`Hrn>H-?qNikE%?V_Kz>K_TZI1+50 z*Kk2rL)wE2QU~~EoF_~A=w(@TIo;S9u8nqGaa7lYRy^4;U(e z0rj?dpsKJ<;XPKE;FDEu8CfOnTE-D;+RB#Ji5O|y{D%0B0^ZoJF;oJ(-vDoVQ5*`v0OWINz2%((u%0F5T|?*uG_!Ma--P{E)f-EvdXImppF zGv%Han=m?$Up$^b){TMq7&Bm0e#iGY;%^aT*2Js7Z-f9 z@5~_lrw*i@j0^4`M^REUFwnm6SFCnAOZRpHbZm-|&GP2!Ipc1gl6J?ijx+xlAD>{Y z*04Idd@Ca6wdx69%tMKw-Ps&Ew{hEwO2O|2IC6s1atgle_GZ0#srP0tQ-%zbF68Y# z880kNhRlxi@r6u=_nCZnHGSq?VCPw<-*ElfLv~udG&@LhSm3=h>o0dO?*E*2v4q@o z>Nkx&S-Y_rv4ZOys*mRBJtM#-H`7Km0&gGc&YK*s!b#`w$EvW3{2q5s;15(odpuas z$~uohg81Ly2Qy}Pb5+=5_Vg(E&C2mt)jK(Cz45TdA7{MrB-ZPkStdF%l2%&_|m->Z`->0l8d)IWBZ<6`*&XI+;i2QbzbtI&=_3*%9?O7($CzzbuVQ> zO({Tp6w^ZTZ$KsDX>@WDoJwm7@JPoi=V)bG3QrE+k^= zfbp(`F;C#XtN3BK@RV<+M|E*El;UaP9gMw=t05GpLn!9Q(_4+>P*$4eO$v869%U}Y zZ&2~m4QbD%c%ewa&@?i1hAWDaa3vuw_zf6GDQ5^Ux~ZWpCmP%)j&Gp&)oH~29IAYa zs>CUXl5?^uJy<=>HL6ez=dAP_hs>KoPD{$s7dcm4tV8>X*r?;v1_xndbZS@*6`3n! zuV&bx?hD6{epF4@B<$?Tz-(iYrOZvVdVfsVE%;%*ONPD2Pm5lOpsREvlZZ&GmfKOz zrMgoYdYEZ3vJw7YqFSXsA0M~$QuU_QD8V~>Jn{WL=KdK+w^KF8<4}Mtay?J!4uWR3 zyTSX=sggw(GIbCg0~MC(7$hsBV^D>vhN((HpH8}PxYU8Afi;Q$}S#nRWs%V@M zSoPHfwQ0Or12>mo?~)Q{43G9LkdW_+gnR|-12iO0Hc&3|aSP{b>rwaxNtY2ObY`ZT zv>weT59*WmnE26UdXz_>fHb~1&T?V9#d04b=n>*1EsH$chLW`;nniZSl$M^Ar6|<= z8>s2$9OO-@m* zH9f+YI*WP`ep)ORy%>)AmGIj{YkqNxq(t}Kc4k7A{fa7k zflZQp5y{vtAm!uDR5-%ubMm#jIfq!x$7dswb3NkMSll@?)pUBCAck+&pr)s%driX3~VkDYY z(5#6W)mzo-JFL}?c#Y|)%8D@+xJw1@RRQ@F_Jntqx^)df32C?9qi)#>z9xM9 z05e3EQ!Nqsz%~(ckV}Sq2A-?weW$AYT-s(n{Mz^JbD7+m>ovOz<8z5|pvCYzZQ;bu zRhKJmbf9I^Y08W*sxqBT1*{nJjT&=aY7L$2Zk4?-t?W4%_^Iq61~5itw(x$g%I+&w z_5!a=%kF1sWvn#o*^9k0op?1yWjAP;`8QG7drFnv=9S$*Wj{zOyCJRY4zKJ-V^_9; zx>l(!9l93@0?7x9a0Vb7bW*_dZ~oJHP6K8M!h!j>84z7av=BoKB@sg7x9Aq5nc+tJpyd4S< zIIS8U@*qy}5E_rFp}?n!k4$Zhrd<$Y)_kvL;j-uyo#fffeqF^@$;W9j-I%|Y{X(3@ z4Umvm)(z1u{F2bIFH1?b@(V1ZHXU9HAtq49Hz*a7Z%^N30r7cEcpl|0RdN$n6V;Sf za|P9$qiTv)4cwOP?W69NEK}Q5pXZJ6`igLI=-e6Ik#ub{Ro$SfPE*%92tI2U`P@8L z|C>V_IJsXS+9fkwAE>Z{)1N_gi*yf9STw}fM9UZq=HjFUj(UWl_JaLas^Hlc`9>`c zGVydW3tGNg{G|+v@)d%+qtd0}U+ZLIm>yn>8x!267+Am#S7~jLG=Kxm#X8m}PqzQE zzSXaF68}iX^F@uv$rTP&)0H)F9$rVvAixn1ISWA(SyB8bUP&0*1~tTIsE=T}Mzk8xS zN*qL5Qr&a~cfEENt1M35p{okeM80tdjmAMisu%}-ogL7qPu0I9U1n=&-AsQ!Fj7sY z`tH-owJsxu? z%`>5@+DdaIFvuCs`k5^E5A~n3!dmTIk^e*@40Uf~w;v}uB}L^?lBeU2LLa7oo`I?o z4#!J(Rb^Z_2A?{sM>@{TkT5w5?64$M&7=xQ@YR`;MlW{iAUTFB28yr$+EpkGddW{Sm{WQsnqw4ObZX*P%4VlxZpX0PLd#b_!D3;M;fa*p*dV%AsA3tr9}n>I80{830ve!pqT`})-hM#*w%?7?_Z5IG6U$ilB#e1E&KLdUg6p*U-xZ0 zwkr=9ZQ#?fVMIZ0iLG5tz4xxdafJ}=G*E6vZk?! zWXu5ukveqzDUp#cS5JqhaTB4>FGPkTq2zjC3}T5MOW)=;{N2HnT|%=&5K&E^5jI|a;N8@nYo zl&Xr^+@xOFv^R@T($d8ErSej(W2#5p1N6jfnqOwTpeCjxe9{!-29gi@5HJjKkqf`Z zl{&-);dvbAO3~(U-*x`t?{cYOv9zWC!YV{}!OFukXL@VQt#Dh>*U9E2v4`?)iD$%fHlF{8p!4|-N0l+)ky59DZww)d4 z43LKu6^kzDP8fM(Vbzm%4xa@e^3+$IQnxh|$l4TE{IsN-nTh(Q{WJjPj`f|a4b)Yt zYTa7*x$h68Ez*NW;ziCYv&oH6<7#|$kwsdP^|IhKg~xgx9!AhkYif1AkF6y+(;Ana zvNT3FM=YlB2(1q($}>KdGt3pKH_wVM4Kp}r8WkQc#Jps8b84*yL0`61^hL*ctdA)4 zn5vlrEcLK=fHY>Y>AcF;^kF+;zUR`XnB2rSX9!aDJzCr{7MbAj4tK)ZkW9xIG@31L zM?C9NgW3evayEL$ZYe=04@@!PP+5{Zs zEkpf07C87?LaiFr9KRkn0WBS_M@tJ7lOUyAWKUk7Zu!CRONZ;h4T+|94bTc(O#wT6 zqeL}v8JkVL90chrNmqjXP6?4{^;h_0q#VhOY8zYVUb<6A|6i=@ecG^pLVd0e9&FT( zE4$Rc*FhwgdPX(%4X0)%c5;o|(i-HtJoZ^Ru2*?gC$nYKfybtNqP$T2XFR z%+D#HeJISEH;}sV-zzh%?dBhN#rIl7M|s2+y-Sc#>LW4sxMu-jM)mZA#yun3gXy@h zwB@jY!mmzuRX=$I7<1n_wjjWV9uYo}b?b%VhrG2&r|4Nlp3&|X@bef)m^c&)9I8f-c~ zQ>DRnM@aZvCxCwzO)SWzeCWuO{j9l1`UV8subB>&B<I{M zz~s-vU;tG^AI@{6&ztK(4C5XI*xY5#0r1!&VLe2}rTyBhQ4ov&cYtFZNUsZ8IM=GX z)0O&%t4_VHt`0Aw@E2A!^%WghPXSo-r;;IKx!a=GRl(=SFeH-%pO-Rx?jMnfOb8fKvnA>k5v+3EZrB0ks z(}}NUop5hmsaNO(QJLyQr(0&|>s)=tUlzj|&Q^)maFP~Vb0C5;cXQfa5bL-)8?;B( zARqY7`R3%TjD*wfoL424ikLkKApF_{{ziD<@MmX^xh~j|Ur$#Yx(QMOS&hmQHGvwP z-K|+_iRJW#sq>8^_1QJrI3IToAN3hNBo3S}PZn_A$PmOj3;(zrvytd)g5{+nP-8ve zhetgmp@Z8D9WeDx;mJ}ZfN2&`b+1+ZUq@ZFD#SeL6X5WAOtz57TdXA*AA{MnbDjh2 z{>cK^yJ=E@>VjXCCUj6n)1L5+365k;l<6=^!_P0%$a=lje?8h-0Z&ee$_z5kMo}K> zHbF8c!RlGV28cb_TxqVHL{4)u&6LO8k*2nREFxtx*se-e?vIR39@8>6xpv_y4!082 zRd!I7n#8qTRd;3*Jo@^NckZB?U7vM$^YMu~Go-SA=Z-7)Z{57((qr90lVBe%EfLja z*lto&nw7w5B28($+2e^Xi!pc0n1XO-UiFZ47t~UdGAwAVXBQG%hR-kqV`)w$xrrE; zOO|Nlw9L?~FmI9|ZQZ+f^A#8G-o5owH!knkb;-p$pE1M@=3ft{!`xe12t0?9rG{rx z8oA+_iweWD-DQSnZc@WDSDCe$%hcM;RfUbYt!zK%G7~P_OBQKLmqPJ4>Z>-L>oDBM zk0gK=jR72%0E!|yqAAWaZi5v0t%@iSW*2NjKKz&I<2#J>4~APU8&M1oTGpXlxYM!@ zVS*0Il9+@$o|VIFEuD5L{Y~Mm)Tgj7ukSq&epnx?Z#aAy%bLuMADAN7tR#H=I>~vd zgRiQQn-&aFQ+&HPxR-AOjeG@)aB2BRD%jlH`7SpISMUGF@C&3&&A3&8kQZwS|s6 zU+w&pIwFxZ7q<}mK41SE=Zhh;xRq4HE!GxWTrpKvhpX3;7E&V)|8A_6*&C3<)Vq>& zHONO*$!IWm;87qqfSKX`T<%tS>xyU2glH}nLR;ztc*g-MZ80yve8x7rXIy=YM4cj? zH~H>k-uYtE8Y8(PiO47`nr4Hg<=TIqf0G|Jb6~^5MZT-rWj-%o<{+F-W7n>}|CC zQ}3XG^UL-b)4D1NZ&2`CZZXeig@59CbLKR7Z`#JM#%O~uGwa*)D&NVMkG}o-KyK7} z%W^d9^_3YQb&dflnk&uob3icOn7z8$Dnbm{n6A|Maie@bWf$76Tv5|mR%y&t$y4FQ z`lt&}g;qweAltpR+xn<@w}zc24eF~%C3T|2bFFDhW2-DsN^F!Sfm)YF8qTGHTU0@s zVQX$h1s^rp+H2s{ParWPd{kpg>)@I1`8C<_bkGZnc8w{zbj|=P_96sTt>aWcPuKBW z70d*3mVOfMvu!Sn@O#`il}+jIO)bEYHspJqv5#i84|58hq$@GpP@f)MzytT~l>dM& zQ2TGFS5B$c@KrKW zr}uHjHo9rOyp1HrdivvB+DoDg-S|`LKzc8&^n?K_GJYj}ENx-%}X#DnUob3^8XZwmc`{0YGXB`#0O{gRtM zoMOtZ!6`bs#)WvR)T3W_TXstrg1O@+W!Jc>;OXox=s+J ze(|l)5840xN0xB;C+S!1@argEBYZ$3{GN@lql1_#JDDvkhBOeY7#8E&BL+-IH>rv> zB-$>h=Y#5zcW6PBD^DaXc#asd*cNlcj+<3|&tFmfYr*+}XvN%|7%;x_pYMC}-ELV7avXVK`OTN@ExlqqO zqa?alhe?=D((Zl=avq&32UsihncQCNoH)_A9{0^uw$jo;k5-w^Va!s1hxs@`r9iO6 z6kbIxc?wm{wPd;x-$G*9Dhi&Fs?jVu5EW9;`-zwb|Pm*T|7YZX2- zrFW%qz2B;GC>jv+23h_WIf<`_`I~{4B^uOc;%C6fS8J38WaZ4@O6cs~vL+w}Ncq0NRy;w6GYs|$fyGyJ5jtg-p_p-<9T$^DuETC1NCdCN?%Lyr zUIwfT{nZ6hL-ir=IZ506$pD?&%_f@MVPA86l z+CI!IR1)}!gZS`_#}U%@iO<`2*y{gPc>>G8{x?MT;r9uQ;%9m74q0gPXGe`3W`W14*kc zmItz4HQ#e^&0|2(N$Ge{bV{27)d|aZptg!Qb6BG_P^HkX1wh^>h2uR_xEQpw40K;H zh-YaKceUC2(Ml*RjC1G2+4N#ToIOXU_7+y@i3ngJ>D#GJQwdsi`i>J zMbgsK^gGXQ>481vu%`6wH8681GaBjCBHwOOPByUrP(Fzl>QehoveeGT?;Ry+(F-`;6A4In>cYrOyfE@jfgr_u=5r?@+50RK7Bu zqN@A{RBwAgOsMlYnp(#pt97=}K(bIrgkMQ>q0D)MH*bH27*j?)>&@@YRf5R-1!Kwn?FjE{IZGg6AL1at{RtGajc%}DrZk;)ogTTzK zST(Lvjej)_=OM9XI?JhDM^mZ`K;C-hooOH&Q6~$dm8IP&EZO?xIHyQy!UiO+NxH$|+mx$n_ZGGLAPT0C@0`Uuld}Te*#V|GDK0ed<#5Ia zGUl^AWL#*EdRd08A8P!F608+q6_Q7Urnh8|P>fAyW|z||7xPx7Z${(F(1OSBDC&Gd zPKt5&sc|KnhWm;zc z7gAAr61eZL^)ea6X)XfDGyG&g%Na_vZ0FH!V#9UnMB(oATw%^4FaUdM7c}Bxwe^Uw zlm+L-_6vBh#&Q(ypelSmfZJ~|t{}4JB!72=-y;Fc4L5R1gsuzeHL|?DeaPP4#9R8O41qV8BJ+7zJ<3)5 z%nH5uS(*=hmxN#Pgq_W@FK>@E?_@?l-=G;~CL!+%-)Ik4s%mBD>WF6{5YN^u@74|q z(+e!MA;T&mxh-95gYof5JNbAz-6Klr^g^6Ts{hEAkz6m~SHGR|KPQe1)F(i&u?!xJ zSHF8L17j$rP+IO!b8#2JQXOPPTd$wiDb;pqV@)K)Ctt?C} zGJ0-zc)|OfR_GM)@1yM(c~!q!c~c7hjI*Ar?$p&O1C|D63VX@E2V#1fsQbK|)>A$t zuKQhp^N1GL=-}8@1&&w6ryK$t79zqz zVy5}en6*b(LK$c{sBt7dqZ%k?w-Znn|1CiIR14$weKs8?u`lu;IFwh&paqiIO38O> zZ=qgcaS6ThQ=hESe?z0W_+tC*^c+&01EE)_qV!_~QmeAw{^d&;GLZ3GWV`#!*aeR3 ziv#*kBgHsShzt0F6HfRaSTU#uIWP_#)Idz`=I(ru)EBU+==AOMZ)WEvtB%9&aGcH? zHfspmM>wpVc%td(HU*;a=>rAu2vM$N3q+r@gt#ILA-sbHV9}WaB!vpU#7Zb$=(LeI zD3ld$r{z=yb}^xnYqi@s#7-vC+**#f406=PdT`z zFK0(t2$21D5jYlFMg$gZByqE@OVYN}R)myTn}fE`Vsd6jY&c-SO01%I(XG~>Ptdl) zehA(n?56<@mPg8kXTpA%c{{c);T3SNv-y&=r5s;vYc z;)$CQ{GuBIhe@dm<>t1lmRVUXJHD(!1iV%hvMsaIs&B1&L1%aAYu1=1Z-%Oom$JP4 z^*b#&b6sqC6a%pI%Es7rNkD=LibeY`xC$vNAegBez~zEmfpGGyb57B@!V?e79c6uV zhH1Q?s$f6ciF~)&me&knk3sz_xDLE8t{i3SNplP8cwnz>*2i_Sjn~8QXpeE^{0s44 z*WxtXW4v75*;N!oER#O{zAr?&Xaeqt|*4uGf!H;e6($D~28>V;Wp?=w-8NrUDYZ zkSh4^U=poZSRK@4%-Ti#&))(mxz<^=TryZF+lH)!D7$@V>Fd!jV9|NOS%kmmyMps0WGQL-qodA<&k28kXZpsYX6~>{gPf5Y6 z5XCozCbXw<%jI^8(Dys`4U! zKwx{DD}uBV%)kRq;H%sMSUF^4P8s0~Jf98tG z@-%4KuFa-^g^S%XFvU*o*Cd_2^ZVu%U$J|jOK{Pw!ia=?cg)(J+ycd2e{|MVtmW)T@Fh%(W zg53+~al!^F0r^lb2nOuR(C2!7S@FCMf+5-OjJ$_%RvO%^ZFT9 zOxCT&dWRNsCn|Uxxf}*X4llcIB+k>>*bgAJx-`Z}favY$5_Fz@%5tvf61~#2@LyBt zF5tO~?Idmt_>4My7W$6^6)5P)0pN3X2|fcGP!OF7h*sNl&@44t{i9JV*qlOrYqp=? z_W|bre{B9W^}QwPrb*{yA$9S}Y|>HZ@_EHHi(R!8#p%3WTb|cNrs7Hq#HX_~Y%+z3 z^6^ai>hbEVE+mMJz8@OMRL=T^VcDznDLM40sUnnC(fq;DqeB^p&xCzw=peJMD~(Fz zwOpj${P;@b^*_o8D-@{{j;c&qjJW-&OCN!USn4x1F@tRu2EZPw z@)fIiK8D-agp9UjWAEO57n^AnhptLX?$)hxHA~FPYwI4~lrh0VzEt@*hn195{dIex^AZHpGr2cUQOu?&R@hgM{qG&;@*TfO7(r zfdYI@O1uWF^|FaVM^=X+o1>{%>)?lgqe!uvraB50s`(2v@n1_VmZn5)0RX{fD)n@$ zU?|~rHBcAhtX2Dm*32H4jgjkV5k9dQ1wd5%fxN91A)z$CSdvIBe06prKU%=xttOSVqMn{me z>LTrgMr3tylCQr|(l2klm~}8KLbe2ZbD@19AGmsR3`ne>CQ`CE>}9TOKDOQScJYSz zf7!M{YL|boo#5(9XcamDh3Ln|uAU&3@7&Yyj;jXmeKUKf0dw1!@1YG0b@ zzto%WSZ~xBSVELpRF-*G=+ah%8Ryik@@8^7JxrIC?{?8dcw!k3V7HA`FL$a{+ZSwr zHlSy&gl&|SdLV_He#s$G;}Ut3X-YUms^rfJR%2#QvIec2wy-h{ce+U7IITc`Nmw#V zBa)gPkNBxQYvaPvIBj)YemX}}tzk=$!in+zcV@`UhTpfP)>~tEXr=MbCc5WN1rX@U2 znio>HjnK{ml-h&>#w51UIQKEJVJI#=or+h1saR@d$xWF-u}a?Xk&?fTpMPVBv zS>CXu>HCx*bUk^`EhX2YjY`aQ5>CBy%Nu9eePFS_MQgv&W%+P9m5Pk%RI)+sWS}z$ z$tc8=(O36vg9LR{_@iE+@Be|`AWRM!1+?AQ0)=W(POXy|gJ_l$CAf7uEme?&bJ^_m z+?09)@wCCXLvEq@(hdz*LIbrXOdjnW(U>JC$dcZQ5=y_yQz&7oDOsZ5`6_blKqs+d zc}@?5NEQZai0ls;omMIO_M||~*qVzpLbeY3U$MJp#xvD=GCLaH32#B;WlzEvG45v1 zQl(t@G|w`*WKJr5t&TDYBkvZ?AT@O*{ZwW)-~|vg_}pzqbIE)rI@Q2*<=ny4r*VOr z0({o?$!Ny=Jo{=1H@v>VU~k4@^zne#oRz8! zcbLjxGn*XJqbYhKy=;I2c_O-8xP@b8wC)}{P^eOXngOe`r1!H8EJe)Ox!g=MmNkVZ zWvD)2)etx_L>W|B;rf-;d5BpfaB*%NhE#BL2*-#N;xPTd7&OdLIUIu`75e>kem&yX z#%?^hAio@8D7P%PO1sdFX@p+PS1-_$I0hS(&QXICHlPZ-^1NUT2`m-&SE67izYpt3 zD>e|_Da?#jOWenD;WA$(7~r@Lrih;66v4gZgz{yyksmPV1za0XiVZV?q#q*;|Fx7% zp{jI4yc3P9ngel&$B?S{rX08Z291Wf@g+HSNP}=ebNJZ-)+{~$ET$p0II7-lg&H0D zofI5Hqb$oH9SI8!>NW*70XCd*$wqe-!;+!qsj1bgMH*0acH|$$($k9(fuSs=eI+Vn z8M&p`)y4TiD z>nu`fT=}{zN3-fu;TiF|B8tlHvM4HU+!>mSRIcVK6`r}ugl8@@;hD=cSV~vs5RGVE zj-T>JddC-=w_Ns&z5C^W&4UUN8R@#h>lvB4&g?jE6p!#r;}yXeaMWP1MX{YYmEPEH zAyo~FATKJ(=UhHM*(r_)_&HJ2zSeojgP{4dNGPLyvIodvm)au(W%-yibn z5;2D-4aiq6B<9~(=8N8^_7w1aYHAMvW4AL7*z6jX|JBCo0i9g0`K2)8c@b6-&oi2l zuMy3nKxoA%lV)ob$$bQUKa>2OP&Zk*SpX_H-<0=dwd~i`jr*LL6h*uQa55^GQ5l&0 zXdl@)+cA#l+*R^+%KDirAOi7Ki6>I-eE3lp+^u_5VSa|6~+=><+JTZrR;DbcM?$oSy5&z4QB(9lhYZ7fp2Dp=ELP6%PI{; zd2T+EskrEW3rp2w0@MHS@|vB{D>E~&#qS7()+1qzY=;DrCKTeS%0h^v8>a(z#7A_* zQ&_W|{vAse*$Z(``)&|{aaB5f=VskEn;4J9Y{SiOP2frie(S(n#*V&&EgOVG!O01> z99G1HpAAVMzx!iw$-vD=&W`-#<#B|`Law{GaSX)knZ{|IDWfvD4j8&5raBoP5V6Th>6C8^K?s?iYOcRApIWYZ{;Tyy zu;UWFV{xhEKztNGL4zNaoB>h#5ZSeay5$|GTq#4w!hTBhE*V@g;7y zMf_UAC!{UOBXyp{P~98b-kFt9-o~P#q00rF@FsS@MtA{3X5xLyW5XJjJueD45tWxk zY&efOer(Jwz(p*)lXJ3-gno=FB>0E0aij);{iQ*sa={J}k5AMW{!Z>pWYm+da6n zHz9N2pY7&YRWn@f)%U&X|2#K+gdDN$;hGC_~D41nLDJ2IW|80S|l2 z&Gk?$KW#=Db5dOpE(mGEM?=~zn2K->yw>ch)D0X1Vz>upM!yyG>lU?ek2Bd>dGlsHi3`e;e;4-qRl0t&km}=!_!b_KBLRHqApTnqRU30Gu(;?t)5d`qF?E) z&gcNG%>b=!(*I^DAm@>JO&F1w7<{4$$uhB0OK_Naw^@x0 z^7Z#S2sc1Ct};ra7(10}hhKM!cDa9L?n~JAq9jjo@|obQUzI!|kws4tFS(&gHtm9s zurOTyaBA06l=ra2EPxNG>u^p=_6VvWAzWjRRW7o7A*C9aG=dKXv?}AHC1&QaBh>JL z|LuIBfxz-ah@F!MQVfVW@ZG(vXK1;ZgyvIg$h$+H3`|~-mGLBAV2+BX2jv$bItJ2+ zyP+{|N%$I>*no||y&ZsQ0d3dJb80#wqaLpi^chEgY+$9p$m+{ERA51Grf)F$WyoG| z$eV;XcANsZrMOSRi-~twJIWaOkfo(_qk>E|niGdFOn@8@%}x8?EGneiLPY}#Wf$Zu zw+nm4+0Xe_)B043TAYk9MhSLu^_2>I#vqaocSW%e^x#&SjN$1zEryA{+je2LSk7dX zGyor%ifCso#YSQYd<^FAcRF19W09@sWD?GB-EKfBlS!D8xEqmw+%~FZRMgjo1!TD+ zUNhW;Advb2dXSm+X*IYp!V27L9Ne~#sj6cqtz#Q$T=f6gdlNXj>hk`7&V1*4X5Vt} zOeV=>a_=lj$Z}^U3n0v7Ma7x0NUKdm2?0!qEQyeSWmQ0}wu-HFtGnH7)mrV(4OEb7 zMQRttrL8MnP+QxVRex2ft^fDudCs}_&LqKrvGxCxykO2f=X}q1eZJ5BJYV#>7^W1s zNJIksTLEq~B9b!nf)-|$ebP;E7|Iu+y>z<KpB zd+dV^zWGfdaz8-9becX3dp^V4OJ#O)SVcUQLyt^ZW4!E`iEEV2{2U32+I6nGYUgzb zqe(#4;cPP!)uBO8!#AkApF0^j`OUlrC6-qH>>K3*!3+AmcBVgDP!DbGo0qA`7s27tItVhOP;XpFKmz@h z3^9g3Hlkw;58QO`{Q3~_XK{?w)DoW}C~HmM2+NFG59N?H4{d#ev_JoO&ZoTH%~ekWE=@d}vA$Nsb40*#6n8Itz^paE){I19Xs9He*+GA{6FD6glDFG3Omw(9(Lm;ff^AJVoPMPX8fjfzPtgQX@jFva zvJO^;7SvxpVYe#$D*O}5;EwQIy2RETs^B`1hD~e`JjwOs^vr0tcxh~vrjEEKe8|br zDyh>n88XMI-<#Oq)9EfqBpI`S(Cc^U#8Z|^vFtjj%hdZQ!y$kESG56G=n%sTZZ0|Z z_#;vVhlU-P8y?G@^q5<&WpR9zc@dB5mYY@hNHRD63<<73(=uySO0C%vuiA5Mp2HD| z)sroyh_2PdN^=F>s(5>ZKW<$z$ZAEhTFx<1*2}<0lX}hc@oFT4tBDqLJAygS46ckQ zG6|!wyEes;qWi*=$1&WXF2aRGIe_T8s2uSFpn2 zS$shX5?#bsdZr234Ec0PjyYBB&@B~!Hk(#GH9^+@)Z(yg-ana3WW>`CBGa4a*;NcZ zz-T382ojUcPXxX&7)>PWbLq8~o8>mFlu<4=h4I-y`0n!DTJ$3F8dDYCa_FeV&dI6_ zZ^=TQue2hPy)v0YT2scaJ2Ozsc)BbxUE}czT$74%C0u1OuI6tavdwuKCt|D!v`x_r z0WXtrkt9!fDz3cqowjV5BquHm^}jh@PI#f1~fOckTJVPnrVo2@T15FtJSsnjBrPLGEed~=b3hdoR$ zUn;A}!*TTndIkMk zgge0s;;l@oV_Q+GXE`~l<@^LsAvee&m$6syYD`P+s_~jsJeh?T3GTzvLzz&p-JpjQ z2j<2*?i>4bSnG*>@p;MFvAsAOCoSHMZicf(}^+%!} z*Ros&FwfhE`e+q-?hCV{yK3HDhdu^I_@;`>*A_J8;lgmf6?{>dNHM*}{_2-)G~jMb zdl3AgOD!%jazu45v97b0_Xve4aG!}DVqWbCH{7V&*eHpVGN}3B`+p!glRm8EqOCt} zPG|tzOofQz@I_D>X4F5pd1{x{s`vsO7f;W+!(nZd(3e5Sh zflDR1m0Zb4%^z1IbJGhGx@|9y8R-&G17%`*E_%lb;je&036F`e3<$M7ZEj~M6JulP z<3PfnWso3G8U-_`H^7%FG0J14!InsHE8riqB}raUbG6v1ir!}xf$V#zC$}ULuFj$Y`|5@kB-EOpU4!je+a#xfyycrMFEV^;IyNd#w7hBM z^U=ANpX&{~b_~T%5rj#J|G1YBJda79}%&vSG7l5vq@)_UTAl;x8VRGsM~JJ-e* z)S1i7-y1iA=z9>tsU4T!njQk3XTrWS*Loolli}$P=6u~QPS^5zr^sj*GW&d=DIGT= zuVd53kk1=eYP2#sien=;)H`6cz>~lk$Mh^?c{rsT3INg)X_tq9NMP$P#V%BA!e@27 zj344HlD}LSg#Zd&L`vK)1&7WoVUpl+lRKwmdJv76kQ^xaRTy7X0}glXWpO!j5|d8 zRHn!UCtK=>;oJ1tc!Lj*SK5@Zmr6Y{E{%k*<#2a z;k!5OG(@zDSZmZXVhA8{<(Z5sDMz{41*J?8!GXd^C#G^z4+)1!3NwPe*&WpJTcZxl z;DIdEGRK(yXp2$kwwbsdY)UkuMB!!~K)%sL#IV@X!lfK;E&@*9s6{P^a4IzX$ckF= zSZOAnPCmXMd-#BJA!9q-DWHrr^*Tv7w`W+ijL$b}vxNx5VUTOML?a2X7nvGn5SEA; z(1_q`AOnQ(2GW|Y)$RDxjQ;Etf}e`pb;(>*s?o|Zc``#?X3c-SEcE>ECk{QI_+u+A zeSiJgzd1%Ze%ybot)Cx#x%;PbBIf@Z0XQ)SWt>P!Z(a;jb>9Dfc0R3EbPj;;-G9{; z*Y5f09FF!V!TaHl7OovdYShQK)x`&{+`E6@!2?$*O9^_7{8UoBX{)3N3~|JPT;Tbd zREy+!#9^ywO7gm(7~a_Bm(xg+-|fHh5EN!l_UzjId-w0Y@|vsmT(Nt@`VH$JM@gv5 zwf1}K#O_meKW^jh4UgMBF|nIbUW9o?C%RIiN{ia^dapjX-v)A>v36M3mHO=Gvqrbx@&Jh*Y^ASu_domlwKy8P4Ia053R zM)qPRfAIl%E#aL=oij+^SnO0>U>A}^? z6nA)zNSwz*%UpCwayqvxynPR;53MX=2Xo5qn^zW>n;zT(tn2`3BWzq*fX;b&|Lj#cqPu2%k$*@`7m-YzddVi-t=Y@` zcaSsPeviN-HLXnfy-djF*t3+|5t|Yd`&<(54DTWxZ7jIAP|MDU8#|^A#8R8I3DamW zc^X0Zc!LNv{eWk<+~qA!TGBmIyFH#Yqezgf(nlbOl)c2~;p z&g30Jr?kI~sR{6Ib5oz~S-6^t^b38teS~rD>b?F_%Yjav)#^>MJSb1e2XLS7n5Wn| zq|*$YLp+AGKyI{<6x^#2NbM0{1k3ZT`0I5%C9^uw{I;NLfkD1E@zyvo+fg&VbuY}@ z`&)1CLThjKi1vEIdD01>V2N^64Np2s%gp0OK#x5hk%rB2We4jEo0v7$kvH}=H6~|V zHZ{SBm_=G;-Q$6#t3?6enA;dx=i&lfDMEN$GZxn`;VFSIYiw=GmOvS+@RaryX_3jm zM}&U~otb9zZ^2?X!@c!pC8$OllLO5<>C~vNBV2&*Cs)o8NW-aM9eUA|66ggiDnqci z+Z?i6iSNLThs3Tpkab#y3p|;JhV^V%>Aibm@1XEPuXJ^W9}ILV7*0V>=xQuHtUCTr z8FW(mu%?lQI%FU05lAMXDE}M0s`0|@F;xun+6FdJ@R@X$*pZmz#jeol%%}7#US+4& zPe&N??S<$!l~6e<3tz7SRUNIHNoY~>>$`59-lwXj-2#3pRsB$W`HKw{isUs!F|;C* zOaxJ&9E%$`bAcX$7Nl}45g9|+uHD6z%z!YK`j=bOS5x1>z0~(=TWw`5=;oAQ{Er>< zHsxKvhpi_t-lW*i7P-f|-f9#Zq+)h4<5W(ll#t53~a{eCkgiue=*gEab7Py&{abe$Vd(Q%p=Wn3UPP-2mbaTQP+ zhLu1vJWVTxvQnm8!V+6Uai>9JB|bI04;)RSf74JghvFQGNHx}&o>sr{O)osiq!H6>~@iesbTk~%MN z=h8Vw(ylm)x9`(4!BK5|#i` z&B19^1h~I5hE32z=(>A zY=y)kY|z+zot$-C<$dXdTM=^stF;6u?zQAKq7;i9-uA<`fiASSVP0&dRv1lb5 z$q?U2A!BSDz_itr0ci>0C*s)L^Fdd69_XqR1{-O=X`3a3Zn8y!u*}7IMJ?o&X^QH<-BwC_Td*(35E`;u7A0sl=aW z>5dQQy?KMvrNb#%3YLY>Dy7ol@HU)}T67baRqvtw%I!qY9j|Nw=L{%&HN#l6Bo;IO z66I|ZgSJxVMn(Cq`>%AmUy%O{W6HZA!Ygc4+V~9PENu*DIY@NKCVXW`3@|@{0`6#l zNs+H&T|dc7y?hu86xF?_D584zL@FVMq9kNr!J>B}T zQQXbWJil(N0?147{c!+^T^x~7j?Wy53pV9R=LGSBhXt5i7$vUeN&3dj^jO{huaJ{_ zf$iTLyUGy*(}i8COW$3Hc@+sl3@7K6$$Pvv@910nE71~fxR-{9k8D^+-W%^7-iJq8 z4EJ@GmWe*S_bP*ryoX1*3PQujJCnmU;mLH?@6NmjZ}g$VC8-B}<=8nSzA?+UmsiNK zI}v2e;d!;8SF3o%oGO?-s#vgzSQ?XWtX-yI*R16lpcc*FJFjC5^Sj9^O|9&Af&gZ|cG4QUJa zKE}HH*spm?yd1UM?mghYR+u{~7YtX8~&EI4E@KbJ48{Z=d(M}M5jB!$xw9pf{= z0S_*jYDEwVdd(-3ttrBnlX!7uaWUMkqV;BH&)T>Dx(z7`_kvJ2jSC7kZUk8sH-Qx{DRbNi6p z-pX394*!+^F4NrbroOl~?0o}O)9TWsxbNjQnam#HUya;fku!CECRuB`KSTc>;i|(e z+$#Z2*nTtAO|bQhXCcI{(;-SC0OPg$B#9#f|E0nW}=rKU0!fdzUmmPWyjX zzGYvP?f+fA|95drl4PzCG9Q2i*26@A00a}@7O4j2?e6_ZsYYkpNdb|RK({i$rR$( zLj4l<=~nDi+zdOFZrisnwC;rmM>nz*V1h&X&Oz{TcnM)uBDKZv@7xVYBo+~ zo&0SbI@WCgmg;D4c(Y>WL<++_S0y;gbcMS*eHM!0t{R!taMEx$uR6lr;vamP@~e&L z!x_T>JcKU*uPS2%$Fw$Q=S%kAKC-h}u>xugVdAspQUU;58nUxZ`7#4 z6iAZIx}2N?$&dI>bm3$G9St7LxRjxpjb$P)bsHp6r6!D7*14cyJj$L9GT_H9#}?c2 z;xEdIZ>*U{n{ExSg~S!t+Lj@P`;Kle_e7>9@8VK@#4wA$!jgHrXzfk znTp|qJqD-Y9veGjEUYcFodlG1JSF!wgSKDp)ZC=uWBMZ8$@jNraPGP@G{kTSo0-q| z{i(eI}dI(_MFY zI(Z7nhDWMvV@X{NQ?(L(F)MtYPycz@?2lx2BSK@1zyae|YWX#kai8imynt^z!b4Xc zG4nPnz{{$XJPwr-G8SI&8&DVKb80 zKdpFbvqX6;1UfVAQ}xFI?+H2Jecwh@h))2TO+7kU$n<~EC%29OwLKhiW7z45`FFQ0 z&;SdZ0cwo?6Cw1Q=$apmpySDXCWQPWk>DB&T)29NQk4LTicX#aU&_U{AYJyMEVJ0! zyoFb1Ev%)50(wLlpAaEAQOH;LeJw5)q4;?sg`PJii1?aQ!iw^I<{E~6~TzmB; zmznQd-EgeEdN-EiZ{}E4R%hto{sYw!`_mlPisLpqfIp55Onu!e) z)$N1Z##M(eK6LdFP&1yrc$Cod@Xja4?M_+kx>nKrM&~<{K8pSw;k-kg$6w7+f$XR* zQpaCsb(k7m{nW{6rn)pL^(gDCLq9oM*nRQk2QI$s$c4`xXD&K?^=`J~ZaL7HixAis zhZ($ra$LzBjzNye>Pzz#ukaJ{A2cF+8z2Nm-;0 z%{8EwtlF_&ikePrgQO$K{s78xQTELkS`#xBtb)Twr-3!x&nDur-NO}+8|y-CRVL)m z$l(Z=HSC#6*1&bzr*g8@0V9c7-}OVmh_Lsbz)AWLxDYGrQM(f;5eLH?%#up|Fj{}# zm>I+da(3js5*ta`2sg4+ip^wwvg zb>|#3SywPEJX@=9s!}*@Hy)bP6lB?3Jk!*KjPpyINm*G)yCx(61oQ7Yy8I=_P9abfUrW80E z)mOmxfVX*BiKhdhuhbO7e_%}JE`}Ea4Y(mlek-80R(k{C1&w;SB|JpFR=P{w2NJ8X zq#ARXT%R#Q`z$MVD1#?&|DcuDSolGPHmWF)gl+C!+~RF;R*kiZU!FI~J$(U48~ywL zxRH))f^~uqGnVy(3~ioFc-&NK(u@FcvIx`d@7|c~I&0SseHZSIXv6dwYe}fA7q|=H zk&oI!d9swT6`|jo);Z`BWU__r*ivfjmt-!mx1gP`_!eDd4j-Inp?#hO?8a2qMpKDn z&k0Y}6qwO{e732XUaZiAbf=c-X)+Ml9NC-qt4DMXdq6RqtKTxD?)85D9tvp(vfKd3 zvFapGDim#OZ_hTkskr+zw$|`zo3Fv}M@-iu@Qid`Z@96d=|`IV^o^R{MPz}Cn%>s% zt?RPseK9hg=1Jg2fkO7SqT-YWkq*a^HQ=6d99b4OqwWlEr1H(-0W{r<*JSm7`#J~R zw>2{owC4ss51R2)XokvScuk9g#Me;wZ>db_83(7fIH>)TmjxuV8vmt%0Ip@}EXBw> z^cMydt>I5{sJIW`Ia^*fh#E`7yKgY)q_w!kZ2b)Td5L%HJNblBe*|l6!39H|;j>?H z({ZigTUhPQ6x%*S)4<<1vI#Q%vCrl!veAB)Tk8Zcrj?_`Kfn<|jkHe2ElcBBq({!? z`D;g3^Qx?x`?G4AS|Z61UuaJkh95+OTIzh;^$D*~rI`~aKmOQ$BqA~upxgVY(;D*5 zWOMlT>yz0_&HDo*AQXaQ?N!EhDE0RGLR;0*#vny6}}~$!4n?X#%>Mw+%(0TGdO^y6n!1SryELEm`9qW?7kzs?+zSYHVCvwkA^q0wmG@#XoS%I`JDbz+ zZ7^yhoqIj{jdkE6D>tfgXyLu)lYRH%YQxhzG_mAV=+j9?*(AP&43I4Wt9&yV zzTbfM_9(N7iSq|Go9n_0L8vP72q*GYH~Zu$_oV@<40ITRSA(h?cE}hAo)XVw1mAHH z{%x~6?4g37m?%NeJ0X5b0vlGVPHd3Bfu9d=!@pgh?YG;>jFxW)kPYwB@GUlHXSl@| zxznA$=OSb2a-XDDgp5Jk`s(E%V`llez)(`wuN|D`p)Hk%$zsZlish7EDO2hL7*hCgMXmcEk#3>+`2Z z02hQ0i4tfr!$-1O{vfO6Sm^k(89M%++mVhR9e?inWXBwA`~-D3#|NkR7;b+U)WIO1 zlB3=^7@D0cR4khM6k+1*UO4haH#;T)kMq>N0+W2Np~7DO6zE|pyc2|>-xdFz&4!}F zHSHjj%{7E_+p!Ufgo%e(*ZDa3wQT!Fuasim3E^`~LqOMooB$U*nV8;?CbI_4JIRp8txI>65ihJ-m-4-rF zyt+Wxb6a@2Iewjq$-y3+8J=E=dvF3}qQ(mG%rrbb(Hq@k`V$W+fWc%r#;1Chy{Ntu(o!dI4cY zOLfV&Yn#G_y2C<1I_x*F;YLuyjXjRxL$ER3;ZMc9ah7g5c1dmrjs~0`17hLz?{`iw z+`~k;ohSE8Cs_(SpL&O#O2Qk_N+?t;oyBb4x!>{5&Cg%?k3U+WU(5@=%L<{u;lNAlS=|_LKM&v1a)y_|CbMzAt09${srSi0-}hE` z_=N2(9%*tup}iG;^+q3HNBFkBXY-eMruqwB34_nAT<*nNjsN+q_nP>hy75o@_^XBf z_F)QDhxR2e^ovKUX?H$;9ay9-vzyJkY%|u=xO-{jD5(q9#^qZq@e7)b=Lw?-34v7% z7fDwJFLRPE6@LcA_#I|xo`zfS`#Mj*2K@zm8-a56>c1PHTlzJMNm|$JTb*^9J>m1L z^k7~ztIUyMS)UPHrwemwwaxf#*40!o@Dypuia=tra3~Z(7YNpuk7^T{4hwNz{A9ehB#sToz2>*N*AP55N|+Jf079gl6On9*`hh{VVj(+H!}Tx_p6n$P zq`h-@!Pa!UL?I#9g<$INH_$h{&^yChDSi^SwgFEGZ(|nE44>t;g;(g{I23q9%F#0j zTainh@@Ts=-OYu9MH^j}%J_Nti8&x0yXtNZL`}?W>-CagUAWWr*c$d z%cDH-Gh4v_36t2-Z7_TGUr{yi3U}+1Xv2vqpbksI#WS5v(RjK! zJ2vuoOttr`Lx>82*ZMO2sXV4#L~vGehnKr6;|A0NncpOG;g-_@*y(3Su899I z-{YVY7g+YIPQZGUZ4w%u#zLL|mzz1p@QV-pbh1vIAY}c&=6(TLdK7qc&eYZ?tUCU> zj-MWSz9hrNN1$6ErD_2eI_3u3GuRY7oSnA}NL3BcAm4_Vu(^Jy&BdvtunaVrjP^P1(@81=Jbqw?xu|0K6{9_!||NXZA{ zAeEg_m|jU@Aj|2zHttXx#E&0W8*S`d1h_V|p=)WZJijsU zhLR$fbvzYoty#8)Nf4-P0IkXV_MZ!3Bf%9&0S(QMomxxpG=Dxdfy93tZ3e$wtDPwv zsh&@~frWD6QlpTtnUKQQ(q-*aMo2BBPiZUjkI~4EaOIFGg|WEyL$=fw9k3<5PmUwbf zf6Y%}825?L@ZgEz&gX3A$MEEd{zVHoU3-q}iJe2xPt zbOHCEpM)-WnqUaTah>~^=NE>EWDZDtnY%vm(+|Yphq`sCoU{A~Y<@N2Up*z7%lpsu zaFP?>frE!s4^CW8vsy%!KGFU_0agWv6lcss1O0~c!cNC? zrQA~{Bc+>dgKP^Da7lF6(kRD<3Y%~;#j+r};lG9tKd)yV!E<4krkoRsT~?HV2^OosC$ zW{4Y?MmWo$f0Z&EcG(eRX~oZ#fVqt6c9b)DHlebrP#zcX^xMee@C!>eL^meU%D*CN?Em3Jv3 zh?5Xdo$rq`1F;zetHoa~<7N9!T-suLX}GjzVrQe6XPe4y zJF2pl$lXsE*o!Ii5I#n7?Qh#0Tl{zpbKEyDSU1HWPv5>TN6RY;uT+KiMc@R)VzqkE*Ld@{xx+Ckeyn3`T$kerURqf|IY08r&?PUR3V z8cVnG0jjUHxEWzl=+Sci!W7Rq++37Wata zD@(%U$%RAPj0m++>!h(GpFv~teix#gCpgAtW4yvuRFH-)K*-M&Or~ICEWmh^FMa zPs3f;lc9g1m_G46oOf!gL#7Jl(Nf@Tp5IB;vEO^rX8#RjF!M1L{Npq^AHQnZ`qcCGsx;(n{Fh4KI-d@{h-Gv|OePS$wfo!Nmld?Xa zy&ki?byQAw-k$Yzi+xPivF3EExo~01!>f^fqT>VQrdR8x4{%O5H>;Z#arFv%soCnJ z9xZXtA%2qi%pRS^wHW)>#Lc5(%E|j;FS`9=L4S1fwmvJtHP1adyHfNyL69nQ6&4)a(8n zlyoOO4U0Lk6GU)|ZKwXspd-sl5H%(4&uRqyCqF zq&V1)(MS<}s@Y7oxS~uY?^gA)zn;!If);V-^4WAW$L@L=K7lcO3;jtFUJllc;a@2- zf|%w-M!n8o<=uLHK@@(_ZM855KH^M zOO>k0N#^~1>~=VqVg@RjqE+eXT3q#!#D~T+VRqRls^QW*CrAn9sVw3nt8i|5s#)!y zLa|cRU(B2wLlfS^#te{;ry7OKj7El}l!-wg55@ZhGUh>3ZA!j&J#Z{&|AnkuTKoLS zq?YCCHKumAqeGGF^#@b|H6phJ$-#QCEs-uclY{AutW&*VK)X~~q{+{yPXiWSUMhWL zFXWzQ9PV5cZ^Y`{N#F4)_$U+9LGC5olf!%I-2z@{W}pHK!j+}CpZpJDk&Pv!n|KDfz*@|+i^N??NA-tYcI9E##ZZ|>$<%!){xWHfUpkOb_8V6S?mt*}lee2mYR}y3Wn9$yq6o%^ zz%t?i*;oDSA`)FSuZXRtJF$v4*EXQ}-RJN>;pdqQDfLPiahssRvpfcp3A=A7beI!Zv zFb)tzk5)U zmX({I167z}PV@nBLzYMr9;1ww}ePY#FNWR z4bls8N4i zb`;ODn$J0HMuJybtQ`frQ@#0y)1hU^lg=H91jCyc3u6>U2c2dbNxN5u(tz)WxJ_a{ znuoY^jWe{=&W6T=R3)otLtCCW*tq%C5rE2ZJ+y0$VWyV+Dr$zp!&xecif_nruA1!Rno98KFz#s4Xap+H^Yn zb3-LAmc)ygh^h%0jagPFqzBf>oSEBXL~;hkfJsflyG{3{RV*ZwBTwPS^xgbd6_o$s z!@N1}$|{8f->3wNuXf>i>3@CFH(p!>}IZN(ixBHN5?F1FW4Owl#KCyU8cI@KBT4= zCmAH{*Abp$!1!b*cg z*ABx0k|`VI<-0J_8(X zc|T3I;gC;_u#mc&4=VJf97)F9Lx*6N-E&@cDfP9S^(X7jZ`Zo>1-er+x1IS{z|38I z0?foxzpaDi_mcXBby1_lLZgg20&v3B((b;H!L*q_cbTaKfR+OIOE68z<3pLi`{fJK zBd>_lOoz;7{|7>BS#Y^8pB7$=Ps0ewMR{NMTS!Cq+4n0{w}q)UZ=%sJ;4PMKDd12p z_u6Yr1Cwdt*aUIw6QmHjb1v^pc*uR5+tXcU>JcQeB`X4?0LC~ESDGZ;QLSA9NBEdJ z!5Iy)ZvKlC{D*OdsZ$WlJ(kChrSI&;`EM)|k zv@Zt@sI8eUH&CJDw62+fF64jHaA~3s)IcCaG6}!#oy2}11k2VYvVf*Wic$o(n%_yI zon$7bBA{nN7jrO?#-Wjn{9I7Z+F$F1|M9G4Nv>1>TC;;jj{b)v{6YtE1l=J5sl{R% zK_bv5WW3zPQpC7JP_{jLeM=liA zL>c|seekON*VLFp2~vKS`(Q}*SM#S%(GnPm-166;yYGr)SXdYk-=z%MEpjZ79!wYp zk|Ttr^z^cY7%hhLk_G}uFIL=fSo`Bb)%8x*)ek<9Nx-yO`t%TCN7-*W!SwJP60?8b71`6P_FS7&C^QmPXTU=jR|yx7 z>s1(4&0Y0`V+#VRBVoAy9Zj=g81hBrq&9W6alyE+H|8SYH-*PuU_6}g7=$fD;KuBk zNR?q_>`56uGrWdrUAOon=;G)(!NbLot|W}@nLxs6F2Z|PU<}~^oLox53_@D#{46@5 z)Rmv2D+)8ka}D7=F~<+7)|XQf))5nzU(E-*fXQ8EX*Jcs(872^1&ntOX?olME)bBa!?u> zO;&ddI!Pzzkwy3#Q=QpIFh75c?D%vzakIa*lY+B}lXsR(8p%55Y?*#mYR)LWdYN9T z)?{@_auU-aM@lpxxv6m*W#^O0kExo4aS*Y;Xe3sB;{fBlj!t>0E7|yr=1!ctd`)7y zHDZipYB!YS+Vr>q)Kx|lm8wduSfG>^&^mjI)C&*ON=x2~2ylHXeQ~@TH`HohKCkwJ zT9mh{cAVg4c+o%%My^EaNy7s245)6`3)x`&XV#*dkj|FgO=h`sG+9abYpILsyK$_+ zzDYh&NqDhzUiIbYcN>*g?v{iVhlz^#)&c(A^`LGuMMji3h`R*C(NJMD*+rpiM#9@G z8Im(R;h%4kMxzE&xZvvES*6PR!jUR-nt(#yFuMBv3fLl49hjX_E0}AG^GRrdaJa#TH*h#e_KU5C z9)c(MZS=@*V+kq3=|!@|Aq+n!V*X8s@yjJt47eysQkUQ~nesd|ir zT2F(|Noi||SCM*@t(6+^7R(GvWvG40f z+a(|iE1dbR(YkIWmgDF~19Cj-Be#a05|d$NOY8BRI77+0q#dNoO=hOTvwHlYf3XLFMr8BoUDl6(f-Ig#enP>MC?c z!V--G*Uf$c0}c;z-Im&Ak$Gn_;F{QAWBNiqmDvz7C-~ucLw_hQrr|w`)$QAOPIYNn zYkCQynb*dfaQ>c8&ob1)fsbIQqS5c@sG zp=1jnc?v9nl2Vnc>nF2za;niHw0U}(#`JXSUv^egl>q&b*JQlRA`yg%`j%0o=WaGY z4@yw;*7w6&l9BnH|AO;P)ox+wH$J4J%=#Bf1{w#=cb)aGskJmybQ^bc{}D4EpUj5` zyT`r^yI+zGVJ;1QZFLB!3B1}i+=|jcgFc`d+_A;x`HFrs+CCQBwf32N{vQ_!tBSOv zN?Vr5TRN{3EDs(ybo>?mteBNeVEaj=!lR3RHEp8*dKlReIZg>iyj-2E$a8;IC+Hy; z`r~?ukNgflUbOqB5a$~`_@pmlIWP}FXq0KXpoY1%7<%OXTE;|xM1)H9q`9nUBJgaz zPO#)vNvH)JeO6*6LdJ+hrm)9QQ=Vc{$q+e$@VuQEg!UzG|jzc+EtNce^p(p08S?)@XGV*US}GnlsPgG&LvTH8w01 zm?0PZ?^O>KE|mGY)%>Be%vV){`hSk6&?l^rgG*No>*)9+1DERrF2HgPT<{C0=U0}h zz#@iDCkus@X(j1HVXa7}ks*9CV^2AbER8)Q$`1xu`K&z2C1NI~Hf&?SUL+|}(%gky zjk8=z!{K7-DF}Y*!!Lujuu~;r$Ux{4^J1Nv$J)F+ujZ+FH7isN7ThDMS!vZgZGJVM z(IR}_s&P+F&e2maT*B$LxSou{Uxtg|IJ8G`UoG?(;gsPj!-yEs@QjKbub4Sfdc1`~ zH+z|vc6o!ehO0`PQ(Kl)rTvZsgoR%~ogdYV;Id6ogvL}LY-!-B92FLY4Qw$1(;`8y zW=YoVa9PE~f4<}3r4bm))*Pay?q@Jx^=;%JKNdMAtaXCeq_V2o$>uv>;EP6vAVA85 zdm5NJlIZflASQgIVMaf+5Bv|q4dE_%gunsPc^$bvsCXiA*&2yNuY??mRD^p*GR2cX zrd-1U7+d*%fqauEjBD@O$=mneyc2`+CmN86?1)G{e~-Dc*w)e>8c8jgN}Khp$QBw2 zA5)clT90DfBe^K%oSFSN6QPhL#~SUJm1Q5|G)K)F^G^h(GJ+|%L5EUmK>cwo_p=op z-iMn7BC^mEOs;--NW&?b3C-6A3Ew_(+Um`ws&Q`|>vuW)3nOX|ugJPsPVt~oa?RK9 zpd7xY;kp+N19TKwMH+Gkv0*UBxaZUbIIj5&i~1XLhygRO-Vt7=Kr*?RE@i^sf}m64 z=yoGrl-a70z$VKwBx{a6Fr0)vTbtc@WVzC8up`~aNWz9YtP}#X1_f#)^X-t2iF@pD zlrO|V?lzJL%m(MQ1X?!lD{R_b)={@}+jM%B_?L)?w6F|q=BZz$94=bon>A@un@rT8 z+z`lHe9H>TH56Pd*dxVM3I(tp{Ter09!?Rgr*FM(ywr*H9G16!b2+xI5#?nU6bi$$ zEE17WYzM;qYB=Vtn)PBoAmCVOg3(zdxw&%wt2FwnvjB zX+KG3(5lMZMc;(miZu%OMSb#lZ%Q5M&QuA)fD3#vLB+T!=T=CwGgj;vi-5MsZiT09 z0{mXySH_SG`(x4j^;90N7N+OOV6)Ew5`0sq-LhL$QF=-Z?Ye^Bb>U<$U6^ruIb7?1 z@w4>*dCi(Cdf!_@!_>u&f2P8T3$+=wwfhY#mPH&yDUHMx$%i`xBz99&?-9(HY0plV zHW~`J(JUnopvW*7Gfb6f<7`8~u~^Tt?)w*w)bEd>0p9WI=q||a?KyB_w>AT=S!e{1 z_UIvc30?f8Q~grgjed>@)8xqm6Bv(C&BWi;W+KiK@e5*9abr6go$C+>(xj(NO8;fQ z^7o{Nx|YaXJ(l7of8E5nyZWtd)U?Q!g7@s~)p|f$0Kdq2q-llUiOtOJ?bGzIUfycs zYyyHUm*O(NC7Fs|Lg{n?tTh=*w5T<2%5L+w@_bYU_AY-|)`QJ=}h!`~zH@iuRI z&*Ygu7cE!-b^)~uwcV(RmFh_s zbp1e~C>t|%nOcQQ@=3JDH9Y8btyW5aKdj9@)3vtAa=chOk8*}0i2MdgA1qn>oa7r9 z6M3SSkYl_G>6Gbc!_(u zK{@(40P8I%b7V(yKF_ovVcYyFbZ?cV2G8KSCG-iNjlExhva!Wbmn~=P;78KEienKy zT4g7buOe__v2aIox=lo>w=~1x$I=;BudUKt6vf-L4->^sDQptbM#ByZ8Lr}Zm3m>u zM*S)8w#hO&voEZ(zT}7m(^R$3H68H7Kf}=C6Q#el`Ki{PIM*)RB{HBKW{4%wej^4G z5mc=yuy82?Oy_Z?A24Z7I4ll==&4{10(-6&;m=*-6Q%=C6DekJA^hb_VZHIytPX4b zU;xZh$PmkW5E@*Sbsbo<4>A~_ecdWY2#R$$(Zi1Re4x++z7sG*U=Q1eHg|-G+A|0A z#`GNB?X%2PHYfJ7oH=(WYlm|P%#r(h5EYeuujEFcW_e+Ua9Jrkl~JJlRZYY9d>WVq zPVNj_=~WTNkjYH~fzyLwyUrwnnUnMIM_`0R)7MiqC2Y%<@;i0g)?^$yt9f&EX1$rk zok!GvC53>mYZaiYWX_sj&Fj4yn=CN|`W+!ag>`~G1*cpx#jahH?_8KASWZOFEJ~uwCaQ5)jFt|3be%EMDRFzM}Pok zWZp17;8i0;@~yPGEgRyXU`K}L4W_V=3cA@ai#BXI_V-}B(uqz&9*6PNGC#03BJ{y% z*J1Bs<`rG-Y6nvmz;ch%#iW1Us{TW5V5K;$SuE3!?zq&V$b=ja2y9AOr8XR~ld>p) z=&2jU_E{?;xtRgWp>_VU|97n&OjeT;Bn|dS<*!et;u>8vhm$5AVJOM$c{=78@X`y$ zqs*D^gY*Dy2BG2Wk13oVQ#kKG_-GS4}XuG=x>-=#p;1dLf6H5|MH{-8(BlakO| zl+wRbA~lC-OT#NP(gjE08dNau8*WCzDE66j4ca8kXVouJDl9+|;0IE4j>Q&~M`%$9 zhp5C^Au3ZBwe5%-#Os}9Od~!DC{;YjqIWcQ4{|$fmUF$xHAJx3;xIeuhSHjG*ds}4 zOho4}zl9{K;ch`%6#nmm7JzBrjM4;6)p$H<8S&a`JPn_Li!g@AI2@el?XhuM=Ai!^ zcP_}pLR8iVE2VjggD)|KvbVa6h-F@Ob}C7Qk@1u#97;b#v&yKxuZHiLOFsXrT162J zv?Z~DHbJ~amqzE2xmU`^IX# z2cB!JG6goc=fWl!(xp@JaePU+$5FZzPu8kQjpa-ob;;o%TS}4HCi%VS>VN|WsGGN& zjzsdVy>ovaafh_7koFx@6z8@D<*8LB(Kl0%(hFkH=r50$gbtLTm3giPf6qL_t!d`E z=;juW|Kr>qOhYhJVpWW58Mk%lHmwK4)SLwT?X-7|EuV^G-iTSbm0XWcS=ecHG&}=E znz>b(j3XFUj1jx&Iu1xsIk6I&I_(~S3{JMoez}~Sl){Cju%yIpnd|)VmYU^ZDY{Cw z=X~45yS#+CFc=3z@`D~rfxsxVfUfA26pcba;K`QG#2)fjG*8e!#*#5xLK${6O#~Hy zR_1YS_j_Z=&)#0fIWAc)(Ai{@23I{xn<(d~nb=D^Bs7ZwL%Wbg1iCi8G_U%HYGW~W zzocnywZw+$M$^C7rsqPj$G4jnQg4h`Gx(_3=-})|m|(I4%lAc#;bYb;D1y>iNv*ze z%bDdW`1^C_X#PJFjDutE9{X0{I{F2^p_D0z|WMj1xK@c^ZQw69~&o} za}PNRU;i*tKpo4k{uqbPk35(F0l*(O*M$!pFRNddN0?k74Tf2aTl-$KaS;#?^30wL zlZ?LxEPckl=dK7w0K4RIhexjLuia3ebw+_#7_~P#fY#KGy;bm1Is zm#pNdb`=SSMY=?psyQNG{dut6Yn(Nd?o&26H@!KP^AD`Gnis6tt43q*c8J#zlP~oa zEEW&Ngu*Q()1R%)QWk{_mSbMk|@^ zM3b2+G;DAn94!LBgV~)AhHI|IMr1W|Xak#csy+6VFY45))B2 z_N}X|X&Z~us1Ye5!;j3JW<*$PxIVp#Ap@k9h11b&X^@n;u||TdoTgsq0vL&D6=n z+EZ-%*<155cmwk_2F#cRsX1LvjUDj&&4bcNH@n_c6Op+MAQ~YO31>M2)?Dy@$W*${^tX&E3Hb`l@T}tFy&g z(k5WdtL}%k=6|fTj0>%LITC~wHp{i0TaSU~7+m2GH1A|%(giE1F5pyqN+zZ1mieXt z_v2~?C5Sg9L#c2LTgLu65^^(MqjZ?LTR?84%~LH)wbQJ$$dPow?O5JBpCQ|H(pTGC zKC0YEo*@(V$}xzFdTrBLqsE5nwVSuAbME#*K$!}d0z+3jwZYsQD3EIlg=s)y>Liqf z3{x5A&(%0iigiL|Vn#Y!e%e7%#XfaiT~5}(@EmDxn;qcjNqft-?Xz?T!T=W1RlSaw zXCR)LOXS3h+7iWN&(fjcA)I&djgm_yo|#a}lcDhm*DjP4bha6-o5U{P}zc1zyyj1jI5Chve=%p?ptabH=@GQ6ytRf{!kI@tG&*9)^(~U=a)` zk(3VE^jA@{`-u4fYN3cdf5)u+iK!aVOV-$491!up79*Kq-G^a)IC9F$*%nJlogp`s za1tSnY`$GYahl4V8_Oc>%L6Rxhihc@Mp{zxpyU!(y96qENNO59!-{@+6q*q6SNM1GTQW*)8^c%;; zh%2s3cVD1|+ZI&WRIh;VsmIcn2p_uLY~e=CZ}u~SpRO2*OD8f`7U}n7gZn1~E}(-%7j2v>XDcIK z8;2Dbhns3ANSKdPpZREJPj~>kYTa*XI6``TuJ(wTwwwZ%4l4`FvwSqkGgRp;u)(r!7~b;;dMrJT<{ z1F|E71gpVuIkGFrrsVH7XIC#PC6J+}G`tk=eno2Z8S1t*e1dJwq{56bSg}-Tc&gGg zun;Wknsk{)+vofy7!W^b6(IQ*51D$~xla=rMI$}~+MSt94Rk(f7 zT@f9Nn~RSaKG^!~PffqjW*AQ|9PJg&ZBL*nhEn5Ur*~PVq~VfgjHeKf?#-BvY3r>z!s0ZuLWQ_mq#T|?sN`YjU|;wVz`w%dy-GUzCPoN5vHOrv@$dsh zpk_V30;YrtNXpDk_)Y^Jt4a8@ZJcCA)RKq_;ED*ITp$*pj-^9_ExvdOF7a&4sdKay zrW*TlIQZxnS+ajbz39R#73J>mv@67ivcgnenNxNx(G&SPeb^?DkibN9DcZ%UIRT)o z5c>(U|c3e7_=sP7r#W!FO+m#5gYgOa2y|oBRaubC6WeH; z!>s+ScfHOT*zLyQ$*&idPi#G=*ql1MpeA6-o}eYR8w3|w{=)@~l%)092-EO%Z;Xr} z=29X=#e##f#B?k&PhqAbkOZto3V%iO_UColl{Ott7Ub@K7GE=;;BbH(NF1&h#zJE$ zzSS5Hb75+yh>)%>ZlGW6R_&RHlBdRK zIhQU`jx?p32!N4&|7>^$E6b@^>g_r$Bz+5EpLAM%b)ebwWv2M;nftN?a!sZ)o+ZX+ zX=q_W;U}wpL*qKR2z`1B@^%;93E}S{8`*lmMA~``!FfJD4L>3SM0TL6Anq6u0JgpC z&s;Fg6Mf|F%ccfkg{cX|oZZ<1reZq~%Ej+%8T}#Fefaa3J`UIRg|SbT|6%C&atd&U znE=xGr|rTv*@<=r6`WLa665KK-Nxm7ra{y)gQ`s#HuYn%?bsut={WmfK!o@;$d@3v z=fV|hwZ!RzXyj{xd~61hQe5Zl4(hTtilLG?wYAp7w6QCw+|R?In+02#VaqT&qZCUJ z!Dcd=Dyj5HIqQup&&ud%hd3y)42U~`Ds-a#a>MV9;lnp+zt#eKObp8BxJR$(vSv>C zQam6=35d0?neOTfyVr|$AXDrO{;3P#R4mJ?GdH63>p0Sm`Y_UTtKuQ8*V@o%HGk<*V1?(UaBGvXix^3MaITuXsUJ6 zl8-gz2}n)b8iy3w>1;!1dc^_+6DHm)q|w9O~tLbohFk&_Wo zv6GgHJ=6&+uY@}b$-A?ZyAeL?13+-9>tkbWn1GdnRhW+Da$F+kwcj+{a|S!JQ^y|S z=r$UML?uR{Sj})zc0Amdfh+(=pkkJrnYbL`o7oV*Ix!x}T-!Y!CzwLmChDKDzhr;} zm#vLYrywVyt-#Z#C`>iYM_nxb3f6=LS;4Y!VCAwnOpqAi=4+U%vzSBSanG(Hysnmj zvpzC-N)jydum2VY?m zj>KuG7DGKX0+k=y$VTm$sTRmKf#N^MHlZePCdV}j z1&INmi-$_pBKaQ6@mO_&mb+BmjHSXTARpspuD&;>!VgTU$^0nttB0+A^8qmSKO=Hv zCQS@^U=aFh=NWDWe@_?%{m-THIeGtMZsBVm%R}VfAo{syiW(_fg6?DZoQIMD_ zGaXyiu4fcqO$ifa41jU*u$OwoA+hO%9UUpAlZ^AyE_9(|gF!JSRCe(;oj(gv`>wf> z2;q}O;aWJX)ZBBW1L;-MEz*%FeyvrNtfkKRmn zo&rg>3q0fqre2JXY1yQx$DiA!<}FFG6LMXgot6eY;ULy@&eVLe1r}IDE0j^-C<{Hl zF?Lc&5myN+e0B-l0=$&b+9a-=ok z?@}OjxdKVt@fnOCR$s0|C|?@e=5*;6moO}gC}UJ^W+kG?vlbW`N3muL)$i8IQ**de zHcs_+WQ&y1D|KeV2>Ld-9**?jgk>!|=^$_-F2ytaW)(N;h#%HmL<2Gzi{dt9^8zLX zW#bl=E9ubVw{R2T)gD$3(}|c26B6`Z3z(^26g#?DZbxUyA7eetvDjeOpm%aUv20x8 zQpHte>@G4ym1mt0OVF6!Vt+|erYn&V#t%qbZ-Ud)1+GgMD%qNb?}0RBkDQ0zUF;A{0SaAE8(;Tu&{Qg{zf0 zmlg9Vph`{_HV7qD88K!YArA}!{sL3z?;%4r3Bse)W67fI);WGQmVvGYc4@X(wip`d zxmUtxj~ILm=~Q_JD!`mX=nV78xT0mVo@fgS>l^XV8yC?Lb)9}MxC20oWb%Mk*p9db zef7ES_gJ*-Nu5j8iW}}gZOtT6HG*2=ZA(X&2rVF}M%)OC zO!%T_`W8iHqyc}HcS>v2%d37JfHi73mg!lf zriO9?`t9t~W8H@Hk$#lv00anNEQ69s|F%rXHmt4~9JY?cp{2237-B@D&XZ&ibd&5b0ez4sp;shE0aT-ICC;)B3}~nXZFau-C^v9nIO| zd5mh)=dG&)hvH&zi-tU`)CTIj2*K%0IF_B$7?Gl&gyJ;|18?A`Nxrc~eKW2J6eSyh zG;Tu9smBkY%(Oe|v6mVXC_zxFlG@f3=_Eb38UUh1Hagd3aHAj?3LPR>2bB5qzrO-+iv|2 zU>2U&hzcGm-A5T_l1xY2l&-uRLszXU(1leh&yHwWU>KHu7gz$XZ#L^mSp%Ml z19wo-uvzvNnxc21u*w7*rnHty$~2AwPw_vi=TIjt!dLB7X0I1{fHsW4oFiZV|p^EkEtpe*+Ah3HAm#m)I- zo(ZQUGDh&r5wsIR7??n9TvT@>Dki&K8q0Qz^LhPSDze8Lox7t`yVLNM2D*YynP@rn ziG@U$A<_W!K2et^F$yU;!si+)EPDtXh!xAb=xF%V4F<=+zK&+oG{^KdW0cqO$&k$L z0CND*i;e5Kg`e)+SVBh?8EH{UO$DD>`1)NZBWM%=^SzpZ7^d zAZf*D?WNwe+eP zcKoW4>IU&tUQs3`#B-=s2I2$C*#;-qBA@+1F=ZoTagc!G72NT`2ps~6@GD4g!QDu_ z`p|j0;=pJpE6p#)NO$PY`2{(2OCZJqsfDr!{*+ys&6}Ck#{71P(HG{; z9H^zo}&&)U7llJoV|9X_*WsqW`^mmj7J%UD2rbn-m3a%kM0qXKkLgGBD-)zit)V$3 z9hVE%e(D2KLuM^lk3WaFm$Nc9d2?*t6j#hjf{5W3bOdw}hm6r!@U{e+^49U%aMRNR zvXc9eO~?*^c%wm89v%!r8>?xF=kUqUUd;^O+tg&yu;YG~$LY++Ry&^>Oa2&0-2*;Y zj@6psweH(q&hD_+&62JDoY+1!b z4Y*l*vu#BkRPVTOQ-VJrz92VLJW@4W>bpbVg<;6P`b~-@^=3Sd>!Lny^FG6~riWwC z;ws||wPudR25hxKhs#VMkWUjV3nt}_yyhatdkmI~L{t7VA(thQ2O68D^Dip4THOp} z%;(%#{d`J#t@#2~Ap6Z^kQ6x#_d<0vyl0_b0F2<~h1a%Zt5=R^iFV8;GwBS>AbY1Z znRb1G%=}UWER+HaG|Nvt5`)NT@_HneLsv(U56vUHu^M!ji#QKug4i z63-!>i8_i(=@!f=IBuQ96FcxxoI#Gqk^k|(n2vE6kBl^Y`9_0rUgJ&}9+1zBrWZ91 z_(1bzq~K|`J=pp#du!<}BihUPT8nDB6V^gtu#-PQn?8tl3bQQ7HydZHYiOfTR8Y7Z z!mT-gg=1b={RbOn5{{$&-J2U%feH!&J`wZgbe~eJm3+R!f9iC_aC@*%u8`sk`yClm z7x5tc1&a-l`T+c33a>zB0-dg5VM4Wgzncmm%;vOE$^TZJ2f#8I_TMPxMHv ziLQi~d(l0fRsi;gr+u^9kI0<-HC?8Q-~GdJXh=en@S1rJXnBE>VV-I`I7hFy$ZDj` zg`wxB&sdJWm&XOGxgD{EFWiD=lAT&e_R1*?rP)xtiRDoeRu|?yZ;-@FoqyLSmJLy+ zgW>`NyaCo_1s$4O@rm8bjPfxm59P5lUY%d9Q?zK}Av~pv7}f>UH3ZHHx5*=^LJ_n} z6}qr2Z8^vGKCk5rH(xqo7GKRGHHUv?ku+UG?^-=*1~P^JMM8#Qqv*>h+7-S{Q30-+ zGFfjXq7;?1tJt1{MWT1S~ zq$m`-HQC&G@V>XlZA>vAHS6@bDhPuMOh&|k!XV&gN;bfdhvBw; z84d=F;mZ_hCZ}`h$=+Yv3bPdNj~%OGJHbMO@g!tr4o;nkH>gq4@yRI`kR7Do1R*gQ zY=J=*vvGKV8oETMcGx3Q>$=d&Jc0s@2M&KglkMR{O(peQ{gDR?agUnB%1j)^xkV7? z>@0M(+Og;3o+Y^Qcqg)x&Qw5s?6LvZj??$$W`I6IOlN}DWhv+`!T*ou7w@ zkOypoq-fE|&U8P&lJG2HmfYMco*PBD{)*~?t(d%04GlGk$kb`=c*{8!4ksH7!S4sk zT4f*bjWugn2M)Fq1ht%ISp-}Q)HTjFB4>^EufeFge|9tuJM0k3YsCHyY=RXep}?x) zd0>c|s;YR=kRuw0`i={T?z;&^6bW&y#qEtta?N_j-(v~>j(bO{+i+O2zRX%k&wWc| z{_SsS_<2hh@mR`%gX6NY=I7Qvb_@kaGLFjtZN}K$2M!`$_oJ2S%4Dvd2u#}!>{!y`pxJ+VMSk(j=`d#kY8>}oUg6>b3ZM9Is zQ&sPqp<>m@iVEsHCCMfO*}7V_rn5KvXBc{}`8k&fGygNY&GaqE04{J?!?1MT4Kv=! zh2Q-#6Nw@)eHTs{R!5q_Tq%W)a5QQlNSzJN|JMAM%qXEuKkn&vb>65Rxxpf{iBH9A zXbKKS&R5>1!WB+Z^<(j*B~j*e+7ky+6#wbGI9wULE-`X?Ae}l7T&Es(7)wfAv^pwX z;x#d>f%6f|FU1u!pr)@I_y?_?JHDGWUkS1;(^A;Ngw)&gv)_F&&RSg(Bj{BLMy5EU zo?#YC@xsM$Rzh0Rpm<8(2z@z>Os*UKiagO#Pmf$q=|VaGE0u$l zlD-p_o$fSAu>3LI$LBmMr?(n+*?Wo(uJU>$$w+q4?BcFK;7v9Db;Cb0guA<78MJC6 z#iZn2GKFMFpKo1dWY^Gyn1V^FS)*_U71x*xbs^4|sahkBAyK)pn znpqw+vC;Gbi>j*PVt2wQ7{-xLlkhy`e9qP6x8!ij~5+p<5?`(9(%Hk?O7p-XEI4hAf6;e@yL=b#+DpO9#4SG&`E%j z_R_H2+t4M@P`F%53vDQc6lkD8Lg~WNAKmD}ok@BjZi-*+?SQ^SmJqz&7uJ9maP7_gcOnaV?4^gq&}Fx@pMf`S3qw15Ft)xbfqFPKjcG z-~fh#w1Gn3coWYNKK(E8sdDyyd|V1xV@3>TEvEoT z2GqUR4%}$}Sir5~_n(5_u9J`yUmvV&8e5f90-4gpR3M_4$mShywEeA3v8?R436}5}pG8B%4jut5p;#|I3I#|2dMHZQ-mR9DkK26E>-7u1jy(cInEi7@HNJ=99Q}}v6SMVNdM80 z)Y602jS>IgsZ#-o{qLhFeST7bcsK^t=~|{5q;WAgF2qCS1MC41A!*Z*0_WSFZX%C~ z*9VG!^i*!^Qv4W-n^c%&s2lo*vr(Zc_ny`l#&5mYB9K6;)IBTJEJlY5_Ju;hHx9Kx zy&9=iVwRC=MCfASJGBDUd#+}rceTM%$Xp-*s_e~}RoxcCB;83>y~@qtQ3c&*yWHId z6F*THc=YD1k%|1fofpT%kBGsIx%x?3|AJxd}_)IxMN7DA0# z+8tXI*-;ZwO2y z?W}A3Y2p{j6levC0p|B{+Ljz3pklEvu-kUeyu=|nkv*Y~9rzfpd_%lq5urF@Y#@lB zF~$ej25UP*bb!9(Z>#;GU=KFq26J-MHzw648CuTc`0&@h=;r54%G!nEZd>UBsQggoewMp~W_$!gx}SEcxMm z*KYt#f2Gb7(M7ST$n2>{s^h*G^57f8Z7V=y8TVRF`ATIKC3{tT5a{2tVyd1Yk}`RN zjh^C-0H%tSowi%6(BRN^O+w@l$RlAukHV%mi`(fsJ$fDC(t*ztyf=0g1ZD1+>$r% zwBl2?;#c7k*(u0o$bjwcG+C}V4ccVqz7hfGnV+!5YUW=wDZi{@6 z1PK#A!d19zZYrp3D3Bjpd~7P$d;yQ}DB_U>4&P5{!JQvgzkVm1#C+JasE05hTEwo@ zV>jDfjBzk?ABn)o>u*PkBJT*Ee8E1-@rYm5 zE6XrJToeXudM^GGp|2H1SB#i5k4)(Y`=EqGUBd)ZmMy~~mEIZsf0w}wA5Qo`wk^CO zB>hjKTh9R~OW~vmk%TqhFW`r{OxCK>8-GB#?iGRkytjvjq1lCpFt;y8Lm3-AHnjk( z(?rs4p4;^QiJ}TGXsKT&fgp{2qf$FeM9&C;+ z$!dfDjduR~bSj4Li|weLL^pw8EAnHB>8`-ifhgl=OLDhVB+{|PsB5ja?=9L>5Drr& z0t;h6s*S^;V=aEYfz*R@_@B7>#fESlqTWA7DpZovMSn?*I%vtoU!QQXMaK%1 z7>q0|qF18hri?V`9M0|0riyovJm+5=Wk8KtMAPNb>GGA>LW2Xz-;yZFLnKTCEfQW_N3J-D>qGV;VOA zDN9;nN!Sk{P}k~b0vh{%TJx`~JJ65-hr%+yK&_B_7u4fKw*P9J0L$~(LRXV|XDcc4 zfjokJ_MkdquZd_1( zr}C-1{5R2*(Fi4h;y+&TA-Bj29;51X;=1NxXE}JV9MhTQ9z_Mdz9-lqcq$xO<)u^s z%52HML0?xhPPev-2b$#@L+KX!=wdV4Jf7peQ%6A+#m_dL!K2IE7dfVKVz`^8JQOTt zaGOnw`;n&@5t&EaX1^LpQQOl)2JE;Kzj}e;7#f-nXQ*T^D(0OsZ=-R2#a70G3&d}I z$C#U2@PvD~RlFVUGmSYBAVXN3-8LlYAbwx)hoj~Fe4`s=-)kY;$H^c~1Db5=@pf0) z-|3^EbPh!SDB`{t?#_5Pt5A7*eJf;+6FmA|k$xYk*!>!|pq zcOFZF#2V$KbOvPmcGb4S+bN^=fQ`uRQG{JS{SAt=*kPJie5uZ(#Xo*0R!JH8;&*KT z|8<};pA!yF)ZV-&6!^{U<(k9kx6Djl3_QY$piDf`%>7htz~g5H3u~+^ba>nEGTc9G z2K}_})VaW&%=5Bs#rhc7RDpJ|QbiS!y}CliF~)~JIHZGwmyorp ze5^(8T``u5|CGBNiDvO_nRveVZ7^5xdl3&Wx}tYi?oah_`Nc}4m?IsUs5^c(RFNZ< z3;dG8e_23Da;QB(WED{2?6Sr^z~g!V#H(l3_2CZkeMMAx<#t$aLFMtr;s}jJ181A> zDc3pu_mq8gk`rP)6quAn2U_n8Y=Dkkw`(LTz{LcYm0h&Y-Y_L^;^4MgZ}T`3-r+>R z+Cr{WU25)8cIf?3UaHqt_Hw_iTRf)N!6Dv?!F1a#*4DD91R;g@`d9LE_eb=4#jzZTrT=Yj73sJZ! z0kymYW*WK+YV{=KbU(4=8tkb5t?SF%)|XQt-td4=;>*MoN2_^30*wJ|$M7+vU`w<^ zE|$m~saL_r=}Vv?4_m9HeoJ1uloA(I zQAIW+%0vo{V|}d&g#qLT9Wq&MJ7f7*9Lx8jvx|Yxx_oUZ{HHFk#!ub52E5;|zm>0% zY&&U;$@Oq&R6ds81~s3U*o!8HCPBoSX%v9H!EllxAe8Sw_4r_5v%Ilg;eOU8e6*_x z^lykXvrOK@f!5ik!tLOkfP;E)gxgN1|1s8|xbpJ>KfiLnw@+Hrd*J7=@KDN&yx-gZ zLQE(c-}7n8-ZVaQ@rfgi8M(BW0z*mFCLhgJt5|3gpjc3 z_dyK*rbomOf8}mi8d!BO*#aC=IQTSW8p1KG@2x2MAZ{k{l#8r=BGIdgewUf&gHOPl zEzoJEtmx?={n(n)Cl-A=UTFuZM(&7c(vjT0Ya|Tl%Y+e3`0+lqSKsAzFiRCnO5mx_ zwq5Z`^$EdcKCL}c?(yPa)zG)+Cs5KTe73q>SH>=#aX&G#vSq}2A2;q3+mp)jdvLJD z#TGWH}~=CPxF_Ls@rSQQy=u zG}Z<%Mo3J+#hWWD&NZ5c=3^7N%_uS)9&V-bC$a_tz!)H&P_j#inF-?!(q;8>F(hBz zZ2J>2sByLnOR||L23#_0j^^=JxPSxr&!s7Dp!JP8k~(L z2ke!Y9>^>pNIibM4y#4kAPuv-?ADq78<&E+B<6e1InuM0z6q5NSg!q5g1w`sJL>0nJ-83lJBoJP`2bhbl$aDQ?w34 zCD{=Wrxna1n}WzHd|}j8Dw2c5c2srmz;&J#&W1j$rezfmq0XeDv1H<{XWt)C5ALVd zW1O=7F9i(hR+2U;hqTMS3}E(De8P(L9kSphW4t$vRz59Q=j+#L)+Av1%khk*t@*76 zT5_&rl5=Z)leK=w)wOP6!-Gz(rg*u2t)YgvZmoW6t#oOr)|jndsK<0&xtlguJ5qNh z^WQb9oZ{Yj#%BKUvw!es-5*2^-)g_avEk7()-~Ai_(zu>BWjO#J$|p%{Zx)hp)=ae zZ3n|mAOHgLMz|+-8VNntBalZnT*~Bes$AHb$q^tC7h0JL_7Gaxp=tH;uz$l(Ai<6x zaF^{?acC^Gw#?kdm_JbEt8#ND3QG?OOyhk352Yf*Q-i)M?D(-wt7$f6JBOr{K)T); zn=GRZJlDNGJXA<#Tyx65%y@QF3Yy` z&?e!xM{Q{KzD2`^ed{_6;O!B1h3x57ct z1j&e^@p;QE0WC&Py6G#?S9DChnOjBQVDxOgJ+$!MPmiKLT37sOBMRnTS^P0R5UX2T z+if4ATLo<3xQn_8$@ZKy32A#AT+Z_?gB@ZkE`#S6i6GL_v5sxzqJ`f8fm)td?%a5n|#5E>3o*>G(8^r zDPQY8sEM)cBJr-K>jXHH#7{dA)072y$8uXZf;Dhs`;SHU|)uWs8}ZW$MZOtItOY${HI zYl^!ZIMzL&_G;Ar#mhl|c^)DMP?vnCAedhMAn%B{>MYKWpefA785u~4t)a14PE-i@ zv>r;Q2`a{Qsz(UkAB65za7RUB=X3K&vs0JVCR7JbC&%HHI9|zTD6N~S>I3))IR|5+)yO^iE z`*@yZ|7xD5*(iHn|A$ba!(c>N(siS|*b%mkBJ!aa%C(ePH2w%e*3=2Et->gE<%?bJtfQ*R<*;)Z$ z$@K@K0V{}kL?o=+=>QRXB@{T!OPO(?39>IVjKDXLm$X?Q5xFhD67&b@oL;eW6!~+dZvg z0TW*Z02GZcUlB}93ZKsh&V7F(Co#TdUgW|z#S;I66}2Jecc~320DXp5cq4%;1e52r zZm$B$KNBb;I@@JyqQ^>%{NG3`MdRL;V!xTW&(hF5CqAh#Wut+lc4oSA_IX}|$jdXX zY(@x-c=|l23{yvE$L+*f`ARPS{{O)^9}4uSI;OdEwAd$K2=^x^?7i+|I_(nsmiIA& z4x<+1#dP&sI#z5k1t8jK!j%80BIe``#3otTk&wI$O7^-*o;HG(8Xo`~VapT*z(?oQ zRKasLkGG1CLry{FddA|gLDhPlBBY)aMTxyePi1c>9lK$ABEJzt)kQ&H&~^|6N2`d9&W?knkw^@HU{w%JphxQnJDFMO$# zN%Lh`iT9+Kb}C(}lp#@F3U0xfSE&pfnI9skp#uzz3Pr|7^^YzA$tu8`{;#1B{dmSh zx*HF!W!p;`1ztXV{_z#?HeDDn(c8WM6ZAI9lmmcj4jA%_|osvF|=+?tTMU<^0=BGhbSj#j^ zUW#ZLQ)z7+k=U(2{6(N75_lBdC@`^IjiN2t3BDRBPNeRz_^aHByaTP`8zA#qKASkd zX^b?&Nk8V$u;j+patvzro5k;P7iQy|pE6?&PIlY`ZxROrn<%z3A3!hC7l+NV8F3`K z!{fFvX5ku}Pf5xbPuT*MBgj@i7n^M^&}epqFfHxZa1fGjCedPFFrR!t(gl$w-IX@m zN_j%BRZFTa_dWyA8r!v_h0woOS7u!8+8m-$H2#Yv-5~{LSf1E?wI;N%qYZnuHa6}Y z)=QQsFmtaSBtOmw=`G4O3OO`-I)#px*p+t|-xo_Ld76RZXPz3fg~iU%T31T0Xo_qu z`eW71Nc@J?E^fqioQ;--<LkSO@qu@S; zD&7nhhQ4H`zFlj|@-8+siImdX_70T;8-pv;*H|d&FSZ{efX*1kLH9x*Q&Y?t>=`%H z8bV-i<~Gs)Iz6ND8{QhKR0w2xxY@3XiDd7LP^H6@re<9L3Sc{sW=y6y(lHDbKlzo+ z^rl!Sc&P_nhD|50asJ9u-Ky#m4vpP0D2B<{SiDn>yE<&{c)B}4bU)?*48!y>1rL&& z+AV=CJOdx9;Ad~J&Nm&!;|(jRl0^+ij-bXLrJ<6XDhJhvY&wE9lznHgXjFMyc*8Gx z+$+#FuQ7`-mM+zKL#*XN#0>2p@|c@BY{xm-UqBYfBKWq%tQ%_AkvdKD1Hn^}va$`M zd$Ws^5z>B|pnfSTjPO@y@kDLKD!wW-qJ7~Vyfr{ z0CWKbfh2OKrOeenQ4+n%Oo?+fGnKmG@x#P3 zn9>`g;Fj2?fqREyRVab3cM99(3BZW_3Z$-%j}BHx_qh!Px;aOI^8e5i;sOf^VJ4PS z>ahF9B1;;%FHn>G{E8U9)EIo`Ile}Nu%obNU&Zcqlo%*}lcs*vn#O4HGOz>@C-B%q zI5#pgMDH+4+H+*(S7WsftCJ2GqDwFa+xGILS^N}}hRNoKu?FR#Z#ey%Bm zZ(O}}A++UJjqr1-*01In8=r!$!6;J2T@}0FVGiOuwCp-0)?31@<5u|g73tYOD@wbL zJLijP;s^;X8!ZHK|G%Jl6mfoFTjpJ*8a znmNI)1c-<=U@1x8ViiW6!{cNO{Tx=%PAL?U@dI)U;%xUm(m5b(l_x3o-ND+T3qzyH zuj~QORUu$wwo-a$Y?-}I=SlJ>sk${exTJKC)4`nUM&{LyGQz>2c(Uwr8F76wFNxvvZUlJ^m{Oe~9n=Jk!yB3n>khq_ zB0%m67Y+H!z^l#nXzay+mJHtU0IwLluQ4W4blfY~?BEPD20JN9EhUAjG@<|IXd#{1 zmbW@48+e+0qr7I{UFG0WQoO&zPVZX3-dvNpYon@Vu>-5ISWsRKyHaLZ9-2yQlS${lj_7UuMrmvK^n86yS8J2t`?{TO(}}V`b4Av~eFS zcH|T!-xT>-xlw${F(Of_I3t_A*O)i%BP46qci83ZgnX5AFyoPGE7zq4ebdSGTEeg= zpb6A`Y-moC58Yh?kpa*Qxb0Ls7yMcAe%LeM^f#F=#4HO|XB=B8Qf7b?CVK8u9Q<2v z0RrOthZn15eh*i+?5oKumw5_Lmi@dAh=+?X4_$=l5Tn&3X|ayrDqClDIKUqze%V8Y zASWPcQ}mUZW9z5&3Len_xYkD$A&U?A6RbR{@qx+(ub*uMuG<0yJThHI_M+ughk{d2 zKHg}F2x7T*SMiH)p+53$|yJ80Kd*|k;CwaAar+lsktsbd%n5o6gKOwDym*M-6mtjur7TRI5^V7zs~H9OkQRDq^Nes7&oeqQAIR$3xx|D4vx&E>4AG zh>swj==8*uybK{BNv~*+V8j5?OrFdBf^iS*>X96m9x$tV06lPEPbHxguW-wg8eyQQ z>Q{hgB|(Hlmmu0zw7`!*n_uQq?iKn=*KFB(AG8oJlO`z+!I~G9)6r#t^pjfL!qpZ6 z-*f%I{#eZW{Gl?&39;Oa1*ikK_;MERz&?iz->88jw16FBxK9AY+A08o*ExH}x_-Ce zE~I9JEsAe2*+E~c|8EBxfJDGn`70qBA1QttW^)JupRc|Ja)2T6=DoC`XWHhJi~jbr z#ipaR7DmDDtwo53Kl6;Fl)-MTZK=6iivw{y&(Y;QHX#x5ssM`jM~gR%5#wMa#-Q`Q zjfYLLFGMPzX7TDOEd#z~$;Dym7NfzAvv>OrgTxMH z&GA%v_L%-6Kr1Gvf71q9Ii*o87siuzde-g%leLKGo|I@XFnKw|)+`=!?0fV)Z(vRxs z3M1VjKYmr69qohhx2*%kx1o+0DgJAWTAS_y-Svxd+ zOo!2}XywZ>Z+;7{p>1-cv0Cx`CU$^ zULJ(%=RZ%V(#ta3D?2_s6?s^gJUx4T3B8NT)Fva;TTq$WnXyY6@4YUqdUgVpE$9-z zFPvUHhrkUz>ImPQFQ-~bsX+B>i(69m9!bO1CUNZJtknpYkHox9b!&s{3k5EI93`e_ zAnbTX#F3&xN>iZ~Wi`NOiT{e$qo8tOH#WtLK(v0aj~eh{w`XR-#KxJMfjnx}pb%&1 z&OHj~weX9ztoTOq1u9Ufeyv2T0TQ}%2lO@Yp#CuwjCQJ7{7QrM*jM~d^uA~Sf1}ZZ zd#IfIx`W<+KTEK;_12n848G7MhlC2HQtprt_p?BdKZ1jfC5j+arSnh-V#R$G4_(wC zqI7B}UarD*R{NLn?1?u`J8%NY#KNJ!R$&U4Pe6zywx(g^^>3k73UZ(`2rgg5m9O^h zjmAeN7cyBBJjnBtA?(>qa{a7pt=mf(cf@@9o)^ozh{ksx`!t%q4GRq7t7f^v+cP;%L4a7yHXcGv-(*GC0wXUah=aOT{l$3Y+r z;puJN8x$1)<$Eatqc(A}qB6&0uSEo6tSJ1hip>*funu7TY5lZsl49Y=V;^&(MuCdC zYO%YeGfgyrdkwNeB1z!aLxg~|Uwo>W0j%4?gXv{2J=)PB0I8f^iGXqqoh!)yS_pdo zDiAbjKT#7#&KLA?MJQS1O353}Z#dK8S0sBLDQi3qht>}hR`hR;l->f>;>N*@Nwj&3?G*k7gh!xwTtic6PM>_7LEO6 zm^yMMppw-4D+P{Foud{tN5}9zB?+mpIHSBa2#ifY35dA~vgPm1AgB}OV?X8siy?lb@{0;Ds8=)cMPqcOVEVZbi8DX7 z(omeM?S*Gn1Co*3J%@5xD9(XC$MUxU-xZk%KYL^O0zz?er9SDf{JRYRpVcN8P z?UrWynZWH=9$<=Gv*}%u>`CqO)vt$3RBeQ3v6m&4S@+g`X&6S_FGw!-CYS=YR7qB? zJi6B%$z?ro5Yh^8G`xY}C~yEVe*y-A)oo1j9%P&G%z*cV2%+_&sMR}yp;(90Mz1mhaEPvBI1KA@WC-0p3wac>F!HnLY!L|4y2~=fC-GWg!J+g9uI<#m7>1M1~- z4k&`hDr!@oM(>~Sn@*3r&na#+I@jI(yy5Ux;}Jdgr|!AW=y|~XW}wQ{rX+>MdkMhH zvl`y7-PM>EFvFy!Y9aE_Dz-bYbzf~peSYKpUR&{tQsPfTm&?|cSY9Ritz2%qm`S6E z6bSc)n6mbiVhWmqeplZ?*E-rVP+;+KqI;N+54bb@b>?4^|E%-xh&|{0^G>~>9EUgi zbED87v)v63aU+1jvnyes_!WX{=+uXrW5;{?h*W(ln2-G{Vm>~bF8w#|skHFe{NpQ$ zaJ@7;gKi7PxGPGyx8{rg#W2+N0K`@vSlx0H&*a!Sbbz$A!<&&)` zc9J!16Dl$aEcTRx+schp7@sMXQ=sC_qt__0X8>HWH-Ldn6<5Yw|M@j4FD;LVeSQ93 zja@qUfO@b7sG?TKcd*9AHO&2sO>US~ggQw%K|;U+Ynam-=pmh|C=Hh$w{-7~{x( zpI78WXf}8D{63)cN)T%g=WBY-a@LHWM%gpCmO;9;+0MUR?U0cldY&a-w#4|M#L+Bq zSCkmV?F*{+x#ri5dS=!EAxwUXR3+o zvd6Is=zMzHGItYKdfS3II^MR}*J^~qX=UHzY$8aE8ays)GhVC9&xG>}ByXEc9pBkA zi*u**v|<2w-T|OEU-G6+V0yj4^h1OsArZ%7#}G4oC*&g2V^kh_!Rm}grcB64Nc$iZ zIBF0E-kSk(WX@7$$o0T+u}6WYMo)NMN`JT}jFyb)Y9lTo5SfmP99CO{VGqOLaK}Wr zmTm8N?aOG2_YCG1Tdh8fFt>J_pIKyja%FrFYQE5Wm_Xg;^@4YCUfA$HMCxJ&cCFZi z%v#KV`aCOIueF5U$Mx8x=*98`mcV1>2`a!>izh~{YcwxD*e9+QEwX7eku~f-j$!9V zxNEc0Uxqr150c-!mzw#6y&`pY?J?zIk0*%l@x-ygJ4fBc-k|K5yQ*(K+*IC3mm4dN z_lv*DX_()u28i1=RteYq*r z*TuVXBFSI0Nq@Dj?p_3kKw7XH{Ziu^ozJ>slUW*v`AreA_aT2A(Bk*--dzta8aTjJ zn^QJ{$61N?`FK2bGV{rZXI0`fn!$(V+r;Dz#Q~Uk{p{ek#L> z8N(U*$(W2}ZFWZqcurR(#kIij7gDcVp2W-dL#S#t79VAFwiZ9c;N&?(61ZdV_M@|M z&U;^D)+J{?Bu4_bb#O`o3vVVnhsexl1x=;fXs2|6Enc6VyCx5lk|HY{p*8F{k;(G8 z^)jzV^O8aGN~2(Ip{33u+_aG#RkNY;f(3L?Wg>>j+?rnHVPYq)bAfDA2_=WqYg6we zi)>d;8|0^o`qQRMy((pl;p&u}XU9|{E=93>lH&@(ZJNDRON{!*np4w-uzSaB` ze<8F0YksYMkp=@$>{HGnZt4@{riRS7oyLk;pRnVhS|)ZILALsfpx*pyH;u9vVn><5 z=)FF@08nf6GpMMDM}g5!89EjKH=#yt={|3*xXL@0F@NBY?*;v@#nwXucBw7xtG&=M z`{Rh1o$o2$EXwDqC)m(9(FH(^ggb4F4IU3DS4E83Np~7gV@l?i*YVb#;^?+|j7?UB z>f#(54RUYmsdDeBa%+U_m0umEX%T&t#K0MiW!uXb#(^<;Un^m%ev(JRW^%V4vzx3} ztBdxyZ7N$WiJ79V{IJP=`fMqU(mq!)bE025rv zuE#7ct7tR~_fZoiT2(tbU9#`HVB_wJtk@0uJjDJO{0>snT7#E2MEZ$gXlLKu+!+QT z_rr)=%bM1Mt!b3l#e4A1=9_Orhh=#|E!Rmc*XsYi&Tw%auOD6SWcCz)#O_7>(V_Q# z#VLe;Rs=v^4Mi}BsQ?X)CwRS=g(GU)6q;{eRN*ni)_mmBWc?E%>`j{_{bF$@@ZQq_ zB1tN)IUizq(~ytg^p*(Wc$Awo^GgClqr-~5o54vU>>ia{Zr~737nA}-vtC#Ce;}(P z74kSE5@{9r(j1Dmv@TH(c}uiYB-V&u-8?dR_zte=o|v)OF5Tq;$JMymp)hL>ST*a~ z_A=$$@#~JWZ{WVDcRgJxzUwPL%y9Vpqo99az<1n(D?$APWH`faTgF_l`r;UH zT=z#!KZ+Zqcg^4#paI;ubX}d298uz~a<6NP^P3DmZ81CIfpxif?jGGr38X#WUiM=y zXx&bC13fG3?cOYxQ?}NPQ7mplM5af$F>PYAVVY)SO~gg|ktoL9@oZ3T@!@_; z+$QjrwH8Rr6^y}#a18x9EFfy<4bEa@XtQEUKFrd387oWIQ-t-14~g~W9Y-%cMf3yn zEB9-?*4NVFx=IJFE_Lbt^4h#F(00vK_Km@b(GYBHY&HeV^q)a2QG>7oaZW~sEws31 z4Q}%QG#)Bhc2Ma21zy?L%g%%Ym5w+Q5<+Ggf|zT^IS-<1nx=kmM61@!^x=&ZD2g0P z?+T|IABv5>9let43IP4~uf!jS(+!O6s^HjeOE$3YRA(e<{x?%6NkxALD_5)dMiyf) zlVrn)lL7_Qbo}mn-B<2zV%=^BvpbS4%qIb3c%!OT!0))#dSC--m5NV6E7rm6y$co| zx1v|0aL6y-A^_jw+pX5o&Z{U8A_2f6!@4{0$o}HD=ocabn)$mcfGv!VwqbRXU~1k7 zORF2ye#btr0Qk529s2Z+lkAob>TYi{^xI!8cqcZ|&Y!29W$_(Pv7!63ywO{HhJX9Z*{jV#BZxu=HjkOItoYf== z*#(4ry|?v+%jz7!m(cqIgr{&61dE+9_l!Fp=B)G}BS||o^7!_?9GKv917l)hOkDES zg85?L)#ko(bMa;2VTEPZw!4`(FztxqUkCOSEFOw@Ly!INjzbRt%iXA6UOpJVbnFT* zOG_iZtYRA~$i${>4sWSVPw`DaX-gixRs36)iEWE7A=WeH>bE;WyUX58JGS#|xXFnI z1Uzv*o_RREO-0x4JQWo%E)o-CWBSro?dlXyl!?a5n;rGu)?FkJz|cDINO{|P%59_W zVa+eAJblyHfJZxRV5(!m8#A$kGgkZez{t*3EOo7GjFdchj_kX`b*)9ReGv&ReX=`d zC&s{>?@D@l-Rtb(P^R_rsv9li*~xB#O9KpK;ZOqz{VV#zY?`dCIM%b9-i(mHxLN%E zWlm857E>J8kFfT6;oI2f$b4VNLp8^p%vK81-Fy_X5X!?UfvJTcQjwQqc`0Nn|6WSr z{YUEe%eBXWvq#Id2NL-?rt-bFFagzs-IASazJWX@oaVk7yyDU?Fu*xtye+4#@Urm( z@^Kr-{OTFX`UZF~+SvNer7Fj>f&cod2ErQt1Py$V+Qa&}PIF>ww7-F3rfB^2Ppby3 zRupy27N0T2*Np~Up~&k}(5Wz5oI9Tit*(@#%amCiy%bukg)XI+I;&b?&ZAnX#c8F~ z;;hzVp&;uN!+D+H(-P~TZ*HfW>ODJ9Q~gD7I-6~&knU+6hP8=sZx#yKT0ocZr-TIS z;L(F_Jy`PyKxK=~SW<7}>-8w8SWBymwg~-EU{e5wQSn3xR87L+xY~5I91U9yS+tLo zYY4QEr7C8{)1IY2Z?pJVgBn@MUuYnPkJ*LQg@h(1%7lEj4gOv;uKGZn!w!1MZ)ELl zn#I1-cKv!f8zi3DZ zoN(YMGji)pj0&z|_e9F=tMBdO6DI$`rH}!|nhi@3vql1>$p&XRCDPTU%j>2VZ1Bdw*+LTku&DZsHe9xt87;K-4T zu#0)X@fV(l892n&pDu(ek@nTAAH6*<#&mg9x=w?z0+0k<4xq2tpZ>3_i$~Ee6}Kn~ zw^2NiP2D>cLWq#&XGaKpr>;?*g!;fxZ^(4Sj%pgVKs0JYdSN|0Ab5K4^*Gk)80u>T ztLk~B=?40~D0rWN<8UDFE{lf~W!SNa083S7>T1cF!tQ`HWixUo!Le1;Tk~j$>B#c? zYEexiNbhKPzoe(!OBq#6o}XKodeKou?=C>pG$f!35i;Q;1MC{huK_^q8ega{1J}1b zDE42&Q|{u3{K0=(5wgyu^I5>wpB~SG>`s?N){z{q=VVcfn2oUiU*$q_mFod)M+ZxR zZfd@S(Hw+SKJDA4hNPYz&tkeapjh*OHccPWS0MMxc*_LrRFa_AR;v>yu*n_&G@can04?4K?BV6?Qd2f7(yw7<`fh;i3>8_GQsiyQ` zxtq(|(17MHs8CnOB(@->k*|$qXBk zXnh~8a_SCY9h2J`F5qu(D*nPKJLz&8X(-C0NxXiOJK9mn%drS>x#47a>&fz-Qza_? zduabNJUd5ws2+_^W}gGqkc^HYBDPsZ2g$_&YqA%GcAnK#$;(wv!Eyr-a}s6AS)O9$ zJ?`Y{f@u(t9p|?egZePH0BzvP3hweqY+zOydIuv)39s0$ey%egUTjIoTW%zU=xBbp#gl6M z)|n3i&!Qr;6PODEe1w+DLJ4M#LNNeVwp!|iJnSrAYZq9-uZd$bubu6CN>VA4!`%Bz zONn_bib)1yl}4eVTR39xTDu?59~An)B!Fn1;8l29Bp!8_#@hErb{ba+e~FNbi^_^4 z+}-go+tuV6Z{>ylEqvx-UrTr|cjm(vKFz5uMPc}KU@|-XvtEsy8i0f>c zsef5Ow0nf)5`bp5(9Lha`Ip@qHDmQ0B7ZoIAJl(fO=Qx;zYlLettRAsw(WTnzT(7gNzxcqr$nO#MsDrVf zhaQzDZ~#G3=xI3%6ZER}u_jjSDA%#SsH-V4J%e6kPr^B9zY>wSk(`8{x|9 zK3Xo)1mS257H##nT?v)lo*~87<)w%aoJKPOt~6anhhq56MaDA3=;>nBBQZq2*7;m$ zz2+Rkzbxd^?)Bp+7Qgx~Rp{bj9j!**%n1r|y4^DzGzt$6FI)zA38iZOibnRLy0^yl zmSC<9hH)#&NXhRS2q&PmCe3s-m;E|aU0s)~kW;8{aS{e~hyK2KmT4lX73Ctn5DWynaxVMV>IZ;irI z?C)p5vf8r-)G|u^5-CDixfDlu?{->6E|A*+3nKmfS~r6J)3JjuWp zmySg)sa|qM*#MwoJ-$q~x?bH5<{D9))ZE+e_DHg+v2gq-2EyuHQh*MVEJD`cv^EOU z^0HYhSR7~rVJ(5B*=?db>llgyj7>_E!BU@$q?A3<<>LK4$LfviQ+WkTH_Z5m90CK< z)%3TZ-T&fU0nS49rK*MY)s_H2u7;}o;0344!M_NgfM@u0{)#T!PZ3&>v?IAnTyFl@GF0Y#rSZUbMJ*T71#^?<3{WmWlo11yPXW6YTn{%Ds;9?o`t-)Mf{_ zF~ejG${6peN78!yesq)VPU+7i*QTCm~ON7C3{q~)# zQZbdRw*x$2PPpy<%`_2Y1x+qp4s1o>q_9O=Y{{Sln_@>#WLWKKO~*Mv5ywD{r#uxd zAGc2|m&0r{#as~f71(7A==6nOs6Y$Dn*FGRmUXn1*Szq<2 zE@Ha5IypDdTWy8O07X&`5c0ryux(9THfe!?=ApXD>h!ABj^FrDHYTpy}MM-VMQjSr9ZKIeahU zr46{x<};IdUcrt6ON<1wez|V82_#lp)0Mc)`PFu}KlcTU9m5QTg zj4GBnxGF~|hBn+`pGe;xU55P*+>Rkz2W-a3RmgSmG2|tsDdebC+j|Cy`TNC}ypDc4 z)SfTQD)+29`cICd$~wkORkjl05l^?2v8xmUu9fSgwb>d(RVGBX56T4i#;l6J(q&q7 z89BbdsqskSUtGlURUDPc39b0RLwg{WlI`;n}9~&6|P1<7}$8VO7RJB^Cf*#bcLsWBw!W@o`|D1-^CxIHi^faY`ZPU#{?fv^7Y5lK z&1`R_)J;oNDrrA{5Xk;GuA{~prxuD>=7D{Ilt5?fvJk&bXHkFunzTBrFIeNo{#1rz{)K8qI`3Gly-y`bgaD728)2xmt10FNF@nZ zJoQD;un;KJ*QU3z;)}y?&x$g4V?`-L87uUoaFJY8yTlVKM@mAG@o<<{rNBI8Nh#pT z7p%GkHzu?Rgz%1#8YbBhh#-|B9L5@B#bQ$L3(GlO4kp!+e}GsTN*M6-n{KI(Y72h~ zEYBO{FEHXND4P5N)3{JmhEv zql+9^c?xm};^re!PL&(Xp`#n`bbzmm!)){#nEJHz%cuAsA%K1!a*lR7qGMss`%(b9 zX#D?RW5<;k^t!A)xzfM?Ff092Tk4e_PIX2(7Iy)q&M8XE$Ro)*Imq+ z>w53M+ehWcinpTq;veW-SS+w%7?&Hc2um5@ zBLm?*s2T#6=N1vic8Zi-hicUkIHc=vp*h%DGc&XSA!W$+dqkJXVcM zIDKx9wvK@q?A*7>*}_(f!b)C#6mgCT;qcsoE`m03lr3CEE$V zp~^l*rsKs%F$*xj*a4TeTpz)f$m{4=7^w2jL>8gF@cxx88;CEP*p%u7L{k~geT=l~STM+2!hWo9%f$z{Qy@(WV_ zWq9MHj+wxvulOf5Y~c+~O!GrQs31M-rumY5dRe1|pgpoCwBOa;j5C$*64CeJ;l3JI zYc)>oM=PeaW>1e33q~^E4y+_VUO598qiF^48rh4t1eg&!7^V$ueQZoXmuLyCIpX*p zt33v^DtVVY+iM=uAWCo;&B$JRB~ivpQ?ub)_vFkXk=(wVp=2C zVoe1TN`A=F)aU+~| zxgB-oJn0Y^-stu~N&@qhFN45*j78g{j}gq`P`O$UBh{mO!-kdWSyhohkDOn~7lbT; zKpr36YqE&}ZD0mLgw++zE;jCpYfQ$HI{+ z9DGecJG20vC@7eF{K?@Wj1g1HhJs*_#oRs?d)sPIMD-?%#mrD4E%Rclcssg4l<|B^ zU^C{cbX^)tEjM=$>?+yQr4RCA8@IWVP?BpAkRxppJKPsLiI>BH9$~96SkPRG{<#L~ zr{t-lOai*5;`#Rlfw!0O(rt#uF#V29ie5LVV2D49$gG>7ZpCHFnunyOO1)MCIsstwKWN z-7LOFlLy%dU{Q9USO#GGrD;0^pCi#E8+TXeD%Jp0J)Aor7)@yp+5>G5!O_!ZD(`qU z1Zo8Y28!=|ni-W$Nw>UCY@k>#0OgA)*7I}T#yQ-)K#dyP- zd&JxMV=iBI7D94}?vq{|U9~NgFv2f{;VW(g8DQn;Zr}^bHXH$y9G`leB&3iShME;N zf>1bOir+1?H`kn_&K2Aj$%LT({N{Q~6%E#Z`~%%o(c<@4g+H81&s8kS1UDrrM(0hz zb~4KDyvRI4j;Yw;j>@^Sqs_BScXRW}Qj3&|t=$>`O0YmR-vp&HBuyReB7HGL6L`Rk z6nEKiBPQ&mIN^wrD2BC*tQq}Wgwq^>=y_QZfO$t7B}Fi9HXs2o zc^;e&N?e#6-Ly{fqV7YgzJ>^y-_CUvB^F~xKRUh;w8R=>cG+$<(kb*9gbo&sO`AyA zP}@r^kFj7irjYtb92wG~4|KX?yK1A5SW;d?^@9vBOa(e%7;qec5K(dPj2W-@I0I+- za=?6FF~KltSWSgfju+dmR~0cBHoH(a@ntc(H`7ek7cM+X4RoAMJE@>R{mjk7zUU0& z!L^azdrB}1$Nu8)DToxm5NN&4YW*8zVeQ#4vMJIL@ikmuKrp`|N10Z>%chTO82Yye z`SpDGNc3(>Z2E{+9Oe`w_iZq8oWLVTBy)W29MRO>QLF`oD?)XQv1k>4jmAZHn8896 z$b0q(MFgr$w<#ganoroyu{GTqe+aB6>*g-K$&bU3z+b-Hb`Zxryup>MOc8M@i!Wcl_i$Ep(Jya|MR#3uZ`qTU{5;9 zP`g-!T42TU)x|?3gYdCqFbMxF7z7TYrD3T!e9UeXM(^&JJ)La7E)mH9dBw1A{y8x8sXeF+kh`RQyGm4 znrcsnc0ki=^mG)vHHr=W{ZQF2p973az=48&p?Kp&ToFDcOlBmS97GwNc!rMWQy`P| zfwgtJWq^Yn5_gIftkspR1<-JmA{B@*D~@uBK?PmM3D-hBO8Ib5ZeVW3zAREzB1^LD-LG3+4XX26p z_LyW4#L+syaQ^dZwx~bf&16}ig!qPezbghH+~T|S>u!g7g$$v2k$eocSP=TkQMwCcktdTdmJl< z3LuIdLMI~f?d}zcI>~W=7J?~mC|bP}>2QAb(uJw{naOL&AkV3v>WWuqi0a6OZfS$_ z#0eZ5#TZKs-q$!x^d^}*b5q#PzvU%7#LpRZl8|DYN^0{u(%K4ChBq`Nbut2Grz7gs zvxbO>O7?2C;+Yd5_5Ztv8Ppa4O$!NOS0EVJsj3XY-8<^D|icsgvvHFg`gh8Vc%O~e%pZGMdzmG9} zn_YdFeF;S;bFFz!HU@5Owp;hfPKjrm?VbW=cvla|4XitXASwi*F`ZF znJS^ovZw|OD9eBnGui#80ww!lDIRf3ruL`{T^OaMjL!~a9etfEv7T~Hd zJjRQDFJ%a>2^To6=2H{Bx!Wga6N@t!rk*%`zUyk?V&wkiVb{kom^DH?Z5UoxiQQO| z^FZRf!K@|4>%9k1_&K=XVm&T`VL)Z?;eldUe}Z|1SzPl#iL-ESL?&bTCys#ZM#4vM zNXUo@D@t~mp>S2P<`f|sNPgTKK9);%q&Q3B#l4hD8Z+dJzx%W<3H(K!_?n;xLpw)} z_rotKyC@XhjIV?IQ>qJ^)DVT9Pj^t1&eg8iaK(HncX=>`NMt3WDwHRU7>=xt0I@oU z9UOFy(C-%GgD$u!?s^otgnS-0iYnGYH_v2m`|z`;jF5ExOW=J`(C66xRL@E2ldP^N zBK5*!i*uJJCsyL9&>exA>)`bHD^g)!0n7=(|6K^qc0Zw#8%y=^7Au2ZyE8kumO~!gErntSLDXwtV`04ozOWgJK5M9^H4twxe z^E0z&m%jW=VLSxosSA_m<_|0^UV1F4ecs^w3Ix{8lr?%uK-MUGzH?1uv{0x{8Xkju z5XK9o1KU=pzfzy+Dyy7BlD)oXgIa_CyrO|lX#LEO)YVk!db8WDulTeszDNy!H9P(y zSZQjhsny~7!$#AkROvtiujG_KW;nmvGPCDi7Odt}mng!yi?oOhcZ$Q3lB?rdMaH=| zQ*QFu+vG<6D9rcz{5iu{gK&`SQFQ{oMy9jWrR7Kn=0f9UoMOClZv~%e9gr#*90TOe zu=@{ZtKVAgB=EV?o3XKNll=AZ!o^58QKE;G@FCpuHZ)PTNsw>iz>g8u6ZCH2DO3gH zH2p>Fu{sPjBVpay6!h*^f;UV^+19BGh0ppX1ks@4MkU@MJ!d1 z8#?-~xTKI&r5H{SS}lX6gJ4!pMD6soM_1$L(AlcAbP0m9@S0JsZifb%_SV~3hA9kJ9$YvN*)mRX07xs4@BzyS&Cb1v+^y-3K+{Up)GG97D4`K}E!^=GQq zl6LDRuR_g9@>u&PUhjTEoDr@TDm>jC9jHx(T>ag^?N0b!EkwaW4B!*r#BeAX6C`|3 zJms!Bfi?~X9>E-pzRz(Mt1$C2oxnz0E0SC*3ydV6REU8hZH)!Cs^mTrDS#;^t8lU` z*oKkT&l-iYsz~*h(h*?tM zuTi=1)WC-VGNujNx<}Y64{IvW#Qme1)C5(ABHzXU!=SQ;%NmvNQ`5HZ zQ@`1+lU8fVat5mWABHH@1IX&C7MIY4p)=~pMZeTeRrZ3H>Udx-E_Y@Y@c_zX^U|p~;G?9r=vtLvQZLo1LpPSwvYQ`G}&sv!-Lu^}BXfU*QNM{=JCa-wyR#O&t7+RDoq2MS?&bG(2woMz&LmD zEfVd^#I(KGKAP;-_SW2RF5 zE#<5saKSa&FNrOQ-^aSrZzhJ-dMehw-3c@~^Fixk1gVBz7ZUwAW_ZYw>q9=>8}sg( z)VHQ!vykLVxJXx z4g1B&B7;Q(GBKO(K$R{hpkCbcUMD66=yGoqvBfD_r11`W^e&xmK#zUx9PO5F<)TAY zaR3Z+5tjR^b@0Pr`ui9S0$8b(0tb!>9`TJNfyH0Zg1&+^;DbQ+!W3IHjV)uPVp6M~ z5ZjU?lVqou_fn*9KjoYpVXuV;h(KH>dx|~Nd-{kKA5ko675D3`vK4xSBk90B?Kb!J zKpI_lIV}~Xu>}@dvuDmx704T9;t}i}=E*}YwVnf>vqy!89r*%GjaSv{3~1NuSZckB zU?ESc)_N-9y6Pv360`UeQtBZ%EFjYJETH1^vuQw}l?VtG{fJ9+aNfle*2C^3G24^I z)gX-HvJaW@Jm@ZDIRQz8Y616tt4T2BZ@gHDS4xU2|zy)yoSi0g5yM zErPGs6=xU=;EP&Wk350vN%m$H0KO~d#43wb9|+7CdrPvDTAz5(l@?2}b^^f1q**Me znWZ_gs_FVB7mwa9 z`NjOLSFt{DWbBF6L%|W?xIZsN2VF~OOFpc+!tyTZU3e`Nm&IwZ<4@JL)l4_eNe;DO zqDZw#a&ZUk*4t@Qz!Sebz;hf9+@X@s?F01~VTI%|5~Y5$!CUd*D0CKAa_G%i*HkKs zY}}7aldTOsM9c}%0)HDWllIl_US5PB2oivFg2qK&NADNpIWPB65=A?v8sN0s#B_P< zXtD?o*@~M@*u`CHZ1W7dl15$Qp{gLT34rf1a4aB5Y^guS8STv)W_|E|II_mhsw~~! zTg?3fxxQ(;zE<#{ZjcimE+lE^<8W<(%#7k+E-$hQlHa8FG!&n{=uotpt{_O+E>oF9 zCxz!eR^!d?a6u{QFJo~Q>j3(3GUdP*t06QW7M5Z`CEj=~LLen8m_A`>JCx^ zzrdw6+w`}21F+7c$gplXN zaB56YfBL0cT<6`9Acn&Mx~bxE4O>vnC+qo%O->dvGthW!wm^yy%BhGmg*4aI6FGwL zk79_dMDJkT>;Adk9RZilShnq2?~+kF;=YPT)bzYB9ouQH!R}x{aqDK1lx{0GlO7b- ztWrR!zuB~tvHkf5NRTG|0O-`0^{-T~QoDHH)OtDn#;t!ZSz^E&D4A1sNy}m`eLKQ* zj4~a&oDSSSb?U}Y66ZTXqp#sk4z=!bR&QoDN6erd-JH$yBsuAKD%4WbDw6$36|iyo zwE`S7?Wx93kJ;qf#nc`m zJ5S7dWpmKn<J($_CzGOA^E%vpfDG^d~&Q^8xBDj z;mU~>vGX@Wl(|Omf9*QZ4l)6+|bBuBy zI?HwJCO;YqwngwT;20GdtC)H`G0sPcMD5v&;tV{L=u!w6`t5d~91V>B}K4$718YJkr>Hq@! zF28~~j_i}R(u}5#*Zm}X6w9%U9~Dsb3IPF4_YC8|_1%5)EI+qWv+w75mIZhR9PVrP zAx?4d(S3-sEBq<2$$naSmTU1TAAc=;%6kj>lmJ}qfzY4IW$0LWP)IT(LGtpNXMk7~ z4JCXxSXj@ayCjGsX&!EkquAr~ZFeST1NueyXa8*w2fj*S+c-r)0%T$sWmj+O=IUNm zBOz~1sJ0A%)PD_h3a@_<{rv`EmtYxj50seD5xIIPrF{2hw0+Vp0%)aK!K0H*;_U!+ z(S{cwfaU^1v~FftEv55)3gPg(SJ6SVM5tqO-`OM55PJ482~dV%y6fiZ|TMfQ+H*28Czx-S0t zr>?b8H7IBmg0-B;R{M`%L1dF~e+G!`VtEUhghy*S3scffXQ4oUPU!5-p;7xBCbdMd z-n*RChP)SRn$@W8)+FhY@xVeQggEYnsxOjP>fvcLJv{c`d5Zk6wTfjA;@jXZ_3w}J zY$P1rpA2ufmF?*j6za3!qxJlvOy;LfpIM3P;-%Rc$m?=ijG7>Y_4mC2BKWM%*2d66 z>w>*cRhZ0b3iOq;^}EnC6pigG;*>sD#(rvcaV6me_2!YC0ar~D8!1WS2?0TqhT$2G zR6YZj95wF+(FG3~TM)5ldSXH5^VgL4^67ByHRIjidL0?=xkqV{Rt^HqmefQTz#?|qaUG-M7tg&E3t1P=(s-Y4|!Uw6U-Qer0OHuy= zl{j(li4Yz7G9Itlx?j<~_@So}4U~Z$lcCn#JteIAUw2R&@8tLSdOKejpPajJVQzM5 z^*@K7B&_R1Cz$iX>BVy_EWkfk(+|3ucEgs9Y}n{bjz;VLTcD=T`(n>LHaXsjMz}n= zICtT(7sD6(I*QGXn5G>ZFE7P9hJHC! z%{LxBQqNg_M_hIHD*B}J^wpt24oPSjChgwvY*TjwE$U-O*i=2}Q?MFr$dt%&svaOw z(H-oo+k*zH_y%lnJ)2}Aj0k6+^lIB%rx2s$hOyD!jHp1O`S@4Jc(^|;;spvt3h|vg zBE}=OD9DHnk0{Eyjxxy3@RdG)=PC*E*oWG+j zV)AJ4v_IYt2bvU((pqh!Wscx+lw$-*4`Cng5~*;;l$8nr$D>9l+(Cg)&(>jKCIY_W zpc5(To?R9TV`9KK#R2u28i!dV9>_Srp|2&Ee_h!t;!l1naNak6PO$`61#&&d0=zK` zQ3vBqFD#y3ycPqu5)b$r55Kxb%vGYpwQppZMUuPa`{l94K^klX0$7PdOg4*78#_=h zo3e}nG}Q6wnC;s>r)K;4G2b%_rxzFBd9B&2W8JQ&>3UZ7`-pQeE=gKG2UqM_czaGk zxS3pI3VNA>-;F6azoIEfQn|zeeMad?hl*WqwPov8WLdpD$?owNsz@QqNdg7Y>Er>s z-mG1rpRDQC6~@zCNT-~{;44OqJOKAEvQUO~u)qPPIzwmZ(qT;>C{9;xP!_L9I;NP6ey+%d6#j+qCIwuJ_#Bg{kqW)AQ%2#_yXy zb7^LFZv5Qo`7@W9+VP7slXK(q7Y`piaxl&hES!0Kd|`gldlShH$Nh=<)3aw9<1b24 z7tfzwoSvJ%P&0s0!3!_D?$gA=J7+u0Wv8brEWdjQjB$A66?Dw1h{G~)}>6~ZEmQX42v+g#`PQzn>(reG86q;vkq=+nwWBQ3+dM}bAwjLqs3bCl1d{m z=oEALW_g<)21m!r+m4k-M@yo9+#zanG3#TkLF}XH<}>CI*=`;s%362^Ka-*9viSy_ zgAFB;(u`#wYxxRV+y5x7{ePpio61+jS6lX#uh8qdKAzYY#xK&z-Ih$BrZ8B*6CNC{ zdl7rK6~BaHsT>)>XB@$+_~5&mI9?3kC62HRaU)UK0OW0GOIVhMT5nAkx^;~8&?6(g zML8NWo@!sLUQrUhhHflcvau-1VJY(`Y34TEQp>@O;fKhyI9J<<&*y`UoJ{y3?i|I} zHSz03{=(Gz$0R+g^kM5-?+H`$_;|Smiv!={QKao_cMK;d>sp6;d&`{?SDLaD{Zce# zoY!`?iXCx*%ci?VGQdiBy9)iV*R{TNB=%RtB9B)AzZ;kZ{Kd=rr`d5rgWDlGxvls{ zpoEgQ6>qMN|FCZR>%37ndQJ02-Y)*65uUu^1H9kC`L1Yh>lh8YsZ~5k=Nyyu$4uzi zEcP^y^}733@u{a6I;MxQQs%|=FZWSK>|xK&@?^WLHA-kd2jJ zOf(|5%foy(T%6#H32k#xnh~OHChd&@AsaVt$_MOj*p8cRSK3Bb8Y@h1=e7&b&760b zO8@NUC@0SU$%cf^3R85T^WJ3;xdZo^L6il$$38b$wu&F2(|Uknza47bSMKMOz}FM4 z1DxQ_gPb+c+U#5v{}k}8rfSTE^$`YA=bN?rSnaIR0W`yRay@`y)DawD5M&xn5AAzk zgP2hE+jus>yDlh2rCaft*L#kkp}ihoyS^Tx_PynfZQN;ZsPB}mOB>2p@!GJ1nfnn8 zV6#1%&B@oqQxE0XZn0r6(!dg=r;7^XI)LX1({YJ3W?)e#rffYK?j>uE;~N)KAI9&1 zk*a$S#aL~60YfD=K<9F-*>kfLVIKIk46W6=7yfhd20X?N@6W^+Tc zso9_)qyn|(D69h)qh7qd3EYqg8KvGJ``8gzxe+I;Lx&ELx1x10;OG(6+^}O~9DAD0 zKN*%kL95s>oen2Ed)`Z{f1Lk4oUiHmEzX+p1Hk^UnK3@Fw%M-!UU-Q=Yl;8hiV|P< zLfZIimiQA(CAOoHU-&|b{9hLNL#tDB|ArS*(x)uxYlk`m$T&vxF3rNpPAyJ6Ci^;Z z`Si?Usq>AA354>+i;MFUi;abIbMuR%mu44c&dyGq8Rh;{D)9`GC@g%{`blc8dUxkxI!AA&8s{!g zOrA#_G4a^U;sS19vu8)+r}LG4j`l4~@a|&cRgZk}=mUoijplM4J#b<2;-%wYti`D( z4_r8Sk^RQFw|MT-g~vFao}WB-9GUouyA}>y7(H-y^uX&5^Pg8(a>vikUZS7_(>U2r zJvljbadBpDmPgammu4qDKd>+rNAI0Ey?DBF-PKN;H#0XeKR0pbVLKC3YFE5@*_%0s zzPC7Y_S_=Q^K%!Gw&?sUuQ_7Tujuuexl50opK@dzDNx14^wjL+)WrN0W3({UShzSd ztM~om4BF|L3&=qWk6(H7#%J(3AtZDsA=phe1j?K(D~>tqs+ke9LCn-UF3rqOomqOc zK;s#drBCPPCsHn~VBzJ$x&68{8$Dy@Pft%ZW~ZK9RNkFI(3@E5HwiVD%1&5YdYFT9 zY4*|rEnrk+8-Cs?dx$sz5eT$9Bb5o3dH1x`* zfY6z%#@UNZyLZT79Kl2`}n~Gn<)C+%*5Q( z#NympdWbHs9^ZJz1BXA(16*e2x<0p!jmz^hi&F_p*-}UuUoFm0&7NI6r_fC|E@u&^ zCm)}kyL^7?%vp3O^Y6$;|9{NAO>kt{b?5geQe)boX;;_`2knr@u&r>=Ll#k0U2HWK z)C5rgstRfp0OF%RXw9S&Kmy3FL}qp-vVdySW9rkKu`JWJ>`>UU&4m_PXrYA`6Ap!A z7G7{M3oW!zOlZM{7Fuwjg%(;U!v6jL=ic}3OC-9gyGs$S=<3S%?$^2Jp09iEx#vAR z*jnvu+*>W4n9H4L0dO?{Ld&Q(de)m{oLE|T=6jp#?{s!o_SZWPSN8TT9VX)n?(QEK z{l2@gQ+1DypaSp*0N&&ms4x=h_wvQWNPG*T1L~ruW~jZ*?RT0Anen66+)`*IKDEoU z7QRCCvi^toHPVj;lVS;ksQ!@i)Xte4d$15x*&B9|4kb4Bb~a2MGf1RA9VM(9%d-ok z*{JpU9PB-ak&VpZA%7R$1-yB~nph0RdFkjC#^_AkylN8Q2T5EiUN%Xj?$yAo$ zc_zaEqb<5YP6=Hjzk(jbrkP9v-Zv9IFog=H79Gzi1$B^VS@_7^6qK3NqgBrIqLN6v zbGMl2*1_gx1D<$F3kU_*AkXoR--9xX%BB(x+2rKLq7qA$hDt1|H3#hvJJNn`%$nAu zrsyhMyk{2@; zt;w)bfdCuB>*^atG8!Nq4>5X<&YI%H1QnJOGMPqU&ee~FP1Ki4nA`wmC7=-OCnu@G zbY6MXT_(${!%oL_MP8X3`zQiIQ7An<3V)ejtKcR^lisKL*Jb=Xtdq4Ifu}2sC z%DH?4jFW`@xh;v;cn zxksV}U738(XKZ{SC+MI7^RNez_D(of$3i;kb+8VS56fKBJwyo5&MyPUZ`@}UREP08 zZ``k<+l$HbvTLBaK=zF;hYTixim>TE2i=FyY1W{vGB_;8C!?D3MBF=217kNud)8J+ z2?pOFvu0vK)84bHHAyBHyJl&wi{Q0{5hI~uUigK@8G^`t_0uCeU=qI-Gfs_@C6>JCty zoiST-R-7 zp$2+zKyOhsa0XKP$M}@+$&?VdL?g&U!*q%1rnkB?(K&^d6)q@%ug#)bRz=~F+ybpR z=l98&pRaFE3ZsliurX*HC8t_B7I!|NDBH2gm(lJ;P-eqj(r#R12Ga;8=$~LP$Uc&| zPuK`#(2(_G6PVEG)wG?p0N-jVWqoue_n*-s;VNp;s$+;1Kx?ejN0eShJJn`X6&t4k zD`G$l714OdyfzafB$oHV{I+&GoWFV#P!jElQimZ5w;GnJ&0^%9i5# zti8uoz*M5Vg46*7I%S}3^dVlsMOF6|upv^gjiJ~s$XfG%62LR}`qEiHd1a8-6; z>o5~f(RJ$5Z>|9yDvdp!1Wi!+HL7x%)@%-{#OXtPc!uga8HnP>7E2az(=e=9#yMoj z=*uKBUzTmhVnzWcba!|I?f~{J5PJh@fq5#0<;CQ5N7+`LH|P( zwswU<^{hz}AF?+ac{k|+k{CA8wJm~1xImFYhBlJ=m+d-o8d*=@jclLEQDh%#xx!6( z_o9=Cei)AOtE>#rTE(~xRto^k6$M(XDFh4i>9Wy0R%p<3AGjnX&L-o$Kefv^1wtmi zE;l{i5^+wU)hJkBmLJ4^h<=JO^FmLHVSu_AbE-pu^0^uf;A9|dl;*VFuwjyTt35|k z8aG>;pUlcC;^OMQ4TNQZ;+efqIP0e^W?d=f$)wYcGYAIVfd%EHKa$h43vBL*I6F=X zN^*K0qFS6aow0Mq?zU7BwT1xjhNO?#fyu3E6YQm=B<6`y+QtYh>V*2bz`Kr$o4x`O zIm7H-HjROn*e(Th0!o`G{PF}95>_a)LfWXpfqKqs?{1?=Jd|pQ)a&hjl1_@0rDo@dK&xNDC;d}=*>Zpmb9Xk3#)Coh8?lI}8t=|i zf4QB-=m!PsBj~?=?SPXCLPShdcSlU2D4ukJlDb-mC@T-RTD$%^(x*h)#nC4u zxQIOdCg)fJJb1x+N1 z(#p;_(Pc*B8`GdxTqr%mXLCB}(PriB3r2}o8q-|DPxA8hSc3GrF& z!i?NAZD^%&a&%sjEt;hFHT&NJ|`?@Cs*{dtS~zm~Q}$>vTLl4_3ltnU=E% zM?y6{Vqb*&Hn+_Jr#;EKG)>whX=M3V@*%#$IjP%a{g1iC5OGS!hgD#Z*%%LYin7Qy z6DKdHeKcNe%XIPv5!dfTKFs54@4dbKjn%h0>+i0v@9b}EZ$ZP^jCCdVUi2-qjlE+Z z|ETT0ylZGi*9y=1;rHHNUD@0$25D+TZfrsuPx021jfM4+J@$z=Ws77{4aIW(3*_#s zZ>{aUT>zmih8&P}rHoK}i}M7mCBs|%cx89(;mX10e$h$OSl#h7=OK?%nx9{l1K{{gV^(wz|-A_-I3U0BZjj@)+ z^!y9zG%_{{D4AA8OEs#FA*X%^lN zQ^M_{(*H7%mp-#D-#3 z4{rkrJ7{{=KdI+XKt{#9JC%$)I)PJ9Mjli_EZCynH+IGdY9J~mf_0=f8FqoFs~8>o z=3OKp9QCDRIy`F3rgL!y0?*hBRm`D4tBBE2Gd6{Nx~SgEZE$CLp1U>arZ|alci0c$ z7*7Rhc7Yg!=+j2JA0cXvaP*~VXwM6>3C|*oVmzCkV4Ylc^`*N z0`ly#3I*&JiI0(CL|Ei1!dSvmIGf{iA9*0zmmmtxQOD9S#zc?fFI*IM<3#VK(fNM$ zOswU+Y&f3iygebXiuvG0Iu&|d-CY)wGKXfDEW}4PpbnWt~xs_ zyBquOb+)#*)}uV6Qdgls)#1cKiQ}x1&TQ>GJ>g~46egQru&W1a7A$6TIC;7lZ1WN1 z4U^eCWh;zB(2c78`IP;pj3*;w%C-(twLhSQdV6iHhO1x0C6Aj9vSmtvP_O_}q;rWG z0^?0Zqk>nCO_df3I~jmfv4x-Yx7W8~erj|2@5$eA&%ZU znw1x*=>w5Ka-?`h;bZd{ed<2MWm4Y#6SSfMH|9U}{xa-A<~kZrm%*<74Y$Kr_Z(Ed zvbV$ykgtFBYj-|94|p(Wh#0%ca{8BHUd<#TNPIc|si!bK!6^99R&~9}PgTry2qmud z<4Qg65PnPSR9N9*{-%myrlVNSwUgF{`m8s=ol#8{CLxylyO@E%6I{tU47=1N}EC(*onEh!1gO?xjc$F(y4*Yk4QPeV#7-Chk zQvFz?_toG}H!L(r`nT?#hzQ(y+Voo{O)#zT^xG9B!{HSXWJ@vai>^&G=kg`XW42hM% zs5u{x%n#A`pnuL0QT*1y7n^|#PG^K$bzaQD-CoKb#lAirD%hxjC{HjWw@rtEiA;3G>f4oA8<1&^8%MLFQ^0p{s!9H)MC8U)y#OgKbhMe)udILju*Wh%=l zZb8UEA_pb5v`rqxQe&V*9|0;yz{R`hR~KD+oXoO)iQ|@tgpgB)=+@!v2>(okmtLF` z_Gc7a5Mz%sf-$vO)2X+kv@{6&Tmldka7pBX8A#2JqFv`{pIu%DnNh-F*rx0|UXglA zqc5j_p_djaV%h*!THPeA25rY=^d9h{khC9&ppLiuXglIackzCnbkFO!q(4mK$vZ>;VJ9i!m4 zB~Czl+#%EjKt9#PcKG~oTK()mN2LH>S0heh>A(2L)j6CwM0kxr*bk=!)M!b*ecTm%o>P2| zikThvjt0sJ^dD*~x_*P08^sgEOx!J=4KMNJ+_p5)RbmREyxT`t-P>%XiL-sFE5|W| zV)X)_TJz4gx4v!}(>c1jdL7)ZUtPsw%j@cfMEFK31n53O;5dc>$#pYK3ngQEcGpL( zI*-HVg@dPrT~du1ebtjrC7$v;RV!HfEmXUPIG z4`>7Kq!U!LWcl8`p<0YNexVZdNKFTOJl4!e=bFkHeJ#Vf8~6X-`T+_BYr4bU2UL z;5=!7-sU(TeYDTz%Ff#Q9=Bk(_SbhGuB@(icDCPH-$jl;8xgL7zrJZ!bw*RpJU@sK zxWo0~vBl;}I+nVa$+LIlOoT|U!{bixc+6TzAmY^VSi9@r>g=xW?02^JA2SLb+rwyt zEOckAZM)*y`r8|;_`1{|25elYoLE;M9pWiM#YtKo9Ul?Cnx=OJema!;AWR_!(L5K2 z`{r^pt_dSB>DqVA@ZjlpOgi2GPj7thc=D`TTV3nOt+e0S+kRL)9c=Av9z1%qz9#oK zttV&F;#Hu^!Bs@Q_i)>nuP&;0AFl6qcGvfGmbtgj87>`g8WK16+wh8NMf{Sdb@)kx zroH#JRv&jB?yfvZXhOCQ1NURD@Dz)zi<>%$UfE2T=kx`wH;c-LI)q4gAb?%`(#+Z5 zu5Lfs*<9aWPc!|1qruiZ_BWoaZy)Seha0-raf0iARrG^Mge;DGSd>Jh%ZW-L4dwwW zhOFwXm}q{E3czF)>sYBfAWSal61cP68Y(Gj@-YW8@vzHi>$-PqaR-Yq5+5jJ(b zhwCf*2fOPK+mmf>slT)G*80H?A+wI$193IZk(lf*N-m3V65kC?i`EREyIo&{ogc4k z?iUCV1G-;~lN98kiFux~pY<@~2GwA6$pKmaKrgXcOuv*6L!#l z$VNgm%h*{swuuO~l*HbC_;3#j*u>Foc+i*Z;^aV(!(Wm}$QQ3@fu|#mDD9$-d1Mi3 zT8w5bnFZ}a`ymeJq^c*qwz113J5N^j-U3kipRp1|cpevY_~2kq5^jCJ!PEYGJL{d* z&6T~q=sOs~6sQZ+45{DDcc^>(>bO|>!x0+nFd7!~kq(dwP|Y`+p@f`TtJSJ2l66!F zbgcJbK_HnT3bf0L10uF^Tsn~lgV}w2`&qglCHx#*I!jg1@3K&fF`(&copMyu;aV-i zB-si8SGTtwZanI&?C;NUvX@dKl`BPs_LO))v9MYVPON$xq{K>!m_o~TR#$db9&BuK z!nAPd%kG8VBm#o|KA6FLzVS5QZBQJGYTF}Io@uMG5E>xWvnV{tH4(w=++l}#@!cx3 z&7Wrv0hdRr8cN zx;Vq)2wBu-RzS|iSEzAmB}@tyoPDw!7lcbfzi|9Za09!|UFL->rIGl%x_r{T z+F}3OyVz6wb%Fk=gk~exAp9^BGGWb`qKJv@)r|nl&?Et#6t-=?MuG^xIYbJpL$}W^ za5y^9yPV5|gGXU5hI<0?GIhb+y|F^XOUo?F@nZDH8;>4WplpA4ds7Vdh_pBB`)E|x zsSVs(o*Zt?&NuQzr^O-_Dk)bk)Y0K;X~2Xwidk6lVxTM3u+kI-bUnBwEMRS|5h_P$ zW>_VPkD`z3R8dtPYcj75q&gRbkle%?`u1TeO;ieXC^KGMH;wtJUpl zfF-Be6lir&Zyn5QFqJhzH}7m}mXygLDGiHS4N9terZlm<5n1H@PTjLQHS^Vg(1`pRQQc3RiQnvYIZDoHYltFN9(6f!1{YMR`qKHN= zUzd8i;(JLn)gsZEcsj&2jG-G&LaD-+3M1>{WPVR~fNa@X3(1yACrh|~&A%o_bakf3 z3z185v==L<#Bi}4Xqb*&B@t?KCQUMCYuzdP=J27CHIzf*9L|QV?s_}*fcZ|dW#LyW^3W;pluf}04u(K*ry?3y> zs)`0Qky^{jkG+odXr^@tMfwD~BJNP?JBa|cWg_r`_D%1$+VerI5rC#5jN@<)bvA9a#uC)5@~9Uz!f=@w7aS4J!TiuDg;Cb zaa{V1gTm$oM*r$MIri47tL~95V6hE#v^qb$1z+9Y-9&7@+8s&;mYs?hum!sVKIJb{ zAf!}L1BaMCqUjNX+{qWrj*ot7Dv~kHovM@+E4j9mR^M5&iY6gnMVs1up=miyL*>Sh zdR?uqt%90w9Y}!%+q0#AQuBUUEZ*7N*kS{^y(V!{mPzMq<07!JsVKWAB8gD!vLKW@ zOA6jcYg$a0276s$2Rc8>RI0a=D?OP4ywmOMJbrI)1NyEM8G6zh_Q~4j6L|W`$`*G; ztbpa3i{5pJs7!I#j=a#d)Omm<^zb4Ev}K`YdSjucTB5;_T5RAMS$({_y|vArQQaAn zdj}6<8Y>T=<&{;dcpJa67dBf!Y20}%7Kp&ISl{OMk7iUNNTSt_)%Dc_g*TREnZrBx zTO(<9ot1-kJHH@F+#|l$6gZEBEVMme?S|JEOblPfI@3xx3B&&S+=RAud9Anjp{_P` zzo%X;M=uinRjQ}J8!)v%-$Ma(9_+5Kyw!TG{y&m*TZIKyR}R+5ICy=%o@}#~U+|mV+h&@siP%*!aC)BU;?5p+K3xqrfU#Uejd{;Lw=|CXv>~1qiEPj?2 zf^B90Nk>*`=i&D5la=JCO60z?vkBK~Pb`aJm7VWuxN5>1G~0lU}f~LOdPdI$!6d(HMA;JXY!%DT-#nWl! zrI~Cdrfbg|irko+YeNUV>;K?@>$p3}Pmr>=@$L0;=!309^B5d$j6m)?2b+8AoMXy@ zZx@!_9vvs%F2JuP`rUg4?S&}nJ|i5(I=1Xr9BfYYSzsf48x@URBEMQQ!RRh1U0tDq1q^3Fmc41&ocDSSZR;q!he7-;4CsoF>XGjnd>u`t&|#Ov&kV z8Pe9@bn=D?*Py4tbHlkJ2eE4ssX}PMgBeh*MN8bVoIBfF(8F~!C%<7M@kusp0L_k`jtO);3liZEagSE7ZtGnQ;dID^w>d<+_B;IH$sj z&K@5;Xw?@r%+(IPC4sB?l!m~?0;D9-HOHFxGeX`qYosk;(b+X9f@E~&S|V@<%Sg(U zh#*301yng(LH~Gr`z>Q`(UNUHSbw+dPL1uhxxTu=3P{zh_0752Nb)09*~K*El~`>7 zMrv+cr^`^d*Uc{$brW0W(Z+u4)!1KmLUyucj+0Tn!j((-f8@`=D|opJ9wrybftFv( zF(N#xL3&q;X1yl;P{aV{Hrmh^hfz8fj?)f&i&nBIOEw}t{qsIQ``YqA0E;h{>t|`m z8Uj*!v?Iu>BLrnV}%hPFQmZ7_F$+~9?+;SRe)z0MGH9&B&# z8^Iadaq^}*4Ib)klvbjROIEtoU#vr=1r9RIU@9A~!!rV^1|i8v41{Qa8uE4>Bb$uW z6qkKUXULB>&TC;F@2uLhcWs@5aKn=DDsA1R@yvBTH7>{gcfnL{eA*a z?NY3R9>cntD@g5F5ABsTNT0OnVP9tOC1#p>>Og$U@dH7eljp0t&tedxj-jlH#p{+D ztM{4$;EsmHL>nF#IAW3wHEe8&7+#ge1N!AafnrV2c=N;M6U#h#f!0i3wHtb?aZh|N z0ngXgMl*pY1P~f%ZB~tp?5u4pB{7WVRGD;A+LY9mvpB_-q zFaIYpoM>hp?8Ys64x)K~IvEiZR=c#iSA*HGLZQkN!e1z-+FRY*z@9)cckqtjd{By5 z2`YUWfspTW{MOy0Zdvc`?M-~ao$a@Y1XGBN{Y$to`^Q8=3?rIcgVf8v_wXUm;s=Sy zWpe~k5+s&p2BkzTfY~6@=@Ftl*%OkZlGoF*;V&dYn!@UnH7P4L8hiWOJ664}$vaNo zD2*AY+RkpoXW>cQey8(feQo353FAE3Cca00Kf;jpB^C`PV$Jx{IzCy!GCSC+h%Qos z#&lr;tMZtmSu6(CUEO=fYLlpj&EzhnL~jvNtq5soAMjOg%xw_6YwkUU~VC zP*#E^?h%MmM45tB8>U!#Tcnby1;^XB-*i!*AIt-eK0IzCcJ;vqw@2fA#oM$3z^!dj z^vc?MH55l(E^zCfB*O=^6IMzXMA_(I5jIb5O-sb$q(WeGLDb!Ab=0u~3|4i4_3oW| z44dkA@3aVJ&^rmATj696%e(;BW|&+EIL|n^epNyQ>@RBt!eNdO35N7qo%FA8#%cZ# z5){tI92|pmge{=FNgOD$Difay#ySe>xyjjW2rbUxCR`9TiYk!-?nPvNF=r(}d53Lf zC#cBmXil(^rolQV=Y$KgZj~;ih`9Jl@&piUPabx;tjn1vxvKg-^7lc(1LE|w!rVC4sbYnIXbiK^6_Z5b@>7=(F90Cg_h{I~6 zDYw~4pGTh#?rLN6u)*EN*0&BecHb+JggZ|{3|~xODTB}-DnGi3Iln68ED+T5f;?N2 z?%?5u(P```Q5ISCCW?ivgI;38DJ2lTDa{YL0GY(JrXR)~8w>CtDT_Yi_l=A}QIPH# z*D~h;GH2t_mLvGuAR&A^Po9JWQiG*4?j%&04B7ob9#KIJuFQkX?UD!pX!MNy#9boU zBlsi<@q%H)t8OJybE`C_VQzYrv7S`T8*=jN;N_V&@u3LLk8OVFQ!FCKAt|x!flB-% ztKpc8BeWyIht@rlio@?Ys*O!@TO(x@#x#c}xHP|lX0>L8O~;+XmosoEmA z-3P0FQ7D}q!eQ{nBy!TxT&u;ma8K$*+2Zkv)W7vjG%HldoMdph5B%zBy@M})U6R^@ zsAatzhhBsO=tdSrA)>T}S5zgwubNm$C3D=zbB4!JTXF~}zK$lt>Rx*u>Zuf21}uaE zUJXnbM3}zJ#!(UX)*5jXjAO}Xjb#~x*>u*&mx!8{5*v|OQfD>^9O;J{%0-9?9srWDJ0newlWKg(OAu;kXtoESrilJ2EAjM#{aK zm}>b`Eb__&!d&4I`PJm?#@UNP!*SCNRq!_uc+0V!SWPNTv%c^>j~-Xn;?NVnJ$la6 zC!P;aND9D*FFEyBU7z=5-_S9iS~#m@l-~9K$xX}e*K^$*9fDgsiOx|260g(Fe zgTzL`Z4NOJx8^YtIs{pble(8ra%*KiL{)oCy9-;B3=Q|;fJhQz&cFhAD9-s)WbGV~ zZj?eXQ=n!I>g)3}iV?ibv2JDmy3WIvM8Pa#v_Nqk1;f?KG7PI@Y}u39J$|M{_GlN- zt{p<|0Ig(~Y&gD#OF(O~$2^#Z4X)6y`}rZGTJlso48`9G)L0_zTi*0@LlRzzJOFg# zPGu-KPqHGpB&3O8&ogGWq^pV8rFaJthp6>fOz*E#WeVmhb3s}cX=2HvDnt1r5S!&Z zoSiPvsxhLD?n~tnE7;D<4TSduUNiGzgiKV!NIs&CJ{M|H2g-frF#?D9c-4n)G0Cb| z-_D!Fm0?Llo!coQvBqkfI17>vdc2XyN+Im3&|C&QBQUzikmphnyZOYlp5Fp264JYy zw9pA>xq_QCEF*%4$WMuc;0SU!JHhRa#^i$WSs&p+yjtXR@ncTv^6__XB!F5jQdap2 zH=CIY83JTtjUUi8>D(P_renx+(!=WC0so#r;s||$u0HkHb?zvuGg9yp>c_|$Dah}W zjUWRVCiTqxMHydd)b)QlzZMrMg%-)qTush|<||!VS-p8hfXolR2%eNS%PA_+vn1x% z2TSEAbIv!?Y4%4S0AbvJRyEjIC;OrNlwLKi>Qgg*9FtQJE2Zht`v^=vG9xNICkHVN z4^OVdWN~d2qmJ_xXEW?@shbQ2D3K{qVtjDTpcNfeN(@LswN#RFVqZbI&-&!IA|odf z{OUyCYID=0X-*f133sRC89C?R`6XB3NlwPS&s)v38pH1~6E|I@{VktWnk?(%>K+uz32Cs~Ei3t`DV30f!InxtD@)6noJ!`7sl zC`@%=q|!YBTN=A1Pm+x&QpCd zNq4%4bH@D&Yep~h?`)qj-zmw)^;J9HZ)?xfch%ajG9<;|HkZS6Wf; zfpmm)NIeocK=3yF{meH(+A9&!tOA{DcWmy$<}(WXl2ipH0CNi$H%FD6Qrja?N_?}v zMx8GnU6Ck=U>^UuPcVGl}|~9&JC8n$#TOIqN}8LDaF~ zEawbyshSWa8IV}k8x_wHYy^{Ov>Mb5h!>R%0u2qCA~h+#cum&X5#K^c9aK)cD9h0v ziWVEdTBEr9*hm69b(HUcJf`rVhSyFlov}1;_=VsBiO$R;&R~0fI2({@jCQ1kjTEY_ z@uIT~yFN2x7#w}T&ot=j*=~FFE^<@3YPG^60r?a#A zfP7GV&W4Pt>_v3fDhkPE-^rKzcQ#hHJKJwTIsFR-VIDody#G3BhDf7kc3OS!9iBJ# zAL_8IEWPB6L@QtuPZ@#+)!yQK4qYNGx?gd~D4qw9h%%&5WVW-n#!`Pzrtd9bp!aLM}xmf4+lRlnCJ9 z(C17wOm_g^DalL(<=mBrSWb@sad+h%Q&)jZyIUEZ$aYAAOe_r@wE)L?3d2o$?~|gb zbIGw*(FbwQMY9$GXnACc@)4^H?KGtYZ*?ESDf5KCqZ;L64`nk;9aR!yHLaFF=+uoFFf&)Lb3_U`Q4i^BT*1ZoJ`I_@`jR(2oZB!ay#onYr63$9!ct+1M7<`Ek7VKKnj z)83xhv*_#5`qug`CqoJJqcH<(R+-n)(aIw<=<1^Z@zuSkS|cPnKUfR(Q0t1l^+(0L zmEWouHS3C^E6GFBTii&Y)kl&(@fjKY`slN$0y`!$9(aRm(u#Evg0)9Q5FRQE8w+Hp z)km>7o?uo-ixfq>g7t}^uVy~gh_3Vrbt5%-JBk64fUOt5kYi~rxyVQc>f=RSy{^PTwadkQH2b(^68P*=J z?u0xRY3q)CUKO@VC{i|lD5U}iEgS~+pfXFoqLv|%t~1;cbDc-K+gzz{&ol$>PGJl- zim5Xz(V|0dn2YB{IKr7EjNz1gN;aaz0#ki_ey0BkDajVOaYA8a6q=?OGV?wVTDo!H zEo+j(!g)d0#cC$|jQH_A0$#AK5+2SEu_D&cxFSVG`H^xe`m8uoxNpk@7`nwox+gvwp&wKIs z_+s#H>FY3}VRy-{2;C3q=|~t%ql&@`el;da3##ST(~axju5~DzfjvTJ5%Su2*ng~$ zmA#dR>+Eh;-;&tnG{0Tv;qLnS?ml;JA zNzSDCdLg<;3h+Ych0oHu@MT7{Beu3qKAIrYytyB*GbTjDi)B@OwRcWOzf3!QGzUrx zhr-J=$O!QKYoiALi15iFiMCR>DlLv*ra$-N?@rCl(*ebh@EUN4E14Vi`=1SJp4q2iTs);+68eu4`J z(YT;hq8RCO9K3Cry0AJKPB}TWr!<>S?RqzfIlGop69ja8LYr*?ADY1>&?-$@MSkc` z@KCsKO0mrE}>_Gn(rhWS++w8g5UJGkts>$HWBgOzL>X8mF)<&Y2X%WRTf{FOPG5FrTAkr(RJs7s z;M}WZ&YX=<^hGDyO++@D=+r%8*UK5H^TYxqD(c`-f+K}~%?;rUbv0}{0Q1}{wi4lq z8uUAdP%Dn7g2TzSmkC0c{u9H|6uXi3$0`4J5_3&!1kqv++sA0+RNLU*#CwS#3p&sa%}ddS-t^95R(-;!^4{59&(Q|*`glex zLVb*4afSO~>~Aec-?^cv1Hyoa?3Ae2VXi#hE2+4T4ZzGujuJcS!|5C~;w$G!3OckL z6RDJFNMr@AhPQ}%HC8=l>5G)7Jd1CM!J~}P5?ezhG>kMnIN9^!XEmYJaEUQ)ke?Ie z=O-|nbOz@+-wtnuQ@I8bbZjbx#zruk-%=hreBhAxli6t3BERT8jp6fKpT6ve)**0@*J+|pmpki6{=K!SqO#;$s_v%w9x-EWaR`EA_k&ghBr zE4GapmZ0anlG%cc?lk_w{cp=?uZLM*|l4rXo8+$F_Vz0PpvwYo_gO{YH z+v7ZRA~j1COM+zG2H+ut**hrB%Am`!ME9s^AL!84&o)STW2K#L;_iBZ@-jsKLcfp` zzHdeD+ZRtTXljS0#<5W0l*DnJam>0m=q;ono?1I}J*KdrPlgvH5T{I>HL`ij4$Yt- zi64XGi-T0pDhihkiO%bbQhW^!*o2s z_hEJIl%Taqk8gucPRG?0<7#loJvqK99BuiU{1zWhczZ2&E=SMtA#+ERLPEsCu7-Zw zuWJjtZEG8`eC0zsG(NM!QgQP@zV0}gCtQGO+xyL>1VrsQ!GDSg(2p3v@Zo-*;r1fX z4%KhnqfOFqLLjqtfoL_pXrzODMThwU1h?Ta@Ks%1DSs*-KVhbq13tYb1aKvpbx7~- zrBgP?hLhj>0|DuCD!NuPnUbrU+k4977Rp$&FiL#p%IQG(@cBR#?l6rhjEJ+m9F-2K z$cDeMU*bnM14!(k zt^3~C6rfg5Mhw5ba^pRNadf+3W8+YrHxm@=+!Fmuq~0TGz|>GW;Tek<_X| zkz1Yv0V8lo=tH^ti^;J9sFnVhu$E(;=5!|0XG$5R146GBwx z>Xon!&q26UiZ)WrJUDH5@r<22AAbq6-vpBuT|?tmd8RcfS1}7Tcfb;Rv7$RIIFlWY z*rqz2tfJ+jPZF9ADdL!RLYG3V{>5O5FI{tyMp3TO3goI#ILVA7F`lriEoFuDIjJ6! z8(8$&x!e4_7p%heMbSqR8J!VdZTO(pcX6{KK$)vkk$0a&O61G)+OWrF2iKhhYo}MX z?%-+yUOHUxisQfyQnukS-`!Ve!h;Pw!RD;&_Vz=d4LY}>s9QRje|#z%Ex3jUE9%bi z^GaulzE7_&Qz(&y7};H=Z>Pm+u0tH+wP-^YKN~n7_#rg1%;@k5vO#pYz2lT^8*A@& zaAqqNP6F0`lr#XVYO3>NbXm=gYaz%=0V0cXN=P!vcsuOtFl-%Yv%CHfPlM*6yMoxY zHF3E!!W*)H5quWvIGvCTI#6UzK9rCxeTt~fJ2e+7dWUcO#N`TtR-{Zt3{t-R-UXJyW5Y5_t-0! z>4DD%(shcoSxaA;j!%#mE6rt=#BR8{D1WohU*n6_SBXMv#7#()`9X z!$6P2t>$6gziU#F3jp=mCmvTF#?9>(nu)E@#RJ!7ZKI5h*^yKtD;+1eSv1WLqZ{m- z+be5g_$&d-MHHjY&-=-@_R(e}GKc-Njw_pSA-TcreSNAALn&!jk(g`Gk4}ycc%A43 zzV9K%kfdxPjSv~`Ux5iF=9Fn~#TwZd_e~~Uy=A8ovlkj1=+TH2QEt(5NG@SWNeGA) zR+yjJJ-BcCNyhh)v}?mKO}CHVao(hyRw}{oydFlNCQYaUSI(0(!3V(&wDTkR$cUzj z0kSFY3=iaCaW@S?=$b9LQpkYP3~Uj(x20&xUE-*;0z@>#N)XFq97ns9{X`;fuKAO- zEyQcgTH1NOT-|2?S(3Td`wu~8v)XB~kv~rTa*h4=?-{s_hyLe)4T_Pxkw!?eR>&!( z1<~>I<9cclu@+S`nY-h6whuPf9&B!-d9qN@?pW4^3_jCJEqik85bP_;B)=|nprwh9 zl@iBGQS+Z=#azE7t~a)nSz`gJ_qIURt1$5U<7fAmg&{0_Nhn+#^ZcaXBjZpJ|HIk% zdWF45&JWIg9ZPY46)Vxic zqz>iw1^bnCW1_Ko`H3t}jHo-&ME|z9<^hqAwiALuM484`zdP(=ZE~A{eZ2D5&*MK$ zmW*ZMN&;q+4xieeR4DN|hKkXRDGW3z-hl1`KW_mU3F8USsx6olsH?SVq-$`#B1KoW zlzqbF5Mh)4sVqtyoN@LI**i;rV^ugvP^9;P%3N71BdLQhIe?-J1Xju4$^>t?&qusE+7BCx&sc-@GL+T`BE_Py%( zgu?6S)d?7T5H|L3bOH2){-0JOZZlvh>a)T6nVm}VUU>to=rL^d3SDEJgV}`DPWmlg ztn6m{miT&-TBFBR)wdPT@Kc`X;u=1W+?M+F?_E7;#26)4d50M9WV0hc6)}e$!?!Pw zBP6_0qZpaT>5~y^z_*Ko5T~hP>csm8Ht7@6Vt6Y+4|QF^Pkyt__Xs$zU#5nDMVnV9 zJEK>mXX-wA&$Txxp-T@k-BH;%CE94#2RuX>>;~n-&z)sMi#gQz-PzgMUQafVwTuKG z*N0+1lw`E5b<8`w(y)Chl28g%f_ZicV!ymPzi{y6!FDCuNF>uD0toT}>9}{vOXR#d zV&}W<2`s8|FOMu=Rv;sfx4F5t)0q5h!L^k$t#Z^RncTvi>5fA?uXgU@?ah^~8h&Kt zDto&$(;zUNm#g29#as@mDIs@ZRIVv)s}Ok^(w?cSst9Z7vxv{i?9f^^=P+&>P z`ITc1h{Cl1ON6Hgd+wRK+$$5v^Rs=Jb0vve{Z;}#s>fh~U;h?FI6O6Sa4eS2itVK)~6URwIFj%pin9A;kf@k2G{w1Mx4z#BF3ry)xmc9ub}HIGvFs zSmd^qnH*)1agEw|V_VwoJV)aM2v34!)H)!Ili?gD^h6$xZN}9pOQIK zK1-39>Y3C8yqtjvB`8xI2(~`ej#v@~4)gV#OBwKIe>^$k2Gxuk<=u06m(BO;;;c8o z=UerUz=(kA^sbH~|4q{i!*f}YW)i*5jZ-(*+vL;2OEbM+ILLO zIQt>`j9>Ait|%0{9L7y6By^At3)m!Bvr7c6DIYbJ1C3?nPTEvc7<8rXUDMMK*w+sD z=#=K@11eu+3dv(bB8Q7(GxoTaLPyBaS11O?_ay~j^5pB*H00{YVgF4WP}nsp4>9NU z5%7DvLFC6XPUT|dQ=N2x(acjuuBNF8qKIU&Cz*-iA1H?n?YPn9Kj--+x$Y*PFd{Ky zgCXOvkV^n{6TlintUZTasWPo(P;N@bVfsw~iEYjNvmuLhbS7X!L&}hWdK=|jMu-5`xJbHO8s|xRe-g~Ntx}}QWSF4u%zO99qxAl{Lp;xArV>-+m z%NaE08As9(j@%umHbAW{(O?&Ms-wZV@9vYZVltK4I2l526_3!25+m|U9;@y^s+g@h z2f`fkk(AThzZ41)uelDYcqmI22geMbDTPNo6ZziLYAT;X@AOTC2&|4V8Q>}W$VppK z&7&C?+ADI1o^vqH7sqmd-1K;SgeO^%dl9LD!(XyYUzT;aK;(q-BuSrUC-2qC=nYMOH)I_$Ps&xSt#bU0o_8*R@nm7Pz2iah?ZAU>P#yrHP$1V;xEVQcX(>1 z@KjPv4B9d|D6tLXB%<}RNZmepu&8_3O)Z<_mzPZ6B$oDLc(MZXOd;w%)ii(=gu9` zIUak2f?=m)aAxY17~zK)l>7i0K6Q4D7}7MwHW3#YG?T*}4VU5t30~1%Wru1ytdUrQ zafG2T@QH3ci`9fxEpO7B&FXWhbb1NT8S<)RS_?ZqI?#+$6qsp3k=gbwLU6_EDLn}*QjoYPwF+LT(HC9D$Tbb7Jc-%s z5TgVE`7;C7CepduNqhCVj9&9$M4(5O9D)R4Jq&K$C`dl?Gz*A6mQupx&_Pn5N|_3o zV8q!B6`n4E9zZwp5h+!Y0cVf67T`K&tMfBjwWNP*lFo+GKpSk8^k0XshLU2qMRZve zSTP`xwcMv#gTzYF`5~%9(pZUuhNC_g!{WUn-y*PmPM8M;pt{qga);u_G9zfTdro>T z2~ONNDXWf>JcujHS=IDp(QNSvjVMttXn~U@h>oqPkIrUX!xvv@4yWDmox3Tm7@2ue zjy!4K%nWEy-L>>8kCjr?A;;uc6N}~8+^8fWTPH`d{on&+C1msI`CM&{q9E3!GSKmn z?x;I>z3C-wU{TJA1(FOeMvSc*4zrIheAo$H%jFnoP2sj_aar;)3E9Ay_B!Mv)y==y zPib;_V#o@%_~n}gm@JFyQ@JNA{uEjVAyo92aNn_nzWc@%>6P?l4lSHaDS|tS%CI}6 z`Mf$g?j6pQ*;52cc)a&tHHc&{Iz7dyFm>8PR@RG#1hK}wnI!t8Mb*)@ZZX_UIg1EF zfskB}ls><{c9!d0H^N(j>(7}hW1TfKr`8&bPBEHdPFDD^0lB+tNbe--y<1an3)F^g zk%c9?+p~bM?N%-i>>rYt1f)1*`ied(AamL^z0UeD8z<}`b*+^)f-#2oj!wkNyVn~aSO#8^ z`%+`6D-??YHSi&|#*!pTOQ>4sXcva0g_U)?v;&Jru69OC*ma`9*-*J!GM5{V z*M_fqw7S$k}h(oI7r zDI+I|Zp`|`$y<1M&a?|C~Edk`;leK>Wfm?G`B z^{+;Y)2eEqD+u~uztR!74?R_U9%DSaAIDjG_=2Zs}&2UThXnKbjM4gK6NHfYXg;LwXs9usa;2# zbyl|CQ)vn(tC69`a<@m2ormCpCMUe=sYMdTsJHbQ@!F~9d3->uyun4py8v>swZzM6&sgVv!NwY z6sRjaL3{%#CPqhT*-8|>eZPe<*syqgi)B36BF2)#j~*J5 z;UTm5j#|M6B2c4K9i;O%_saGWj*!PT8s#V{9VEE{|E644@W$+T+b5T+HL5u5cX%p86|+*WsT8Yl}AtYgOE~bxNHo$gyGKARh)*^a@`TH&b{rw**JpMAa)O z_FN5gFN;$@eSV4`@vl1IZ@!z-JtWF0=OX02j>B+2IrWqu;hj!SDCieTZl;8Seo$cF ztHM%R630b3e`ZQ7=Yja&2w9mR2_A5PAT>^-T~3YbGQr*gH}#V9vzeUgnhsKQYF59} zfuNG?`eCkNBz7yH&`4$C-Lg@Q->8o-)ulc(c?v+1)5*C~-D$vg)7WYD z1*G^aOzvFa3zVjL7FCL*ejaNMF{xeswrDA6O%iHH>in2#+!ZWnsI3TW{bEr3FzCN%Ll_Nn7=DuPgIqW83)O3Un~Ny;bOtG z1a+w%Fiy)9qNyhtRr;i_!_s3II>`e%FG1dsMQOdXLUntw?YwQ?B`0rDD^X8WNh{8S zH%sx-a40_0MpV;RyOv<^V7BcPks0QuMMXNVaZx&n=o2FpHDtCbaXC&9KJz5S>o)o{ zYn3Wnr*T;&c@5o9GClp9t&28H{te%0>*C)>qb^ztKMDeN6tA=>B?#pRg^Py|M@D@O z!)E=We>&rn@9{3$cvGJ&Dt6=PR~na@$UJrG1X(fDGdz4x9TBK75${TrFj{C6Xx-;_ z)@$~87A9yvFmpvG<@!3&Pm>92wx{&#PDVC61P{jH)IX~atYgzaM(Kr)&QBFKtJrgT zQXGjf?hBrHB4i=Is*oYU4~u@Fi7A{@mILdo>jzvG!f}SPK`2hxi(8O2A&8yT(p4M! zfDHWF$T2?}X!_KfG=mzI(o^zG$m5uZvLFINDxr^h=&LtibG4MSLdU_RR9K)~% z8qC+FoEhJb48ZPy_ud2RhcBM#hlRbaO<}e3Z6S_XwX=#t*0fv84SkW{SK8c{77aP- zy@INMHKpQD6GNuANrScxG9gp_5g%l#w1`&iHf01z zgo4#5ySP$9J=K)wn^V2SrCOZ8lFIa??t?NSW>9HBaC@L>Tq7Sb_fC9@VBfw9tOjDL z)qs9tEW37bxclkQDV{0gU_61ZbOi=V`P^_eM5hsOqxYHAT?wp4?J1Yg$Xpc3JG8i} z8b?OLJT%}p3insZ(?0g4nL$q>oic=JaSW7i(GTet;7|zl)EL1E1X1rq6^g%5d_Ikg zEf119Dp%RTLm3EFPR5{!Rjhbk!-Ta>!j)JEMN+s&Nh#ganN&(J!R2jox#C@NnPshK z&E-Y?Yl_SAz!R3ASOD4Ss@G^!;P^XHdd<_Hs zAb*W9;Rin@5=x&|RH=dST>Kc02Nk3nRHbkVBq6%$NhW4KqQvjwaJNB?MA{J;Xi-H`;-ux~b%DZX*m>m~xos z%kBchoDd{LGo4i@L92`mR1ElnkNjIFf%rW6=bkzasZw9)3)89rOI0{@NmSn~kGm2H zhxoGyZTp zaul*a9)c-v z6PPwW;iljP);-nuoUN_q{xTL1_h8}Ea>PP*i*cJG_lsiXzuV(WRH-^~s0(GB_EcYCFkVefX z44v^)N6ESX#)-Qj{$Vi=JNcSL7-aca!mreygZVq(-rBpk`(|gCjG0OuFjSC;9BFs& zboTUF`2P9qe0^uHqc4c^k;`wlYS*rXowr)=>t0AnuZ>Xdz1}X~+|dpFEGsP!pOssd z?`iq;=;-$8aJGzZYkF~f^yM$#e)f7~eEjm4zy9X3X7be|4u12vhXa@wk|Vj8N4|Hb zF5;49*vft%Idip?B%-y|2Fh)jLbK&-tX_&vWd>N7`sb{gwb3fPa^dEW1g1u@6xPjJ023XhXS%73pFk7+?6TWUdM-Md% zdZ>GMYXC|@ykWGU>{WSZIuGD^dzoH9vw7Mg*-Rgx_1@R(fs>_$RS!jz-bn#jhc`d~ zYwfBh_0aHS!LBz6mc6?gKMfVk&=yS%rf(8WjeKkPdJ*gaT_YmvN$DyZ*Q!C>4YTvq z_J}M*`T%Wmf5PHp()XFU&AK(_7W7F7?wR;3d5u46@dWys`8zx z!`H0&jLe}n;dnuKocb9bOS~8yp7=D7fhChU?5{fKht#>mYZ+A#XBaZb&6(VRl5QMd za^DsKz$4nyA8=;-gd{xTl5k&vcGFYcdFrsAQ%glMUBPKb&o11@`Juo7m^=nUV*BK$ zlVS9BLfn8t(UH=C^*}d<`S-MYPS}yYJIXI+AGzm+$_pM#c!F}7^x2`umU-2g2vtKa z_|SKJywu^~q=a+Ih`2caTpgpTKYJb}5ABP^a}Us^EU z{naT=Xie0SbSuMY~z(Wv|Tz1}Q$>P^am+KzWHLS;7=%X`@ zwS2g-xvm9|-J_;6ZM_QO@`g^;iZz0hSXcJte5*YrN0R%28&Z5Ql>JB|CvSo!yhug@ zzIB0DA9uIPRUIu`+<8(VPbcKB)@ln@3=Kx*%K}xc$E@fvz;u3<{^94*GGbP*AYnSi zHiDF(Fe3G}Yr>@}|0w`yji8uVxr0q*)YDp`Mz|i15mk><>dQ1vTU~lN7k~ifHB*6q zX;cs1xX%aZ#W_%0e2^fqCuCT2RDY^OCxJEXBcsLnVabT&uceO9)v@kP$BBMNpcAq~ z@KofSV}s&j2VYib=JW#GMWcz3m)eu>^~33hSeD?+ymam!b?Q(f>ZVS8&viL&yV7M{ z{}UkAoish%G@_BP?Eint0Rx?Hzq7XSh?Shi*17{}nqn381W8?X2TyBK;+r30KP2L~ zA|K3d{EX^3;igJECko<)SlOMaj$&vLO~F7&n7t?4YkD7>WcQcGjBg}S1{5=Hjlwx( zCyP{^)jJz&eBk!m>$}@jAWkVxfmF%+6JD_!)mJv6eYDzLACeij1kb z+&HRd|Mm*0LTC!2qAf4psU-3vtFv-!swc@3PnjDuPM{X_UlYSkODU*E%Q~_<(MD&D z&wd%F?WyHlf5q&St*$dSiH!ex)K5Ty2B_Lw+otbGPuamn)kjRk3|estOcK@J&iZP# zv&;XiQ=fJ+Mr$zRyG7OB!%dP7G?iG``6}~^nG;{v^@QXT;$d(dpl*Q@x{4L)oP_@y z#Z=NAD^|U|Bf=K-tUl(0wZ#0WPKe*KF48wxKU>}}=E1aZ;*C$qgCV5rHM@yYTx~hl zf)UfA*x~lVwg4-g5yFnf;ieSAlKj(cA>zKPv%>+NrTTUES*PM|7-E{7L~N_TQg;2= zmXaq`9_zY6;#b{j6}iZNaL5-f(kS5`!w)-FexPHI#ZfXM7j5N8_NFIu?kv|L!xEo_ zRZv$0fm~2mO#?aQT1GcI7Ca&{xar4J zc1VvF<&3cHmJ48^WuV(Y%Z#eS(oad1SQWYipjhH(BZUWY2=5;+0Y(s;R#3DS0=C9a z&Cy9X^sapPt}~h;pC85uCbk#5lFijoAHu=iBx4wM#^W%+XZ4H|_UTmFu5_bE=LMmA z^OJVcoqk1!cwKcX2Bab_FzHA}!7^feV^PyB`4IR_^{MV4sashnV+jBfa-UqNP6cdS zAeBkb!Gf2CPv)E{=JGKP(WCcebO}d2d7tf>$J59Mi#aZLuQ6KL@@0^RJ|OaXbo<#! zi4rh5?45E5#1}{m8)`<37oq*fxW;Cj4r%HJJ8gBEQeCS7sg45I!eUBY5!@^LFwiG{ z<%>PehH>o8OhVd>Ed)%%a0_FW?0)f|Q*#?988JAbi6*e%oXe%d(b*w26??0QeA!JLXuMT0*o|0opHgCdL za;*m29sy6l$TpNn8m+ijOsv+R2Q8l9scFN#C3?J~6$8x3v#t1!qcdb1px}%rXBOTG zuSg!hU(GnX)Oo=tT5eq()#9>BJ{{J~GNkuTEK|WPf<+gC6M^$WTS|u1ukP{td{ec8 ziqihWTLjz@(6>G;Cg*qBHw<`bat>b`;w_p?1D9?vBO36626kg)(XhQILQh5hmu)rj zO}4|cI3{@sn?JO_?$&8^{VS#zJ&RCH{qPPPPUXHKT{GTGAxc_W%mTBi6n?1sF5(?27ha@4!orZ=(bnh{Z|j>qJ)(`k zptIZFdtBS&*HC_J+x48UnfSn~?qabimFq3DNrC2=>I)ip&y7@0JfVe2KUtX0w4^;m z(g-K4By*-EEuvU2&MozWTRJ^9RFyuDh@gDg(X~@}8DP2gf5tU}Wp?p63nplW+ww!- zzxe82GuFq(?h)2w-7n^q`fa*fjOkVz!2(mw3;EjQrk zu+y0hY(WaA8N$Im38nGq@@w`BbylTqdK2!rr(QtH1>ef8dpgjOtZvlRT^uX?R~bbk z!ZtibIIPgecuW%jYd!9K32S`VQll$~()Y46AjgD+@?O)JgMe=EXn`<30wMcOYI_)M zA6SNIAe~86hli<4yGc3YJmsK#S{-a&a37K7jN|coMDTDb{XD&Qn8DmY>=A&&%fa-l zPl#^cS(2Y}gBPbli532D)%o6Z9RlCj?1N&p?JEUQ-~m`*h`-WgV8D$*)rV5!5J z+BUfPj{||(!QxNv)pd{W&HAFJppRLfh2(S@!vnL6XsV3FeX0aHjEfVlZ|xn3&txwU`xZ><2{%I(g_F0cI$(+u-9v8qAz{cv zbbiPGze_)7{X6C+A}-)%?Wg)ZPK!9jwO?Kx2;Bn>qYK?2}CV7%8DFmIp~N z3!!LQNBtA7Pjp%V$S1Iyk}m4hfRAIK%4JKniem|M7#vD{al8 zFe&BeJx*7u&JK3>W*WF|iR??8=;v{^?oB>zrSVs@9{PBY$xQ%sS(VspfW2kQ_rVJ&#jd6aXuQESGg@P(5Ov7Yn*6TTpF-Y3W!Ra>tBcc=?=8oJNn zmEmY+=jVJe;YEAIViO=oBaRSaT4sk{>txLIhh$E}xO-t=NlCdG9Sn7xh*0RD6{0JG zk?boqiL1$d3_ywsS8P7JNazsAtnRmfQM9lLoxV=Pm+ z%G*1YolwT9s(#vh(NDc2gupNLTb_UyPCY1GJ43GmjzuRl@$2g1tUpB?zkDw^@t8zD zc=7>>)Xhuu(d>mk##UG~ln&hueg3VZc$VVDa0k}};zT()bR!U(Q5@wj?k#X>E)h6* z9dRHB*JQ?e*-nBD)k^~D#SIe?r~0(K8cjxMugU1{y*Igw;IPp1{?!}zp|Z&86A{r9 z^rOPBx!L|TzS}@teteT&5#WTE%62EC1P-=tQS;vQnohK+Xs`}L(|SRF(vxlCzEg@Lwf}QS4S#izFf|xhwqkhGl8pWc1qWs6FqyqYd9u$L!{7W`-x|h zjuBblAhv$iT^$u@`FbhHE3#oYxc=h@3*#KSma|WDTGszqsEjLN^`5 z%nk28*-EsIGj7@`y@~9%7mS3jJWt1Df_=~Trg9_g93Z~_M?%OH2?k8rwRHXe!-i321%qk{$wc^(EV@7}c!}u7NUPy9NcAf}Wi;F{&H{ujtS~VJP;Gb6#v@SY>RonWsh<@fLUSDNkw7V0{bXO;ME#G2kvgf9YBAjSUF_KD= zzu~3yrnxgEr_%MevxRSw{I#r8zAc$AN%G~V=^5L+*Q@HMs;c^b`SY3TC%*IAPyKyA z^Qzi>x4Lzoe;1W6@&3D%|8y$Xv;KU6zpB5)-`}PDi~Os1de$F3ue|p8U;ByQ`iy@s z=_P;u0e@FsyY*|I`}NQMhRVt|KSSArxi)`9-%HWvyPx~z&$_>|jeh5G7Qz1`%JoNm ztL~5Z`=|8z75-gMW2v3qSMOD~R3|@wfoHYL&#JQYDW5YQe?&j}Q;w(S7nLtjr-VoC zh3g;jSAV|2-_-)YOFaLGzi%>^H~DwvwWaTV{+IuaU-^5#_LIN}^ry>IfnoI@_-brtK<;7;>ZyT78{4?d%I1>RR)yOYbm|BKbFC+1b>zXdAvWTo_^=|d5(X@d*Pq?x8y|b zt8Ak&%QaNl=YNv%I@PWJziRsVNBQ!PE<_k-7d>eoK|>*AzlgLQ?}3VMf@uqtB(GBmA~-ccmLim|70y= zbNLrOTP=Mv%CGTfZvPdRH*~VZb1pk}*>(Am`=_}2rt4hi|J=uX|5^)`?E{VMPkoB0bqwfT$G zm)hk%qHp8+S3Z|0Aoul!UkZLNX(PA2PuainI4z$0QZBE$)ve!zm|C)M<+YtWuireZ zZhgb;V_q4?AM*b5yw5Q3^BUiOoU#Xn9?7u%31j@J$8N#?IG1b8@64A!cRT<(lLC+Uos%zi-wy_j&8My7fCQE9Ue# zbdT2h_bE@ZrRJ$T-k(sW-hc zI$Cx9lse`7G`8OBkACNQ-}GK>bNwaPZ{(%mQrV9gL+$f(brSkDxBY3JzY=X*_)y!& zlr6ce;W@oOOKmcqgnPaJZQlQ`>le6x@S1r+<#$f2TmN#t9Q~B%_g9pE)8*~)c$H*P z!y_fmHU8hq*x}E2_}ikVwb$-wt}4HCcAbxN*$!oIxNSpIx$HM6yHD9_A35 zvf&M7ytZ9k>Ri!GiDx|@>wo+a>`VO3&;OL)HGec#pJj8d^P%gs@gaQW^7j{%YhEh< z3t<0GT;AYC^UQ6TUcCnYe|x_OkALv@0hm9MMZ$reKmUGp>&N_V(eFygu3TTVfh?C@ z^eeJba@)VA?O(fX+g{MvYWtT@t6Tb=pZV$E!f)<7?3gxwbJ>0BWqvQ)=zU3ROGSU* zaM^WQ6$~X^X%2r36a6(X{;u1!X+-r^u0K-w^X>Kgx0HW>(Ae90)*sPAF4yy|^e&gn z4$6B+)y?lU$IR3Eo!^HZXmB*&clo?TJ3W_k)${NF+g0@gVAa~^XMURh%4dzcsQq8k z{)cI>U?1w`%d9Y&u{YluG=)@=Cbco_Wijs!K8Le z9|UhcDtr!luRj_q<2cvX`%?d8c=Y~f_?ySf&ntx;F+X3`{o%jM-)X@9B7XgA>aP8l z)vaHoUFO&MKK1<50Q;ryG`66gzrpiQP^Nk4`5*DDy5;=zUVoPOo8RaDeu4Tzi(t<6 z=H+AVn<~}k`J4M#;&*N%*cYv9Zu^Uj^KsjXc60yNXm|a!FO}nO-Y|aI$2VQ4En6}k zDDpbz`p3W^4zFAL zh_b(zZBx!szxB7&XBz7Y2i?yAJFH%>Z+?G&?!9oN`fI%ZhU*tN;(5M*J^vZ?_2*6g zY7Tn-F75vnzf1pUuDkh9t6QI=EI;q?Ec^+k+*jbUk?Z+=z|`QmY_mlBOuxBrUe$Zt z+=pzG-0r)Kt>@fM^H;s^@&3Nww|x$|{ErjN$oiT!ehc49?w6+5WfA@Un0A6KkEh@B z>m^6*-%zjQDfMdy?SFm4d&(Ep|NIU0Z{6^oZd(1!!>9TGP>akTt#|T&)jpYA{zdw~ za(O{N=$u^s{YB*uVy~I|FXuB4hn{!-ePI1=V^iw+i#&gmvRwWy&mvEOtnwkx;dg9k zD3^VYvVH26`aAc-Yxh|`i=XoIpVPK{{&9NNx@lbf5lv?uP`(#VUi3bX^SAV?wi)JI zznpFIWi;Xh5;np-K6d8b=kYFh|9Eb^T*m8azAWSMk7=hl<@x>@&)?vA ze%vqoYWsa|zr%aA&v+T|{3ZB*Zg2QF_fJ*BGT*=6i*7QW)qg1uG?zCS=Cz`R}S*f9CSGjg{Mf z?za~BM({1puead%{C~v%`11|^mUGDOZ^D`S%5}su^Us1Mm%qvHT1KVwf~BH7_J`Ny zP}#>naUTUf@Kt8`|BCtQcgfEh`*Z(&b*tQK3C=;A2`ypk2$nO>$>#w~jT&w)*e+oII zx$9YfmiU`_Gr#{6>go6V`@fibpU3?h-k-UCdw#k6mwp?%HGUSCfB%23Zv7=jWee^H zul>>@`upC0%sl?r_Bshxz5f;7f4+cQ?e$)NWJlzBdXDq;#zxKcLWVSFWSWD@{yBZ` z@O$3BpmkCCzoz^Rmp8H?kALfbt8V=gWx4K{=kVz?b#ocjs-NTU{CQZ0?`_Ijc;ZZ_ zY&*Y4EX#h;Z5NMu?<2~deMFi1FJefH_%p5M*2j)J8|9f@o7jEby*ZCLJd3-}1t-Hpl{*MLc{;SP6Klndy z_MM2{)W_$3kabhg+y6(~`@rWp-T(jB-KI@iQFjR|g1e-olMxtEvW@%MG;$S>D1IdHNV&Ex~`M+x=!x$ z`98j%-}QL3xu56tKJW8Bf39=Rb=}u}-=9AMevhsou>9OG@bjj3{5xv*9H4Ll%sv$-)2ZJ@U?;GJIhLY$h28>Ju+oh zL+74I=O5(u1iM`Jc+(OEHV8&~>5X^Inu~NSP%sIrJs}iB!1pQoJA9#MT z9Qt@4Hni9NO%~s%BT%1T*!t*tM*Do|8PFLo|BsyQJjO3yGrb$>3B0CnGLJg^i##__6uy@l>b0(J-fM-v6aIp|v8?x}+582l zpL3pJmLAx@tWOyhoaP~3q5!W=y%{IdyOCal*OB=iaVA2&0p)c2`oMlPK8lBWiDt}` zk-Fj@ohiF)dGwx!Nrzj1e3`a1>6NhOYt!~@W5&wEj8VgJq#3;q`N*`Pz6e~2*Y5Z- zc^SXS+Y4LfGclw*9DTpRq-P;L&G%{NL;A}>dRCJ35~SxL-L$*$(}?t(Bi7w@yCdI`qCa>!|E!8kT;%sMkYAL&=(wR`@u4XFPNdNE$>{?PdR z2pUe`{&T?OS&2GLLwb=stHL?J*$0%@F5+5~4uR?mVa(BUhfv?#$hrYX! zhvmBc?6yzEk*N1C?X@YH2iwH759?ym^Zj%?*V4{twZ0aer&%|nV@UM-)Or(weeqsI&hpDJClwi-^QeCT@t>%ec##mE=|%N%xBI$_04p1J*IVP z_I*d{cXC80G!26d*D}`17lPPlU8h=gDlGW*cr1M^>xu0TutwwqR z>3TjIt?L`K9p9j3JTlOyi7yYDo^K|-9O-OlGnUzBY==6evpy!KM(`phUblbAEk|P> zdo+l{a1NMd7%m30UkqOfW*gCl`5VB&z9>3(7`+R6A#5Y#0nAvLKjSg854HVn^1{Rm z_NYE%eT!0Tjd1NC<3_!H@08%6vY0Qi*aSZ;$QICJgVl#RZbgUo!&mObwj25iXw(X3TgYv6=zgA;x%(oO; zzOUIj8Goz~|0x@vNcJ}P`y%U8>k;^rc`@Ao8DGJivwOV|{=<2%|JgtFf3vUmmyLH% zg7!B4b*<5u6VZJB*fn{!`kKUq_iSiy^fF%`xL4FRV!buaT0c+3r+>e}_>4mj`_q4B zN@L|dWOo|NaOWW7Gng;>+r}SMbE8o(^+pF$Bez_Sd0sdDR=&+Ej1oP z@sH!ra3NlsHHBp|J!`mm4t-!u(R@+e!~i$`vpCvD8UyDN6GI)!ngTX4sE-0a-QLe~ z>r5Y;^E~fU)LF-zN#BKZo|k5xHtC7Sqw}{(FF-oSgo(wZPeZ!SXC}QA>3Og>dl$ye zcoreO+AlXc4yf_aabSEgJz3d1;42@R8&l2`=Go(5?odDMV`Fb(qW^G?>Yu+f4_})+ zCcOq_@U`21jZV6jk>~rd_2!r|^)B|cfn&z#ZeF*)Sx)D1m^V>=sZ);8dZA%DLS1YO zM$7zlun%*u0qBzl$D7vGq~{~uw2kpq3}4CSe3K^_y8~mWM!spjKdZ5gO}=3Muzkw( zHssNCw_V6vkH`Bku;Un_KXM;9f!8K>la3qh1Fk7)pNDkT&)D-d)2AWbZBzCuwR&j5 zdJ^qdqqjk?_I)PTvsQWW&4J#4&$INupKr?cev|xOogXi>l5gByc-^z5hb-ofAj zdU1c<5nF*DUv#W6HXb@AOqoot$3LgcGSm0e>C=pJlP~@U(+|4lKc~ag z$-ifPONu-j!ThDr1OLg(Zc0)o;~SD!?3NwwCrxYv+HCTOTz8J5zeNSOR75OE+Rz{K z)Em~A`NYObU)0*6CGeVUO6GAC{<-rxwau{2^ffykOdgIU^-%$K*9&8t?`ZUCv;p-F zpKUezBG~G4Xqvae_Z#hRjcM^We+D*TrGE_Obu$+v!t_R@ zZ}5E#+;6iE%*$gr{zc9O+(%{|eBaL}Uo%YJEh$dksU!G^ho83*c`My9H*rLvJEmBV z&0#Egcx~!IJCn}WjEUT{HhA9H?Gt0W92bs}`h?@0dhH9ipE58eKW6HQm&`s*=Ff2M zpk4-@_i1FDVYCGEDfRDti;k>bsh>aUKUtgfol5KAy;yT!h;3!kx!o~qJlou)=M1c$ z-=9X`&(CM?^=aO_eNAF33Z82(Eo zcOVZB#;nXZlraqb@nP(FZs~l&IvQ;&UPs19_`I;unKxN{te>$d@NMk5sr~~kIwz>! z>Xsj_J;rykwZ~}HPPwKHcA;Ha2FC|&N39!ptz&%T`aXjBRO4#f&A2i7iu`=`zKP~t z?Q1e_@IJWeWxl@qHd*K9KRtLa%aqM~WbQp&^&i9*DL*%XJSP9)e*Wb1ps|_a+eCc$ zdq|@vDI=nn49p*iVVd8*-yB1M?_=P5)+UCUf&0utZHF#520SOAdYh|<@8uc)wZ1+u zMjiXpd>cFV6JV2n@xU>(0!jVj5-&Zy##g_L)4f+?{Bm4lK8buT&S<4>nW!`Ejm|Q3 zo;2x;{dDPXtb3Y|=b>4P5_oO$1^qm*jWqAxzHhr{(RG{WZ0BVBha-W1%Jjj1s+-td zJJySK37qTIc&+m-+tT6DO?gyH1pXrTolIHk&y)l6NNk#} z_Wv(sw4g5KD97xN+;$@8PsQguVK)@74G&r$e1?SWPMyaj{Bz$oP@UH(k$nR=fq&8b z1Lpe1roiTX793g`*<{KxZ{ew!ozx|hv&L`2U+ z|G_o*^#;xjC5(l7^DDvU%M7=G6VMFfrQiR4zr(%*I^#0q&csN&3U|*Q?ukqs^r`0| zS?0PDF-yUj=s+ALa^j7`z^ z{t!1>R_0aO1Tgo&d+?;BqHB51oi_voKTG5&?uul?`Et8b2f z*LMSaSNQ1z<4Pc%zPEgXjn+K}_Btk2)?u--+-a^YW0e}(gi ze0Ije^=qLIzV~%yx zwjAl7IZCSOgz9*lV{D?Cr4=QiT#K%U^20BCOr@7#lGKY8`mR!iKLr2;%|BJt$w;(2ZZ;G*athH>-aF` zAdBC=W?k*?|F_M)(w=`t%Yg=$k#T4=`YXUcotI6F)PncxqHU$I>@G%4H)S;-j^I8} z_#6%{2#l|_o6UO~(f0cY>ADX~ASSj?#yeiT7O#`7dB$cDZ0dJoV`75rUEtf;b~E)) zc{j;>>fw74jG^~Ev(5xDbIiE&SMCg!5VUaue+{q3>twOBY-6*?w;9;>MlbU9plr?8 z>ZeD>mA}U}`I>OTM%IP!GaE)9g^EPw-oZO9+A z^FZI}pWyz1+ji!=Y#8^pfzKG3coTk^!8u^c%7T5NpKi;d9rIK|+u~~j`!d;>?kmS$ z=hJ~>n&~{!-FrqwBMK8pr(S`4?RdSrKA}zKKky9KZpH=msy_1>s%X2KGFqVr^TfdV zaJ-v15Afr#^OQ+9`xSEDc5@AH+l_5vY|Z|Zyco8e<4qY$!TDgbE}8TVNDuA-2W6Xd zm`1*%#iaMaJ`b8XPu)Jrgw}W|u9yCq#Nb}+myrdncf4xn(mfQ zPPq*K;mF26!#j}A>=URT{#meYX?rlebT{erhiN$yk0~cv`YrI2EdBr1k87Vm0?WMv z{$IrFWMkLZK=$7FhHF+6Kl|UbgWH}wXG<&ad9od5evXbkT~FEf4X~|*?frP|&SS1` z_UTI4{|ENkR>|zTVVCxKu!l3TGC$Kxkk0c&#|qOckk0sB`#L9`HneX-dJbN@*8|kr zcT+~^ZqhgJCcSqz>AQB5p8hYh?%I6><7q&8lOJnzy)kVP|04Q)r%BIt(%rUBz-Q6r zxIYWKV7(YPZyB2#U~{4$!$2F?FUxO+-<8PY_7&4RoOCxo$JS=pZGc^F3j0*n;qW?L z$0Ey1zXI*FSM+m+u3y^a!44N41L9&j9vY3LyZIRxe%jniz^)6gBm1(`g7-+N?||Om z>Udwl1`vzw7%O*!J{En?DYU#m^W#z-O`RllJ-8 zSfme)#WM%SP?*fV3ijE<2RzS6-(|4x91-*H z8SAx}>zmvN+dkNGPIGnoS`K|D^nAR=oQ1D~ynFD(5sPAsi(2kpv2cHccEvEiJ7v;{ zCd}i>eD%S;2KL#$ujt%NZ7H-AX!K2P1_$Lv=MBb1y$gDd*{{XAxUrolEFwgaB)$FuK= zP%k2*UUFSFf&jsIr2`|zg6GseK^Vmi?*I=9# z3>*ta>xCAyk)5Yl4)bN49E+E@=j)__&n>fFOJL7~^RQb_mbDssZxYU+yQU}|VQ)BURyq0l2 zWkgl5_E4{YzS!5LFL4hg9civVe7CvR3;Up+;XR}9eIm96b+6FOOKAhzl|Iwwc-}9u z|1;OcT87`p(6iuU5o{%9znycSwL&X)v;>&ij{bZD&p%^RKQR{m4#_|p#z#LHlVbj7 z#0*z}*@mn)^>%Qu{@MLM(|eIV;JNw9!MzRYB}K7#8+^#dtpE4H{4orhw8>__73~kx zHd~+v*8tA=N8bIW#Ny)zj{jT}ck$_FJO^+i#mMXuAToJc9dPwl7rs6uPcm zZkgmh_-R9#eC_INyZC&(uM0hn*JkfTJEnIbo#ngv*mlLx`=HnR`J^Ai=eej?pBsx` z09|8b{M7yk?QB1+rPc_o(f2cOu48-BCT)h1Y&zjj+%scw>>t|Qv zm))!8&6#!dteMwV&pLYIwUyW7ci4}{Z&z2|h+hjm+PAy5W_)g5uK#-6b(Pl~o$Tj? z`SZo|YOeEt#u$HtU-~@iy#FQd_`%TGm9wt(!oUA}e&=0(dG#!>(*M&RbBH$_gI}_p za~Xcebk6@;fmc?~!%uSi|MwRc(ElH$&7NC}pQvTGupck$$Nr-Kclv(LtT}!m;otvd z@Awt$xt08Z?dsWcuko(9wl#3R=* zch@*B#hQ;}us4K%cqI7WVE-vmT=(>IDwA=fB>4Ye|6K*Vh#MZpWG{bzlYh9+IhnBp zUkvv4;2*D~pE=v{F!}cku;1T^fW!X>dwV(Thuxnx*c;jZnlA?X-(+c%27CKh@O93v z_89E#YXPqY`!lvp8ti??g0FM+vBzLoI{G1{(9<*D*Qz^{_v9m31t{ z4?-RU=6ee%hYJ53yq_@Z zqy8CBv7?*uz)wQ0gl>k37q*A#f9_s>pF}^`@mDJRJnh4S?Z@(KMJE?vtqe?3yq7~; z{-OOQz6i&AENtI8$=?HcLC9=>)_1Y!^uJX2Z{YhJ`_-b;zC-vc@EXT{i|G5{6y9)v zmk7?};eP-3ihc-$ZBG7_@wUH@gx-bx!N?r$$3H4OA3ZPC%Y$w>24?+O9{%7M?wtqS z9HxEo=3{?*(tfk>hMZo=3gz${B6S2 z+l8rj2ve_`5Ut;0Vc)+n^RIQd%i-+fqW=En@WIDN^=5~kboieRugH()A9X^Mn;af= zVpJdHaQR7AXMOSEk4S$fgsHa){}AIF4;Cf3bBJNSVEb$po%SgwNByM$(E8-)42yc@xM4#v#qZH3k!^JmKZNbb1ItRF-C`LWyKK8MqA zz9Sosz&_z{zQZLBS28Bhm-Mp>l_e+u)h8kJVBWL)`>myPdm-#r(PmVeTgvj4lJqogCo^H z|FEVfd<@s~LSfqDx!8z~d;k4ReX00od7Fi)Z*e%kC>rnm4)+PuU)toTeO#D&wlK@f zb@&E{pLIBWO4NUi@TW1)n-9*1UvvI16`kcL-1A??3-yKrO?w6BU%v3ZgJ2LIW_+&@ z|E$k%9Ddf}4u`vh{rFCg)-Ow#dZjSSs}iQZLYR81@L`Dmad0itP5Y!2+wx9?{$ydW zALV?12DmqF=KoahJn&PZPl6wOad!WD!t(2csn-irZxg28E=+x=F!f!+)VEHx<&_T# zu0MHC&8$y-qA!Au`9FbS(Xa0io&HkJu>M$Hx-j(|Vd}ZU)Qg3wmk8g3@~4A&U(vL8 zrRdC`<&4K2&Unm{@ke|15B}f?#wYv7$8bJieFF}3_Ls7`UT6L`#AgmOo~tE3)~C_o zW{1~0{4e3>llad()3*1k&<_Ih-mht&0?}E1vBRYfe@{5s^~oa9*?uj;^pEe`NZ=2S z;QDB>F!kkP|5wEOFgOe8Cf>E8(|(;W%j*@UzEe1cTQpySi^N~fG}}J3FA%1`Zs8-4 z|2vn*{OOG#{e$t!_>hbv;EyLp`DJH3zv6K3VNv@|M{knr-z!j`gVBCLdj$JA za!~#duMxUA%=xie;%EIj9qw^Br zvDh>91Ls<+VH9;qV_FUgvP9!>>8~hQsd)Gakl^ zKRAN}JYQKqWwxg>`%jtur<^jM0l5`cY34rq1~A2gh))eMs<% z|C{zpi2Wa-j|S`fS13CD7YoyWxiIw#Vd}NQ)EgXb5~h8#Fzs7}skaJKUnxwzN0@q_ zF!l0s+g|StL4Qv&<1^^LCedlX?h;S!XIvW9M+sAJ7H0l7Vd@)%V>my?;{Cwj zd zrI_D?{c_OX>qMu0r!f6(5cb>qifDPu9mbEgMdE7~roR=!etE)vc@A$CrhQ^o)Ia+R z$vA@Zh4u3h>(?68w;CMuXR7xmcoFxn=x_G#4sZ{y#{xab&;ASY2TWbr&+jJ$I{gQF zs<$5=G1v+FTqMvx<0S`rzzvml|B`1ONq~VlAMp8@{`MZ63IXF6OgO#4b< z+E)ovZxW`yM3{Q!RknQUxx&;p3sdhCrk+)0^OISB{J|0Q7u%O)nC`%s1BKkeZKOKCW=(mYZ``#ME*x02X5iO%wxg+EMU-y%Bg+l70R*yDNm{`RANmoVe)7N(vt$J*~q z;x8dO^XEETDE!C}7=(uzk5!@%O7pzg;9}UA`DKOZheKb2@r^(I{ku~1Qy{DYH%k8O zxi)^zCm%WUNuKDe?=)f7r&O4Fy)gAf4zCubeXlU>`-G`y&a?4R&l0BI>M-k%WE{bK z!20+Ip23C*57WLYC4U9m2V4mo)4u67(eg8dS$?iCNf#{UqQdz;`0o)2q~^^fu38SMV?zDoS_`Kfj%{~y8DWc%0a z0CtNQ_%9KEuUTV%z5EayGvUC0Djwk*B+UB6r9ObD4wMR_g4 zCxGu3X8!wynP2UTVgIb?w0~Kc_T9pl!2WN-)QhgQ?M*IqxWeHYhZ`Ke!{HSUZ*e&L zI$J*D&l6@mg~HUQ2~#g~xIviqi-l>wRG9j5Vd^V|skb}4*5Ou%mpEMNaDl_!(jF}D z6o(5P-XQ&VE&9_OX8u^`_)o8mw(lb6`G&Q!|7}d-FCqDtLD%zTMPR=nh++HJzXn&B zfN(xN1LoWn9NWKs8C+u!`d`4jcOM+vzy2%O9>MdC)1>?lp>RPX_!pAAkIJ`a4Ha2fb0;Y+|Pg|7tPEj$l=i!go%&}$XucwH^b{%8|k z2>T7f{|Ee*@Lk}43jY|qOZYzU!8h3Ueh^$F{4n@x;m5#Bg;#-lg`Wg}B>V^P&>O9P z)@OvnabeakL%0L^_Y-~*oFm)`K2G>GaI0`P_zmHA!Q<;}JRg9IgnPh065a-`75)s| zD!dcCLij82lftaeT8Cc~9)w5MKMUDhZ}f_u20d+ojn_XP9c~le8}^%p+1`cUi{>vD z{toOf6+Q@jweVr!I$`>|+2ICpX?tpoc%+i#B&n- zEf+o${4?Q;z|RV^eLIEcL4Qk_dgk||?U^IY`m7cEM&vh#SwD&#`^7HH`f+cP{4I|C zI^oBY*msJ)&e0ifnzY|$(YYV|0Id7Tzk%%*Z~NE(1nYkA-;O=~H#z%H{4iht{*&#A z4-!T=Q<(V=bvVo6{Tv?UaGLNi8?3)SW%=2n?+bk_nD4il^RYnmeCQ{G2Z?@)==67n z@Ko5J3FiBk#$UPUw6An{gD~sAQ<(NCH`(^0o+&)XuU|@nofPx-^zUyWM*?Oz_VgC` zdO&78W=Z~Ap^pKxLl`gp=ZgLi^i14u;TSOY&+=saFupvoXZ}KA>P5oT>m8RW}W_X<(xSgzjI%3XQu71(ct`9!RNfq`{QMj z|0w7)!2E2iIsfL0em3-Z-~&WoB>EN5ZwHr3e4V1-2>s89?>y*c{A?DT?bRdfj|XAD zJ%ty-UpwYYUIXy`UE1#wo%ZPqZTnJ>3sY|tz8n6EYi>;z>gue6;FA+R1Gu+z@o`(1fVQ^le~WpS|0o?UN8@du9o< z{x!nXYlW#d3R7PsOub2%`VwL4t-{n-3R5q>BN{L3i)0)@f3iJ%1P_sqyqfkcmHc}{ zKOf9;%zU|2be6YP_-NQ~K>w~AWZQS0=(OJ~Out)%si)j&ERM!kE=;{anE4kAQ%~F#&7UJoyB19Fe+yItIx^r{m}aN%X2s`%tAgj30k+4EIW$`my|k*k1yDG+5W~D$#F%p5n|8wW2pbzuw8;Ci*hyYZKA= zWu551g1#QS5^jr1i}u1F9Krm=_V*F|Jle|~W`3%Z{H)(C4&UMMTMow` zh?ZX^On)`PFDEJgC!)Ur{ik5vPqvD_75d}gY4B_2&z++G6Z)56UB9L^+xQqyiSST- zCBby?!8l)yzq!k-{eIBrfzOcg+C)Db`qSXzP-pw^5}oCFKePT$gnbO$BIUI_Xm#4B zv_v__;S(LMaCni!FFV}jaN0xB@~R!a+2MBKb5S32nDLbIbL)@o5f{EBiG7CXw9gi1 zd*ldHFA%0)=JuW?4O4IDmY#I;Ti4(5Jzx5(JkBs`!~S} zsHXfr(OI9J!i=wJNYr0})R#Kr#UC8OeB{R)@&_o-9A^A9i@!eT%fJONGV!bvJsmsU zI$q!7f{XRvAG{8qcQw~vjJI3t$3lM-TqFJphMM?-_Gpm!Plf$LaJO$C+^;EEZpR1x z7fb#U*iQvF$85Z-Q?38Yp#Q1R_8;??IsPhz*?zUcw67DU-Y86ckudem!qj_(se2Dc z>yzSemcu#1%s)+-{!4_Z*9%i`6sEqyVYUyFaRlSV?_Xi|uaD5LL3^6RjGwL2-gVIN z3`-&lMrQn^q?!Cdf2RrG4*Ox?T(Qp)o$==j{}T2mfUgYgssBv$Hs}w6gY_XO?<3J) zg8ni1aLK>YX^$RZ`cEGgjenFd+p|)b_BF!PJB6w5693fmei^55xyc3UPmy{cGmm2GLpm3Sq|AD(u(4|Nic9Z!-Lu!?f2& zVt)zW}F+y|==a{{{3ISg#jKL_ZWa3eE=y^Ltbdv4Z2xlMjj+E2oEh3vuM?fzC`^Ceqc)zQys>j-@ICFk-%FkC zi$6Gm^M!iAL%h9cA0B4Bri(w8m*a4;!&f@o;Bc2PmkU#`5%%L1rrsz_eTl!a{poWS4Cp~cj%MByTo7q zYU}U6q2v3#BJ)?F=rMdH=R|O~#OYdIj}yXL>~uzfA9{;ze{x5r$1@^ z6~cZ`aAwT5R|fhIW;lZVX0|ZfzoO0R8Mi zj+LBAEeLGl+qZ{yns3rk9&|8tMF|3zo~4Z^H%qcHU?Ypp*r{oxOe z@ccl0K7tQNdFEh!bHH`Z{-ek7SNVeV&+==9Szg*pRxgIXK~8-VqBDP)!`~C8KgNSU zID+^GNqx?C;-|l6C;v`|Prlk-56(!Ef0tvQvCh_q{znN{Cdr==o$)sc*TH@&${&h! zUa$TLTmnuHnf7G-!7;>p+VMY(8J+fAEdH6lS(x#*2vgtcF#RDJ2gbis9`o-Kd-9<5 zwmn`*VxK1ZE6|65TbK{)70X{D`diR@G5_*>;(YfpIO{09e~Jl%ydAt5Ivd2yhbtui zzo9<@PQ86Y|J0iuZV{$^ zn=tJ=gsC$={J{~7Z?=bzA+tS{*&c=uNBrh6^VMeY&+=+Iqwx-UHOeD|@$6>*Vf? z<73E-S2=C7<>DmuFBJdhK%WSv12bOAMQ3|gIJ`)h@ihz6ez`F9c42?K2vgtcaCx2Ds`MZ&SwUeK$ z`M+@L-!1w3kbk92nH5j&*3g%+ULG* zc7rozeJY2jS6T;Lhg{jvFQ(rAi zy~E+R9PSnN%YW0xn zpCe5FwZb1F{}Gw7L=5R>KiVMrXV4ddi(p{8-b=6$)84oChr{3D z(mvGLUigC}*soA086M+sHsT5N;QheW&i$blhg%(9?(j;7dHx0dQ@vcoYYwh=Cx8!> z_*vg{sUPbz%Hb7`f98i7j^SRBm1zsWcxm%eT6Xf`j4afQeo;lg&EH- zVd{-N(fo@XZWE?`+9y%_bYbf4e~;>$9rm_ao%RV~#+M~by+W9Jr7-n^Pp!XGI8ejG z><^1Xr+t}l5$y4dMPd-r&3acMI_=Z{Vg0lGOkv+&UsSJhxK)_;IoqT5dBW5e3A4P# z4lfm^eWx((H#poUO#8$?ZTaLjXMSLNAQ?xhcUF@2%#!@2(8qw+!rIIaTSR9(J;GNd z@wY?tdC)%xj}QGZ|KXq6cprv-1o$Y?OGSSV`uUE2i|F)shw#A%At5}>cq!Ro%R3^8 zUMc!9N%a4SenJvG?Q`pY67*rR{ik@t|Y!IF0Z~b>P{$0Y<`~KVNb28k&1oulbg|AQIFCjY1uk=iN1=q{iZpngzzx)N4Ds{ zNfK|p==4{(hxNzuN`;?JlD|^)WaF()boyU6!uo$ciN8+KY2PdSN)r1%(P_U!xGRbM zPSI(fy_b!L_01KgUM2i)5`Q(K(|(CC{Vf%yzCoCJmoW8R!qmOEjqjr*<)@4Oc@jM# zddk6c7#wDN93}dQBzlSH-+?|IoC_CbeW(|m@iqvvK9`QP@sqRnu}u3yVe0w&MfGZ7 z>Z|vU>KlZqugHw*J;Ky?2($d1!ql@5issJ|rrs&c{N2LTYY(>h$z^qhhj^K2KQj08 zyq-K1TrK>sBhY?ezF%&h@4Q0VkL6VgADN`T8m0U^=(mFTc}LSz6G||BDWf>RW}Ww~uvnVd{x-Q9WOn`qrbZ-k2o*KGA94nQQI+ z@hW^*lKefQGru=Jnmp33y+PKS0e2D%d`4VlEmL3I_+zY zxArYb?CVAUHT0Xnt;lE2my(lge%7yCnEpEoto~#Y|La750s4AyR_OoLB=(i3Sby}t zRG8&27pA^anEGmA>N(#r`?FN}J;MJ=;;&b9+V2vkKd;cn6HBsR$`YOVmkTq0t1$ImVd^`Csn<@lC#y{kNX! z=)%;y&a!&4@_Ix+1o3{MEwali0V3PWukw6O-7l z6`l4Qgc)C#@Z==<`$T8{l=E!;&Q4+<7oGOG!WSm7&l8>YrNT3l*q4b;`vzgwr&0Kt zB>9^~zcbnIXNi6@@;?Nwf?w0WTSRAhX{EM37*C-v^)iRcg=t?WO#6Ca>PsD7ooVL( z@c9RaS32D8aEHTf@_SmpO4eRZ`5T0PM|*spE)9Ro{mm_+GyaV8ZTql(S;ExYgkOZe zR>Y_8PqvFr`@##N{>mM$bGX^z4u^XjPPs7ZKhxnnhszwUcevT%PGQ!E^~E0?L4UG6 zeZ>9It|a}jMe?&fw+ho=pD^_u!qmO8X#G-zsmFzxKSP*$LfG$5;dhh7nj&;<1>+OHX9Ld7jD@_1 z|2#&v*t33HF1Go{!#)f4aF6kg-`fG_Oa3##A565LH@g^I2%R^;V%{F!Ebvy*>7Vi7 z500R}srwi*{V6lvfcNm9KVZ+UUXik7>e< zj{RK@Gk<2C&HoeV*|^`|hjh*l)U)LN|IeYDgYi)>lJ)=b1oC6QI|%8_|0LKPwEwp6 zQ{{N+kk7Y~<9nF)4L(m;F1$8@>v!SJ;0?m>gYliB_@75Au7%OR!k>airCWUmI7|57 z;G=}S(YQY;JQO@hI33(190$)8W_v9XX8qKDKiKa#!b7P%QoV!0y<*S&J;Kbd`r)u| z-_z!&{i6=I3N!y|;T+^o>}B)kf#bsTcZ0)q4wp&$(mq}IMEEm@8Q%?(zbJ|ROVQ6w zqPL4aD~Y~A^tvSaR?+WFqVE*_r%Ci(qW|2{{rb!2`F;<5h-m{I{EFl6 z9q>x5|7QLEJ9vdK^ONxhN2>Rwlb?FMJa6`&BzodNlYhAH#r((q8hR+^b6M|3f$i@r zr{Z1>_CHeo$&Oy)@J#S1@prw$i@;hQhDx&_fXGZx$hxvQSK_3R|!=VmOaJbKD-zrDP#2)$^ zhOWHqV+k_VSayUP~TwvYH;)=4*%8R{41mW zuXlK>!-rfIwV&zmPaNLh@aGQiUlsK?!C`*hFQ{M8p9>uR(&1xgNA0IM{D{Nr9Zr}1 z1pD(ehxz#uji=nv zhY!Cl>hDa4=R5pMhyUzwqBiR9`0JxQ-QnvUzSrTe98TO2^>>oPmpZ)I;Wmd8vcKl| z&2{)(hgUe9F8gcd=l(kApJ09~ar6ruUim#+pPykporvoRb}+B!CgE?PTwl=tG~s7q zKi#n}5uNts!mq=Arej|rI_;~4x5IwEV_zdW?dye855x1Sj(vmZv|lWIAnfmP?3+ZV zeY5b9uz$$0ZxNmLt-_OGzsj*+DLU=jg)fHv8ppmvblP_c-wgYWj{OGFX}?+cLD;|N z*l!V?_PxR{!G61A-zPflcL{HSee9Cx`0>Cn!x20`k}izzI`Kw2_HohaKU4TX*pGJX z6Qa{TNBBh8ALH2Picb3i;Tf=>=-3yEPWx%Xb+DiA*q4Y-`*Pt2VL#KcuMnN~)xyuf ze!gR0BRcKtg+GA(LdU*AblNW#PC>#wj(wBpv~LzZ5(y7E_AR2*zE!vc39B6Ym7>$W zUHE1sta0o+M5leHa5EA%I`$hxr~PK(r;+fUW4}do+V={-g@o;neV^#G-zEHaB;Y#~ z{rg4yzC6yKqn!P6mhfJODmv|# z3%>{ZM;!YVqSJo0@E5Ru+OcmFo%U;mGx5C0ddGg9=(O(=J`(nCI`-Y7(|)V)sj$EE z+TeO?Z_KafgO{Bbiw}Yw`C9M{+%Lwo;Pb8E(ReLM>*81gG%9RBqlM)-hZ8q?;h~0 zxj{V4{{VQ?qqaYv2Y28WAF{(J)q4#*4xj(w=N0I$7d-YjFa9Sm^Jn3W(s3QO{f-6S zcZV(ivn#PaqCaxN{HH_T)NaSqx!{=_y!hdvJ`>!7`$K8qktly5c>AT+|4+d)FrJLR zpM!rlH~9P}a}2go;V%(Ie#n! zzbEtGz2J8+Uzzs(8F)|B?{e5P|I^^laee{8soq8~-!C=e?eE~bF1O=p@Hl+`?T_tz zGXl)_W6k+{Jovv4vGdz$;7_ix^JxiquLbseD+51sq34f3)_*Q|A?CMW{HJ<1fKT|P z&HrQSH=(`5_*=lgMSapkeiHn6pBG;g^3rnnM}M3CTf_WicK&+}{Q1=2d4HDQ1FpjT zLO$;}8tpk2ACwqV80+_U44C(WIsbC}od8}NUN6RBKNz&&T{@=BG{IH)X!< z1wSY2iFY*SBb?8fVR?IlH_Zy#gZ_^I{{Wx&;CLWk2>u$M&oF!$SnI!SFwQr`Yv$Wy zr(!)pe{kQ&{8zz#a`=7>$6GykJuW55|G{ z`65%^ao|Vty?9ONe+KHy_aBU21%2FI!S_AU-%a2h7|(fr{6oCO;QKHi)1LZI!P6hM z`-NYEmmME`UY_l>4*U$}k3?v{5xo9RJ3jsne)>k zxn4dC-gdJcFPp%daQC|4{^a>c|2x6!Wj@^p9X|n|ujcq=yraSEbM5?_1Ab4|pHsjK9tpnRnD+C* zpU8Z%2)yccFTOnVw~YB02EU&{d&KVDb1%NX5FJK-7R>LDWPQ0lZ3N$Wzg=Jd3V!of z_`QtKUwi_tFJwJA4m?xVzhdwV>}Pg__S3=po*avpgzN7`;8(G~&j|He@axhZjo>!% z|2UYRALjVt{PGl-pEoxA5_m1_*}l|Y2bakB{TEpK=WDQee{UrA=X)H7`55EZtWW!c zZyM|+g84AjI||%`>z80YO7-%=(`CIn4ZI4^@8u5)+Oq`w(1TvQGOXWa;Crw1;>{s{ zA3P4%14SYK5X|pO3Fgls{H~Ztys>GR58v?O7lrn}g#NsYk0-zru-?W){Uzp?^Y5=< zejkeQ-wXanogJTFgU8)s=jXkSkCtDK^`Z&Sixk2?+joEH{JxUwLLLvEbB3L7&I3=C z^2@>eewV>$ALhRvd=S=yoG{*n;Pdye`>ET&{Jvq+zdr&Wb5-#Dl^n0F;Cp1h*a3d# z{8+pt^tTbb?=S57@HrXlC+B*i|d2zP(KJf`f+4+@(w-`&u?MBQWSD7`D9$*gIVA2 zfn(e3`OyS^pvdmuTET0uzcuaoNAP-FPmT)xy#c-l&##*C@-BFW^zUcjjo457{fYT# z*hz>F*N3>Q^W!@Ry#44{yeH%%z$asTPYU@Y@E17$%=Ks~_^$D`yo+Iy z`riir{4KklG=Ue&`n3$aOxFMPV4Y822lM-{e(}Sgy*~xdT5j9pKi~ymb3P2mi8xZO zzYYQ4etOJrZ}!I+uu_dl9?<^HnM4MaH`k{4lPkOn<*c{Q^7QdciS_ zHxtj-U|nzaJQ?G^*ozm2^-F-a&9d!xB=`sS+x`6U;5RW}!;N45>EJo%#^RX9e4Y+A z&)@KV$XsxT+`qaRd=ow|!12xa8^JTsKjwV+F?a~tFA?ewftS5x=f_px>6pKAq4WHB z3jE&WSRBiU@9$agzBk(WZXI|k)<5H~8$1&8scEl|!1c0TAAAb>|73f=D+la_{S!xd zLnq?op# zecQm@c%Fsz;ePo|Fuy;|%tt-o=VU$H1s;d}s+lj+PsMyA`}G6Co5K3Cf3m^bF`u@C z^ZTjbg>gI&jsmDp1@rsjOnDc9w-wm)|8lUl&o$s-S9|f^F#hj@*I>W1+2>U6F7Tlf zy+j9?>vc2ucW2xFdKCP2%uAGn_UpmNV7-~*bBgyVcs;I{ibM7aF&`}szQ2<34hOH_ zXwQd(z+1-z{TatQxW|Bx!F-nRg7I|@cwej!)41AOcA*k6V1aXEOK>}ReA7yLMQ z|1OT_yY8U=m>qx3;ID8!V9v+Kz?a~9KFtgKkC=?{y~Fm;OVIgy2f=(W+gT8Oa?bE^Up}*@x-Ve<0i!=Rq82A#*A7*^zfxBhC zDg}=`$m$n^@B7&9H><$jD6>9q|9a1I+)w%h`|)tTx&itLI3M!E@*f53`1mcD&*z)^ zz775W<24c5{|$WBpMvlIW`BGJUL*78*Wf-m9}d7m#qT3D_4_V(B=&Eny-!6!dcR;i z?PY&o2;Nv}`(rA2G_Dt#5fA5|8Q@RAm0^6hfM1jO;z97!J$AkR4fy&O@OwD1pug9F z&&PUe_7j`I54|GwW&Z1J|Ly?K$Nlvxzr0j$@6$Z*LbMN-aesV{0gprfw1#{X_%d1V zCxIuX8m6c=J!1$ zke~C_3*ftC{r(bc&yT&l^dhX+82?v?@h&+B_S@}xdj#~aus-bw^+K?hX2;hl`(yu@ z8A~7)jg*eMpuaA+@7K%*?~C&f)1Kcxw=;kL{&5fQr{J4#eVYjNr@{Bh{^Pv@>~~(b z_Zwb<{_s8a{OJN`VSmH^$QhWpFF7grejA=ov%s5VKD`nAs$B2h0sa;CtNZ!+Q@wk@BQbt}L4Ck{ zem@1w@wW>65Y{gmFurx*>%a2ib78>p-T-&X{_JD0zQ6QO@cEeUbHn^!gKxxoQylVl zPRH{T{o`-AcNlp3v9Wkfczz!Vo-gb9MDT}*-(P>R-@Xw1Fs@HbeAj^2WBi)=X~7Y= zzQ*}b7M6Dl^m@F%5!7$E*95*5>y_!x--1s-dmH-~z%yh#zX{%m_2A&p-(lD|osac5 z+vim8edzZ580PH&-zEFyufg*-TK^-^5d8j>Af8ljGxY4d;CjxSe>vb~xPCVMJrVry2CJV19)|s9cUay9;90mn+Y)j$c-0wL|HJ;T13&X@ za6gvyzYT2XzwKW?03L$*+w}iq;Q90IczzE2Rf9c$Uk2-X*#*}9>APTlpYLFl&-rKv zc>Qa3K213zntufNt973LeddgBfAG=R-yIs(XEgXm%tv!WJ^_4BwT<^I@MIa^SAfTC zLi}O@??K;&{gl~1VeEPxvR>a0UW4_|^vBP^GqC=ccvgaEpKh<0UkCT$ z{sQ}-_1y+uh4C{jjQ1-rzYoxyFX_0SG8*?^IzoMK@EY|00U;j(-h}%NrC^S?bHIAP zyYyb~A)L!qs37-0AFTT_FpW~DSoUW5J5Ampds3fA}c{(ZUU9XZHL6#4Ps z_qCwo;BfZ`Nhf#))?eml{d>VV1zut)nDzfBcz>M#lQ5p>Kj$o@|ImxC4(*R4{~`Fj z8|I$~9`=ykkDUV^Gdk9PeqIdz67#PgFXrFNxgN>-IUD-If7$hF9_>qU|1TWRw}WS6 zeV-JTzXUu4@dW*u;{6OfQ_hFg;E|Z0SRcmM0Zw4POv8ZW`uZyPD_P&(2ajv9@Ave9 zKUwR=7l--(4ZaWicQZc?KO6G}-mfwJxi|P;T<@Fn=Sc9IIA4py{AYrnM}G|kvpp{X z<6I5IA3)+_)HUjKB0XW@G0elY9* z2Kd%T?E9}@gY|q#!~Sn9K9ATNws!`2m+U9Az?aB=Z3;LY`<0-)RPR#oWUM!4KK(xJ z<@~%0d=ut(W?($az_Vn3+6K1m5%XRIe~A7I#&3%E9+=C>@4DDwRFCm#u3i2d1!(EcRw$_jhGV+wfkVYr?_ zfQ;{K@bp{kezgL;@e7;}IG?Cr4c7M;>%ez@=EYwO{r?`k3HL+IeBXfku^VN4tY`kb z;Q0Z@cOc%_dk5>$k}!WR`0e|>{`*aZU_C!B2W$Crz>{(RxFF1b7x;9%-(%|g0C*ze z$2QE5|L5TEpK13?kAU_1W))cdzW`34y+$EF@BjP_yzNvwK6Zfl{qUbb=X|>7dFWr% zkNv~?O#ttS{Uc9V@-%RRoKKg4^?vE~;4h8~_E)rj0Q@_g|INtH_J0)o`6af0{s6un z{blB#m%;pgZk*nJJk=Q3Ge7n4lT$(d_o4Ii`shwyPs2jI?L9A^2z4&ZPygEP?~VZL z^ACmKJu#j$Li^LfI1(NBZ=^TWdx`JI;Q8xpFyk$QJ_hq8hN;i9!FoPj2i}P5i@Z?3 z7rZFkuZ~80J_KHX@x=D0zsJBYVE+&Yvwb?jGyh`qe*{+l{{T-7`wNe_|BMeg2mD^C9UoJ{d%kba_gUbR!{^Hx&oAIlpC`Kp`V{Hk+rhuX^<*OS-vT}X z=O>nJzdlcapIKw|HQ>*V_u@}NXT1LaAA|L$Ftq;y{5jT-hL8tcfcc}#zF(9M*7u7K z1MBt0G2l1l{zW0~=Y5IiolN`YL;rl5UH?u4e}(zb^yf72?{Gbp5te@ec$wS}zY2WN zmG=F=TJZiS1kZo5KED9#cz*)?9Ogf>Klvm0na6DTuYqSS0f+0=$KXH6e6ka){T;gy z<5~I-_mVI=Qxf*XF^4)`FfPo}=7fHi+Hcst%t;`z(|Jq!F{EEaz^2O;^)zW^DPzEK3Jczf6fX0{RVuHTwkvPpM~*a#^*-xkavUM zBV;`9fIq={z!RL@1HMo84=H7y_fxqZ8wI`{`yI2N8Uxn%vyTN|BK0|kyx6w?MP#`? zoduqN_TzlU@~;Pv%nRO+^!pdA?|3w6PMi1|MSYy0m6Yk5OwVErt# z<>6k9H$?g`3p^F?FBOLId>8!8L-v04X<+q#7I-YygHfUVCE)kaekj(jPc3*V)=Q)R z0LcKVpwOZ&m>wd!23XYKO5m z@J_<`I6N%xZtxiFw=%)(&lWJAnPPE1KL*A6XN519S`55b${{pS0@Uwv%%@2kkT z{_y(`*B{S<$IP?(%itkczfJr81>7k2NB#!3^TqbB{|V;zf%$>NxN?od227Io>Y-Uyt*%G(4Z@fpvbr3A}BFwO;~W zhV?x^%)bn*_Y+&eU*i6S>Hpt=Gv$8Z%itE-Z@dfM7x#yF!ZMyuz@MCL%iBr4#_k_6 zw!QoCeqXRYqs$Ii75aMIpI(U$Cr<gy-0$#^pX1{#@X6TUv_WS)+ra#NtRH}>539iSh}|VpTqr{Qjh*py#_GegOB$iKE|^i{2PpC zGak2qKg9Zx1$*kp%=A3|p4IV#gLuyX^Ygng4`ZIWawH*ul4Oyz2TRm ze4Kx#zKs|^XJP!XevIc(=+mFU`Vb5Jj|c1c*>fWL8{?-kEWZHyU6|i8LM{O>#Qlhz zkS_;!$b7QE@%IDp^|&9E8`?hzo{9BfamcNX{gdEz;%^;T_a}b^kH+6<7{JsT_H;%`@fS%fm=zrpdx@zw%9W{w@N zE5R>deKPaq@4-6$o(C^G!(I<>0WZM%To%T&1N>ho@05@S%|iWTzkC4r71=)>4%Yc{ zJowcM?ft^Z;F-98Z_c-K!1{TTa`59A4|!pE*MRl;utxBFtl$4%Y3CLr$&%jnJiC^` zT;v6LZ7eThjn-m?yiHei_sldxXy;P1(>gsfz1=hHQ<>G5BOxpV z0zdeH2P7`9An=0)1_>?VWi5k*kdQ1So_IpCB_w1COMt*n{Qh4=0f1mU}nY8}je?j`+bo7zmC;hjGch`Cref&StA3Py8_H?tZr&^oQRfUJEtN z-v3v)zXtz^{OY^d@4t)wCVEr<{uTFs6L}cv?>_AlJxI&g~peTjan_e;M02I*ht{gG|TeLO)m4vn`%AZIom0duVu+(RqyJ0{Jq4j@+z<0WxB{_`6~HZom`f) z%q_}=o0O}3*A)w=T36*f$0>C!G}T0tZEs_ON03deMA^vpdyefWIj9*w?r^uoC$ z%UAhDQPug%)pIwQm5aQhTvob^SvgK;F00E`<i^YXrweQADMpYMCz2f5ai^Ha_gX>jM=cAL4FTXb$9H^5ny-Ev6!1}6( zn8D3XyVrvU&b>N&bhN1IbT;$VT@i!5;-%KUET5&fc69++rsJxdt?N8i`{JH^{`BbS z%fT=bz+;GXbhWc&kTjXEV~K+?6tWl<;m*#a+%4`H5RP|~-sSDl#h0JE<N!2XQEK1KQwsIxyI4T~tM!s$)*x76d*jK`%M;%#OIqE_ zqHJno3Y6Tg(I}{W`tgwY9SkVjjMC|e27w8TH4k<*;Vi?ndNVumbhPi>x*A)S`lJrr zR|eNA@OrpkuQQkB)nrvHS*ToI6_eae#-qVK3i^8?S5GrB?y|@r&tLkL%v@r6$}Q!=;mImgh^_QM1T5 zG8gcSX@T@uUOEI0O)E@Rf>#bW^H6vjL>De%C1uuzi&<)X$eJ7;<3|}Tjq;QOtMZ_ zVp5ky7`CPa1HlWZlmTINT;$8Zb2l`;xQ(wcruI}mMzCLc|p`u%A zw5s(Ad-|4JH^~fEO(XcE6@xvy-m~j{yFRebd-i#s&up%D&-KQ+k_^snG8^uy0H0Jc z9N4w0g)%9e`77O0ouuh&riN#Z<_@RDO|pXUv(NHXnXIS7EScT23i;$IKKGL8tc19` zv^w3O2%l~!!jjW>P{gE55x(jULHLYqdXQ$xDy;AAZ!Mg8KHtiFK6-vOI#2j|eDWQA zk=hSQ`|hr*IeeAsSK=(qHGE-;C@+_8EM_AySS)76B8TU!@`0<-gO;UbY(BHDF5mGG z>jxTIFA5kLELSXu(T6j$wwhdrH6b3QiLqO-pDbBPm`DXqj2**Nkra!ZC6Y^HH?djO z*{m2-M3S8^R0cYR!d;=g!~9%+16vUn&QP$lO4H>sTw}oShHg$G#RT=j7u~K)8dcNJ zq*z>)Z%|9nZY%0S-juV3J*W0|GoE6tIogfYzq<5#%6eR7&Ll8GD%`VVxPEKBidAdq z%)(+wkr+4WgtkxW)y&;Y)iJBu(&II?iE*tfeTBl2y-%`9(4AD{5~azN>sqtBsHjsC zBS>XOQD&l^Cep6F7N%!N`RqB0Pm?{BdS6Yd0@CcO(-iaN5gZdQA222+b0(~-bz3pD z-HM@%WOtOJPnvFh8NG6yW>@I~{Sc`pb+}#!LeBFyiJMN{a*gR}ZxUZ)q`D;>nqf@q zl}g()Q1o5TcCZ5(jW53@|KARHhM_8 zt8~Uvu!mslva8)qv2<5O>K_ZYCRo_z3L&i-^QH*z@V2|R)r~xK>E-Spa}Wd>U6K4J~;yv!@|RXGifOne(el(Zus9Jr#Qt{Gg#<;$4S439Ul zk)lPJG5tB_T28spBvXq!Nr}nWb|Zc#y*ZiOUhnT=oKG~owzgNdjA{n|YVNrDQnOs8 z)7(jIy;#8mjB)rPsz~#WR?L#Pt89|~@G`vr14_Ac@^)R&QKOj1bAzrJ0T-=>9RAYL zi$A356)ZAEp-|Ny)Rrta1#AYGfhk(TMsLkfi0$aTl&QRBYP~J-LDgTU(7ANY>vHwR zTL~ZjoEa4#R{SzwMD^QV1!L^B{O&n5t@ipyd^T$A(2I;Hb?|e%6*c4YKIR#WAes;A zo3wlz^~Nm8(NCq-_D5z6y+F9LYuL-8tZrp&SVHZSgox(hdWjgqWU(dU@AV6YA;^H; zoYf%Gl9e~RPH!9Y$c1`h_2DVMRwc)Hf0avR_E}ykH%WC%Mwn-cV3xLkWjVi_ZqW+* zW6={pz6La$S)4?l<1O3R%s2}EUT+9vL#0GvCG?*Q-3!%da2aBodyOqXmLJ2(?POL= zEPs_u)~gkEY*Q*jhf)Peb~%yxs4wf2guTy2_?qTXT?z`Z0zRjE&GOwS4n&IOpz6Z& zr~`#;Tgxk8ip$9u3YdDG$#U<^@ei!>$(6qvBbEJCmfuxLc-6uW_kf4Zmx5b2h~~O)cAa zH$n*SzJr1RNESiUY@SjL&C%yVi-%9M#StoqMoWeXWahXRTo7DAranu<9j8r2kY7-N zzh@p0c!_)vSUfctl{rK(kBkLj`bgzSW*SE2+43tjNlPFO1IPrJ#riFuHn@{Vub#S- zmoJa)AvMdg+SJ*1&fNLY^U=#!=WXWEx1OK4Z=Jq;b<*a6Wt^QodB`5(rt(T|F7dlLJxvsPF z8Zfh1SaxXJ($skYor?gpDKR~d7>1)jE5X2lSMR|J06sePlR$vP9!^XVt30OlgCFFFIFh_$h# zoq1BTMs_9`im%V=w?OZ0Yq4S<7$dly{M-U5y;Y3u9##fS54AITZ~!O+JLEtwpHWR8?~&O3VYOr zuUJ=gW^Mxj5tn`g?x_hXlO~B5ge3V3KXY8wrEH&SJzFMII5jTNWua>IPzz|^tPM}*%H8ZgP>#F7ryy_ju1`@$se$CA z{4z9)tI6ex<+au{V^6N<;{mFO1l3!GCiJq_+gVJAN@Z8`%+<3>*9_<^EB3hTxRtyI zFZ9|^jr@2Fi`2s4HcpvDd3~6EBa1AZbch6}qE8iCkPzKMtjBrGu?b@^j>bgwGUjp& zh8zZ1ZdJ+OSSV&`etXZcz_#)_8S%M(v6$-s2XVYbPf8Ky8XX@`DGk6JM9O$%qsiQO zXsxGQbJrth=q$jEZLaT~u;EUgO>CRq1g+XTv3+Rfvo;sb;umumUQ|gbl&p`YF`G?g z(v6s#0-JUC=OZ-KR^;1%#~VV&?6twv#QbR=6g&v@j;a!Xo%R--X|e7RFO>S;+i%}{ z8`5u|?jm+J+a5lEK?`zxcmI1c6lUa3)Ud5%bC9>FXd@5?klBv~K{KOqThDvI)3#6# ziVVGpdXvXD_J(cg?(A$&>PEx+bS%=3c%eNSTs3;zD0^? z9%_cN>n>@l*uLHKfV2f$2TPk5x2-glnk3^i(vyTCIoFYp0L(4et@0-hRf zN@<2H761p7pIp^lBQtSxsU^t%i@~lpnS#D&;y|N^GaqFMMIkO*YVlqJznIW`Eo7ji zIbItE$P3*zg;21L$4U#A^@!p#K6Y#(lrdGOGxNFSq zF58fo%dDqju?D+T9D$DpMbiOo0DAK^MehkVtQm@~DuPnJ63`eW zi-xHUWIMF5HThje3Ql_Q04>|1`38s2hoFtM5MwigaJ+RT9S3!ml?O}j$L-l}Gq8Jrr8K+$p-)Ro3tsf6IA`pkWryk@w zNm1lZgS~dh%t*ic3`)3+I932taI_JxgU3+eo<_eYfrgBEna%133z8Bb^aCQ10xJQI z_CV%_Jllvrf`uv6BymA)X391~OoTLfB*rbPe4Uk22BrS3@9p!iqyAA)c!X8~tynKS zOQ&G;Qgl$ASeN>yz%-UujlEDT2p0&|?+w>5?lm6KDHf?Cj8o1;D2A@;TUHOvl|+() z=jQP@32A0B^tbn;x9;p2gFyah>@A~W^?BC&V*O;%huR;KSxgqt=Q%dq&&GrWnl zydR)yoZUi5o2Ks#E2c$(IglR^c1v%o$-e9#LTXIN1}~b$uo-y#^ zLAi?0OYpWfjKWWv@#G}9bYV*j9;?9IW_cjmhThXLMs|h@;KM2MY{~jlcri`ii0U&RKEv08rhYhLrvk({?!BlI-hVa-sE-za7)`ltysZ7qS`oU&>s^@(zYwPP4+&@R2zN^ukSx(s> zowyGhIR*!#7n>2T&R`vQngN~i9dw&^r_|qSs>RJjGr;RDeo?l11;kS2C2XF-Go!4b z%GkZV=hejnwi=w5pQNj!`N`#Ibai^}&Ve~idqO>EmOt8(;_ZEmy=}hO2%&~k`>^KC zbrGy1ub~L#UJxxq6JQ`8raizcwzoQnRyv|Xj38flN0mp>^-O0o!sKdfqOG@*6;2l; zp%fscwF>uylFh@Zcq7m(3zjy6;<5ny(utxtkOwhO z`)}y9DQ0QrZ_zJSK6*Q0$RL@-|Dd^4rt7xi-jvv$;Ce?OMf4a#{6r~lwvTlo_g^op z%?I$%NQ+-9dAlw{?Uc(I)x$|0PhFHco z-sL2VMX@c$kQ7!G^c-8M?_;qen^cU9173ap{IMgJm^A`HVisn zz)GbGaiZf=3;@UT2Gvid@^nB}O?~ogdhKE8bqR~J?udU+FX5HLJ^v(+mtc0m6B?aS z&0@dj1@vH-xK9P;p?@-R*?OTUY4-J)C)igJ`sAzVi0eewao{T!9kQu^XvqAofyBe; zt)1`&eKT~tiK*ERcQsx2x~MNbl>rv_dX0(hRUfK?Cl+AOt!8ThGy@Bn)V%AztTZ{H3Yzm(e#5-5 z?+-8@x3;FJuLW#kEv>fH5P-O;ha(zXMgir-?QR(Y*~;{XEmRv^+F%C!tbz=hP!#7q zlT_q=1|7~Lp3_SGzz8sbPd<)r%$73e>5bEv6Oq8&c=xzrp4yO;v)k6jA{|?JmhD~{ z8d>NKErs3%E_D>D$Sfc9*iI8`;u(+BO3k!z5kg2!%?!#f&F!gL<}@L5%<_!3o~;~G z?-r2}Yit!*ABm3Kcp5yM?ehkmYzkT9^%5Jl(<_PFbK7l}Jl|`m_=o1(0&aj(%u9_q z6^gaWm&x6R-T@2NrpO1GXXr&2=JN_@i%s*mb|j)IF=4iLTCY7Go=Up#8U-JB8zLM$pOczzR>= z3v4X>tE9Qb__r=22`YYIfOqTbo&`mv2GOh_HSkw$dwNvXM1%O{A#&Q>xNCY^xl&*p zT9}Wy*Ir*(PFQC5s4BevPX5_i3k`XDKMbOWa4T4aRpb@cyO)tn^{{|CQHSnz#&+%R znXD=nusc~EA)=W`R5t1ZGPBQ{ey;3zfFZlajRnB?1)2sYxI+HfP!ga$jJz#iUI7hE zxm)ep%S^p7JPday8=46m2{Cp+>4dQvoGvdx&w{Twe8M6+YlzfBd!ZjsehdthZ0kBG zb>>g;zS@>6&`z)1`U#!3G9{9b^xy`Ete6%9BH1fnUISdtYKaMLjUvPN7T!YzB5(B| z5TW70qCe<2>~rn`!y&>70>G~@C76lULn){^+i=U>ew~iKfPm1pBdu$(axLw4fpyhP z(Wu_ArF!Wkhe+2i7kMD!^7Col6BhegPlQ)a<8W@@#dN4i{JJycC4YYlo zO;A}OqfPjompfAPlCGayotH`?$E&fmh?tmf$QmQQDi&1R863D_Wixp%=pP159ULt3 z3wHNo3!5~qWD$F%)~2eF03l*BhA^ljL{Y_=AjLS#+aO)ljaMa+OSsi+M8s9D%(2#r z&S11!FeR0gibR*`a>OAuD2O2@QVLoOe>YD-Uuqs$03t0$@5P=9^kO5^w5(bDC}7}Y zcgDz&3%vmCJ0b*$0YVkH>H444fw0Ddjs@mSj+wa;N{r~j(1$ZWvcQ*_7>utT^~JOOPKqXh%gWXkXmPqv_O&xO_VE>|{c_1Yzz$B_NcqqshZ7?bQwGXQFF zOSn)tlEPzf-fA?wePaZt-cYot0h2*N?%Oc;e7S!81r?21M;Rv&Rkp1*le=paDce6+ zjx|j%B*pwfh2}6vF<|$OIjkZejZz&IA~rhGDDzxBe_MmZq|5mRtQ`DBb^x zs1lAd3XSs!l$nAyrQRfB>HCQCs96l|dmZeuCaPC5PeH-*hs5n{Qf0&>6qwx{FA*fD zV9Bi(^1P0t5d5vpt7x3y^n{oyhr%XrmNUHbGEe$MHu76G7@MB7>^cY1pItHE{L!UmrCEo%OC(L~?x(YkqU z{a$N)1Brzk^(IcxVY`FF8}hB+R0fvEgZ*kZj|2oJb*~}I9^pvwZG)7yW~cY=#()a1 z?dl_zWg_G*-0KdVM0(|xV+_$8lpTgAfOAIH(woGXTJO0F3J|^9&|U(o*iah6P{bfi zG_|p8@DEj%wwh{6hS^GCBN!(S&{V&-+`MhHtMbwA){cHb9HzuaP0I-nvFLJ%svPzQ`11xplvnT<}w>&&jFjJ z8!I#$w1G)%0&Evtdwh&d%Xa)(bZe*qD2Tow5e+JYqQ<@%4iI_Y?aY% z&_{4j#4K99-n2=Jh|$4zK`XL@MFN`M2pH-%hg+X3cAVoO*w3pd?+)zrtGR&zEvBg@ z8X=Q4);*`u0ZiHi>HrKWOdD%SqeWJTXZBt=KY~4T%p#k*lH40rLOpDYQw)IB7%O0^ zkv*K@qA;=Uq&%Qdm}YVBxM56|3QtGRYnIv>VqNpZpW`-XKZrIiOPmp05z2cQ3KEIb zTHu5(Fn~m^Euhsx$mMaLmxtfxa~`KUhNE44q8+hL z3$fxji4aGz8GuTgd+ggFbwU+2S6hLY5{?_XL|~HwZJ@14ei0Yy5SwA_Cdf@cGsjo! zaBAQpEUsn+M=&N}Gp6-O6YaPr5ym>eO$fMJ+&Y59qhnwe>q%OoHUW91GXy-^5QRl= z&5N9N|6MSHx3ukSAmEM3>@)9EyqX4;DpI%w!Ca*T!4PPBbaFW-2*$_22u!;>@-=E+ z>=)*&NQ>jSyCD7CFu(RCmgUv~`C{6om2}X>RymQ{$V^>a0Npk4Sd0(RHW{11zGomP z*0R9cIKCc?rA~LnUwZzOypNts?f_k{ZNo@KVxX5Q}zz2%>tY+01sg8J-!#7H=;XoS) z8I%A*`2DjscN1aqL4k@|gyDS?WbZx4lyF z2_9!RY#b4(06Hr|RB!&e$Xpan1B>-R*um}AU%Vk+Tb!I|v__A3EW{AZQlYE@jm#Gv zctbc?@h1;l}Ec8T^D`!hE zy#0PpY0Fiuvyj8yXEH=j_O2L^75f&)Z5?)4k{>ZQoRIQafsATphJ_bByg^SepL6i? zYjC#ow^rzGaIdI-u~e}%uyJe~jNg(#MXg%(L?H-r0x+Y1Iy#P*-l*S|f`>55Ow`d< zEKBD;89hGd{L=G>kB$M$y2gdVru-%q6J0*`$@e3I&Rg5~0zIF9($zMMR^);AV{#W0 z3Zu2bhv-+gp2#{HM}H7njXT9FObtVXlI5_D%)@(*iFJFuxR%GMs~5|I!ofx}PR+6H zUxK|15|gLe9LWHAra%!7q6ZGp!>v846}lzqce}}CwMx=4w5F|fUBMW*FGq?7 zg5MQkvA8jR6^$sQ-fSAiQ@kwz03F9Tt@nGU)XS_0r;tqXdq|wKd96`m} zH0AeYaDJp0OU%JNfB1G7{;Qth(|UG;?IV23(`vNs+Ua3gbS9^DKEf>Gz#2j>N!wGi z;(j`me)d67i8eoXHmhnW{pe=v1Nq!uB7Rsnh8f{0VM}Z24YMh+Re!kp2M1x#+gXfT z>yKeXX1$}tA7h|5c4^tryByTz7A z9gOZSA6dU;{awy5+B>%sdzL#P(3bs&YD83b?)BJpWLO<{P?WEc0m|VZkF#feQB^q% zXJy;IEa*c}468*>qf$6;6;ADt1?;y*4)2kzrNE}b`m<2ohN&HyJl2X?HbF5jw*0cq zhI#Wh7#Eb9Y8Q60h0YQe7q*->%8G~wKTm$O*+j`x!$Jh83a39a2LyxD+8)F$#srbH zq4XAM+8H=|m4$eMH+9`-nEbLXS&ebH8K3A;;$5wmv<0H<{2?>M6taN}%xiewdn(j% zqt&+PBl`=d%}1*>M50&`YheK8#eoW=_3Sv;4I~Y_7#L4wE>;^(5Rd~E~clobT$%-+CW3RW2+b8 z?xXjuI|1j09DUSN%hKIv9e~EvpzU@t@roCXDvNBRc+zkujKV9}7!;g&ug-pMmGclf z1kv-mki*8>u0?K+1Y=NIgm?}4VU|J>Jso4a^^CtyUGC_G_{IGXs|1_I?+{)uiR(sG zML%$4CT7|Pam5DOGe7Rn5VD*&2zQ6L?Qrh6?NW^kKkTuu1wj$hi~KU(ULLl|l08mO->v>AN3LK~B-a=b%wSoF9pSC=SDM34SL_Ph-KO3&o@pzSA#T4}813=?l+m=NQ z{y|O|>fIJ58}Bg?@zRbHj)|}}R=-*Ip?^O|L4MMTU%a+Ie!hv6GQwZH{PU!B{YB+} z#P3k?Lw&#VH6{FCEcX{k#&W;&3;f>VFMO1IML&8P{$e?1*vi>^^}AyFVdR~7m*0*H zv~yB~ci`R*5zf2SYS3V*TOH%aU1P{UUr{OlK#ACQiJ{H&Dyo${$NdhZVs z{oeN%lN7OYHI(yZY2VM&f;-CnqfUMN zs^M3Yzt}JLRqpHWpYfkNOH1fu_{HSwO`>hn_sP>ccf-A}Q|?c1l+*p+R+dBU1M!7%pum41H@moec_Ja7t|JW$^%eOz7{D;3} zMeHNC;14#+J^QtvOul{6mW%cMF)re@?*0RQjPl=q8fT%s_tT+V9GCBY`=^p$`%3$y zuJr%sLpjx@zdyS8a`H_PNBE01Yssj5tnb->`*QMsL}cMl_u~I{6q4kdzx(CnxBqjJ zX#M})pYZhZC9b*jYn*TWed+r@o&12`R*QeCOMicg|DD$)zy0TaCi$!JCimjy{|AEj BH68!} literal 0 HcmV?d00001 diff --git a/rpi_pico_rosserial_test/include/README b/rpi_pico_rosserial_test/include/README new file mode 100644 index 0000000..45496b1 --- /dev/null +++ b/rpi_pico_rosserial_test/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/rpi_pico_rosserial_test/lib/README b/rpi_pico_rosserial_test/lib/README new file mode 100644 index 0000000..8c9c29c --- /dev/null +++ b/rpi_pico_rosserial_test/lib/README @@ -0,0 +1,46 @@ + +This directory is intended for project specific (private) libraries. +PlatformIO will compile them to static libraries and link into executable file. + +The source code of each library should be placed in a an own separate directory +("lib/your_library_name/[here are source files]"). + +For example, see a structure of the following two libraries `Foo` and `Bar`: + +|--lib +| | +| |--Bar +| | |--docs +| | |--examples +| | |--src +| | |- Bar.c +| | |- Bar.h +| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html +| | +| |--Foo +| | |- Foo.c +| | |- Foo.h +| | +| |- README --> THIS FILE +| +|- platformio.ini +|--src + |- main.c + +and a contents of `src/main.c`: +``` +#include +#include + +int main (void) +{ + ... +} + +``` + +PlatformIO Library Dependency Finder will find automatically dependent +libraries scanning project source files. + +More information about PlatformIO Library Dependency Finder +- https://docs.platformio.org/page/librarymanager/ldf.html diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/LICENSE b/rpi_pico_rosserial_test/lib/XL320-bene/LICENSE new file mode 100644 index 0000000..c0f8284 --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/LICENSE @@ -0,0 +1,340 @@ +GNU GENERAL PUBLIC LICENSE + Version 2, June 1991 + + Copyright (C) 1989, 1991 Free Software Foundation, Inc., + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +License is intended to guarantee your freedom to share and change free +software--to make sure the software is free for all its users. This +General Public License applies to most of the Free Software +Foundation's software and to any other program whose authors commit to +using it. (Some other Free Software Foundation software is covered by +the GNU Lesser General Public License instead.) You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +this service if you wish), that you receive source code or can get it +if you want it, that you can change the software or use pieces of it +in new free programs; and that you know you can do these things. + + To protect your rights, we need to make restrictions that forbid +anyone to deny you these rights or to ask you to surrender the rights. +These restrictions translate to certain responsibilities for you if you +distribute copies of the software, or if you modify it. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must give the recipients all the rights that +you have. You must make sure that they, too, receive or can get the +source code. And you must show them these terms so they know their +rights. + + We protect your rights with two steps: (1) copyright the software, and +(2) offer you this license which gives you legal permission to copy, +distribute and/or modify the software. + + Also, for each author's protection and ours, we want to make certain +that everyone understands that there is no warranty for this free +software. If the software is modified by someone else and passed on, we +want its recipients to know that what they have is not the original, so +that any problems introduced by others will not reflect on the original +authors' reputations. + + Finally, any free program is threatened constantly by software +patents. We wish to avoid the danger that redistributors of a free +program will individually obtain patent licenses, in effect making the +program proprietary. To prevent this, we have made it clear that any +patent must be licensed for everyone's free use or not licensed at all. + + The precise terms and conditions for copying, distribution and +modification follow. + + GNU GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License applies to any program or other work which contains +a notice placed by the copyright holder saying it may be distributed +under the terms of this General Public License. The "Program", below, +refers to any such program or work, and a "work based on the Program" +means either the Program or any derivative work under copyright law: +that is to say, a work containing the Program or a portion of it, +either verbatim or with modifications and/or translated into another +language. (Hereinafter, translation is included without limitation in +the term "modification".) Each licensee is addressed as "you". + +Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running the Program is not restricted, and the output from the Program +is covered only if its contents constitute a work based on the +Program (independent of having been made by running the Program). +Whether that is true depends on what the Program does. + + 1. You may copy and distribute verbatim copies of the Program's +source code as you receive it, in any medium, provided that you +conspicuously and appropriately publish on each copy an appropriate +copyright notice and disclaimer of warranty; keep intact all the +notices that refer to this License and to the absence of any warranty; +and give any other recipients of the Program a copy of this License +along with the Program. + +You may charge a fee for the physical act of transferring a copy, and +you may at your option offer warranty protection in exchange for a fee. + + 2. You may modify your copy or copies of the Program or any portion +of it, thus forming a work based on the Program, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) You must cause the modified files to carry prominent notices + stating that you changed the files and the date of any change. + + b) You must cause any work that you distribute or publish, that in + whole or in part contains or is derived from the Program or any + part thereof, to be licensed as a whole at no charge to all third + parties under the terms of this License. + + c) If the modified program normally reads commands interactively + when run, you must cause it, when started running for such + interactive use in the most ordinary way, to print or display an + announcement including an appropriate copyright notice and a + notice that there is no warranty (or else, saying that you provide + a warranty) and that users may redistribute the program under + these conditions, and telling the user how to view a copy of this + License. (Exception: if the Program itself is interactive but + does not normally print such an announcement, your work based on + the Program is not required to print an announcement.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Program, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Program, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Program. + +In addition, mere aggregation of another work not based on the Program +with the Program (or with a work based on the Program) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may copy and distribute the Program (or a work based on it, +under Section 2) in object code or executable form under the terms of +Sections 1 and 2 above provided that you also do one of the following: + + a) Accompany it with the complete corresponding machine-readable + source code, which must be distributed under the terms of Sections + 1 and 2 above on a medium customarily used for software interchange; or, + + b) Accompany it with a written offer, valid for at least three + years, to give any third party, for a charge no more than your + cost of physically performing source distribution, a complete + machine-readable copy of the corresponding source code, to be + distributed under the terms of Sections 1 and 2 above on a medium + customarily used for software interchange; or, + + c) Accompany it with the information you received as to the offer + to distribute corresponding source code. (This alternative is + allowed only for noncommercial distribution and only if you + received the program in object code or executable form with such + an offer, in accord with Subsection b above.) + +The source code for a work means the preferred form of the work for +making modifications to it. For an executable work, complete source +code means all the source code for all modules it contains, plus any +associated interface definition files, plus the scripts used to +control compilation and installation of the executable. However, as a +special exception, the source code distributed need not include +anything that is normally distributed (in either source or binary +form) with the major components (compiler, kernel, and so on) of the +operating system on which the executable runs, unless that component +itself accompanies the executable. + +If distribution of executable or object code is made by offering +access to copy from a designated place, then offering equivalent +access to copy the source code from the same place counts as +distribution of the source code, even though third parties are not +compelled to copy the source along with the object code. + + 4. You may not copy, modify, sublicense, or distribute the Program +except as expressly provided under this License. Any attempt +otherwise to copy, modify, sublicense or distribute the Program is +void, and will automatically terminate your rights under this License. +However, parties who have received copies, or rights, from you under +this License will not have their licenses terminated so long as such +parties remain in full compliance. + + 5. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Program or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Program (or any work based on the +Program), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Program or works based on it. + + 6. Each time you redistribute the Program (or any work based on the +Program), the recipient automatically receives a license from the +original licensor to copy, distribute or modify the Program subject to +these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties to +this License. + + 7. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Program at all. For example, if a patent +license would not permit royalty-free redistribution of the Program by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Program. + +If any portion of this section is held invalid or unenforceable under +any particular circumstance, the balance of the section is intended to +apply and the section as a whole is intended to apply in other +circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system, which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 8. If the distribution and/or use of the Program is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Program under this License +may add an explicit geographical distribution limitation excluding +those countries, so that distribution is permitted only in or among +countries not thus excluded. In such case, this License incorporates +the limitation as if written in the body of this License. + + 9. The Free Software Foundation may publish revised and/or new versions +of the General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + +Each version is given a distinguishing version number. If the Program +specifies a version number of this License which applies to it and "any +later version", you have the option of following the terms and conditions +either of that version or of any later version published by the Free +Software Foundation. If the Program does not specify a version number of +this License, you may choose any version ever published by the Free Software +Foundation. + + 10. If you wish to incorporate parts of the Program into other free +programs whose distribution conditions are different, write to the author +to ask for permission. For software which is copyrighted by the Free +Software Foundation, write to the Free Software Foundation; we sometimes +make exceptions for this. Our decision will be guided by the two goals +of preserving the free status of all derivatives of our free software and +of promoting the sharing and reuse of software generally. + + NO WARRANTY + + 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY +FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN +OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES +PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED +OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF +MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS +TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE +PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, +REPAIR OR CORRECTION. + + 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR +REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, +INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING +OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED +TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY +YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER +PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE +POSSIBILITY OF SUCH DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + {description} + Copyright (C) {year} {fullname} + + This program is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License along + with this program; if not, write to the Free Software Foundation, Inc., + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. + +Also add information on how to contact you by electronic and paper mail. + +If the program is interactive, make it output a short notice like this +when it starts in an interactive mode: + + Gnomovision version 69, Copyright (C) year name of author + Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, the commands you use may +be called something other than `show w' and `show c'; they could even be +mouse-clicks or menu items--whatever suits your program. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the program, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the program + `Gnomovision' (which makes passes at compilers) written by James Hacker. + + {signature of Ty Coon}, 1 April 1989 + Ty Coon, President of Vice + +This General Public License does not permit incorporating your program into +proprietary programs. If your program is a subroutine library, you may +consider it more useful to permit linking proprietary applications with the +library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. + diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/README.md b/rpi_pico_rosserial_test/lib/XL320-bene/README.md new file mode 100644 index 0000000..033ee0c --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/README.md @@ -0,0 +1,42 @@ +Dynamixel XL-320 +================ + +Dynamixel XL-320 servo library for Adruino + +## A Servo library for Arduino + +Clone this repository into your Arduino libraries folder: + +``` $ cd ~/Documents/Arduino/libraries/ ``` + +Restart Arduino app. :-) + +Open the example Arduino sketch to see how it works: + +``` File > Examples > XL320 > XL320_servo_example ``` + +### Hardware + +[DYNAMIXEL XL-320 servo manual](http://support.robotis.com/en/product/dynamixel/xl-320/xl-320.htm) including specifications and message sending addresses. + +### Wiring diagram + +Looking from above, with the servo head at the top, wire the left plug of the servo to: + +* PIN1: GND +* PIN2: 5 volts +* PIN3: Serial TX + +![Dynamixel XL-320 wiring diagram](http://hackerspace-adelaide.org.au/w/images/f/f0/XL320-wiring.png) + +### Setting the servo serial baud rate & servoID + +We've included some example sketches to help test and setup your servos. Out of the box they're set to communicate via serial at 1Mbps, so you might want to set them down to something more managable by Arduino at 115200. + +Follow the instructions in the sketch ```XL320_servo_set_baud_rate_or_id.ino``` and don't forget to power cycle the servos in between setting anything. + +Note: when setting the ServoID, the servos default down to 9600 baud, so after you set the servoID you'll need to set the baud rate back up to 115200. + +### More information + +Read more about this library on the [Hackerspace Adelaide Wiki](http://hackerspace-adelaide.org.au/wiki/Dynamixel_XL-320) \ No newline at end of file diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/XL320.cpp b/rpi_pico_rosserial_test/lib/XL320-bene/XL320.cpp new file mode 100644 index 0000000..4048bc4 --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/XL320.cpp @@ -0,0 +1,567 @@ +/* + + Code based on: + Dynamixel.cpp - Ax-12+ Half Duplex USART Comunication + Copyright (c) 2011 Savage Electronics. + And Dynamixel Pro library for OpenCM-9.04 made by ROBOTIS, LTD. + + Modified to work only with Dynamixel XL-320 actuator. + + Modifications made by Luis G III for XL320 robot. + Webpage: http://hellospoonrobot.com + Twitter: @XL320 + Youtube: http://youtube.com/user/hellospoonrobot + + This file can be used and be modified by anyone, + don't forget to say thank you to OP! + + */ + +#include "Arduino.h" +#include "dxl_pro.h" +#include "XL320.h" +#include +#include + +// Macro for the selection of the Serial Port +#define sendData(args) (this->stream->write(args)) // Write Over Serial +#define beginCom(args) // Begin Serial Comunication +#define readData() (this->stream->read()) + +// Select the Switch to TX/RX Mode Pin +#define setDPin(DirPin, Mode) +#define switchCom(DirPin, Mode) // Switch to TX/RX Mode + +#define NANO_TIME_DELAY 12000 + +XL320::XL320() +{ +} + +XL320::~XL320() +{ +} + +void XL320::begin(Stream &stream) +{ + // setDPin(Direction_Pin=4,OUTPUT); + // beginCom(1000000); + this->stream = &stream; +} + +void XL320::moveJoint(int id, int value) +{ + int Address = XL_GOAL_POSITION_L; + + sendPacket(id, Address, value); + this->stream->flush(); + + nDelay(NANO_TIME_DELAY); +} + +void XL320::setJointSpeed(int id, int value) +{ + int Address = XL_GOAL_SPEED_L; + sendPacket(id, Address, value); + this->stream->flush(); + + nDelay(NANO_TIME_DELAY); +} + +void XL320::LED(int id, char led_color[]) +{ + int Address = XL_LED; + int val = 0; + + if (led_color[0] == 'r') + { + val = 1; + } + + else if (led_color[0] == 'g') + { + val = 2; + } + + else if (led_color[0] == 'y') + { + val = 3; + } + + else if (led_color[0] == 'b') + { + val = 4; + } + + else if (led_color[0] == 'p') + { + val = 5; + } + + else if (led_color[0] == 'c') + { + val = 6; + } + + else if (led_color[0] == 'w') + { + val = 7; + } + + else if (led_color[0] == 'o') + { + val = 0; + } + + sendPacket(id, Address, val); + this->stream->flush(); + + nDelay(NANO_TIME_DELAY); +} + +void XL320::setJointTorque(int id, int value) +{ + int Address = XL_GOAL_TORQUE; + sendPacket(id, Address, value); + this->stream->flush(); + nDelay(NANO_TIME_DELAY); +} + +void XL320::TorqueON(int id) +{ + + int Address = XL_TORQUE_ENABLE; + int value = 1; + + sendPacket(id, Address, value); + this->stream->flush(); + nDelay(NANO_TIME_DELAY); +} + +void XL320::TorqueOFF(int id) +{ + + int Address = XL_TORQUE_ENABLE; + int value = 0; + + sendPacket(id, Address, value); + this->stream->flush(); + nDelay(NANO_TIME_DELAY); +} + +void XL320::quickTest() +{ + + int position_tmp = 0; + + for (int id = 1; id < 6; id++) + { + sendPacket(id, XL_LED, random(1, 7)); + nDelay(NANO_TIME_DELAY); + this->stream->flush(); + sendPacket(id, XL_GOAL_SPEED_L, 200); + nDelay(NANO_TIME_DELAY); + this->stream->flush(); + } + + for (int id = 1; id < 6; id++) + { + + position_tmp = random(0, 512); + + if (id != 3) + { + sendPacket(id, XL_GOAL_POSITION_L, position_tmp); + delay(1000); + this->stream->flush(); + } + + else + { + sendPacket(3, XL_GOAL_POSITION_L, 512 - position_tmp); + delay(1000); + this->stream->flush(); + } + } + + for (int id = 1; id < 6; id++) + { + sendPacket(id, XL_LED, 2); + nDelay(NANO_TIME_DELAY); + this->stream->flush(); + sendPacket(id, XL_GOAL_SPEED_L, 1023); + nDelay(NANO_TIME_DELAY); + this->stream->flush(); + } + + for (int id = 1; id < 6; id++) + { + sendPacket(id, XL_LED, 0); + nDelay(NANO_TIME_DELAY); + this->stream->flush(); + } +} + +int XL320::getSpoonLoad() +{ + int spoon = RXsendPacket(5, XL_PRESENT_LOAD); + this->stream->flush(); + return spoon; +} + +int XL320::getJointPosition(int id) +{ + return getJointPosition(id, NULL); +} + +int XL320::getJointPosition(int id, Stream *debugStream) +{ + unsigned char buffer[255]; + RXsendPacket(id, XL_PRESENT_POSITION, 2); + this->stream->flush(); + if (this->readPacket(buffer, 255) > 0) + { + Packet p(buffer, 255); + if (debugStream) + p.toStream(*debugStream); + if (p.isValid() && p.getParameterCount() >= 3) + { + return (p.getParameter(1)) | (p.getParameter(2) << 8); + } + else + { + return -1; + } + } + return -2; +} + +int XL320::getJointSpeed(int id) +{ + int speed = RXsendPacket(id, XL_PRESENT_SPEED); + this->stream->flush(); + nDelay(NANO_TIME_DELAY); + return speed; +} + +int XL320::getJointLoad(int id) +{ + int load = RXsendPacket(id, XL_PRESENT_LOAD); + this->stream->flush(); + nDelay(NANO_TIME_DELAY); + return load; +} + +int XL320::getJointTemperature(int id) +{ + int temp = RXsendPacket(id, XL_PRESENT_TEMPERATURE); + this->stream->flush(); + nDelay(NANO_TIME_DELAY); + return temp; +} + +int XL320::isJointMoving(int id) +{ + int motion = RXsendPacket(id, XL_MOVING); + this->stream->flush(); + nDelay(NANO_TIME_DELAY); + return motion; +} + +int XL320::sendPacket(int id, int Address, int value) +{ + + /*Dynamixel 2.0 communication protocol + used by Dynamixel XL-320 and Dynamixel PRO only. + */ + + // technically i think we need 14bytes for this packet + + const int bufsize = 16; + + byte txbuffer[bufsize]; + + Packet p(txbuffer, bufsize, id, 0x03, 4, + DXL_LOBYTE(Address), + DXL_HIBYTE(Address), + DXL_LOBYTE(value), + DXL_HIBYTE(value)); + + int size = p.getSize(); + stream->write(txbuffer, size); + + // stream->write(txbuffer,bufsize); + + return bufsize; +} + +void XL320::nDelay(uint32_t nTime) +{ + /* + uint32_t max; + for( max=0; max < nTime; max++){ + + } + */ +} + +int XL320::flush() +{ + this->stream->flush(); + return 0; +} + +int XL320::RXsendPacket(int id, int Address) +{ + return this->RXsendPacket(id, Address, 2); +} + +int XL320::RXsendPacket(int id, int Address, int size) +{ + + /*Dynamixel 2.0 communication protocol + used by Dynamixel XL-320 and Dynamixel PRO only. + */ + + const int bufsize = 16; + + byte txbuffer[bufsize]; + + Packet p(txbuffer, bufsize, id, 0x02, 4, + DXL_LOBYTE(Address), + DXL_HIBYTE(Address), + DXL_LOBYTE(size), + DXL_HIBYTE(size)); + + stream->write(txbuffer, p.getSize()); + + // stream->write(txbuffer,bufsize); + + return p.getSize(); +} + +// from http://stackoverflow.com/a/133363/195061 + +#define FSM +#define STATE(x) \ + s_##x : if (!stream->readBytes(&BUFFER[I++], 1)) goto sx_timeout; \ + if (I >= SIZE) \ + goto sx_overflow; \ + sn_##x: +#define THISBYTE (BUFFER[I - 1]) +#define NEXTSTATE(x) goto s_##x +#define NEXTSTATE_NR(x) goto sn_##x +#define OVERFLOW \ + sx_overflow: +#define TIMEOUT \ + sx_timeout: + +int XL320::readPacket(unsigned char *BUFFER, size_t SIZE) +{ + int C; + int I = 0; + + int length = 0; + + // state names normally name the last parsed symbol + + FSM + { + STATE(start) + { + if (THISBYTE == 0xFF) + NEXTSTATE(header_ff_1); + I = 0; + NEXTSTATE(start); + } + STATE(header_ff_1) + { + if (THISBYTE == 0xFF) + NEXTSTATE(header_ff_2); + I = 0; + NEXTSTATE(start); + } + STATE(header_ff_2) + { + if (THISBYTE == 0xFD) + NEXTSTATE(header_fd); + // yet more 0xFF's? stay in this state + if (THISBYTE == 0xFF) + NEXTSTATE(header_ff_2); + // anything else? restart + I = 0; + NEXTSTATE(start); + } + STATE(header_fd) + { + // reading reserved, could be anything in theory, normally 0 + } + STATE(header_reserved) + { + // id = THISBYTE + } + STATE(id) + { + length = THISBYTE; + } + STATE(length_1) + { + length += THISBYTE << 8; // eg: length=4 + } + STATE(length_2) + { + } + STATE(instr) + { + // instr = THISBYTE + // check length because + // action and reboot commands have no parameters + if (I - length >= 5) + NEXTSTATE(checksum_1); + } + STATE(params) + { + // check length and maybe skip to checksum + if (I - length >= 5) + NEXTSTATE(checksum_1); + // or keep reading params + NEXTSTATE(params); + } + STATE(checksum_1) + { + } + STATE(checksum_2) + { + // done + return I; + } + OVERFLOW + { + return -1; + } + TIMEOUT + { + return -2; + } + } +} + +XL320::Packet::Packet( + unsigned char *data, + size_t data_size, + unsigned char id, + unsigned char instruction, + int parameter_data_size, + ...) +{ + + // [ff][ff][fd][00][id][len1][len2] { [instr][params(parameter_data_size)][crc1][crc2] } + unsigned int length = 3 + parameter_data_size; + if (!data) + { + // [ff][ff][fd][00][id][len1][len2] { [data(length)] } + this->data_size = 7 + length; + this->data = (unsigned char *)malloc(data_size); + this->freeData = true; + } + else + { + this->data = data; + this->data_size = data_size; + this->freeData = false; + } + this->data[0] = 0xFF; + this->data[1] = 0xFF; + this->data[2] = 0xFD; + this->data[3] = 0x00; + this->data[4] = id; + this->data[5] = length & 0xff; + this->data[6] = (length >> 8) & 0xff; + this->data[7] = instruction; + va_list args; + va_start(args, parameter_data_size); + for (int i = 0; i < parameter_data_size; i++) + { + unsigned char arg = va_arg(args, int); + this->data[8 + i] = arg; + } + unsigned short crc = update_crc(0, this->data, this->getSize() - 2); + this->data[8 + parameter_data_size] = crc & 0xff; + this->data[9 + parameter_data_size] = (crc >> 8) & 0xff; + va_end(args); +} + +XL320::Packet::Packet(unsigned char *data, size_t size) +{ + this->data = data; + this->data_size = size; + this->freeData = false; +} + +XL320::Packet::~Packet() +{ + if (this->freeData == true) + { + free(this->data); + } +} + +void XL320::Packet::toStream(Stream &stream) +{ + stream.print("id: "); + stream.println(this->getId(), DEC); + stream.print("length: "); + stream.println(this->getLength(), DEC); + stream.print("instruction: "); + stream.println(this->getInstruction(), HEX); + stream.print("parameter count: "); + stream.println(this->getParameterCount(), DEC); + for (int i = 0; i < this->getParameterCount(); i++) + { + stream.print(this->getParameter(i), HEX); + if (i < this->getParameterCount() - 1) + { + stream.print(","); + } + } + stream.println(); + stream.print("valid: "); + stream.println(this->isValid() ? "yes" : "no"); +} + +unsigned char XL320::Packet::getId() +{ + return data[4]; +} + +int XL320::Packet::getLength() +{ + return data[5] + ((data[6] & 0xff) << 8); +} + +int XL320::Packet::getSize() +{ + return getLength() + 7; +} + +int XL320::Packet::getParameterCount() +{ + return getLength() - 3; +} + +unsigned char XL320::Packet::getInstruction() +{ + return data[7]; +} + +unsigned char XL320::Packet::getParameter(int n) +{ + return data[8 + n]; +} + +bool XL320::Packet::isValid() +{ + int length = getLength(); + unsigned short storedChecksum = data[length + 5] + (data[length + 6] << 8); + return storedChecksum == update_crc(0, data, length + 5); +} diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/XL320.h b/rpi_pico_rosserial_test/lib/XL320-bene/XL320.h new file mode 100644 index 0000000..a053fc7 --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/XL320.h @@ -0,0 +1,140 @@ +/* + Code based on: + Dynamixel.cpp - Ax-12+ Half Duplex USART Comunication + Copyright (c) 2011 Savage Electronics. + And Dynamixel Pro library for OpenCM-9.04 made by ROBOTIS, LTD. + + Modified to work only with Dynamixel XL-320 actuator. + + Modifications made by Luis G III for HelloSpoon robot. + Webpage: http://hellospoonrobot.com + Twitter: @HelloSpoon + Youtube: http://youtube.com/user/hellospoonrobot + + This file can be used and be modified by anyone, + don't forget to say thank you to OP! + + */ + +#ifndef XL320_H_ +#define XL320_H_ + +/*EEPROM Area*/ +#define XL_MODEL_NUMBER_L 0 +#define XL_MODEL_NUMBER_H 1 +#define XL_VERSION 2 +#define XL_ID 3 +#define XL_BAUD_RATE 4 +#define XL_RETURN_DELAY_TIME 5 +#define XL_CW_ANGLE_LIMIT_L 6 +#define XL_CW_ANGLE_LIMIT_H 7 +#define XL_CCW_ANGLE_LIMIT_L 8 +#define XL_CCW_ANGLE_LIMIT_H 9 +#define XL_CONTROL_MODE 11 +#define XL_LIMIT_TEMPERATURE 12 +#define XL_DOWN_LIMIT_VOLTAGE 13 +#define XL_UP_LIMIT_VOLTAGE 14 +#define XL_MAX_TORQUE_L 15 +#define XL_MAX_TORQUE_H 16 +#define XL_RETURN_LEVEL 17 +#define XL_ALARM_SHUTDOWN 18 +/*RAM Area*/ +#define XL_TORQUE_ENABLE 24 +#define XL_LED 25 +#define XL_D_GAIN 27 +#define XL_I_GAIN 28 +#define XL_P_GAIN 29 +#define XL_GOAL_POSITION_L 30 +#define XL_GOAL_SPEED_L 32 +#define XL_GOAL_TORQUE 35 +#define XL_PRESENT_POSITION 37 +#define XL_PRESENT_SPEED 39 +#define XL_PRESENT_LOAD 41 +#define XL_PRESENT_VOLTAGE 45 +#define XL_PRESENT_TEMPERATURE 46 +#define XL_REGISTERED_INSTRUCTION 47 +#define XL_MOVING 49 +#define XL_HARDWARE_ERROR 50 +#define XL_PUNCH 51 + +#define Tx_MODE 1 +#define Rx_MODE 0 + +#include +#include + +class XL320 +{ +private: + unsigned char Direction_Pin; + volatile char gbpParamEx[130 + 10]; + Stream *stream; + + void nDelay(uint32_t nTime); + +public: + XL320(); + virtual ~XL320(); + + void begin(Stream &stream); + + void moveJoint(int id, int value); + void setJointSpeed(int id, int value); + void LED(int id, char led_color[]); + void setJointTorque(int id, int value); + + void TorqueON(int id); + void TorqueOFF(int id); + + void quickTest(); + + int getSpoonLoad(); + int getJointPosition(int id); + int getJointPosition(int id, Stream *debugStream); + int getJointSpeed(int id); + int getJointLoad(int id); + int getJointTemperature(int id); + int isJointMoving(int id); + + int sendPacket(int id, int Address, int value); + int readPacket(unsigned char *buffer, size_t size); + + int RXsendPacket(int id, int Address); + int RXsendPacket(int id, int Address, int size); + + int flush(); + + class Packet + { + bool freeData; + + public: + unsigned char *data; + size_t data_size; + + // wrap a received data stream in an Packet object for analysis + Packet(unsigned char *data, size_t size); + // build a packet into the pre-allocated data array + // if data is null it will be malloc'ed and free'd on destruction. + + Packet( + unsigned char *data, + size_t size, + unsigned char id, + unsigned char instruction, + int parameter_data_size, + ...); + ~Packet(); + unsigned char getId(); + int getLength(); + int getSize(); + int getParameterCount(); + unsigned char getInstruction(); + unsigned char getParameter(int n); + bool isValid(); + + void toStream(Stream &stream); + }; +}; + +#endif diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.cpp b/rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.cpp new file mode 100644 index 0000000..5a5acc2 --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.cpp @@ -0,0 +1,64 @@ +/* + * dxl_pro.c + * + * Created on: 2013. 4. 25. + * Author: ROBOTIS,.LTD. + */ +#include +#include "dxl_pro.h" + +/* gbpRxBuffer gbDXLWritePointer +extern uint32_t Dummy(uint32_t tmp); +extern void uDelay(uint32_t uTime); +extern void nDelay(uint32_t nTime);*/ + +unsigned short update_crc(unsigned short crc_accum, unsigned char *data_blk_ptr, unsigned short data_blk_size) +{ + unsigned short i, j; + unsigned short crc_table[256] = {0x0000, + 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011, + 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, + 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D, + 0x8077, 0x0072, 0x0050, 0x8055, 0x805F, 0x005A, 0x804B, + 0x004E, 0x0044, 0x8041, 0x80C3, 0x00C6, 0x00CC, 0x80C9, + 0x00D8, 0x80DD, 0x80D7, 0x00D2, 0x00F0, 0x80F5, 0x80FF, + 0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1, 0x00A0, 0x80A5, + 0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1, 0x8093, + 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087, 0x0082, + 0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D, 0x8197, + 0x0192, 0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB, 0x01AE, + 0x01A4, 0x81A1, 0x01E0, 0x81E5, 0x81EF, 0x01EA, 0x81FB, + 0x01FE, 0x01F4, 0x81F1, 0x81D3, 0x01D6, 0x01DC, 0x81D9, + 0x01C8, 0x81CD, 0x81C7, 0x01C2, 0x0140, 0x8145, 0x814F, + 0x014A, 0x815B, 0x015E, 0x0154, 0x8151, 0x8173, 0x0176, + 0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162, 0x8123, + 0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137, 0x0132, + 0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E, 0x0104, + 0x8101, 0x8303, 0x0306, 0x030C, 0x8309, 0x0318, 0x831D, + 0x8317, 0x0312, 0x0330, 0x8335, 0x833F, 0x033A, 0x832B, + 0x032E, 0x0324, 0x8321, 0x0360, 0x8365, 0x836F, 0x036A, + 0x837B, 0x037E, 0x0374, 0x8371, 0x8353, 0x0356, 0x035C, + 0x8359, 0x0348, 0x834D, 0x8347, 0x0342, 0x03C0, 0x83C5, + 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1, 0x83F3, + 0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7, 0x03E2, + 0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD, 0x83B7, + 0x03B2, 0x0390, 0x8395, 0x839F, 0x039A, 0x838B, 0x038E, + 0x0384, 0x8381, 0x0280, 0x8285, 0x828F, 0x028A, 0x829B, + 0x029E, 0x0294, 0x8291, 0x82B3, 0x02B6, 0x02BC, 0x82B9, + 0x02A8, 0x82AD, 0x82A7, 0x02A2, 0x82E3, 0x02E6, 0x02EC, + 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2, 0x02D0, 0x82D5, + 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1, 0x8243, + 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257, 0x0252, + 0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E, 0x0264, + 0x8261, 0x0220, 0x8225, 0x822F, 0x022A, 0x823B, 0x023E, + 0x0234, 0x8231, 0x8213, 0x0216, 0x021C, 0x8219, 0x0208, + 0x820D, 0x8207, 0x0202}; + + for (j = 0; j < data_blk_size; j++) + { + i = ((unsigned short)(crc_accum >> 8) ^ *data_blk_ptr++) & 0xFF; + crc_accum = (crc_accum << 8) ^ crc_table[i]; + } + + return crc_accum; +} diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.h b/rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.h new file mode 100644 index 0000000..105715f --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/dxl_pro.h @@ -0,0 +1,37 @@ +/* + * dxl_pro.h + * + * Created on: 2013. 4. 25. + * Author: ROBOTIS,.LTD. + */ + +#ifndef DXL_PRO_H_ +#define DXL_PRO_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define MAXNUM_TXPACKET (255) //(65535) +#define MAXNUM_RXPACKET (255) //(65535) + +///////////////// utility for value /////////////////////////// +#define DXL_MAKEWORD(a, b) ((unsigned short)(((unsigned char)(((unsigned long)(a)) & 0xff)) | ((unsigned short)((unsigned char)(((unsigned long)(b)) & 0xff))) << 8)) +#define DXL_MAKEDWORD(a, b) ((unsigned int)(((unsigned short)(((unsigned long)(a)) & 0xffff)) | ((unsigned int)((unsigned short)(((unsigned long)(b)) & 0xffff))) << 16)) +#define DXL_LOWORD(l) ((unsigned short)(((unsigned long)(l)) & 0xffff)) +#define DXL_HIWORD(l) ((unsigned short)((((unsigned long)(l)) >> 16) & 0xffff)) +#define DXL_LOBYTE(w) ((unsigned char)(((unsigned long)(w)) & 0xff)) +#define DXL_HIBYTE(w) ((unsigned char)((((unsigned long)(w)) >> 8) & 0xff)) + +#define RX_TIMEOUT_COUNT2 (1600L) //(1000L) //porting +#define NANO_TIME_DELAY (12000) // ydh added 20111228 -> 20120210 edited ydh +#define RX_TIMEOUT_COUNT1 (RX_TIMEOUT_COUNT2 * 128L) + + unsigned short update_crc(unsigned short crc_accum, unsigned char *data_blk_ptr, unsigned short data_blk_size); + +#ifdef __cplusplus +} +#endif + +#endif /* DXL_PRO_H_ */ diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example/XL320_servo_example.ino b/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example/XL320_servo_example.ino new file mode 100644 index 0000000..fa791e3 --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example/XL320_servo_example.ino @@ -0,0 +1,72 @@ + +// ======================================== +// Dynamixel XL-320 Arduino library example +// ======================================== + +// Read more: +// https://github.com/hackerspace-adelaide/XL320 + +#include "XL320.h" + +// Name your robot! +XL320 robot; + +// If you want to use Software Serial, uncomment this line +#include + +// Set the SoftwareSerial RX & TX pins +SoftwareSerial mySerial(10, 11); // (RX, TX) + +// Set some variables for incrementing position & LED colour +char rgb[] = "rgbypcwo"; +int servoPosition = 0; +int ledColour = 0; + +// Set the default servoID to talk to +int servoID = 1; + +void setup() { + + // Talking standard serial, so connect servo data line to Digital TX 1 + // Comment out this line to talk software serial + Serial.begin(115200); + + // Setup Software Serial + mySerial.begin(115200); + + // Initialise your robot + robot.begin(Serial); // Hand in the serial object you're using + + // I like fast moving servos, so set the joint speed to max! + robot.setJointSpeed(servoID, 1023); + +} + +void loop() { + + // LED test.. let's randomly set the colour (0-7) +// robot.LED(servoID, &rgb[random(0,7)] ); + + // LED test.. select a random servoID and colour + robot.LED(random(1,4), &rgb[random(0,7)] ); + + // LED colour test.. cycle between RGB, increment the colour and return 1 after 3 +// robot.LED(servoID, &rgb[ledColour]); + ledColour = (ledColour + 1) % 3; + + // Set a delay to account for the receive delay period + delay(100); + + // Servo test.. let's randomly set the position (0-1023) +// robot.moveJoint(servoID, random(0, 1023)); + + // Servo test.. select a random servoID and colour + robot.moveJoint(random(1,4), random(0, 1023)); + + // Servo test.. increment the servo position by 100 each loop +// robot.moveJoint(servoID, servoPosition); + servoPosition = (servoPosition + 100) % 1023; + + // Set a delay to account for the receive delay period + delay(100); +} \ No newline at end of file diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example_with_half_duplex_hardware_serial/XL320_servo_example_with_half_duplex_hardware_serial.ino b/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example_with_half_duplex_hardware_serial/XL320_servo_example_with_half_duplex_hardware_serial.ino new file mode 100644 index 0000000..8400914 --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_example_with_half_duplex_hardware_serial/XL320_servo_example_with_half_duplex_hardware_serial.ino @@ -0,0 +1,86 @@ + +// ======================================== +// Dynamixel XL-320 Arduino library example +// ======================================== + +// Read more: +// https://github.com/hackerspace-adelaide/XL320 + +#include "XL320.h" + +// NOTE: WORK IN PROGRESS! +// For Half Duplex Hardware Serial to read data back from the servos +#include + +// Name your robot! +XL320 robot; + +// Set some variables for incrementing position & LED colour +char rgb[] = "rgbypcwo"; +int servoPosition = 0; +int ledColour = 0; + +// Delay between sending & receiving data +int delayBetweenSendReceive = 500; + +// Set the default servoID to talk to +int servoID = 3; + +void setup() { + + // You have to manually set the TX and RX lines of your chosen serial port to INPUT_PULLUP + // as this is the state they will be in when they are disconnected from the UART + // you also need to physically link the TX and RX pins in your circuit + // You can achieve this by connecting the data line out of the servo back into pin 0 RX + pinMode(0, INPUT_PULLUP); + pinMode(1, INPUT_PULLUP); + + pinMode(13, OUTPUT); + + // Talk serial with your servo by connecting the servo input data line to Digital TX 1 + HalfDuplexSerial.begin(115200); + HalfDuplexSerial.setTimeout(delayBetweenSendReceive); + + // Initialise your robot + robot.begin(HalfDuplexSerial); // Hand in the serial object you're using + + // I like fast moving servos, so set the joint speed to max! + robot.setJointSpeed(servoID, 1023); + delay(delayBetweenSendReceive); + +} + +void loop() { + + // LED test.. let's randomly set the colour (0-7) +// robot.LED(servoID, &rgb[random(0,7)] ); + + // LED test.. select a random servoID and colour + robot.LED(servoID, &rgb[ledColour] ); + + // LED colour test.. cycle between RGB, increment the colour and return 1 after 3 + ledColour = (ledColour + 1) % 3; + + // Set a delay to account for the receive delay period + delay(delayBetweenSendReceive); + + // Servo test.. select a random servoID and colour + robot.moveJoint(servoID, servoPosition); + + // Servo test.. increment the servo position by 100 each loop + servoPosition = (servoPosition + 100) % 1023; + + // Set a delay to account for the receive delay period + delay(delayBetweenSendReceive); + + // To read back from the servo + // TODO: Fix this.. getting invalid packets.. + byte buffer[256]; + XL320::Packet p = XL320::Packet(buffer, robot.readPacket(buffer,256)); + if (p.isValid()) { + // Set pin 13 HIGH so we know! + digitalWrite(13, HIGH); + } else { + digitalWrite(13, LOW); + } +} \ No newline at end of file diff --git a/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_set_baud_rate_or_id/XL320_servo_set_baud_rate_or_id.ino b/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_set_baud_rate_or_id/XL320_servo_set_baud_rate_or_id.ino new file mode 100644 index 0000000..f11adf3 --- /dev/null +++ b/rpi_pico_rosserial_test/lib/XL320-bene/examples/XL320_servo_set_baud_rate_or_id/XL320_servo_set_baud_rate_or_id.ino @@ -0,0 +1,52 @@ + +// ======================================== +// Dynamixel XL-320 Arduino library example +// ======================================== + +// Read more: +// https://github.com/hackerspace-adelaide/XL320 + +#include "XL320.h" + +// Name your robot! +XL320 robot; + +void setup() { + + // Talking standard serial, so connect servo data line to Digital TX 1 + // Set the default servo baud rate which is 1000000 (1Mbps) if it's a brand new servo + Serial.begin(1000000); + + // Initialise your robot + robot.begin(Serial); // Hand in the serial object you're using + delay(100); + + // Current servoID + int servoID = 254; + + // NOTE: comment out either the XL_BAUD_RATE or XL_ID, only send one at a time + + // =================================== + // Set the serial connection baud rate + // =================================== + + // writePacket(1, XL_BAUD_RATE, x) sets the baud rate: + // 0: 9600, 1:57600, 2:115200, 3:1Mbps + robot.sendPacket(servoID, XL_BAUD_RATE, 2); + + // ================ + // Set the servo ID + // ================ + + // writePacket(1, XL_ID, x) sets the baud rate: + // ID can be between 1 and 253 (but not 200) +// robot.sendPacket(servoID, XL_ID, 3); +} + +void loop() { + // NOTE: load this sketch to the Arduino > Servo + // Then power cycle the Arduino + Servo + + // NOTE: When setting the servo ID, the baud rate defaults down to 9600 + // So then you'll need to power cycle, and re-write the baud rate to whatever you want via 9600 +} \ No newline at end of file diff --git a/rpi_pico_rosserial_test/platformio.ini b/rpi_pico_rosserial_test/platformio.ini new file mode 100644 index 0000000..94c11bf --- /dev/null +++ b/rpi_pico_rosserial_test/platformio.ini @@ -0,0 +1,26 @@ +; PlatformIO Project Configuration File +; +; Build options: build flags, source filter +; Upload options: custom upload port, speed and extra flags +; Library options: dependencies, extra library storages +; Advanced options: extra scripting +; +; Please visit documentation for the other options and examples +; https://docs.platformio.org/page/projectconf.html + +[env:pico] +framework = arduino +platform = https://github.com/maxgerhardt/platform-raspberrypi +board = rpipicow +board_build.core = earlephilhower +upload_protocol = picoprobe +debug_tool = picoprobe +monitor_speed = 115200 +check_tool = cppcheck +lib_deps = + frankjoshua/Rosserial Arduino Library@^0.9.1 + +; [env:pico] +; platform = raspberrypi +; board = pico +; framework = arduino \ No newline at end of file diff --git a/rpi_pico_rosserial_test/rpi_pico_flash.cfg b/rpi_pico_rosserial_test/rpi_pico_flash.cfg new file mode 100644 index 0000000..8645abf --- /dev/null +++ b/rpi_pico_rosserial_test/rpi_pico_flash.cfg @@ -0,0 +1,19 @@ +source [find interface/cmsis-dap.cfg] +; source [find interface/jlink.cfg] +; source [find interface/picoprobe.cfg] + +transport select swd +source [find target/rp2040.cfg] +set USE_CORE 0 +set RESCUE 1 + +adapter speed 4000 + +; init +; reset halt + +# Erase + +# Load the program +; program firmware.elf verify reset exit +program firmware.bin diff --git a/rpi_pico_rosserial_test/src/main.cpp b/rpi_pico_rosserial_test/src/main.cpp new file mode 100644 index 0000000..4dee81b --- /dev/null +++ b/rpi_pico_rosserial_test/src/main.cpp @@ -0,0 +1,112 @@ +#include +#include "XL320.h" +#include "HardwareSerial.h" + +// Include the ROS library +#include "ros.h" +#include "std_msgs/Float32MultiArray.h" +#include "std_msgs/String.h" + +#define PID_PERIOD_US 10000 + +static unsigned long lastTime; +ros::NodeHandle nh; + +void servo_cmd_cb(const std_msgs::Float32MultiArray &input_msg); + +std_msgs::Float32MultiArray servo_fb_msg; +std_msgs::Float32MultiArray servo_cmd_msg; +ros::Publisher servo_fb_pub("servo_fb", &servo_fb_msg); +ros::Subscriber servo_cmd_sub("servo_cmd", servo_cmd_cb); + +// SERVO CONFIGURATION +XL320 robot; +char rgb[] = "rgbypcwo"; +int servo_id = 16; +int led_color = 0; +float servo_setpoint_raw[1] = {0}; +float servo_pos_raw[1] = {0}; +float servo_pos_deg[1] = {0}; +float servo_setpoint_deg[1] = {0}; + +float map_float(float x, float in_min, float in_max, float out_min, float out_max) +{ + return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; +} + +void servo_setup() +{ + // Talking standard serial, so connect servo data line to Digital TX 1 + // Comment out this line to talk software serial + // Serial1.begin(1000000, SERIAL_8N1_HALF_DUPLEX); + robot.begin(Serial1); // Hand in the serial object you're using + robot.setJointSpeed(servo_id, 1023 / 2); +} + +void servo_loop() +{ + // LED test.. let's randomly set the colour (0-7) + robot.LED(servo_id, &rgb[random(0, 7)]); + + // SETPOINT TEST + robot.moveJoint(servo_id, servo_setpoint_raw[0]); + delay(100); + // Serial1.clear(); + byte buffer[256]; + XL320::Packet p = XL320::Packet(buffer, robot.readPacket(buffer, 256)); + + // Driver diagnostic +#if DEBUG_PRINT == 1 + p.toStream(SerialUSB); +#endif + + delay(100); + // Serial1.clear(); + Serial1.flush(); + + // Get state + servo_pos_raw[0] = robot.getJointPosition(servo_id); + servo_pos_deg[0] = map_float(servo_pos_raw[0], 0, 1023, 0, 359.99); + + delay(100); +} + +void setup() +{ + // servo_setup(); + + nh.initNode(); + + servo_fb_msg.data = servo_pos_deg; + servo_fb_msg.data_length = 1; + servo_cmd_msg.data_length = 1; + + nh.advertise(servo_fb_pub); + nh.subscribe(servo_cmd_sub); + + nh.negotiateTopics(); + while (!nh.connected()) + { + nh.negotiateTopics(); + } + + lastTime = micros(); +} + +void loop() +{ + while (micros() < lastTime + PID_PERIOD_US) + ; + lastTime += PID_PERIOD_US; + + // servo_loop(); + servo_fb_pub.publish(&servo_fb_msg); + + nh.spinOnce(); +} + +void servo_cmd_cb(const std_msgs::Float32MultiArray &input_msg) +{ + servo_setpoint_deg[0] = input_msg.data[0]; + servo_setpoint_raw[0] = map_float(servo_setpoint_deg[0], 0, 359.99, 0, 1023); +} diff --git a/rpi_pico_rosserial_test/src/main_blinky.cpp b/rpi_pico_rosserial_test/src/main_blinky.cpp new file mode 100644 index 0000000..193573a --- /dev/null +++ b/rpi_pico_rosserial_test/src/main_blinky.cpp @@ -0,0 +1,19 @@ +// #include + +// #define LED_PIN 25 + +// void setup() { +// // Initialize LED pin as an output. +// pinMode(LED_PIN, OUTPUT); +// // Initialize Serial communication at 115200 baud rate. +// Serial.begin(115200); +// } + +// void loop() { +// digitalWrite(LED_PIN, HIGH); // Turn the LED on. +// Serial.println("Hello, World!111"); // Print "Hello, World!" to the Serial monitor. +// delay(100); // Wait for a second. + +// digitalWrite(LED_PIN, LOW); // Turn the LED off. +// delay(100); // Wait for another second. +// } diff --git a/rpi_pico_rosserial_test/test/README b/rpi_pico_rosserial_test/test/README new file mode 100644 index 0000000..b0416ad --- /dev/null +++ b/rpi_pico_rosserial_test/test/README @@ -0,0 +1,11 @@ + +This directory is intended for PlatformIO Test Runner and project tests. + +Unit Testing is a software testing method by which individual units of +source code, sets of one or more MCU program modules together with associated +control data, usage procedures, and operating procedures, are tested to +determine whether they are fit for use. Unit testing finds problems early +in the development cycle. + +More information about PlatformIO Unit Testing: +- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html diff --git a/teensy40_brushed_v2/.DS_Store b/teensy40_brushed_v2/.DS_Store new file mode 100644 index 0000000000000000000000000000000000000000..dde91b36e82df3a070110630fa16c64d5e7c7e11 GIT binary patch literal 6148 zcmeHLJxc>Y5Ph4RCTNq=@~{>`f5E9|tq>c#kPkJIc)=ug%Jm}n14LU3t%EJj%-l=O&*f4k()z z`q_M@_H{nq2sfXP<&&$Kf!3rzS~~N%`Ai<==fnFk@{~yvRbQ9a!N}wCKOYbIZJf)S z^?H1&V)(i^M9t^BxzK#tp`^YjiW&gIK`JwE97AE1W@#rAy0+%z!`eJH`HfAqG$^ZUG7S6-`_KC@Yd;;e`v3Wx%tz?cH`n;sz*#>ir7kh{2FUjYaMZnM#| z-eUdDATM`M*B-{_h7#OB4_V{*?kMh|BRREyGnfwsYGDsx~{Hg+9iH^bE literal 0 HcmV?d00001 diff --git a/teensy40_brushed_v2/.gitignore b/teensy40_brushed_v2/.gitignore new file mode 100644 index 0000000..beaaf8a --- /dev/null +++ b/teensy40_brushed_v2/.gitignore @@ -0,0 +1,6 @@ +.pio +.vscode/.browse.c_cpp.db* +.vscode/c_cpp_properties.json +.vscode/launch.json +.vscode/ipch +.vscode/extensions.json diff --git a/teensy40_brushed_v2/.vscode/extensions.json b/teensy40_brushed_v2/.vscode/extensions.json new file mode 100644 index 0000000..080e70d --- /dev/null +++ b/teensy40_brushed_v2/.vscode/extensions.json @@ -0,0 +1,10 @@ +{ + // See http://go.microsoft.com/fwlink/?LinkId=827846 + // for the documentation about the extensions.json format + "recommendations": [ + "platformio.platformio-ide" + ], + "unwantedRecommendations": [ + "ms-vscode.cpptools-extension-pack" + ] +} diff --git a/teensy40_brushed_v2/.vscode/settings.json b/teensy40_brushed_v2/.vscode/settings.json new file mode 100644 index 0000000..7f71f22 --- /dev/null +++ b/teensy40_brushed_v2/.vscode/settings.json @@ -0,0 +1,50 @@ +{ + "files.associations": { + "memory": "cpp", + "array": "cpp", + "atomic": "cpp", + "bit": "cpp", + "*.tcc": "cpp", + "cctype": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "compare": "cpp", + "concepts": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdint": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "deque": "cpp", + "string": "cpp", + "unordered_map": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "random": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "initializer_list": "cpp", + "iosfwd": "cpp", + "limits": "cpp", + "new": "cpp", + "numbers": "cpp", + "ostream": "cpp", + "stdexcept": "cpp", + "streambuf": "cpp", + "cinttypes": "cpp", + "typeinfo": "cpp", + "iostream": "cpp", + "istream": "cpp", + "cstring": "cpp" + } +} \ No newline at end of file diff --git a/teensy40_brushed_v2/include/README b/teensy40_brushed_v2/include/README new file mode 100644 index 0000000..194dcd4 --- /dev/null +++ b/teensy40_brushed_v2/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/teensy40_brushed_v2/lib/Arm/driver_motor.cpp b/teensy40_brushed_v2/lib/Arm/driver_motor.cpp new file mode 100644 index 0000000..4060995 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/driver_motor.cpp @@ -0,0 +1,371 @@ +/** + * @file driver_motor.cpp + * @author Vincent Boucher, Steve Ding + * @version V1.0.0 + * @date 30-May-2023 + * @brief motor object + * + * @attention For prototype example only + * V1.0.0 - created + * + */ +#include "driver_motor.h" +#include "pid.cpp" + +/// @brief Initializes the motor object +/// @param direction Positive direction for motor +/// @param port Port used for motor connection +/// @param maxTorque Maximum torque motor can output +void driver_motor::initialize_motor(uint8_t direction_motor, uint8_t motor_pwn_pin, uint8_t motor_dir_pin, uint8_t motor_fault_pin, float max_torque_motor, float torque_constant_motor) +{ + _motor_max_torque = max_torque_motor; + _torque_constant_motor = torque_constant_motor; + _target_torque = 0.0; + _target_angle_ps = 0.0; // The desired angle to turn to (sent from software) + _output_motor = 0; + _gear_ratio = 1.0; // default for no effect + _angle_full_turn_es = 360.0f; // encoder angle corresponding to a full turn (considering gear ratio) + + // Linear joint by default. + _is_circular_joint = false; + // Foward direction logic level + _forward_dir = direction_motor; + + _ctrl_period = 0.0; + _sampling_period = 0.0; + + _motor_dir_pin = motor_dir_pin; + _motor_fault_pin = motor_fault_pin; + _motor_pwm_pin = motor_pwn_pin; + + // kalman params + _kalman_gain = 0; + _current_estimate = 0; + + _err_estimate = _ERR_ESTIMATE_INIT; + _last_estimate = _LAST_ESTIMATE_INIT; + _err_measure = _ERR_MEASURE_INIT; + _q = _Q_INIT; + + _error = 0.0; + _previous_error = 0.0; + + _error_int = 0.0; + _error_dir = 0.0; + + // initializes pins and resolution + // _pwm_set_resolution(_PWM_BIT_RESOLUTION); + + pinMode(_motor_pwm_pin, OUTPUT); + pinMode(_motor_dir_pin, OUTPUT); + pinMode(_motor_fault_pin, OUTPUT); + + // TODO: is this not necessary for pid? + // _pwm_setup(_motor_pwm_pin, _MAX_PWM_FREQUENCY); // Sets frequency of pwm + + // 24V motor therefore max is 24 and min is -24 + pid_instance = new PID(0.1, 24, -24, 2.0, 0, 0); +} + +/// @brief Sets the torque and writes the PWM value to the motor +/// @param torque Torque value to be written to the motor +void driver_motor::set_target_torque(float torque) +{ + _target_torque = torque; +} + +float driver_motor::get_target_torque(void) +{ + return _target_torque; +} + +float driver_motor::get_output_motor(void) +{ + return _output_motor; +} + +void driver_motor::set_target_angle_ps(float angle_ps) +{ + if (!_is_circular_joint) + { + if (angle_ps > _max_angle_ps) + { + _target_angle_ps = _max_angle_ps; + } + else if (angle_ps < _min_angle_ps) + { + _target_angle_ps = _min_angle_ps; + } + else + { + _target_angle_ps = angle_ps; + } + } + else + { + _target_angle_ps = angle_ps; + } + return; +} + +float driver_motor::get_target_angle_ps(void) +{ + return _target_angle_ps; +} + +void driver_motor::set_control_period(float period) +{ + _ctrl_period = period; + _sampling_period = _ctrl_period * 1e-6; +} + +float driver_motor::get_current_angle_es() +{ + this->_encoder->poll_encoder_angle(); + _current_angle_es = this->_encoder->get_angle_multi(); + return _current_angle_es; +} + +float driver_motor::get_current_angle_ps() +{ + this->_encoder->poll_encoder_angle(); + float temp = this->_encoder->get_angle_multi(); + if (_is_circular_joint) + { + temp = fmod(temp, _angle_full_turn_es); + } + return temp / _gear_ratio; +} + +void driver_motor::closed_loop_control_tick() +{ + // IMPORTANT: es means encoder space + // setpoint_es is the desired angle after gear ratio translation + float setpoint_es = _target_angle_ps * _gear_ratio; + + // angle_multi_es is the current angle after gear ratio translation + float angle_multi_es = get_current_angle_es(); + + // For later, diff can influence PID coefficients + float diff = setpoint_es - angle_multi_es; + + // Determine whether to move forward or backwards + float forward_distance = (setpoint_es > angle_multi_es) ? (setpoint_es - angle_multi_es) : (_angle_full_turn_es - (angle_multi_es - setpoint_es)); // CCW + float backward_distance = (setpoint_es > angle_multi_es) ? (_angle_full_turn_es - (setpoint_es - angle_multi_es)) : (angle_multi_es - setpoint_es); // CW + + // CAPPING ANGLE BY JOINT LIMITS, only for linear joints + if (!_is_circular_joint) + { + if (setpoint_es > _max_angle_es) + { + setpoint_es = _max_angle_es; + } + else if (setpoint_es < _min_angle_es) + { + setpoint_es = _min_angle_es; + } + } + + // Feed to PID and determine error + float pid_output = 0.0; + if (_is_circular_joint) + { + // Backwards + if (backward_distance < forward_distance - 10.0) // TODO: handle hysterics? 10.0 was used previously + { + // set_direction(!_forward_dir); // set direction to backwards + if (setpoint_es < angle_multi_es) + { + pid_output = pid_instance->calculate(setpoint_es, angle_multi_es); + } + else + { + pid_output = pid_instance->calculate(setpoint_es + _angle_full_turn_es, angle_multi_es); + } + } + // Forwards + else + { + // set_direction(_forward_dir); // set direction to forwards + if (setpoint_es > angle_multi_es) + { + pid_output = pid_instance->calculate(setpoint_es, angle_multi_es); + } + else + { + pid_output = pid_instance->calculate(setpoint_es - _angle_full_turn_es, angle_multi_es); + } + } + } + else // linear joint + { + pid_output = pid_instance->calculate(setpoint_es, angle_multi_es); + } + + // Set direction + if (pid_output > 0) // pos + { + set_direction(_forward_dir); // set direction to forwards + } + else // neg + { + set_direction(!_forward_dir); // set direction to backwards + } + + // Output to motor + // 255 is the max PWM value, 24 is the max voltage + float pwm_output = abs(pid_output) * 255.0 / 24.0; + + this->_pwm_write_duty(pwm_output); + return; +} + +void driver_motor::torque_control(float motor_cur) +{ + + bool direction = LOW; + float motor_current; + + if (_forward_dir) + { + motor_current = motor_cur; + } + else + { + motor_current = -1 * motor_cur; + } + + _kalman_gain = _err_estimate / (_err_estimate + _err_measure); + _current_estimate = _last_estimate + _kalman_gain * (motor_current - _last_estimate); + + _err_estimate = (1.0 - _kalman_gain) * _err_estimate + fabs(_last_estimate - _current_estimate) * _q; + _last_estimate = _current_estimate; + + _error = _target_torque - _current_estimate * _torque_constant_motor; + _error_int += _error * _sampling_period; + + // Bound the integral error such that it cannot saturate the motors + // The typical error is less than 1 + if (_error_int > _maxError) + { + _error_int = _maxError; + } + else if (_error_int < -_maxError) + { + _error_int = -_maxError; + } + + // Calculate output + _output_motor = _error * _KP + _error_int * _KI + _error_dir * _KD; + + if (_output_motor == _output_motor) // TODO: why are we comparing it to itself? A: Its broken + { + _output_motor *= _PWM_OUTPUT_RESOLUTION / _motor_max_torque; + } + else + { + _output_motor = 0.0; + + _error = 0.0; + _previous_error = 0.0; + + _error_int = 0.0; + _error_dir = 0.0; + } + + // Set direction + if (_forward_dir == 0) + { + direction = !direction; + } + + if (_output_motor <= 0) + { + digitalWrite(_motor_dir_pin, direction); + } + else + { + digitalWrite(_motor_dir_pin, !direction); + } + + // output torque + _output_motor = abs(_output_motor); + if (_output_motor > _PWM_OUTPUT_RESOLUTION) + { + _pwm_write_duty(_PWM_OUTPUT_RESOLUTION); + } + else + { + _pwm_write_duty((uint32_t)_output_motor); + } +} + +/// @brief Sets the resolution of the motor +/// @param resolution new resolution of the motor +void driver_motor::_pwm_set_resolution(uint16_t resolution) +{ + + analogWriteResolution(resolution); +} + +/// @brief Sets the PWM frequency of the motor +/// @param pwmPin Pin used for PWM modulation to the motor +/// @param pwmFreq Frequency to be set for PWM +void driver_motor::_pwm_setup(float pwmFreq) +{ + analogWriteFrequency(_motor_pwm_pin, pwmFreq); +} + +/// @brief Writes the PWM value to the motor +/// @param pwmPin Pin used for PWM modulation to the motor +/// @param pwmDuty Duty cyle value to be written to PWM +void driver_motor::_pwm_write_duty(uint32_t pwmDuty) +{ + analogWrite(_motor_pwm_pin, pwmDuty); +} + +void driver_motor::set_gear_ratio(float gear_ratio) +{ + _gear_ratio = gear_ratio; + _angle_full_turn_es = 360.0f * _gear_ratio; +} + +void driver_motor::set_is_circular_joint(bool is_circular_joint) +{ + _is_circular_joint = is_circular_joint; +} + +/// @brief Define the forward logic level +/// @param forward_dir +void driver_motor::set_forward_dir(uint8_t forward_dir) +{ + _forward_dir = forward_dir; +} + +void driver_motor::set_angle_limit_ps(float max_angle, float min_angle) +{ + _max_angle_ps = max_angle; + _min_angle_ps = min_angle; + _max_angle_es = max_angle * _gear_ratio; + _min_angle_es = min_angle * _gear_ratio; +} + +void driver_motor::set_direction(uint8_t direction) +{ + digitalWrite(_motor_dir_pin, direction); +} + +void driver_motor::move_manual(uint32_t speed) +{ + uint32_t duty = abs(speed) * 255; + if (speed < 0) + { + digitalWrite(_motor_dir_pin, !_forward_dir); + _pwm_write_duty(duty); + } + else + { + digitalWrite(_motor_dir_pin, _forward_dir); + _pwm_write_duty(duty); + } +} diff --git a/teensy40_brushed_v2/lib/Arm/driver_motor.h b/teensy40_brushed_v2/lib/Arm/driver_motor.h new file mode 100644 index 0000000..649f8a8 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/driver_motor.h @@ -0,0 +1,207 @@ +/** + * @file driver_actuators.h + * @author Steve Ding, Oliver Philbin-Briscoe, Maciej Lacki, Colin Gallacher + * @version V0.2.0 + * @date 22-February-2022 + * @brief single actuator controller + * + * @attention For prototype example only + */ + +#ifndef DRIVER_JOINT_H +#define DRIVER_JOINT_H + +#include "Arduino.h" +#include "hardware_pins.h" + +#include "model_encoder.h" +#include "model_sensor.h" + +#include "pid.h" + +#include + +#define _MAX_PWM_FREQUENCY 146484.38 +#define _PWM_BIT_RESOLUTION 10 +#define _PWM_OUTPUT_RESOLUTION 1023 + +class driver_motor +{ +public: + /** + * Initialize a actuator control pins based on port and control parameters + * + * @param direction positive actuator rotation direction + * @param port actuator connection port + * @param maxTorque maximum torque limit actuator can output + */ + void initialize_motor(uint8_t directionMotor, uint8_t motorPWMPin, uint8_t motorDirPin, uint8_t motorFaultPin, float maxTorqueMotor, float torqueConstantMotor); + + /** + * Set specific torque target torque + * + * @param torque torque to be output + */ + void set_target_torque(float torque); + + void set_target_angle_ps(float position); + + void set_target_speed(float speed); + + void set_gear_ratio(float gear_ratio); + + void set_is_circular_joint(boolean is_circular_joint); + // Set the logic that defines the forward direction of the motor + void set_forward_dir(uint8_t forward_dir); + + /// @brief Sets the positive direction of the motor + /// @param direction Positive direction of motor (CW or CCW) + void set_direction(uint8_t direction); + + /// @brief Sets the control period of the motor PID loop + /// @param period + void set_control_period(float period); + + float get_target_torque(void); + + float get_output_motor(void); + + float get_target_angle_ps(void); + + float get_target_speed(void); + /** + * Control torque output + * + * @param mtrCurrent detected motor current at time index + * @param powerState main power state + */ + void torque_control(float motorCur); + + void position_control(float motorPos); + + void speed_control(float motorSpeed); + + /** + * Set hardware PWM duty cycle + * + * @param pwmDuty bit resolution value of desired PWM duty cycle + */ + void _pwm_write_duty(uint32_t pwmDuty); + + void attach_encoder(std::unique_ptr encoder) + { + _encoder = std::move(encoder); + } + + void attach_current_sensor(std::unique_ptr current_sensor) + { + _current_sensor = std::move(current_sensor); + } + + void closed_loop_control_tick(); + + void set_angle_limit_ps(float max_angle, float min_angle); + + // private: + // model_encoder *_encoder = nullptr; + // model_sensor *_current_sensor = nullptr; + std::unique_ptr _encoder; + std::unique_ptr _current_sensor; + + // JOINT CONFIG. + uint8_t _forward_dir; + float _gear_ratio; + float _angle_full_turn_es; + boolean _is_circular_joint; + float _max_angle_ps; + float _min_angle_ps; + float _max_angle_es; + float _min_angle_es; + + // JOINT STATE + float _current_angle_es; + float _current_angle_ps; + + uint8_t _motor_pwm_pin; + uint8_t _motor_dir_pin; + uint8_t _motor_fault_pin; + + float _motor_max_torque; + float _motor_max_speed; + float _motor_max_position; + float _motor_min_position; + + float _target_torque; + float _target_angle_ps; + float _targetSpeed; + + // PID parameters + PID *pid_instance; + float _output_motor; + float _ctrl_period; + float _sampling_period; + + float _torque_constant_motor; + + // TODO: Where are these values from? Are they the aggressive ones or normal ones? + const float _pi = 3.14159265358979; + const float _KP = 4.0; + const float _KI = 2.0; + const float _KD = 1.0; + + // Filter params + // kalman filter parameters + + const float _ERR_ESTIMATE_INIT = 1.877e-3; + const float _LAST_ESTIMATE_INIT = 0; + const float _ERR_MEASURE_INIT = 1.877e-3; + const float _Q_INIT = 0.0044; + + float _err_estimate; + float _last_estimate; + float _err_measure; + float _q; + + float _kalman_gain; + float _current_estimate; + + // Error parameters and variables + const float _maxError = 2.0; // 10000.0; //2.0; + + float _error; + float _previous_error; + + float _error_int; + float _error_dir; + + // const float _MAX_PWM_FREQUENCY = 146484.38; + // const uint8_t _PWM_BIT_RESOLUTION = 10; + // const uint32_t _PWM_OUTPUT_RESOLUTION = 1023; + + /** + * Set PWM signal bit resolution + * + * @param resolution new PWM bit resolution + */ + void _pwm_set_resolution(uint16_t resolution); + + /** + * Hardware PWM pin setup function + * + * @param pwmPin hardware PWM pin to setup + * @param pwmFreq desired hardware PWM frequency + */ + void _pwm_setup(float pwmFreq); + + /** + * Manually move the motor forwards or backwards + * + * @param speed in range -1 to 1 + */ + void move_manual(uint32_t speed); + + float get_current_angle_es(); + float get_current_angle_ps(); +}; + +#endif \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/hardware_pins.h b/teensy40_brushed_v2/lib/Arm/hardware_pins.h new file mode 100644 index 0000000..1d68d3a --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/hardware_pins.h @@ -0,0 +1,53 @@ +/** + * @file hardware_pins.h + * @author Steve Ding, Oliver Philbin-Briscoe, Colin Gallacher + * @version V0.1.0 + * @date 11-March-2021 + * @brief hardware pin definitions + * + * @attention For prototype example only + */ + +#ifndef HARDWARE_PINS_H +#define HARDWARE_PINS_H + +#include + +const uint8_t ENCPIN1_1 = 0; +const uint8_t ENCPIN1_2 = 1; + +const uint8_t ENCPIN2_1 = 2; +const uint8_t ENCPIN2_2 = 3; + +const uint8_t ENCPIN3_1 = 4; +const uint8_t ENCPIN3_2 = 5; + +const uint8_t PWMPIN1 = 13; // enable pin +const uint8_t DIRPIN1 = 16; // phase pin +const uint8_t nSLEEP1 = -1; + +const uint8_t PWMPIN2 = 14; +const uint8_t DIRPIN2 = 17; +const uint8_t nSLEEP2 = -1; + +const uint8_t PWMPIN3 = 15; +const uint8_t DIRPIN3 = 18; +const uint8_t nSLEEP3 = -1; + +const uint8_t LED_O = -1; +const uint8_t LED_B = -1; + +const uint8_t CURRENT_SENSE_A = 19; +const uint8_t CURRENT_SENSE_B = 20; +const uint8_t CURRENT_SENSE_C = 21; + +const uint8_t LIM_1 = 9; +const uint8_t LIM_2 = 10; +const uint8_t LIM_3 = 11; +const uint8_t LIM_4 = 12; +const uint8_t LIM_5 = 22; +const uint8_t LIM_6 = 23; + +const float wrist_pitch_max_angle = 30.0; +const float wrist_pitch_min_angle = -30.0; +#endif \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/model_encoder.cpp b/teensy40_brushed_v2/lib/Arm/model_encoder.cpp new file mode 100644 index 0000000..777a528 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/model_encoder.cpp @@ -0,0 +1,135 @@ +/** + * @file model_encoder.cpp + * @author Vincent Boucher, Steve Ding + * @version V1.0.0 + * @date 30-May-2023 + * @brief encoder object + * + * @attention For prototype example only + * V1.0.0 - created + * + */ +#include +#include "model_encoder.h" + +void model_encoder::initialize_encoder(uint8_t rotationalDirection, float offset, float resolution, uint8_t port) +{ + _offset = offset; + _resolution = resolution; + _port = port; + + _angularVelocity = 0.0; + _quad_enc_pos = _offset * (_resolution / 360.0); + _last_angle = 0.0; + + // TODO: check implementation multi-turn, should default true or false? + _turn_count = 0; + _angle_multi = 0.0; // angle from 0 to 360 in degrees + _angle_single = 0.0; // angle from 0 to 360 in degrees + _is_multi_turn = true; + + switch (port) + { + case 1: + _pinA = ENCPIN1_1; + _pinB = ENCPIN1_2; + break; + case 2: + _pinA = ENCPIN2_1; + _pinB = ENCPIN2_2; + break; + case 3: + _pinA = ENCPIN3_1; + _pinB = ENCPIN3_2; + break; + default: + _pinA = 0; + _pinB = 0; + break; + } + + if (rotationalDirection) + { + uint8_t tempPin = _pinA; + _pinA = _pinB; + _pinB = tempPin; + } + + _encoder = new QuadEncoder(port, _pinA, _pinB); + + _encoder->setInitConfig(); + _encoder->EncConfig.positionInitialValue = _quad_enc_pos; + _encoder->EncConfig.revolutionCountCondition = 1; + _encoder->init(); + + _velocityEstimation.initialize_parameters(_resolution, 8.0, 1000000.0, 1, 200000); +} + +void model_encoder::reset_encoder() +{ + _quad_enc_pos = _offset * (_resolution / 360.0); + _encoder->write(_quad_enc_pos); + _encoder->init(); +} + +void model_encoder::set_current_angle_es(float current_angle) +{ + Serial.printf("Setting as current: %f\n", current_angle); + _offset = current_angle; + _quad_enc_pos = current_angle * (_resolution / 360.0); + _encoder->write(_quad_enc_pos); +} + +void model_encoder::poll_encoder_angle() +{ + _quad_enc_pos = _encoder->read(); + + // Useless since _position always positive? + _angle_single = (_quad_enc_pos >= 0) ? (_quad_enc_pos % _resolution) : _resolution - (abs(_quad_enc_pos) % _resolution); + _angle_single = (360.0 / _resolution) * _angle_single; + _angle_multi = _quad_enc_pos * (360.0 / _resolution); + + _velocityEstimation.update_readings(_quad_enc_pos * (360.0 / _resolution), micros()); +} + +float model_encoder::get_angle_multi() +{ + return _angle_multi; +} + +float model_encoder::get_angle_single() +{ + return _angle_single; +} + +void model_encoder::set_parameters(uint8_t direction, float offset, float resolution) +{ + if (direction) + { + uint8_t tempPin = _pinA; + _pinA = _pinB; + _pinB = tempPin; + } + _encoder->enc_xbara_mapping(_pinA, PHASEA, 0); + _encoder->enc_xbara_mapping(_pinB, PHASEB, 0); + _encoder->disableInterrupts(_positionROEnable); + _encoder->disableInterrupts(_positionRUEnable); + + _offset = offset; + _resolution = resolution; + _quad_enc_pos = _offset * (_resolution / 360.0); + + _encoder->setInitConfig(); + _encoder->EncConfig.positionInitialValue = _quad_enc_pos; + _encoder->init(); +} + +void model_encoder::velocityEstimation(void) +{ + _angularVelocity = _velocityEstimation.foaw(0); +} + +float model_encoder::getVelocity(void) +{ + return _angularVelocity; +} \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/model_encoder.h b/teensy40_brushed_v2/lib/Arm/model_encoder.h new file mode 100644 index 0000000..b4b07f5 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/model_encoder.h @@ -0,0 +1,75 @@ +/** + * @file model_sensor_sensors.h + * @author Steve Ding, Oliver Philbin-Briscoe, Colin Gallacher + * @version V1.1.0 + * @date 26-Janurary-2023 + * @brief generic sensor object + * + * @attention For prototype example only + * V1.1.0 - added offset calculations for current and inkwell sensors + * + */ + +#ifndef MODEL_ENCODER_H +#define MODEL_ENCODER_H + +#include "hardware_pins.h" +#include "velocity_estimation.h" +#include "QuadEncoder.h" + +class model_encoder +{ +public: + QuadEncoder *_encoder; + + void initialize_encoder(uint8_t rotationalDirection, float offset, float resolution, uint8_t port); + + void reset_encoder(void); + + void set_current_angle_es(float offset); + + void poll_encoder_angle(void); + + float get_angle_multi(void); + + float get_angle_single(void); + + float get_full_angle_from_tick() + { + uint32_t tick = _encoder->read(); + return (float)tick * 360.0 / (float)_resolution; + } + + void set_parameters(uint8_t direction, float offset, float resolution); + + /** + * Main logic loop for calculating detected encoder velocity + * + * @param currentTime current micros count + */ + void velocityEstimation(void); + + float getVelocity(void); + +private: + // QuadEncoder *_encoder; + int32_t _offset; + int32_t _resolution; + uint8_t _port; + int32_t _quad_enc_pos; + uint8_t _pinA; + uint8_t _pinB; + + float _angle; + float _angle_single; + float _angle_multi; + float _angularVelocity; + velocity_estimation _velocityEstimation; + boolean _is_multi_turn; + int _turn_count; + float _last_angle; + // Offset compared to boot position + float _zero_angle_offset; +}; + +#endif \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/model_sensor.cpp b/teensy40_brushed_v2/lib/Arm/model_sensor.cpp new file mode 100644 index 0000000..a6fb875 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/model_sensor.cpp @@ -0,0 +1,94 @@ +/** + * @file model_sensor.cpp + * @author Vincent Boucher, Steve Ding + * @version V1.0.0 + * @date 30-May-2023 + * @brief current sensor object + * + * @attention For prototype example only + * V1.0.0 - created + * + */ +#include "model_sensor.h" + +void model_sensor::initialize_sensor(uint8_t pin) +{ + _sensor_value = 0; + _sensor_offset = 0; + + _pin = pin; + + _initialize_adc(); + + pinMode(pin, INPUT); + + delay(10); + + for (uint8_t i = 0; i < 40; i++) + { + _update_sensor_value(); + _sensor_offset = _sensor_offset + _sensor_value; + } + + _sensor_offset = _sensor_offset / 40; + + _sensor_offset = 1862 - _sensor_offset; +} + +void model_sensor::reset_sensor(void) +{ + _sensor_value = 0; +} + +float model_sensor::read_sensor_value(void) +{ + _update_sensor_value(); + float sensorValue = _sensor_value + _sensor_offset; + _current16 = sensorValue - 1862; + _raw_voltage = sensorValue * (3.3 / 4095.0); + _current = (_raw_voltage - 1.5) * 2; + return _current; +} + +float model_sensor::get_current(void) +{ + return _current; +} + +int16_t model_sensor::get_current_16(void) +{ + return _current16; +} + +float model_sensor::get_raw_voltage(void) +{ + return _raw_voltage; +} + +void model_sensor::_update_sensor_value(void) +{ + // if (_pin == CURRENT_SENSE_A1 || + // _pin == CURRENT_SENSE_B1 || + // _pin == CURRENT_SENSE_A2 || + // _pin == CURRENT_SENSE_B2) { + // _sensor_value = _adc->adc1->analogRead(_pin); + // }else{ + _sensor_value = _adc->adc0->analogRead(_pin); + // } +} + +void model_sensor::_initialize_adc(void) +{ + + _adc = new ADC(); + + _adc->adc0->setAveraging(4); + _adc->adc0->setResolution(12); + _adc->adc0->setConversionSpeed(ADC_CONVERSION_SPEED::VERY_HIGH_SPEED); + _adc->adc0->setSamplingSpeed(ADC_SAMPLING_SPEED::VERY_HIGH_SPEED); + + _adc->adc1->setAveraging(4); + _adc->adc1->setResolution(12); + _adc->adc1->setConversionSpeed(ADC_CONVERSION_SPEED::VERY_HIGH_SPEED); + _adc->adc1->setSamplingSpeed(ADC_SAMPLING_SPEED::VERY_HIGH_SPEED); +} \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/model_sensor.h b/teensy40_brushed_v2/lib/Arm/model_sensor.h new file mode 100644 index 0000000..d422c03 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/model_sensor.h @@ -0,0 +1,51 @@ +/** + * @file model_sensor_sensors.h + * @author Steve Ding, Oliver Philbin-Briscoe, Colin Gallacher + * @version V1.1.0 + * @date 26-Janurary-2023 + * @brief generic sensor object + * + * @attention For prototype example only + * V1.1.0 - added offset calculations for current and inkwell sensors + * + */ + +#ifndef MODEL_SENSOR_H +#define MODEL_SENSOR_H + +#include "Arduino.h" +#include +#include "hardware_pins.h" + +class model_sensor +{ +public: + void initialize_sensor(uint8_t pin); + + void reset_sensor(void); + + float read_sensor_value(void); + + float get_current(void); + + int16_t get_current_16(void); + + float get_raw_voltage(void); + +private: + ADC *_adc; + + int32_t _sensor_value; + uint8_t _pin; + float _current; + float _raw_voltage; + int16_t _current16; + + int32_t _sensor_offset; + + void _initialize_adc(void); + + void _update_sensor_value(void); +}; + +#endif \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/motor.h b/teensy40_brushed_v2/lib/Arm/motor.h new file mode 100644 index 0000000..e00e3ef --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/motor.h @@ -0,0 +1,366 @@ +#pragma once +#include "rotation2d.h" +#include "vector2d.h" +#include +/** + * definition of "In the x,y plane of the robot" : + * Where y is the vertical axis centered at the shoulder joint and x is parallel to the lateral movement of the arm. + */ + +/** + * Struct that stores the model of the motor. + * @author David Ly + */ +struct MotorModel +{ +public: + double stallCurrent, stallTorque, maxVoltage, maxRPM, resistance, Kt, Kv, gearRatio, freeCurrent; + /** + * Creates a new MotorModel with given parameters. + * @param a_stallCurrent The stall current of the motor in Amps. + * @param a_stallTorque The stall torque of the motor in Nm. + * @param a_maxVoltage The max voltage of the motor in Volts. + * @param a_maxRPM The max RPM of the motor in RPM. + * @param ratio The gear ratio of the motor. + */ + MotorModel(double a_stallCurrent, double a_stallTorque, double a_maxVoltage, double a_maxRPM, double a_freeCurrent, double ratio) + { + stallCurrent = a_stallCurrent; + stallTorque = a_stallTorque / ratio; + maxVoltage = a_maxVoltage; + maxRPM = a_maxRPM * ratio; + freeCurrent = a_freeCurrent; + gearRatio = ratio; + resistance = a_maxVoltage / a_stallCurrent; // based on ohm's law: in Ohms + Kt = stallTorque / stallCurrent; // Torque constant: Nm/A + Kv = maxRPM / (maxVoltage - freeCurrent * resistance); // Velocity constant: RPM/V + } + /** + * @return Velocity Constant in RPS/V + */ + double getKvRPS() + { + return Kv / 60.0; + } +}; +/** + * Struct that stores the state of the motor in terms of velocity and torque. + * @author David Ly + */ +struct MotorState +{ + /** + * Creates a new MotorState with given parameters. + * @param vel The velocity of the motor in RPS. + * @param torque The torque of the motor in Nm. + */ + MotorState(double vel, double torque) : vel(vel), + torque(torque) + { + } + double vel; + double torque; +}; +/** + * Struct that stores the pose of the arm in terms of the angles of the joints. + * @author David Ly + */ +struct ArmPose +{ + /** + * Creates a new ArmPose with given parameters. + * @param shoulder The angle of the shoulder joint. + * @param elbow The angle of the elbow joint. + * @param wrist The angle of the wrist joint. + */ + ArmPose(Rotation2d shoulder, Rotation2d elbow, Rotation2d wrist) : shoulder(shoulder), + elbow(elbow), + wrist(wrist) + { + } + Rotation2d shoulder; + Rotation2d elbow; + Rotation2d wrist; +}; +/** + * Defines the properties of a joint. + * @author David Ly + */ +struct JointProperties +{ +public: + const double mass, length; + const Vector2d cm_pos; + /** + * Creates a new JointProperties with given parameters. + * x, y position of the center of mass is relative to the center of rotation of the joint. + * Where x parallel to the longest side of the joint and y parallel to the shortest side of the joint. + * @param mass The mass of the joint in kg. + * @param cm_x The x position of the center of mass of the joint in m. + * @param cm_y The y position of the center of mass of the joint in m. + * @param length The length of the joint in m. + */ + JointProperties(double mass, double cm_x, double cm_y, double length) : mass(mass), + cm_pos(cm_x, cm_y), + length(length) + { + } + /** + * Creates a new JointProperties with given parameters. + * Center of mass position is relative to the center of rotation of the joint. + * Where x parallel to the longest side of the joint and y parallel to the shortest side of the joint. + * @param mass The mass of the joint in kg. + * @param cm The position of the center of mass of the joint in m. + * @param length The length of the joint in m. + */ + JointProperties(double mass, Vector2d cm, double length) : mass(mass), + cm_pos(cm.getX(), cm.getY()), + length(length) + { + } +}; + +#define GRAVITY 9.81 + +MotorModel shoulder_motor(111, 5.28, 24, 3210, 0.696, 120); +MotorModel elbow_motor(81.9, 2.49, 24, 4300, 0.497, 1); // todo: find ratio +MotorModel wrist_motor(24.5, GRAVITY * 90.0 / 100.0, 24, 13, 0.7, 1); // todo: find ratio + +// Distance of links in m, CM... +JointProperties shoulderProperties(1, 1, 1, 1); +JointProperties elbowProperties(1, 1, 1, 1); +JointProperties wristProperties(1, 1, 1, 1); + +#define ESTIMATED_HELDMASS_OFFSET 0.75 +/** + * Calculates the position of the end of the shoulder joint. + * In the x,y plane of the robot + * @param buf The vector to store the position of the end of the shoulder joint. + * @param armPose The pose of the arm. + */ +void getShoulderEndPosition(Vector2d *buf, ArmPose &armPose) +{ + Vector2d shoulderPositionVector(shoulderProperties.length, armPose.shoulder); + *buf += shoulderPositionVector; +} + +/** + * Calculates the position of the end of the elbow joint. + * In the x,y plane of the robot + * @param buf The vector to store the position of the end of the elbow joint. + * @param armPose The pose of the arm. + */ +void getElbowEndPosition(Vector2d *buf, ArmPose &armPose) +{ + getShoulderEndPosition(buf, armPose); + Rotation2d temp(armPose.shoulder.getRad() + armPose.elbow.getRad()); + Vector2d elbowPositionVector(elbowProperties.length, temp); + *buf += elbowPositionVector; +} + +/** + * Calculates the position of the end of the wrist joint. Asumming an offset for the point mass at the end of the joint + * In the x,y plane of the robot + * @param buf The vector to store the position of the end of the wrist joint. + * @param armPose The pose of the arm. + */ +void getWristEndPosition(Vector2d *buf, ArmPose &armPose) +{ + getElbowEndPosition(buf, armPose); + Rotation2d temp(armPose.shoulder.getRad() + armPose.elbow.getRad() + armPose.wrist.getRad()); + Vector2d wristPositionVector(wristProperties.length * ESTIMATED_HELDMASS_OFFSET, temp); + *buf += wristPositionVector; +} +/** + * Calculates the position of the center of mass of the held mass times the heldmass. + * In the x,y plane of the robot + * @param buf The vector to store the position of the center of mass of the held mass. + * @param armPose The pose of the arm. + * @param heldMass The mass of the held mass in kg. + */ +void calculateCenterMassofHeldMass(Vector2d *buf, ArmPose &armPose, double heldMass) +{ + getWristEndPosition(buf, armPose); + *buf *= heldMass; +} + +/** + * Calculates the center of mass * mass of the joint. + * In the x,y plane of the robot. + * @param buf OUT The vector to store the position of the center of mass * mass of the joint. + * @param jointPose The pose of the joint. + * @param properties The properties of the joint. + */ +void computeJointCM(Vector2d *buf, Rotation2d &jointPose, JointProperties &properties) +{ + // function assumes that buf is already filled with the value of the joint position in x,y + //(joint position is not hte same as joint cm) + Vector2d orientedJoint(0, 0); + orientedJoint += properties.cm_pos; // copy cm position vector + Vector2d::rotateBy(orientedJoint, jointPose); // orient cm position vector properly + *buf += orientedJoint; + *buf *= properties.mass; // cm * mass of the joint +} + +/** + * Calculates the torque on the wrist joint. + * In the x,y plane of the robot. + * @param armPose The pose of the arm. + * @param heldMass The mass of the held mass in kg. + * @return The torque on the wrist joint in Nm. + */ +double computeWristTorque(ArmPose &armPose, double heldMass) +{ + // Origin to CM of held mass + Vector2d heldMassPos(0, 0); // + calculateCenterMassofHeldMass(&heldMassPos, armPose, heldMass); + + // Origin to CM of wrist + Vector2d wristMass(0, 0); + getElbowEndPosition(&wristMass, armPose); + computeJointCM(&wristMass, armPose.wrist, wristProperties); + + double totalMass = wristProperties.mass + heldMass; + Vector2d centerMass(0, 0); + centerMass += wristMass; + centerMass += heldMassPos; + centerMass *= 1.0 / totalMass; + + Vector2d wristPosition(0, 0); + getElbowEndPosition(&wristPosition, armPose); + + // Wrist joint to new CM of wrist with held mass + Vector2d wristJointToCM(0, 0); + wristJointToCM += centerMass; + wristJointToCM -= wristPosition; + + // pendulum torque equation: torque = -mg/L sin(theta), theta is measured from the y-axis + // used cos, since angle is measured from the x-axis, so it would be sin(90deg-theta) = cos(theta) + double torque = -GRAVITY * totalMass / wristJointToCM.getLength() * wristJointToCM.getOrientation().getCos(); + return torque; +} + +/** + * Calculates the torque on the elbow joint. + * In the x,y plane of the robot. + * @param armPose The pose of the arm. + * @param heldMass The mass of the held mass in kg. + * @return The torque on the elbow joint in Nm. + */ +double computeElbowTorque(ArmPose &armPose, double heldMass) +{ + Vector2d heldMassPos(0, 0); + calculateCenterMassofHeldMass(&heldMassPos, armPose, heldMass); + + Vector2d wristMass(0, 0); + getElbowEndPosition(&wristMass, armPose); + computeJointCM(&wristMass, armPose.wrist, wristProperties); + + Vector2d elbowMass(0, 0); + getShoulderEndPosition(&elbowMass, armPose); + computeJointCM(&elbowMass, armPose.elbow, elbowProperties); + + double totalMass = elbowProperties.mass + wristProperties.mass + heldMass; + Vector2d centerMass(0, 0); + centerMass += wristMass; + centerMass += elbowMass; + centerMass += heldMassPos; + centerMass *= 1.0 / totalMass; + + Vector2d elbowPosition(0, 0); + getShoulderEndPosition(&elbowPosition, armPose); + + Vector2d elbowJointToCM(0, 0); + elbowJointToCM += centerMass; + elbowJointToCM -= elbowPosition; + + // pendulum torque equation: torque = -mg/L sin(theta), theta is measured from the y-axis + // used cos, since angle is measured from the x-axis, so it would be sin(90deg-theta) = cos(theta) + double torque = -GRAVITY * totalMass / elbowJointToCM.getLength() * elbowJointToCM.getOrientation().getCos(); + return torque; +} +/** + * Calculates the torque on the shoulder joint. + * In the x,y plane of the robot. + * @param armPose The pose of the arm. + * @param heldMass The mass of the held mass in kg. + * @return The torque on the shoulder joint in Nm. + */ +double computeShoulderTorque(ArmPose &armPose, double heldMass) +{ + Vector2d heldMassPos(0, 0); + calculateCenterMassofHeldMass(&heldMassPos, armPose, heldMass); + + Vector2d wristMass(0, 0); + getElbowEndPosition(&wristMass, armPose); + computeJointCM(&wristMass, armPose.wrist, wristProperties); + + Vector2d elbowMass(0, 0); + getShoulderEndPosition(&wristMass, armPose); + computeJointCM(&elbowMass, armPose.elbow, elbowProperties); + + Vector2d shoulderMass(0, 0); + computeJointCM(&shoulderMass, armPose.shoulder, shoulderProperties); + + double totalMass = shoulderProperties.mass + elbowProperties.mass + wristProperties.mass + heldMass; + Vector2d centerMass(0, 0); + centerMass += wristMass; + centerMass += elbowMass; + centerMass += shoulderMass; + centerMass += heldMassPos; + centerMass *= 1.0 / totalMass; + + Vector2d shoulderPosition(0, 0); + Vector2d shoulderJointToCM(0, 0); + shoulderJointToCM += centerMass; + shoulderJointToCM -= shoulderPosition; + + // pendulum torque equation: torque = -mg/L sin(theta), theta is measured from the y-axis + // used cos, since angle is measured from the x-axis, so it would be sin(90deg-theta) = cos(theta) + double torque = -GRAVITY * totalMass / shoulderJointToCM.getLength() * shoulderJointToCM.getOrientation().getCos(); + return torque; +} + +/** + * Calculates the voltage required to achieve the given state. + * @param requiredState The state to achieve. + * @param model The model of the motor. + */ +double findVoltage(MotorState &requiredState, MotorModel &model) +{ + return requiredState.torque / model.Kt * model.resistance + requiredState.vel * model.Kv; +} + +/** + * Calculates the state of the arm to maintain the given pose. + * @param pose Current arm pose. + * @param heldMass The mass of the held mass in kg. + */ +void maintainState(ArmPose &pose, double heldMass) +{ + MotorState wristMotorState(0, computeWristTorque(pose, heldMass)); + MotorState elbowMotorState(0, computeElbowTorque(pose, heldMass)); + MotorState shoulderMotorState(0, computeShoulderTorque(pose, heldMass)); + + double wristMotorVoltage = findVoltage(wristMotorState, wrist_motor); + double elbowMotorVoltage = findVoltage(elbowMotorState, elbow_motor); + double shoulderMotorVoltage = findVoltage(shoulderMotorState, shoulder_motor); +} + +JointProperties proto(.2, .07, 0, .1); + +double calculateTorque(const Rotation2d pos) +{ + Vector2d cm_pos(0, 0); + cm_pos += proto.cm_pos; + Vector2d::rotateBy(cm_pos, pos); + return -GRAVITY * proto.mass * cm_pos.getLength() * cm_pos.getOrientation().getSin(); // or getCos()? +} + +void maintainStateProto(Rotation2d pos, double *output) +{ + double torque = calculateTorque(pos); + MotorState motorState(0, torque); + double voltage = findVoltage(motorState, wrist_motor); + *output = voltage; +} \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/pid.cpp b/teensy40_brushed_v2/lib/Arm/pid.cpp new file mode 100644 index 0000000..082be05 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/pid.cpp @@ -0,0 +1,130 @@ +/** + * Copyright 2019 Bradley J. Snyder + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef _PID_SOURCE_ +#define _PID_SOURCE_ + +#include +#include +#include +#include "pid.h" + +using namespace std; + +class PIDImpl +{ +public: + PIDImpl(double dt, double max, double min, double Kp, double Kd, double Ki); + ~PIDImpl(); + double calculate(double setpoint, double pv); + void set_PID(double Kp, double Ki, double Kd); + +private: + double _dt; + double _max; + double _min; + double _Kp; + double _Kd; + double _Ki; + double _pre_error; + double _integral; +}; + +PID::PID(double dt, double max, double min, double Kp, double Kd, double Ki) +{ + pimpl = new PIDImpl(dt, max, min, Kp, Kd, Ki); +} +double PID::calculate(double setpoint, double pv) +{ + return pimpl->calculate(setpoint, pv); +} + +void PID::set_PID(double Kp, double Ki, double Kd) +{ + pimpl->set_PID(Kp, Ki, Kd); +} + +PID::~PID() +{ + delete pimpl; +} + +/** + * Implementation + */ +PIDImpl::PIDImpl(double dt, double max, double min, double Kp, double Kd, double Ki) : _dt(dt), + _max(max), + _min(min), + _Kp(Kp), + _Kd(Kd), + _Ki(Ki), + _pre_error(0), + _integral(0) +{ +} + +double PIDImpl::calculate(double setpoint, double pv) +{ + Serial.printf("setpoint: %f, pv: %f, ", setpoint, pv); + + // Calculate error + double error = setpoint - pv; + + // Proportional term + double Pout = _Kp * error; + + // Integral term + _integral += error * _dt; + double Iout = _Ki * _integral; + + // Derivative term + double derivative = (error - _pre_error) / _dt; + double Dout = _Kd * derivative; + + // Calculate total output + double output = Pout + Iout + Dout; + Serial.printf("Pout: %f, Iout: %f, Dout: %f, temp_output: %f, ", Pout, Iout, Dout, output); + + // Restrict to max/min + if (output > _max) + output = _max; + else if (output < _min) + output = _min; + + // Save error to previous error + _pre_error = error; + Serial.printf("output: %f\n", output); + return output; +} + +void PIDImpl::set_PID(double Kp, double Ki, double Kd) +{ + _Kp = Kp; + _Ki = Ki; + _Kd = Kd; +} + +PIDImpl::~PIDImpl() +{ +} + +#endif \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/pid.h b/teensy40_brushed_v2/lib/Arm/pid.h new file mode 100644 index 0000000..606c279 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/pid.h @@ -0,0 +1,47 @@ +/** + * Copyright 2019 Bradley J. Snyder + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef _PID_H_ +#define _PID_H_ + +class PIDImpl; +class PID +{ +public: + // Kp - proportional gain + // Ki - Integral gain + // Kd - derivative gain + // dt - loop interval time + // max - maximum value of manipulated variable + // min - minimum value of manipulated variable + PID(double dt, double max, double min, double Kp, double Kd, double Ki); + + // Returns the manipulated variable given a setpoint and current process value + double calculate(double setpoint, double pv); + ~PID(); + void set_PID(double Kp, double Ki, double Kd); + +private: + PIDImpl *pimpl; +}; + +#endif \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/rotation2d.h b/teensy40_brushed_v2/lib/Arm/rotation2d.h new file mode 100644 index 0000000..580b5b8 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/rotation2d.h @@ -0,0 +1,130 @@ +#pragma once +#include +#define PI 3.14159 +/** + * A simple class that represents a 2d Rotation regardless of unit. + * @author David Ly + */ +class Rotation2d +{ +private: + double _theta_rad, _sin, _cos; + +public: + /** + * Creates a new Rotation2d with given angle in radians. + * @param theta_rad The angle of the rotation in radians. + */ + explicit Rotation2d(double theta_rad) + { + _theta_rad = 0; + _sin = 0; + _cos = 0; + setAngleRad(theta_rad); + } + + /** + * Creates a new Rotation2d with given angle in degrees. + * @param theta_deg The angle of the rotation in degrees. + */ + static Rotation2d *getRotationFromDeg(double theta) + { + return new Rotation2d(theta / 180 * PI); + } + + /** + * Creates a new Rotation2d with given angle in rotations. + * @param theta The angle of the rotation in rotations. + */ + static Rotation2d *getRotationFromRotation(double theta) + { + return new Rotation2d(theta * PI); + } + + /** + * Sets the angle of the rotation in radians. + * @return The angle of the rotation in radians. + */ + void setAngleRad(double theta_rad) + { + _theta_rad = theta_rad; + _sin = sin(_theta_rad); + _cos = cos(_theta_rad); + } + + /** + * Gets the angle of the rotation in radians. + * @return The angle of the rotation in radians. + */ + double getRad() const + { + return _theta_rad; + } + + /** + * Gets the angle of the rotation in degrees. + * @return The angle of the rotation in degrees. + */ + double getDeg() const + { + return _theta_rad * 180 / PI; + } + + /** + * Gets the angle of the rotation in rotations. + * @return The angle of the rotation in rotations. + */ + double getRotation() const + { + return _theta_rad / (2 * PI); + } + + /** + * Gets the sin of the rotation. + * @return The sin of the rotation. + */ + double getSin() const { return _sin; } + + /** + * Gets the cos of the rotation. + * @return The cos of the rotation. + */ + double getCos() const { return _cos; } + + /** + * Adds the given rotation to this rotation. + * @param rot The rotation to add to this rotation. + */ + void operator+=(Rotation2d rot) + { + this->setAngleRad(this->_theta_rad + rot._theta_rad); + } + /** + * Subtracts the given rotation from this rotation. + * @param rot The rotation to subtract from this rotation. + */ + void operator-=(Rotation2d rot) + { + this->setAngleRad(this->_theta_rad - rot._theta_rad); + } + /** + * Adds the given rotation to this rotation. + * Returns a new object that's dynamically allocated + * @param rot The rotation to add to this rotation. + * @return The sum of the two rotations. + */ + Rotation2d *operator+(Rotation2d rot) const + { + return new Rotation2d(this->_theta_rad + rot._theta_rad); + } + /** + * Subtracts the given rotation from this rotation. + * Returns a new object that's dynamically allocated + * @param rot The rotation to subtract from this rotation. + * @return The difference of the two rotations. + */ + Rotation2d *operator-(Rotation2d rot) const + { + return new Rotation2d(this->_theta_rad - rot._theta_rad); + } +}; \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/vector2d.cpp b/teensy40_brushed_v2/lib/Arm/vector2d.cpp new file mode 100644 index 0000000..4c63865 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/vector2d.cpp @@ -0,0 +1,77 @@ +#pragma once +#include "vector2d.h" +#include +#define PI 3.14159 + +Vector2d::Vector2d(double x, double y) : _orientation(0), + _x(0), + _y(0), + _length(0) +{ + updateVectorfromCartesian(x, y); +} + +Vector2d::Vector2d(double length, Rotation2d orientation) : _orientation(0), + _x(0), + _y(0), + _length(0) +{ + updateVectorfromPolar(length, orientation); +} + +void Vector2d::updateVectorfromCartesian(double x, double y) +{ + _x = x; + _y = y; + _length = sqrt(x * x + y * y); + Rotation2d temp(atan2(y, x)); + _orientation += temp; +} +void Vector2d::updateVectorfromPolar(double l, Rotation2d orientation) +{ + _length = l; + _orientation.setAngleRad(orientation.getRad()); + _x = _length * _orientation.getCos(); + _y = _length * _orientation.getSin(); +} + +double Vector2d::getX() const { return _x; } +double Vector2d::getY() const { return _y; } +double Vector2d::getLength() const { return _length; } +Rotation2d Vector2d::getOrientation() const { return _orientation; } + +void Vector2d::operator*=(double scalar) +{ + this->updateVectorfromCartesian(_x * scalar, _y * scalar); +} + +void Vector2d::operator+=(Vector2d b) +{ + this->updateVectorfromCartesian(_x + b.getX(), _y + b.getY()); +} +void Vector2d::operator-=(Vector2d b) +{ + this->updateVectorfromCartesian(_x - b.getX(), _y - b.getY()); +} +Vector2d *Vector2d::operator*(double scalar) const +{ + return new Vector2d(scalar * _x, scalar * _y); +} +Vector2d *Vector2d::operator+(Vector2d b) const +{ + return new Vector2d(_x + b.getX(), _y + b.getY()); +} +Vector2d *Vector2d::operator-(Vector2d b) const +{ + return new Vector2d(_x - b.getX(), _y - b.getY()); +} + +double Vector2d::dot(Vector2d a, Vector2d b) +{ + return a.getX() * b.getX() + a.getY() * b.getY(); +} +void Vector2d::rotateBy(Vector2d &a, Rotation2d theta) +{ + Rotation2d temp(a.getOrientation().getRad() + theta.getRad()); + a.updateVectorfromPolar(a.getLength(), temp); +} \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/vector2d.h b/teensy40_brushed_v2/lib/Arm/vector2d.h new file mode 100644 index 0000000..f140d95 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/vector2d.h @@ -0,0 +1,117 @@ +#pragma once +#include "rotation2d.h" + +/** + * A simple class that represents a vector in 2d space. + * @author David LY + */ +class Vector2d +{ +private: + double _x, _y; + double _length; + Rotation2d _orientation; + +public: + /** + * Creates a new vector with given x and y components. + * @param x The x component of the vector. + * @param y The y component of the vector. + */ + + Vector2d(double x, double y); + /** + * Creates a new vector with given length and angle. + * @param length The length of the vector. + * @param orientation The angle of the vector. + */ + + Vector2d(double length, Rotation2d orientation); + /** + * Change vector with given x and y components. + * @param x The x component of the vector. + * @param y The y component of the vector. + */ + + void updateVectorfromCartesian(double x, double y); + /** + * Change vector with given length and angle. + * @param length The length of the vector. + * @param orientation The angle of the vector. + */ + void updateVectorfromPolar(double l, Rotation2d orientation); + + /** + * @return The x component of the vector. + */ + double getX() const; + + /** + * @return The y component of the vector. + */ + double getY() const; + + /** + * @return The length of the vector. + */ + double getLength() const; + + /** + * @return The orientaion of the vector. + */ + Rotation2d getOrientation() const; + + /** + * Scalar multiplication of the vector. + * @param scalar The scalar to multiply the vector by. + */ + void operator*=(double scalar); + + /** + * Vector addition of the vector. + * @param b The vector to add to the vector. + */ + void operator+=(Vector2d b); + + /** + * Vector subtraction of the vector. + * @param b The vector to subtract from the vector. + */ + + void operator-=(Vector2d b); + /** + * Scalar multiplication of the vector. + * New dynamic Vector2d object is created. + * @return new Vector2d multiplied by the scalar. + */ + Vector2d *operator*(double scalar) const; + + /** + * Vector addition of the vector. + * New dynamic Vector2d object is created. + * @return new Vector2d added to the vector. + */ + Vector2d *operator+(Vector2d b) const; + + /** + * Vector subtraction of the vector. + * New dynamic Vector2d object is created. + * @return new Vector2d subtracted from the vector. + */ + Vector2d *operator-(Vector2d b) const; + + /** + * Dot Product computation of two vector. + * @param a The first vector. + * @param b The second vector. + * @return The dot product of two vector. + */ + static double dot(Vector2d a, Vector2d b); + + /** + * Rotation of a vector + * @param a The vector to rotate. This vector is changed by the method. + * @param theta The angle to rotate the vector by. + */ + static void rotateBy(Vector2d &a, Rotation2d theta); +}; \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/velocity_estimation.cpp b/teensy40_brushed_v2/lib/Arm/velocity_estimation.cpp new file mode 100644 index 0000000..93bdf7a --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/velocity_estimation.cpp @@ -0,0 +1,150 @@ +#include "velocity_estimation.h" + +void velocity_estimation::initialize_parameters(float ppr, float error, float timeScale, uint8_t skip, uint32_t delay) +{ + _ppr = ppr; + _errorMargin = error; + _timeScale = timeScale; + _SKIP = skip; + _maxDelay = delay; + + _n = 0; + _size = 2; + _firstTime = 0; + _firstPos = 0; + + _foaw.newPos = 0; + _foaw.newtime = 0; + _foaw.lastPos = 0; + _foaw.lasttime = 0; + _foaw.k = 0; + + _mult = 360.0f * 1000000.0f / _ppr; + + for (uint8_t i = 0; i < 2; i++) + { + _coefficients[i] = 0.0; + } + + for (uint8_t i = 0; i < 5; i++) + { + _pastValues[i] = 0.0; + _sortedIndex[i] = i; + } + + for (uint8_t i = 0; i < FILTER_SIZE; i++) + { + _positions[i] = 0; + _timeStamps[i] = 0; + } + + for (uint8_t i = 0; i < 32; i++) + { + _foaw._positions[i] = 0; + _foaw._timeStamps[i] = 0; + } +} + +void velocity_estimation::update_readings(int32_t position, uint32_t timeStamp) +{ + _newEvent = 1; + + uint8_t count = _n % FILTER_SIZE; + + _foaw.newPos = position; + _foaw.newtime = timeStamp; + + _n++; +} + +int32_t velocity_estimation::get_last_position(void) +{ + return _positions[_n]; +} + +float velocity_estimation::foaw(int best) +{ + // As implemented by Steve Sinclair (https://github.com/radarsat1/FOAW/blob/master/foaw.c) + // adapted to our data by Antoine Weill--Duflos + int i, j, l; + uint32_t bad; + float b, p_mean, p_out, t_mean, t_out, dt; + float velocity = 0.0; + const float pos_err_max = 1.0; + const int time_err_max = 5; + const uint32_t max_outlier = 8; + + /* circular buffer */ + _foaw.k = (_foaw.k + 1) % size; + _foaw._positions[_foaw.k] = _foaw.newPos; + _foaw._timeStamps[_foaw.k] = _foaw.newtime; + + for (i = 1; i < size; i++) // size is n + { + // basically doing end fit instead of best fit -> why? + dt = (float)(_foaw._timeStamps[_foaw.k] - _foaw._timeStamps[(_foaw.k - i + size) % size]); + if (dt != 0) + { + + if (best) + { + b = 0.0f; + for (l = 0; l < (i + 1); l++) + { + b += (i - 2 * l) * _foaw._positions[(_foaw.k - l + size) % size]; + } + b = 6.0f * (float)b / ((dt * (i + 1) * (i + 2))); + } + else + { + b = (float)(_foaw._positions[_foaw.k] - _foaw._positions[(_foaw.k - i + size) % size]) / dt; + } + } + else + { + b = 0.0; + continue; + } + + bad = 0; + for (j = 1; j < i; j++) + { + p_out = _foaw._positions[(_foaw.k - j + size) % size]; + t_out = _foaw._timeStamps[(_foaw.k - j + size) % size]; + p_mean = _foaw._positions[_foaw.k] + b * (t_out - _foaw._timeStamps[_foaw.k]); + t_mean = (p_out - _foaw._positions[_foaw.k]) / b + _foaw._timeStamps[_foaw.k]; + + if (p_mean + pos_err_max < p_out || p_mean - pos_err_max > p_out || t_mean + time_err_max < t_out || t_mean - time_err_max > t_out) + { + bad++; + if (bad >= max_outlier) + break; + } + } + if (bad >= max_outlier) + break; + + velocity = _mult * b; // deg/s formulation + // velocity = b / _ppr * 2 * _pi * 1000000.0; // rad/s formulation + } + return velocity; +} + +void velocity_estimation::_compare_swap(int a, int b) +{ + int indexA = _sortedIndex[a]; + int indexB = _sortedIndex[b]; + + if (indexA > 4 || indexB > 4) + { + indexA = 0; + indexB = 1; + } + + if (_pastValues[indexA] < _pastValues[indexB]) + { + int temp = _sortedIndex[a]; + _sortedIndex[a] = _sortedIndex[b]; + _sortedIndex[b] = temp; + } +} \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/Arm/velocity_estimation.h b/teensy40_brushed_v2/lib/Arm/velocity_estimation.h new file mode 100644 index 0000000..2d16ca1 --- /dev/null +++ b/teensy40_brushed_v2/lib/Arm/velocity_estimation.h @@ -0,0 +1,62 @@ +#include +#include "Arduino.h" + +class velocity_estimation +{ +public: + void initialize_parameters(float ppr, float error, float timeScale, uint8_t skip, uint32_t delay); + + void update_readings(int32_t position, uint32_t timeStamp); + + int32_t get_last_position(void); // may be depreciated + + // float htt(uint32_t currentTime); + + typedef struct + { + int32_t _positions[64]; + uint32_t _timeStamps[64]; + float _vel[64]; + float _c; + int k; + int32_t lastPos; + uint32_t lasttime; + int32_t newPos; + uint32_t newtime; + } foaw_vars; + + float foaw(int best); + +private: + const uint8_t FILTER_SIZE = 16; + + const float _pi = 3.141592654; + + float _ppr; + float _errorMargin; + float _timeScale; + uint8_t _SKIP; + uint32_t _maxDelay; + float _mult = 0.0f; + uint32_t size = 32; + + float _coefficients[2]; + uint8_t _size; + uint8_t _n; + float _previousEvent; + uint8_t _newEvent; // may not be necessary + uint32_t _firstTime; + int32_t _firstPos; + float _pastValues[5]; + uint16_t _index; + uint32_t _processTime; + + int _sortedIndex[5]; + + foaw_vars _foaw; + + int32_t _positions[16]; + uint32_t _timeStamps[16]; + + void _compare_swap(int a, int b); +}; \ No newline at end of file diff --git a/teensy40_brushed_v2/lib/README b/teensy40_brushed_v2/lib/README new file mode 100644 index 0000000..6debab1 --- /dev/null +++ b/teensy40_brushed_v2/lib/README @@ -0,0 +1,46 @@ + +This directory is intended for project specific (private) libraries. +PlatformIO will compile them to static libraries and link into executable file. + +The source code of each library should be placed in a an own separate directory +("lib/your_library_name/[here are source files]"). + +For example, see a structure of the following two libraries `Foo` and `Bar`: + +|--lib +| | +| |--Bar +| | |--docs +| | |--examples +| | |--src +| | |- Bar.c +| | |- Bar.h +| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html +| | +| |--Foo +| | |- Foo.c +| | |- Foo.h +| | +| |- README --> THIS FILE +| +|- platformio.ini +|--src + |- main.c + +and a contents of `src/main.c`: +``` +#include +#include + +int main (void) +{ + ... +} + +``` + +PlatformIO Library Dependency Finder will find automatically dependent +libraries scanning project source files. + +More information about PlatformIO Library Dependency Finder +- https://docs.platformio.org/page/librarymanager/ldf.html diff --git a/teensy40_brushed_v2/platformio.ini b/teensy40_brushed_v2/platformio.ini new file mode 100644 index 0000000..a0eaa17 --- /dev/null +++ b/teensy40_brushed_v2/platformio.ini @@ -0,0 +1,19 @@ +; PlatformIO Project Configuration File +; +; Build options: build flags, source filter +; Upload options: custom upload port, speed and extra flags +; Library options: dependencies, extra library storages +; Advanced options: extra scripting +; +; Please visit documentation for the other options and examples +; https://docs.platformio.org/page/projectconf.html + +[env:teensy40] +platform = teensy +board = teensy40 +framework = arduino +monitor_speed = 115200 +lib_deps = + jchristensen/movingAvg@^2.3.1 + frankjoshua/Rosserial Arduino Library@^0.9.1 + diff --git a/teensy40_brushed_v2/src/common.h b/teensy40_brushed_v2/src/common.h new file mode 100644 index 0000000..02c1782 --- /dev/null +++ b/teensy40_brushed_v2/src/common.h @@ -0,0 +1 @@ +#define USE_ROS_FIRMWARE 1 \ No newline at end of file diff --git a/teensy40_brushed_v2/src/main.cpp b/teensy40_brushed_v2/src/main.cpp new file mode 100644 index 0000000..d968a53 --- /dev/null +++ b/teensy40_brushed_v2/src/main.cpp @@ -0,0 +1,509 @@ +#include "common.h" +#if USE_ROS_FIRMWARE == 0 +#include +#include "hardware_pins.h" +#include "driver_motor.h" +#include "model_encoder.h" +#include "model_sensor.h" +#include "motor.h" + +#include + +// CONFIGURATION +#define CONFIG_NON_ROS 1 +#define CONFIG_DIR_TESTER 2 +#define CONFIG_SINGLE_MOTOR_TESTER 3 +#define BRUSHED_BOARD_CONFIG CONFIG_SINGLE_MOTOR_TESTER +#define PID_PERIOD_MS 100 + +#define OUTA_Pin ENCPIN1_1 +#define OUTB_Pin ENCPIN1_2 + +// DUMB POINTERS +driver_motor mot1; +driver_motor mot2; +driver_motor mot3; + +// TESTER VARIABLES +int stage = 0; +int pos = 90; +int tolerance = 0.5; +volatile boolean is_homed = false; + +// FUNCTION DECLARATIONS +void process_serial_cmd(); +void print_encoder_info(); +void brushed_board_homing(); +void brushed_board_loop(); +void brushed_board_dir_tester(); +void brushed_board_singe_setpoint_loop(); + +void lim1ISR(); +void lim2ISR(); +void lim3ISR(); +void lim4ISR(); +void lim5ISR(); +void lim6ISR(); + +// Define the size of the moving average window +const uint32_t MOVING_AVERAGE_SIZE = 10; +float cur1_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +float cur2_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +float cur3_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +int cur1_voltage_buffer_idx = 0; +int cur2_voltage_buffer_idx = 0; +int cur3_voltage_buffer_idx = 0; + +float moving_average(float new_reading, float *buffer, int buffer_size, int *buffer_idx) +{ + float sum = 0; + float oldest_reading = buffer[*buffer_idx]; + + // Add the new reading to the buffer. + buffer[*buffer_idx] = new_reading; + *buffer_idx = (*buffer_idx + 1) % buffer_size; // Circular buffer + + // Sum all readings. + for (int i = 0; i < buffer_size; i++) + { + sum += buffer[i]; + } + sum -= oldest_reading; + + return sum / buffer_size; +} + +// Ensure counter is initialized +int counter = 0; + +Rotation2d *current_rotation; + +// LIMIT SWITCHES +IntervalTimer lim_watchdog_timer; +const unsigned long DEBOUNCE_DELAY_MS = 50; + +volatile bool lim1_state = false; +volatile bool lim2_state = false; +volatile bool lim3_state = false; +volatile bool lim4_state = false; +volatile bool lim5_state = false; +volatile bool lim6_state = false; + +void setup() +{ + // Initialize Serial + SerialUSB.begin(115200); + SerialUSB.println("CONFIGURING BRUSHED BOARD"); + + std::unique_ptr enc1 = std::make_unique(); + std::unique_ptr enc2 = std::make_unique(); + std::unique_ptr enc3 = std::make_unique(); + + std::unique_ptr cur1 = std::make_unique(); + std::unique_ptr cur2 = std::make_unique(); + std::unique_ptr cur3 = std::make_unique(); + + // Initialize encoders + // 43000 clicks for wrist pitch, 32580 for wrist roll + // Only using 1 & 2 becase 1 & 3 conflicts + // Could be 32768 since it's a power of 2 + enc1->initialize_encoder(0, 0, 32580, 1); // new small servo estimate for resolution + enc2->initialize_encoder(0, 0, 43000, 2); + // enc3->initialize_encoder(0, 0, 43000, 3); + + // Initialize current sensors + cur1->initialize_sensor(CURRENT_SENSE_A); + cur3->initialize_sensor(CURRENT_SENSE_C); + cur2->initialize_sensor(CURRENT_SENSE_B); + + // Initialize motors + mot1.attach_encoder(std::move(enc1)); + mot2.attach_encoder(std::move(enc2)); + // mot3.attach_encoder(std::move(enc3)); + + mot1.attach_current_sensor(std::move(cur1)); + mot2.attach_current_sensor(std::move(cur2)); + mot3.attach_current_sensor(std::move(cur3)); + + // Motor init, forward logic is 1 + mot1.initialize_motor(1, PWMPIN1, DIRPIN1, nSLEEP1, 5.0, 0.0); + mot2.initialize_motor(1, PWMPIN2, DIRPIN2, nSLEEP2, 5.0, 0.0); + mot3.initialize_motor(1, PWMPIN3, DIRPIN3, nSLEEP3, 5.0, 0.0); + + // Set motor configuration after initialization + mot1.set_angle_limit_ps(wrist_pitch_max_angle, wrist_pitch_min_angle); + mot1.set_gear_ratio(2.0); + mot1._is_circular_joint = false; + + // Limit Switches + pinMode(LIM_1, INPUT); + pinMode(LIM_2, INPUT); + pinMode(LIM_3, INPUT); + pinMode(LIM_4, INPUT); + pinMode(LIM_5, INPUT); + pinMode(LIM_6, INPUT); + attachInterrupt(digitalPinToInterrupt(LIM_1), lim1ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_2), lim2ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_3), lim3ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_4), lim4ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_5), lim5ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_6), lim6ISR, CHANGE); + + // Watchdog timer to prevent bouncing or stuck limit switches + lim_watchdog_timer.begin([]() + { + lim1_state = digitalRead(LIM_1); + lim2_state = digitalRead(LIM_2); + lim3_state = digitalRead(LIM_3); + lim4_state = digitalRead(LIM_4); + lim5_state = digitalRead(LIM_5); + lim6_state = digitalRead(LIM_6); }, + DEBOUNCE_DELAY_MS * 1000); + + // Initialize Motor + // nSLEEP is actually hardwired to 5V so not really necessary + digitalWrite(nSLEEP1, HIGH); + digitalWrite(nSLEEP2, HIGH); + digitalWrite(nSLEEP3, HIGH); + + // Modelling + current_rotation = Rotation2d::getRotationFromDeg(0); + SerialUSB.println("DONE CONFIGURING BRUSHED BOARD"); + + // HOMING, only linear joints will be homed + SerialUSB.println("HOMING"); + brushed_board_homing(); + while (!is_homed) + ; + SerialUSB.println("DONE HOMING"); +} + +void loop() +{ +#if BRUSHED_BOARD_CONFIG == CONFIG_NON_ROS + brushed_board_loop(); +#elif BRUSHED_BOARD_CONFIG == CONFIG_DIR_TESTER + brushed_board_dir_tester(); +#elif BRUSHED_BOARD_CONFIG == CONFIG_SINGLE_MOTOR_TESTER + process_serial_cmd(); + brushed_board_singe_setpoint_loop(); +#endif +} + +void process_serial_cmd() +{ + static String inputString = ""; // A String to hold incoming data + static boolean inputStringComplete = false; // Whether the string is complete + + while (SerialUSB.available()) + { + char inChar = (char)SerialUSB.read(); // Read each character + if (inChar == '\n') + { + inputStringComplete = true; // If newline, input is complete + } + else + { + inputString += inChar; // Add character to input + } + } + + if (inputStringComplete) + { + SerialUSB.print("Received: "); + SerialUSB.println(inputString); // Echo the input for debugging + + // Process the completed command + if (inputString.startsWith("i ")) + { + // Increment command + float incrementValue = inputString.substring(2).toFloat(); // Extract number + float pos = mot1.get_target_angle_ps(); // Get current position + mot1.set_target_angle_ps(pos + incrementValue); // Increment and set new position + SerialUSB.print("Incremented position by: "); + SerialUSB.println(incrementValue); + } + else if (inputString.startsWith("s ")) + { + // Set command + pos = inputString.substring(2).toFloat(); // Extract and set new position + mot1.set_target_angle_ps(pos); + SerialUSB.print("Set position to: "); + SerialUSB.println(pos); + } + else + { + SerialUSB.println("Unknown command"); + } + + // Clear the string for the next command + inputString = ""; + inputStringComplete = false; + } +} + +void brushed_board_loop() +{ + delay(10); + + if (stage) + { + SerialUSB.println("Already reached target position"); + } + else + { + mot1.set_target_angle_ps(pos); + mot1.closed_loop_control_tick(); + float enc1_angle_ps = mot1.get_current_angle_ps(); + SerialUSB.printf("enc1_angle_ps: %8.4f \n", enc1_angle_ps); + + if (enc1_angle_ps <= pos + tolerance && enc1_angle_ps >= pos - tolerance && stage == 0) + { + SerialUSB.println("Reached target position"); + // pos = -60; + // stage++; + } + } +} + +// WRIST PITCH MAX LIMIT SWITCH +void lim1ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + is_homed = true; + mot1._encoder->set_current_angle_es(wrist_pitch_max_angle * mot1._gear_ratio); + SerialUSB.println("LIM_1 triggered"); + last_interrupt_time = interrupt_time; + lim1_state = digitalRead(LIM_1); + } +} + +// WRIST PITCH MIN LIMIT SWITCH +void lim2ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + mot1._encoder->set_current_angle_es(wrist_pitch_min_angle * mot1._gear_ratio); + SerialUSB.println("LIM_2 triggered"); + last_interrupt_time = interrupt_time; + lim2_state = digitalRead(LIM_2); + } +} + +void lim3ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + SerialUSB.println("LIM_3 triggered"); + last_interrupt_time = interrupt_time; + lim3_state = digitalRead(LIM_3); + } +} + +void lim4ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + SerialUSB.println("LIM_4 triggered"); + last_interrupt_time = interrupt_time; + lim4_state = digitalRead(LIM_4); + } +} + +void lim5ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + SerialUSB.println("LIM_5 triggered"); + last_interrupt_time = interrupt_time; + lim5_state = digitalRead(LIM_5); + } +} + +void lim6ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + SerialUSB.println("LIM_6 triggered"); + last_interrupt_time = interrupt_time; + lim6_state = digitalRead(LIM_6); + } +} + +// HOMING SEQUENCE, go forward until limit switch is triggered +void brushed_board_homing() +{ + // Only do homing for linear joints + if (!mot1._is_circular_joint) + { + mot1.set_direction(mot1._forward_dir); + mot1._pwm_write_duty(40); + } +} + +// PRINT ENCODER INFO +void print_encoder_info() +{ + // TEST LIMIT SWITCHES -------------------------------------------------------------------- + // printf("LIM_1: %d, LIM_2: %d, LIM_3: %d, LIM_4: %d, LIM_5: %d, LIM_6: %d\n", + // lim1_state, lim2_state, lim3_state, lim4_state, lim5_state, lim6_state); + + // TEST CURRENT SENSOR -------------------------------------------------------------------- + mot1._current_sensor->read_sensor_value(); + mot2._current_sensor->read_sensor_value(); + mot3._current_sensor->read_sensor_value(); + + // TODO check implementation of get_current() + float cur1_current = mot1._current_sensor->get_current(); + float cur2_current = mot2._current_sensor->get_current(); + float cur3_current = mot3._current_sensor->get_current(); + + // Middle value is 1.5V + float cur1_voltage = mot1._current_sensor->get_raw_voltage() - 1.5; + float cur2_voltage = mot2._current_sensor->get_raw_voltage() - 1.5; + float cur3_voltage = mot3._current_sensor->get_raw_voltage() - 1.5; + float smoothed_cur1_voltage = moving_average(cur1_voltage, cur1_voltage_buffer, MOVING_AVERAGE_SIZE, &cur1_voltage_buffer_idx); + float smoothed_cur2_voltage = moving_average(cur2_voltage, cur2_voltage_buffer, MOVING_AVERAGE_SIZE, &cur2_voltage_buffer_idx); + float smoothed_cur3_voltage = moving_average(cur3_voltage, cur3_voltage_buffer, MOVING_AVERAGE_SIZE, &cur3_voltage_buffer_idx); + + // SerialUSB.printf("cur1_current: %8.4f, cur2_current: %8.4f, cur3_current: %8.4f ", + // cur1_current, cur2_current, cur3_current); + SerialUSB.printf("cur1_voltage: %8.4f, cur2_voltage: %8.4f, cur3_voltage: %8.4f, ", + smoothed_cur1_voltage, smoothed_cur2_voltage, smoothed_cur3_voltage); + + // TEST ENCODER ------------------------------------------------------------------------------ + + // Channel 3 is conflicted, unused. + mot1._encoder->poll_encoder_angle(); + mot2._encoder->poll_encoder_angle(); + // mot3._encoder->poll_encoder_angle(); + + // Read encoder values. + float enc1_quad_enc_pos = mot1._encoder->_encoder->read(); + float enc1_angle_single = mot1._encoder->get_angle_single(); + float enc1_angle_es = mot1.get_current_angle_es(); + float enc1_angle_ps = mot1.get_current_angle_ps(); + float enc1_setpoint = mot1.get_target_angle_ps(); + + // float enc2_quad_enc_pos = mot2._encoder->_encoder->read(); + // float enc2_angle_single = mot2._encoder->get_angle_single(); + // float enc2_angle_multi = mot2._encoder->get_angle_multi(); + // float enc3_quad_enc_pos = mot3._encoder->_encoder->read(); + // float enc3_angle_single = mot3._encoder->get_angle_single(); + // float enc3_angle_multi = mot3._encoder->get_angle_multi(); + + SerialUSB.printf("enc1_quad_enc_pos: %8.4f, enc1_angle_single: %8.4f, enc1_angle_es: %8.4f, enc1_angle_ps: %8.4f, enc1_setpoint: %8.4f, ", + enc1_quad_enc_pos, enc1_angle_single, enc1_angle_es, enc1_angle_ps, enc1_setpoint); + + // float enc1_rev = mot1._encoder->_encoder->getRevolution(); + // float enc1_hold_rev = mot1._encoder->_encoder->getHoldRevolution(); + // SerialUSB.printf("enc1_rev: %8.4f, enc1_hold_rev: %8.4f, ", enc1_rev, enc1_hold_rev); + if (enc1_angle_es <= 2881 && enc1_angle_es >= 2879) + { + SerialUSB.printf("\n2880 here^"); + analogWrite(PWMPIN1, 0); + while (true) + ; + } + SerialUSB.println(); +} + +void brushed_board_dir_tester() +{ + delay(PID_PERIOD_MS); + + // Run Motors + mot1._pwm_write_duty(180); + mot2._pwm_write_duty(60); + mot3._pwm_write_duty(60); + + // Print Encoder Info + print_encoder_info(); + + // TEST GRAVITY COMPENSATION -------------------------------------------------------------------- + // double output; + // current_rotation->setAngleRad(current_angle / 360 * 2 * PI); + // maintainStateProto(*current_rotation, &output); + // printf("current output: %8.4f\r\n", output); + // printf("Current voltage: %8.4f\n", output); + // if (output < 0) + // { + // digitalWrite(DIR1, HIGH); + // } + // else + // { + // digitalWrite(DIR1, LOW); + // } + // int analog_write_output = (output / 24) * 255; + // printf("Current analog output: %d\n", analog_write_output); + // analogWrite(PWM1, analog_write_output); + + // ENCODER PINS TEST -------------------------------------------------------------------- + // SerialUSB.printf("ENCPIN1_1: %d, ENCPIN1_2: %d ", digitalRead(ENCPIN1_1), digitalRead(ENCPIN1_2)); + // SerialUSB.printf("ENCPIN2_1: %d, ENCPIN2_2: %d ", digitalRead(ENCPIN2_1), digitalRead(ENCPIN2_2)); + // SerialUSB.printf("ENCPIN3_1: %d, ENCPIN3_2: %d\n", digitalRead(ENCPIN3_1), digitalRead(ENCPIN3_2)); + // if (digitalRead(OUTA_Pin) == LOW) // If OUTA is LOW + // { + // if (digitalRead(OUTB_Pin) == LOW) // If OUTB is also LOW... CCK + // { + // while (digitalRead(OUTB_Pin) == LOW) + // { + // }; // wait for OUTB to go HIGH + // counter--; + // while (digitalRead(OUTA_Pin) == LOW) + // { + // }; // wait for OUTA to go HIGH + // delay(10); // wait for some more time + // } + // else if (digitalRead(OUTB_Pin) == HIGH) // If OUTB is HIGH + // { + // while (digitalRead(OUTB_Pin) == HIGH) + // { + // }; // wait for OUTB to go LOW.. CK + // counter++; + // while (digitalRead(OUTA_Pin) == LOW) + // { + // }; // wait for OUTA to go HIGH + // while (digitalRead(OUTB_Pin) == LOW) + // { + // }; // wait for OUTB to go HIGH + // delay(10); // wait for some more time + // } + + // if (counter < 0) + // counter = 0; + // if (counter > 180) + // counter = 180; + // } + // SerialUSB.println(counter); +} + +void brushed_board_singe_setpoint_loop() +{ + delay(PID_PERIOD_MS); + + mot1.closed_loop_control_tick(); + + // Print Encoder Info + print_encoder_info(); +} +#endif // USE_ROS_FIRMWARE == 0 \ No newline at end of file diff --git a/teensy40_brushed_v2/src/main_ros.cpp b/teensy40_brushed_v2/src/main_ros.cpp new file mode 100644 index 0000000..4fd8959 --- /dev/null +++ b/teensy40_brushed_v2/src/main_ros.cpp @@ -0,0 +1,469 @@ +#include "common.h" +#if USE_ROS_FIRMWARE == 1 +#include +#include "hardware_pins.h" +#include "driver_motor.h" +#include "model_encoder.h" +#include "model_sensor.h" +#include "motor.h" + +#include +#include "std_msgs/Float32.h" +#include "std_msgs/Float32MultiArray.h" + +#include + +// CONFIGURATION +#define PID_PERIOD_MS 100 +#define PID_PERIOD_US PID_PERIOD_MS * 1000 +#define HWSERIAL Serial2 +#define DEBUG_PRINT 1 + +#define OUTA_Pin ENCPIN1_1 +#define OUTB_Pin ENCPIN1_2 + +// ROS +ros::NodeHandle nh; +float arm_brushed_setpoint_ps[3] = {0, 0, 0}; +float arm_brushed_angle_ps[3] = {0, 0, 0}; +void brushed_board_ros_loop(); +void arm_brushed_cmd_cb(const std_msgs::Float32MultiArray &input_msg); +std_msgs::Float32MultiArray arm_brushed_fb_msg; +ros::Publisher arm_brushed_fb_pub("/armBrushedFb", &arm_brushed_fb_msg); +ros::Subscriber arm_brushed_cmd_sub("/armBrushedCmd", arm_brushed_cmd_cb); + +// DUMB POINTERS +driver_motor mot1; +driver_motor mot2; +driver_motor mot3; + +// TESTER VARIABLES +int stage = 0; +int pos = 90; +int tolerance = 0.5; +volatile boolean is_homed = false; + +// FUNCTION DECLARATIONS +void brushed_board_homing(); +void brushed_board_ros_loop(); + +void lim1ISR(); +void lim2ISR(); +void lim3ISR(); +void lim4ISR(); +void lim5ISR(); +void lim6ISR(); + +// Define the size of the moving average window +const uint32_t MOVING_AVERAGE_SIZE = 10; +float cur1_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +float cur2_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +float cur3_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +int cur1_voltage_buffer_idx = 0; +int cur2_voltage_buffer_idx = 0; +int cur3_voltage_buffer_idx = 0; + +float moving_average(float new_reading, float *buffer, int buffer_size, int *buffer_idx) +{ + float sum = 0; + float oldest_reading = buffer[*buffer_idx]; + + // Add the new reading to the buffer. + buffer[*buffer_idx] = new_reading; + *buffer_idx = (*buffer_idx + 1) % buffer_size; // Circular buffer + + // Sum all readings. + for (int i = 0; i < buffer_size; i++) + { + sum += buffer[i]; + } + sum -= oldest_reading; + + return sum / buffer_size; +} + +// Ensure counter is initialized +int counter = 0; + +Rotation2d *current_rotation; + +// LIMIT SWITCHES +IntervalTimer lim_watchdog_timer; +const unsigned long DEBOUNCE_DELAY_MS = 50; + +volatile bool lim1_state = false; +volatile bool lim2_state = false; +volatile bool lim3_state = false; +volatile bool lim4_state = false; +volatile bool lim5_state = false; +volatile bool lim6_state = false; + +uint32_t loop_last_time = 0; + +void setup() +{ + HWSERIAL.begin(115200); + while (!HWSERIAL) + ; + HWSERIAL.println("Serial port initialized"); + // Initialize ROS + nh.initNode(); + nh.advertise(arm_brushed_fb_pub); + nh.subscribe(arm_brushed_cmd_sub); + nh.negotiateTopics(); + while (!nh.connected()) + { + nh.negotiateTopics(); + // nh.spinOnce(); + } + + std::unique_ptr enc1 = std::make_unique(); + std::unique_ptr enc2 = std::make_unique(); + std::unique_ptr enc3 = std::make_unique(); + + std::unique_ptr cur1 = std::make_unique(); + std::unique_ptr cur2 = std::make_unique(); + std::unique_ptr cur3 = std::make_unique(); + + // Initialize encoders + // 43000 clicks for wrist pitch, 32580 for wrist roll + // Only using 1 & 2 becase 1 & 3 conflicts + // Could be 32768 since it's a power of 2 + // enc1->initialize_encoder(0, 0, 32580, 1); // new small servo estimate for resolution + enc1->initialize_encoder(0, 0, 43000, 1); + enc2->initialize_encoder(0, 0, 32580, 2); + // enc3->initialize_encoder(0, 0, 43000, 3); + + // Initialize current sensors + cur1->initialize_sensor(CURRENT_SENSE_A); + cur3->initialize_sensor(CURRENT_SENSE_C); + cur2->initialize_sensor(CURRENT_SENSE_B); + + // Initialize motors + mot1.attach_encoder(std::move(enc1)); + mot2.attach_encoder(std::move(enc2)); + // mot3.attach_encoder(std::move(enc3)); + + mot1.attach_current_sensor(std::move(cur1)); + mot2.attach_current_sensor(std::move(cur2)); + mot3.attach_current_sensor(std::move(cur3)); + + // Motor init, forward logic is 1 + mot1.initialize_motor(1, PWMPIN1, DIRPIN1, nSLEEP1, 5.0, 0.0); + mot2.initialize_motor(1, PWMPIN2, DIRPIN2, nSLEEP2, 5.0, 0.0); + mot3.initialize_motor(1, PWMPIN3, DIRPIN3, nSLEEP3, 5.0, 0.0); + + // Set motor configuration after initialization + // Gear ratio needs to be set before angle limits so limits are scaled + mot1.set_gear_ratio(2.0); + mot1.set_angle_limit_ps(wrist_pitch_max_angle, wrist_pitch_min_angle); + mot1._is_circular_joint = false; + + mot2.set_gear_ratio(2.0); + mot2._is_circular_joint = true; + + // Limit Switches + pinMode(LIM_1, INPUT); + pinMode(LIM_2, INPUT); + pinMode(LIM_3, INPUT); + pinMode(LIM_4, INPUT); + pinMode(LIM_5, INPUT); + pinMode(LIM_6, INPUT); + attachInterrupt(digitalPinToInterrupt(LIM_1), lim1ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_2), lim2ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_3), lim3ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_4), lim4ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_5), lim5ISR, CHANGE); + attachInterrupt(digitalPinToInterrupt(LIM_6), lim6ISR, CHANGE); + + // Watchdog timer to prevent bouncing or stuck limit switches + lim_watchdog_timer.begin([]() + { + lim1_state = digitalRead(LIM_1); + lim2_state = digitalRead(LIM_2); + lim3_state = digitalRead(LIM_3); + lim4_state = digitalRead(LIM_4); + lim5_state = digitalRead(LIM_5); + lim6_state = digitalRead(LIM_6); }, + DEBOUNCE_DELAY_MS * 1000); + + // Initialize Motor + // nSLEEP is actually hardwired to 5V so not really necessary + digitalWrite(nSLEEP1, HIGH); + digitalWrite(nSLEEP2, HIGH); + digitalWrite(nSLEEP3, HIGH); + + // Modelling + current_rotation = Rotation2d::getRotationFromDeg(0); + + // HOMING, only linear joints will be homed + // brushed_board_homing(); + // while (!is_homed) + // ; + + loop_last_time = micros(); +} + +void loop() +{ + brushed_board_ros_loop(); +} + +// WRIST PITCH MAX LIMIT SWITCH +void lim1ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + is_homed = true; + mot1._encoder->set_current_angle_es(wrist_pitch_max_angle * mot1._gear_ratio); + last_interrupt_time = interrupt_time; + lim1_state = digitalRead(LIM_1); + } +} + +// WRIST PITCH MIN LIMIT SWITCH +void lim2ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + mot1._encoder->set_current_angle_es(wrist_pitch_min_angle * mot1._gear_ratio); + last_interrupt_time = interrupt_time; + lim2_state = digitalRead(LIM_2); + } +} + +void lim3ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + last_interrupt_time = interrupt_time; + lim3_state = digitalRead(LIM_3); + } +} + +void lim4ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + last_interrupt_time = interrupt_time; + lim4_state = digitalRead(LIM_4); + } +} + +void lim5ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + last_interrupt_time = interrupt_time; + lim5_state = digitalRead(LIM_5); + } +} + +void lim6ISR() +{ + static unsigned long last_interrupt_time = 0; + unsigned long interrupt_time = millis(); + + if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) + { + last_interrupt_time = interrupt_time; + lim6_state = digitalRead(LIM_6); + } +} + +// HOMING SEQUENCE, go forward until limit switch is triggered +void brushed_board_homing() +{ + // Only do homing for linear joints + if (!mot1._is_circular_joint) + { + mot1.set_direction(mot1._forward_dir); + mot1._pwm_write_duty(40); + } +} + +void process_serial_cmd() +{ + static String inputString = ""; // A String to hold incoming data + static boolean inputStringComplete = false; // Whether the string is complete + + while (HWSERIAL.available()) + { + char inChar = (char)HWSERIAL.read(); // Read each character + if (inChar == '\n') + { + inputStringComplete = true; // If newline, input is complete + } + else + { + inputString += inChar; // Add character to input + } + } + + if (inputStringComplete) + { + HWSERIAL.print("Received: "); + HWSERIAL.println(inputString); // Echo the input for debugging + + // Process the completed command + if (inputString.startsWith("i ")) + { + // Increment command + float incrementValue = inputString.substring(2).toFloat(); // Extract number + float pos = mot1.get_target_angle_ps(); // Get current position + mot1.set_target_angle_ps(pos + incrementValue); // Increment and set new position + HWSERIAL.print("Incremented position by: "); + HWSERIAL.println(incrementValue); + } + else if (inputString.startsWith("s ")) + { + // Set command + pos = inputString.substring(2).toFloat(); // Extract and set new position + mot1.set_target_angle_ps(pos); + HWSERIAL.print("Set position to: "); + HWSERIAL.println(pos); + } + else + { + HWSERIAL.println("Unknown command"); + } + + // Clear the string for the next command + inputString = ""; + inputStringComplete = false; + } +} + +// PRINT ENCODER INFO +void print_encoder_info() +{ + // TEST LIMIT SWITCHES -------------------------------------------------------------------- + // printf("LIM_1: %d, LIM_2: %d, LIM_3: %d, LIM_4: %d, LIM_5: %d, LIM_6: %d\n", + // lim1_state, lim2_state, lim3_state, lim4_state, lim5_state, lim6_state); + + // TEST CURRENT SENSOR -------------------------------------------------------------------- + mot1._current_sensor->read_sensor_value(); + mot2._current_sensor->read_sensor_value(); + mot3._current_sensor->read_sensor_value(); + + // TODO check implementation of get_current() + float cur1_current = mot1._current_sensor->get_current(); + float cur2_current = mot2._current_sensor->get_current(); + float cur3_current = mot3._current_sensor->get_current(); + + // Middle value is 1.5V + float cur1_voltage = mot1._current_sensor->get_raw_voltage() - 1.5; + float cur2_voltage = mot2._current_sensor->get_raw_voltage() - 1.5; + float cur3_voltage = mot3._current_sensor->get_raw_voltage() - 1.5; + float smoothed_cur1_voltage = moving_average(cur1_voltage, cur1_voltage_buffer, MOVING_AVERAGE_SIZE, &cur1_voltage_buffer_idx); + float smoothed_cur2_voltage = moving_average(cur2_voltage, cur2_voltage_buffer, MOVING_AVERAGE_SIZE, &cur2_voltage_buffer_idx); + float smoothed_cur3_voltage = moving_average(cur3_voltage, cur3_voltage_buffer, MOVING_AVERAGE_SIZE, &cur3_voltage_buffer_idx); + + // HWSERIAL.printf("cur1_current: %8.4f, cur2_current: %8.4f, cur3_current: %8.4f ", + // cur1_current, cur2_current, cur3_current); + // HWSERIAL.printf("cur1_voltage: %8.4f, cur2_voltage: %8.4f, cur3_voltage: %8.4f, ", + // smoothed_cur1_voltage, smoothed_cur2_voltage, smoothed_cur3_voltage); + + // TEST ENCODER ------------------------------------------------------------------------------ + + // Channel 3 is conflicted, unused. + mot1._encoder->poll_encoder_angle(); + mot2._encoder->poll_encoder_angle(); + // mot3._encoder->poll_encoder_angle(); + + // Read encoder values. + float enc1_quad_enc_pos = mot1._encoder->_encoder->read(); + float enc1_angle_single = mot1._encoder->get_angle_single(); + float enc1_angle_es = mot1.get_current_angle_es(); + float enc1_angle_ps = mot1.get_current_angle_ps(); + float enc1_setpoint = mot1.get_target_angle_ps(); + + float enc2_quad_enc_pos = mot2._encoder->_encoder->read(); + float enc2_angle_single = mot2._encoder->get_angle_single(); + float enc2_angle_es = mot2.get_current_angle_es(); + float enc2_angle_ps = mot2.get_current_angle_ps(); + float enc2_setpoint = mot2.get_target_angle_ps(); + + // float enc2_quad_enc_pos = mot2._encoder->_encoder->read(); + // float enc2_angle_single = mot2._encoder->get_angle_single(); + // float enc2_angle_multi = mot2._encoder->get_angle_multi(); + // float enc3_quad_enc_pos = mot3._encoder->_encoder->read(); + // float enc3_angle_single = mot3._encoder->get_angle_single(); + // float enc3_angle_multi = mot3._encoder->get_angle_multi(); + + HWSERIAL.printf("enc1_quad_enc_pos: %8.4f, enc1_angle_single: %8.4f, enc1_angle_es: %8.4f, enc1_angle_ps: %8.4f, enc1_setpoint: %8.4f, ", + enc1_quad_enc_pos, enc1_angle_single, enc1_angle_es, enc1_angle_ps, enc1_setpoint); + HWSERIAL.println(); + HWSERIAL.printf("enc2_quad_enc_pos: %8.4f, enc2_angle_single: %8.4f, enc2_angle_es: %8.4f, enc2_angle_ps: %8.4f, enc2_setpoint: %8.4f, ", + enc2_quad_enc_pos, enc2_angle_single, enc2_angle_es, enc2_angle_ps, enc2_setpoint); + + // float enc1_rev = mot1._encoder->_encoder->getRevolution(); + // float enc1_hold_rev = mot1._encoder->_encoder->getHoldRevolution(); + // HWSERIAL.printf("enc1_rev: %8.4f, enc1_hold_rev: %8.4f, ", enc1_rev, enc1_hold_rev); + HWSERIAL.println(); +} + +void brushed_board_ros_loop() +{ +#if DEBUG_PRINT == 1 + process_serial_cmd(); +#endif + // delay(PID_PERIOD_MS); + + uint32_t current_time = micros(); + if (current_time - loop_last_time > PID_PERIOD_US) + { + counter = current_time; + mot1.closed_loop_control_tick(); + mot2.closed_loop_control_tick(); + // mot3.closed_loop_control_tick(); + loop_last_time = current_time; +#if DEBUG_PRINT == 1 + print_encoder_info(); +#endif + } + + // Feedback + arm_brushed_angle_ps[0] = mot1.get_current_angle_ps(); + arm_brushed_angle_ps[1] = mot2.get_current_angle_ps(); + // arm_brushed_angle_ps[2] = mot3.get_current_angle_ps(); + arm_brushed_angle_ps[2] = 0.0; + + arm_brushed_fb_msg.data_length = 3; + arm_brushed_fb_msg.data = arm_brushed_angle_ps; + arm_brushed_fb_pub.publish(&arm_brushed_fb_msg); + + nh.spinOnce(); + delay(1); +} + +void arm_brushed_cmd_cb(const std_msgs::Float32MultiArray &input_msg) +{ + // 0 is WP, 1 is WR, 2 is EE + arm_brushed_setpoint_ps[0] = input_msg.data[2]; + arm_brushed_setpoint_ps[1] = input_msg.data[1]; + arm_brushed_setpoint_ps[2] = input_msg.data[0]; + mot1.set_target_angle_ps(arm_brushed_setpoint_ps[0]); + mot2.set_target_angle_ps(arm_brushed_setpoint_ps[1]); + HWSERIAL.printf("WP: %8.4f, WR: %8.4f, EE: %8.4f\n", arm_brushed_setpoint_ps[0], arm_brushed_setpoint_ps[1], arm_brushed_setpoint_ps[2]); + + // Motor 3 is controlled like a forklift, only up and down, range -1 to 1 + // mot3.set_target_angle_ps(arm_brushed_setpoint_ps[2]); + mot3.move_manual(arm_brushed_setpoint_ps[2]); +} +#endif // USE_ROS_FIRMWARE == 1 \ No newline at end of file diff --git a/teensy40_brushed_v2/src/ros_tst.cpp b/teensy40_brushed_v2/src/ros_tst.cpp new file mode 100644 index 0000000..dd2b1be --- /dev/null +++ b/teensy40_brushed_v2/src/ros_tst.cpp @@ -0,0 +1,361 @@ +// #include +// #include "hardware_pins.h" +// #include "driver_motor.h" +// #include "model_encoder.h" +// #include "model_sensor.h" +// #include "motor.h" + +// #include +// #include +// #include +// #include "std_msgs/Float32.h" +// #include "std_msgs/Float32MultiArray.h" + +// #include + +// // CONFIGURATION +// #define CONFIG_NON_ROS 1 +// #define CONFIG_DIR_TESTER 2 +// #define CONFIG_SINGLE_MOTOR_TESTER 3 +// #define CONFIG_ROS 4 +// #define BRUSHED_BOARD_CONFIG CONFIG_ROS +// #define PID_PERIOD_MS 100 + +// #define OUTA_Pin ENCPIN1_1 +// #define OUTB_Pin ENCPIN1_2 + +// ros::NodeHandle nh; + +// std_msgs::String str_msg; +// //ros::Publisher chatter("chatter", &str_msg); + +// char hello[13] = "hello world!"; + +// void messageCb(const std_msgs::Empty &toggle_msg) +// { +// digitalWrite(LED_BUILTIN, HIGH - digitalRead(LED_BUILTIN)); // blink the led +// } + +// ros::Subscriber sub("toggle_led", &messageCb); + +// // ROS +// //ros::NodeHandle nh; +// float arm_brushed_setpoint_ps[3] = {0, 0, 0}; +// float arm_brushed_angle_ps[3] = {0, 0, 0}; +// void brushed_board_ros_loop(); +// void arm_brushed_cmd_cb(const std_msgs::Float32MultiArray &input_msg); +// std_msgs::Float32MultiArray arm_brushed_fb_msg; +// ros::Publisher arm_brushed_fb_pub("armBrushedFB", &arm_brushed_fb_msg); +// //ros::Subscriber arm_brushed_cmd_sub("armBrushedCmd", arm_brushed_cmd_cb); + +// // DUMB POINTERS +// driver_motor mot1; +// driver_motor mot2; +// driver_motor mot3; + +// // TESTER VARIABLES +// int stage = 0; +// int pos = 90; +// int tolerance = 0.5; +// volatile boolean is_homed = false; + +// // FUNCTION DECLARATIONS +// //void brushed_board_homing(); +// void brushed_board_ros_loop(); + +// // void lim1ISR(); +// // void lim2ISR(); +// // void lim3ISR(); +// // void lim4ISR(); +// // void lim5ISR(); +// // void lim6ISR(); + +// // Define the size of the moving average window +// const uint32_t MOVING_AVERAGE_SIZE = 10; +// float cur1_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +// float cur2_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +// float cur3_voltage_buffer[MOVING_AVERAGE_SIZE] = {0}; +// int cur1_voltage_buffer_idx = 0; +// int cur2_voltage_buffer_idx = 0; +// int cur3_voltage_buffer_idx = 0; + +// float moving_average(float new_reading, float *buffer, int buffer_size, int *buffer_idx) +// { +// float sum = 0; +// float oldest_reading = buffer[*buffer_idx]; + +// // Add the new reading to the buffer. +// buffer[*buffer_idx] = new_reading; +// *buffer_idx = (*buffer_idx + 1) % buffer_size; // Circular buffer + +// // Sum all readings. +// for (int i = 0; i < buffer_size; i++) +// { +// sum += buffer[i]; +// } +// sum -= oldest_reading; + +// return sum / buffer_size; +// } + +// // Ensure counter is initialized +// int counter = 0; + +// Rotation2d *current_rotation; + +// // // LIMIT SWITCHES +// // IntervalTimer lim_watchdog_timer; +// // const unsigned long DEBOUNCE_DELAY_MS = 50; + +// // volatile bool lim1_state = false; +// // volatile bool lim2_state = false; +// // volatile bool lim3_state = false; +// // volatile bool lim4_state = false; +// // volatile bool lim5_state = false; +// // volatile bool lim6_state = false; + +// uint32_t loop_last_time = 0; + +// void setup() +// { +// pinMode(13, OUTPUT); +// nh.initNode(); +// nh.advertise(arm_brushed_fb_pub); +// //nh.subscribe(sub); +// #if BRUSHED_BOARD_CONFIG == CONFIG_ROS +// // Initialize ROS +// // nh.initNode(); +// // nh.advertise(arm_brushed_fb_pub); +// // nh.subscribe(arm_brushed_cmd_sub); +// // while (!nh.connected()) +// // { +// // nh.negotiateTopics(); +// // nh.spinOnce(); +// // } +// #endif + +// std::unique_ptr enc1 = std::make_unique(); +// std::unique_ptr enc2 = std::make_unique(); +// std::unique_ptr enc3 = std::make_unique(); + +// std::unique_ptr cur1 = std::make_unique(); +// std::unique_ptr cur2 = std::make_unique(); +// std::unique_ptr cur3 = std::make_unique(); + +// // Initialize encoders +// // 43000 clicks for wrist pitch, 32580 for wrist roll +// // Only using 1 & 2 becase 1 & 3 conflicts +// // Could be 32768 since it's a power of 2 +// enc1->initialize_encoder(0, 0, 32580, 1); // new small servo estimate for resolution +// enc2->initialize_encoder(0, 0, 43000, 2); +// // enc3->initialize_encoder(0, 0, 43000, 3); + +// // Initialize current sensors +// cur1->initialize_sensor(CURRENT_SENSE_A); +// cur3->initialize_sensor(CURRENT_SENSE_C); +// cur2->initialize_sensor(CURRENT_SENSE_B); + +// // Initialize motors +// mot1.attach_encoder(std::move(enc1)); +// mot2.attach_encoder(std::move(enc2)); +// // mot3.attach_encoder(std::move(enc3)); + +// mot1.attach_current_sensor(std::move(cur1)); +// mot2.attach_current_sensor(std::move(cur2)); +// mot3.attach_current_sensor(std::move(cur3)); + +// // Motor init, forward logic is 1 +// mot1.initialize_motor(1, PWMPIN1, DIRPIN1, nSLEEP1, 5.0, 0.0); +// mot2.initialize_motor(1, PWMPIN2, DIRPIN2, nSLEEP2, 5.0, 0.0); +// mot3.initialize_motor(1, PWMPIN3, DIRPIN3, nSLEEP3, 5.0, 0.0); + +// // Set motor configuration after initialization +// mot1.set_angle_limit_ps(wrist_pitch_max_angle, wrist_pitch_min_angle); +// mot1.set_gear_ratio(2.0); +// mot1._is_circular_joint = true; + +// // // Limit Switches +// // pinMode(LIM_1, INPUT); +// // pinMode(LIM_2, INPUT); +// // pinMode(LIM_3, INPUT); +// // pinMode(LIM_4, INPUT); +// // pinMode(LIM_5, INPUT); +// // pinMode(LIM_6, INPUT); +// // attachInterrupt(digitalPinToInterrupt(LIM_1), lim1ISR, CHANGE); +// // attachInterrupt(digitalPinToInterrupt(LIM_2), lim2ISR, CHANGE); +// // attachInterrupt(digitalPinToInterrupt(LIM_3), lim3ISR, CHANGE); +// // attachInterrupt(digitalPinToInterrupt(LIM_4), lim4ISR, CHANGE); +// // attachInterrupt(digitalPinToInterrupt(LIM_5), lim5ISR, CHANGE); +// // attachInterrupt(digitalPinToInterrupt(LIM_6), lim6ISR, CHANGE); + +// // // Watchdog timer to prevent bouncing or stuck limit switches +// // lim_watchdog_timer.begin([]() +// // { +// // lim1_state = digitalRead(LIM_1); +// // lim2_state = digitalRead(LIM_2); +// // lim3_state = digitalRead(LIM_3); +// // lim4_state = digitalRead(LIM_4); +// // lim5_state = digitalRead(LIM_5); +// // lim6_state = digitalRead(LIM_6); }, +// // DEBOUNCE_DELAY_MS * 1000); + +// // Initialize Motor +// // nSLEEP is actually hardwired to 5V so not really necessary +// digitalWrite(nSLEEP1, HIGH); +// digitalWrite(nSLEEP2, HIGH); +// digitalWrite(nSLEEP3, HIGH); + +// // Modelling +// current_rotation = Rotation2d::getRotationFromDeg(0); + +// //brushed_board_homing(); +// // while (!is_homed) +// // ; +// loop_last_time = micros(); +// } + +// void loop() +// { +// // str_msg.data = hello; +// // chatter.publish(&str_msg); +// // arm_brushed_fb_msg.data_length = 3; +// // arm_brushed_angle_ps[0] = mot1.get_current_angle_ps(); +// // arm_brushed_angle_ps[1] = mot2.get_current_angle_ps(); +// // arm_brushed_angle_ps[2] = 0.0; //getting angle was causing it to break...not only issue + +// // arm_brushed_fb_msg.data = arm_brushed_angle_ps; +// // arm_brushed_fb_pub.publish(&arm_brushed_fb_msg); +// // nh.spinOnce(); +// // delay(1); +// brushed_board_ros_loop(); +// } + +// void brushed_board_ros_loop() +// { +// // delay(PID_PERIOD_MS); + +// uint32_t current_time = micros(); +// if (current_time - loop_last_time > 1000000) +// { +// counter = current_time; +// mot1.closed_loop_control_tick(); +// mot2.closed_loop_control_tick(); +// // mot3.closed_loop_control_tick(); +// loop_last_time = current_time; +// } + +// // Feedback +// arm_brushed_fb_msg.data_length = 3; +// arm_brushed_angle_ps[0] = mot1.get_current_angle_ps(); +// arm_brushed_angle_ps[1] = mot2.get_current_angle_ps(); +// //arm_brushed_angle_ps[2] = mot3.get_current_angle_ps(); +// arm_brushed_angle_ps[2] = 0.0; +// arm_brushed_fb_msg.data = arm_brushed_angle_ps; +// arm_brushed_fb_pub.publish(&arm_brushed_fb_msg); + +// nh.spinOnce(); +// delay(1); +// } + +// // void loop() +// // { +// // brushed_board_ros_loop(); +// // } + +// // WRIST PITCH MAX LIMIT SWITCH +// // void lim1ISR() +// // { +// // static unsigned long last_interrupt_time = 0; +// // unsigned long interrupt_time = millis(); + +// // if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) +// // { +// // is_homed = true; +// // mot1._encoder->set_current_angle_es(wrist_pitch_max_angle * mot1._gear_ratio); +// // last_interrupt_time = interrupt_time; +// // lim1_state = digitalRead(LIM_1); +// // } +// // } + +// // // WRIST PITCH MIN LIMIT SWITCH +// // void lim2ISR() +// // { +// // static unsigned long last_interrupt_time = 0; +// // unsigned long interrupt_time = millis(); + +// // if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) +// // { +// // mot1._encoder->set_current_angle_es(wrist_pitch_min_angle * mot1._gear_ratio); +// // last_interrupt_time = interrupt_time; +// // lim2_state = digitalRead(LIM_2); +// // } +// // } + +// // void lim3ISR() +// // { +// // static unsigned long last_interrupt_time = 0; +// // unsigned long interrupt_time = millis(); + +// // if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) +// // { +// // last_interrupt_time = interrupt_time; +// // lim3_state = digitalRead(LIM_3); +// // } +// // } + +// // void lim4ISR() +// // { +// // static unsigned long last_interrupt_time = 0; +// // unsigned long interrupt_time = millis(); + +// // if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) +// // { +// // last_interrupt_time = interrupt_time; +// // lim4_state = digitalRead(LIM_4); +// // } +// // } + +// // void lim5ISR() +// // { +// // static unsigned long last_interrupt_time = 0; +// // unsigned long interrupt_time = millis(); + +// // if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) +// // { +// // last_interrupt_time = interrupt_time; +// // lim5_state = digitalRead(LIM_5); +// // } +// // } + +// // void lim6ISR() +// // { +// // static unsigned long last_interrupt_time = 0; +// // unsigned long interrupt_time = millis(); + +// // if (interrupt_time - last_interrupt_time > DEBOUNCE_DELAY_MS) +// // { +// // last_interrupt_time = interrupt_time; +// // lim6_state = digitalRead(LIM_6); +// // } +// // } + +// // // HOMING SEQUENCE, go forward until limit switch is triggered +// // void brushed_board_homing() +// // { +// // // Only do homing for linear joints +// // if (!mot1._is_circular_joint) +// // { +// // mot1.set_direction(mot1._forward_dir); +// // mot1._pwm_write_duty(40); +// // } +// // } + +// void arm_brushed_cmd_cb(const std_msgs::Float32MultiArray &input_msg) +// { +// arm_brushed_setpoint_ps[0] = input_msg.data[0]; +// arm_brushed_setpoint_ps[1] = input_msg.data[1]; +// arm_brushed_setpoint_ps[2] = input_msg.data[2]; +// mot1.set_target_angle_ps(arm_brushed_setpoint_ps[0]); +// mot2.set_target_angle_ps(arm_brushed_setpoint_ps[1]); +// mot3.set_target_angle_ps(arm_brushed_setpoint_ps[2]); +// } \ No newline at end of file diff --git a/teensy40_brushed_v2/test/README b/teensy40_brushed_v2/test/README new file mode 100644 index 0000000..9b1e87b --- /dev/null +++ b/teensy40_brushed_v2/test/README @@ -0,0 +1,11 @@ + +This directory is intended for PlatformIO Test Runner and project tests. + +Unit Testing is a software testing method by which individual units of +source code, sets of one or more MCU program modules together with associated +control data, usage procedures, and operating procedures, are tested to +determine whether they are fit for use. Unit testing finds problems early +in the development cycle. + +More information about PlatformIO Unit Testing: +- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html