From 079310eb5af4725e9b587d8c0b81abe179d93e26 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 12:29:14 -0700 Subject: [PATCH 01/15] Fix Make `PWMMotorMediator` physically realistic #88. Also fix #100 (use DBSBrake to ensure unique name). --- example/src/main/java/frc/robot/Robot.java | 2 +- .../java/frc/robot/SystemTestRobot.java | 23 +- .../mediators/PWMMotorMediator.java | 9 +- .../dist/protos/deepbluesim/DBSBrake.proto | 18 ++ .../deepbluesim/PoweredHingeJoint.proto | 10 +- .../deepbluesim/PoweredSliderJoint.proto | 10 +- .../dist/worlds/.PWMMotorController.jpg | Bin 0 -> 61658 bytes .../webotsFolder/dist/worlds/DBSExample.wbt | 54 ++-- .../dist/worlds/PWMMotorController.wbt | 16 +- .../libdeepbluesim/WebotsSimulator.java | 29 +- tests/logging.properties | 2 +- .../main/java/frc/robot/DBSExampleRobot.java | 2 +- .../java/frc/robot/DBSExampleTest.java | 25 +- .../frc/robot/PWMMotorControllerTest.java | 254 ++++++++++++++++-- 14 files changed, 352 insertions(+), 102 deletions(-) create mode 100644 plugin/controller/src/webotsFolder/dist/protos/deepbluesim/DBSBrake.proto create mode 100644 plugin/controller/src/webotsFolder/dist/worlds/.PWMMotorController.jpg diff --git a/example/src/main/java/frc/robot/Robot.java b/example/src/main/java/frc/robot/Robot.java index e30b9ba7..1c911ece 100644 --- a/example/src/main/java/frc/robot/Robot.java +++ b/example/src/main/java/frc/robot/Robot.java @@ -78,7 +78,7 @@ public void autonomousPeriodic() { // Drive for 2 seconds if (m_timer.get() < 2.0) { m_robotDrive.arcadeDrive(0.5, 0.0); // drive forwards half speed - m_elevator.set(0.1); + m_elevator.set(0.3); } else { m_robotDrive.stopMotor(); // stop robot } diff --git a/example/src/systemTest/java/frc/robot/SystemTestRobot.java b/example/src/systemTest/java/frc/robot/SystemTestRobot.java index 54651579..7f8b503c 100644 --- a/example/src/systemTest/java/frc/robot/SystemTestRobot.java +++ b/example/src/systemTest/java/frc/robot/SystemTestRobot.java @@ -37,12 +37,12 @@ void testDrivesToLocationAndElevatesInAutonomous() throws Exception { 0.2, "Robot close to target position"); assertEquals(0.0, s.position("ELEVATOR") - .getDistance(new Translation3d(2.6, 0, 0.9)), + .getDistance(new Translation3d(2.6, 0, 1.244)), 0.2, "Elevator close to target position"); assertEquals(0.0, s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), - 0.01, "Robot close to target velocity"); + 0.05, "Robot close to target velocity"); assertEquals(0.0, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), @@ -61,7 +61,7 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { s.enableTeleop(); DriverStationSim.setJoystickAxisCount(0, 2); DriverStationSim.setJoystickAxis(0, 1, 0.0); - DriverStationSim.setJoystickAxis(0, 0, 0.15); + DriverStationSim.setJoystickAxis(0, 0, 0.6); DriverStationSim.notifyNewData(); }).everyStep(s -> { var yawDegrees = @@ -72,27 +72,28 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { DriverStationSim.notifyNewData(); stoppedTryingToTurn = true; } - }).atSec(1.0, s -> { + }).atSec(0.3, s -> { assertEquals(0.0, s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), 0.1, "Robot close to target velocity"); - assertEquals(19.0, - Units.radiansToDegrees( + assertEquals(62.5, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), - 1, "Robot close to target angular velocity"); + 2.0, "Robot close to target angular velocity"); assertEquals(0.0, new Translation3d(s.angularVelocity("ROBOT").getAxis()) .getDistance(new Translation3d(0, 0, 1)), 0.1, "Robot close to target angular velocity axis"); - }).atSec(4.0, s -> { + }).atSec(1.0, s -> { + // Note: Large tolerance because turning at a high speed means we can overshoot + // significantly in 1 step. assertEquals(45.0, - Units.radiansToDegrees(s.rotation("ROBOT").getZ()), 2.0, - "Robot close to target rotation"); + Units.radiansToDegrees(s.rotation("ROBOT").getZ()), + 10.0, "Robot close to target rotation"); assertEquals(0.0, s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), - 0.01, "Robot close to target velocity"); + 0.1, "Robot close to target velocity"); assertEquals(0.0, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), diff --git a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java index 5a16c5c8..db37718b 100644 --- a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java +++ b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java @@ -35,11 +35,16 @@ public PWMMotorMediator(Motor motor, PWMSim simDevice, DCMotor motorConstants, d // Use velocity control motor.setPosition(Double.POSITIVE_INFINITY); - // Disable braking - if(motor.getBrake() != null) motor.getBrake().setDampingConstant(0); + if (motor.getBrake() != null) { + double dampingConstant = motorConstants.stallTorqueNewtonMeters + * gearing / (motorConstants.freeSpeedRadPerSec / gearing); + motor.getBrake().setDampingConstant(dampingConstant); + } motorDevice.registerSpeedCallback((deviceName, speed) -> { double velocity = speed * motorConstants.freeSpeedRadPerSec; + motor.setAvailableTorque(Math.abs(speed) + * motorConstants.stallTorqueNewtonMeters * gearing); motor.setVelocity((inverted ? -1 : 1) * velocity / gearing); }, true); } diff --git a/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/DBSBrake.proto b/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/DBSBrake.proto new file mode 100644 index 00000000..644407c1 --- /dev/null +++ b/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/DBSBrake.proto @@ -0,0 +1,18 @@ +#VRML_SIM R2023b utf8 +# license: MIT +# license url: https://github.com/DeepBlueRobotics/DeepBlueSim/blob/master/LICENSE.md +# template language: javascript +# tags: nonDeterministic + +# A Brake with a unique name to workaround https://github.com/cyberbotics/webots/issues/6578 + +PROTO DBSBrake [ +] +{ + %< + let name = "DBSBrake " + context.id; + >% + Brake { + name "%<= name >%" + } +} diff --git a/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredHingeJoint.proto b/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredHingeJoint.proto index 169aafaa..0b6e81d7 100644 --- a/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredHingeJoint.proto +++ b/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredHingeJoint.proto @@ -14,12 +14,14 @@ EXTERNPROTO "SparkMaxAbsoluteEncoder.proto" EXTERNPROTO "SparkMaxAlternateEncoder.proto" EXTERNPROTO "SparkMaxAnalogSensor.proto" +EXTERNPROTO "DBSBrake.proto" + PROTO PoweredHingeJoint [ field MFNode{ DBSRotationalMotorBase{}, PreconfiguredDBSRotationalMotor{} CANCoder{}, DBSQuadratureEncoder{}, REVBuiltinEncoder{}, SparkMaxAbsoluteEncoder{}, SparkMaxAlternateEncoder{}, SparkMaxAnalogSensor{}, - Brake{} - } devices [PreconfiguredDBSRotationalMotor{} REVBuiltinEncoder{} Brake{}] + DBSBrake{} + } devices [PreconfiguredDBSRotationalMotor{} REVBuiltinEncoder{} DBSBrake{}] field SFNode{Solid{}} endPoint Solid{} field SFNode{HingeJointParameters{}} jointParameters HingeJointParameters{} ] @@ -32,7 +34,7 @@ PROTO PoweredHingeJoint [ let encoderDevice = null; for (let i = 0; i < devices.length; i++) { let node_name = devices[i].node_name; - if (node_name === "Brake") { + if (node_name.endsWith("Brake")) { hasBrake = true; } else if (node_name.endsWith("Motor")) { motorDevice = devices[i]; @@ -40,7 +42,7 @@ PROTO PoweredHingeJoint [ encoderDevice = devices[i]; } } - assert(hasBrake, "PoweredHingeJoint is missing the required Brake device!"); + assert(hasBrake, "PoweredHingeJoint is missing the required DBSBrake device!"); assert(motorDevice !== null, "PoweredHingeJoint is missing the required motor device!"); let motorType = motorDevice?.node_name; let controllerType = motorDevice?.fields.controllerType.value; diff --git a/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredSliderJoint.proto b/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredSliderJoint.proto index 1d780f68..084b127f 100644 --- a/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredSliderJoint.proto +++ b/plugin/controller/src/webotsFolder/dist/protos/deepbluesim/PoweredSliderJoint.proto @@ -14,12 +14,14 @@ EXTERNPROTO "SparkMaxAbsoluteEncoder.proto" EXTERNPROTO "SparkMaxAlternateEncoder.proto" EXTERNPROTO "SparkMaxAnalogSensor.proto" +EXTERNPROTO "DBSBrake.proto" + PROTO PoweredSliderJoint [ field MFNode{ DBSLinearMotorBase{}, PreconfiguredDBSLinearMotor{} CANCoder{}, DBSQuadratureEncoder{}, REVBuiltinEncoder{}, SparkMaxAbsoluteEncoder{}, SparkMaxAlternateEncoder{}, SparkMaxAnalogSensor{}, - Brake{} - } devices [PreconfiguredDBSLinearMotor{} REVBuiltinEncoder{} Brake{}] + DBSBrake{} + } devices [PreconfiguredDBSLinearMotor{} REVBuiltinEncoder{} DBSBrake{}] field SFNode{Solid{}} endPoint Solid{} field SFNode{JointParameters{}} jointParameters JointParameters{} ] @@ -32,7 +34,7 @@ PROTO PoweredSliderJoint [ let encoderDevice = null; for (let i = 0; i < devices.length; i++) { let node_name = devices[i].node_name; - if (node_name === "Brake") { + if (node_name.endsWith("Brake")) { hasBrake = true; } else if (node_name.endsWith("Motor")) { motorDevice = devices[i]; @@ -40,7 +42,7 @@ PROTO PoweredSliderJoint [ encoderDevice = devices[i]; } } - assert(hasBrake, "PoweredSliderJoint is missing the required Brake device!"); + assert(hasBrake, "PoweredSliderJoint is missing the required DBSBrake device!"); assert(motorDevice !== null, "PoweredSliderJoint is missing the required motor device!"); let motorType = motorDevice?.node_name; let controllerType = motorDevice?.fields.controllerType.value; diff --git a/plugin/controller/src/webotsFolder/dist/worlds/.PWMMotorController.jpg b/plugin/controller/src/webotsFolder/dist/worlds/.PWMMotorController.jpg new file mode 100644 index 0000000000000000000000000000000000000000..28ad5bb38e425827bb42160d99cdab7cba3858f5 GIT binary patch literal 61658 zcmbSyWmJ^m+vg}L5>nEPw9;JyBOomxAl)J@-8qDG3?ZPTbb~ZQcXvxlcX!ONkN?8VwgZfw&5Wu>&D3w?8J4L~Le7`!hNo)f3{+ zj^kJ_>3LTfPXCqmpUVF43JduEs_cIi_P^_z2VtW;0VWRx9|QsI&4aPJILCLvq0+p! zm+u=ZlNa9qv}I4=3?rK_5H@Fu7G)VBRBDbDV9VL?3>{&qI$64k&9amnZHclqd%KB3 zU!HZkt2bfbCMx!+mP@Ujd?QeT&L&)sVWW;RBz6nwQ!Sm3a)=`y!`29S`ejI)V5*GG`cyGIZ?p}quSNL$3N zq;-i?26^Ct^eDV2e_`!emWvjz_fRP?qzDoCmIx8kPn*(} zUs#=+yJkC$UhBa&)i;_Olf+D?Mv)ia#``)Gx6786do69~L&((WUvI?kpm`|ldX_GZ z3e2(VZ+z|wjpkPJVX6uaVzu*f`i;9tQ$TVZL8LhA`ko?LChnKGd32hl;cC~{ARlDql&*P0%lmelFmLd+JnC0Hd_gay(%0{%8NgmgkBa4 zi99QAdCu1a)nvNGs>AEtuR_+I5drU3?h%CL8tRn|?w$2&(S7~yf>o}x-dohTM20%o zi=z7abtQN4i)=doTMaLFbW&pv^Qq`5)!wg0_7L)sN6@!@71TqjSKwHyuDrwe?BlBaL|nq4$3^QJA7!>X^Qs_971y5Kihjr($)l-_|?> z=GWx;L&4_fP1ABx;qKDv7aR$c4h646P?$3ISkl$q=&-u(v1f~RUdAe9&Fd{m#On>D z%v%!i)OwIHrT-{R_@vxOiZb^(h{b|(M#NE+`%WFPl-7x|D6Qy1O$^t6#-8-a#465) zE9?nc=!pCNuKsEahl>BP9#d4JkM!LiHsd%4@)zDUYyq+tS=VEh=N7h*NN2%2eV&Xf z6T3a;l5~*?Y1dw0DM|s;NCFOV`RTirCI*?;ZyhP^{=4KTd9M8pd??#GHd*^}R;o!ndTz2U5xLVnx9Zn- z9NrechSmu!np`uy&S83Bu5RIPhO1%!mMB={`snG)ThcMX&2WlaPBUmFfP$D^cqqzg zh}vkot&4BHpCCk7PpqFr2mbE$w%e$)CJ;bV#jGCxkF1sIlPwrJdV<))|B9FF^2?F2J6$un-r?TVb zm&TQDiTvxSG4}5?-yylivUgqe9zj(U&>)tYEDWF62$IewC-ywij_ya$Y%!1JnY+M; z^s|obL+ozJoZ_=}!9LLCR(?`%!#hE(qm>;$yr~)6%yot5_i{F3ot)98b0d0BTQ01g z|2#5NTu(E-(F}lG(>;PHr!`Lv>R#WLFXCOP%bXEUbe>!d2Q(#ri^lAG{mcAzdaemA zC-XL^9%}Lm+^5zgnaqTT3-`I2`_c$cUL&?2rHs_pGEc`N-hV+)%V%K{MeIjswH`j8 zjIpC~S-lLMkA+>9>2}Ah?2^Zcn|nCmq)21S#=Rh+#7FvA+Ts*iz}}Og_^ZfqzH=K2 zh0GhV^q93ari9sUL$7lfe=WsF_43||zuVy}#r5EefF1NjO<^z8iJzk}6$tKrlv-tT zIPvWmM4lHQ&B|_A)b4SsuFM3(cWmxBcY$R=4-cpQlFSP}C*V^#s4r(v>X~0aEQGE0t-kZu-(do;%JwMhXD`QpIbV@{y56J1S5-;2;i?uuz%x_Oe~O|=c6NC5 z1NJfdZbmuMSzWigv5JLm$bnuZM%S$jgD(g#`0^)gFkcCyn0;kiLN=Gk*)3fpcx`D_ z*x)ABD2(ARERUHDqf`sgh`h|;?v#`Esk?w)JXy^r@S%L`*vw4Ws;Hep zYxFK-?MFdpcBR!F_iUv=R|RRy?!Wptcti1W$cK=-&t<)<`dHLb0U6gn>dyI6if+a% zHDOkFUze?*9vy*4!l&9i-tQaeu64XwkoSo|6Vj<HWfHiDW%cylX@biYvaDuLTQcY*d85L}-!G6| zi?%YQ0AXk)lh1oY3)LKwH?)}yeyu8x4 za`X#4HR;XbRjloA2{pI3fd)vc{dfd*X;d$BjngnFPFA4=pen{d@l_WX;B0}4Cq9Wu zj&(2e^`E`#al^*nk!Hc`YDfybh)8FDq04nkA5C*hxs6`lzkc{eiGZc{b7H%@#K@; z=HwAu`tqGF^i2p0y`N^>-p7@By=szSfgg~Tt_{!d92_x~0*d6kFl^2Jmq~8K^8@x_ zl>TWxuu@?TbnD9Vt9OA2I1yB*3wvNSHoWo-Q?P8mGo6c@sA_6)J4-pb^%xpOp0(*x zk%H&P=X!rOU+@U>j(;f5ALFG`lTwX>64h>J&=ep7L{gssZ4EkoK|cDzOUH6P2R0x zGw-;bIYe8U7-+8T=?Xk>=yuSUr}WIryPCH-_>ldbXOk>sl4!c&d#O#x=vt}O7QY;O zPY)?GogV(JMo93b54C9RU3vz{VdC#ENSaQ>>hui63rcWz5LtKLtsk*EMMrJ(P>MV- zf~qNq!=-10>y7Kwaj?0V(}ReNkm@FaI~beV{5ph|uH53LP=484)EgJIi?%WWt(hjZ z+$B<5TU0CG{a%7Y;{ylTVd;CSmg1a+{TChrAA@_B>^TQ7__l?QgY29gO;JW_M+siv zXCpG_ixk(W%+${J+(fRlu>k0r&vrQV2-+{pi%0A}E0W88pDe1`l^oTbn7EIwvt}4e zjIQOG&N8AVGtB^D%y5<||Gu(n5WhMstSBHSmBQx0F-l_+_v{eqv#*`=Y|sX*r>0tw zc9^*t>#nO4<6yK7SvCa^O~v0B+zsH>>|y<0prPn98V+!1qf+#IyXWdqOMSGYoEc+& zJ1ejjTVT!AZj=A+TsN?JNr@Qtj@w5F@#dVLcW!(=iW?Jv&~F1mpBB)(1Nkx*w{|f+ zf)YKA#SZ^McDhZXBq&A6?1*nUD-xWd>b;hRU*kQ=Go+9}&yg}6$bnEb)S{WxV~Br$L6 z3)?WnbR-M%{3UQ6Y9K#aS4{S<+ThZ4$5BE(fPKTGF)2Hdb)W20NA*yFByMkwcCi%O zTVT4c$k?+?Tz);vVY^nV-Oere@g*l7L|(&qpzAbh$gZ^dU@Y`XNS4TTb!ATCCo`3TZ2$jJH!^t?`6W1Wp+x2AS z>(ock2MzDm7dAYhC5(30sT^m+lHlk~c=~Ia$!tlMZ-cT*+zvahz1!fC&tdp`Dm?8r z9`qXH6|%AR{J;KUU+#wI-L>R$AvO_%cpkbB)=jWB9r+jo-K4vEaG!ep165|euFcA^ z?8>^*j(6YLb(|c!jGp37?$B1*LZ)mqkqdaIYG%n5%}L0{f2=hu>3py>n1AJ_Ll+vciu~oUrLS9XwFv!H9CmWB&QTC~$7+c1 zTuJIC7culw4FzyjB2uDAVO^h`>ui)h1o30^vYX^{Q{?ju%DtBp%}uT|kDvwy0kJhD z!AoL!LrQDq4iWr+XbdvSXMZDhtdVfMmQMN?Zo+F^sl`GW3DYA_hlD6*WT>Ga=Ad^M zv#(c}IX6zt;2gTw;G?4QGvXg>lq(}<|{KpkNSXH7qZ zAWQ0o8_dPl!Z}SX+0HT!TggINaJ&zvA0XBzn;Y(%YD3@?!i-%5on)Vb);$|0=(P!B zGJ8JB^EU~9VgsKJDbqG5KKpic`r*d{ZLppvelnlrjXI10);T}a#F%1_cQ0255P}Da zGJtNg8}lG`Ngk}HdK~sY#9qOYrNsAiiG;YEs*(UgoyhidW<_~wHLaXBOp^3OoGMzb zsPaLg4g)|+QOE~BsHBSfK;NDK|HK^k(nyi&`)|ia!T}BorB37SYI;erMt`BT1Fb`2 zrBjx4j>@4V*btZet`I~W8S3UDYx`t6e1{-=T z3(2#V7;Kv_t(g*dx`yVyC^#>-<8vw<N+J}$e zZN0-sP;_oZW8&2Ak2uEHZVEjz59n37H$esQ_r(gP7mH-A1zE$fgLDn|49Pv?xv9)0 zm~TJfLYU9=KX+d&DS2s(_We=Y%a7HWaNpL2Hqrx&6#fDUFGi9!1nN(l>zlnUE0af| zXfpY=$0>L$F_x1&ovO8!gE`t!2oX2vr%uR|g0Xk};X=%PhsxJxk@gTjg&E6m!XKjX z+LNm0JZ7$A2Z^(B_E`!sLt5ninl*TcC}ef`+DH>3cb6WDl}y9ep3%e-XS*;D$b7W! z<MLrQ`4*Dym$v@eeDm4+&DuA^>Z>%oyC+M9eR3LjYtS0w7<|M?A%bi!kt7K zM$t6^ZDzXp{IhhoYFCF0*^#W^@QnSmkgeYBReFMsGI-bINO!44^gC21U!d#tKuoeV zcgFD`Y?8?8nd~P0%%wKQXrVs%-m3F%TA)5r^+WvIjH@5X`_7^m@}~sK_7j7s{{0qo z#%F<(WK=A!98Y(`uH!r)%SqrtqN8v}*>elVxMy(|sU@M3EGT_^`v%~dN!`gr)3%>t z+G=BuApbn6RZ%RwMx%Vh78`H^A4QqXdyi?oXWeu->&KjTI*!hY|5BUtm4umF7G=3u zp>SRT>g8bvzMt?n5O8NVu8(8MiyxK@#+EDkyOr_Ui`Nq`f??d{t>`|~)^-it_t zn;EL_)A}DGf(^r$9Xr?dP57xW!2~0`TA@r20K=(J+|=nM1^Tu@E5lp+KE2paiYSnD zaNRon_y{WgafIr&KT)@ObK1#CPw#SgAJjn5j>;h(KOu9hTKkS-|>p3?eW{_zurAN>)r{QUlqqkJd_P`{a zp=(UW4s&_92xl#>ZHdDM*B0wW=G7%};LEV05%KVjP5MIIeU0#JZmJWroeq^HfB1&j0J(wd?oefe(8d8m=FqMYTbYrFW2A6RW$+ znGie5Bpu5n``eswOnH(^}hhRJNh>kXzmtT>M^!z%&DE_cXnw2?5x6H zhKt>G$1$D!RI$5fL0|ffegj*Zg!m)K>%ls!ex`asE$kBW#hu;u8F6O)>%SbEdMlwK zJm}Tf<3*j$kVsq##PMk%lXSo7X>9aDP_r0W1J5>8n?vZYWq8D@3KlE4 zmq(Tt`oIb5tfPZfT-QS7%CPnZau=ZWT|^=IY$3Qi6+R1?c=v;ix6|kB!2lvF*44JN zqpb@y-7w02u%5Ls3Q?{M{-dud`2F=LILgt0Cvi|Ym_mWYJu_W7ZJw*TC^}74`K*i* z&b0MexsX@)hn?Eoiuz>cnxe$C^1W*L&9qRHOjd8&U8D@6?VrTy5MVVOl(J&jY4vj` z`iWQ|Jo~#|zH#ZU0Fu5wV5?2$iUxd?E?Hgcnd)-!Q1smp?~)K%xwQmc0w7n}_MwJr zEWM%&wnaD*#&_%|H`A6Pk~!ViH7wAZ=SN6&X5}v|RVlF5edwU#dpy&KM^O34JslBh z{Fis%xP9{0eW&C|HZiE&g-UNljI(7PK^(cG_gr;18fN9WOYY?db*?Z1oo{cka{`n+ z1j#P4jteGzKF9$U3*cmhoGSw+p#cs}ahF@zKv`XhBJHnMxS8ubiH8tlv(7wfT>$S~W5PSO=zJ>c$myoH z#;f<>LsG^#g;4zu#(i|I(m0<7*Qp#v#O6r;n5ZD$=-i`d&Ru@+^F5?MptJPR&t7^| z>Z-uOM{vVUb<^g?1b?r>)Vu0$;{)A&F6lyX*2B{C%dgXwnYnwd;s?QYxlV7gtR{Sh zg?9q?@rifENTVh@XQEyW_B9R?_V=$}bbpORSiaE`D$U&Fa#z-m3A{pAK~5GRYiuDn zR^*bsh0DzJFGnglH3uoFK@ZjwBgjQxzLA@ze#RiSCaK&+>5p{EKmNY(#LJ}|B1##{ z=IDBkk1QKlZC$2;_5gzBvpz9{LrVR1`KfJaC z1PIqKjj&%x(J3B(>#x7=DFHodak4rM()CisDrua|mJ!TPT0kn;gE8@&?u5FW@i|`u zv}xlJM5AeR%IZsAORliMd#)Qtme5hAES7#zy@Pk3FGmtwt#w+bK6 z&ADxkoq+@kHRdf-uI>A_$3G=sS(F?Alug}^01D`@6ZzQTf={E3w$Fr?NYtvT#!A+j z8^WK(iI!595eEy~d+e&UM(_&O3+zFcH0(B5LQe}u!^~}mLS;5#yLziuM7ETLd!EiM zg5xAd&0VcWy|67Qv*o=RG4?nd#y^byOV_NGuiIV`j)6bSVuere<3GE@`ZLZ}&gPQx zHr`q=h=F3U=bieFoZxQcq$SN+PMNdAgHR;pU_ql7>pLiq=I0w|9=pJ({{oQ}(HNL0Xaweqh zqHr5b-vWnzoTxz7XjO4-hKc3OX6APu@s_6$JB!82UJ^kVPI~xYW=f6Ewv~ zqUkzjvw)MltP3r+DUS(JhOr-hSyF3F4Z+#b*dVIZ?~IY754=e}Z#MimO*dt0v(;KJ zrWYi0jEU;{*GqL#(TQhfUNvyb6lHN*+eP;^bY?}D=ECxmW<+&4o$1n#yZB^1hsf~( zz7Kmfhg>zKj@lOvR1=kjNdv|~ww~uJ#HtWf>o`Z_XfEVp_MKT$d(xq4Sueg3!G?!T zhQUfXILg!SZrn9Mu@vuZ$m&(W@K1J|PhJGjTr10E^!mx;%qD%Q_p$tcQN6*oHFIx^ zA{(>(m!g@!H>Ce06SK{>$e$e6(fo4G?{MAncFN|+)K6PCTe@2b(RF$gK9ba{GZeDv z{uxl^xe!hoE=zA*noV=ZmRU-E@i22zD3^;msb`%qR<3Wqkou2romZmSpdR0?voYXi z*aumB0*xuP!`ut=C=wz6q5G48EL_gd4Am7CkgA*^cy>Rwbo)pUW4#Y75|gX9b?HKn zpz1l1ucSl~q;#jbzZRmR;dJjo^j6tpPgKpRAPM%#D-kt59BRp<2Uneg5SH(DKU_tv zsSPQt%dgo@V35TyXqiO?WmNjFEg3X>PWM;QHJjA0$5Ujd$)AWML^pf%2STUztOyfs-jRJjjnZ99+Wke)gzm-StTi#FI&`Do2eEIem==R#lA zfKaL7)gx$<5fF{87``xL`Bz5<;Gw6I$(&5oH|NK0&ErOu?rd)D2?PBsAvAKXytF4<5qL|#>qhV8fEM0&z)G|BR+bPk*M>|O z>_5f$pmN`+n*=#T1J4x7oxXq$it?OVw%$#ZD6{^Q?9m~dTlT4?9kzaRd!uww7LO%3_PZ)SJcb z))kwg_x=p@g`86dH!E>qTR4D|6anF;IT7jND$1c0_~U>r9=sGK#oxdEo?N5Cu4s3B zDf?SrXK|{HXtx|=MZP4mN~K2itw-@kYhnG`(){M)_e7U621VBW#|O5&`*pQ&i8ziu zQ7QQ;m2mUI{-g)M;UH;I~`O6JH_t><1B759%_r|P8ECl`--7Ol!ImD#f>jz8|JxPp566Fj`LxIh&FNw zpKCbuIu&o@4VG$z@H?*!wMyj=Nc7(>3skBr9}Ew4>(pLsaX&Gm?wU;guIlAC{G-o^2dZ+Q+xG%y7~+X-1$eTiJ2w|H4QgZ?eA3RUsuT z+O$6Q5wz@R=@-)$*tg-OCg0t|MsDwJr;~xkyL-Af2xvY#O=M-V()(ZjBN=Cwj^enF zIw-KI1RpoV*Fnty)O6T+P1;+KS+69&COATs$c2`gvZ7#djM=uksgG zBxhZ-6AS~=3juQEe~}W6t+*>Y!l~j$6}17oGQ%X_;dg{&n#^TUrMDzZFhbGn+QZ=?Nd7~F z>~6g5gwZ2NGj9RqkhILCmn2r)2JIU@>xaWFu`!GRVc*t);*3y|uX7Q~f$@IN=w~I6 z6jjsO94@@B@L2Qo07W!Ej?M z$YD&;7Fbv$;I+Y;b2z6094mX@ppj@s*r!C}&;`|+9E~i7L%Fb|oK#QJc=bA*bVeZU zn~BwWbp8eL7QLUNrMLL0mFGh`&G_obq5KN+>3wU0T2l8N0MG~bA(cIViJ}>MGkF?q zc@_{Lit$lx{Vg9%!H%8u%MeU(p?*EmL}(8xp9}6R3>&K3!^`SYKBuh{VZf|7Swz>w zoFJsZIa_CfjbTm1Yfc*fhvOhzbW#@HE3QbU0SZ>p`f&5l)}@cF>l%}74I&CZsaM-J zj_e^Z#c}TW(y(JIu8eEqlv}KPjha2xn;z`>QE}WK3otA<;^hx~PkRKyT`b0p z>l)5}McPPxG9a=?cSujr(D%~({xF{~N>}|2%De(wMVzk>Hv)+>-3R6&D6XbZyqe%6 z$cz=hY|d&9g0qeAl%MPjPU$5Zv)X@A=#vu`5?Ko|!CWKHAPB2T;6V5cqHnCXyCHz> zYU@nmVJ`OKM)63`K5Njhr%a_5juuW^hF#Bet>yBfHW+kxSuyXz zJ6z2^Ylqz>Ux~ia=8d3lqc8$^b#ypC6&#Nf)-iujzmVSt0rxPy1oXa*`wDv z;7PvSb%+iwvJKV~ZN~2EaoFPTwQBusrtASuQ#-N|1%DenKD$&j)QT@8W{`4Iy@Ifs zKlN4>2)6Cf4*L^C8Gl~t(O^lQI(K$)pGTebviB_08ZJMo;mqy*Zc0~7zqANuuY6fl z<-VZfa5hNff!vV1+bWV=wXs!h{O|EpxPx_)D6+zVpa*!8*W&H_<&&oY<1O3mHY7-rsY@+zbGKFT z9O{?*S;uC_4J1R_k@aK;ja!5J{po>z2`1n6nYZMW7V>Cf8l&C}S)&U01CC$l$EA=5 zz_=o~Uh||S=rDaTK4&53o!%4OpQ_fUlWmkfHIi;i)-m0aWZ+N3q&5VMeZqC+~?+n@?Pl(KiNbvC+eDSi{wcqJJ{MRBmRo{mJpZ zKe-@Q*7{~(F`L*f&i%gKw|@PynQ z{dA{{O|yFNsbAA&Hu=qIO?9vEIM=CUcJ(8H7@OK#f<0w>KPZp((}|Uy`I6Ze@>h9+ zQ=Be~y5*u4Qqud{l-67(=UhySUG2M?M zpBC+S@2oWm6jHJ11(+a9N0S)Q-605X&9co#%J5FZXBJ#9qze0vv|;CEkZv_AVcU|E zZm2Wc7mBQ>svzn#uTMt`)#)L5B*s&)u4zk`=UUKN{RJRr>ZchY=fvB49WT3$$YV?v zwfH^FQ-Au^)pO{oSE)Y0Yw`OZiU4g-WQI-;tX+5`A1NBgwRgsGQ6kHjIJ3(XG|(4G zCVOB#SKTbmr^ruHO^4eAlU!8!z3E;|7Z9;}RkHC<3(h7)ut-2cxMS~^#AWU)%Iz+*O!Z=^d>Jv(zTP^$3mm6 zQq$RHO)*?E0aD=t%sP!y=SNd2UBwLf*2D>WH=0{ru)8atDz6)aHc`yatO4hF7dn-` z>9p386jPrLG`07L#~_z1Vo;5g0<({$t()Y{KyQ>x&K?i6_&40hD>UVS1==}p9?IJ+ z#ZEi9d6u%7KpM2z8n$l`Mt|XlnLX6(^-D;2m2h8efET+1+mD0{IPJ zAP*?t+j2^zb9q@YRZ17VM1g(sMG&ku4(Xrb^?Sthd}gUbRsaWN zeTfVgpFIb7+kjSDICzS?kR$9|ihS^gCR(78>HXaZTaC?*m2XJpjt#((icPo9hED+| z(+g`Zz5|G{#;t+Yf~yZt?A@$3p5KMklhjd8k#oi;4;4y?VaihY*1LeY5gZo-l2f(a zIJUI)D(#AnIyFGB#X6ul2@b>`m}9|5Y?~p?%4M>4IT6FcizdjQSQHGye4pq0N=ak& zaKQ?7r&r7ZKpE9t5d(u58?;m;!)W_4!f7-yomx~f2g#zmB?h< zi4wCuez^SOt(Yy9cK00zxutunNxY_gK_zW0`t9EK$133at5YnVwqKWhq@3&<^|hR< z?`Bh(UU-1C)Jr9l9mbM=A!aDLFvRH*kN?C3UJL=mO>G16(+~5Kr8R>*f8sB>?qPOT z7xhfxTSUoZ?_=u+DpLcc{%||WaDh9Q_@FaOdXTm3JB_sE3@?-HP+lO@2sVXP9?n9#$N?AN>EPt`TY|<@?=nzij4*U%pB+mFR!ZHZ_b599q zshckYpr?Pwc{O#I-KcWbz<;>hOFUqSB$~REeScN_EHu@QI}#ejXYy$}GCq-vDMM$^ zTWI}R^;m7vpTya$x>Kf`aBnDH4IQ#_Z~Dmv>&isA)X7GS$dU~5_FsMPgrtsKU9a(% z-c?D`%27lXzv<%>gW_eDDAIMxNJq`gBh41YHvEW2%UBX;Ma0*9m`{KG%=$)nCgSk4 zL{ywN^1JPYC|bfo9#nYi@)$#^2)({`0cS-O8iZ_J*W+Dgnq>m>=K|2lJ_xBUuPBd% zUe?v&AuoWHr{l^dmAw#|DeeBWDWhw?aM~rz6z7N9wS!X+2DIy3XPK&H+GW^SW9!Vs zhIEA%#ZSg`eQMT$IOscMujKCss4M52gMN*$bp^^wN_wT0qe4DMDmt|vo4ogNZ+&-W zD{zVg+aBIvmp;7m{j}Kr;cS78R#6x^v#%9YS~Bxa&Shjx=(+!>)&AybOL)kp#|E%G zM4%#?Z`acl%UlExI=vIuS)Z&s0QU+W_T&3SCTlKDb?&Oha&P>NAk%;J1n#?lShcqA ztKWdymTKQS)lSRwKbWRiJS}1@4vqH_m$Ayb06kcCf{+`CLw@S zzF(Oo7QUcatOEyE%LFJJjeKq?)sJSu6N&2alMWZ+gAg%RO1U&8PmdGg)rMnct6ehf;6zz1Rr9&_Yu0 zt|M%g1~WbvBXEGU(LA@$P7aWuQoiUmp#+|2e*+OpYPY`)CRHj9xwvn6XA5ev?{9uxXrE#oO)aGL@)U~WoI z`z9g>wE_zwVJ&Gls zLH>6BXY_B~oYK?0X0hG-%e7C6cnwG^P%kA`eljMM;5eoNmWB%ovUcweU}>z3sqeH< zQ3LD!L<@R%xv&YqirGAo1$6ysnL?vC`td^}+G5~2+LvC%Ax7N7AgKJ-)@fo{NPmD< zc9fWUmr*J%hTiP2;S$SJY`)9dPg8j^P_<0#_dT7U(u?Yv;v!wF3@ zzJY4gjXS?Ctug1X%;r>g5i%WdYP;^%iSH$+H#$tz=0fzrF1zL8RpCvEwJ~^0^BsYR zgr~)O{HM#i*DpJO;NTyWCu6ZQ@ISsZmVu!MM?j{lrUqJA6z46qM>{bqTBq;`n#md> z((W86C9D+eeA7;S(PrH|{=k#x9zL`e&$~-MAr$v|5lv%MyvGL+Wc~n{lF|fh#&I+W zsFOvT@Ei{_bj(ud^A()826eH~bTPL|K2MHs*P59*uy@7~OJa+_J8x`F(}gMj_VYcO z090gGKB6)v6|PZMF6@5VSC?iex6|5u&CIXd_FRjjvqw;8licG*6xdw1NZd@ZwVzYV zr%QcF{TSm&UBwiBfjKJdXLqdvyC{R|w@x%EUCn6VuATeRc@SE~cm{aR;+&MW@6`$g|qTKr}}P)%dWL$Bf)U_j10K3asa_K0`LD5#ej=7{beb#Q|QIHy2~`1 zvs+{%r1mn~n!aDn1+zAsWVffBCbd998%XB zgltVBelmq&+$*7(FI$tpZKoF?56Y$sC}}bJ3d?<^q`2qtE%~ba4Pqo}XsrXrHe9Ky%^*!)aQKwu4)U`)09s%$sJgb|o&>mylrvszN!e=%)j4Xy zC_QA$k(Uv2mqW;07W}$#aOzJ|i8Q~D1#XF1YTrC%Q3x%AR5KDtw|~zH+P=)`|DH8I zYb&&Sr?MrG>w$!?mAZYH+Nxyy;|fklgf!)6ZX|aCYREwo#gz(jpa3b6nB&DWbIo;N z9dOzc7KWbx)MxFb>7{6tV|l4nyt!|-bKBLq?t@js(xQxW{4+g(MrenLjDKE#ZY7&+ zkj*cW!U80;Tp1w~rQNGOu3v2?&A`X2(4XZ><9zNlQT%UzBw73XA%VCwhEJew$5<{V z@q0KMV9acSdGWh5j{AUgRZ(q*>Pand*bu%BTC`8434*IXf~;v90=k?Ti$}@eL2EHD zquMpp7F7x36Sqk?x=i{aKA?;#S-<(IAMFQbe3(bt!=q$fTLQPQ#Wy&2cL{EJZ zqVM$KRIj$V$fDu!fP=_sURL*Od}RRUHE5O{GZ*zGU1t90@2YS24MSWjY5QD+7^KP2 z1=~=4>c7k0>ITd9*Z zfPa*>*1hvQR9#us1h(o6aPw4J$UT=oLXn@{;!-$@NvC$k2K8#fQP6!94KK44=Wrg5 z;Ax*pR_}w?HNXk{qqU3>(n2K=!aZt+3EO8Rfd?hNaqCf^zTCcDf_n^vCT~VTE zMWx!>tA2XjPAwAr(MvN(BLu` zzAWxUkr8i<*76Oj950v;{s@}hJvXWN%5h$D5hu%_ZTz_`|5acBjweZoh*_OK8y_}9 z`>N>0yKzwrAKG;a)bW_@zX#P3j~Yy&4br} zwcRp|n=u~+BBXWRJlN!BrB}n+L6tor1KOVghTKQE=FH-M3+66;vlpwmP~( z_4Nrp5uR~)=V|b-T3_lkbd=HiT-5VX!%4m{jxN$EQd&htcsI8$281&BTZ`3dsBa!JhQo;pX#oj@-KLx zMq^-=k;dJ7c4j%U(TX%g7;3;5=w+;R|qz8)?@ zOdV@`_p{mZOSPe>+F;w~R!)rcRE1|RjD@)SI^M?-b^HP(M6&xIe`o0AC4+Rw>kr#HvJ)NCNU$zq{efc(bjXfOvadNvd zj--_@N})JQ!yI93BDcBmPA1!*S4IFZe1Wjg!D-RQ0|R_`D1UR(7V`H$0cXJMlAD=U zgDl5FdzzIU1FtQ;yAP#0=Xt(OTttjMt8Pf!>p4Z8*I*p<%}QhH((>=paRx%ozo0a_ zE$oiVWX&qGD32fs;*H_%=PKP!ELFdg*4VBeDk|!fppjM3AoZl)Kr?qrx zF10>E<^IU;#UM<0BT#KHh=RW6qPII|(P zD-a8G1;X;(q+*Fn>YW!RAYdsJ?Eu=HTKpPS{Ub;%Uv}kq0BCBlB2m#d5q4X;+WJqf zsj|dw$-sTH8S%A^bZZQ!Qd8vW!$k}2yn)*?gD4|hvC&Pwd~gzfUW>kS)U$uNd`RM( ze3SRL>OVK{gK-3n{JhqhtvE0(xKhi~L;fStl=Ws?a+;W>+16i#ew=I062c3qYd5&+ z?|bggy|F$AEYpMBsghUp3ec}1*K0AV#&AK2N~Rwv?+4DtfkeBosOgQc$wXtI6Z29Xd^B%}m}gn*Q^gE&V~WO~52o z`STwN=x({^+1yQT=QE?g{zA1Xk#k0 zAM-e5iiH*lb)(IfHU(8I7AO;6?h_N}{H3M-5-o-)guAaRID4A_t!T*v^2vT;&&c5HCKV;a02%Z`B4ZTFc_6cS6W>{%cm+rh2!I%ihqB!IeD_oL6phz zRt1>XlRi{BBCJP^C)sxSf(LehzwjUI%!}XfOyd})`Mt~BJzI8XprvO3iAqb^KrH1I z3B_zM9;vh{?JC|G>m;A-PvXREqCzwDBmR&reYXn$SfACO(66(_+t6ml6{82EIN|Yh z_mC%{at}Z0A~u|H4vH}v@+u1UxX5WfBsGTswWZ0Y&D;2^he!?2o!tV@(Wom?dsjq( zT~_lis^FY?*%jF&5+OpA{(%iUS zS2Qbx{=N#4bN+Xu2Uoc&5Wr!ziYr>QN=yOzJakj;aI05TseHK(Udr~M5U;C8HVg{_ z9k@e)Z0NF6xd|2Col!0IS;Y^$dzU?h$E}9TA_rHzt#PTdzWBe}CgM$+t{80!U4AqX z8ov?uZ$Oh;!SAxQ~AVtHQ zZ4{qHo!K6XF)yi`6li45UpFg{FZ?mxdO`R`XEBp=U-w`lG8iy@;#x6lN7V~GV+$cN zM)*D*BRBk!+-@Kgi>i9frGDh)<~^#SheG#%C=1y2#MRIOhI{g?>%b@L3KC2hF}t1g zuX7KGXarJs3;^Uk9Wc>Ki(ubRkb)(l+BlqY$0{|b)t-ZbOt>i7Gt)#uuNqV-8Ts8X zh28Rsgk*fiE~bQ7D-`Q-AC02D*)#5L?WlD3;?IZ!lyU}edgA46;j2iHnE_G2`)f&K(aH|zYWBaPU6j*hD7g{P(e zVOCHgPw(E_Q0g5*w}i+Yx8(F#YM{S`rtzarZp=V-X0Jf8Ht8nryGV}A;MP(DqQe>- z3Q1Aq2B6ZsS2dZw=BuXbXm;G2XtPT-x_Q3cqa-~~9l#${g|4_r_jlTx-QH#wxkOumv8<~N5kZwL z%`t}>d1pkG^s7AMyFhot(+@ARZNXz*ugM1g#S22bV_Nf`+l+ z&sl8`l1llA&SrjN7ia01(?KLjS)7N;mym)WbHv8*(=ab}(}du!_ns(eC)7gjSqIo2+MS)kHc{Zh=rmwrD#(ZigY5kmL z-ejuw4h%RIA;_zNkNGQfNK;9O+&UA^f_Yw8khSjO z?a$I5l7dEl7;VjSEnbC|syh~}=q7-7{wOX*~7$A)ou0(l@BM@~f`xxH{vthR93 zj}vBD6|PE~CG<#zL6QmG+Ft$%yJ&Z><-Adya7FJmGBchTV6|#bUBDf;>c_FS-HD#N zJ~>Z>wNvW@CZSLCk3)c!LO);H*~W|b7sN{NuNU?usgHa4fPB|;gA+KCcA8I6t3sxO z`!VKLP2(P$xx1uhTu_!>0oPzxuv_DDqcz5u7dt=eTk5_KTd|%M|I?>c-9bkJCW`nb z(>~HYzr=lpxL$U0tGszf$sU7b@m`uqZbo_I-%U{0u$Zf|dL;48HYu4)9(d(1U_I7v z#VyIVlsds(7msb4-zBpTxn?0c=GK{ernBgC^48zR8+$H!gDA7(;OImb@M5Y#OJFg0 z{WKnKPlm?*cGFwT9)v8C$vovJrg!0RY8Gxt3*byt1Hm8Cb_W~k6z*PtXPWS)RQ_D; zOT@`A?Ax}=7F+X2wIv=E&(sW5HGf2nmFK^%*a72OjBVOw*+Ez3R!3TEWDqMQR$C77 zWquIu!+0z8H;ydZ)zCH|DleTN01Nw8T^oW>E64j6XMD^4G4O=NWN^dxHK?Pw6S_1A z{a641Dnbx#jVy8t=tc@)o-Zjk+l91!r)NVee%K5@kM}e1y0UDi+V{r_AK1PChXTil zis}&(B<^facwF4xugG8eg#(rJFx6UY^8_aUhVq)K^K+$C%=*c%U&}0u2t5&`nim_o zMcj2QtFN{?a0|Qx)rJdJEU4Etg}XkEe|EehpRLc)h|-h(*!jk{G+m#3+=xVve--&0 zh?#m;hAUg^`JK$k(Z^SiaW6R#My}zCrYkRLD;Q7HHrEIF-E1(xADvKD3ubFA;G?BF zAk$dhi%N3A=++5i@|}#p`AisZM5|z^Xp1E($$KN?tcfN8==0?RC6;N}aP`7~yQGfW zanmLZXr{@K@1|1b4E<6echE{_ry+LDi^&PBJI2$bHl7CR3hBJ$exG&op8jF_uAO2o z+7z%oAH9XAXVdP~58G4{EBrRWuFS@96q6Y2s4l|YAT zFU;s7@D+4Zt5fxJg#XcdqyKw69X$;6{y`|*+p~_LNiJI&wvOUT=`+fbn+(PyofH-Y z(%o$#FwFUr2T0fT-TMD|Ww@JiJ#~$1ba9U^#jU;V4DEPgVKge;pJ&xWJdKNWS zVB3dQGg1q&sD*$8^Ec0Wlz@jC_|gy7>ms4e(jeG#Zyqm=UviG^f)nlI)|7epAP!K{ z*Vm=qS4Y-q3B9RD`7w1tprc+O#7ycVS~^U1Sy>q8^g_};u`QHB0=@T@KuS5*zH*PL zH!q&H0zE*S>UZQReDf^qa<#@$3eguUCK2kf#OMb;4JAjudrATO^<^_t6w3xQ#P;IT zVcywDSf#~7cB8ef$YH(ON)yduX5F4Z)mV5`q0JilQ*mSZqI%W9=q7@P$W%wR-j(*v zAC0V$V%c*F=yp;H+z1$AzN*_txdhiv39phFy$rlGbf^SIgG1dM!Hpj!R_t{ny#R|D zK`vo!4Js4|9cndXvQ4wab~%jIvfSq3MSi-vE~mRHpmE49AoQw;DY)}{ln*{xRrp>O z9nZRf>o{Vq&-9J~I<=q!M{XHvq}_qF$jl0EEMp$H|DgPbQoS5=RVnAW9%>i=Mf6|< zorbY6h4tB$(o+eHf!qd^p_rgIK@G$%OSEynG0vQ_ETMn8_6sn%Kk8qY{hMIzjq+Be}tKvZRv>}d6! z28tEI+z!vIr7>kYIdx~FuF3{o zh?Cq25V0tg_)Xn@LAWwsc=E3V%##>;O%mS#086!ChRY-Dl3PF#qDc3AHZor46yJGi z(s9(FH${KwYS~`vtT(Ty-&SbPI5LmcMkY(qQMV#(ZE;wCN>4{mn?#z5-E5RHk6c4w zwUWDTec4YBawZVs(~I z;`>KwN+KU(&dNQmD9mhZChckt{->Pjzn(Qk5U?Nv*T zl>iTYu2ASAlW)o`gF6@{4F&vtvsK;jC}^A|Q|Y~VZYl7WtAyyw=WopZQecr+805)b z6e-DzZ}l%`UWrW~pBUqR>57E__BH>s4c6@Ld!D2{@WLR#*qNS>G_ftGGIT6OI^OTZ z$)vqM#|)t#H)lqZwt{aZPzc4e8ODmjWJljvHH6jgoNq;@CsG+AMBXmlsc1~pVX1>^ zbQV{rw#86emQ=ou*C!RFLC}Y~J$Wtwy3_PU*|`OO?V9amg(vdL1j>IS*Od)lW9&SK z-zh?BeWMk+=z*w_Z<1Y&D|C{1%JN-f&~s$5U7 z>URlQQ>-|S-<<@mg@g|FMjfRE2!?I(b{%~LrrsfJx0`WqoL1Mh@qGBvDDASP z{^vQ>K7Q$icBg{f;uSLzJohtY_x4DTpxBe&I;<#_%EU5RK+*$^!@Zi;sof5! zttnLu2z!mcidve((;mA2R}VDzBv39FmFfzAdf^77B)FKqxESDmLu_9UGSZ?)f`+oT zm|FTrWj44dln4Jl_|$tPv}yz^pOWPmW&1}%C@`R8P4wNb*iq-vCpQs^X!jEw@wORe zA{0HJ`j!b(H}dbIzi+U7%5qNwh zYrI$VWIal=IFl=lzkJhO75^QdZvVOPIb^mue#D#g2*h7922;xd_Oz^4L$ zjoeEJS2pD5yn*~uST;7c0k;YXYI==pLQ#(e`X>w{0|L~#YvY~M4y?HV{;$? zWJnIQVwjTHigp6$h#EAul*8)b=h}Vhk3ryt1dT)x9F3Y=K4WA($U_wNc>aeHX_KWi zy^;FIZ=#o~8cWzWpCEFx&>85yqG^d58X7*3a}`EuX1C@PkyO`oz6*q3auMbYmZX7# zT<7oQgn(aSnFtu69X&90e}4PX3LIA{NRioMJNkx0c?y1&rq?!?bAA*nv4V$l8naeO z05je~8R5P*$kZmYpxP{;%FkhFECj`wH5(CGPc5+`f)!id5>>1+7i%O;6mIU=JNqZY zAG#3Tbur7v^!KTGY>}?>(inHe;AIKWL=~N6R4UJ7pOnykV4?5Fa!V7-_NLO&EKa3n z@Xb_sbeBr%tZGAxC&iF5hCsBF05VaLJQiJ+qM&>0UQuT2M)gCS`q)k1wiXQ}lKj(i z$A!#y^znfIN)TKIFc(ctC4eoy<}~$q&y3%uW{tDpe*5_xQS+q)|WZ(TUdVVL+dbtU5sU5F;n$5 zY7t&K*$tKtdtSGn9{(cpIWLsIgDA}u^Px=E1%6BY?E6jeTIR+7p_b8X z{8)vGU>Xs$&HfL?d=*i>tT1oRw@Cs40N;L=FknuSRjY02nB1;wGQsQPPl%-K_3x=2 zCF(qtj?ApfU!Z%`mB!(jP^bz&4U=WO?b|4qSUdJpO8jjKI_8f#lzYb$7d3U}S2yON z)BP&f>Ya)Gm2@aR6c`>={s3&9j@#0)Eu~j5Kv==B+R2w19uDu45mPJ(iDym`+8Gb+ zR~qU||&(9=0Y1^4+KdjfiAcX$@XM$4Qns$8|8CF?gfY{drK00jG z`GO4)?qI=zrtDN+OJtHM_>=K% za$}{zq^p3he6K*6*}(5DU_J>H8!O?7+aA9Y=*Exr`>V3N1!xbFY$(>RQR85n4^7}c zje_9abR^gDN+kHBcib_pGe2cisfSyy<1XETVYN0)#4P_Bu&%}Y^&tlmCMV9j@Ubf>|+ma?3ra{n&}s#+AB>Y$}`T*^fi4b@ta`k_Y_Q%m%M+8JJTl6rB78iee`$Ts43FtJQ|F5 ztgn!s?pAViQuMnydSiJ&mb8!No=lWsnR2;9Xjs6V0q+sCrUvqfXp#!o4!Zp(Z*X@kJ~G1Mb{cpt7KYA-Nu?Fnf1Zbj$+*iS$RM6fVpt*3I& zcp^YLTC~EIjL2VQXLrVsAe3g?jwc*Dq|1+EBjY>c9;E||`s5(GwKd8B1!S8`{PLm* zC)XGNj~p1sEpHTYAlA=tZ;YQcDiGgE{uL??NPk%;aR| z9+`kH0!an3JHJnEORXW})b@wr7m>=wnYDvA7PkTA%fxR7?-p*4v_%?Th1u!YaR{G6 z&z`Ik(s~}2dleS7+4o7FwN&D2)}{&)9GEOEOQ-P4x1^x%VR)(3g*LF3U&O||UkLAh zKuv8TiYp#)ruZ?4t3&|(;mwh6^(oKd21Vs}VAGSFu;EQed=HRi(Z%~lHF_Iruwymg z;k7G~^h#VkN_m1&HBlXB$T^lh^_rs7bKHn{tKFO(t3`AEegz}dKR=?9khDsw{ zlKhxwE3dIw;$0AjKRQJ|30&&_Ce;THfV&T4dLD74vDJUxNnZ(JUKV6?#S6W15u(#< zn6piZQMc$yxJzxIfVJvE$SuHgB8=U}?U+ralLlI%$mR>IbHFK5!ZDrvDX)$7j32u< zxm%k{u)P2k@bCg3x&{(|nAJ0WWx_ql^YvV(7^?9k40T{sX!b;SzS2N0J&+Uq0nPsb zdx)7|;~VHZHzQxt&NAmzWEE1)Qka|-l2)=i^{>w>f4n9h@-nXT#By$zdvENCe^N1! zZg?>61oNt_e=Q21yG!iIS6f`V$~m{_`}@W9+t|PqdL!ZQsEAjtpM^%42CmBcS z*8=u;FN2Y4n@hhBWu8#OnZagWlr4gOj5V@C9}H@x$#WrnA5l=E^Sx*IeZbSSG(I;~ z(f^^a)8DIgghYkeOLC}bT#w#qcwSPj7O;fbCx3BJ^5Kn5?=LC7k*Yyhi{XawFl0-6 zIsoJZ?!KO%10P{;{~Fr;*u3D-_Q?}n;XavfZ;t&AqHu;MmEL@WR8kZ!-dDkDPiXCo zo2K*&_vTZ_KpT@zSae`9C3JH^e)TBzd5zc=Gc@>bmfIoy7RR&LiSE;5g7scESd0KKxd_ zz8LpwF#Y{hGfxqHgzJy$nRq@!Rr4r9n=TyZSm#MDqJ-%34b7*i?X``zXtq~-W4_D$ zlSmAIKz{i4yDkKw`Uwb?8Y(&5gq~Z#Sj|Dr4M~7H>G}fJhAB5~!<{DE`@2aq&vA!S zQu582!uGIN{a7u2;~#P|)aefK^yJ=Day>TE(cCYqQ)+y|?=59-Sxx{%`@I-6()y@a z_eh!NYy;hnEDzj!rABK^`1WXgRr;KcGqkqmNZ)=x9I)H!N&8>evZx@|h7l5uMJQ$& z(as`MczewlVL(5S0&=pY7T1+IY8Ty2?Nw$c=quTBM3*)f+KVD>AWD<$ep#WgzPv}E zugU59%mkG4AIiLSJLxcnaO0wOgCJCT+W~co_6f|!@j*&SSQaZTOg*+ZWdoXv;ls2=}QWw0qh7h}z%d5G+m07dIbM!dFn= z7(a2sw?StT705VRfG$ZiH68Ppf9r1Ea1C@?U3tmv1P*yvM4Z+DhDRxd3ye16uT!~G zS9^9Fdxw1#F^(FjyKxVb|1kX_G=w+}>I=mN8UlZGWHQMQu0Lq&_BbN)J|*$s6cDn3 zVQ$YK@WI$o%VC{nPx~)36~qH(ebg!~Q-98UwH?bDsP4J_c_o;j$?4Ie_v_8<33v%8 z@niaZo*DTNoORRp$MU$>fsf8R(ywkOYAzhF+}7wSwYP}(VOVUxEpj+!S4}UadT0nf zl^W?dES;4atj*u?-1^Ye6_Motbr$eD4txAZURFviXMW#kWf#TV9&zsF55H!^^#~Av zQIH|OG^Db{r5e|QbDm#k59E7gkj05QVXlH>%Ts)ma=UJ?KjS`zKrc!;Jq|@f@#&I` zk==k05GbrMxAcp2!((+9LSkwcr18@u;!A?W6t-cSC&xH%L(#gPO9x)C?X_-q`2@=?owysD(S}+-MtfQst@0$YifeL^It&$ z$HFw9-sOG~)#H-}t;VH2jDaoUwtOY6-Mh$^7I<=^qUdV#U*JhPo(T1L+3*vk;4V!b z6F%GX_cHou6A2N7= z*~j-Uz!iFqqj9yO&W2;(SR8P*=z+QyrVcp<4KFChdk6x`y)Ph`3(bv!Xt_Nz0%0Ai zK>6I;?eo?+{{DA~{~zJBGHpoAz*@tWUe1LK>5nr(EUJ^=Lh zqo7gvz9aC?M7Zn?Fl}YgQvPho3}kAU3V4*OnPSeI*q~$oe8e6I&~ts)$Jm=++S#R( z!kVHLKYv4VAMpXzeAjY3uhe^vD`*B9Bu|Q_6jkYrdmImYs6am~t(t{Kl6_{XON^(r zB*k%+6ybSR&d}1|&5m=SX`q3i;irMXN>HMU@Vj%a2l5R@(#-zRk-*Z&@G{~c*ZWY@ z$z|VVVDg1Aw4#^yp*lYI1DGDM;13(qDf{ZTczTNk-S{u49TN>bxIgS1>yC!_fJ^tN zMeK4@KagJV^`0tvtIOwY4$F@m$T}BxJr8yG5>$m?7mZU>V);H-DHz z#^0nS*@``^1ND54^fgj)E=c@yBdz1A4w`;J+M+w5m^!RU)s|mgl9>yIFk3UiW4FP$ zc?j)nm911P!$N2tia84QnxNrKs_xB9s)?mN>%@hi0TbRB4$`$xnk$}XH|}4{Oxw`H z&eV;xtB^1yT}Qo`02dH1D_{$&m1@7q15#=ZM1ZvW(>c|R2gdX)K#0TsokicLcm>A) zP>jImJ?00L1no0*q-+I^Qp#U#B+*ke$k8U63|`H@JNBBP=E!O7-6el*J?m$@5RwfT z0DB;32cUb~5&>uv31|wCbtx@BI$i2^R2hO}D~e5=5til7Po%j=nPx`twc*#S^@|-V zfZ7!0)Xw7J;w$z}j`p3x@=0P2o%`0=3kt`WnYQQM3if>(@gCu)$6nW4DFbD{X7^g5 zGE&9MZCY6@Ll^a?nGo?2e_JrX<~5`3UO}Oc&~bBDAnEN62`4K2`J|tuz{+G z_Xp9q$@W%(hzW(u($%wHhqumfe7$l%V{}w%{oN%cqo1_KR@GsyI`gO_`{^--o2owv z(w+53K_OS6&6YP!hsh%F>#{g)ogRNeN6CMvb;)m>lI>O0)*2Sf+~*(Wu{zR!H$(rJ z>azJiX=zT(e#`SfgC;3^s zy5Ii{Gj!qh{+hy@nfEADn|A%oT(K=~?XaR7S8iyh(#tv1651+|CxW8)KR^TUT&$^& z+}1=RC>h|Z_xjV3F8N=syzqL=ZHe(DaEuY5oh5($SAL0J_izOsd}84IumqUJX7zP8 zr_j28bnNCctPVkCuB7dcjxTps7JH!!vDoWRa;Cx^WwZ~PI<-eE~1VLcdNowv$`20Gn9mIT1?@S8pYwrM4hLsIaV;@>J&% zfdoIy8K7?<*A+>)!3WtdT#4*&Y2eq~UTmlfT7Ai%mgFb@ehF(KS>mH;vwShaQ#G{~ zoxvz2-1ubO4^S^{^s>u=VU9$38Lp^kM z>VIx<+K(iKWres$)!$6*qLfD*Pl5LJdQa^~eqo~_>#I709ETl?+K zk!*8hN)OOGa1X5OpBn>}AARJUDkhhG+sS_!bHs&n3P(Bhdk6?Gu@*eGjNkUjZc=y| z+(SPK;SoY*u0O1-1xRB~%|=@#$r+a}YolhdilI=1C_Na(Pc^nYi5JYeYQ>y#zsoxi zoWR^xUC=W1>8EM;t|9oUnGfy+n(@myjL{wMW=f+VwFXO+GpQ?5VU0B5R~^r+j5Z~$ zC28Ag44o5dFTgO*)%iL9cqSc@sVuP$>qG@^J!~$M#whp=#@E-ZN*RIwABv*2nt$nS)zG=i`2N>ja!xfC zvC&7dUTZCBM(V_^*)-Wos~Vo2DOS`GKM2!PmFiAYW0URVD09*DQp07LmQQnER;7eZ zIKkqeJy$G0h=b>&ByiCjQ>{gU3JhQ!IGUEJNrkqR>#Rpj5wA69T`?(F2f`cK%rR+C zjb$`XJoBfcjlm2BG^sZvJ}h}%w=RP|(0X2|;PhSX;b-u)whlZ7z`LHi?sX9KH9a+$ zN$S8ZlU-+DJQzF3^?4==_w3*X1vSp;)Un3_z6ksZ#+MW9K^rWBEmffDO?IwlAeSIJ z{h>A%wA?TN|Hu3N{5ij`?6D{kgVbLT-;3h~YM&KCQ)K{)V6*c{Y2N*8s#|^!x;K~m zq>q$xd6lI|z$f=X1iRv$cb6A$s4Z=)v!K&`kRaY~?DQ>E_*acLe0-oNTMu(B+jpAL zl1?n!_jK?g<2y2pP1BQ1f8qeH&mlz2yVKi%U*<}feBxX0GS6gmS}gBn+5JH9^G`HX zyRdgLRycOu;S(#Up=&^j2@73y#wEg5=WEjRwAwFIa_CDpZigE0@gyP9r#+&UObT~P zmc*s{OV)W~+j5};f`{20k4RD@x`rsu zsY(a@YK^se+RB1${QH2viwB%&&~O&qM*q~v5r_Z+T{Hg6WSK9|U;GA2DTf;CQ`*H8 zuy!BFt`cIs0Ep^%ho+f;p1J}qi-&A66|~K`f^aO=%iJv*Lf(G|*c$j?R%avlvTR{l!YMgcoYtJG0*DaqeLsgESibyCj-IVQp&*_( z`=sET-KyAc7*DJl*6=3M`y9cP4shWxs=pGppmAxWSxcMt2#fxoV>`mPc9EDLeI-0U z6cy?MJ4I}r8ov$v-s`F&3=dGq$)k^~+n4?iMVh>{QaBv+Vrzh&%Q*OhBb>>L~tT`i~@e^nvdykDM;t0;@g#r3JdZ zL{Sf&Fym{=yp=f4AEVz^6Q(9Fyp7LGlQfbZe&oCJjP88dq>9<{Js5q$1ZkV$kU{hh z?==KAINoh&u{1m+Ec7P}BJ4oBi2I z)NQRLVefJipwWuEd`MVN*buz%4tNr7#u%1R_hr_P1!F#sZH4@GS81=PhB(t2(pvdP zFI_lag9@yGB|q|@1DGAq+E9kDjz8x}KJ{ved`;QRd3^p=^bA%o zwNxzh_jlDrkyEAEmH$vO-oILk8Hsz|0&soTvuQq}O_z0zhM3#ol#m?Se}*G(?&Y>d z#PJY25cgcuNI%pzD=Ir|aOb&k>VNkeYt5%T8wHELs@I~afEzYqPGuBpoS^sI4{O$R zYa!nl(M0@U2J1OHRr8~5tQTEH2LzF^b`z&;I|G@qv5m`XgfMHb3;o_}pkB5D6vB*x ze?Ym)3`KZx`D>BTiT>xph7SW?3~xPyuY_g zV&98nyM8Nak9SDWFj~BXduw2SQD7vLCKMEWO;SwPR@Z_pREGBuH%kA;ztUZ^=7-=h$;Q5th{o_5BNtD0dJZA?}vjrPXgDL5}|q1rf;#5IY6{%r%P zaPXwKa7bOG-D^Y={NSSAtk{WMc|Y^v@gZvT2}7)7prqf~Q2>qkLi%JxPK58^qlgFP z6~_eLU5|U#>%wmBAoCg;KktsejbfZJR!8lWQW!bDq)3Lu4jKT-Wvk3*2DS*rY|3E4 zJL-UUd14jeI^6oN4?-omdx4hklKV3jP<+z>{U}Lfmd1w`!i~p483`rObh_IV5&fB} zrSOOcIt(x1?Uv&P0_aP8K$O!8@bHPsuvK-gcG_MGv^e0NY`dcE$*F7R3z95ez>X!? z?JLk9AltARlZ(rY4)*8f9bb{$@@*eKGmK!%oj9q%W$+!9=JJ0_VJ;yoSIwOGVLJJ+ znP>4QhL_ltRraDCz645-ng-l5gcg?#e78Fd`RCL7##;+I*;hUd7t~EwGUMMEDyxl| z)wJw}?^{jFWt`%Bh^r-WFNamqy0u$@*u;a<;?`g2-skcGCJD*Z1%~12wB>5g%2QSm zg5^;LicGQ9k+N|Ki+G(ki{3v7l@(DX2o+JKB?wWJl_wNYm32nxU_;K`i~lH~+qV>i z+>V)WOSj~tINiUZ(uAK%A{si@^)2%~ntk#Az@mOP%FTamUv4_!SJ}RcDB=0SGt-Ye z11_v~zdBxdJNi0_=2&G&zG;l2b>#U@yd8`2lu^uW>{GR&t2ofaIs)tsakDvYlIr+Z zqG=V>PCZ=&U0s!>-lco-x1kEHxLj@%BV(xdEweiDBp$%qOCz^TW`FOE8oL*Yx?AE% zRWs0j^sl`oSC2k*ltU}2fJf`xnd|<_Xtn_etEi3 z*<{9v;hE?k%p8hW9^1pU^~v~)BP}LT;lJ}$@xAka_$x-$2Qijfzcj_H9jl+2Y_nzq zb&qV1p+K{;p*h#}P8y2@vDpkaV>DeylY=*@Jow`^2*>KT)q;#vX$cpUw)FGv?0F?M z)u-FHW$VX!wYEz1f}Q`N&~_oR42ts!qQ;K|TFkGC7(Z`5ePmc+q?X3>hoB~gI9P6C z7J;KU(;eN=PAYd*>#*{sm<#F}qqG?@u--brTT0+FzmTfp95SIovPR$41r5|DKTK3^ z0p+9Qz`*0-HRI>m1aR5Qd$CW=FlBs`TqfnUr2Zw=qSuu#6RM|x&VDUid!TbAe} z=Qj^Fkhwm5x#%l4z*Oe8Oc+Qr!_xd}=U$5@;M*=&LPoqN_py$~7wl_|oK zMV*XSApvzl@-qU(CUu(mr0SNq;8<=LaaTlCN5|ARapYejq(}KEwnywVWtq z?g>aqzl40B*_u{Ii^No?nA%@P`RgXtox2I{sXefvkC5$dCWsPkJnykzu;WxZW;=Yp zb;!$)(DVDa2}Cf`(ua?tKAF2chG}kK^^>WS6Qsg=u#U0LgLSLEy{YN)&3fXN@x8Z3 zt!I|O$ZtV~^}V_lz5P0S8c+-L)SC?Rh1P*557-af@U;uz3mZ~PCd7svBN4x3h)n;a zj|bmA9S-iE_tr5A>sEE+ic|&0jFiZ3=vkTF*S!e&2RuuEJ8{l_T0Xy@@vHQ)1*)DR zgVVm@A7M1E^Rb3gs_OugkjX{{<|i&V#^er2P1%(gsb$4si>&M0TZ`bqf~>4$m|0XzB! z^+qqHH3&e4r1 zXh>%@y7TrX;G(68r0gd_HkBjXPLG?9w|kv{L3Y<4epUY4$xB6QVz30p7RH^@zxuDt z*B0mx6gplyd^{`xgbqJ3tLE<*mI@y&7~dO8HfGT1Yt1n{B)Lp$uqE z=u+R<>`ubV43OJJKI44q@w!!5=Ss{PP6lSEH=^H%4*0(pNEP9z)^x*gezVC_lf+ zpq7xb)e4IG%oOh!>3Rjupw7#ix||ha7a)z!q=JDQsSBgUOXDdmX z50jZ=ylmE!Z<(EJ=r__NP2gnl{a(p<&UGOQTUpTQJJ*qXRHik;ljQ5%pXCnakeB`t z;K^2URDJlsMRS{)Q8{k%{9gwGsfQm;&!m(u5kQP#U+9|nGQtI*WEdrR6Lx~u1*=S2 zI)5DW4HX3#Q2d%o*`IjVJQs@A00vKY_MOoq+wmg#ec=6UgJ%du$e1FdcMEx>0j^8! zE!_gXP%pt5T%17DE9;skQLWxr<)9r}DAhhd;}KL+87yz}AB>xyc2?Vy-PgYy49 zpZ-a-LLpfn{JDOlX)ed3>-F@Eeg7W#<8G@3+MWI(CY=_p!p(PNZ3xkQonR4pmb2)A z@K4x8-jW2D9o#>FuRsw(QhaMVJK3fcz2eyzP6~wBtMexeBX|aB7Rq6a3@@UL;mdHo zCwIR@Ithv&h=x=10L`3{FO=!(~tya>G#=8FIg4%V^7>m=v3Y#j-0yp1X1X_~uJnBS^3&)jl`EKP#$> zEU}q+NY`-4bZG&)REzpUI*pkfdX1 zm?>fj;eM!lfA+e1&7Nl*0LH*0{$Bt6i8G|hxYMgL(dEHp^g{MhB4NBGy6tf63{ypy zJFDxkk(D~@QJN;62S>26{|_j%U{=ty#F9T~#%N%U%RIyZ?r;Q=F;mtZT^6VilFnym zf4d!jcM5p&0uZj(_`DvE%opy9p!?$`QES)JmFZ?@GykH}-V1mK!q8VmWmu>EJq%j6Ec ziVDqSk_0`ojuy4Z37PfD{+B|^+b2usuTOrp0c!8yh#p>2`xilY>BrT76GiEa+10WG z5S!k1frwZjRs-B~)If@AA)?_i4roJgr!l`3$!?^;%I$uXCJ(NpELqok&2}^x$WjY= zZLT=-{R&>^Sbf)J@GExqsN;khSaEe&Q>rU=)|a#CSobqJx7A*Md~3W;n&lS(>3yyf zdlU3wD#hjKb}7KtST!AwHP5Z{hLZ=(JWYKBXYFb0AAY{3j6uOES`gdj!M!JpasI}X zOl~XWBY1o+Gw-o(cfhGfK}ngWRXM+kUF*$>I)!L99i@qP{k9MRSVe~9^#Ie$F8(dA zoz!xV=7^UZj}J)h`ZrgF&RpOjUDv0Q76j*4+fre3Y$2=k=E4+I#7T}#(RhI(G=umh zd1X{9zp45(j0Uj=oT`CkxThLfnfw|sU5`r9nD?iNqhfEh{GWa}g63`>POA9#YN$e= z9!&@04*i#uc>~>Q_%i0Wi2q_SoHV3r$31^AxaZx@W+dv^P0lp)kEdLh_%ZKgXo9pvD`UfBY z=O=tniBRWqKp9yBlU4HMe6!Euzj!XxC57&o$$hpp&UO=(CpCr|_H9YZz(I&9VCyx% zBEuhU@5~O~a4r(zn;bxta0V(tm9pU4v`~jp-p8sR3Cb8AO&Ez0wg;3!AdI{y9(qQJmLb=+P$MN0@HzW4# z`!;c82=ty=KZl-Vzs=YHz1Fr?PjiaX%|~XjQ z=G(eNz6~k4&u=jS>yxXI!=GTn;RxEEK9{AovjYU9<2av3O! zf>ZVKZZ=A;;$R{MDDBv~0vZQOe*#qVNxT+t;MD@H9lj~Y_^bP4_#fIE#P=rrRf}d_ z_KlKWzU(V%GodCKuW734@g(xI&+c*cL#@-|?q?-Q7biWQ$^`c&2Cthskvw6-WIDj} z8^HCWaE4LQb9Sc(cihQyzPsz}WX^baiVk}F2B?g? z^FhylKbRHBKq0`;EfWaUde51WFx0#Ap?$$zna&m8GCY-h^#hN6;04F^-w)bjlEX(rCY(%4%w?*@tUo2?aK??-rbA z2EL(Vr4&bY+adtyd*=@TX!T@P$ZdVhf#oaFo6p0ZPe7o6wbSDJ6g$WUi`?rubuWn)NF&g*- z<%K{EP-c-s98&wsaeM!!i(<%_i{1N+$93_C3v!%w|4JiU9rO2y=FdGv?#I}&Nfzp{Zyx~_2sLOtlkpHzt=kUgGX(A7nfcPAA zL&DQjP}#rH$p4Yci*OZ>MFSz3K@)Sc1Z-?np=5;O>q7DeEn-Do)+rJ%y3!*Zqq8-L z{B|i5oxeE0ZZJe9zxWR&2OG0537*rlCP&8p*pme8OQ*Rvs+0h>6f@gQ8r$Dqtd7+A z8?S<76kmH{o@e*;-!gR-?9cpLpz^OJzzxXkm-|0+7rn}^7r>5cVBhz@%GOEWjiIDF zyBKaZoQjqe&8TYez? zsie0{q6Ey;N~w(h?r8>;eBhq`cUQ{*cQyY1F7TxI@7UoRY&=91SX-*K!3i4b#_}V( zmS>ad#Hlt9F6FWdzb!7H{x$G5=&y=X;8=VZ_VA1GTLGOv=MBrEO_#!S5rSMlp?fQX zIJjK|5`#rCiz{E^VZO+$BX$0g<|hQ^-)MyvyiEHtwV|{ldNEl0zmaRU%UN1_f;D~iN)nIYG=x9GB)|0csIVjY1_}MWFVdpp@ z244!taCFly=@SEIyt3c^qU|Wx4{5N6M*Kg~$c_wHl-L;FF;OfFcwM$+i}gMUMZ#is zMLycxgt&w`)0PHKM>8d!8%}UjaQjcO_)WgnW?Ko6zS^8=ooi_U>gbo!Cv^gkMXfUG znp%j1xXXT^+deDVB8r1t13Q`drt?u+Z>nN$!@vU#t+*Sg?v{u&hyPGIg8YuMHWUlYZ!t)MoF_Ua|5xAIJAPK~4+Y`Mt^z z3KqD4C~SL~W;f>9*;i~a9KOEz?05voo$`kQ<}}B)Ge1R{#V+615vc?4F%{qkYAJX> zZX*Z8_LP*{7fn@}wlvw+_AOx4T;FTGLKZCs48T34M3bdw*Jtauo1=rN<+4`n6(-=- z$g+MOc5_=Ib^VaO{iU5Gk;e@b@6l}2`&E5e2fGik133wP%G{X_J7y1lG;;Tv`si&w z&c|6w-q0#~PG)Gq2by6%<{0sPdX4-iKvuz+G@v^5;<{JrJ6(~li#Zp%vzR(C3g+m@ z?G*D?n2Y)YAWY@MYoxbU`p{QNrb0rAUv*QqeY7IqY&Xirrw5!U6j9H~7TlVH@eP(? z7RL17WR~emy*ht210sgmOE6B3B=&uNRWU_+`4BDSKJ8^ke z^9^GkXzyNFI+&88)jVDUzPE{fGoeGbQoWF`%!O-$=c@PvFyDKy)g?yi8^cLO%6DY~ zB-lb6Kc8c3lMY4&e&9AJiu7We%(K#F8LjuZCO9}`Y2a%AN|&E(H2E6-vqaxv8WRl? z1F(M9y3a1#prUdA8&$+#WJg3nSajYk(5=-5jBD6mLJDNGqRLs?=NcQgZkoRJqb~fA zhm~JUQ*Zr>iL0AxXw1Ej`L1b!g`&~-9;~BwiK0V~)du?6#yI&W#d2BMUk+DXxzICAFDvI8~=_EH6{wIw`DpHINb-MyA zDH`-!^wrzK1oQFfD{K15Pd+~N1)Uf*akqXrRs5nAr|g!;`8NH^4oWHcD6_p+fgY<& zAvh}PM$yZsM~wZhgH!%UdAfg*v5{~w*aLb@VFA6 z^p5-#b4N(+7sR{izMiFbY5hAy&q?yE%fhjDx|qEl*X@cI8-n|)^Wut`N;D1-KJidW zpP#xP225rafzmGLz0mTcBKuA?QBy$UZ5;52l3KSf9T)OzWNl;$TrYQSw5FFdEtmX$ zAY?>+=9hZrkB%f7GUZ@eqb!?1SAt4dqCVev0_#pOdH)J=IpfFg+`F^&&9GT3?a-55 ze;C^g1#k-iYlUFCS{WejKG8^eXJwQCh4~3ar;axJuUy-#;a|EnM^Tli7K>vXT1EUO zR0A&`1V-y5gU9Ex(3*XSo9|R-eYGa$jF1x3942n0lM8gQ3XKw`0sR%9#UD<#Os9(> z1?pp@l}o4RWR8jSanCvX+#XrShj;$UQ&R*IM(EM!hOy3wROj)ii$8nI{uV^6E)4=o ztoXD4+g>O5{{O;?1&qj8X)*D~DhLn&Vc`{dOiZ-H%3)u7&7-j%Gd_Gi9$XZ1x!yV} zmK$|^fYrGqskTwkiUk*Z+k!gDrqZMcrPtL7%X{fpj&>h%fdFsWt#c9?Z&kGvKx4Jj z|Lvc-m%96r$}4o^r!cK zL`siqTb65fRb~HkzNd06bfS0;%H-2gP49jTKCBf8vq6F(no1y;M{}Q1(}J4Tu-)fN^tQ1^g9TRjhiNuCG28S3F%IXMo6T-M zG>058Zx>)3POm{pHu0RGtDW^mZqFt&fA4j5$Dshl0j$SL0hvJ?*<+2y01;buFah|*32_<(Ksv*uyMYGY@)G;fVe&#+%B+btKEpus1{s2{+F_>Bh~NX$!+(WXcN+ z-l212#}G!8dUR z!^Z|__gHnsmSm)qRNdKd_O_gN)q=v0vZAc{Y@owu{IF(ZaV=w}65?f~zE)z`D9m|z z{YPT6SjwoT$(SoA{llEg77RD&UD+bz5Ns}+29PtMc>i1;XgEt3R{lVX*vyEZyU1S| z^PEiDdNoDiq%>_YS*3BhP<`l5lj8ck112+D(GX73(nKywgZEJ^adSutBn`Fnn7${u zUzSb^L9l(=2)-RpMgjNOJXQy%pvaF*gLlV_lBM(@w65{xyfBWy%Q39tXTX5z{gc=Gl&Z8yG7^5Cp%Fe|rn>w|h+bVcAYA;~fYA!hd#a`Qw(aeJ~F!ITpppWDrT>k`W z#ONz^l(aBmc3mg z+A%bM;I=%T=H1c*dW&eyNxCyLwL@(uo@6$Z8lkV28Fe~d!7E4A53ZlkXEUO&rQJn- z@yr#NJX@DO2>i!m;I>|DpI<96bb4HP0WRQ%n8VFKXMasW`}lU+c>t5hc1{RyrR4#|{wAd!=1v4DTyH@!1Wz0Qv}}=N8kOny4N#Ky0d$bL;*Y zbYWivyAd}=R8FzZeI{<3qX~L?F|eC+#u4Ug7X^i_#sHW`(oJ`o^pBqoB7B^zy%a8{ zaWWVk_Q@27FqW}7GuG_Gr+X;Twf{g8JoV3*`CGOw)>aK{FYNYWU`?+fBQvJs@vG?` znlD|5C&tO)0@nrGO!pJb&qOAxSh!bxiSb_u?D3wKFb*`U2~@ps3L5pS#hKtBqsFa| zD7^&l(jG(5#FNs<{&U^o|5Su49~6kc$xHNKH<+ z0M7{sQ2$9*FB{Jc?jv7CTQcA=)J_*{z9# zbQ(47QntHGY=>f&aEO$g3$*UftNYy?>w{e?8b6u!%87yUA|pa=miKY4j8k@E6IKz+ zwaAKF?F7E5vH37e>MS4u0Jee3v;R`X-d-)WW4QT#ByR_{vA0&V$-1D;m6scaIP6Z6 ztyAdOjHU?gUhL@V@o<47F@d{9=%`(Q7lJ)+*jQ%EG9Mu@-<7JLvre110>aQ>PR8$c zvZp6vsdr@7#%Siv2y=OtCrbq&@SM1>>sy_c+_503rCdmbWN`Bo0cx*9Y0g{#K}jjEJ{1rbq~c#G1De)ydvmz z^?5QowmZpax{^JJ?7zw(&=4}Xe3E+fmPs1irz|^l>z-Xx_*v0c*gSHzFNZ^XdpCy9 zvRU`Sm}(#L`8WT#Y`AqmQopnhz(;ZP#_=>SFvTtS!k#|iAIE{#_dT<(-Bqpnr%FfC zq(gATmRMd*iG{MDp>9c^BNIKYcwy`q^Yg7lP?ptqmTg~bGv^98wsn!zbXRO>eezC% zhX?=0r|+$Hc><3!iNjI7CMJ+XsPu-imBabG0LDWP-Y(RpYawqAowcuu>W4OkMn|uJ zzwE0y=G?*JTWj$ct7?ijfx8f<)33%-Ct8KK@swH1(1?Z8^Q}wJjKSWvH}0CXsh_wG z92i_x5o8)p4`tS7v=1qOSnJc|?UGUQ=}Niver(khaivaO?BV(ASgb~@Sbsc0k{utW zvm+>fSH*Ngc|UWMLgvw@^P|OvF~viEdfGpd7~3o_MKun`P{Iv~nI8o2#vDa)7)u-i zLTdI~GrFF$i|ursz7YT-linF8MCc}9v<(0;2E_-I89=veT#zyp~)5j(D=$^U|kL>;C zi3~1*8`YQ4Nxf<1)W%@xTn~^dO4AJJ%I7W(?xGwS!i-|7d%XFlfiF6`UL|h)sbX#3 z+#)ZZI8j~D`q_1h9C`HnSGyuB=Bd80NyKk-(PwTEV^eaI1CC?8KM$2HO-c7!<`ogR zPN+PUAjp~{kjcQ@?p-02_3jwqVH*t@N!#^6KavCWa-QdztCAkY2mDrx!Mi4YcTS?9 ztfSVfB=7CG1@8T4o&*|7_n4%`n2nX!z5I*z=}w5qpwV?%PDS^c8t=$Zb@)G!D1;@a zU;$=vz}MIVGL4k-c7Px0pow)KNQ_;X{$X@f<`@_DG0$C=)s%0JAD?j0O=-kX^5O0D zl4)Jz4XTDX^8|W-!#L+%juU^#ZEx#yeZJKbk2{{*2VwgU#03Rt)zf>b&tqcTFLPQ1 z(9_~rsRrSv?2JH2?;xN^t%zX622oGOaHmZ+osBhcpHez^KO&m$W+TKfXA8hQ>awVZ z|3E*ibPb7+Vj*I`MS}Cc?`1i51J-v&aT0KfDv?@uFHD}o^JmRTCo)}BpP3By=%el) zS>#c4%UM@KUd*Sb`gbO&>A6d-!skVk{uN74+WTO%M_lQ25@ZiGdw09ViklUVCg@gN zzMijMB7o`QnZO-ZBHApGU;I2T@|=^ypz2g_4qv`^jW=4#O{&l zLu+KFHC}h5Jp8X+#W<|4<#%=klMgk^x^gjR|BWd?9$#@3dIH5R|J?}@vN1T{cMLtd zQB;2zw4?7gS%Z}cCMF=`S^W6gbZ zAr2WZ#3ro5{uCn{zGYAaeA7S0W565Dp9QY<4sZXaS%@^5RB~oM! zB8jJL#~#9zTkTF%?%G6&jD$R%9bDW1Ryt?*nig=TImnIf4opRJ;PKR<6R8Fdq|FBG zl#%U9TMOCJ!sOL{He-Cs!x*nFRw=T?#qK_PI@i8O(k9}Z>KHa^Yd%j)Ds_pDv?86u zIO|lM`F%fw+rT^R6?besk=7+NvV9gCU1`NI!vROuqwnYDY<||MvyhIJZ`OHl&p}mw z?t?8YY0#u0f5VGM-1_=~uGqSmtb8Ki^iPhh!Zd7H{q~7<`Y1)QTZyyOwcM&uZ?gzn z@IJ=vGI%Co6z5q{cK(UhHyYBJIc0avAO@MWK1bB-%nA5AYL^4^#_zbX9zzP_$=U0Wu0x zE~n7_f$=ITw_~llwRz@JSifT_pNZ7if|~ybzGZ|*PE*!;>s03bQ!8F6_P2}UOU63C ztZBS)t=Y&epMGiPPxDuFuP=#zhMr<~?e<+Wl!-ds*@C_C0 zyizy=`u)9#cfreWxhp0eE~)cjzd_Blvnt^)Mj75)V7$SnG4b^KhaVG74k7Ehm7dCH z`c{nq`Qn_tJ-ukK#rIOQPIG#ZV|Y~n87l`*ys46Hy0y22Y;B?d3x0dVIGxu?8hJo;+ey6DNo!l}54Se~R0!rp7=toOVl$8+^PST_d77VDh@` zj3c-%mYD;c%bHgPutxxHBY7FC_t8Ky<(8V8K4+La4I@t z3k<(r-Hy7XzEgeq>GIeb45Uw@mYD|sTcgW}mTi}OO@C1w0q;X8-geiu^pRoO#`gEz+LH9~B;c;C_Omw)8w0OcrvK4b{|>7xWufj z>$I#*+Hm~GMT23~@n;wpOW+#e7W`f;ZA6&jE&3h0qD1jPaGwvU3tp*iZ~vz)@I5|2 z39hCX{hkaaXb}7u2neC`O|f5scbQiSgC%Ca#tA#Q&a;QZcI|hf@knv z=JzOoL@-9aRp9YE8d2B$}iao)~V^_tqh==mm-2jt|mfJ1cTakFgAn{jx4&f}dH{|6$3 zut@Fge&=IA7zF{}Egkq8&3>CDVpU`!7vnP!ZZVHQ4phCjvL`RYaK1hFiWypeGIXFaFuxhdOB>K`{C#?ewG_^4V0r z@+2qiV4A{kn$x16@uG@t(iSyUy3i>hyrb5=B!WsjK}&hSt9Yua9I{^5&_w=Y7U;yj zzi$wrcFe~5Jb1-}+`5IP;^L80R~Oz*;6}i(Oa+f23K1oC`5MiWA{U#_29k|}h%-t+ z>-TZ6`;EeRr)?xL^|s-h)0AZl_o;4)E1FLJ@$uPBCyv^z z-9?Z_Vyw-up9|C3p+1!oxot@Xeziz4HUl=#25L?V85DyDqui$adfSD!v7dwS|3?b8 z2cS7kE%V#hZ}aEQxA806>`32iD=y)paDo~Zf#>ZqN8yA0`4JGk13)rcC;Xy+VM|-U zHufUAC++wcU>)(cYc^&P#|`AHq>~QPF$PG;H`}@0ucy`F6pV~{{d5P0atBP*#}l=K z#-#2?+P+ml>xq8%F_sD_k{AVOCwNo=fK7k*_EaUt!@o@GTQ7o&5iv`;@W(q0pnGUs zcA+~f^2%$@?K=6?wYaRj?#(0R{bZRUi*-i~bieJ*lD|f7EphL43GA6U00)lm3fsa`LVoTJr z-)j6n&!0rn-I;fLo7PLIXf%}C0CA6b&e@SvZ9)48Zskq^3d3af7p4v)s-x0TCa1{b zQKXV$?OSt~$2d|Nb677 z`J=j__DMi75iYYnJ2oza<&{?>H4yV32(#!V6tBRrzeCj?>frpqo}J{1{?R8SN#cWtb~L#+;!ouTgMX5MKVGCI zGjSA@+8##>TZjAhP>|z)bLgdac8-VB`#Rdhp79Vwfxt6+&v3C3CJ?ChX5SuzzT1$@Lw zJ2}%jO#4@G!OI0>hl;M}Z7`6vnASNoUW`yRlPxoH*@w56pxLxTY|)+FBFatv6W!9}D{gK|-itn1_8~cbLZ`dRH2$xKLFo)A z0M?Aasj$zR#PEnoizv=l50vVM%&P`bOWJ%Kc;bSiMor^a))C~F!?}1cCcnE$erAiE z=lM-dpuNwU=h*oV z1lY&r1N4*sKp{D}^1YTH!#8@v-u=D8+y<@!$^Z3BA~-oRGW$CT_wB*=CasYZ(Ho5W z%u=|+y~1>2?&N2;79WC7q2o;t!)y&F9kyWD zFJ*02CNTZrf7Jn4^pQ0L6oqGXQ{t~oB+Ed{NB))0pLGx*Am2>9tMzTj&rkU|^%$=) zS~7Ic4T{=~!BcP;nsP;x$UY{5JIv-cWh%PISsLUQyRzc;ET6?Z;am8ga;+@zCmkA1o7!A>x_-AIQG~2}FYZ*(3kK zAA`~b-;;PG$?X?`6)r|irro%9pHDH^i@AJ;zrvP`a6b9RNRbCpmJKX?a+qkul-`{a z6K;)`iU!21D>_-*af|it*m(yuF1HNIs7i))GX)av5kqEBQENLrhal&=24r*&kU{k;|^8bsR>s2 z)56q}K8pByIE7_`gGr&IeR;qn)(re3)(sJ|z)_=T0%5s*6(tN1`|db?OZ6f0mxBX9 z#IjR@v1td=l1#h?6yY|orC}Ji{+HnFd^S<{qAyMZWw^MA^^^SLIdo9&xnbd)Y5UO2;j~JLb;i^qW7-6!C>Dj_vBqq%eu!s z`se|zEB^3$7eSF22+K?4kG5tM<bxKwU;yOTNQ};`=qJHVvGbK1J1+cg;jbXZ|%cYw_+OT;r4d z4Vf*oQ~Rci*VplK6F1sQM5_J|iQY5TdfR^WN7jIriJfqE%nPz9fG|OM7$nz0(WQy^ zF4QV)SGTM0&^|MDA1HuaiS+MZMP*OuFHm1IJjjYL9;t+x(hmfJ$Tw5i?a04=jtN+P zU9vg#?qvyqY3$&aUWU!4uceNjZ}uC+1$Q%FMc}ov);8U`ml;S?hdY^&bkgmae1om? zmVmpT3#^r)9g+e||Js5RXl20z^LLRGQ}qdl%c79}>?-ZxjbC9wdivpm@7*;H(U8fI z3QIQIN1_}QwTL*bH9e^Ji~+vlbfC12XDr?J2tLq6((*F7rhUD21` z&rWcm1`<0sx(CMSEGXkNqXMTMT}jg<&x6i8+oGipJ)i5pm1d29oM^^<&-@;hRlz5p z6Y8qSC6m|22gzVfo!2(;(DKB*Dy;)-V;aHj|1#m3Oz*H~y;gtWd66aG|lTX$Iww)k51f;Tnq)>;W6o~1!F z3WBOUIKN5|^@ttwxGdPWCIyC|ARuC*|C!%qm1aPv9yWEWD!{?DGk~#uy!GPE)z4Zv zh-rFQZ@L&I#j}j2HFCtztHaH5cS03TxUo<-{$FTz3~!bLf>FanBwW~X8W1qm zfp=LWX`nB<`b`yf(_@7M+nuUZH=zl7oRl?R>ACu_fiS2p+eR`ckIH{%_8%HuHyZG zkAJ*7q{l(}Pk*dio}>^*@qq77sE=F9^)-?eFK4$SzDGz&Z!Ga`9e6c5jX^Z6-AC8V zUpwpr^BcnQq8bvmgTTs=W;k&>t~9S7v0sQlZZ96Wo$Mxyr+!Jf-BxRpW37zii_(x= zM@ZoGicftb?f!KnnO69xDY|xFUsc?e9sTCA1wlZr9P0+e27Q>(+E`sQA=NT|eBl{( z#SDbd5In3%E~s!{$h9C#E1eYBxmE=ap_s4E3TwUsTvJl(>y7^b z+&&R7B_k8h{-RIx$c_w_HrhGBIQ3&H}CIkHz|#YhG%VL6H)IGrE%0A zlqcuHF--5s54SGz69W(V9FoEKYy>s-7Hq$Qep*7tiboNod-M`TJpg=dzZ16ES?HI( zRiN$_a!`P{Zg?-OguhofaDf~w)wnIvORu(-QU9MmW&g`DOVAY$jx^OOIPO6k@itv^ z#X!ODrrP}_HWOU%-lW3*~AsLMHya^naqV(+t-=ru7F;p%i`YrdbtaFKMl}ma^*IB4mUlu!=Sv*QRw? zJMXnK+rHUdEgggoaKG0)#>Low_O%g8SHSvORp2sv{d@7n;Jrx#;bgRgN|&P~mqc0G z2cz$8UvRl7ou7KzQIuxLu$umv@Y~cE+q6@Mlwb@q|1R{Qh@^iMK{+9N$_Ajy z^8hiM;@6uMfydrJX4FFxfOcT1#ja&^I`n=6V(;a@*5b@4g5f}><0m4wBfW$TBl7+S zg8x8K)`e%&ikmc|RlFafHpO>juAX9h`tbb78!i)>xc`jXK=0vwe0$Ee7yrMTsoAE2 z9X7r62Y5#?&dVs^(uIE0=OR|`u#S>Jwo`@bs8zDN*>u|Hvu5ZX-DKdNJJhEtEpnP~ zV)gbBE)G)D3V9;CkYF7R4u+0M$go4#SOndj2 z$mngU>4V9YCniw&BzeLDc6|_4{80^qK-d(Z&4pB2i~ZAV*Q}Hnc#{AG3YHjIfvIVBDu|F0bq4dr36@2MT3x|06=a2g)+R13={V zg?n!tx?H>!I=9ye{)jxVM)veXX(=)rB>Ie3T$FiuXp2S}C-SXl6tzEdwpWAsORBaY zTIKRdSPKQO4;b582c5Y{3FG1OyNeR$%*YMJtcF|jKBe?hcMH^$??9H_!kyF91#iy* ze}C7#!qO4x)blhMw;ngUZn`R(;-8zMxizHsHjz=M8?e68J>hVBsV3S#$wP3xi%=B3 zaXOVJt26i{2{@2r&4|?w){MGd!h3qD``wK0g@G%-7c?-TALo-)Kbb3bzSMqTa`YrH z66FuM3O%2+(h+sX+JPmi$L((FtWFKVA2+wtbij4q!%~tnhKmB1525cBPIU({5C=M+ z&x}JDx*l-5=G(&nk^3sTlR*EElolzyfFAbyNc>_S z-ouC3d+k674q~J=*(m2t{{`==yJDt(nosXd(U59`#cRCo74{cgs!oiJ>yUy^&1Vgj zsYNRW&=+S$<;u0H@Au}Y5sR%hK`0`LZ^D#pL2w2)m%h3Zcr>?KtBa^aV$Gd-$##oy zDE)of90CZJ$f#P8Kw_gzoHFrvW5?5{GgzDd2zi8k6xli}5Ez5XlaDc>VdPX+b+%^L z%>Ejr12b%!{>B#4VG*-W(M()rCe&TR4aE0;kxkiJ^Y?YVuN!vaG`G1<}v*h1>AP!h=FzqK`LPha;|I_ZA9^ zh%H8fcj9-ptEx5(LvZ%3SW}*j5K6I>$-YVa>^{JgnHOHyvXSr1GrHQ4S9&lB^@x~t zM1N?!Q@u&9DZkdx2U&4?u7lbj~)x|6sq&v6>T>iuc7ymY+(BZUe-61 za(XPN)lCst06Y9mBkAQQZ4&OtzmOSPcY%{zdl(h*hK4O*IaXE2b=MpjAXho(3dSCQ zkm)}xfc#BmSK+5cC5hB@S`^^vKF2i*>;jgt5YQ`c8Lv?LQv=$Z0vni6vHaMkJP!bb zUx>!R2=-&}vecRwACr~=2|7u6chPOMe)I#a8}g3$&Tl%~L^w)N0QGUuluoSv$U2nW zju054W2?V@_Mp^hv7&CH@q*x1=67Y@lm7<-ZX!5I0a>>`H9GI*DQq6=_m&|;aJh5^ z)M2@B#wU)!si90fcICH1zS$mY`ZO)t_~yg-AoG>G>SZsqdn1Du#HXu|IQ$uXq^F=G zdT6eA9(CYqjzqQ+)+vHajt6B6h&+ zi$CYI#&>FcmAxMX2g-sFy=4SP$h}yuSG|4ha6H9Pv{ko{SR$kJ-{KCpqIXKJ#eKLh zN{F}B`hGNOJy4#slWp49aUCQ_r=*~E;AdH(QJh}27`s-NMu3HUpY2n?s)HD&SAkP$+Q-H3%0uL9 zT^`)27rRKGw(?w<5LTcM!IS&|cPOR_Yq5>piZ0;^9*L|%U;Js0^I=EF`Phu!!%RIs7r%g}SN#g7i+->rrvEvX?geDI4w@RJ(I^1viozp|5*IDmW z%v=4%kYA%O%f`I~0?O|rB2n94V5z)IN#sXiN&(AhFP!29-F(276OR`T?;a*U`}hLG zJO0G09UD_q)C4Uc z?*k$#7}htzQ3f8_^p+~6vzH{}^aGHiC2CK0_hM?wD=@ljH1>yO z%T4Gyj}q+y!1v%>U8P~JALU%fs49?Lv^xMhg8xqyz2WV!on;}+ULa7y?N;9E$a-6(5d zH<7(NZ=$&f;$s?(*@5GJAwoO&9b&L=drs_`0%(6>$LXfdAL&3b#X%an)_s-i4JVj$Xi@ zwUA(tw*HiM;A+szAzP-%c38oikPnsp5z~hbI)oQ*;kXU+1Q=3PT-2I%!D0!Oyef?D zjA5@3HnEmPZ>T-y=q8^SdW~bW zN+VRv;BVo!A7SbBE=L~_UQWGXd~E-HF>37pXA=D(oC#>B9p6I=^e-?`*c!p22$eop zQ(!Y$6Xs@YJQ-7a!?V);FsdZWj=-84J3BXE+QkHZu?UQdb@;_y=oQI{-cHk!v+z7$ z5<3yeQ&;NfX)J`#%sVF!eO)Cp0=efK5(1)@*xZ*qkAiT zQ$GdjdlTQ5?BabD=9t$pnT3%H)OG4LLO`WssSte(s_E@rCU_9>h3TP>Z;QRw#eCg3 zO_arUXFrv5@CXxHCwHk*opY&pexcM{YkeE8(5w;govNuxZ|4MwQ)ckWaTejv#V-gM z(CQcq5th}A7tDhVc^`EIY?MbpU?ogqp`xF&iV%=rsQvZndgd_wM>L<>QzUb^meu+~1Nt8Chb z+;HH<7Ig!%SleM(kcENUU;PBHS}C%^f&W1LydzuKID$W9!9lDEIkf$z8`ig173Ojc zek3E4jHgCgMx0B?d!6iV3ws+-7J*i3?D$V{%Q9O?Jm9<)v$B>)WK*S@mHh3N8`OLkS9-MxhFfb^3mbxZxLga ztutP>)t~!cP{gI)(DE0rqAv5YtX|TiKS?_Z03K?hh;sqhH7zc(>gADr-l261!kY6X z)3GSthEW48g%m5PHpNqC-VNQ&4shopke*rrt35SH-2k_Ucnuz0frm;cw4ya@uvSy< zCpX$+<%3ZN$ODH%hf7`=bX*mOtUqaVaGS|dPYWx+3h)Q#5xpNQwfq37lfCqKB18Hg zsM75B`6#;1K16%+^-TQ%yIJ(ph`g;tyS{dh>mkpVEw&t*W;N;ffHjx%8osk`Egcz= z=|k++U93T4MLE=nb>_sx&8${%-i`|6)#X!|!E_s?RH|K+RL;?;a3NJO5TF*kF&3Aj zG)JZZHU|L+pWZ}x7YZB@YeF4$dJI#VFzLtzyuJiaG^K4t`U#}yvrd_LkE;*#%$@?( zw3T4RgaY-^{i7@z=dDSU+V$+d+hbH{)!QCd(j zYbtQ7<@}H}px$g1FKX^pn|1c|wpQ_!|ADzf?ILpwUF@^7Qq^*F@{+5Qly1yoHLa^Q zMwH*7=+`oBj{$l`);>(Mk z0UR5$00*E4^VQYp`yZxZ6&x-3`f>Erwth6S>G{C$On5sb5$@+~a8GXoD*(kGTi^MV zD!ap@f$J%BnE=f<20dC*{yz|!Ay9A$oCmtjE9}ffYe5)SrCZ$-x1EJe4m^zqLK|Py zFx4<=yb+lh`yBi##}|cNU$PWHe|9@0feSyD&y1fNEbE0gj@3aHbjgG_SVRZ=mp>hix9p8w_IG1y|$bxL=B)0Umv?$m4lyXQW-J_YFup7hn& zo5)aFBd|&SX)C64asfQ(QX-^mJA1h23!=wsc4Uo#8ac>QqiL1=GQ0AFvy9%ZbOQ zcLjRYj;3v?7muLT8gA!=i5z>_Lu}{NQ&HN`nm7Jj2wNJb7Zl=ap74u;q9VN4(B!$kjNI#W`9o97y$MvOiqi~dgmMPWzMSCpMfe^Yq}9P z)j}3kdVi}izOjz}qSIsZNUYdI3(aF1!TSd5L?xtE%NYD!WmesKv@$s1JBz-igI_Sz z6(O{nAgj~n=!N(}DBW^@fx>N9;z)N5HdSwThmjknVH7gxcZTdu%T*!sK#`v>TKggz4_fS&nG9sXte1emF@-GiZ#-2q#rVxYBseQF`Mj z+Ol2GsW0pAjYbB%rU2Y(rWn)#CV+@5L-NbVWmH4F{U(l(B9ldHd(@(=_$YBDNy4Mh z%%^sXja%;UZf2T9VER;OOJ6SE7rS{9)0^e7ZGIbFCf-+;T%%I%3QjTi5EVvD!|F`H`f$?Y5-B>JjFVt)2)>mhdUF8))K z5%U~}#7fBsulth{KqDqm|1>lZ4Agayq3YEBTgg%qo zUhVnG|FM=(-b4&ae8bpsVi-K;_9QTvC6asK_1X6h&Vd>;ZPY{Q)>Q?$7}%;3=FVIH z`HCu(?wsVHfS$3E`GXC{YF>iTOgb?bXH4R!y1*$R8;o0TmiBqg)M;Kz*yhn##E$+q za%7N;u)}nkn)tpnFR@|?gS$=$Zx#V`F=Ce6iVLTRX`r+%;ZpEP%YuvIL(ap|QmCku zf?SmbA~UeHFLn11x4Yd-21tl2$#%gvRUo5PaeNVnhbL+;C!gAzd8>#grE53#J9fIo zZx4g#qL!VSY2w0B322A3m(MRUR=DD!!f0H=G@oYrm zt_6Mj#dCI(LiMpe;xG7U95?S_hMjUMS;ln<^BSz6%E*|u{`NN7dHs%*fU)ofxXQK6 z5wi_+_&}=&?xKZdS`Dbh9;~YV5=-2nec$?^6Ke5tAn--7;27k7ds=yu#u2qC0IM&0 zE`ymewkqF$Hdng1&~1%HZ}}30=9tIk8UI(@3s1ApWQzA?(g-O(7v9HzYoI)`z^lRd zov9V4$Lo(M^A1-+4>b9m0gpzp1iVFB3o_pZck$&}M6}HRg>li0%wO0~cqeheDqNT3 z4yW_%D}Cy9jV5KOv+!)hX}`{NXJtQW`Pt#BHc^QP=> zuGV(;y~M_wwVUC4ro5TYr};Xt)99P*S;JCUPR8ML7aJFXV3Mc(>>YCH)3P zbeg5`f4taI_bmmTjH^jYenVVhscxuXL)z4z)8A_l_TQE)_x0St8+aP=R-fc>2$}nO zA`~`EB#~QgNY*}=*|kj?@&7#iZR)q8HBC6FX4C72h$M9qqH&u^kM|>tQXqF z$WR0iB&V;RwATPRcw@~`e{8mH=j<}2w@21hC~3(L44%(e_NCRvQsw#Bcc#2aO-OIB?(V3aBxA)~MI94iJY9n^1y z4bvk&+0a(K0XVsNw=ShEv|oGcO@Sx7W0Wy|Ru}<@x~`^baPutC@wz42ZWhDeU&__o z$LoDVicP)gyJ?Q6Nd=_zts^I3PGs>#o{H|zqrMK&stqOLgJOIWC z6cP17GoqNOaQmQxH!{$&G`GzkJTj{A`#I0E-3uIV%h8CSL>Ur?++)E6A|N*ofX*?6Cpm*TMPIA2IY{xEt=X@EAS z0xi#vN_g`6bM~3)rgb_ZBenGm8AVL$7Z?yQl>?+fy`(r%YHr{so&3}J|7to5zbM}K z>o0($XaNjwHO9j2P5M%coKL5@>dwku8AXJ+sW+n(roJ3ow-OOng_1S7hm4XYPimI&n zc^f7*>$T>F!wOlet){>Dgbbx-%n}uzC_>_L*3RFZBfnGYe*VtH4%n6CVGp(JSG2YCvL7+D^}+D|F<_5J57{il_9n9U1xt|cLEKm&WZPq)$7=ObyJ@kTcJdN> z%<5I$w1wMu@U%cgfSdGM<0BjE2pjVHsSo=ZJ2PF@)hA-{qJxR53Snk2QU=w!4>3e?(7&5)_z5-Kh96sRWG zOW^iqheUhDMxXNT-W>Tk1~?Qz`HUm}1KoO`4!z8W(iRk=`-}7jZJhCx2*qgTe8`n@ zvUzko)5vOu;&spH?th*~JFroEjtF8T$h8ekZ*4VDH(yOXp}1mMdw%2FV(VQX^KtQ{ z8UPY~D#kKWOgoCHh@0(Snrzz4!0l*|lRC(dTJ&d9MX~2)pRO#WugOnK4m}_1#o@EX zQx#f`9#iH591BDL>r1eD{C^-#8?JA8PiiGDXRV??%9BJ1lokYXtVqha>WmR{syQXPGh|V}r2B+CnQvKBgfu zOLg2mRh!Di8$Dc23_;TS3*C(xeY7ZC5bE@C`<)LF^sfZ0%nR&P=FJ<+W_@aHx;RvQ zN1+e|c&l|Y8bOcI(yhWDWsz|BBw;_+22JoQjyZhYu~R#>o+$Jz{AdGR{|a6PPz&C9 zu&)a>>~hMW>R+@_mNkDWL-Be5aNns!2>2k4(P4-kItw&XB+!1xxQTx>cCR;kB0#%> z$2cGCV@cB#ak7(10_)-@I`3-~9JcSs5inC?qdz&=(LcG|0#;k!WyoNSz`SBD_uFk%asHFP0!b71AJfPdVCXt;@ zB;3^cT=De>w>)_Opa3w_qk2?x)m@E=y;PLpKcElw$S9A0J2A5*UTv$0&Jo}LV4-~tnb@=J$;a4>P1 znS{SdBV>~31_JO%kjC#%Hp{*_@!pz2-)$(uI{>3JuTN2aeVfM5Cq(qqUPF!at^1 zeGtPzqQ7^oPC(>F_Gj=CGgbv6B{nE3 zDI%)&)t9yv#>5`n=feli6q#8i$=4z!&UlfkP0rrrk1bAm2zT=v7Xwr=f10U+zRae- zoT&q!FDjgs-2?8N_8tEc{%!Xyuth`yMyl^l&M05xbyl|pZhr}Rp8$D7>cNK
2H z~uB z(bZeR#R%X;L#{0!{0Dk!hoq|l+KyQ?TyCCEo+-6Gvp%Y0j#6 z+W4gYtgnBno{8}*S=^Fs2vPj_?7JLi_e_*-xXD}^!<*IdP<}CE6`7Za(<(hJmk|!N zI|%^Q17XX9A|)^@+=8gqJR3L}21!2m{HUZ+*Tl!^cMokmo{PbMk8(J`WAl#g7VGwa zWO!DcN^;c$gWTQZwYNVH71Ex#UB;@(sIq?1`62NiC=Td>n*X}ZaqpDEG#-8Vhnkp0 z6dmyfStOck#$3+vDhK>GONdIMsoI~i=kiAB@ti`@8$=6~`zL+UE)2-N<}c|K@;I2m z?>|eDj*;W+xFAg6XYKD{m z?YSC*k*3IU7OktGkB-aiGTVM`2gZ?3h?#je(u`l^i_E~g#CderoGvJk)O-3{?NKQ@ zn-u`Ti1Z0YcUNo4YO78w$Q=iF-bvts2c{*B-dCpH62(6(=4YWly^~J0M40=ua((SI z|7Wk5J4EJnsq%JIuwh^+pY%Q#604gHGsjpB5X=sE$Sy6OY1;kKr(i78pQ}rIQeyTT z(fr!+eRGMsPznOV^~yQQG(uI9b9ga*&Tk>P{z2{7GBA#5n`=*IFj@qRNEZYkg@Fsb zB7$5gnhG=rI;B89X057B-lO?*}9mHQ`jBBt6)ey-}Jqz?(6=QEDDi+?-sPP^STji znAzjaO+@NP2RWB^TIZ5-g4poWKm8Z$>iAc=-Onw_LCq++O(yGc;wz(eWl>Od%F7CU z%_U+2!Kk{>KRJrcw!rQri)v^T9VoUb=8g+d)Ac-2@hAySM{+3s*bk;AINg~)E{^~h zQT0!eX7&gV@+h2VvH#=H-M_TeTAg16Aim!f&=E7-;6p2nwLpSLWtMydr8eGPk0@xd zh~m5dHnwQ!K91XuBM$0RNnuKMSxDn7b>mO@z~bijtqNB(bLM4`Xl(aUFEvEq3xQQ7 zu+Ek?wp5TYs)*f?GD>_J^=J=SM|4*HEQUhe;qFI~B<~|dGU)==m!A)0ILI_cY<`h} z3asGlX6c$-*%r!gu4})0*sMX)h|dEW*0}F_o`-~}Jwz8nw>F?Msps#4aobpH{-TC4 zNwI6K-epmWfRnKZXA+x~Xl_3hSywgY*nCc8vc&4w2ubz_Go>2d$I|2#eeKe0jlL)!SCuq5E^ENf=kL$~BlFK3o1`-Rze(vxRRKJ^k`ADYLQ@pl<)j z)9CqJc}ZlH@e57DeA_6E)Bl&yHlpn5%_g?G0Y-tmx|04ksve ze^u?`4j{bcf&+yVUjysZm;(T9n*->{8XF4va_$f?n_lgM%f&9j@DD6&+0Zqk8b(Ic zQ;9Ul$<5 zFsSqZ_LM7RSDyXgwW}<~@@T)2=ZzAHC~n;g=T(Y+rBbr6P%!7T;pq{56m|F0=+l5s z!e3-EIEsDHXe-l|#(rG46M?DpBc`>l5k$vDuD78;-7CVVY$W=Vh`=cEy`3uP(& z>^YZ(qW?g5xT1QOMp}7SN$b;cI-M!@LkvG}Q^Ue2H<4L|J{f#dOcq=ba(K;W2sVOS zYtm6vU?>UxsQ2rJ)zldhLR%9PTN$~%N2fD(bw3zDaa?XQhp-Hv*UNXr7`s|%j&=XG z0{vQm-Y0%HsZ$~&2d{5ylO8hpo|(3Ad;u`BAb%K)Nlx76R`B|l)tOAMlMTJ`EN^cU)P_W=|nHhTRpdu@yMQh#K8!qFTV-pIVFjnvYUnl{mFz@O|&jP3TV6)sn8PKcv znAReN9l3$^SPOS2s+}JXPE39U-Sz;O1ieL!?bJfkq;T5GVc(?I1{bt!Jm%<2kNwl z`8}&A&a?mQ6l-goUwNUw4rmbRtMCEsL{n)ZYDwwS!bTk=T8XX-m#x$6T0VSB+N-W1EMmJI;j+X(hW**5!LSjo+$~Od(qE-qO1) zhy2DK%aYEW&Yx2jt~9@oW$xFzTux{2Z$;tWTW@@~nQ@=E#mKMW3z1ablwD3Fd9CAU z@|EtZdi#6j-H%y{D}k`@q?SnKnc4jZf>1fj;jmxTsjOZCQGW)_!9DjQ@-KH1kVh2- z)2Nol5P2|x_w+AAPo#8xpWUeiP^HxU@|d#gZNAN4_9K$PT*G^mKYUmU<<(rXU}wc9 z@ilbHLmPNBfE>NQ63Wy{2o6!-Cv__lW9X8nI%5GGxuCI?8=UV}+ZD8fm>X*IxJ2ML zG)z}=?S=Hy!}aZ-i~QtK*Np91!lg624c9;?qnGo$sk+AP{5N1@Psmg;a9=HeV1)*B zMb$Y<(rI%wvsrFx#zKSfS>TE1G)xuSI-3V3m0=+1485%} zU*su8z=fnS>W_oNvwFIS-iV-j>4@sebL#8V2i}ih#P0{)od$w3D(C!c5a$KK{p%4P z1L6tqznAJ-#=Zt9bW+qx`~3#dz!uF>n!-nOyUQaX481 zr8i}v!74#l41>OaPRma;#vFZ(e81R<|}X<9$BVmYoie=-P>bg+!e-dqt2J{Z5oyzh8M~IeK zVj7V2F4N^)6`9CX7Kn>g+HD_@94~&iN_CDItAFDk1LtS(qJ~Gr30`o?kMjv8(Df+If>>`YIXTs{1?~?e9ws-e8^vC>JwqtpjGTxS-e}eKn;JzGm}E(7%+3e1B(K8khKUt?88y zJ^q3w8UI_XP_L*M(l((easfVB7Jx;kHFlySSe)X#Q{5kYCvT3IaTZkON9J?fTSn3B zFg{2eUHPEt#nA|sigLL&ulIKpr9@&y8+daUKb-N8!dt^2%XZaVO9X%De=XRcCnw}7 z9&0+_&&4It$G;8(eliKFqye3`oMOQ4N8YL-koS6f874jq41Ww&-57FyU>R;&e@sC( zy!-8lh47-ge*B@^#t+E*tI*?$XUIFPJUhr#@e)qNNg$tlJ`u)_X|$unhr|QwI7?E@ zK%wxR;#h3>tw_*@LAr#iVm`fNg?jy^PaYRO_p|_fxdHza@RtS&QB(6($ur;V4r7Of z*fbbLU6JS><3JQ^Kj^W%cv(0E}0Y?TyyR-8fRXQO<2j(Gol#-*R&BIo5tXUuPb zxB&%q8}CUOiArlZ!3CknnKK5?xxLpzRe=hIjBByJe?}DKusb1_e#Mq^YijY0QCIQD zL_`%ku_Mh!K!zKdq-n*SYpE1+Uf`U&2~CnEDpQIhx}xZ(8j+rf?fU7M_*qL?kL;_} zNny$$qaZ-%r}1a25pN52aV!eeXazTHp;}<+Nz4Sg4b=TmXMfg~k{)jj)LA26Lxja9 zTY;p)7T_vqwl;;6(r=yRNH2IG7~zSuj{@FK2fdRSxy!y$tSs~9>rDA{hj?KOMuo@x zUcy$S3+~yZKXdAuV*f?ai~Z-dfQI>mgWH}#)hEIxfqhZ$f{%>9m*Y*qpLWi?d|Ptc zRC}s8l5mR0qcTAEyfe{$i+6&KYh;bj){e@YswYl+Ikydp_m-uyBMtFUj$!sIqzoj_ zECt}pBrMMH0rSRXf?ORzf8o5#EDH(jS?X{avWfob?sxsLJ$j%FJvpc*QzqePBxH&< ztUa3F$=TnYj1mBu-`d67TL~{*1|dag%QIetO>A;JU77vL>GyiG9Nl(je7|(1>7~ab zBopCXeQn4Xs@~!g7q90@($iax?x(+S?{_La1-qw~&5=XQ&CMb(L!EC1mMOL!-4+fs z3{%euBOlD=_B!nGIMO|wALfBI1h*$y1J-9-SYyEebgAo~F_eH~#$pc6KWn`Kw!dLC zBKmq(2bjAX0|E#hVS_G-(O+PcCYP}Oz%4a>qd5PoPhC|9b4`bB4W*+Gx2x>DwUd!| z)L#PEN5`dLi4W#tSD7u&kFm0U@}66S%<;<9RNbmrj;@hKt%orf1gUS8q>cUhH(nHP3gH+JPVSInpRYTaETT%C&TtoUBDqt^s^Gfe^P zzSJ3p?~+YAG&w{mZ2uU7j%a-nnkya4t6IO7ug;GhrsB$Al#Td(_dN^Tnb3AuTs~JI zmZx{6dTCG;yEDTSK^?*zt?tbkpc$}T6AYA0az=L1E_CBwor86qp=E~k6KsdU3*zNj zRRg*FNP35nRq^zgpQBsG$rK*tM5`}4PIg~N-xQC4-e>{Ex8PVl)4NI0Q#XCCthGFm9Nb^r6BD1vnx#uIA^W z*TyC--}n^{lK)Xyd9AnA@`V?xCBOq(WCBk^Q7skp_-Ny#BfN-ha?*~?71-&M3K3>% zO4d^x`PZ-P+e&~rh1l-#HOg^)qRNADh|orHK~SUlQwJnkWdTJyX%{2F^{3^L;EIGG zQuja5*j!6iY;vn^$9!6s4m>RrpuGr8ZC>Tj#Y1^08u3-f7soaJbQ#0{@8{zM+ejs>n3>$FWUW3+^cZ)V1_2Xh?B)H^ z6f6uO`&<6Uqnlz7R7?LQ9ICWtZC)t>+2B6@40+8VqWP_vUS3K=qn=x#*4vN~Zz5pm zmtp@N@bt&3dcz0iLw~e z>iVb{^rMIxa`Dr1ioWyEnE6X9{S+#PZzTa(PXKJpcS)t2_^IXR$?YZ!F0fV2_MBq5 zVef6CWc924zg!id*+J(O9^546+a2|1Ab87Gd!81svMOH=Gpmc0Btt1;hrbw0)}Q$D zviyWJ#?zhrQ!bQ74Uc3v?<*OlX?eCArazqC&pMa;cOe-rS~3jLuW)3c**;EqFK!uw zClskf=-hEVaWs{xE7}7sW7VV<$5HOUNt$ldLL9uFuP)MA)PaHg&^p&erJr5Z($uIWnD9AcT8BK%QY6#iBYLiA2dx(0$;+gTA*T&;T zb5N5AS6?ArkP&ZmDJi@Swb!-4?(BC>yZLb)e`o547J!Qm5sdMkn2vwP7y{4qxsyO3 zAu2RQZI1#d>58L-@j#S`t{pdYbhmV=V|b&TW~Bk=Sz*!1V9-Jz6~!oMj9h6xDZ2DW zISZ_ah%rM14q-`}{KZYFox0^px$6wUtVqZr)@FubbfZTj4E2B!3^7pSWt%=KEco+z zM>_n#!JN6~dm(hBn(e4Oh)lXoff?tO`w~OQPLL_{QP$@n*UzJ=7$+eu_m)AslXaL! z`{kr7R(|3!6P;ZO_2+?LqBC4lyx$R%ezs@M1T$WzVLyi$(F`6IZA3*qERil@8ewe@ zPmefl#qaVa%gvMaHTy2jxt^=+FSFp=fHopvq#xT;*gx$9HzOPV1Fg;GnJ>zEc9lp} zBd+*~4=x*OTL4$mH{#!TWY8NNUKQ+n6h1TnurS~wTo-tMVgLxR;Cjwg+ z_UH^_lmKzYH zy4c~kR`!&J-UF?io6Z;#at}NlG}rteD0FW8s>W;K!deiJYRmDHShS}uG-ns(+#Vz* zvy$9fOMMcU=oNp!#J`j((kl@$IDW?R=d{6zA~W50aC@=Ggt*m3*DWc>R5R+@JZAwk z!v5$4mCC|jniB4^~u_Y%$;Kd_^JyHt;XB)oC)p-a4l{` zh?#qCNR0PRX$ssEUTb?gz9jbtQQu9Swi(`cGpIhTm6KRrI+QW9MiCSfidODe{pmJw zoJ|X6YsgkzfrtErz!j$AO)TR4(K(&2=6E|(%`m*n(7`zC3)hFGZjQ*R{q_|@g?evQ zX_C_SiRc6XH4RKLT5sDrr%4iIbQNfatc1%i%=Pc(@_|5E45tX z8Gl&&kl?baubm#Ip>BcB-0W=?J?nRc5g)ZGFB@U%J)W*BaS7Z4YAXg|r(&yN76k8# z%S?>5)frVYh)Rep0xUYxol;%#dOwi0tXMAEXE)z64G5tSVYLETwkiAUJ(lf)BQte) z?tJRRVW|`>V)yZQBu-iF6cK2^JgsNy3JB^;Vnui0n_uso^$7lqih^e*JsUOUNHCfE zkok9^8*+1uhusl(qTH^-N@d?akD|h9hg#Z#78Qja&a6dj?!WRvATwV$KK~E&1q3Mq zk^@W}eW7YnJsZgFyLVj&t9WB)qD4>wZYkl|0DwZVOxNn+ZC}v4$3Dq?pCMZ_lAKwh zIz97})KPkcftLQUX(?>pd?{Nfnj-Oi%DPM(_zJBl^U1?4lWEEZwg3?OD(r*aO#r9S zemU~CFOl{ar8jYoWcHf6=Z6ms&wi*Sk_omy!0s48@G&S?+&g^?O*k~GLW8(1rNDmF zOsOQa*7~FY#{jT6cJ|u(8DW~X4_Ym6x}0vqKW)@#kaj6ialdu-S!>Vpww#!UBzY;s zcpkl5Iva*2v5LM;!DwgpH0^E?-X^Jid~dSOCGMblzTqOgaEw2TU@c(;n=_Z1Qhh87tceo`CWxIX-V)TY=v}y7^$$!}9q-!Oc}IYsaGmPxdx}2IiaYtZ zn}W3!Np;!}P_+`>hbc#X_m2HNrYUa~R&RLef6Z#2`8*LaGn!5`r$$@qqVdXm; zzhvD0;F&7g-vt20FK<_{CGd-VQhn3`wEFDBhqkeSytb6iThe+PuRQq0}{@A*IMpYaE|BjdsM#1IlLDcfw5DChMonowg0dd?R#lX(93;m z;EVoRR+4C%qD{vK_kMW6_w~5BXmo!1HS!7cl!;5kDO>}5c`<=-`InSA@q~=`4)Sx82>gvhnuptfe(Rkl4~o!KI#y!I z0#s4UXMk~EF8n;YRgIp&qxReUJ2x%cD_I?rpLG6@a#o2}G zpSN=Cp97G%t5(Wt|i1G0R8;-o})%ZEXk)?+E zWGyu96TlBk6#QlIyNFFS-b};&*ip(o escb.accept(simState)); LOG.log(Level.DEBUG, "Handling atSec() callbacks"); @@ -607,6 +607,29 @@ public Rotation3d angularVelocity(String defPath) { @Override public void close() {} + + /** + * @return the time (in seconds) since the robot code started, according to the robot code. + */ + public double getRobotTimeSec() { + return robotTimeSec; + } + + /** + * @return the time (in seconds) since the simulation started, according to the simulator. + */ + public double getSimTimeSec() { + return simTimeSec; + } + + private SimulationState() {} + + private double robotTimeSec, simTimeSec; + + private SimulationState(double robotTimeSec, double simTimeSec) { + this.robotTimeSec = robotTimeSec; + this.simTimeSec = simTimeSec; + } } private record OneShotCallback(double timeSecs, diff --git a/tests/logging.properties b/tests/logging.properties index b4e4ff87..bb5cdb12 100644 --- a/tests/logging.properties +++ b/tests/logging.properties @@ -34,7 +34,7 @@ handlers= java.util.logging.ConsoleHandler,java.util.logging.FileHandler ############################################################ # default file output is in user's home directory. -java.util.logging.FileHandler.pattern = %h/example%u.log +java.util.logging.FileHandler.pattern = %h/tests%u.log java.util.logging.FileHandler.limit = 10000000 java.util.logging.FileHandler.count = 1 # Default number of locks FileHandler can obtain synchronously. diff --git a/tests/src/main/java/frc/robot/DBSExampleRobot.java b/tests/src/main/java/frc/robot/DBSExampleRobot.java index c7132312..9b0b3af2 100644 --- a/tests/src/main/java/frc/robot/DBSExampleRobot.java +++ b/tests/src/main/java/frc/robot/DBSExampleRobot.java @@ -71,7 +71,7 @@ public void autonomousPeriodic() { // Drive for 2 seconds if (m_timer.get() < 2.0) { m_robotDrive.arcadeDrive(0.5, 0.0); // drive forwards half speed - m_elevator.set(0.1); + m_elevator.set(0.3); } else { m_robotDrive.stopMotor(); // stop robot } diff --git a/tests/src/systemTest/java/frc/robot/DBSExampleTest.java b/tests/src/systemTest/java/frc/robot/DBSExampleTest.java index 0a2294c2..52f59946 100644 --- a/tests/src/systemTest/java/frc/robot/DBSExampleTest.java +++ b/tests/src/systemTest/java/frc/robot/DBSExampleTest.java @@ -39,12 +39,12 @@ void testDrivesToLocationAndElevatesInAutonomous() throws Exception { 0.2, "Robot close to target position"); assertEquals(0.0, s.position("ELEVATOR") - .getDistance(new Translation3d(2.6, 0, 0.9)), - 0.2, "Elevator close to target position"); + .getDistance(new Translation3d(2.6, 0, 1.244)), + 0.2, "Elevator close to target position"); assertEquals(0.0, s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), - 0.01, "Robot close to target velocity"); + 0.05, "Robot close to target velocity"); assertEquals(0.0, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), @@ -64,7 +64,7 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { s.enableTeleop(); DriverStationSim.setJoystickAxisCount(0, 2); DriverStationSim.setJoystickAxis(0, 1, 0.0); - DriverStationSim.setJoystickAxis(0, 0, 0.15); + DriverStationSim.setJoystickAxis(0, 0, 0.6); DriverStationSim.notifyNewData(); }).everyStep(s -> { var yawDegrees = @@ -75,27 +75,28 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { DriverStationSim.notifyNewData(); stoppedTryingToTurn = true; } - }).atSec(1.0, s -> { + }).atSec(0.3, s -> { assertEquals(0.0, s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), 0.1, "Robot close to target velocity"); - assertEquals(19.0, - Units.radiansToDegrees( + assertEquals(62.5, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), - 1, "Robot close to target angular velocity"); + 2.0, "Robot close to target angular velocity"); assertEquals(0.0, new Translation3d(s.angularVelocity("ROBOT").getAxis()) .getDistance(new Translation3d(0, 0, 1)), 0.1, "Robot close to target angular velocity axis"); - }).atSec(4.0, s -> { + }).atSec(1.0, s -> { + // Note: Large tolerance because turning at a high speed means we can overshoot + // significantly in 1 step. assertEquals(45.0, - Units.radiansToDegrees(s.rotation("ROBOT").getZ()), 2.0, - "Robot close to target rotation"); + Units.radiansToDegrees(s.rotation("ROBOT").getZ()), + 10.0, "Robot close to target rotation"); assertEquals(0.0, s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), - 0.01, "Robot close to target velocity"); + 0.1, "Robot close to target velocity"); assertEquals(0.0, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index 3c8c731e..82eef8e4 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -1,44 +1,264 @@ package frc.robot; import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertTrue; import org.carlmontrobotics.libdeepbluesim.WebotsSimulator; import org.junit.jupiter.api.Test; import org.junit.jupiter.api.Timeout; import org.junit.jupiter.api.parallel.ResourceLock; +import java.lang.System.Logger; +import java.lang.System.Logger.Level; import java.util.concurrent.TimeUnit; -import edu.wpi.first.math.util.Units; +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.system.plant.DCMotor; @Timeout(value = 30, unit = TimeUnit.MINUTES) @ResourceLock("WebotsSimulator") public class PWMMotorControllerTest { + // NOTE: By default, only messages at INFO level or higher are logged. To change that, if you + // are using the default system logger, edit the logging properties file specified by the + // java.util.logging.config.file system property so that both ".level=FINE" and + // "java.util.logging.ConsoleHandler.level=FINE". For tests via Gradle, the + // java.util.logging.config.file system property can be configured using the systemProperty of + // the test task. + private static final Logger LOG = + System.getLogger(PWMMotorControllerTest.class.getName()); + + // Should be the same as the basicTimeStep in the world's WorldInfo (default to 32ms) + private double simStepSizeSecs = 0.032; + + // Derivation of the math used below: + // Let tau be the torque applied by the motor (Nm). + // Let J be the moment of inertia of the load (kg m^2). + // Let alpha be the angular accleration of the load (rad/s^2). + // Let w be the speed of the load (rad/s). + // + // From rotational mechanics: + // tau = J*alpha + // alpha = dw/dt + // dw/dt = tau / J + // + // Let k_T be the motor's torque constant (Nm/A) + // Let k_e be the motor's voltage constant (Volts/(rad/s)) + // Let V be the applied voltage + // Let V_max be the motor's rated voltage (e.g. 12V) + // Let i_free be the motor's free current (A) which we assume is the current needed to overcome + // friction + // Let w_free be the motor's free speed + // Let i_stall be the motor's stall current + // Let tau_stall be the motor's stall torque + // Let R be the motor's resistance + // + // From electromagnetism: + // tau = (i-i_free)*k_T + // i = (V-k_e*w)/R + // R = V_max/i_stall + // k_T = tau_stall/(i_stall-i_free) + // k_e = V_max/w_free + // + // Substitution gives: + // dw/dt = (V-V_max/w_free*w)/(V_max/(i_stall-i_free))*tau_stall/(i_stall-i_free)/J + // + // Rearranging gives: + // dw/dt = (tau_stall*V/V_max)/J-(tau_stall/w_free)/J*w + // dw/dt + (tau_stall/w_free)/J*w = (tau_stall*V/V_max)/J + + // The following w(t) solving that differential equation (where w_0 = w(0)): + // w(t) = w_0 + (V/V_max*w_free - w_0)(1-exp(-tau_stall/(J*w_free)*t)) + // + // That is an exponential decay from w_0 to V/V_max*w_free with a time constant of: + // t_c = J*w_free/tau_stall + // + // That can be rearranged to give: + // w(t) = V/V_max*w_free + (w_0 - V/V_max*w_free) * exp(-t/t_c) + // + // Integrating with respect to t gives: + // theta(t) = C + V/V_max*w_free * t - (w_0 - V/V_max*w_free) * t_c * exp(-t/t_c) + // + // C is constant of integration that we can determine from initial conditions: + // theta(0) = theta_0 = C - (w_0 - V/V_max*w_free) * t_c + // C = theta_0 + (w_0 - V/V_max*w_free) * t_c + // + // Substituting gives: + // theta(t) = theta_0 + V/V_max*w_free * t + (w_0 - V/V_max*w_free) * t_c (1-exp(-t/t_c)) + + private double computeSpeedRadPerSec(DCMotor gearMotor, double moiKgM2, + double targetSpeedRadPerSec, double initialSpeedRadPerSec, + double tSecs) { + double timeConstantSecs = computeTimeConstantSecs(gearMotor, moiKgM2); + // w(t) = V/V_max*w_free + (w_0 - V/V_max*w_free) * exp(-t/t_c) + return targetSpeedRadPerSec + + (initialSpeedRadPerSec - targetSpeedRadPerSec) + * Math.exp(-tSecs / timeConstantSecs); + } + + private double computeAngleRadians(DCMotor gearMotor, double moiKgM2, + double targetSpeedRadPerSec, double initialSpeedRadPerSec, + double initialAngleRad, double tSecs) { + double timeConstantSecs = computeTimeConstantSecs(gearMotor, moiKgM2); + // theta(t) = theta_0 + V/V_max*w_free * t + (w_0 - V/V_max*w_free) * t_c (1-exp(-t/t_c)) + return initialAngleRad + targetSpeedRadPerSec * tSecs + + (initialSpeedRadPerSec - targetSpeedRadPerSec) + * timeConstantSecs + * (1 - Math.exp(-tSecs / timeConstantSecs)); + } + + private double computeTimeConstantSecs(DCMotor gearMotor, double moiKgM2) { + return moiKgM2 * gearMotor.freeSpeedRadPerSec + / gearMotor.stallTorqueNewtonMeters; + } + + private double computeCylinderMoiKgM2(double radiusMeters, double massKg) { + return massKg * radiusMeters * radiusMeters / 2.0; + } + + private double computeCylinderMoiKgM2(double radiusMeters, + double heightMeters, double densityKgPerM3) { + double mass = densityKgPerM3 * Math.PI * radiusMeters * radiusMeters + * heightMeters; + return computeCylinderMoiKgM2(radiusMeters, mass); + } + + private double timeOfNextStepSecs(double tSecs) { + return Math.ceil(tSecs / simStepSizeSecs) * simStepSizeSecs; + } + + private double expectedSpeedRadPerSec(DCMotor gearMotor, double moiKgM2, + double tSecs) { + // The robot autonomous code runs the motor at 0.5 for 2 seconds and then stops it (i.e. + // sets the speed to 0 and lets it stop on it's own). + double tMotorStopsSecs = timeOfNextStepSecs(2.0); + + if (tSecs <= tMotorStopsSecs) { + return computeSpeedRadPerSec(gearMotor, moiKgM2, + 0.5 * gearMotor.freeSpeedRadPerSec, 0, tSecs); + } + return computeSpeedRadPerSec(gearMotor, moiKgM2, 0, + expectedSpeedRadPerSec(gearMotor, moiKgM2, tMotorStopsSecs), + tSecs - tMotorStopsSecs); + } + + private double expectedAngleRadians(DCMotor gearMotor, double moiKgM2, + double tSecs) { + // The robot autonomous code runs the motor at 0.5 for 2 seconds and then stops it (i.e. + // sets the speed to 0 and lets it stop on it's own). + double tMotorStopsSecs = timeOfNextStepSecs(2.0); + if (tSecs <= tMotorStopsSecs) { + return computeAngleRadians(gearMotor, moiKgM2, + 0.5 * gearMotor.freeSpeedRadPerSec, 0, 0, tSecs); + } + return computeAngleRadians(gearMotor, moiKgM2, 0, + expectedSpeedRadPerSec(gearMotor, moiKgM2, tMotorStopsSecs), + expectedAngleRadians(gearMotor, moiKgM2, tMotorStopsSecs), + tSecs - tMotorStopsSecs); + } + + private void assertShaftCorrectAtSecs(DCMotor gearMotor, double moiKgM2, + double actualSpeedRadPerSec, double actualAngleRadians, + double tSecs) { + // TODO: Make sim accurate enough that this can be less than 1*simStepSizeSecs + // (https://github.com/DeepBlueRobotics/DeepBlueSim/issues/101) + double jitterSecs = 3 * simStepSizeSecs; + double expectedEarlierSpeedRadPerSec = + expectedSpeedRadPerSec(gearMotor, moiKgM2, tSecs - jitterSecs); + double expectedLaterSpeedRadPerSec = + expectedSpeedRadPerSec(gearMotor, moiKgM2, tSecs + jitterSecs); + LOG.log(Level.DEBUG, "expectedEarlierSpeedRadPerSec = {0}", + expectedEarlierSpeedRadPerSec); + LOG.log(Level.DEBUG, "expectedLaterSpeedRadPerSec = {0}", + expectedLaterSpeedRadPerSec); + assertEquals( + (expectedEarlierSpeedRadPerSec + expectedLaterSpeedRadPerSec) + / 2, + actualSpeedRadPerSec, + Math.abs(expectedEarlierSpeedRadPerSec + - expectedLaterSpeedRadPerSec) / 2, + "Shaft close to target angular velocity"); + double expectedEarlierAngleRadians = + expectedAngleRadians(gearMotor, moiKgM2, tSecs - jitterSecs); + double expectedLaterAngleRadians = + expectedAngleRadians(gearMotor, moiKgM2, tSecs + jitterSecs); + assertTrue(MathUtil.isNear( + (expectedEarlierAngleRadians + expectedLaterAngleRadians) / 2, + actualAngleRadians, + Math.abs( + expectedEarlierAngleRadians - expectedLaterAngleRadians) + / 2, + 0, 2 * Math.PI), "Shaft close to target rotation"); + } + + private double computeGearing(DCMotor motor, double desiredFreeSpeedRPS) { + return motor.freeSpeedRadPerSec / (2 * Math.PI) / desiredFreeSpeedRPS; + } + + private double computeFlywheelThickness(DCMotor gearMotor, + double flywheelRadiusMeters, double flywheelDensityKgPerM3, + double desiredTimeConstantSecs) { + // for a time constant of t_c seconds: + // t_c = moiKgM2 * (motor.freeSpeedRadPerSec / gearing) / (motor.stallTorqueNewtonMeters * + // gearing); + // moiKgM2 = t_c*gearing^2*motor.stallTorqueNewtonMeters/motor.freeSpeedRadPerSec + // moiKgM2 = 0.5*densityKgPerM3 * Math.PI * radiusMeters^2 * heightMeters * radiusMeters^2 + // heightMeters = 2 * moiKgM2/(densityKgPerM3 * Math.PI * radiusMeters^4) + // heightMeters = 2 * t_c*gearing^2*motor.stallTorqueNewtonMeters/(motor.freeSpeedRadPerSec + // * densityKgPerM3 * Math.PI * radiusMeters^4) + return 2 * desiredTimeConstantSecs * gearMotor.stallTorqueNewtonMeters + / (gearMotor.freeSpeedRadPerSec * flywheelDensityKgPerM3 + * Math.PI * Math.pow(flywheelRadiusMeters, 4)); + } + @Test void testShaftRotatesInAutonomous() throws Exception { - // TODO: Fix the expected values to be physically correct and then fix PWMMotorMediator to - // pass the test. + // To ensure we the flywheel doesn't spin or accelerate too fast... + var desiredFlywheelFreeSpeedRPS = 1.0; + var desiredTimeConstantSecs = 1.0; + + // For this test to pass, the motor and flywheel need to be setup in the world as follows. + var flywheelRadiusMeters = 0.5; + var flywheelDensityKgPerM3 = 1000.0; + var motorModelName = "MiniCIM"; + var motor = (DCMotor) (DCMotor.class + .getDeclaredMethod("get" + motorModelName, int.class) + .invoke(null, 1)); + var gearing = computeGearing(motor, desiredFlywheelFreeSpeedRPS); + var gearMotor = motor.withReduction(gearing); + LOG.log(Level.INFO, + "For a free speed of {0} RPS when using a {1}, assuming the gearing is {2}.\n", + desiredFlywheelFreeSpeedRPS, motorModelName, gearing); + var flywheelThicknessMeters = computeFlywheelThickness( + motor.withReduction(gearing), flywheelRadiusMeters, + flywheelDensityKgPerM3, desiredTimeConstantSecs); + LOG.log(Level.INFO, + "For a time constant of {0} second when using a {1} with a gearing of {2} and a flywheel with radius {3} meters and density {4} kg/m^3, assuming the flywheel thickness is {5} meters.\n", + desiredTimeConstantSecs, motorModelName, gearing, + flywheelRadiusMeters, flywheelDensityKgPerM3, + flywheelThicknessMeters); + + // With those settings, the flywheel MOI will be: + var moiKgM2 = computeCylinderMoiKgM2(flywheelRadiusMeters, + flywheelThicknessMeters, flywheelDensityKgPerM3); + try (var manager = new WebotsSimulator( "../plugin/controller/src/webotsFolder/dist/worlds/PWMMotorController.wbt", PWMMotorControllerRobot::new)) { manager.atSec(0.0, s -> { s.enableAutonomous(); + }).everyStep(s -> { + LOG.log(Level.DEBUG, + "robotTime = {0}, simTimeSec = {1}, speedRadPerSec = {2}", + s.getRobotTimeSec(), s.getSimTimeSec(), + s.angularVelocity("SHAFT").getAngle()); }).atSec(1.0, s -> { - assertEquals(175.5, - Units.radiansToDegrees( - s.angularVelocity("SHAFT").getAngle()), - 1, "Shaft close to target angular velocity"); - assertEquals(160, - Units.radiansToDegrees(s.rotation("SHAFT").getZ()), - 45.0, "Shaft close to target rotation"); + assertShaftCorrectAtSecs(gearMotor, moiKgM2, + s.angularVelocity("SHAFT").getAngle(), + s.rotation("SHAFT").getZ(), s.getRobotTimeSec()); }).atSec(3.0, s -> { - assertEquals(0.0, - Units.radiansToDegrees( - s.angularVelocity("SHAFT").getAngle()), - 1, "Shaft close to target angular velocity"); - assertEquals(-28.8, - Units.radiansToDegrees(s.rotation("SHAFT").getZ()), - 45.0, "Shaft close to target rotation"); + assertShaftCorrectAtSecs(gearMotor, moiKgM2, + s.angularVelocity("SHAFT").getAngle(), + s.rotation("SHAFT").getZ(), s.getRobotTimeSec()); }).run(); } } From a70840e217761e803c1bb14c485c4041ce86ef55 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 13:34:48 -0700 Subject: [PATCH 02/15] Increase tolerance on a flaky test. --- tests/src/systemTest/java/frc/robot/DBSExampleTest.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/src/systemTest/java/frc/robot/DBSExampleTest.java b/tests/src/systemTest/java/frc/robot/DBSExampleTest.java index 3aefd205..ce489c7b 100644 --- a/tests/src/systemTest/java/frc/robot/DBSExampleTest.java +++ b/tests/src/systemTest/java/frc/robot/DBSExampleTest.java @@ -84,7 +84,7 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { 0.1, "Robot close to target velocity"); assertEquals(62.5, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), - 2.0, "Robot close to target angular velocity"); + 5.0, "Robot close to target angular velocity"); assertEquals(0.0, new Translation3d(s.angularVelocity("ROBOT").getAxis()) .getDistance(new Translation3d(0, 0, 1)), From 16fccd46ae7c2f818c259738410ddf593a69d78c Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 14:26:14 -0700 Subject: [PATCH 03/15] Make flaky test even more tolerant. --- tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index 82eef8e4..66ca7e90 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -161,7 +161,7 @@ private void assertShaftCorrectAtSecs(DCMotor gearMotor, double moiKgM2, double tSecs) { // TODO: Make sim accurate enough that this can be less than 1*simStepSizeSecs // (https://github.com/DeepBlueRobotics/DeepBlueSim/issues/101) - double jitterSecs = 3 * simStepSizeSecs; + double jitterSecs = 4 * simStepSizeSecs; double expectedEarlierSpeedRadPerSec = expectedSpeedRadPerSec(gearMotor, moiKgM2, tSecs - jitterSecs); double expectedLaterSpeedRadPerSec = From 7ba1c6e20b00587f6f70cdf796042b40369dd241 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 14:39:53 -0700 Subject: [PATCH 04/15] Run CI on macos-13 instead of macos-14 in hopes that it will be faster. --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 0e6cd1fd..070dec7d 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -11,7 +11,7 @@ jobs: strategy: fail-fast: false matrix: - os: [ windows-latest, macos-latest, ubuntu-latest ] + os: [ windows-latest, macos-13, ubuntu-latest ] runs-on: ${{ matrix.os }} steps: From 37ac375e5b526b32b7272edd8b5536548c6e3c62 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 15:15:53 -0700 Subject: [PATCH 05/15] Remove duplicate call to motor.withReduction(gearing). Co-authored-by: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> --- tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index 66ca7e90..67d0c1aa 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -229,7 +229,7 @@ void testShaftRotatesInAutonomous() throws Exception { "For a free speed of {0} RPS when using a {1}, assuming the gearing is {2}.\n", desiredFlywheelFreeSpeedRPS, motorModelName, gearing); var flywheelThicknessMeters = computeFlywheelThickness( - motor.withReduction(gearing), flywheelRadiusMeters, + gearMotor, flywheelRadiusMeters, flywheelDensityKgPerM3, desiredTimeConstantSecs); LOG.log(Level.INFO, "For a time constant of {0} second when using a {1} with a gearing of {2} and a flywheel with radius {3} meters and density {4} kg/m^3, assuming the flywheel thickness is {5} meters.\n", From 456f2be0d5bc821d4ad485de44992c517dd308e5 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 19:01:43 -0700 Subject: [PATCH 06/15] Fix math. --- .../frc/robot/PWMMotorControllerTest.java | 64 +++++++++---------- 1 file changed, 31 insertions(+), 33 deletions(-) diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index 66ca7e90..7b0b5549 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -41,55 +41,56 @@ public class PWMMotorControllerTest { // alpha = dw/dt // dw/dt = tau / J // - // Let k_T be the motor's torque constant (Nm/A) - // Let k_e be the motor's voltage constant (Volts/(rad/s)) // Let V be the applied voltage // Let V_max be the motor's rated voltage (e.g. 12V) - // Let i_free be the motor's free current (A) which we assume is the current needed to overcome - // friction + // Let i_free be the motor's free current (A) which is needed to overcome friction // Let w_free be the motor's free speed // Let i_stall be the motor's stall current // Let tau_stall be the motor's stall torque - // Let R be the motor's resistance + // Let R = V_max/i_stall (ie. the motor's resistance) + // Let k_T = tau_stall/i_stall (ie. the motor's torque constant) (Nm/A) + // Let k_v = w_free/(V_max - R*i_free) (ie. the motor's velocity constant) ((rad/s)/Volt) // // From electromagnetism: - // tau = (i-i_free)*k_T - // i = (V-k_e*w)/R - // R = V_max/i_stall - // k_T = tau_stall/(i_stall-i_free) - // k_e = V_max/w_free + // tau = i*k_T + // i = (V-w/k_v)/R // // Substitution gives: - // dw/dt = (V-V_max/w_free*w)/(V_max/(i_stall-i_free))*tau_stall/(i_stall-i_free)/J + // dw/dt = (V-w/k_v)/R*k_T/J // // Rearranging gives: - // dw/dt = (tau_stall*V/V_max)/J-(tau_stall/w_free)/J*w - // dw/dt + (tau_stall/w_free)/J*w = (tau_stall*V/V_max)/J + // dw/dt = k_T/(R*J)*V - k_T/(R*J)/k_v*w + // dw/dt + k_T/(R*J)/k_v*w = k_T/(R*J)*V - // The following w(t) solving that differential equation (where w_0 = w(0)): - // w(t) = w_0 + (V/V_max*w_free - w_0)(1-exp(-tau_stall/(J*w_free)*t)) + // The following w(t) solves that differential equation (where w_0 = w(0)): + // w(t) = w_0 + (V*k_v-w_0)(1-exp(-k_T/(R*J*k_v)*t)) // - // That is an exponential decay from w_0 to V/V_max*w_free with a time constant of: - // t_c = J*w_free/tau_stall + // That is an exponential decay from w_0 to V*k_v with a time constant of: + // t_c = R*J*k_v/k_T + // + // Let w_f = V*k_v (ie the asymptotic speed that corresponds to a voltage of V) // // That can be rearranged to give: - // w(t) = V/V_max*w_free + (w_0 - V/V_max*w_free) * exp(-t/t_c) + // w(t) = w_f + (w_0 - w_f) * exp(-t/t_c) // // Integrating with respect to t gives: - // theta(t) = C + V/V_max*w_free * t - (w_0 - V/V_max*w_free) * t_c * exp(-t/t_c) + // theta(t) = C + w_f*t - (w_0 - w_f) * t_c * exp(-t/t_c) // - // C is constant of integration that we can determine from initial conditions: - // theta(0) = theta_0 = C - (w_0 - V/V_max*w_free) * t_c - // C = theta_0 + (w_0 - V/V_max*w_free) * t_c + // C is a constant of integration that we can determine from initial conditions: + // theta(0) = theta_0 = C - (w_0 - w_f) * t_c + // C = theta_0 + (w_0 - w_f)) * t_c // // Substituting gives: - // theta(t) = theta_0 + V/V_max*w_free * t + (w_0 - V/V_max*w_free) * t_c (1-exp(-t/t_c)) + // theta(t) = theta_0 + (w_0 - w_f) * t_c + w_f*t - (w_0 - w_f) * t_c * exp(-t/t_c) + // + // Rearranging gives: + // theta(t) = theta_0 + w_f*t + (w_0 - w_f) * t_c * (1-exp(-t/t_c)) private double computeSpeedRadPerSec(DCMotor gearMotor, double moiKgM2, double targetSpeedRadPerSec, double initialSpeedRadPerSec, double tSecs) { double timeConstantSecs = computeTimeConstantSecs(gearMotor, moiKgM2); - // w(t) = V/V_max*w_free + (w_0 - V/V_max*w_free) * exp(-t/t_c) + // w(t) = w_f + (w_0 - w_f) * exp(-t/t_c) return targetSpeedRadPerSec + (initialSpeedRadPerSec - targetSpeedRadPerSec) * Math.exp(-tSecs / timeConstantSecs); @@ -99,7 +100,7 @@ private double computeAngleRadians(DCMotor gearMotor, double moiKgM2, double targetSpeedRadPerSec, double initialSpeedRadPerSec, double initialAngleRad, double tSecs) { double timeConstantSecs = computeTimeConstantSecs(gearMotor, moiKgM2); - // theta(t) = theta_0 + V/V_max*w_free * t + (w_0 - V/V_max*w_free) * t_c (1-exp(-t/t_c)) + // theta(t) = theta_0 + w_f*t + (w_0 - w_f) * t_c * (1-exp(-t/t_c)) return initialAngleRad + targetSpeedRadPerSec * tSecs + (initialSpeedRadPerSec - targetSpeedRadPerSec) * timeConstantSecs @@ -107,19 +108,16 @@ private double computeAngleRadians(DCMotor gearMotor, double moiKgM2, } private double computeTimeConstantSecs(DCMotor gearMotor, double moiKgM2) { - return moiKgM2 * gearMotor.freeSpeedRadPerSec - / gearMotor.stallTorqueNewtonMeters; - } - - private double computeCylinderMoiKgM2(double radiusMeters, double massKg) { - return massKg * radiusMeters * radiusMeters / 2.0; + // t_c = R*J*k_v/k_T + return gearMotor.rOhms * moiKgM2 * gearMotor.KvRadPerSecPerVolt + / gearMotor.KtNMPerAmp; } private double computeCylinderMoiKgM2(double radiusMeters, double heightMeters, double densityKgPerM3) { - double mass = densityKgPerM3 * Math.PI * radiusMeters * radiusMeters + double massKg = densityKgPerM3 * Math.PI * radiusMeters * radiusMeters * heightMeters; - return computeCylinderMoiKgM2(radiusMeters, mass); + return massKg * radiusMeters * radiusMeters / 2.0; } private double timeOfNextStepSecs(double tSecs) { From 85b3b6396ea9808ff3e3e75095a5815f84a72ffc Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 19:19:42 -0700 Subject: [PATCH 07/15] Fix for linear motors. --- .../mediators/PWMMotorMediator.java | 21 +++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java index db37718b..924288c8 100644 --- a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java +++ b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java @@ -3,6 +3,7 @@ import org.carlmontrobotics.wpiws.devices.PWMSim; import com.cyberbotics.webots.controller.Motor; +import com.cyberbotics.webots.controller.Node; import edu.wpi.first.math.system.plant.DCMotor; @@ -41,10 +42,22 @@ public PWMMotorMediator(Motor motor, PWMSim simDevice, DCMotor motorConstants, d motor.getBrake().setDampingConstant(dampingConstant); } - motorDevice.registerSpeedCallback((deviceName, speed) -> { - double velocity = speed * motorConstants.freeSpeedRadPerSec; - motor.setAvailableTorque(Math.abs(speed) - * motorConstants.stallTorqueNewtonMeters * gearing); + motorDevice.registerSpeedCallback((deviceName, currentOutput) -> { + double velocity = currentOutput * motorConstants.freeSpeedRadPerSec; + switch (motor.getNodeType()) { + case Node.ROTATIONAL_MOTOR: + motor.setAvailableTorque(Math.abs(currentOutput) + * motorConstants.stallTorqueNewtonMeters * gearing); + break; + case Node.LINEAR_MOTOR: + motor.setAvailableForce(Math.abs(currentOutput) + * motorConstants.stallTorqueNewtonMeters * gearing); + break; + default: + throw new UnsupportedOperationException( + "Unsupported motor node type %d. Must be either a RotationalMotor or a LinearMotor: " + .formatted(motor.getNodeType())); + } motor.setVelocity((inverted ? -1 : 1) * velocity / gearing); }, true); } From f88463816da383719256f696968f48a858fb77c3 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 20:10:46 -0700 Subject: [PATCH 08/15] Improve assertion message. --- .../java/frc/robot/PWMMotorControllerTest.java | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index dd5d2200..1554b36d 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -174,18 +174,22 @@ private void assertShaftCorrectAtSecs(DCMotor gearMotor, double moiKgM2, actualSpeedRadPerSec, Math.abs(expectedEarlierSpeedRadPerSec - expectedLaterSpeedRadPerSec) / 2, - "Shaft close to target angular velocity"); + "Shaft not close enough to target angular velocity"); double expectedEarlierAngleRadians = expectedAngleRadians(gearMotor, moiKgM2, tSecs - jitterSecs); double expectedLaterAngleRadians = expectedAngleRadians(gearMotor, moiKgM2, tSecs + jitterSecs); + double expectedAngleRadians = + (expectedEarlierAngleRadians + expectedLaterAngleRadians) / 2; + double toleranceRadians = Math.abs( + expectedEarlierAngleRadians - expectedLaterAngleRadians) / 2; assertTrue(MathUtil.isNear( - (expectedEarlierAngleRadians + expectedLaterAngleRadians) / 2, - actualAngleRadians, - Math.abs( - expectedEarlierAngleRadians - expectedLaterAngleRadians) - / 2, - 0, 2 * Math.PI), "Shaft close to target rotation"); + expectedAngleRadians, + actualAngleRadians, + toleranceRadians, 0, 2 * Math.PI), + "Shaft not close enought to target rotation. Expected %g +/- %g radians, but got %g radians." + .formatted(expectedAngleRadians, toleranceRadians, + actualAngleRadians)); } private double computeGearing(DCMotor motor, double desiredFreeSpeedRPS) { From ce96942454d00d5976cf7ec72d9b09fe49cfeec5 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 21:25:38 -0700 Subject: [PATCH 09/15] Fix damping constant and available torque. --- .../java/frc/robot/SystemTestRobot.java | 4 ++-- .../deepbluesim/mediators/PWMMotorMediator.java | 17 +++++++++++------ .../java/frc/robot/DBSExampleTest.java | 4 ++-- 3 files changed, 15 insertions(+), 10 deletions(-) diff --git a/example/src/systemTest/java/frc/robot/SystemTestRobot.java b/example/src/systemTest/java/frc/robot/SystemTestRobot.java index 7f8b503c..2b0e8548 100644 --- a/example/src/systemTest/java/frc/robot/SystemTestRobot.java +++ b/example/src/systemTest/java/frc/robot/SystemTestRobot.java @@ -77,14 +77,14 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), 0.1, "Robot close to target velocity"); - assertEquals(62.5, Units.radiansToDegrees( + assertEquals(50.1185, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), 2.0, "Robot close to target angular velocity"); assertEquals(0.0, new Translation3d(s.angularVelocity("ROBOT").getAxis()) .getDistance(new Translation3d(0, 0, 1)), 0.1, "Robot close to target angular velocity axis"); - }).atSec(1.0, s -> { + }).atSec(1.5, s -> { // Note: Large tolerance because turning at a high speed means we can overshoot // significantly in 1 step. assertEquals(45.0, diff --git a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java index 924288c8..6af6b35e 100644 --- a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java +++ b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java @@ -37,21 +37,26 @@ public PWMMotorMediator(Motor motor, PWMSim simDevice, DCMotor motorConstants, d motor.setPosition(Double.POSITIVE_INFINITY); if (motor.getBrake() != null) { - double dampingConstant = motorConstants.stallTorqueNewtonMeters - * gearing / (motorConstants.freeSpeedRadPerSec / gearing); + // gearing^2*k_T/(R*k_v) + double dampingConstant = gearing * gearing + * motorConstants.KtNMPerAmp / (motorConstants.rOhms + * motorConstants.KvRadPerSecPerVolt); motor.getBrake().setDampingConstant(dampingConstant); } motorDevice.registerSpeedCallback((deviceName, currentOutput) -> { double velocity = currentOutput * motorConstants.freeSpeedRadPerSec; + double maxTorque = gearing * motorConstants.KtNMPerAmp + / (motorConstants.rOhms * motorConstants.KvRadPerSecPerVolt) + * motorConstants.freeSpeedRadPerSec; switch (motor.getNodeType()) { case Node.ROTATIONAL_MOTOR: - motor.setAvailableTorque(Math.abs(currentOutput) - * motorConstants.stallTorqueNewtonMeters * gearing); + motor.setAvailableTorque( + Math.abs(currentOutput) * maxTorque); break; case Node.LINEAR_MOTOR: - motor.setAvailableForce(Math.abs(currentOutput) - * motorConstants.stallTorqueNewtonMeters * gearing); + motor.setAvailableForce( + Math.abs(currentOutput) * maxTorque); break; default: throw new UnsupportedOperationException( diff --git a/tests/src/systemTest/java/frc/robot/DBSExampleTest.java b/tests/src/systemTest/java/frc/robot/DBSExampleTest.java index ce489c7b..acb80afe 100644 --- a/tests/src/systemTest/java/frc/robot/DBSExampleTest.java +++ b/tests/src/systemTest/java/frc/robot/DBSExampleTest.java @@ -82,14 +82,14 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), 0.1, "Robot close to target velocity"); - assertEquals(62.5, Units.radiansToDegrees( + assertEquals(50.12, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), 5.0, "Robot close to target angular velocity"); assertEquals(0.0, new Translation3d(s.angularVelocity("ROBOT").getAxis()) .getDistance(new Translation3d(0, 0, 1)), 0.1, "Robot close to target angular velocity axis"); - }).atSec(1.0, s -> { + }).atSec(1.5, s -> { // Note: Large tolerance because turning at a high speed means we can overshoot // significantly in 1 step. assertEquals(45.0, From 4e43ea1eae0e75d511e3d3d4f090c4a330735d9b Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Tue, 9 Jul 2024 22:50:32 -0700 Subject: [PATCH 10/15] Revert max torque to stall torque and fix how test computes expected values. --- .../java/frc/robot/SystemTestRobot.java | 2 +- .../mediators/PWMMotorMediator.java | 4 +--- .../dist/worlds/.PWMMotorController.jpg | Bin 61658 -> 61662 bytes .../java/frc/robot/DBSExampleTest.java | 2 +- .../frc/robot/PWMMotorControllerTest.java | 15 +++++++++------ 5 files changed, 12 insertions(+), 11 deletions(-) diff --git a/example/src/systemTest/java/frc/robot/SystemTestRobot.java b/example/src/systemTest/java/frc/robot/SystemTestRobot.java index 2b0e8548..470e4299 100644 --- a/example/src/systemTest/java/frc/robot/SystemTestRobot.java +++ b/example/src/systemTest/java/frc/robot/SystemTestRobot.java @@ -77,7 +77,7 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { s.velocity("ROBOT") .getDistance(new Translation3d(0, 0, 0)), 0.1, "Robot close to target velocity"); - assertEquals(50.1185, Units.radiansToDegrees( + assertEquals(63.9, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), 2.0, "Robot close to target angular velocity"); assertEquals(0.0, diff --git a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java index 6af6b35e..f5f896f6 100644 --- a/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java +++ b/plugin/controller/src/main/java/org/carlmontrobotics/deepbluesim/mediators/PWMMotorMediator.java @@ -46,9 +46,7 @@ public PWMMotorMediator(Motor motor, PWMSim simDevice, DCMotor motorConstants, d motorDevice.registerSpeedCallback((deviceName, currentOutput) -> { double velocity = currentOutput * motorConstants.freeSpeedRadPerSec; - double maxTorque = gearing * motorConstants.KtNMPerAmp - / (motorConstants.rOhms * motorConstants.KvRadPerSecPerVolt) - * motorConstants.freeSpeedRadPerSec; + double maxTorque = gearing * motorConstants.stallTorqueNewtonMeters; switch (motor.getNodeType()) { case Node.ROTATIONAL_MOTOR: motor.setAvailableTorque( diff --git a/plugin/controller/src/webotsFolder/dist/worlds/.PWMMotorController.jpg b/plugin/controller/src/webotsFolder/dist/worlds/.PWMMotorController.jpg index 28ad5bb38e425827bb42160d99cdab7cba3858f5..f1a50ddf18307f30401d0f09122f9c00229878e4 100644 GIT binary patch delta 56411 zcmXV%bySq!*TqLs!2m=+nh`;|TWSP>p^|e&n>iQI(*;JwG0cZv-_V9mG+^6GOQC$%%!=$mrJIlbDB^W zF2>ltOfX4w!UJ z$KTAp8uBMO5~zXR=M8hNJDz9x!{G7Itm$8Xo$$ut?m4!yx=wa;3O1_WKc6lZHt52H@47N*eigp$T<~QG(@q*oF-xN=3(bn1IMiS!_Bg# zj*VX*yLcUSEj-tSgwdyc+cl{mzJS7`k^;YzHX$~-?jr*U=m7)x@YrWspW1-c&bv4T zquBd?@V(t3*xW0w?$yIP<)UvL#iXtwK0VhE&hlrwqYcNrdBAxNYpf!DowV=XnWU-% zi+E2V6PzXe1y_%S>X_@g|F1uu`^=A77P5{-_8)`$VI31bC3r1ywAP5+){h|mVd-24Gu116_hhC}Mn9byXn6u19G=LKJmFJVlzzr< ztQvmR1<{@eO($7|)on@g=@4u^c0VRAe`X>37fK3n+7 zkV)5-x(vc7{URh*EB6t|AuxVxPxI+H2oiF?z{VIvR?$?mQ z$`D{KniOqrx4aoGgWS493t;@Sid2_dXkje{iomS)LYD!Ovx@A!=5Q%Ie_pM%sX7&f z5kSIuLSz{f^YfsTTbhBnDhO&l z5*a$2{_j2U734A&;8czk|5(<3za#xtjNVZ$B5+_cL5b*L4N7}toX!bw30l}N@1I!ds@J8gncR_zvI+#Se`Otu zJkLn`pS59VAb3D7b1H{`X8DuZz#WZKxk~j zE%QecP{JK<*t`#PyzGKY2SZYIW-A`K>2k%7#yJf$uCx2c+YbWOzhBK56SxTVFCU0j zv0oZl5yXm`Yw#g6om$yI1>QqRbm3>futA^O$(*J%9Da#lSUWgQ? z3R_A(WC7r}jpT%Gk}l~4hOM3}GGpbXE(7er3#EPy883G>T?LZx2wKZ#n+7VBv9UrivlI z^*)d>t0|C}pzUb7!^6#r4)yeteo)=9NDNgQP(Mm4ro%Sj?1!)MyfD2`mDS4c;P#x0Lwf3K)AMkI+FbWw5#WSa3*KZ0lJc ziq?qDkJ=L8kad?@J#BGSFFR?eNA~d(H!bHqH3$#HJWk5&;moy09r&b{=vqwKF;;8f^BQS1%Qtiiu@$BY#P)M$8nTcpH53}nLPViCI8>VYWq`Rdf=cmyhW?J02?m>ySg@WfK+@+0tuOSi+Prqsn z&HEkEMZNuq4qW#5z>@Sq=37BEl-T}i?tA*KPD!NuAqSK%U#s7)V{y(?&35b+P{Vl* zd1+$I_VKiZ7cZHUJoRE}ut73Bb2&zWc#4N6pDM$&IBhB<74T$are&{FNx2dSA&7yH!#&x6Brww*ThVEM%beb#EIY_f%%cWB~t=Re3u%5ip5*Hs6s+#&2 zT8;Fc`J)C%$7%U1g>92QL5b{@PmI-Z0xIyV?&ba)cl+@xn-vv!AOW>KyqR2sb<6J> z?B}vnj1%n)9&iWltt)z+D_`k-b9Q3`56(gI8q!1~qF>=CDp4=PU@G_t`6}Y3peU2u z7Uzxy$s*x--H{lkfbdi}jk0B|HsS{yS}M zvnzB|rvtr+Jh8Wp^^3Rv&Jy!UFX@YdHEN0B9=Bz?80H`9GTH2?*J+e$Q{=9VxP0u3f4@-UsZ^mNQ_nF^Wbw0+uu{uAHtt;=hMve2;yi%M zhr@V=G`+)ktj{^#EGC*?SFxV?sFaj=>q;unqPjM;1_22=i-qC20c6Ex)_1+Mg>S2Cap)>HQCxs%^#nj<&s=d6qmHIlsFG}M!Yo&)CMNlv6zk&2FDle?#8tP6&r-HjhbWwt{;S!9+! zp9ta#%to>^`qVj41TUP2I~IyX_` zm73xb-c+ZvX-$Lo>A%Ra*hYRK1d51QtxjUM_2Isw-YK8#px=6g0e`>`{?uI;4+-K>UW4BWR+cfQy`Wrsd4Zc zvh+A{MyoM_SEWl-E}hq;Oj$boLU$M|+sJmV&tHz|1AB?drED2W6UrOrEsl7s-hrpX@MOn&F(TGOLqI^2ZY&fU8f_6kMD{G=^Mc*}TeXdX?hPC-+A zEA~9n|2ARk4l=OCeL*(96Xs9i1P$dr@Dr+?ieoohMME{N7^>5_hOGX%ji#SzAx?@a z{T7ro9xJbc@&yJQcKDC#Qz5N-Yf`TvbJ58SRN<%o@AgvNg>b9PmqR@v3JgVl@iXSO zBhF*v%0o%sp^yh&S9-TD0>W{wS?{8#t|8_H_O<;>sY+(sWZ#(Wr>yW#H5tNd0f{+) z0ev^M(2EUhCC9?GlN#HW;&`Y-5zODmdqIxyq*!%v4!9=}9_s*`_reJn9bsjw|2_Tr zy>;HbwO8c9JITZ?zl?B=mo^;MFz22l)!3Kd4Q+NJdFhubllNmM-z z&o^#HExc$I4bKt&Ox@cRg+IJm)LV=mI=G4{x`xcW!HcXoUv4SOoIIcpfwOxuBFast zof6?1BYW}d=-4#{nUqts>Fm2Z<2ld0Kf%s(fPtfawhwp5#Dqxs zk>lgu9b4#%%GnS>;}E^P1?edPLU3yiUb}+3ZK@e=M-wb>H)MGY*&fIKVjo(@On-&r zX6ue9wJm5jhY*SWEU=w+pp3nVa`m<8#m1}Jgx!_eI@}OP!}%i*R6&vU#ftGevPA@d zn?#-Vo63+hjpYVj6MVNVPJLO+Q5cw z_z0ev0(fSp0x1C_EWz39ajyarJ4n>hd_Aur2k{*l#xv-v6rq|`Ep{tLBIb&JjwP)R zOaI`;!BwUeTxCYh1uG?D`m1Xn)Oi(fJe7OvgDlLFV)VMVZ*PTE-2k*Mxf;i`Uh+Vk;+g#SLvYy@CBb`5!8CR?^u#al&TVDRil z%)G#$4>kSUOf!nI8oS4wFQP$6PzaMX?`BNMQ^1#XP6^;9zXB??Ko)f;F_%T?u4PFVvkEO*A&^?W#G z^-#y<(sbVra&Whe!&x+brQ^&J+5#ve($RW7pR!_;R1S2FYog!AZ7Emj2=5NcU$$;?N%03O#R~czE(3;V)`P`88`f z8bhBuElzD$(@p`Nef8vQy_^Bi1L3Y_woKV`XNqe`b4Tm<+?Jt|f9b-H$?iWl4XTtA zO~I@b6gnr4#(Y>)RE7kO8Tm*mY3{r6tbmvP6&H%{_Ndq+1@B@10{1_kMNH{O)&Npl zgzTYpBX7Q43*T=4?8|c-I^X>>4X%{B1K%p|sHZO?qXlVlsGt7q8qmmUa=YUf)|Qvx zz2R^T(cY-Tu*PV)2v>8!53V8lmSVHUY*->BwpflY-0LRI=`%&bCpmVZr~SSI!defy zIWw*y_91%D#=Q&v9E)%%oE;komjQj3Io8|Bd4)?DA{ypThjP3AGfzVIZhKbw?Hd72 zXMW%WL12~3er>m#Gx()(>}SVOzxm3{&wN1H{%5IU+^viX-W0YNz3Sgy3<<92zu%YZ z)jXkC}?i%889|$vx zS{i-*?);S(e&+>X96*}PrkZO$<@i|H!#biM;5~#hnAn~m#4x}uY-K1>zoO-v(ss0x ztlC*uhsRa==OAUPz-QIRCA{HT?ai3z$oS{3C(_(i*ANnba|NrjB-&ztOrvH1avH;S zRvyg_umUYi!aF_D#!pR5zSEbutE|$$d6njPV$4{|HaAlCEAJ^R)#bvV!(uAe*-gX6 z5L?Mukq)@6nMaqEWq#%2ptQ;os_%M?C6aUX~lM{89R&c)F(OjC$ceezb!4#;p)(#fo! zA60iv%;m6M-78*3Jm3laQB3duz(49advJ@w>y9kPsxOv58(s%q+CfvbD}pL&`iV_C z$eq~Z=8UF4>UXi{@H3)BM(qRm!cHZ%L|Pi&LW5c2qBzbW6Kqr;eJ+V)t|2dMpt}-? zZ4+9%kIgTwe3L|vWN$^`(1N5D5KneX-`eOM%L9B2>Dxh`0iBDBrlMeu`h0{0akdC^(1}dl*WOnV)xTD-3bLYM2*4H z(;CDk*zbjm>S%HOr>lZn0v%rTc6-kEhag7Sw z2R$z|x$C^+5=Ht8LCu}NAksiwS|X+3@(2{i0EHL%fNMC%QaQz}sY}hMWx`C>>@61P zd244QSB#T-jd=R25Yjw6z+_DKA(j&0T*t~TeG|#BjnSve#J+Z4*au>iB}7&EqP@ij zu)t&3PABS0-!^lF_|Dl}>3Us#ee~HRNJRf`(FTwI@EkOgxB3!rBC~j2RODD<{6Q2r z!SQL1i%@;w8gcxH-?cSG?xw7WjKB}J`bg&&{>?X0@E!NND@E^!ay{OyHgH>Nant{p z+p-oj*U>7={yFLiwt=GjO}F$=-$02Y6}MVaRbA~7;hLVR(9up`@IR-KtOMI{D7Fbi zH~$kh4bX6J!+H}U(y_OI#4npcVBkBWo|6;L?yCMlbaOPN(}c_GaLvk3Q)b%YU)cv} z&dXFgJ*ONF+8k`$D1^F?n-ux=;2LT9mj)!J$YTMv(PZvb(Xv3gtwwJt?9AZGn~ocou+ z1pUfxNN}PEbU2~>r${hDw+q?^YD;GWM0fetv2|^>Cv5IZ`BBmE{9MoPmeGH~#&Y&+ zma7s2^xY!s*)DDrnrsO)RyE3Nh--*(!`C5jH&{>gmOYJ#JV}3`h+f)O{9?0ew)S~- z_3+BFR`Ff+SD=J`eDElunXRl#7DE6oG7h7FaRc;|4>8lq=sxA6`*uduTx+qU;P;2N z16*OW8$qVlNV&xMr^CI>>}2_U?nKgr!?Cu1lw0lzVqa81w|4T~&Lb=iK`bWcNt%>b z0Nx^PAlFN4leWE26g?ph9=BlYzcPhIoX0g}4H&RLb)W!@eLw4e&cI8L3WYd1XIv4a zZ6Zw5Fhl%oH`zaf zMTjfRG%Z*fE$K~&8_9`kGv@Z2$$#O2J8Zffs~)M|22S-K_W)BM+BJ1fCu2kHoou22 z%n>>EeGy^>rx!9qTon8;ecir_EfKD|LQnc&_V#C8SB)3o$TIjw-tTjzQ5U$(U`{Nl z6Zfnt>De+71^rDpb6UpRvQB9NMQ|w_2Pa^(*m0&L3AT~(1tBHpjJnXfJsSEePNaE1 zW$IVxR_U_lxfQ{c?ou2aqSZ%_hXayXTfV*llqm*vTC#%hn(TzXKT#T_(wuJ(ZNsVV z;50Es{n#)MMiH7r?%k;bB5VbYD}^P!;WQalif1h3aol2%=e;BoMu+Ogx-Yl0>M%`4?LB>N} zpNz8OYf`?vT!~RsZlim7%P|M~?PvE@;Lw)#ucPOnfF{vDd_~|wvqF=)H}Mt(k>3`rtl~6 z%7lj^8v(yEi{J&bGyQ;jP{TdM{6nJM-)Duh>Rv+Q)7qiyHUzVvXfa_2#urSOP8@U% zqN>Z8ZRUOevnj(X(YERAW5PbhXWypB>$tDPW6?&sy=(k`>!khnBMYG)M7p2zqd@8E zs)Z9$UFBG|r3mUTQlwe0|-YulG3S|t4$He4gTPhjeB zJ~+>tm8JB<{iY0Qo$(ICn4;Oxi#-&jikYTbbh;RzRjq?wFXgKA{~?Z9VA#?>7yQj# zI+Sgh|8Ch2t6-V)>qGqp!PJQ(((@M{GH ztX~5V6aSltvzKBQ`eFHP$8J&}C~^4dH!1ivikkT_H)AFywt-m}!tw^5aWm&1A+)Dn z-K}H#S5jfW-C5w9we*A@u|7%08U$ZV%>*V%0EJ&w#d*oedx{2xey6AW{b%um#Kc#> zbVV0tT^qf2@}NVjj8kZs0_amU{KDsogMZ%}G+V6XC)R7n-=yIkT$y0Zm!(bi(wzZb z>a3Ak_U(~0xv-|sv)7QyoUzRlGi`Hnjm9U}kP+5$OMSWb1$0VXPYxXZdB zT{1SO@jnVWd>GR(5)xHmvn^N2TYSw{x#)9JH}-nL%r^F@OsrB_c>f7yhu?+*aJ)jB zau?IS{F;zk68iTGTi+>5(lWyb#N3qW^WA!IQI638BJ!b)!-GHzFOcg&#}IKZ7m-0} zDJ`b;?cLVjHBd-?{*P2}C9*Gkz@yr)wg4x&T1;oVADye_>#2U9p$k6QXsex$fnp`p zCGDc+!M_^bdk)7OyG{48+dyNeQ967m(m)oWGuMoeutdyF&w^`!Jy>Qcnh~LRBXoL{I!-{P{iyq^ zluf2|%*Ko*_jqO6h9unx+BDn4473(v%F12l2`g)ka;TX?VB@ubFfn0UV{KZ}O*VhR zN6aek^syZIF8zEqg&Q;PDP8~KSJazhx2Af!!jBn0wP^4?u=ju_se{_5`92`g#P~g5 z7GL)FzwK;P$2rYgHrMI#Raq*-w7A;Af0)=qTe-vm$o zwAMsX@=>rH(7B@C6zKGk<0(FSRJT-tIxipvBtVwpE-FI!ttx=YbmFs5DS<)F-{w-! z&~t5WLo7+40SU3x;-N-I=Uqo1QN}yvM$KllW2LzoY--G!;v&L($UCx2ihou#LTID^=q#@(gWJnWNmJ0FOOk&pu1E5~^yj>ueAb>MGMscV1)xANaI!i@ZVEyFxB zJN4nZSrd4HCe(tXCtlhe&f4Jri)rqrzO)3zla&q2g(anag~}Q13$A zx|*2FlZ@IPi;V>5VVfr&WWSqWk|oF>$SAZr$P0%){X+t4?gO14s|$>pMT46+$cHGQ z<3-(vBvQ*fB0uKVP)8K;*2ZwPWJM(5?1)RqS+s$`N>tbDnh$@85}zV_*hF>c4T?LK z)Jgc7Y-qqMT?Gi~uMAZeyju$c#Zj$X@wcGOBchDJ&%^A0cvm?Qr2#uShUl{jlbTVo z5_<~U7cDY*mCbKFh{MBIBdN#5Qa@TbS|MMtGXWbok@P7mw}W!7E}X*!N@ny@R+cfO zfa5SV8I@a?^gz%Sp5ij=(J7E}3d_|&ERD9Wo1731S+ZTmnWR1XXn5gB!1dAL?w3!O z9!S*YZ3pFI^xz?Drei+7u~dCGi*-NqU&q1Gn8*5jADB6@I4pKpG-G_m3a@v6E}25Q z3UIEbaSUZ+rlaj}9kzJ6!ro;Q9zE-klS^~e!WHZ2ubelg{aJ>apv@lP9TL?ZC8Fo% zx@0j0Ayi@XH&X0!^^oRcYcSDVuaWAH0OtZ?33q(RGuKG!Tz8@O4NqU@#hT}V?=!^P z7H#G&dz8QR5fe03*^oBsF01-|M_GgmsN*)$ekfy=@(8#Z%cpuT-1YmB*{m4$F8rjV z)FJ$%t5vw-_iU$+b6nyi8l((x26f_v7mbcxC-mui_^(Y}c-kYHAgxl>)amFp*xX+b zV-;PcWr_(}nEnJcjXrEViR;;mGlLYx2H$(qGn8x7^QnRUW#+0b4#GptImL=VSO{ag zK6#bUqdv{ii3+qzca9M&WacI*)?4f6ZkPYZcaJA*I_G3wz^0ji@5Mham`#F`KCvI; z(1a)b0e%DHp{+le53|2VrKSbCWz1g~FNqYl@+!GhH88tsELHoQJ65r^YiK6r;d#VB zJzv{wK@qd`qaxAL_YIr{yW9-wu^0_!|A62TQmy+|m#=DObM1;HXk?x^@}%>QkHPEN zuEva-T}s6-Z6d)mk0%q(OONTGwhrVAtI++2t$kyY&7`Hu?}rqim|;?MvM@uIo1Z1S z$To-Tsgm~kk_|h|A2d+ zG$Zl}dq>{=SO=k_%G_s%y3ExW81cUdiORPVyOg0%lbQ)N_2rsC>&E*!6y7vL8 zx=AS7+3$CSwScCF_=c=Ll?NL(`k$w$gL*pDMFI^9?Hd*2fLs&vewznXeIaYMrhCA$ zxRg)7Gd#~>@R%VLXat%bA<&xN@})ItmC|HCD!OI#`!JFUp#!4h&Dyvh$HPA*DsV=^ z)sUzHtkcl%7{VUN)xG=@IX+>h-q#u5pT2H2^|)G2Xx|9t)<$+nu&@yW|G$0~sjkG3 z$i(-vVdBWJhvw#f>p$x4k{y{>;n~V7I00bHXtn_atWJ*C5FOpplVUg8Ia5cb`MyG; z!`lxu>FKW_r%eVA)5RROn#sJ!jjM}gtZEbazR!d`kgz^E%`7JF?Ae@0EbV>E-l%Wz zTG-ISaqgHC4KZT|CDYGx-9Y1+wIxU4yhhS3tBdpq9;jv>O-?eMw2| zf$=_CF7~mcY)>Vua=FL^uMfM3(+`JzJ2###fC z6&HP{h-ZO1^p4aLdpr|q)laj1N@7L6Ra|~U?!#-H2AMB>Y+(}?8Yo=YeeAIT(*a2g zS#M2W`abO9-rJWOaLT0?CA9G>IrP*O2x{OL`U83e%PnttCRg=o!C*qvE#s8fwQry| zzk<~h&Cc5zcwlfYH!j=wi6;JNO}S_p z^>uYIXRn3Xvr zHIZ6oq?$DcKzJHOvUt#{JB?u zebz(+7qpvp;3DkYVGdjfkr2t-;uBb1RL(>!M|NIcL-d?(f;^7$^Kv>ds$|B0e8pzg zY7I5#u^Eips{SQC^kwPMmge~@(sjp_)`z=|FY{Fv_PeMqZQpAp?74f&A9M|M<(g^G zDE+yU)z$C)Rw6BZnb?-KC47f{fvcC!bs*0ZX1vXGz!*_P(+3~PPO+-OV8SS36_u2vfsn+ksLtp|B=A}^wZlrl~ zpSr!&4Qng86j|Wf(Sp>BL`6qi`ma2AaE(95NQU-MZTe+t zO|Q@tas~;lKRYW|``}mhMmh7VGF@~rN0+b}l8wa+Aj3+J7~pKi+VGsPT!%UId98$a zsA9`gB~(wh@}1AXi!;9)7y#;&qmTk& zy@3aW$6|E!1xXC8(}JA}4>qD%N93k0Y)#A~7uwU8IS#Qhqll~CVqL<)DnO-$sx9lq zu@4lp4jPP*HL8ZGnOV5c&He|USzHB6@}G=eil1E3whv1Qd)v>sl&`zA?J3<*yIO8= z@oHye8!o54o6If?V@5sXY#Sw4>Q>x;IS3e;HQF7QxtSk$8)rC0x%`|vWxKH0#*4J6 zF9&;i96RbD&WSA6baO__H?AQjfgWs_VIziRwMHB^2`odK}JKd~rkNmUOxvAs0GorPwF$bZ7sl9c?4Yg?NGUpv3J&$YK38 zqBnBt76Gdpb!lMscSJ``(x-<^%!(tMf0SLhwMj~w&u@% zLo?2O#Z%m z(#y`MR}u19gj*>Fe)DI};n`Q2wVDx}9AaC&?vN1sOi(q)WLmnim)tGo*K+Yf^xJGon{;Hgmn{mc=+?)2QFmfMD=u4(O_Bo^%)p z@})AqnOttvygB3Fcn$gfk16bj%*K73y6>T%iF|nOM?2{Jv)1or2A#h&et0;!<+IoD z&l8%9;Fi{L4D&E1!K+UICbuL5Nwdd@=7`F()GOGl$R1K{eV02JI%D)k@2ujk^?Ydqoth&JZq~KnW zwCW9&oitm|?gRXvhgEZ?k~iW839byp#G-4wWz-&Z&^rJ}Wz4r0-6hsr?zmWKMt%BK zJBM2kwmT{pbGx@Kq_WOMHEp=dEw^enI~Wz)N=EUEW8&H3mLO>7y5Gjj6)6`x>fB^$ zZ2+vepxefW7vv^hJ%2!<2z+wffs%?4fE7IFg&Q=%a#k}e+xlrMx=~J6C0eTbz;;9e zYM0UyfWNR$(7#(Eah|-4GjTNP8LMOyGN&3A5ww}GXDvmf=Z5JU%G(u!rqkI&=OI|; zqwGGm43RZYzX{W?sdcK*O2yVuJ>?*HNl!ztVh}h;W`G1Pfk06o=)))p!_&V>11pGw zG8&hSugmP#fQ`1(&jY=aiRtFvfL$3T?q7C*xMcXnM36Wp8>&KHp?*}%D8d+3to}aP zWkR}79*`JB{54+9j(Tiy{vCc=ZZH=zK`{a%f6}AOF4LV==hJ#AuDls^a*9xJCPgjt zjZb%_kGGR!Eh2m!VP0>9t|7mcfJDdecIs~yQyO#TqMBV`-P@K46^}{-(nO(ojqUn1;9T8w6%w*r^>-ejj6X z7*@{lV$rIGq7`KN1CKyY(8ckw%p9HtssR%wQoH1YDXTYZGbMU_qg zx-a%eOZ5yG;3;>@c@LkZBpUDb@$U6dS3Z{7m5S^Z&wR2fZTlZ=N%Mg$>}5mIruZfx z*DrOqq=cbk9jkc6I`-uB)@d1C2;v>bVbfnUi%Ym1jbbrG)rSwV%Sc^1Q>_a~4H))x9i>9|n{0q(AJt6}mW=Ue?DZL)t;bXJOQiY{pUuTyQTj>50@V#6Ux%8YKN;JL(6(&Qa?{~rSoQi7GwGV1Tz(K?wHtU|k z6n2TEm!JmfQ&Q^03*Rv_${W9C49gujDbfy-8=Xw&ogR}ZQpWovEb}~4Cx0dI`Wwq- z7T~5?P@=cG(jpu~Vd;(huXt@-9|>&6@tsm;FG?P$Vd+6<#6)`Zt{IGS2YQw zgf7@o9R`nd@nx<3A$j+H6VS>)tb<&>^QD>Pt#AElJe z_L6;;Y~LSJgr}yVW-bjpNDz5#eZKld!SYY^YLv36^>{j~f zO1L+@S472v(q14KrznJ9Rx4wUnUschFbKz!t{fvE+sM+! zZ_>snfK2K0b5?7G#eNbYq+JsZ4T@Of-$J*8;=v&ChzF{LlB8##!vk7bUFuX6FoNWrl>NbAx$1yafMS8O06WK62D_TzW?b>sM^@CsbcB+dpM(70GRQ1qQyWV+5HoOI zev@wN6h4j{=Tu<4`7~q)jBWFeJ|1Wr$@uLLy7n1q{@Yi!70)h0Y18K%N`j|N0hNZ^ z=~z~YAOqlS?rs+Rb)5XWbJ=*Mt4P9LJ752{*Yv}#^vNd|&7@i73(C2$T~)+dWCPX5 z6ZQayO<NEKsUf@j{i1=_0e(ndvI%{|H13hWZ|W@|*GDU=D~etB?ri;%%UE;YHl+=&R-biOM(?Q`LXqJxo*Q1s8rUm9FXE^VLNvZU*n zv6$Z+`$0E74J-L?`WP%-_MpXe)%;Fu&Jt!sBv| zB%o8`me1{w)tYKRv zE?=%nz@^rI;*-n1aH%IlYdyH~I;!k<^2-?p0og3~>l zr1iUG=UrWR#pa7tpjBmOAR?)Q>Xn0mXtCR^VbWA6H>r51qQv3F_^SD>p={JQwj>-{ z09&ChB!8**eGT)8Slsi*zIhGRM`7xJ2AVJN$Do^FU^P_zO`uAn&NM)t-PwGIKD=#a zusqOu_4e=Yo*p|uuCMl%{=-MlT5Df!4uitw$FhlJU^>a%!wz~TBl14=3=)InBdZbN zI%K>YC$J-;&XBM%735UZUaK*Fgd&@_)k>t<4V_^-E+)f@%K^cKVng6zZclJzTGS?$ zn3(Rp4yo-9jV@dSPdM=5llN~oq|weCqSbIVs{J`FD zI@%0ESR*J`B*an_I#;34wI2LWs6#&{6a5PK73U$+{8Wy`aP^7TAU>h3AMh8u+HL@! zX{@qcP84k=(Mp|>&zL%jzE}GAx=$!=j@W;ck$k*tS(&M7f$l-^Wh4Qq)_@9Gj(PI8 zHlB&+`TSig1!c*6H=Kw+?1C?DhV3p13^Fg?dbgd|9h3p}VXc2td)6ZsZfp}1_oCxp z)KBsCKh{*-lQ=Jzg7i|1?v|Gk^=?wHTLLya z(Hwd$4%+@w!K;$PAM(0NA#d8o1yUe}OP^zA$0LHtLK7W&+l0Bp zy@^mDUbMCn(EuW%W4n@#9*E;s=VY=e=lvVd=3Xno4^8F(2b280JXj0Cg~h~S2J^nO zqUs^J&hw*Emxqks^{ud5DQV9qa$r1v;X9zR>-UO@Q(x$m9I43X)@q{q%*XcYgNur6 zpleLxC%xNBSAbP%KumOi*9=@bg+F5TRgYCP30LQvx-@sG0v1o8@#BOO$ok;w$2@M% zdym>bEW;y~g%%EkzYE1C!2@oR8vCv>5PJ>#p=6`*7OEH)XCPNA33VlR@MTUJ9R>j; z9$eClSj@;4OsP6Z+=-P9-QAPkMxCZUb%DMLbnu4){`B5Hr)7h9l4L#WN$W5C|<6o{^@5_r$9XT%+0GWFPRYj%4rlUwk%!~NV*V5-1qX)p195) zmp%``r5=jY`v|U3a*0R7|MrGejTVW?qsiXGIOTg(%!q8j{A(r4XsIki^HBPRuFauq z7}@jD8?YT_=qlGgpMFL&MqH-5nwl3y`aE>SNPZDB7-t%BavAhCJD-Tx27H+f!CM<} ztU8!8O{f@4I&AYjQOfu*KYN(2vZ4Rgnjf%Xc^If=IqFieNfsnt1>N4?a66|UJp?@{ z0>zlh1qX1#31HtBNU<#gySGj5Pr-)22E}S#{lSY&JRlg4`qteo#K=dqDFE~)L(eDc zP76eK9}eUZoiv5l#xo_vigK3knvvW^Ybi0mP^-*B=)dN;tGuAoo_{=Upxk>I3Ap#H zuF}4zJ+YufUx{FeJsxMH~*0$Q6H!_&tbBsK3ji4AcN8WWHo(RXE#?e+`ze@!T} zj@7UBc5&R7Z+i55<_qqkd#S@2zDR5oKEPArzjYsp4KoX0n%yD%QPA1Cr>J>KLGU#o z)fZVjvn~2zc?y?GI{$LhN#2hB3*hu)2um&eBex++>)S8>7q2M8Gbt06LAqxwvXE4J zE2MR-C(h3ODh+(5TJob(@>sY3)A8mMz71=vG$ z`(pbTQlso7tGdcx91KK{ze+UD#vf;CXb=Q~!GPP6IbK>9FU^q9&1b=LVD7Gk>V3^; znaf%PY#s^gGRSk)`8U=f=?87Qyhn5vFSI=5UGQr?-I25~g0}vPEYaVWw1_j^d!6YW zSM;|+{pe$dGTp`tl~?+ifOo4@+Q9D@`0AamDmx8Zlsx5{4EtzoZrK1Ewkqme`2>m! zny`AaTu{@Soj*OTe7`H^v*8B{t1?a^Ji}xNW~Mg@RB7NNh8U5&H7>Ze_*^)O4BLN!T8qEAG-%$qRcUIa$huoUXgWAr6U1BNzq^p2UqAL=|pu^%}|`n zX*IB~mVGs*-28uJy=7cf?-%w9A|W6n-3$`aAl)V1C0z;#3E4D`Y@)#cz|9sbuh|uG``}s9hMCXn1z5pVyeVk-?SD`s6xKn_MPr@4Gxt#lXSB+^7O+;)LC`A5X84uETPG1Y7?#@266w zYx2sZ-}k|@IaOWHuZA1(MXEt#ugRCp&^@#GZ&a4}y`|zI%=2aEyI$Qs)&(rX9;BS& zdZ40Exp-@C{M`yR3I621IEWFSQ;EX3eEKHIV7xawHtDbq=yaWN-Hg+_XHE_mO?v3n zhX9*}d6<#Ue<)?O&92A^U1VW{m;yu8+Tz)l7{*rp*y_KU^%N!xwarQEY*b-&Gc-rw zQt2%K-FM33T$z#l%K%QCn+jSQm{SEL9CFkgjo;j#+h{h{v?ox^dg}?wN%1`EGpk<$ zO+FM<4pT>C4||}yDiLPhI>TWSO`z*!)W6;CqNe;CkFl*mdW+Dt&0wr7%O}R9F{>Y`>n;%cN z{<=d=oXvPNhEm}asxrXS-MFhdn}6ze)bp4HIU0QjHlw8;5x?DZAq1ZNqGnldWq!gt zEQuL)EhvpQe0c5%vRyV zkuDNwqy^DKU-`(-_XXA0hG+omS=Uq*Uvi&t(YtG#GPU&+07Cb|aY0HR%OH8@vQmBV zm!Qvg6?c2rj}7q|6N$^Mj$ZwJSCs~Mer1zwsGp~HYZi|0DmMT6u(?Q@Oj4SZ?vBK) zb^Y~DjUCH2Zyx;eWlTM`uOu@lSEu;!$LKR7ex|ZQGG2jSKIF2; z6+BGbqoBHgJsJPA#Cg`bmtMc!dVSKtvM*t9T`AhvfU(|-Q>Sf4y5Jn|k%eqWi*VTg zG`Zgr*#&y(G!7@Lk@cF176#P}R|91%1^a{>12xTX@!5Z>RS&3IIkgt4O0I%L2CwQw zU1aC9e*P`w?SuOFYmVW>qR5N$Ot6L|i$N*@k*L$2{|hfHPKdFU+6q<_^LBCe&y&Ta zae*t;>2Gi~>fQ^a91ZN4Eii4JJzTl3pfs*;j712+{r1CcaB1g#lY=GnI9}mEnr0+3 zVVlszDf+Ui&Zw`rJ9Id73yxNr`6x=Uy?IvH%0hqi9`k`4L|^62U)a?uiXH3$`6hu{ zX%j+*n^tpGyHoRKupi4tT}1EaVoNa~&PFe5fct3^ zb$^8z<6BR|6e$XapP=pv8ka?O5xlwf3lhbg6mu^`juJd86|Z+HeDDt4=<;C6R4APZ zq=ad9v%-c5ps;(m4CXPK9|(}KUfj(*^QW&u)JzE-nwjr~kDOJ;&ZdSgZm3Fs^8biO z{2$8wqy2ZLbj=8@s7enWP{=b_X9KlOo_}J_NZXlz$>$Ktkl-ArcCyI#p+yz%xe8b) zgVCAuX59R^x^5QS1U>FQqno(JdA{(Cb~QRP_#=ZXoCFhR=%2K$0>AG2r}(*Qhk=Po zEX>D5aMtj#9K)62Q4A9|{F(oOZ|c=gt=}jwR~+&9@A_{rHUs?=*ps=YdOR>ij@UXK1N z8s;3_kU}HSVwN4yKIhQHTD+At{BSLHl|#v5Xy>Bry;JcNW2fDR&m6Cu2*Pu`*N@!Q zMTS(#{8gjizL4R|IvE5CnISO3#8V(lEqHL=RPvrZbkhQuX}qPl%!vk%Gi#YOQvxbW zjj*_XU0>>Un^S?Aadum6Q`TVsx>v#|{UxoB_DgX4pR*`dEziqP95j=RUBFqL*R7FK zvJfcph51#RRs5D&Pc5MWJCULKKu&M*_C6?l%k2bX#qK(H zf8luiw-RcEfY%k-dh=>u>cZ)9CufjvCwj%^`deh)%9r!HI>FpqS5DL+nL^aggqF&S0$DYfg} z1>IWIidpb4i$1;@MLJc}V40wi--tV(n5KAKKC;BqrV2#ME`gTuXsmo}^&6WArP6)g zNEN{4&*29!+#-j4Sjj@^ihtrZtIH|hgdF&*{c%&01-W*~KUPq8-taO+fvKj1Z=xZw zg?tQrzgo<3y$aPxq@7$_RG7q~3wie?f7j5DyQfswszPS|wx8GQ&62nR;i;JUCb~@q?>}XVHGF@7qse zdh$=OCi4wntbMIPr+q}>BXcp`^{_U#tMazT$g#V=;r>SVzMuYz=IZCj8L6hl=QI^J z=+TGH;!>X59h0Qv5hC+rc_GAwVu4!hZBQ3{w>A+qzuxj(DLS)n<%c?4R2vHX@(N18 z!Z>kOah%YbnTIxxKU|^k!0gd5;{#)%~Bh^n5 z$rV)LJ93gJur2nTX|nXe&vjIn)PVVxX&7cD+knP5exclR2ggjD5B<@6eS_^G&Z#Aw z)g@}(slh{N^Mk7!$|K);8hq&`e#P%g6cOuQi83!j{2VFA2YJneOgE`Mw$?&jQ*CjN ziQmSnqku-7yiL&)B5B_$O4~ZPr;Z7L<#7egcwWuIJ9aYf#iV)eHbJ8gKb<1Q<(d=USln= zfeGkX-O{ybZ%OvQ-iAE`Ghrq`$#Ne5|4NoK^9a#$ji^-jKEyNd=mbQJh;v1_LVqC7 z@3+3kKk0>RYn&4=Z(b93+lpkw1Yh2Lykhb?!7W(ff72t4MiniBi{y9F2&1q-tHCMi zdtk-9$p65wC^8%%8vZ`6g@wOI>5Lk++vvT-$v^O}ROyUR(?V7+aR7O}jm(YUX69As zyAYbJ$hCR6aO|7V0B+|pxrg*~ZN1OF^Qu+I#xu4aeY0dlVQ@{S@zvXuAe(skkm^@0 zdGzEzl+mw;`huL1=jddw3KTyieT`bm9L%4q?JAi6HLTaL2YL^6vy0PFFef8o7HCY@ zBE0#Q9odF%GZ&VLJH2@lOya%_+|SuCMbrsJKff1{Y>Hf+ECFsG`>vmQorqNJYFt+F z{G|}YakU#$OX^$T^ImA=0XNBH(BbeRu5M%LVG*|qwCf`zhTskXpz}EGn9!uNuj2s$2(_4KqclIp)-thaPP_W3~?~uFW#K5 z+P;h*1u9XBz!(XB`v1$j_?QU&DO!m1#K&%szUon6C?Ok$%LmP*5rwt-DLs8bM`Vy7 zP4-iht?L-&K{XlWeb~>V5g$a$N)p!Hzl4%(#b;Gw@ZSp+N5i$o#*TpsTvWl+7}_on zb7exlkfi1@D(7$vRGO=4h0_OvPdG~U(3t@M`KGe#bY(NvdfLLo!(afJTU_bp?6uHt zKi9@B+;ln;bUaG;2W(nBw~z_nNW0SBN&5Nm0xj7<)Z5uBoK>v)j+7#`hb%5H9$M>7 zaM2#6m_J>o;Kdt_P7a*g_iurdAaj=;9_9mU86sE#k;hnzaP$!AWY!QVR-{SDeK~)4QdZ<=?+%NjTXqwDrx0eM|GSNKz!cq zWhs|Y7*aS@?APuLPdmmmrphV2FB!2fHC}Fu-ey6g?h^)ARLaG8id;_$q9@l~J{L2( z__7izmf8ARxs=D{_2Q8|5jxU%4j%1WaoGwAzTpSKB@Cbd)pje_QJC2KvV}i(0)bfPvMy5opYI72l=pH^IYXf<4e>Jj7lM~P zSdDD9W2~4cQ(>deeV>9~*t#TVhQog-PbfPx%p=smy`FACi{(Qcs+8~BPiE*dMhk}J zl{^i{IC%|k^6>J+QTXSFs`g&*_!q$XG#Q^F6Y|)()t<%zEnC#eKl&`q*vj^5U_SZR z@n{dV=Wv9|{5Zq+KYQ`FV^T4+D@pV;63M@`kmk3hbgxBeYYwo%QHWJvx~O=XqkTGZd~0 zQ)*#k%Nm#m#z@k+RoUq$tw64-)OWyhqO_X^Wp=qy)L0=iCp~ME4YYj=av)ofjNk~0 z187O5=gy?8hOUI~FD8UYV+OK#3fgTsj#jL3JmGenSXIF9;tO+$Sj^co>0S|^-Fz^q zcq;P<&Rl(bk>4rjubzx$hNQ4t*k%g95PALbix|F{5?A=uK$F88Ip`ruXTPp6zp4BN zo&5o*R``Ixc3^@4%qz6(e9tE?`YDVyiGyS!9y8}&&&>y~g1Z~uU?d3qef(O~+Mjnn z8)=3zONB;n+;;^U39D3|j|mq!UcSH6S&D(tr;J}Z=yWyk#t3r}qQ@^;y}S8!b6HNA z73R5rSUoRIj`>vBn*L5do3APzy}Hx-e3r6Y z6mvm7fcw!E94gftCE*Un&sn}xxvKXj$_?-vU&ooL3~VmA2=*KJ*YB-RoS|1%S(D-r z4_od;I%he2&G4-xcDM5(LpzHn+oW8-?+%dP6~q~jB|kbzchgw$ac5* zpLVu7}<0WbHcRImNCC+fI9<{6IW1;AMULyt`A!zXbcTx4ek z+xNoFL&KzX;;^va%eWq22i-)@))h14AryS}ou`Q~*Wtu#cw241M{f=mdW?DEAQ`>W?y=FAR42ywj1@NL`o&Ji&|*pjHz_p_7NbR z(ue<|V6YDfp1-dPfm`gzX`sk7cAdP$4p7br|v#5~?SDN(B0d*Sz}zK8^~ z8WRAoYaG0~s-I*9?;m)_ul{VDsihk3@jT`#ZV^aGYoa`Lr(dbwxb-Vll)pQ&q()k3 zoRP0bTPs$u-lRVPF66A5}iL&<94WwSC=IQ&Xss%Q`T6@maW9?up7!=>0oD z`QYM9f1!W|3UoANVB3bvbB#k#aq5^K2M`2~1gh(*MI}BB^5BWk$T_=u#HECCP_>f&|I{L%cdHfXZj4 zxV&;lvZW#Af5}B3>-232XO}JcR5H<%rWmp6d2Q^dt z2Vm6X^}T=Lq?|W)?AcRxDTcWIjU1w|)Q&zQ-ps55mUrR`<8zEm-5eaQTZ_v|SJXqaBpo#jab9Vd(EcbxR%&`1m40>4S~~@#wa5tgInMoP zcPKytmi^KYEHKt35}T7|f`)^*V0hz3?|dNZIETM6d#|M;q!#8iOUg#%DAsG+|C{C+ zqPa?Mfh16$j6O&z!}wBo;4>_zXYwrlorY+>d|lZFA7(S(wmL-&(tj;*w9N&hqK98;_u(7rC?i66aP#-n z0JOK!;&e6&N`J3Rp%U@SN4wEG1vk-O z^iXhmS;bzT+)rr?@(gGDz@;hEPh!|5{^Ue_g|^i@JYp`3LHEpzBlT;|&0!Tz?4*KV zTqBE~UYrkp_yyl-N7*N(`UYN^tawx4Cnj~+K!K}|ubqW+mYo@ILyKY?YQpw^Qo>)GF8{e%Lf8O21Um;bZ|0wce&=0H1dXj7E?WDuWi$E)l6c;?o zCd5HX=vp`ZqdOuBxsHnDd(>XJ_?1eR!Me6W$aNz2m(to##Ixj;nu@Fkng_Eea1R)r z8-9LYrIImsm^bk+X&~oSeW_X&uT~4~^@TBX^oy^6ujp&(BrBRj`)_9%86COfYA`;6 z6_)d1ttQTcLrf;(-{cIj+X~ha`P+#L>nbWuJ7Ed&0=PvI--*eLb@U{$4&WOff&ze! z!Or2C{tggzxak-p1+9*VFI9lt6hCvlxCmu&i^w^q<&y4C?@j-@W0^Fu`_;9c?Ikq; z8J2TnTht}?mOnRIj^Ij(k;1=@Zj2)PMk@y<(JI~YN6M3h|n;rQ0U-wmF`vvO) zemJEYvrBok-)h<`2v%%6c41r*fTM|S{P)Br@qHM-jR1!pk05XQJA)F1Xs2rd3I#; zlg7$YaYQyW8%z3yT{*DW#}SDMjjBXmMCrZ^kqiz6^QCSN31MmKJh){ldc({3SZb5b zmrYRsa7BR652_^--Cw@iuV)_BCcu>|5|wJb&iycrc2ZR}t)KcO9G#4XEi+FrrcP)P zixX_TJj4JV*6*G8uzMn;t}t_7?7<)sE!dRnnv({H(L7t&Yv%Q@3M=w9`m=kNkN*#~`FrjQVX znnb8jxV%k`>qYi{$9iec8nwR#x!aAo=Lhp`du0#>;6X8whSo{|u{qzG>aBfr+q?BW z_MD#vDyDxhpn0y;+^WyJwhGx7Zo!JBEH3;O@;TbMb(&@dUVM9@Q`-{1wD;o|9Tomd zc0g6ra>z4hg#>U_8lVdFFKlZ8XzX1c``|&=FM-`tjS+VGyQ*7#yhKkzDw(G>(CZhe zi4OAjYk;q}GgGainmY}_nT6qDbtnCR7(>ymcuYOk)Z5l%BZNP=$~j_+lzDh+N*K$H73ElX}A)?b};~vO@>q@O4t5jKcx|~Z3kC7 zUx1+{GXp}fy7-bhRa3G;8}yAZnEPr)Zaf5liEf*D=~LD9YHUve#d(}4ZTnxxYk;0A z3(2z{n|&I>j@kNWTm{XF+NvMr(NpxP&?cMBpZ}pe@|mUM$!Tm9`s-@edOkuq3YbHU_0q^arn?!ZTR_$Qp?TvQ=d2`mU_cy~>oIe+GH%bz2ZH^%8nlclVW?Vf zNimbqc6+8IWDnnM>d1AD^GnQuK3!d7#1rQANZ?0+PSazqm>DJIz)yUm(SNWWXxS7j z*SO)^>w6e#yqo*+6|J3f3yN%cbKRkkY0LSU_M+iO%(G^#tXe_G9w|4+NGiwZQh$<+Wr<tT)!|o{( z7Rp=5I;(Do>bpuwiW#lq>j;RwniGTU5`K@5`4@g}=RE#A0<%9qga;P9p|fo#hlf6K zMhh54uYy0%VRzVxIM`m)L1k78jDG6@R=tI+Q62QNyhnFazsN4{u`h1UR`Rlz7mbQ< za5XNtiIp|T>>XV=6T}l4k=e6lXu8+JnVczm>N`}tx*TuD9^UlY8$M&9OW2%CQ>n6> zY=F~#WB}Bj)=2FxZdeorO}`a2pu!KjEW2u4i+IkfJsnk#U|de(em}SwoxQPmr=^d6 z_;)ko5T-&s#+O<>Y_mm_?`qZs39j?1u z|7)sSVU;?#!{+$2KVA^~t2?tn+K&O7AMv)AeP{jUv46Tb6ok6=?Jj$!G zs&JrSA8w=wIbPhd{3r1!D}TH!5p&1}YbKY&%S$j|FuZ`NTaD3m%V=5nMpp}QFe0jL z0aj4ay$%KzJ%hSzX)@6*WODIm@wIl!Zh?3+;Y{JrziF`M(bZj0HVWCosM2G48)Vve z%NwG~73hUY&Jpn&Q`Ly)XwEe^8d4FzD5zv2NL=^N!STZfiU)hW;g|;NQ|qU^n?Y>J zJR!r6b)AjstH%)ZgMW3P1s*06#ibFuB(0g$o-mGtrG|^jKb8*V;`@a6b2(lcGO%@u zbbRDF_qTxkp?M_n4pOK8Q`oQ{k#$gxXjvo*o~yFBf^s8CM47TeQjzIvaYSL?dD%7c z#T=-4CSic+-9GpIxM-fvFaMVUq%!KwNhDK({Yq=#rclN#-UULg3MQ;Md!ZS?(Nk9> z%iBBJ{3Xp!$ue!Qs~Jj2YfT<>(6@f;s$be#TX z_(-8G=KG(}B2y}iAy4+N8?{UdHeU>o_p`wt(S2yeobOZL9AZ-1l7iWqTkfC(V%3(5 zh{u2-c#h7Yo1O*%DDN=d2A6>u>c$F}Z-A7_6TR99{U5%@!RW?$sDqi^`tf!?A9@qK zuIJbSh4rY(JOH{lO{GgdtFy#*7RkLH%m;jMQ>?7!s@pV{QoIax;`?HlvV)OXbWu1$ zAfE`YSlaW6Uv`A~iZqX|nbjBBd9-B2n;JDSFDtl9gtTd{g-+JHQ9C*iTq;10P0fLb8fVLJgJ>&_?=>Ap z3jPd<2lcg+jnP+lPJ9;n_Q`tsPxT+VzKehG3yj(2+*Il69p)|zWI=WfRK2F%S&rw^ zMX9r|&AQG@mGdtL;8~w?0E51V{Hz_57!;lApVviJV8s#0WS+ZHQ(l>HBH`xyqKIEi zcCt9xS~u>N+yc99zOwCt&Ne}wEIj6Qzj}kJNXHQ`LiiJD-7bhJM3j<#=^z9<_`V9du)I)dg8b8E8oMd8M2$mG{0(w8eFy;1Dd<^iy0{p#veX3y z?1g$Ib+TcP6Ge%}92`VJ3G}71j!4xpTH1CYB?_WS-K9U3Z{>P5Lk~Ub z@0{XyW*qF{lFvy7$(cM_5yktH9RQ+4~-uMQSNRc!|k$r>_s`N<{H)32hvL zf}=~6OxF)DZD87-WU8%E^9O!;fCIx>KTY>d!KZBvSx=!pWi0+JSFc6WSVW@=*`;FA zeR!T=*wweiooPqRhpNUq?P`!-_$}iT`Ica1VKHcX8FcE6f>$aedFnKtR5HRJZzj{V9b|FiNiUf#!(7)T-gay1Yma0W_}9>%%<B->jWq>%&G$iO<iN*iyun3{WjrPUfE&yo?+VxX;h*cEuyPZ;pMf3BT+5XZI98JqrV5XxLOqd&VIeG9$3k^1INtF7iR%>o$ zHWplG{H1>kSw@slU0bIKqlNP0^Uy>Bga$6R8&cBWQw{$w_oK_wK?eg$o5Oq8#vY9I z?^Ch0{Gu_CXig=jivfTqTQT&FT}{u+jUlJO#(MJE`;7-_`t#WX9&hi_)#O0l)k1)x z$Si@1$Oiq@jWFv*!84)aLu~^_v}6CejgOm_YFKS>F`x70nP8#BxJS&G_8JrUo!FE!axee;unWhs$b7 z?~5ef_ECt~9zUd*Uwk&@p~Kba=o6j5(24Ka_mYY~kKW_jPfjHn!qr zWcB`Y=S;ClwVraHNG;?!G*K0=*cXY>{O7Y%h%DWEy|cR~2?dke8Nm2Z+uk*U|zwJq*_#aqq$rA}tRGOYP)!hBxpRa&RLWf&Ft`QfE- zg>&V+Xg`4BoDL1-fI4Vq7UgFMEQcZIs*-=M?!(`tJI1_UUX&~lRs!(>E%`Gg0>wyd zA>4A&AQ}xaabW~3eIw!r)Ey8hD3+ti`M^=pZ8xF#8r+`2(>$QS_4@AG#n1%bfx7pmrMCRx}13H{Q4mp%4KWa~5|QE?|Lu@JlR`}#)7c78B*vUhWaq+KJr z0X!x~3YY(c*;9nD@Ni4=%`;N)WQx68ckz)Z5r`>Pa3`hxw3kWl$2M2a<#2_=Tv@T` zri~k;b!eX+x&~~gO3s>^3>;#i-RVW_66}e{p6%)=5$$ZFE`GASz2qYw={2SdB3lDQ zu%A4$K)IibGPPgWP#uuSaVy8e4rL44>(NYIU;lfY>dhd2)6CcPM`EX51t>Ch=D%tK zPL$DI{h8WMSBi@2wC%LKcX<7bqG31;2+*@bo#+&;{W?=r!>KJj#ng#(i$*znjuc4y<2jton@qXNBd~X%WtUS5i zs5B9_cDxNaW>+gM;0uU?zb=T@)X|>OL_t@SK&y_AD!{IfHsg!Q;hU%}h(w%6@q=)?bZ`C5Pfx(L;w8+Vh6*k?vpC0f=11!iid$ zH`(JNh*8du3n`E345%B&yZG+3(>`@8DGF5a&ScTd5A&$W#NtO~pulgX9u;o~(>eSZ z(%v+6p)uxVttez>Zmcw)BdpwsuHJR=1uI!yiVsdA*$&<|HMrTPTjA?`gH-y1GY|C{ zac_|8ii(0{Tg=pw?_6t@RIjuL4q|WVw`MIT?nKB9;$Ud!Y_t~spBFh$ z^lsCp@_p;ZMfs!I?Ev$#!fH(G;Iv=)DdaX?pt)4sybTq4pX8tgGFdp zVN1ht#s%8Y39Lvxg<^nFhO$Ht`asHBYx6nhqak{#rzouw5sKTcWG?W-&s_3 zt(lVG2T!d_o@{ky(7Ib_pISJaR;2VQaRO)870sM4zgioD+nwttKwDAw)Br}KFU*O) z$AR)lF)mDwYzM8#WR`Y7m?8DqW=B!YP}S~u%!-{yr(7)Iy)OCZ4{NtEq-rlO4Hgk> z0|EW_+82#y*>5Ym;r}$=QCo3j+Cfzd0#ynjR1?5%Bdy3TyJQ28bQnbR3 zG}R>U+UZIRp1|HL!qe(G;sB>lPw#q#TD~zvsA05uKF6yIZ)VnM;OI_Yd_xNQ`^G?+ zwciJ*!vuGhejMS8ur^nQoj%0qWHPi5xYa>nBXjfd&>j!2~Z&hy8>ui8<{Te<@#TtyvP6 zz0M71E8qTCUZs`f$nwEInNjj{!%_Z!g_oSq+8_munBkLxrGW=&jS3s^OX6w7D%q&W z?4#>KMeE|e*0OA*4Al>8QU>=!;XYIb1MptY1>nl0!s{I}zNaU-0!RQ;Djf3U@m$L5alE_YyexzFrs*9)!v z(<}g~{M!@`95F;I&I7N{H<+IK(6eQX8;DnHbn8!gMZ;y8dS3!rF8oAWhnW&5iH$s8x1 z3%;@zkp@|EQ9Iiy`7UrFGJ5+IcZKkft>BZyK-FFYi^-4tOt?^l*MxE_N zvIO-i=o?#fgB}L1u7Ng6XHrDNv?(~DLiX*ODJ5Ib(SPpBkuWVNZt{CwX<+X<1J)+w z4!J_EA|Y-7W}$dlR8lVmqC2D$wA(lngOATNLwlVxL=Hk3Ri5uoyy0^l^D3%T>EqAj zu@S#%dhl{U|;Yf1l(Pmk7#oayBr!XrH`wl)4reLi(=<8d+r1I z(k4p|)HpE+Yaye%ub|6S5_&_#;&O`7XNvLNJ%E)=Gno7z;JmHS>Zmipd&QR%aG3j} zjki*v5?0z5k^G~UtFvmu_&r3~hF1pB(`P=I);XSP>7aEXq;>FiYlg2Ma^jBjK_ZGZ z2(jB_u=UwtZHl#_0tP+7yuYM20DRgIXOr!A8$CX_-jL6gJ}*j#K|gpHvafN@{o9-z zZOT)Hokh;KF(!EHacz|KDZ|IVvOBQETj$&%T`=QE54bRp16XeIj{J)r_Nw9-<13q^ zFF-G~-Md=0RGO5dVgSmF(gg)=Ub5l1^^k}7iiP^hHG5J z8A26N2ZVNgo37wpnq#+`p$wBXA_i^fIdV6XFpUQn=wA3ZXwwS?qZPqp>&fb9J@F83 zAd0w%PLMgx9bHQBstcK0D$e{1-Yr4+$Zi8|rM%jnnYym*vj0akUITXGg3`o0t^823dvYzXvzDZy`nr z{y=RHs5$<94qigAJO;j~v^vP&ps)yFUy64roP8U3!UAFgu6i{MgFV?u@3Lst&f8 zB!lUlgbc1$Q z>0?g5%l$-qZBz14eszxc4d4_;0Ulqv|40sBTV!GEG}JP3E^GJ?Zy#n*Rer2wabcrI02Hbd{ zpy;;v8;=lg>Ob>f7cw5vwV*0=e);e|dYe0ytUXuEXPVF(595>G&$()WiXu6JyPNBY z1`HWxRA_}k{K5j8H!%Str3MP>LYwkh(2{ajjtgKUoj+!n)Z;^ha@;9T{}4Wc2-XBc zU)TY6M{p_UB6&vF)|Sa4wZtto16K`#0^|wjUFng|(b@VW{yW63vaWcI?~qB){#l)| zH&rah*H2$Xkv*;tf!AQ-BdS5eXJs&n0Ia(4;m&Et=x6mwOab%rOlgGeYZt%4(>)*e z&ihu7iTj^H!3yhzyEKThi(*GLa_`0b{^IDmB6Pm^Mgdd8WY-0=QvZG~3piV7=j|4- zcg|j64~VTk*?U|~yVp;_wG6+ixifq2o#`PU5N|Q5CFhy`UXDl;RY@Kk6T|;Ba3nMN4JPJmSb z%_au)I&hoL&VWE#DsXy4ujvHw3c=|ai&tkrYoY1fxW&G%ld!Ve^<={hggn&`4hv-% zGm31^RqLe5%5XN5oD3exwR2{^puPLBAd+)(OL2(exIs)kOt+00q6sq4y5BEi?a{ni zMKdWQbzFE;r#dG&IrxPSNJs24ByXkX?D}-xC^vYChi88_YCU$DqfIkw^6Bgri}f@hhH7zI`A%CRy10 zOV~Sibaz>$-j}o9WZOaIg4+^dMTLm_8`H=49}50$sL43z*Td@0KmIQ#rTCU~b- zN_sr}Mt#xI`)$ulZH*P;&G_3sv*hh%9`|D(v3I9t1jUt-*?Vjbu9gCIC?bIdwJ$Q4lG%$({4T)+Z zcbD)Z;M!NS?KwSBSM^R3gj~`>woF|%rmhNx@FFEytz7%N8cs7ZGpH&G+Zt{-(_~wR z{6oVpGBmX398SQiNjqB!^4|T>Q{bqFpqaSvn~97#u;{!+ZcQ zUAqrng9=KV?fEiUg4zum#RN})mv61lIz!j?Jglx2|8>$Rbb&lVh!T@ds~G=5h_q5C z=!qxS7Wq+n0SbLFE6e|cN-&tIIXK#89V1)&_e!^W%FU0(dEZAh@5L8vm1h`0R>^_S zG~5Wh=@vVO&i_kj@mMpzIv1Kf+-1D)1(=jC{mA>qdVfMeu$3=+>r@2$Am`S-m>YDK zv;ZyOy*Regr)z|dj@cvoB;abRD7$&$SLU%mT!3Avwpd8of8_Nb;^?U8J$YCub~}kDZb+0aIrVa z|8v2QQ%Dn{^EOohp5$S9>?-%QM@>3diFcN51a)aHMM;>O9&iUw;SHFt9XIoa@VO^&bik zTT{JUV_gXPrUFGa0)ti4b@3uU%+;6bqa+@?!u{ewsN`Wl=lElRl zW0J|m7&|}SzK8r9z`j$m9hc8F?WpcEE}|o^?y6yi;jESzjD~Zfs_iqK(NQO#mM=@K zf_gv6e7&pmLjH>vHYPtU(|;(_ET0tQiVNBr1FY?nEucqDL{$0Rfx?()#c7ziGvuF@ za(*FebsCu-L!TpRK^u8T5b08?(*NUHuG3PKy3&i{C=_!DV04kI0E-YJDB`=mdypL&0a5rrp6*$nDrnCHa) z5G-3~x2Z3EH-FOZQZbJR#F83k3+nNbUiXI$Yt4jAWQMdSf-ih1jak;m-lR#MdrD+n1i+d=!$=U@!6+|j&!duAb~Tt13_ zhiSiCOmGlsnU!n>gO%)=99YSSwB%5TzJq0rNE@tr;YP|*ME_r*Bho|{S2I6UKMOFG z_y|?M%FDg|55)jE7(PNn{2&rGeK@cn;(onxTHG?nRkznN#k3q113+aa!8_cV^ZvQP z)eZk-%T!-JN)xr2Qm(lTBK)O$DELnx=&Rg&rzw(2HW`v5-spQ zFS522ch&dTS%^Bl@WBbq)iAk4jb{_+BsbqNdf`P6?})_U1sa)=Dfto~rn_oe5_|XA zk|{sNHOTpb>31@vuxc~u*mykYzCqvcwY6K%;^xPznL11OO{6yvm>|hpa)uX7bU%UY zil@wZ%|6~m7a!W`pI`=ga&Z1**?~%B|GesQ#A1GVMzLVVL3@!i0_;1k1RCw0W`d`?+V}0bpNk%SP*)#TH%z$H z6PRR;>~`Ogjk5d^_Y;|P+~F%|VxWOVHW%9Q?&+6!egx*-#iEBrgUmYf?DZCU!j~2! zX`(|*vy{(1ybPeLs}r~LgJ>Fu-SB}MLbRLE+wm0M;F&So71s$l3=?;L?ZNX^?Yijw znXVq%e)`7hn=(qJLf3h3=S8qQH~664roQPsvPd2wlByjn6*u@IMMWAZ#mT1 zvgdteKa`ThyEMe~aIB`3zd$YXwxRxrKEUPKMyGNq;;+8(Up6#>0`Wz*kHG>ZM@?WS zSo&MN|C0Y1#Zx)#($^@|=*+?!sZwP~IZ?EwaU9oh7ZJ-dzTSkS7PxN=Er8_TGZXa& zYI15D_2aga*o&J*^)pv)D=8!)_JU8bE{C$p#Pm`SV^0mlLJ9d+K%d7{UG;Iwh~jzGLj3`jbKDM_;J6Er;Qk3AvU3CG zZpHyu`{EjkF~8zuN(_e;CQWMZq*PJ0VqHE-eE%{aj=yXLrjKT{oia;E#`zgB z^^78B@2xeM4_4i&-Lmsg^FmVD+J7W-_?Ohsk0+%n#e1>b@b|IOz&RB%u=G~oB~y6C zGqG1Yk~afYhD#k^$C-|8V zXrGvP5D|{ir-uG)VYPH~Rf#!KR5r!jVq$EpNk8G(PphsJ29E!Y>Ot7)9 zAs%;s0*=}=C*W+Eooe*td)m_3-N^~3z+IzjzvxM9*0x>suF{FRI7@I#xQ+a;$cq>| zGw?=t$^e}a*7H2^J(N6@plDaK{g`u3B0RR=RBNtghe2-k!F^~I7`i@?3y23aAX`NZ zr>}rVi7v_&%=ej2*Zg21Ln~f_-?kdJu|>`4i0!^yWE$pJox`Sz|76c z>=#iE9`-GP_a>6aulD@W&pqP3tT(##UG@`Q<){mWlGN^&cU@4fFxw47*E-a#r#qiU z+{2Y9n;D{?N{UVPx;D)f$er#e>pToaq(B~iLbm>$KyN||N?iYUBfWq|odUd3W>1ej zQy##BPCE!6MFKKrU8JFI#s1q_j#$T*Pv;0Xl4)yZkDfY*As$>%(1PkaA6WN)iRvl5 z5>R%l6JB7>ZLjV7w>cvKivy_Ug`+4l=f*z!-;g9ngrcpLsyhB;LbHCD_0tFGtM^(0 zc^@UWiV>*%oX*D8e-ew!FUq7KsAIr5_P6>k3k3cZ+6U6^Z1M6HmR=!?!}W&KAM(Vq zEEV0oTj?N`cCR`z&Ew{Y9I=n6!Ux^g7%lRiF}XMhY#fmkcO!<*8`q397d1pJnEww+ z=N(Ap`@eBQBAjGoA1izBeNgr$TO=~G_k2h)!odlVy=5hP@4fe)$BvV|`TU-~zd!L0 z=N$L*zOVOny)H|TtCKqe4{|C!JM?kb`UGYBOZepjlpRC?N!`N;O?xU5sEPIAdQ`t9 zQ*`gAyoUfOnrRdPkvhoz45l;NdFvJSxM2Oq)0%0A55|OHlw|zu?h+UijhSfsa(o+P zjt-ljKIp~Bv9(=3uB=ecJF`JrT}9;6bqOV@`#I4moC?aDMQ9^0Dc*D6p6pzso1|C# z&t7BLpRruq*L#&z@$=Q#xSQOQv^T5I&I=gnjest35?PIXHBC@wJLue=dMop=@e_GM z0v7i=V`GkKM+!O!-pf*}uk3H^`+bXU=N+W`z>u|;azUw-(^wU`u^g5_|3zDpy+fKI z5_N}Fnl_xP-rFdHxQ73crO$P*-^JpeQPzxvMWw(Cj!tDPRNIo!JclWpqh(Ek`-f>i z0^`mV+bzOlf$f1#nQ+osY|fa-doYK;c|&nAtlUGb++i%5gT-iq5p@Wrx5ZmAntZ${wcJ*Y zoXPQ4+`;Ne5At4ANtuZ!I}zbsu`)M+Yp(-OY;S|D&;tA_Rs_Q|b>yak-b;MH1`<%L zUC%`y*Q=4LDRhcqhUf9O zW)jDyF0ih*N~5UK(pW!~#a%a8O6A~d*63MLo(>_gZtHHt%~)n!oh$Kc+dkcAg70Y1C6xj$|K3+5AHEFKLp| z0_@@la$0(m7Vjjc`|mev#u2Fr_<-5HXZOEx;#%X@ERX91vc$ad_347*4u^!OTb6+d zQEdvv>XyXrl*@&>nr@y5%9jg-SIcZZTsf|$^OX7hY=P&foZ5hg&Cgp{C2%FPT9 z_cQ;2ocnj6E~V=1yYGy!PszRhcfkP5RtiYu(l*7@zSkCsW`>N&KLPexlScz>DIq%P z&9-{-U*z21mk{U%w?B^45GY8;r%QVy^<>6MQ`JQ-<8SMg?y|U9^-*5cf}1hr*KgmF z-%{cl=VJ%*!bci!|MVS{FxP)PjO4q+J0scP7gu9Yp&Jw@bt)3f`fQxOW5L}eI(ic= z2IkoV1_2rHmUmIL?+>(AcJI|lfL9ayT+?ORG& zmh<=co2?#LB$#pgiJl;Go-08hKEcXPleWeVW0ti~9J!6a8Kmh9zPB&B26n(QM1e-` zgL|f#xgb23LZ>p(d%HE}xd0Z?l`>=pv#T1brg)%L_L71Qpj3w#8+S4I;fbvpDA?vN z->@ne`U~bR@HxO4`$TXlUV2^5$14hj-y6Y1oh26)X!u|`QJ*JRGy=Xjw5NNoT%EB6 z8TEt_|DhFDrE6R=FkkCZ)bOP8pt&hakJu}(b{b8M*4a+}|2m%MirMI!|G&DCzYpX^ z=I$Ctzzyxq-3d+HVtT+J7;+_h;iaaAL)j1H6^A)P?lS|;^jS?(gTA@ z#<`e3D+*qQ1e}gGO z?H3G^?yS_^7T$5a7bFLY>v{2fKSSc@Kz!Gfvs0%%Kf9bz8rJe|o1(H}b2O?Gr? zI(=BrEK{-51v{2Oi|KyVAGkw*?e%os9e%m8Xl)GmmIZVqGk*e_k?Cgk$mK~z!%@zPx<)k_8&%kbr;0E3=c+x^5{rMo0EvlPo$ob)X^?0VqxyS0i8_BeSMUZ46s{H z&ke#qCbKcBT37C1qXiS(Zqw@>42Tmf#U9k-9*UfCUyyi+&$2HhUK=L6`BiAFQ)PDj z5r(GbH{xPk*;~n_Wf)zu7}C)f7z9MiF04I};oQ`MSDdVwPy13zl*D>O_Bt0ayyv4= zQ_Q-J%n@ieEQQ|RNe<@6t)gbRW|Qz-tr17>+32@olo)TPB(!(K4w^>NfU-=T5CMz* zjw}b|Dd>655$3FD3cu#@zaPgnEOgiHGQy-`Jy~L7qt6iMP7l?VRtQ0ELcZoyHK7@% zgE)AZ9YfJFO+5OU)*Cl@J8Hw0oUONC@qL_olXF3=cl2wMihjm>+vMEgR}LuMurc+4tHv;^tM zOxYemPew6B`8I|=c*r|Fw@E~9PrZYogutpy6ECregLmGy%D@ZKxP8qs%do8^jQE1q zbyLrdX0h8IDQG+n9h1`dR54rk6wp>-a`9sge3;MdQ*Ijjh-x6*(02p&)v^zv-pCU< z1|j{GW*W$si;xE??j7Lr8Q2+X8rDWZWfs5$CXQ=aK_56#A)HGOFLSEqblBF7WC%~s z;5%R3KKm??d6XaF$dlsF2$GeBL6CZgYE>1DG2GIA*+}&#;;&9u_gJ4@o;kOjVd&?(GM|M+Jmb-{qG1 zetVD_&t_!K;J&T+4=sWuL%8efJD0~9?0!wbKq6p2a&wut{)MGJaD>?!)@6J#iueFZ zwAmnwzAUZC`0A@!l)cMq|L(b{&zac2Bu-8G`iZ+a;O(>_?ZlB=Di-ru;L6x3y1}F3 z(h?6aYNc+jqJ83kl!ny>0c;&d>89< zm}Kq`um&CXF@2JTx@#)_CS#1wi7jTp<3rL$ovUsly&M&)?v9oX_KO6hseljVp=5U_P0rq&3%E~w{OMu)?YXFqf3+clN3PB%Nqmuj{a1ob;$w2#6FU;ece|50UOfOZd;*eKb5Xk%gLWmrKY_EmLP z(M1C#^wrgJ3}o*>1%g-o=$jZpB}d%qd=K~67Z@&2kaN~&nbX1~f2p+BVyYQk`dMjA zJ`V5Z0D^}+yD4v5B+~e%75{EM0uoFNB9G#Jf~D^q8r7ms)OL@k={N~n{K7V^({eI) zB2T}Fl)r8qXFPsaJEeN)fDYdbFWY$Rd;VADMdzV-h~V^~#aJlFQwEm|72CNRpSpr_ z>dW;(pER*G(|oQ}IRo&@=-HLMLJ)*oy%t#yfc?QuKrIU4DQ0U=0)pSh=_P6u8IN z{;@&*2fj4lmhtyF=tp$qV>Juih*KsMBlmYI9lo@RiPCz3`rnp|tcz z9y2wHL-BWqorn($x*3170AAKuzZLsM1c-lp*@2hg6!R>Y4E6TcCTd)Qs+8$8!4KPy zu<-+jjsL|m5)27jZ)trsX~vH0Bt%Pwq}0ULfTl(u%`B{)VzYDmlSu38Ki_MyL$5ZB z&1*nBl7nVCmAbTR1$*+d@EB)%@=1%%8l+5N;-}g%&3i~(KG5~q>)$WWcG(s8!$C4B z(+m3qdhdJMWN|E-`$jvyQ7pNI)?Qs&qw+Px0}dNX8A6pl1*#Kz*V&5cTImYhRO4{5dvs;<0)1){h8QSQImW&nb_dB7I=Cq{(U`BqOPzk zh!-EeRLt&3d_c-LO#TzxU;l?@ah`ko>V|tu?)!mZe@;r#jw0~&EI-jz)aq{cmqDZY zlin+hE!~6EmjgRF&i2+ARJi^*6|edbxA|!ofFUH$bY~{NwyLfnAaP7ZJUG6B&f-Sr zH-V0bk+2)QBh`UGO25-naNOA2_-(^zQZ5(}7?nHu5ABRY_eui0TqT2Vh0-4wHIx~> zKTSzu;mZ5zZ~zzg`w^sE74<|!WFuZYc_aCyl8Iszxv@(heM2eGF1+xjpL6KwE@R%}FMI#taEVNie``AIad{>l*;tQbwtc z(mV+idL@5= zOM^s=dkdX95dY$ZP_F^hUaTo7r|Vbj{NbNeVVgk%l{Kzr^3 z7HE%!t)mLpd}>MiBqJ>DiVQ@NOYP$xhVB8{>~$w^T<9SirW?&)7WOHN!6n+9ge%Jj zTF){e=oe(kO@vhcKdWc?%Df#7@zEb@wzWYjwfe3BvO-DaY4&8b9u0X9nTP{`O|ua$ za>w4gbNr>5mu(i6c{ca6wGYtqU#Q7*ZEbF?N6hEFhjEO%_%ZoeRvNVls|mQk_20FQ z6sl}U5}+qdImE!~7U6rQY)YJsj0j~2l?OFT-So@pwAM(jGwx?5i%*~C8E>1@Ttp`r zKy}~)KOmjxv|ufTKC*QY{0z0r3(oYd9gubHr6&2kSIf6mHi zABjj7ujJzhs8N0QmR&Oc7W1T>@fa4i`nqM{(M){&dnb(xHI=c2)bbpjCn#35vjVDe zWyduZ0qRdaD6y%;%jd>J2-&TdpvlKmkdPS@L7rC!@Gf_AiS8Nw@-{QB+j5@=H{~B4 z9=uDR_~V!MxsJ=d$iD_#Bl%DBm)c?8xPW}7T8dw;y~!)D4(+@4vo@(a%aZ?0gO)JEmL@GKh6UoJ-I zp`yn5&w{_C`5KjyiDrbmo;%x94x_ixjn`I%qhOL6&2x~WV4NN{OR{Cyv!JWNJFW0C z28$ldPeu5Xc$BQD6gF=llBWa0Gia|A>lEJxvP1=43LkkZyYAxxh2-N~YU_h#> zw0DiQu{pp-7>`JXiWBQs^027<8|z5{tPm0MzoyFtio^Lv>DVZp+F#|6*t_b(1yf4J z-{6~-hyxlzHKXN%(fFf0L~Ss4 zjXEdiT4j7b_Yv-r@kh6oWxp*@aM$dayPwtu2bpZKbe?B)-M)ALdr1BG)>lrP(-)I< z;NiO;s@P24sRQATu#4O_Xuq9WmE<4G=*axQrua^VS|*32Id1s9Q1jlrjk{zj@kDzW$F3dmh(X7uBs45-eqAo7Kd;f} za;8Nbo4hH`dy5Dm)7m%CmtXbTQ!_aegc>ASeE1xuXTcO9PS{}3cF`{=w#zq! zUVRM3BXv=L9ktJ;Knz8Og%BsrJOQ%#p>*=3++<8bIMc+o25gu;7FQwT+$N&Mu4`xX zC>QMEHw`&D)mpW8Dc~J^?LUPEY4Ck$9Vu8)I>(ua(hJ{rIE$8=9$d7&80RJ9q+%;L zBXM`ch|)H{hZ%iDfVA>N%V-79kARpy|F4p+vqIqFxgXdVE0=8y0gb(@a^HCGzSv7S zQQPo@)cCyYwTx~pB*teRe|`m5rbv&FU@Q5cwXM*53^|QFdBm6dzL^WTA@_;(gu{^$ zcK9skI%RPDPB7m)Q=KIPKqOAmilLt9s|TGMTQ`Mvf&IgJ&Y{_cJ|m~k%j|7_K&b_;vQx-Szf z_y5j3Iz3(9Ib4&>KR#5@&osC4)eUdeaWX5=6wCGlbyj!TWs$upRGigPlf36|kmvLb zMTgn-wedLmu8MgEV6o*fwY4fj1(@3T9ZS`-$^hLk?Md(InRMK-2gTMGFzZRnk3gVw zYahjE-4&vUmqsqF$_{8UgrAc1#8iELhpfnRQ&&u*S`nQsU@V>JK8PznAGTid4$-gg z4^aP;K1io^jXT_qEkIaZwEOj?sRH^Dm8iBoz*|eCLtY@ z{8Na~L&aNaWuAe!Pfz}+@^NM-&&8|b_aS{vh=BC9CDT4LyL zo!K4B?cV_s4uL#twPPYx)$q&)x5X_@$RD{emcfb{R;O3jx}5rIaNUadnROWjD7%-= zTqJVq>e~)IwV*Z4~hPbH>!TyY}Z=o@z9Ni1?*2SmfkmuO{z~Kqd!#F)aaTgSVrN&OBrohPf9h2 zzYL%}yGSdQK*%p>a~P{W>ZxbF7MO37^oq_HB{?M52W=2gLj4tpGtQ`qeatY`1 z0xkcct%KF9kSBIVLYcMiZ+LrX1hrqmU%hQnaK*wxQUfM|?(x6U6bRc1+KsxALm_#i2+8n0N&0-VasdxiK|{dG#! z4M5@ZKQuS6B-SEyhbai61AgL!n_w?5N;gzQ3L5GXF#f(fAtloSr&v|}l0(TLqtn)~ znY_P_Mt{A~2r(^=cW(3p6(yBm(T{bOVzW?Z*|f0mDW3%qVxP|h-!r3?cybCsVVT3%D-5{wBgU^y4GPLSQSHWI{8q{XuXz0TE;1w8BSD`;+XX^g z9*825+gH&xIhUk5t+xj+?f|=}RYJ$qz>SXo7vVw5vEtv6HIXvt1`bD!Ohb{yHAqV? zrgx&Y*G^^c1n&|c4P)4Sg(AZLRYCQ3Vce1;RpClzFx;spcFM=YIt8XmaL(u(aBy|P zv4dc~Vqj`6qhwbxI~O`C0O>?`KYQH9Z8JS2;N)LB8n)W50r$OcKrJZj6=4TgC!?+W z>h3+30ut?~A7h(9N-2@lCYt9js;pCckM{TFx@Id1Zo`dlBJI7mAKI~^NPnS!#1zk9 z7WW=?Qa*DNFk4}2QhC#R(Y=484*u4Jxo@ESm(e~=9%ahj=_1YXAaTy{)EjP)7IUbK z+yx_|dRoB4H|umPtlWt7?F}D(j*~tOFION$@nrg6uQ7atgF zPM;iEq&^A=2L+2$>%B99=(YO^;ZNj>+!Va$Z1`#vKg$QuFn$qFgJU!|dz6QOkU#=T z#Pvyj@X7Rd4o4KRkI?`A52vp{+Kvfcei{$-FsOATH{Vw{lq+y{{RcUpYtdH570x1X z&u+ansxdT6l)DPWwqUqp5p@BJ1MZwv)Tnc`FwXEVW) zAFdfodi4&`okFXK(1qSEY>{JikR;6o+3c$?ZXNmZOfl?ySUjvU?$4uVVhrN?mf@P47xYcOPK1AmwsNP+d{2l;2EfB2=jCu$d2>NR#%*`MK$$+Gr-B1mX2k62 zN)J%jm2)@7*`LdzQ_fL6C2OIvE1Qq^GiV39MdM-0;0>=uG)cQpQnnkuZQpc~BvC7H z|MjoNH`D3V&oGF46>Y!dQ2JufLxL5uW2V6>!^0()q20Gas9&Np!^ExEZm+WT%7zQu zLM~3?#5&BxUM%$rT#FUxOabJ^&_ug*6+~UUMo}s7eD6QB`Gxx_Xxr#Ev*_BXAvMmh z(nMoaFUFL1(GE0}wZ~0avByRFi6p*9Al5WiO!b8l*|jhO^_BTVz1FFJM`{_EV(6K3 zrw!SaLz|w4`w(C+n@of;UrCo7(p-C}(J!1op?UA$DY~%SyQ43PQgvmEF(z_4&*f-o zx_x8p(?=ZU=?zVL@$@+tm^k#fHH?;asiXU`s zHnmG2qK^?%E}mWz0v8C0N)B{Agl#1h@U;-5*0m z_2-n#=g!Lloyh)7>;&9`hpagm3@LDXsa83Qo3*c|z%euPC)p~7cOQl2U3CMrM@-)eQYi6;OxLv1?T#5?z?iR79=jY4f=yjM#yUCzpU-%WpSL1vl@j z){jQuXp|hBSLbTI=cO;%)6ec&kAgL1ee#wf+1b7IKRRbakb znY^7|<{uExyqS95*uW=>7sVql7OCF()pqHqLlR416FE~Wp^_~X4HRZ@QXc${w~%x> zG;r!x8u#1hHf0^0q~7NZ`NSqCO3a&8njqEF=!A8ZaWK^I0lCctt8=?!zHL=T@~7j| z_DLbLvNyizj9r>D@FHOeEX)!JlY$U`c|mp;3oj-odMGRN{rj7H1>Zj+*a>(0F;*o9 ztgNdDHHVxlg{>4%-~jiLqi8oT&5PDjt~GQ)M^2(Q^$h)!C<7X|tyma8XsNeq6ymq} z7u*M{Mr<71Xn5lq>oZd^_TE}bJ(`LcXPnvPokQHS&0qOGXYz}dKF}Tf2&W2A%9XNo z@TQqP03QtlWqWgdif6n0*ZOi*h`lTQ?{Y{r<(Uz2<2S%3k!;Oy<@h;jey|&{g=?0n z&;AmM0(ZJB{F`2q_87A#g}L!7ybXqN*u}q~BTbHPjWz3*w^vO>&iLZlGGFHQGp27& zKr2rrzc~2G*WTWQwo)gmtqv5nMxG^al3rAjGk-gX!lZSS6cs7wu!zDtHEtoOeL?fG zYGBJ^nGU#U6S;ShzJ4x{eME9s!2ebT8psE7Yj>rnWM%^7!FDoNp4Oq1!$CZcZYCL& z8m4G}Y7-1nW%F~uAsBaB_N=3m)N6fAyqSLGO2>>$7^74~zJC8^@?qut{jL9M---d$;tqC^P zRh=-WJmFd+eQ`Nq^33HJYSsasma~ZH)=&|uZ3G3wh{_Y1vape@xy-NUz`or-aklZ!F|fl|&E3dXMt$;|A+(dLhuQkU7yIVo!T4fqIr zq7{2^#~RooJA=lR)65_SXPp!PP#Q_|(~3p|jUtgJYEH^64aZo277Rxv9JmSM60who zOKjDRQujuXhw3P)>U!)DkLznvyhsp_(mFKr%?wiQBb5BI22L%1qOr@G;>NYZ;=A!J zDoWoC(iyg%Kc!Ho*a|NFUv#o93o7z0nY0!zJqDD2@La@6+-e~Dr#ZIvetR#Tn42zs zk;LA%$Mj~Fk47-p(F4&+iLa%_6T5YiOvg*x`S$giJZNk{lhnom>M-ej?^NpKlTEmh z7sS$cvqfZ#L8oRbPbz{E&}94EN?5gp-CtSn3TqC94$USLu+Dd8DC<)c5H%sXpLy3P zRv8{rEQoHR^_9o-_VvW*R z_?z721*Be#mHvk|y%$IHuwr(-UEXePi+(@+jTdskfN`VS%9F9y&EmF_7KQ2opP3fK zM=h;+bRST*jbWE5-(!q7ND9){H|w;9h}en1q?o0CBH<~~T;xTm>*8Sp^#P>{X+-2F z@fd}DEbms}XsUU5&%vBGR*sf36m#u7lV@~nLV%bXQ?s6U>EQ@(D*cQ%=l7LQ;QQA4 z3Jw>xzh*zr?;)U-*Yi^J&b~*0{qMnY;K1&EcPwanYVd}QH0N$L;04&`q-R$WF;L-Z z?o1M64Pz6C2>3-wwrTQr`D&cb{#huo^vT8LzZ;pJ&1Nq zISMj|*=`Q+Y=6vM!V*L^iUj5L82eCibl$!C&@`UUXN4I~me7P35X>0+UNKeQm=tbW ztTKl$h{#4Bz>mWI(G!MdmYs!9{b+6Z4QnXk%q0z<8vJ4KP-k^&1RZhrQkD7ELYnrW!J~? z^+l3ddbE$Q=i>TB>Ec@})Xr4xRDB2DrEB%RaqLMevD(f(S6~KL+yacowkI{>;#lDH zIhwJdcD=nau#A2CaTvVwmE{$f*e0DAEpg3TNZjz8le}?J-u_7_dFC4U7pab=;6c1p z#v2b%SP(-y_1p}S{4K7!-+Py9s+i%g5Pxj?y2X9>G~~vr%7Ew&n&4t8Rfni;W&qGA z@gTGZ zpUmXlm|VJESKD^Q96Yh8KmmSwyv9(P+>H=4#*kTo4)Pebs)p@2M@58I4WW8lcZZV(r-HG*Myh|^yGQiDe+4s93=)_k8;`%dd9pNtHm*h2*TY;@2hFwY!`5sY!Coy!mJAD|&E^3tBS%@F(!u0s2&+KwSe` z&-9dZ;4=wdc)>e1V_kh+y=aP$rBvA_=p(#n=17_-HI(P4$e3t)or>o-TWQ1Bl!En@ zXolqB4Lw_qh6QvZ_e5rYYJ~q1zN6B_Z6Onr`-9kvDM()zngH}iM5nePTk-k0SB z)9+8t{pK35(s~~x>=$u>otGfT`goL3Ve1O61wEUGZ@b;wfy(kwc_}s`eJXk(xh_i6 zPEnESL7;AgBHMEySO;TrN!$0)l>HGOzF%lmtLN;fS)aa7)_d!SeOmGd4iN7quKHA^7H z60vKWD7tGa9{|}hnF75VSt2?TtLGyefP^m21A{aSxvCL&zZuJY@;IRQ z`&fi#F85pjfY%pGtluDKQW$)wFy-I-u?+i}P&`IB$`6Z8S=2`nUB~Iqh*+S}vjyLe zM`nqA&Dzl1HLC8!ph^8pUh{1T_L|nwgbf{A4Y$cp4mMzf&9RL^87K4 zeS_gQy$?sZCPu0!q}INsSBdiX>zznXXBXAo zw)8JaLDL+$WStf>jT&fn4{B2>mgS!jJ71Zv8e^LOL`!|it4Z{;FGO*kZuhjuMx8^I zZ4oTX2A4GA2$j$W6kya}d;B=<eD@9lEmcY4=fvRF?1Cy5p{wGBNV`ut#!y_=_Q zoQxM;mnBO^^-O_wy4ZnPr~VoM8|y7;iiw^9%4gi@`{Sktk|phd^EiwZP=QE4#L`7s z=Z*xr?5hO%4Sur&0n;vE?*J51tq*HTS>W-F?uxs{J)4LpnkCK_#`vo> z078jyL40k9P`1kwqrrn!b%_MNMZvOy8%g(U8u>uY8t*mkz9+Is0LTm;i?m}&(pEhw ze`YU5KUqy)Vl`z+sjd~L>&3e3iskluKk4$-Rx5Ea|q^D zs0XFS!EHTkBGZHwu(+JPlk;dqn$F+oe_mKtv+yFB!jEA17-HI;WjAhbWa*`Ow9Kf1 zs&#pj9I9xzH2s`lz~!&{YWiHE7vbW0uIPDz8#@tAh9B|7Qos=#pZDgZR}_dTenB0@ zO|nb)$5USM(|rxy_eGdD;MtU|xFAX)tX&p{Ns~F-=+t%yTK1OlQCI{`!GX0O^fZV@k?0Z zGC9z&27ssvltwf9k)#IsS5>eHhR0y353ERJxYmm@C7NZ@NYd~ay`0y-PB~vv+Qni{ zqT8Rl(S+Ifq=Mz%TNrM}J(A?$q*z6N<;8C?+$whgHnCK%IxrM#N4M19jGOx@QMvj{ zR-pML=@SG7;ch#gFTavc2@qDV=UG@(?8~tMm_tshX>?*aY0<2s2Ac#|B^H<}tzyiZ*T@55$Y0M2+$f251SaNS-fv#^s*XVdSxq<;%~GA9q2416 zi+8UIGj6k8uLj$sZ zTE_6}hscBA;@$Dv?%J;c!xSBq?7^&cp`H!&*4TgAviQX!Z>bGTeR1CwNX(LhPk(8R z`Lk=Y3wl}a2JsY6| zOFgWP2`bzM_l3c6z+(VDkudOP{?7@fsbSD1Gs(6o!(>^xgo4-0gr>@#E$8E+56m{B zl47%>j3-0aiTbX7mCx-bo1W<231yxuy#?YPsvLFeNk-UU*!GoiUpYgjH?{8V&H#dH zeTJdBnkYX~i@V~<1{&h=Bmnl%;7K?2an1b7rm;1kuoCk6E3`Ik51)d+E$% z_I$Vj2jpnykF>=c`js|j?@^@Zs?HlX0*M%7;*K0>Kr4nykZAv~;I}xiANVO2HO`%y zTRMNGuqiaIM|?69@I;TnC8O=89%k{c7e?<^;g?wwB)6jNVJX!O>k6~(#r?S`J{t_c6xuTk~t z_dSOt9#8$MnBCQ(G03{RO8xbtnM%?7l{6mELg(<{5eNky*}JiDQt{kMfSllGKi(Sd zjjP6Y#OL6bWra~kOGv4U-WA6ry=^!O%=l37*68J6_|b31AM)sXlY53lcZyS%@9C;) zqdf8J!5+H$Fa|%GZx}R9IyEdP7~2VJlT*1$e69V9Di`i^%$bijsB-6dgia&vIgKsG z39(6FfBGD7@(LFf|5}cEZliE?gPL?6>>V_AnZm(<_UT8yu*Ko(LM)|DSUXF&O~jc0 zRH>gDUay(0Hg1f5?rm9RJ+l42(cnZLBIvrho`)226nw$}JsVa5hcyj!I|qxB`{;<1 zvM*?7E|YicQ+G}0S-9FRo+9CaR0f%kHXeL<@4HQ&J_u%E2cNM#oN)^`f_;kY1-u2W zFbd7M3*rNXs(_*I{^B{(XlhbRU^(y)@QExhZor^f(MeIb`v_eJ4O^O37^=+id2_z& z>OZvCkPkF@m=^9(jw}UT$s12Z{eTbqyOSfLoAUDlBC(2z9iV_mRL{O^6j$9i%}INB9p?0SP#+m0fcl`IeEbg>!28t17l4ojooYT62-v zNbEn_F-c1p7@(YfuFYT`d3mU#VBzDuT34N7cFDl0zjl=0=mOp=AYL6{o27#gU7Buq= zsQ~Y3ek=Zyfb-7#==}yGuyg)7Wh_x5%uERb7pB&~!9kE1HSCK{we2xlHa# z=*UDZq6%7fP0dnW<|f0DD+%*<-;}04v>IV+2iOjHIi6*rp_gJhdMhuPcqcBx6FK_4 zM_j=441KfNki{6f3AD5EdEmVN054vbB8d0CFhXg}gs>t|L##jnQrckXm~*`9=g+g5W8P>wsTmUT?i5s`{{|?0WjG25 zyH14P{Zum!>AdN>IyqZR*U*b9Kg}2a=1O7WNkX@0oVbEJv;2Ez??q!DC}}H0!Y+s5 zLfgdu!!Id;+LniC8Xvc~@vpDs_|8FahmPh-yk$9`^U*J`b+V9KOOxd7ns-{{Jh_M% zpUZP_Z|hb%Af-eX23vx|Mg_?G-S**{Pyb|eO;8ul=6Rp3yqvKHxw@kn7sgH}-PVI1 zF3w7cK8!oX^#a(SUYhQpp%%1ZKWHI+6dm{<8u9j; z-f0o>O zHDMGo+-??#kag6z(gs7&Ths20y~}oIia%!luA|=s{;~8(lt;)dvHjl?r-|Ag1-{=@ADSUt$VHGpZi8+*09`hX>bKV3`s0My& zb|^qJ2FfpefzcgBKdQ?-w-C6mBRa-u=9CM$kvEhjSF4*v zlqpUz3i>_7H16mExI!#-kLbC2Uur#&06Vn)Js>(2@@>k38C}&O_;2GKn0#6nkE$TQ zE|MnSInTTHrFw8jVINKMpbhxCT}>Jui9lluo|(8Pz8`g(2%;7LZV|b4=V50oZRiPK zR?R)0+XRdbBuZ}eV37x14`d)xuf*>^w7-aqJ>_nBqja%VXSniv@E+`qRfh{`jOh*r zQ0ms9br-x9k$e(SalH}Zsbhj_EAX&e{@UJfFhY4?jD70}7IS@uLOg`tS=QCatYTI? zya`F>Dq!@X*~qV|6Y?5+OYm#px5chZ*)}xnX&rg>V}?4#BS708>>XQB22G&$5ehj% zu-GgnW^HD5zBRt!kUr7OM^eDC*^a6C2EMVuq=!nH5c_rflP82&w9md{;>Bn@uJ5mY zx|nx=zjShX=Sm8`3RXo+7yacWoEkTBON7uHTl(@-!3@~fGfGdkh0h$o-gj=WGKI>q z2lP+Joo6F2REqWy{<7o9j|$XXITZ$N&?1rymt#(SDf#aPp4?n8X#n467si?g<=IY{ zS55^NwsPZDqc2Kssuz@~JC$EoC@>Em_*xeWK zD@ML&{qzau2j1n+TdRe{qPuel-n%xXd~w(IH7H@N+aWFpRswwkp$wV}GI^b^90 z1ofEHyhO^Kl->CUt=&kb{-s#NV(rJ*uDlB9X=yBH`7EYDK9rHBH@{r?&VgO;eGT&& zQyvpRuF8#29swe4!XF^)bRauCi3fB{;IuoZ1*s0*Oaq#5i-PfLo9Z-=7bc1Yr;q!V z+cd+*Zgy6hNmrFBYPKoGEg2f*(I0d-aJz)DF)7Z=aqN+Xld`JU4WF@MttrE-^1}<$ z%3{85J^h5mq%Xo$h#Z01i9^{Ep9p8!%U$hPJJ@E=vMXY-M` z;{IyKt}BNgn}*(hEy`davSwW-0=%Y`%5^O@eXFhQ7Csu4eol-(M6cJ|*KMRwoq!~y zi^%iHG1DYip++2}P@wZ=Vb>Yx`N_*>rw-?B+o7H8Rk!2ui;PpGM^JFFETEkc_tJ7{ z%rx^sAK8WnBFLx0fY_3Gf1pUT%h|X`DinTNX0R?NU(if{O%H!P_RfjeP;jM;6yVa1 z<6g$)!P%Rw-Fizb#`VKdCZ=Ov5ye1$cl_p#88Y7_XjSlO-%{$D5k5)s%K*AIIyLrz z>94tTG%;Ht#$u#1dZRWg;~6wTG#J(m&*Q@eHJRv4uWo5zF!*xusL&X?!n|*5VhfJj zUF2PX&={V!YeXS~WDql0Rlp}kap(`Qo*ZOhzDshH`~@p@!E??Iv0QZ_%|7CSF1#=c~DV4z;?M^1M=srO>&tP%aR?cL8+a9TPcMYC~HfIqJjC*_JAZMlz zSXcm!fFnOPbO+&Q0a79(z*cT(Yb;5p#TEmxSEhfQSaOqJnM!Q@D*{+O7~QlN(;%|D z6lT5nacxSC^tV7abnByamMM7=5(}O>;z9g>70cfEuUA}R z?s%{++*6COHBQuWC*tA8*JRTPLNs}KPDIVyK7Wygbko-pf$JI^mz%*Tp zoH(;ui8BuwaNe5WOMF?Q*Liu#(~Ux5p9&6ogHdLsY4_ENP9MCa5A7tMnTHccRb#-w zBI`2$@SL+9J%2_X!gWpqVDzEw?=3Z*2tBMRa`3Tr5GW-MZc!Yx^nxb%-iZl@RtyQn z$^-M#umt00^4QDJgqNhxe`dU*cOtP#?0mjL-y*7(`#VDxZEfZwm@jj;`Cg*p!rhRM zy)Wms0@B#>i%1TXG4-E*Y3m(ghfDfuc@h?omU&%5pTBT9ao^|!rnh=`v8>dNA$sp$ z^BDC&ZeM~&heAB>Y&FZhO}#SVf#dMTz3Y0Q{e>m~l9s_k=3M;xD*a?b+BYmVPWO#@ z{jRN<$Y`FDEjx8Vkl;&|BKP?p5rN(j4@dj#ddv~-z+nKJ;6bX3rj1|Dcvd?y`p+Z?*FqE$n0` zKauoV1B{B3<;DIlf)su0oPY4sDO}+|rmk>mjYSzPntnOvk$U@6v!9@(#)irFX{v{X z10uH#8)a<{{Z#PC{Olz`cq}p^!sCpuON*2 zG=Nro{x8sN&Kms~{{XP8-^fxPryJw>OKUdqV*!64&*Dk{01D(As0XEYnvR2W;_Kt9 zSxdL&r=Nubq9C1Zk7oc$?O@K3FJWL^Q$p*eXj zW%Uf;571VG9u&~w!Alt1AKxXvnV>zQN0Kif)rf5FZa>u9O(*+^O?wA#=&8LuYK%6R6zW5IHf;Y%<8z}0|lRRVdrW%jjzO~PI-9&%B z6uRL2tcU*q9s~N;?&3xQ56-eYPa8?$oAqEgk9S`}5A>wR9ns_1;2z?Taf)BzrZK_J zJ5-%aUgY+rY!By5-Odk8Q6qeV)YGtBkd54rr47Kyr5(L7NJj>c&sgwWrhf|BlgUlU zdGuqC(-ph(dJ5zI99$RC?ydTm=g)s$#1HT_*_H2tYK~cMH1z6eqY4SBHi7L(N{&dN zM0@`L$)^Uu;Qo~y*S2<}Gu%NJ{d90Yoo3JCy$;yn^$3{%0MjsA`3gg`dm%hY0lo0; z^h6x_WyjTiVf?Gealo%jy7A_Ys>-Q6;EWxqf%=-rv+ye3!yV7twnHk1MG=4Gg*=XP zNt;3Ptxg@eBvTGISEyV3J<^qdmTQ?$a9jcU3et5ZK^k9!L2#-UI+(3g>)pr>)E+Vi^-4B59?X8d_vV^1VE-!9n2eZn@`qfT{KD4EJdr~UNY&d`9f_u>$vN&~O z8AxR#f(U2&Q|6k$WDarCVL78I~|e>x0~J@0z*D=)awC-w(A++gxe#H!+_w zK0x60{c-u%YrApCC-SOH<&5YD|DX$fiiXat_3P6vK3*qMA~` zbOS$~M9x_8pUQwp%kh6bq1E&&i*-yojp%*HK9%GA; zg~U@IF+DlzKRT9eP1{2R@Mz~htr8C7y&&}Tq-aP6Y2A1<#604Za@2}LLV(0qYv3JJ zM|CEbF$78T#kl_f5b8e>&2gk;`_z{A658CwaSIieHV&sf#Wa7(ly0nhmN&Ij_R1s(DD3RxwF1l=Pd zDDKPv{b&L)8Tb6@+aItWjZmM&nk}#}$sl9-4AyMkKG5L@WRlEBXyQND6to?r z`W&B*bT+WmMf`thi+h9fU~sSh0N3kWi(@&i=foa4u+?0aNM+HFr($ z7LRpj4bi)}mN^hGD$1b#hLyV;DOr2RoT&%tP8kK4@~>Tk!JZzs0~S7E9o^Zp`r@=A z(=^Lg%r-XBk=boG_l2k(|#D<1u;uM6vn z%<&G37PqBIY(j~E-4l`bTl^{7+Y!&q{p6Dd;xT`Il{Yp~U5V~>8~d@D?=B_v4=F#^ ztA^(%niyk|(vuu?pmraearqjS(&B3y$nLG%WU)5oH3$TZ9=)hmB9PB((DhjL%`!Wv z%7?}zQPo?xtv@Ipro3;%TJ*XWq$J#a%O)08_VxOT^~k1Mh*ngSdN|6J=tWv*G~s4U zBYsD~el_IYC%XGrh_2gqRU6A3bjKL{^Ie>NJGHyKj?&J`ca~PzyRf|eW~;~W{?VMh z-Td-99mJ>$lls*JUAH{xh~13Sx+#MwX+%|jpXCIw=1W`i}#Br(* zMNleGJrh1^itCsp?{t&x|Rn!(aRAxBijk(-MQ<2jd{Oi)f zj`hI&MYtY)g{VJuT1FpI0RBdc0-KYt$^Iivov>->r`6=o@&dD_@!qj1J3h}By2pQ? z=1p@1Wtjd{;4zwIsH0ME6zh|#Zq#O9`sPA^ELL>4w|5!y?q-yq@5o#E)F5$=*rfoL z98ffc$Pf5aSZB9NU*a^UCjfP%GuZq+0f)nyd|&`Pg*`n+f30bVhjUf!!HU`_f#DP= z$FQj}&n$mB4t77vO!I^Fr))vmquhV1>-ic{AjU;8YCk)BQM`H@jL1*58Dcu9{3r_? z_l~9i0E%Wsz#F7N`seyrmE(YYE7HCoF+aM3+ zT6W$K(4lOL1!nb-vwt%}Mv|!$$6N0Tnj0&-t{}CVTp!?!pXFZN7L})49KmOA86DCk z6=))L>Fg?y%<+LtJM zW_jJbS6%_Lmf^x({i)Rm1fW6zJ$cW6N~b@>EnUG7!)+dV9i)-@n(DlJZ|3-3NiaWi zA~)-|`qz}4_0JSCpp=!_wKt3P$-xbN>JMa4zsOc>+MV^tWt#TlL7tB(HBj-II0Vuy zBpJg4>rcm8X+L=nwd9wJbZw5@fw(o&_}akP>+LSwEy9Nf-=VH%PC!1rX>~diy0~LF=dC??6v63FPrZRj zf*qV1YYaANdbc#BXM;$s%|8v_{{Uuqg4S=~X7b;R@Z5hqSFzxZtzHgBcsypkkHdH8 zQ}F$y;AO&Waz=kXW#In+DyW#%T}@!C*Cf&M4#JaTkM907><;Jh;;6)F1&;@httXe0 z>-f|&>biBH#P_zb5!y*qALm)K_}4*)Am1aA{{TGEoAm<}0#Bi`B0Y!|%y{cZH<~HC zTp4YCeE$Hm-lLb|Hkg?Z+g!-Qrc@|Dtz=((NS0_`D71gbz;IVGN=`xc0Dn4HMaDBu z=MHd1G&WC8MS5O=;XMaY(xARD$sm<-QKdg2?mk>}u7VE^Xm+FbdSnOPa?=NFX=sImneaFq>4PN1onW=wVkb4OVkH}VYv&c`F<%#acCV|j? zMuIXk-jTJ2js^`ocLBSOw18xB-=!*poOU!YKz?i*@BSZaN9NJzbKRiN>c7^w4pic% zx4M?j>MNLBq_HqyM;y?!6r;?Kc@d8M(Y7(%R$h;(Ca-jy=_P+&JJNCpWn!$SA%_GSN!U}3)sDZx zHU{g&DJe{(3S=bo2cWM}+3Lo)Z-?-0g6`vK49pNWu;=;LX^q32pT@O0rMV`^{i#4t zN{DSy(t#k(0L27Yn~uOzZeV&;W<%Q)o0~i~D7aXYdGrFjx5l?7yqUD72|r9z`NCM?m@_sR%QBU{{YoNtu?7dh7NlQLVi*@aZ1_g>rs+O`kDOHxwKMKR=_^(e-Mlbm( zKhly3XpdcCfy;kNZ+zyY3VWJB0`6&)T_7s}9dsdG-kKx>` zqt3ny?2+g7%|Ump-*`>`0I@8*wu*ltxJe@AiEdAPcl57J+IwU2uPE`z$BJhE0Iq5L zsWHM_&r+oRE!Sr_H|(l=BC7uYAz9OEceg8vuIG>*%^@{d@OtN^Gyp&z)Ee0#a!4Q6 zg!{w_MZu>i`LjU5xLQTy^P)lW(l1QX=p9dXx0lVfib0Q^17x33PCxH}J*$5=MVY10 z>>Ft$+sBeW-4%Zaf=BCBbD66#<8FTOKS53>XyJ49rUC)U{Y^MNdUX0wNO`h$O#U?+ zO*i*Ir!$;)Kcz*j$o^I23(iG*e75FTUNU%PAo1&7 zBlgjLifByi}II;f# zp%GcLd`gIa$G)8-k69!O`T%KN70D(^@e@torNMd|Ed%X2^l$#S73R!A71v&P;(c9( zjqRihV=Jo5w6^fM9D|+$>Mo;puX@gJG?GO4re~r9H)gw_;89Cu|MT6RT9zzF&^~vzbr^ur}#zKEHT5)&> zSCb6yZx^w0Nc@F*YLa=|%{Xp71}NnhwPytn!-l{!>Lc7Ff7dl8rD=EIts8!oaLpXD z{`bxSwvsp_^7J*{ZT0?DPgt;BPe{76In0reyk`ff>+gyzPqc07e|aU(i*?z^52(r) z{+WQE$O_Jy`tIbPKI&!gLhokKKkjM2E-@wU=E=|8PW(PhwXI)g|!AEiBq@ls&^ zGytW(P~F8C-HvEc)KU!epl5yX>r!DP`dp51e|r!l@#;U7dJe@Ln()0o`b|Glg7P*Y zqhQ<&@!#~#dt6cpf1*i7NMVthq|7Qt&gGoP>M27lLKQ*jic0C#T^nbKkCZ`hSNPbx`y;rg6+Pf^1)s8;39QN?sTge2uWRXg+ zBe9|CR9`E(;YS2fxP#KJYIZHA>UTD6$%)7Z)OM;&4nCEcf7R0A(>SFkJk)1B2h>ul z^XzHZEYn43>P1F(GQhE()j-$Z3*YIkSChQ)T?e;OKhh_CKHw5^e^nY_i?N~@0i zXRUV@`X-%ihKof_uo*F{{T{drFszB RJ5#Zf3D8l>h3#a2|JmsrtUCYz delta 56384 zcmXtePi#DYmQ$?BS&I zMS|w^F(OQVUMsf6@v-D>c!vF9sySJ@ip#N-7;TTXH51xIqp8d}-PN7YcM}o)QqQ5< z_4aot^Ur?dMG8`@RN4LM!y~AyxdB?Rj(Fxw;65rPcD6WhgFKMFTPqn{9})090QjJf zpeM=*i`GyNl6hEgl6bw&?JgX=z2^Zix>QF&%0AL>-$+<>Jcle|)JTVOj(xNt8ta)4NRV!E1p-{$Y1&xV;( zYRUf^f_#sbUL&TTwq`)_tj^6{bDc)7bzz%o8*ME~qNY=$$cv!yf$qfZilya#OBZx zCjy}LpGpT4E)aCK^T1Lef9-rtiab?*7}2JDIU`(sOs)*#lpo*+2fIyJH-9nQR;eRF z9{4?i82_})*tjrR9@Mr}ir#&C&kgcFa+KmHAOGFOYo_Bqs_?TaV1~&n=}d{v9`x;1 zo0Wj*yW-KL0{GD+a9JuK{Gzn|B~L4$L4S+YfZM%a10d_q2vP4*_7Q~T8s?P??w|E) z*ZJ`Af?2k_(Obl*Oqw#^i>&tgLp5h9UM{u&t-6={a}pyD^Qo9AmHuyr_K>%K9zj9- z$}%(jHs#7hAN5K8`8t=+0jq)o5473+qjRWVZ#@9Ywe*PPqKvqQf%|_NX!Ox84fNkm z`;iBLJio06K(@Z$5+rLx+D=W-$JTl&%zqY=Or790%4JzK{qEe3_&ySGo{K}7RJNmFr zPdUTZB;3nbKumRbwH&Nimw5EjWLrFHr+04EZ{Rqh6TbGW8z`AvGq}#92Obz}+j-lX zRIz`G7cFuqdHQmf{hHvUJ$+S4HEhL)hL~M=D9LM%-srq-fOp(ayhd10te?b$WPz)a zt}V$PtQLJK$8*4}KWrXBPd`6`1ic5y<2KCcY2tnB4g`HB9zkE{WtroO*((lW*&RmY z5?x~-LB-Ynz)}?MuD{{A{XY^WryT)Z3F>j_`pRmtrmQjwt3K=*RlRq8*vS2o5@aveqkas8!0jN?=(IlImU8#U3DKpHDo|AQ(X>*Ph2E%cdHY?S|IYP_YpK( z%4K=x&i6Uv?AP`ocCSQU>DfB}0O)e7FsZ-!BfsX+%8noI)QoNRy8O#~SsT%A_88N- zKe|ubFRWgs9GNMsr<>kr1VFB-A3@~P8mIaVA8sobaj(>*&xj_vPp(D+T2q5!Fb6(l zncq&&wLZ(szRha{Ox}Tk0o7KCRC?T3O+Ht1Ut5||*NE&#$)mJ1%`nj&iE~S zK6h`$DH{?sMLm4pBM5uu>W6jFjkJ7o;vP>^13J5A=J!kCtMXf(B~D03v9>v~IZ*4` z_rsVzafo$K963N_iuoH860C4U3|}IFo#LHu?&cz&@jZgHOJq+mluhni^Lg6J1M!Ano>^pSSwvpP=C1*T<#Wd zn&(b~Hg`$1FlRvtPMl%-;YG4Uqck*P0rbtNj(?*tY~N3I~3bzYBj(z@vQ7Sjn2yH@|>b2wQ&y zIr1Ru)S<7fRS}0$hLFEPKmvK002#NiQFgTGBk0hcm1UdeAAsftmfH%lJq(UczQ>-4 zZm;tp0xmROLur5YE!4|x`cvHS>|OCGE&uIxvS}EK{b~~7W?^%dJ77FfM+zG(Tw*`? zq<|!vzEND!nK;H8HsPDgyZ?7ud*`pWLl0h+>4WO!F2lc`uSh&y@6+a~sV3cURSh8E znkgDQMN=R>J3LB;DdpbHK%<=1bb4EAn5cg{05r<6I&KvhJi)jjmnpE}LPd;H)|G8> znS4TLw+!KswWU=-{hKtyaN2*c0!9{$Zf(&9GxPf|`|s0)<)nvqr<}A--T8Fkq;+4w zhjJZbGc)0x#W%pH~MmW8=ri1yF7S&87vz{t4wjbNJJQT42W zqOFYj+FmLdx%Wh}_mJ2GA~#ch$s%H_^^iy|*wi<9b5%?;>zv$<%(dcJ_>FP85MLFCu3ek{zbWUy*oDeClPOjHHj`MyKbyhvoG3-vJunO8FeC z+0*t+Y6@VB29NUue@9+*-{N0;b#)s3oJGZA`u$EfF-*6uBu+xvIpVn6g&LHr%& zz+7-gQR%q1kRNz?Wnkqf3p_RH&E!?8Xv-_dF9~x zA%h|TQ^Or2Y+q{@DNxf|?@lIfX>1fg6N|h1k(O!C$;ln2m2_<7_J18Cc%z$O8A=DV zQSpqq0}>NFW2;96A@;IoVx$WPGF#334;VRAx9#Kf_Y(l%SLm#2Nq!yDszsMnKXJ}x znVHc1-?}w&ySbfus(S`$zHyed1~9#cVD2cJyrJq?c7^<&*n9iQuAr_WohDIHz<}W= z*AW9J#gDPStRFX?e6ib{JYvaMzS991LYZj%G~)M^R_1kUiAVU7A?-aIo)LLCqRK^N zsRiNK8npXwlH7>qhwQ`2{nLG5<$`R_t*g(kJ_aJ12m$RL?4i}Ti0U(V3Qhqq-Tb}W zCUkVI+-i$gmbI^sgppbo|5iOTPQ^zS6=%X}v<0!>LEmenkNsvHPM#HuqDih(=Fp zbZ=tf{&Vd$gE*q+nw}X{#>LS-!QnB5QaAE(`DoO7t`mJ^ZiUSHZiQ*W-RT!ywBEK)!Bdr(mfQ z&CC#Fnf^|-R$_@(RJc9vSC{Fx{FvtlC;^uP|8?i{uwvbz5x?~j+fM-Nl_0iB#O6^g zGK-=M0AI#S8HYOXR}PIrphP4HOSmNTRNe7#B;?y#@OFs?0sh#N`jOY_{;Pcys{I{(jDGcEb-$ zy}@CjEMsUTkCl+Th4j&34)ogOX=*~O6D1!}>m=?{H#N|lH>>vVGV*hCWAoHkc?0-Y zU$>$Dral1c_-y4@;8`W-X~Ke@d%&kbBP`5L3a+X3^PGoy9HAZ8YWGS>m_UaL@K*{l zff{&xsQ9($;fT3M5YSJwt*oi9fUKBtdjz?1T5V`QuVh=AtauKz1_6QsN*{9TpaeSB zy|oKGF7eK$OYb_-$dL(RqLkT>Af2Mjod4ub$y=5hcXJhD&mJ?(d0x#&P#C=5=rHq7 zgF(NixVf=z$9fRlA zHe6w4bavNiY-b}9;F!&(j1N?kxe`o4!!nAT4m%&bJDZ|j!tnQ$xw>pTXw=86Wa8|3 zv;JXU?nV^cwdZpnHW9cU}5tJ3N0PDWvhPXjd6HV)nj&%EW4xq+bYJM#Fo#xc7 zgLf%B!=6F^?%8dv2vxpJpZ+I<>o6j9Jp)Bp=#-5Hasl_WlFWQmMfN(&a05#KE%w64 zb8Aw!TF^D!If?JH8zaNTcBS0b`iW>A)o>oiBLHfn0}?HTiO+6gcunfm`DikPG;(B1 z=EP;-O7#Y1-4B-f^Y7fWsly^yky#E~dOAf{i$GRs_{qUKTT#>YE35cD46cs3`nR#W~M3{Vh*^wnEkNA$i8uE z*2JcB4L&NVJR_QN=asqCkxyY8x2-Vw?t5iO8W7hxc-WQ07CM93(b}Hg?uS)gvd|D% z7BsKWHPYix!}-D1FAibJ+x#5%$rbMZ+7ghsQG?OKy61nl(*3ZT}rt9Crmvl@#04Ar#Y?dQ0_GDuBw|9XZR1OAL{rGjFnGW zQaeJ!h_N9qg*~B&1{Nd{PGTuI;?jb}#bQmS(~h|}L8y%jzN?mfB2`DnCyfmp%RmaO z#fLlR%j>52o~}J}U*w;c-SIh<3ic{B$%0~9{I_}?#Jm(_rb05y;slnYQ2(F=-qt;Q z1jXc6wIojMCdbo#aFg$o1|FW*a~(HKl#8>^RE!zgF8j}{*+W=9=a;XI)NADK(nG1DX~fzKsyL!t7serJCF_13 zJ&}tM)Uq%(?7rVsn#kMB%4S5eMLW}y>&YMoUjw@8F5A)0I+2#|cpErNi&d~HAn6`E zi~Yg$JB(9;E*FpQKzj!jWMgHYrX913a`PuziQbf(P;7X{X|6!n65`wY;aG3jfv~}1 zoA7f3u_||BDHvJL1kgr*W1LdHTeGW8iu{!-@9={4w3wyQ?OjHKHWa*Ta-_4=F7h4F zF68U^Fch0=&6#;T44WjhdLgq(GjpkhF|VJp20K znMs|=MAOa`Q7zT6N05JkKQV7QoDE{mI~~X5z`xe# zeIsV%ltEiAl`ozb2fRG&!1ojW`h4!JMvd`I1@IAx5Nz3!e_NR!ytn~R+(_DS7a@^- zz}9vR-11?e0jPG+-Ruag`;n(bfd0iOcH~_bQHYeM3(W zq-C##3Tzcw)??RL3%$Xozf})1c(sMjwI>(#N=#-HV?XsU!y<1? zu6*4qa^Xmg%^75d?)$VcS(v|h^S5)Q6gr%I2Y(&Qs_xBZER)f+dDuEZ;%N07ryz&Q9n?PKVBt>lC}_y}lw z;-=Ee=j&@(y^(eJ8dl`#2V(TWu|V_J^t20JA5T=TYD<>ckCG7+_xftwh=BIA(^R#^ z&wI=eON<-q`}9f5k~er#CTcx`LLmtbNQRRi`l0Z25(*%#Irw0mU}==ji#uqthCwoi zr>-&Xsvo_=(?|)fVLWzeDSGt7<&p#cVc+RjJ0o(0$;8vis(&-~GV1;wV7xGOaly{k zk{O^*o3sgpM+#TZ{#t$)^EH)BI(%wV$1?zTTW|ELZaF27rLWwa%6WAjMB<|;(`$PS zSt@`W;{mxvj8d4?fhvDlH5S+NZbHo<)0&EppksD}(-KE-$=L0oNooVv*vuWq$_Qch z`d7AP4jUX>%p2KPmqdYY!b|>$Mf}?IKi*99b&=~m>zn1~u_II{%aL|5x5C$XmlNCR zMLw&Xz0*!Sb@*xKYID)&B3_EQa1l*6O&@=DPhOCjRN0`+2`}8ZhK@ zt`j>y-`%5*ngFW&r2!6B*B!@4OoW_~j1=a9NOuRe0 z?K7h6#t;A4Hg#9Rgt?yAVvm<}J42#gks*#xi|M5XO;2M&NgqM5wSGi0N+!wuo)R|7 zT3)DYow+8)&sYE<%^LM2pv{xE+AoWu9C7u7JOh_Yic6}jfDa3k7i|#DDSgaJg`C&- zbt#U}dZ(ya1#ovMJH!VN@;p%L80G1D&-HVzOs9TauOsBLO`9U|I+4%q4FWxfjydpb zL!~X0=31Idw5DjWigWqT^1=W(L5+EIxQ63epb`q}YJTg2>QNWbNFH0rtDP#J1x(!g z;g;L!bJh?5rEN-ewCwEOH-wpP80J1$&)OJZ$O5|1b)UcGTxe9EOIF$uqfU zXF${EIciH{(nX+W7359yTgK30Zk=R1)wvb5$?P=+@oDJ2O6AS8K&y04fBIdNG@|oA zsOAu0H68q8#h}|N<#)^z(ZHtM@4AIX<-2@H8p+0htxoAHD)3Q;L~Xrin#;vQ$#(v(&+zhVbPr4Pa13cCjvD9y6p zqVxS!`^ohSAXplj2fM{fw=o@+_? z$P!aXVI4KyDrB^J4?ZNJiK$;&5Qw)Pk(yurkO5`n?6-ms zgYEL27;>y8d`1L!0{8KWc11~|C%b2&-whA648I;6T)*i37KN~6&=dg5vo|^1p?a}_ zSI?D^lSRlnTL_NTTZ#VSWk#Aef2!FvhRG>G57rZZkc+-Ne{Na_>4I5WCG!)dl&GP} z|L{C<^T~e`{us+;>v@TftQcDDSf&E{P$2BZfT(_IE@D>}nJ_}IS~ng+R2qh-%)W2y-^wp=pX^ie_BY?%>`R$`XgvYMwSI z`mNuuyPcO>7Fwbd>0TKN3Xs&0fF~ONioQqLFw7S_{r6|UYs9lJ0C=zL)trs$P7rFO zl1ve<7BnFF=Wh0oSuTsy5#wIGwKK!Ia>8YJ1#j=fay~7bC9R1K?_<_K0s-<%v^H0c zowwWuZi)?ewMHH3FXr4f$Id|f#p?5xKd$Wuw#UDuURjhKpe7kLI|2X&?j{PcBlw@j z7;c{lED-~$H8o>pYi-RDFXBbY$t#FL1noU`RXZZN`5XE6fF*Ui4W_WuqS0`3+uvc* zo3LHoRVzYU^5Q*D=XU;a;-j{nj-!6qmZaJ8-i#<~JPzGoI{&3>=IRff?_Q6AKhI)C zOz`5rxWoE8&Qi(Z@4VdZ#KKI`;Z$bYiTk;4k{xUH$Sz?z4VFH}M0fq?r2 zn5ZsJ8ZrvD^*mo8Qh}gb$2%Iua3B|R@63|Ak`7HP`tc13Hau)H^;asv(Vl*H46{2f|6+Wr@M1 z%`|^(nW-#`i;wjPppIp6d$Pjo0)y@fjBO#0=p+3#e zT8NHmqW%P;vC18LqGC<~Nw7~{iLCQsQ%xN`xauB;Fnza6b``OvG$6CCyk<3lK^DV- z3X3Z8=!~o_>1X!r?(bsiHYq=h|B#s`RdYaJ5!T!hkzQ4nU-PlG>nQpISpra0SaY1` zw!ALcydza73_5_cww=dy$Vi)%&H1j)@jk>7dbH*y8j&}>bD^iA|5~y6-6Lp{4n-@j zXumRI`PW7T;66_yl|GqhY%7f0ntv5txtkiLp}c!slUvHKH@s3@k#pTAsGn(nbr$}+ z$bRVk4nV+^eeUzjL0@3p8@TB!eCm73pZsL_RsTuei*pfK+M7_r+-p~jS6;S^9qV6K z))@MaYHPvA@|nB3QvJqHi;caWs8dh6kcJ+Wu^J%el2L87^nH^G-@lHZr=rc7^JC@h zr&W~C7vOWePI}J1FUL$s?irl+COD8%jU=sH10fiZ@jf?4vl2b+Cu_CdN^oX4MV(RR#H5kFK@!$f!5lsz(2;qs8Zi z651Q^`3D$Z0>KvjCu_nmK2?;q)9Mj(^f22zU$ z&N2Ln1MeQDm)%YJC@o^TmF;Qnt9~z{9V{a+ZhXl*G0*J^?5>sA&PVhkJKu`?TsHyN zX}B8)s zBWT&t(l53%aA3nrRj#*><*mKDop$Ck?%mV9VHEP%X(g?Yk=pLAae z9CF+YZvf0t3g)o;nxwxdyPlpd1_Mwyv28JOOv2M!__e=-;?VdJJ1)`Y%Hu2qmfWlM zjkg;yy3a({F`hOwH01O2CkIn-<{1Vq$Gy^6JV!NI1MsD~`Y!U;44G3ryguRxZ61?G zZWyemHmw0zz1GcVT?r<8V{b^oM~|RjC;Oe${61`6zE`*a^ZI!~nZlt)CzrSM+XBB^Tsamcs1)o4m~)r5sf0XksRd|=4#ANVN&JLcj$ z=SfD2P7dZ6d;8-!^w zt49kKOVNbO4*NBK(6~@I06}Txl+vF! z)H=TUB)Oy4dEiN&-F1leD`Y3EFUE}3)#I?;-)q%6Xr|(!iK_n3Ms$-<$oTA1$?pz) z0a5)QH?=DWtNBxJ6}}MLKCSS-!Q}Asa*t-f@@?AO*~NVUWzL)avux`oxlwgzPVbLX zI-+{zB`|yFWl4?ug0{oiFrf!>L*j0$L}Jy(7TWTE3#xJlYbTNAM4;?(@Fcf|(5K~- z9wqA;m8HGd{E=TnNG>6j?5G_4NN+WL4_!|Db( zC8reJs;8dh-tma}vxJf@;nEj{zg05|qnYjKF{4(*Qul-@%_lBNX<9-wS!iH5%n@pY zF)8#g<(t`D|F^i`pIi_@HG}jmW)r)_I6rmyHm+axGKK%S)6A!jaOPKhi=;;WV|fVv zlGOi}+=murBfO`+U2APU9pSSd<(`rrfJwvq?@%hRq^8LUIWr9)3yKzY)t7mi8>b}N zQdIEQut+laQQ~diwSvmmc4@!lL~>HgYNG6K%)Dm1xh*04E_`w(q>PV@Dc2Jc+H4HV zSlb*0(xop-tK6wS!Hz#30rLqR1&jx&$T;Gasl)cjcaWiC`E?vDVOV{lXe1eUS8l_r zcTQL!SBKrA49Hd2j~=8xrE8tlZJNrOuCOU=OK)v>hs(ZBA-$^?l_5N#Dnzgcwf6(K zw4P3^^v##e;>leV@K3S3Eb3H>SV&6kYmr-Xn4ELaFODCkUSJ|Av|yLBlPCgbB>o5z zo*wW<%l+hd=tO@%ihNqK0U}55V?9)w(%dR%zceu z5{HCx#@#Q8N#9qQ-_1G;x{Od$QUAOfTcA!)ODqS9Z{(ryQ5HtQn3pod7*$)X6OdO{ zvowf|kxeCg8gbr+M*5;`&7%2vxa``9qwTA#e?WCf$AFqZosXP8YIbrFk$`iuzJI2+ z=F(0E*J7mxq{M>g(C(ZvwfkF6ud=a^3FgFJQ!#!DP7Z+J%Z&6LON>S0PeKw@rkMK* zO=-*4IR-c;3mYqifAps=L{WDU-^T$lR%sb5v!)oX*(lNNg8D90irq@46gmo-avg~i z_HImp#uZ^h~EUmn1*Z4`>5v{YPB-`J|DZ`^n9-ADamz!HXT?`}*;40X9j1gt~}( zY@Kj?5z=FKyP03~2=YbcmE`){PYJazFRP}?sbiMNuus17gH`97MwY5n#n2~F1lW8eYDLSnV;ExFC);SKW47U?o{!@K?EXVQTi zFCWCjDZz>KDHrm2Ga2lSg)8t|?KqJAUyzjDu8P@IrHML=XdmvS`p^Fmon{8Z$)e{- zL%J=mUZ1G0&n#u=3W|WQFOj~&XU#*sFBDuW9zK1wkSFL|j(qS35-pyQ>i*jZUyaL+ zlWR`nj0?b#jLWdjZJN4x1mRh8@Ekyl)Nl1Q7hHX~;_ha(aQ!X-$tP)}?84`CPadii z5hLW~O4pd|2@(@~lO+`YsD%q;0b)^hLE z)0Z>7Omf4xQK2i?QQ6!#*heq*L1CANz1msc*o{#Sbl`a4*?WN>i)SsBc>BvHy&{NT zf@z$AKVic}ng3sq52OCwQyeIF^QA>W*zY*+rVevkl+T)Z510FihAfeUQkc?|fjuE`NCE`(?4~^VtIY9TzLm?VY&J{AAq$ z6+(X4hYt!*)?J!v-_?xe-}oCsrvK{l-S?ofGaxxb(H2wHB{rqK>r-;CMrE)Q}#?)P_U)Mk&Yf@>I1TN0l))(snRq{w&m(DSMlBsA2GJw^n0&Y zdNTK#PyJ)1x7><1zyH%4M!C&{w-IrniKN_JN7yV4XBw9xa8MBqV4l-wCl3`UfnM|) zaI&RS8qKXWL(z0R+TWcE^sv{MFRlW`70YZdEn+WzMy=oXpt4>=H?xD2wk$Rmn{V=S z&0;0aY)L!+h=vqgj|qIQmG+b?y8QvxXKYPP4-%FIY``^gxp%Ws+)=lz2mOfLR6BCd z$xULa{rDT$Cm1bo$q&0n1!Z-w8gduiGxo@qxQ2PVcwf*6xjAK|d(C3I4_0cOlyK{l zRH0vrucXi=l;Jq0q2RU)8nS-xFA8q2jH&IkQ&6Jz@rfpIce${MYRj_)!VAy!rlpGw z8T8=4|7eMV=ia~ZDh)N{6a)csTU)1z6`_Lxnz_-UfLf1X+A9p**{qQ=%TsKg%lhM^ z+gwP3M~l0TR;mVvX8T0Hr77+uE;Axr7<0`63RqhPeoqp!d() zbnJmqxm9pC?yAe%fhJ;Hn}Mi;F-Oe(OwU5L9vr32_~mJg`!eWx-sK#M)G6=WcOvm` zmA77x;p=OlLeqn?3(i&d%+?6WFG)R~ze|&*%t!B88g5l;aLxYYuHl=@Q#PvHJ~$wW zx>;J!(j>8A$UV4TXuxqn`}CIltmWwwQ{Y^nYZ21dvf96->+?ae+b%)#wCF-l`y2YC zZPSr4_3ccMFTpG=xn?ygnlS_^_iR6S)mV@Mz5xhZ38o?88Jh?!qS zf^G<35p62kM44#0*SxPG_eaFHW<}m&;lYUShtum{A7X$jt98M8hJ1&jf(q9&C2xu3 z%q7bzwiX%a1(BQ`rB(dXQlb*HolwZ1rtj*uMDk#x)Y??_Y(9>;MZU)Hj$hF)H>H8R z8z+g@NtTNFF)n!$Gwj2t>vhq($~XSG{ctefr>Cgku_+%9&_#LCY27ydz*XQL@p})> zy-PD85dUHEnfj<$pATxd|BKQ|E-*(0{p_xlVHXvE zUdKeM;?<1$tF?1qYLC}ev7P~*vpAjo9fUVatIqMf-PzcMV-d_ea9e&B;17wt^tOiY zH*@}+4JVncoRe3vp{&~Jlf)yh)RNdJz!{)6j~w$?0QYZ944AC7Ua z_{@CS`mInG4d2_~Twwd~@bKq_ zPkq+jm|luRJ64uk!OeYhojb42bsnsmmlma+;V*PiqE{$678X@p?GxW6W%V zx$%25j|Wf@loI^pA$ZX~jViba<(xyoM)k6SMW03`BlL8>?+XCP+cU zw12$bT+l9@mWBMOZk5cD&9QpU{2D!z8+y2lqBpH+ZiOb2Bq}n#Gx{)M zSBCQ#vnW)i&O#$IE+)q>>a~W5IFx*c1JT!*gcvw|IMuChE3s%kJYXYqnwQb}2Cojl zyavs(V&Z}v$adu&~R*Q;Y0mGv*Kyr8vV zDX;yzQROg1GUo@)E~m5cOSI2joR;O$6MY@-@={GSL>b8)-kP%E8RT}=;Ha}A%aMRf zwTMdSMJvBEFZYCmRSNT!EF7jHsRVJC2Hz$!9d>SLuoT`X-m8cHsf}OkjR(+(A;YAE zle|#*nwMGo+Rdy@ZrO{su@vJCD`6LQ$TnNalQoolFYjph=y|BJvZ{ePo_OH4sr1l$ z4u6CKFRR6+U^KmU{frIz)r2Fz`{*;=>~fsL`6dKc*G#I~KvP3=6M=t>rXfN~pbYYQ zkCJx6_62d^L7A`Y`)DZ<0F_*m(k*U#bx`A}rXb$8qFih3)i}Lwry2!T^3sS`sI)rE z%v5gLo)Cv5sCuOo2*g{W9M1ZlapP$&6RnejW|z5$WicnROt{gr_8_cE+z_6oN6_@{ zxk=SGw)3)!co|wPBjbv~cYy&op2VTTW)1!J} zSVW^lHxyCne6YXzn|b9K=Gk+IAv_P z>EJpGmS~b9a`-i%{3Y-7DzU?HdG`_Y?;W6>E>jy*rSjnfpAgq5qWd%?tKOF~{W;p` zeLnj6sKF#pI9m_N6mnm|d!^v%t&cITahx}id6nOP)~g%&%ac%q`vP+O#%{~1DRyyuqtl+L=?1VUrC7S~ ztB?sN`G@TSnP|?N<52>`3r<n|Z+L;kM6B>C=rgMNt?({!v$wFk}j;{9Q3!#%9yxY$on++ReP`ZE)r0%3V_ z4)2F30WL2(W>!!M*Z&+?1Ll6_9{8ShUSy|djft0z^kr=32IB(+m-Pq2=0YC1_Fq`o zO_G7eQQI?Vsyqqo`4xO~QfWDiKi}9SOhg%HdzaE?`L)(SM0L2+xPu)dBTfBFyU29f zDs>&yJ}7f)!ZRLm2$LuGG>Z)tM$z%J6u{f0QbvZjh3hXh%6>^pMOLw~73=vD;6D^q z2}fPn5%qOa3_;(PX;sK_9MIPWbqu_=^zJ>B?4IWe0wyjZM_<%7 zr|t#5|~*4l}xZhU21OvM1_)M5>Q9}@bjgZ@EJi*!>Hf6!DE`-w;c(wb>k9>aE&H$wC)* z;I{NI+8>U%m{wn&CSreXi-B|WGnDN|2T5coH2HL^ma=&tg2Qj<=e5>m#fE9Ykyeor z`akSY(VuI{Zeo^h+jtSCG}o3RfE(J-rGGUz@Y0`iV|@YG`$@Nenmn=#a_zjK+n z7BK3e+v?OejzP$K6}ucs)O1pzD&Aqkrdi*#*o9^T#~@YhdIW)gwT0n*6gtnis3-iP zO%0D+T~2J|)Ljx4nZn)FSU*t@B)QEozqW*4RQREdsnRg!a>^BnED-9(m@lpit6I!c z0tqj7iC^pdqIv%*MjS%~cUM<<_8JaUv}B;J_W6nf>7EtE4!NU7B6WSa7HHWdT-e(U z68bI}L6@bC@iO18`??vC#(v#XP7^_v#03THw9VVxTcqSJM3a*LSd4z^mFJ=cVAM~& zv$}x1I!gAvLK2N$<2Br!qoUHqHW(OF@w@?Fog87U#tvxQCI!)8*|#srt8?2adfJ{;>4832?`RfLJg z$2}DNWc+sYV4005mFKGpFs~=Qt8_qEkD5%fZ3~19ZJ`$PpN`9oU-S6EIYRw&o4IGU z^u|C-&pS{lFnxaT=iKF|re(XcT z3vl(Pj#-{RypntX$+2QzT9wp+K22-J-HSSgX9t*nElicZz<>h5*`m4LLXldhzg?Iy zlGp|OoolUTWFFgSLjltC_eBb>?Kn+S&MTZVSASNSWmst}VyHzPL1;25{R*!x&?##V zhcKQu?FyS@p>7JWj)}E0w60xG6oy^kK+UEK5hMN z?#P-vh1@+{8-R`anEJ})vZ5Ip_VXfC!Rfz-8B*l}ecfMPtF){|qs$bb&r3Vy)^COL zE>$4M-c!X69O`*-&-UEnwNAf%fPC1JW7*et_&3J2?@ua%@o$}Xp!XXM=Y{qz_#5Lg zCj;@nHor}of0~57#s08N6%%dI#I~L}nLz=n_ z&^Uh=$V{OVhrOtFma!aqK|d4ZFAk)5>$dLr=J@eEF?vr= zavl<8mA@UL$5;-E*pMz9S#P7@7jt5}FTyx~-vp(WJAKuxGCtpBy77V#PiG;6Ygcz~ zA}RzM$P2)=V%CnX7kSDS`o;v|^Kgh<^GEWyfsXK;}y}cdfVwDylKJ3!@iz2mg*kuk?YJk;_ zJyb42?Cn$21VYc6Co*!1+u_jdvI=+-0Rzy@1dp`>S&w^b6ziD|faYHjP(dBwONyeIFj^GYbVgB;4hbN`% zx0`h^5iv&~w)E$NP`cl_3&|{EU=W!TDm=8aMy{hjd!p%yucc2nD=e9-ck5*+Lx#{Te&dE)e0(S~G}uDj$f%P88_LS) z6DrasUB@Mh;>-wXEirhrUxQ5{C5BupL2;5VU#Bkxs%bl#9d;%fZYHbbuoqAHg7POa zM{9rAmpRmuSHE6ZRA&~XEa!MC0`MN9!nAmdDRF-TYpT9&yLu4qP?Dae4iOB00hXO* z2RrS|uCKESonx#ZnAX*Xh@i@rX4t+)?#Y`<`W4>sZPZQYhhR^$P2odb&&dY=g)>6@ zLmKnmoLvXRi0Bkp6_3Z^T>ySi2oL4ZGZW|<;?-iTZFk%}H_P2LgRoZ~z_u8$2fe`r z&!nfk`L_FeZYQ9%u=j1;RNdbV)O9BZ-(Ar_6fjLa_$I9Orpej)UPqS71HXz1Pdv({ zR}9?U@($wV;rIwT3N|<`s9nsrIP#d)b|I12bm+* zMjl4^-ZxDMCsTQVl;kM^P^IzYp{nAf&0%S@cf9ig&wcjZYp>5bPgs{*VLCmh zLZwN$mW2HnsT>0{QM?j3qTnabGM&^*)6>ydX)&>tuzE@}YdTSN1Djgbl|o(gG36}L zjlKajS3;m3WK^0$&J=SQ$P5@j^=&V7t(n~BTWxKEjCstV2+eE4dAQ!b2bNM@x(tZ@ z)v6q5#gK*e4ri7OW6q_N5&V^sewk~(0aIa~xaRd9n^9bJlfoxy&s`swptw5>h7L^5 zv_P$jQ59>O(Lj>aMQO3Kmx`U;g`VCRpRf2|9o~#wy+szg;b))r8^n9j!`4hs-&VfH zaV7h^PO35gP~39ray0jB>g4O$KwruuRXChd_B}8Wj^gpcgII6iaU8;@*%U8|8YJ|| zgrSn~4jr!m_%`|tuDmyz6Q1a;W_sEqL+mDoPR8ftT_5%WeQW-QcguSHj)csVarI_BWIKNGy9}{i z92C~svyPIThKb@`G~+ys3MRkn0oTyzi{cs-$o(L^OUcjfdNVkx8%J zLd?ys#@ymh#D{d2J^5i85EYuhAO zV8b8T9Dh(SRoPeGz=Rf~z<*h~1;eu(S+~ou1D55Nhngy7kxPZv8xC>Beo{P|`*GG9 zFC1AnD}ZJY9hHF#AVNP^R0Si|OYr~UOD{Q?0*_ct``3JNp{)gNz(PO3l*=A@K?J3( zltXQRF&|%9W(!Nqx22l>>Dkc>?$*OjRK!nY{ZfMV2`RG)tt^%z9MJj=pVZ1nw(X5{JPO38T^ z9Ec)T@I+Hp7IYL%CTSaLzWH6PF?8QMp{eCgS6Oxs7wJOHV&0#XQ3ysgjhRqvr3KEW zBi@GtO@bk!jaF!+)W#+mWAy^SZv4LOBy<2HHOlUIJOAjow}vLy6vZ z=CKrKd^1f?er4W{S;3ZLK-x}|Yb{brYZSQDC=XOhvi({tMiN2)$)d1}e>!_J+Iqdo z+sKZ^s8ND$)i|K>kGw=8KI*Rn5T4>Okt@zn9 zuie$=nR2j!SOKX}rxj)|`1eqDOosA#y?&7k9?jo1QAv2fAt28?I#_wJs=xABdzc?z6Z4J+H$i{&A6$3Ca zr`wI%Fak7FZeZHv=DAl^(RVz5Apb!s7Nal9CxUk3P+_hMfHQD)u(SsT^^0%sG;Wf4pQMVDVZqD zBjNY~!oaW#Th%TdjKhej3f;v|af}qNNrjt|dw?+?LgI4cL`Q3X8UQ<-rKLN)ipGqY zRYAt*Q@D>1`Hh_t=Du6Jb?__ItoO-u~VE z!j^#~7C+;F?ae$QVc&L4AiG z@C{G)BX7=yfJFjBmudV9umw`fo#OTgJ?9Znl2W33JRK3IdraWGFzz^P*p*~3aIt8w zebSYk-)k$hV-k@~`$aZG$x*K~Wo3TQU_xJ4Ux!rYHHY~yRW^mDz;YQ+_3EOZKIXOG zQ{CQ$46vC_YPB zbF9}^e5{skViNZ3cEkB<33H5f(X``e&xtIj3vV@S;51~~<@h2+;I^g1gWBPl#lmHG zvzr+Rq2x)2bK6pc){`0)Qs7Gyr5z0u!__A&NE1+-l{0*S8=z4al*jYzb`g`irRZYlMLB1@AXqFfxp~^#2-I=W(kmni9E-oNc5siN}PXb za5nW^Z1V8Pgy3U)j1*`#3P@RF%j~%2P1u3W^@FmN+38R{`(iRf>q3O%?N+R83iT;g zF#V_n3%ZPT_XeC&D7x7wMie18{KC36v}WscBO*2awGmR}<-!f1sySATtpTmnonLyr zDTda#p!#XFCLupX3S*$dllKgi{mh;epIY))t=Nv2dZI2&0sbrb_RQ`T#g!62>{JhWM7PK6 zTWw1gznqJrzy)5-77~;!e^s@O*EDaUt-Nza+ViY0_)IDM;W5;*;GBfld#RoRobRuQ9OLyFwU)}UR; zI;Wv4_dU24tnnt(eX!Cl|4=h*YB9s9FEz0Sn&-^O80N00R-2z?^Q=c49o8@YyiXk$ zv2ZBLiF1G)S#Clr1&)bCy~|!%Uch}-^#GhkujrwmnIB2p*9U@x1)lsiq4~+LO|23I zBt6hc|ATxex%IIrmG)>*yV9C|U}_Cx8=MYd`>~IhL`7^dYXH zUAoG3!}sj9x9Zx*c3aTq`eZSXAsKxhxiEvTGjRJasAA?pphP}0*|q!Oi5tkP^K&zQ zbTP#HjNH8JXQai5fDUAAFgNxN%dT-#s`UT8^QrNIH)#f`9Fu1mX9h$`QDOq*_4FOj zInZV?#@CVY=(l5>akgpZB9xu)dKQV2*K%&6{MT6DWw@t+YP34-O=tnf8)i9EkQj3Y zlqG)tAj@9AO|{Y(rT3o5iEtf;W9+c~ie+2o|q8%H#YA_=fO=ik(2K zcMRCr&tzN$0NY}2%qfZDJtSYP)q=D=q!)V+isZco`Sl|xI&JL0i4sExC$tUX%TR~R z+FT;7h09N^HMNEwB1Uzu;f(6Nq!bwlHz)8a4T-TI4MDAO0kZkP`ZaV0f4yn1H48S@ z)U!hV{;9L|uso<;aeL0OnSmn2J6O_71;db%qi6xGTcoz4ZQysW4#X63THpOxxlR7w4}L#T zU?`mMVA#Uy5hL4PHZrf%^FK($mki~}wd6m3V_mN+u!Vhd2qV_>obNQDG>wr11A}|= zuELN84jV2JNewOMo51dKZldh|!W8H?*V$WnA@Emcf_gy=(qdI!gg#I=;n?1sHRtEE?0JbOr9V@4k zj7;Xe?~xYT4b1apDzP%PYN;<8&frpRfL%?5MYXFYPpj27dQuLkUw0l_+8` zNJUV*d+a!u{)#>hblnKTilt0eZ)he{4xHk&*zk#C zGMtu<#P`cZP_7D!q4?-TDJ;7w+Zfi!oC)iBP}CL$lI!i`5ICFI16uhGVPz5b1eB*)6U= z?O$D4UlqD>>G1@X45mNmV9=RmRg(m`Xq`4JX>%-s{me@*=u^v)=tKqo|KmmSdxRLB zE+TGo7lJ6c6a$g!X$>a#B{~#92$cjb9Sqr{(QYo;{+RYFKohNeYRkf|- zo7MHE_&xma2&%4t&Z=SJwqu!y^y-{Bx_dpDXS`#IJbm!j_1FuUzyrp$b=98;P9pT2b8gN-4+gQsl0+f9S4EkLa|VL zw||p}oM1&tJaP)xNxN&g(9~Ec;lviim#c5oWOj44e`1Lr?iO|TA&M+V{D;9Jp6u4! z)1z8?{YA?+&;uzHUyfgAH`5F1>ySj75WJ*-DFH)uN*#eKLG0b}xxJ*0K!r;04{aO-m1rkgXW(2al$|x zEb+};UUuf58DwlF70GY>-nlI_1&_Y5-w!*BP%%lb>c6tQ{#vp~^0NPC?)pGSr1p8J zovt0H@G)@mU;|I-yj$#21m<-(c1a&Kmf>ktB?}VnnJz5KB)wN?OhVhi^ir)3sbwoU zi;1S53+uQ;ORgu5E$DNm{N9hJObC4U=FG8vmu-0kQT-iQ{~#}HbQK)e3EJEB@ISvE zz78?mvhMTn+LlOoF0K)&GRCMDukmcaIff(olCsU^<(~(!3Bg|5FTl&77i4;P27$1$ zZP`smJ^^C0oA1V48*_T~&?S&NQ>VKLrx(^p20xx!M%Y-LkH6)@J9+iszNiYt5dPx8 zidR~w5E+z9f*;Ft*(Ek>oC|XQdz;8RfpfjzWCq}ozj-^N?-5HDQ}O4O%!Lrvd2S|m zoX~R@Av&$v8QY|2K*O>fev@2FiD=T3qOgR`h%k1Tv|!a2jT>rP#6PQGAEbNbleD3-|Xo$J*viLrYORawV zV!uAK>U&L&V?D%yYkZj}oE5n+du|7&IbFXE*Ha*wxC*tiT?P9wa4cWI$$i_JBYJ%) zV1M&82&KNh0Q}yUeLxFifth}#zHLQ}M_$AfD1c5~5cu(>Bz$R&Fe6Gr) z{)2GP->SC;M~2!ML7vWD6xesoawc^{M7TUc-R3?0lEvNfh zqox4wQxN^_L<4U=eYorQim5n0BQ=XiBH&B=Gv^rRac*LGRLPpw!^GywT5}Zp^PLgj zMgDOVW&kKafBsz^j8uCEQe8&M4p$+kmIyWrXhUrRxTkV`f@sE)pZvm;BG>i1UMt&i zi%U}S#fjqPpjXXE6+zt}3Uai`R`Jxtu4D>*cCz7LAD1W8`Gl#h>jf46!0cWqc=q=aKW z#5^s^S!4o#rvWn*%(hTOjW<@|xw1rVW4Nh5Pj7>MB3}$|*WpHglCSe0q%G0?yi{>@ zafi@Ai_7(qDKzUp$gE8Z*&rsM(qQVadliGXsM`iEvoW+F?4$)J?XCOrFou54fIa!g zcFrw=zwgb1*k1UZP1asOT~2^pPdg5SL0{jz>Zad%%Q{8Ux!O7sI})DB9){|5v~%-h zS;M_-E9g-jrepQZLe(4}hO61h=Jja}AXA%q74w~_hm4iy27#;1r$&HzO8^J5ll9?L zP1wZ=`}k>2Yz-y0neaEwN-L7xA}ikO5K&J0fqJax3x2Kx;wNkPs0NfI7-Iqfdr-Jq zZPST)NWN^H`?vo4;SZRz84788GH{hqO8><$+@p-CrUXM$o3U-zdxi@&b(C0v%s(&L zzyw=}P}5fTd8WZ2kUli#12EaJ-#D=;Y2Qm zwwXWdK228?|2plXUS^g2W9pObNLF7(=k<>ZLAVx|N2C7F7t=?u1$Dy>=HI935qCiu zS3Q5M4!a!q=)5ERs<$F%!thIMjW3eB^55SLitRQ>3`TFO>nBwV40KNr13WF!aa z@V7p;**9}VW;kd8&H{diq4)oUu`=n!bpN#`4pFSlA?GgsuuFD4kFNpo$PtYuhCNs^E9ulDQ94|w;%z*!NO$G&I?0bPO#sssMqR1{di zj*&?)%qJq3N^;?&+J2Lcr)&_LfAdPLz9wvwuD)LCRlpJi7K6}wc=hX}s6L+zbU8NV zZUkl-yWuNokB_|65hi2A<^Bf39PR)hvVbB@?X&s zddi>q3lU)i)^{#6oQ89Gp6#+|4@E#KxJb zwY0P<8(3ph>YNe?ZCwWAjb3h^HUY8xy|3b3 z`82R%Y$lqR*CeJ8O`!`AH? z-~+_fF6DWjYjhr#()86z0!R51N@{c_osRpRuc6`TN77+jH{3^6>J6XI zzB=@pdc&F3)U{24YcuUPev!;Np$Sipl9*uN5dag2j{; zm^ve^N}M0aejTKn8+We^;O)tIGA!45fiNP7q06qG*dWXHRxK4sXZmdvAK?WRWOt*iYYOm#LGh6Z1RG+15L?&Tw`Z6U3s_2YivACxPwj0;Gt5mQ{K9iy zOX}M~!P%q(uyHu#<-k7`{vb9^f>dvwM~VeJ?7v@QNx5XErOcu~2kG0j3gWLnR5dN! z={q9OH+D_RG*j-3!AJx`RXdZKYSE*djBP#tKZ6YIcwIjy@TX=yiq$7wKd_W;irY9W z>BW{9*{ODMO*Muz31o{v^#9j)fa(cb@;#3Y@y8)Z8tj7FU^2ob=i`MJey4>k3BJTL z6J$tR;opFzpQ4wY+<|-V7`WapfKHxi1Ksrr^p5YX+c^x&1Ay#>jQzpk`4)WDN)AJ6 z01c4==dczA9&CESk-V8+ZZUB5pV=*<0aXTDp0HCKQ-Q^UTOV)gVU<3tsbaZ;S@Dj< znjK$qk>?&wAlQN#r|G;mAkT5r`KCE(azB}M2~n!Iuv`8##FU050`fc{7JiH3FZyGPbsO>9F-!Vf2)yZT+nfc?<-%-pwCf_v;i*M}X`H9GykE-w9S=9&hV-;7{YUTb|xT>SyyBtL#)*%UXe#1huidUIBS^4=7}~EPX4oqx0Yj{ z?CN26CBn-W!}I>;SZVm^5b?u12sXi`&M5d9!PnEEMiox*A4JJUJ)r2ieBjh&bobLX z1(!Oj*zmnrmyNazq=fY=szG$0o8`N1i#8Q6?~kT$7j)93o zk39mB?h6E8R*(m6kO+=+u9i3XslK5+TyFAhRSa~owy*o2==0;p?5>K(yht?4U`~7| z_B|MpsTh(h3p%G7oR5mKZ>N*payl`*x!uQoq*Y4Ftwg@QbMHrTDBXCsd%X{_rEPK+ zbh`Z}i2oZWbpx&YljaLPK4_#Z;9;R{`${WH(usBRmaaSB*7Y)gdp2=At|0FQNXt2Ode z{Af;&Q2)LD8Pv;dlxmMd$bc`Ad3f5BMLi>kbF%Utzj|GjzK)7uGyg8=c;SV`8`ho# zHPb)TaRwqmDr72Pkv#qB>671J_SisOO;U@PBKGzj`2{@23+&z;Z_u^i7|Bbp;y9@d z=G^8fSLibsQxZ z2%cT+eN*6_dG!~;r^R!N5>AOR;rc>Pzx7CI_}GH-0w8Dcf~b7)8O(k=pv$ydVjZGN5}m_Kgo zRQI{>_fC5`Q5f)5F)N!sqIy^6KZpVYY$j3)6clZe5nVomk~{aFIXDBuAGj}JX}p$k z+*N6I+j0{L`_6K+lSA$}mk0sX>WPE6y~#h46j6J=&poo*@p7$q_!s8rcH%`nbVE%p zsj`=1xxNp7UWQMMpLv^{7A0sV+6j+nT z;OTh}Avnb9eNE{bU2QMNQ^lm?xgG&jwW*W29uh$0_B0j%*LLVwK(~A}RbzGf(CXn4 z4I>l9OCCKco0e0J+*O3mNR>P5RR^>&*4WNBnv(gw!U^40wk_q@vQ7!-v#<5`yP~zc zi56^lRD2gkAZFo9(jJnCX)B*X8TT(BBJ%_@E|{HeB0~e>_caEYqd=(9${&;~G&@8Y zHKHhSs1`4?^8}vlkOingkK%wdCp|Q|D6DD$>H?a=s#D3fvHZQdD)D2l4bF74@ z-~MXzBFD-xOaDRAsGl!H55+!i1eK%9=@cK)`t#~KBdpCZDnKfW_MctCn`g1P4tY4h z0fJX6nyLFb=K00@weGxEPQ9;wW3Tv>WJ0j%%eyS=b9oR$7O#zCOyK&D{jjIaHs*3n zko6>Y=7`RdV|72;x*E}C3{X=ZX)$%mv@?_)8Cg5OL<+NYxzO+6fH-dtU%=*Dry{xIrX_rRd4BrD5g3-IZDCZZSRjkA?|n%DSx?L-pKG!ppR3{~ai z1(IAirO#4sH6sYWbH7lfX;Fzb2KC`!nemH;z4!6 zIfj4J>7Id`*P-*xqLRkXyY+9K7+19QK?{{MW|l7*iXpz025dYsRcF%!8-=3RWwE01b0BzBS?dj99H?QAazbsxo)UUEtrWb7c4?^3H%rGp-A&eY75NNcx$Y=bp z{=mer#P~)AKR^mCKG?yEVjU|V7Ri+iNeiV}K` z>Fk)$wbJ#$aOkW5S1o_x>UB+>tGaPc#R7e1^siZcD|e1+Z|myn1oF~l@O+Qt1%fNi zg^F~M{PUq@h;@(#P-0Fw71|EE6cYLcR}MeK<|52w58Q3ru^H%+k_8NwCWs2>b<>^) zf2|f$m=Y*3t=7sR)3CyW#qc0V+QTDTTPHq?qy7@3JW7UfJYsfg#mHup`^3-jj-bj0 zg%rCiHnh6hq-MGWZvtdhKCQpLaW};~wg+FqA!5Io`bLF5ntk6Z*m^7zy&1OKG~ne& z91z2_F&tnX{oP2f3X_BVRGxOS>>5w zIP_akadoGvJ<;CtWbAiRQ1rRZfkee~pUBvAbutmf;!dgl!OWx$ z6nk${-(8z)?_u8ox6~vxGOcpH?>Qe|@SYYnjEMS`UP5Xfpe-YW=Ty}ib~nk!nnq4f z_E>FAd_N=C6EE0D!ZCBT-``&y7GQw|j0)dcl;$sC6j(r!2AApVZNy z>xcdR?bEJmILd98rr#}|-cI?I`Pg#L2So&>e8&HE))|eS&$Ds9_a06m=Pn2e zit=t$kXj3y;$FRq0{qM`mwUd=j9PZQ6I+C$llfrsR{jFTwJFW*M~>%W=Ri94gjv;Z)3nV<9jSQds5%Hb%2}Q6w51*_kTelgy`-r65~SPl zVZ-5OmlHUvZ3lE;l>Bz`Qk5R-FGR41@+9>x|I1jk1=FR34j1cfk)Hxkme+TS8SFvmGYxL&~0-ehM_ zoKFjJh){$by}5Cu=F3o(xO{>S8whJ8X`e@n<~`f&LG3(6K35;)8{KZc$&8XIQweTs zU;(@sbHLwE9Lb@%dQuvWed}@)eSd4eElsKQqlq-dhuPdQPA=oYx7bcD z`1+SIo^qdwB9`WKdroyF?^S4x@g@1%cBgqlI2B~xe)VK8JgC^eegSvFrs2Zo6(E;45FQk`!sd zwb}G|vv$;yXI&T>NRL+Jj2VUV_S4LjAQ%~*M4EIjcJn>B`^D2qP<}_&9$S3X${HG> z6|1Kor$HtsG&d186M1+{S`WxFX|3p#n%fcH{Z}*_XCbkZ?u1WoC$fT2v2J_+{!YRnsAx_dEedAgc9e z=_h@<56gv<-%ED;7N3hon8*6}SWj1+v{d>&lEZ+LrebQED`5-ay{)D`!L3-a=N$$6 zTJWG#8&DrPOVyjSd6mVx+?fua$(>8UM;oJ>_eV~!RP}f=+JXH#wl^8~GBk0#&jjmw z|3E`>rv=Rlt@yu98TZX_TLe3FI~+*KnycsyFA9_j$>eZwyxfetIR*{E@!+oJ-Cj&hqlP*!J!ihf(Qc-U1n8;NUME75O7p>! zP)lvU{iy~>m(wjM{cKwSg8TPj5};#uVI=tP+~%JFFVh>?G8&N1ED3#N6D4Yy6+G>e z`43IV-X%}vuStBq25o8Oj2c`}|L1^y>c`!C6-nic)!w)T>S*3}fyfxpn-3PaHy~Rv z7hZcG3!=#GG#1w)nRS%dzdG(^D1yqU3V~I9T=s+hK-MZLTnnWk|BLQw$BLVF!=EwJ z2dzhMz*jN$D~t5RPI|J|9jkvt{c5r|7~L4HmSO!#NOt?niK8C4n@DmwxL){bYoeBl z&z9}hcE!aDW0`z&(9PD_+&lPqMFo?ROEfp8*@I_C81wXn8M*vMFcWNaCO!MUdK>6- z>Qq!#p=nadDd*6Bail>hnn_1x>Rq!bLgoZrI`jS7Is|2KxJf$d$Y~nZ5m_*PZSHSx< zuo&-HGb5c}6QSo(CK^qB96v1fl2tq4;kzSr=IZXKoPVeCb;!fLSzqjaz=F#AK(|W1 zv>9%aKUlS1M_D(v%+A7aW*`dy9ERWDm#>4_Y_;6Q(?SKTs#1!j`{WAE?oVk6bb1?Y zhT43WLBVpdti7L+MuxT}L4xLW2NC+i{_sz#Uk$@gJW6&4YTlQ~7eix*A1Yz1Via)M zo?YV;;y{vRnOxXm50J+!w*0q&0_v<70v_b20RMz03nw<@Vprjrx6wwJIf-x2=dlAL zFh0lTF>sXmGHnftt7D^);uNcwiCjoe@1CpfF+5WH#Oa}YtMsICX*(1Ru1Grka!T|B zl)D_0>=5h2dS>OCYd3DGo(+M}>o?t(MPDXm8CF923E)NkVgTe>`O}-}Ncqyev1pJj z-?#uV+@c?#0(lgt4PFmbAYAU7bV#tgJ3{cbrB-}rEI=)P+GW=`;px+!{ASZPq@$Jf z<(;0ye)gH2u6}6M+C05%q^aU$hZE_ruK1u;GbhpqEQD+;Y<3O2uN6-)OFK`Fwo$s) zFF^VJ^HTu$?nSkVTtLb*xMKYpb@H6;Xg@icF&Uho1Fm0y=|ML>7&+AaDWR|>AAnk4 zG)C1u)iD`knCAPbWQN6Rv7FUKHSe{Gw5Er#!h-Yk^2_f25^Lw}!3nmXR9zb2>T(xF zt?!u}nN|Z#cIbf%+9=qS&f3g+GJc6$BgN4XaBFTZoU`?_NHp_3cY!;H(09%NPm1Z> z2bdzeNcxAA9VJLy~3d`%`2_x81o&9Dqo0*AL51zFZ06y=zoqL)d_=1j&N*vW;i*y9k z-rfX&ZKg&do78np^q$po(W?)Go)4hsm-Ro0A};KW4NEHd1^$X-f$Vjq0q4^o&I2_l z+mU1H{bU`83}M5(g(iX*{h^t8k$Pi-9l}IN#@%bFX0HxmoDrJtJE}8*N|5r-A_=bg z>A1Oj)lNBJ!p-6R(c`kO!|X55f_^-L>6Ft|S81Fv(aQ3s zL(r=|;@h$6;)BIDP*s64>6P!pE*Q`j{UW6Pm&KX&KAKw#wYLEBD!`hAr>CGwK%H^G zJzO{t^vT7awWmfnMrCRe`)yOjJAZV>tu;a=KKT!lg@e_T(4Ez}B2Uh7-&62eD+zeyE_#t! zBY+cG%ds19k*S-y9Zf}dayIY;Ik6*yKFtgk{7Ov-uB6SlkA!(5KgOQ)6J;{z?rTp} z{FX^(nJ#<$%ILO$ zotKyrdqb@%2(GDNqA;{=buz9&lKkb)r9^J-x8)fSP}#i#{46~Nhv_?D(8Djl#|CrAU;SGtDx*DKGu`;YBJ}KDSkpQ{UGP0=-i8HFK9HlQW9>Xkt0HUS z!zjTTJ71eiYd|r@hIa&9%x4()sQFdJj?Jd(TJ{jFU|G+Hx6M6dKevvJ){F{ ze0L*Xq`}Po!V>%Z@iLS8THA`QS*-G_JGIvj`E!9i!(QS-i4s#QQ&k&v(ZLkb8H@I^ zqr<-+io3a4&20&lbwj##<~I`rk*g@4{i)h_OS)2yb{}JVvVH`}bEP|On%)OcO5dsK zqBr`v9Atd*wJM|KV8pb_{Ycr*3qK8FM4N`c3WfryfrqmB6w^|*f$w@RAqaIEv)ODPAf(DBLZ41lo zCl`%YLUI4=s70_dBcfnTn(VVQ%N2nmD)tw!TuHU45~il1UIq zn}7nM-?inG=Dr8KS5%;0W#HCx3L?W|7eBL&rB8-{YASm z+XEA}T>@m951{tKI5NF??^S+<1$G>%4ozck_5IOlQnb;f@#VarEiLaNJyd_}4>>fbs^H*?7BtGL~blH0|;aAm>Tm(HHgq7^5{SYe=;@Xr8Sl-xg*#J>{G zme7()KZgJ{D@smq0_+WF*RL;B;UFOMHW=$}P+=kCisJp*pmJi@-7`ZcD>~4t3MQb4 zjQK`t$J_!06an9P);w1-bS`XKLv)G_c4iy0rZZ1KphBURKm*c=)L{w1f->Pp3hwG1o|j6z9X%On|ip@36xFinMI_nl_EfyCzGAU^7eHbA3{HWhHs?e%5(#f3**)T=_p0uih| z>xfnYCFsKLw`k2o=*V;iTAd$J-L2x3zuM@u!Gq`oo3RJ+*ep$~Y>lW%U^l`@tAo zSL-JQ(t}R-K&5MfVk7X1N;o*zVcp7EDv9zZe`;l=fQ*lB>0tXFCj<=nTR(d#>8q&p z6C@foyB+=|&M15CE4+Ro;jvv4Cjf(37g8=X_;mQ)Z%4o%#0&O!4MNkJv0tugjQ3gz zI{)qbp9jqA%9iPhRZ;%y8Si81dKw`-M|skTs9N@*-uq=BSAYc;3{(9C0lX6P#o?cN z$TgI&HP1_+L{{6{V^lASx4X|fe33Bn1&;FE7ZexJNQ}1$`QP3d$yUU)e|;{MI{kSa z@w^K8(XgYnt`5dK`nMGvBI>0P`Dx|P2>KLF#ejI4EP>*X9C8Cve4TeU&e}f<|?%*i5ydi80bDq{V)}S}n`o&)I7tNRr+Q1mcv-Gt( z4?oI1Ho(`_E)c#G;R%HQD7;Nm3~^z|pNhVsh*^9RU>-z9^h4*<8@ z2<&)v1yY zPZJhnWh%hY?C(8K%Af9-&4A<-qB{I#eJ!aFC7!x){92zlM8e9_YvS(Z-GW3y$SI5V zYVgfS64&?1Vap}wQ3=dXt~?4|SIerEQG1iM60duN)4P{S4&NpXf8Ol=f^r#~-N9S4 z!U1292{YkVel*NfaA}MIaWHsyQuf18<#)sv!9fDx>R;9wu2il!Pgiwz2X>-z&9InY z8z5@nUAWuemt7K4CGc~3sF$Ngjq!>eA@}}UTFF3C8JoG@uro`>aXrslxTWiJmAUDv zD6}5>C?r$ynMi4En+B$>tapvZERL<}ydzkGH3H~Oy~w{sK6>+AofLxm^#{f2;A>@+ zga96TjXX`NYV0^PG>^Na83%3|4WhmK2J!2)iT6ye1YA9-tepD7;nkjp$6>44Cs&nx zkAyh4_eSHP2<$mx*)5|D)oF-%?JrP@eEp|N>wIy;aL4+=5U=|E>t4q%firPH{PXyM zL{&J=y;^n?}QvB$yjXsqYeI?;3*up)XYmBiXvHR`cHkiw1u4!huP~RCjiw(`?f|(DS z8)cgPL{q1maOrshSBMb>#-QMvZ-K@H9z`SYzjh#y>63h!*1seF$Zsp;94y11FfAt5 zR8bwKAQGjSb>nFSIk(RTu0;$_OUId~jffhjDZf8H@7c;aVGHxOi?RZiVnDGv;krFp zA}GaCke7qGlg!m5P7U>ce>WzO7typ0lC{tqI`4OC$;zOP?DUtZF)J-6GA z0cxpX1Cu5r@TF8Q)u*mRqa&olAFgsY816>vFa*cSn7EewiC$oT*ycGZr0=Oy`cQ`L z{C&{7;`t~W2?cIdM9~Fwi|PP|CX$d$5-n>QCqcd?qmEVhA+xU|NW@!(_)f#6VJg<{ ziLdO8$?qS8w*XESEW(BKPCp6zpu8OQLob)uv#X|&XHnFb4GLyU@g#R+Hp&QcIj%9+ zyUOtyM~!Xv=RF)<@Ik<**-F|^mg%{y4ZlhtWpW}@A*qsrzZc(C)h5#ddQ88Ry~3*D_?(xbak8dN}1KuSuu2?6OCpmcY4t4QbQ?rs?!W4^cl_v=1v_qKD+b*}4I zcZA+_ru1W3V76}~Q&R+~u|kwRW9>9IfmS@J(K-b3lM{faH&?1pYV}3NrEwGa#`(*6 zTSfhUp{R|A{OgY5wd9`se=`)u57rTCvXmeQH#w>C@3!|5uutT~6ZW81(hv?&Q%Ti5 z`1C%RBhVI@S~;e>yDvNU>ktpFTjZA6oY2RlUDYaMzctUbCt;0*%P6|p)ck&Ovz2AH zyG2XyFTYYg+FM#+N}|ib6X(u4?jSL08?jK0F1yl=e=$Bh6NX2Z0lE_dtC$?ecNN^N zl`@+qYdnKFo51S!a={wstS(ccsC1`POmfv>^8NE%cp*qAHujaSL?Hzlu>-8xsC`3zw*qi%73fkCu$kF)SdNA64=;^d12kCfBJ@Y2mbcw%MpceyTHUAIbV=E z;Os-_ZJB3Il=qH1bu=LE8CLhF^zK%7&B_$@w!|@~kcf4OoT?%#HDMF|qHbq4W+KV_ z*kSeu>j{ty+fN)Degqb-Wk>?M0-1^S*wET%?&h84@U|nkMwl1Lng(uVO*?omqc9Jo+mDG%1w%}|> z@88HAzRJHs&}1ywM9dzYte-(9jkh;^h?ecl{U!B~U>B!>qSSV|EwQs;xcv^wH4MhC z=1spHEtcBt#8#Y>mFv~S?wvf1wSQFqC^i5pOup&McD!%%vb}7guC#|eN;!Ss;ADTU zZdhgSB{RcsY1|DCd~xl)VT@>9Lb|N*^{}%zA#0IS;Mc01=Ct+)+!CAZM~p&Xe8TfL z@e%s*xGlY)C3E2}O&S<-q~L~28%*uepCN;AOke_RVJ1}|8Dsy44rY2+o8`Ay^N;}7ad7ZHA;S>7dL8FP(5vgq^95=E- zVEd;)WJnRxw6=&zhOwDf7nkGLN}ysvvQA)oE`M=IJI!D}UKCr+-Q_<`X2Jf&5?OtU zx}9ZXlaf-xXk}jWTlaM;^#0Eutty;&M@FJ%5kIlT?|VcHgUR5%&cj_PdurC^6x&TR zDkvfsOpbaGeAyXvkY;c7DHF+fet-hJ?4#j>$y;97`-+e*-jf_l4T^n4;7`pM=mpvH z6LMuWJiVQQrwMkCgFoLhkEfNp$Q=4WFC;W_4D3HX`b4nZ2N(qtu8P0Y;tlzt`ic z`U?K~EZ@8=7*q*&75L)w5%)xJAx`o(yS1g;{lR)Cf@mbW8_x9?!e?VVmOQbo@gOF~ z^DL`L2s=5BleQ0e#0^G`gC!}C{ys12x zfR+O0_AeyZR^NmaE%8+X_$d~W`)NDFxdU`KGL4f$Qdfvodw#|f$UnK?n0P4PPWzV4 zc$+!u`i?^h!?cibF7lcE=*Z~WEGad6zFG97U@V|){$6W0z_8Dk$|Oa3TeW??Rj9I7 z=4^&-%jf6)1Rovr6a+G*V;6K^hSCA=Ogp1!4460yg}F1NOid(!JRhOE^TW>cp{MYv zS~SfMtFY1mm&ommOTzokM%tymu*q#$^LV*<1IzNZ?)veIHny!Lq0_r-g|i{ApZy|l zwOYg+?$~6TBh&4m9g#}NKMrLhKuy!n%rZ7#I*t{!Lf)QB^PY3TMQ4$FHUyoRfx|-M*R<0j<&w&scD8 zd#=Y2t>5VZYXO-UCuG@6I4?u|vAmO7&!7##x#N9R+TT+haHli?wFZXIg~ zk_dRW@$rL5*R;b^2GGc0H#@rHOA?lofVUo#7*Gl8O`ZzeETPP$%+&GSnF1KZwe1=5VV((;Ut-aN&v672bYSiO#d`4S(;!7YWZQKAxtqVfQnxEb> z0flyjl%=DAN58Y|l_!7!t*d)>sYBF-9!0J)7m7_ODTA1Xsg+Xe2jf18%5GckXl|T5 z6E$j^&t;={V@3CJAGvM{rJ^rszH%w?NqL1(js5B7jL%x*pD_U)c{LTe?%N~BZZLDs z^z@7@CG-e)Ra4Ey3Nm;}+%0YbiaJDcUWN*&IGx(^z%FTllXB5Cn@>DqKH$VNT=ASu zk5A@gz`svt`M5&#ooSlSItcA8W=m>`vGIS&fQZ zerTDBquA6pUgKX~??VFtc82UWFX$ud#C5!a-vF2xkY+8FZ)g;~FfSW;7k@9|yGU^t zEumNUAJu@PwJj=w@I)nJcHEza7E2r>WqpK&zkBW?8cv3+JeDPm7Woe=<$Xs#@CR*F zyThhh8zW9-EV>^lZx?B-AJQ;Ndx9=GEwHOtgVWE7^|+61PAbmWyYkaWU6_gT%%=>@7yJ*x>dfX_?5ZaQ(aV+iDWKkBpQi zN@J^V(Y^_&P34q%FQ5uB*PH+!w#B|g5+XJAK2G#js0(Gb;_#Htn*b9}lfTxs9%f8D zm8-ZBAN}lw<(XFU1^m0K+OuT_^(5O|_Y;3m?!+bMp*X2f*+s!Rm)a0jheZ^V_;uDh zWIO#+6bRN1Q?2KD{kIg#8ZLn>Oq!c}fIy{@0+mle>vzfA>{3s#DX4nFc4RjR(gK61 z`|53=CB4fdQ(q)#Mpv*0#>=jb%yF;B8=FSg+chNl&&udo+Lv`}y}!@V$|V>oS!h4T zLNcRUE1M)DC>330{`DwP1n|gQ_yDdPQRI-T-8d$8x^}7@ zICJ89g;?C+M*C&j@&Td+;lx!OLJwNy_rv>oawFh|yP(vqM)YCN?7FUyee7v;XY#=T z$mkvvC2-+QYY>b!V-u??>y!uRBHYfpDGlkz>I}|J3CPWc4@d4Y@s{w3KyOS`(7&fIStgOUue~t!Ux4)j z=ljE`=+3QJEoJ3{JRse{wLI>|nz$3H@J%8o{oSw`mec5`dt`EK}wpcz5tJaV;Z8m|V~-S)Q^E zuM?`-XSh_7`D}mA0W)_tgabF+6y{Zc6-$(DLE2Ny^RZ-u-p!QL>~^z5HhK7Oja5wp zA(aHA{L0kuh{&VQIaM;fAejQM0N)0hXVTNA;b`OJddr=e=#KrLnRL%tfdyT@<19=Z zQ1+}7T0LHjbk$uVpLVF(+}x z528iw!u>j_sUClH>SA{1@8VOAYjl0vKOZGUK52(}_+u)rk#&kRZ`W=Sq(R!?nAJ8_nA!<~+HrqCAugnBERtY0Jbl zR~@|%_Qtqo2Keq28>$@`CZ^oqkaJ?(@Ds*uEXjQ4g?Q!MhD&$x!G}FcA9^0CzT!IU zvn!S@2MPOg%C4=#z7ja(sSxTKm}@&+*x2xGJ9>A)m;B%!ll~Ih$X^Im-I)!OF*Qh; z5IPd|WlRW<7_*AveR4~KAkKLX$cvlG!KP}TUU?S_G1zxiL(M=x3=Ul)k4qj`6I~P7 ztFR-n1UkjQt8a}J@9LX__vS>yKSAljs1@l;B12Xi_a(A5s{auxzJk5_D4sv^j~0m7-En?}L_uvYivr}-NEKKZUQoSf3gGMmIh&WG z&#V3Fa&y0@jNc)&hl=`d_#shiF;Hcv{&9CKsmudXq|;PxL%ND*oV9Uop*ts0cQ$JT z;%{yvK-v;!>@rsO_V`DGQ~xf)A2TzLMj1Z7qBV-G9+jia|91rO9Ywj%Xm&i&Gso>1 z7zbS@aFCa;8m?Yn`O-_mr{DB1_4)(pHn?Kmsed5>WoR%9eWF)aBIn#r9qIBD&_4 z6>2IFBKkg2XD1e9#h;YM)+gu;x@q;9`zuyhMy-DD@5M<1B|bTiT+zx#{%~>vnJx~h0GI9; z2J+FTpcwK4Fh2nB8@&t3%;ggIEO_VATSD~B+!0ee{O~ViG2+ptFC!y@rhpT`-dA4m zy_eE575K4TfcW=_5nk$e{CjyHen~7L>OZE71&TxYhUvIRIt`T-P?wYG1{)81#sO@M zJ}dl~Sen1sh`_rkXRy6Tz+c^?>%J3OKeN{fF_+Q;UxWn-WJjquy|$dF-FKFqo&uGJ zuOIj|n5SL^H;vk-2s5rghctjIy_DoL4HA=CyTs6f-DzT^tFcISI+6H|yI=^+@7(j- zmbZ1y-8OS{@2m5d;k9nUVli+Id~|S2BZj8GU+hqca)Q|aV*xq^((VpKzu4Q7S-$@Y z;K*{x8P-IH%S6Xdm&&ZzlRU z6x*oVb)e5fZNs+o+q?H1)01|48}%=08FbJS>-?t8lSk@Ze7dv}1?$k*NZ>2wpfHrehH(Ys^7|YRxyO@#x zV%j$Q2&@Pe!8#rYEtg>JQGm1O>bygn^1NI2PhyAWTBA;91z&qID|ACve}n}Y8in`q zcxvxqp})b)tXTuZUgC2S3i0Y>q=P155o>wVUni*<1nU%>3;@IUH@lB|`CHBXmwp7P z;VXqsu8x&X#&7CNHo>AeS-ZWg8%LPG%eR#Ee)OQChwj)iuvQD`dmkb3j5xmuJyyCZ z=XgC<-q#+%cFx6_e%Bm(o_S&)e6~hrulqgcWfn*5 zdQF9H+Y4htwt!E>Os%(tXw>CRgGPUwi{$Z=zf=CaX-`4tA=lf6@2Y+b>o~Dft{A<w!(L~3J9ZRcClCa>T=(4fKdaCQ{AEZ$*Q^2RVH}JB zuGhfTXTfZvjK$rUhTD~f(;*6|bu@#iGp=C`QHG}rCV$Kmz7Uao@tw=we){p89IX1u zn+=Zsd=WOXCaI|tA^1b_i%2`y=2TKCGf1q-1iIkoh;C3%w1AM2txvxBUQy4UoSV+P z95{0(Dc^`yu4F0{ToV~iV)<5teE&o^@(1w0fwFjLWd7ptlw&B*GhbwW@65k=$r!;5 zClsr;nOL}}^#rJssDW*9M$+3nZ0|8w-b#%X5pH#xp+6KxxckMg<>pW&maE&QN?+q_#R` z9n*muTL*{yL#8sGUf%$OC%n^1?sreDM~<|}v%+4#6dPZU?-v(nPH5Iv8=_N0)o?iB zzZ%$5bTW&0a;vYtMSyOYEWpl4Qd&?&&b9lc{A(kUtd&Sk(4Wlzt59|ql*&P2jl;RfSOt$uzQL`|DUjU}_fpo%co157cH zoqV;rG-pQf>doCl@33=r&<~&Zc2Rm(o&Qv^30++7qRh>=B)n&X2Ru2>uX+#i^(Z9U zP9I{{crgiS|Ih$F#(-U`fNn%jYl%;}`TP5f)Q#G6oc z=cnVZy!Zz)MjjzEdTu)XzNmQg+_EX%sZp{^8+|uSPm)OR`LFCZy4S;DP?Xr{1WNHk`Su4X zJAr@kC?{q3ZwTz-G7xI1*wY@fXq4$_0yY&Hk;Y;Jz96ag>p2C2UQ$L=S6dPA{xW?oN90VG&kYP-U}z-8|*O`ah0PL*N>nSYxr>C z5Q<`(S*oBDggzZN!`6P~`=_qwX?^~>n}@on;}KPTyq({Bita1czA7+Gt+bcd!fa7q zKkC6BwuYPw5X#Xm!QyUpQU9gtEE+5OUsihJ6R;tLZ_L`PY!2>Cr=cb4o_o7{H$uKL z!J^?~Ehp+ydrD|)zVwYC+Lp1eei$aLZR-`St;Zr}0fNlGqcW3CR=g&R`i^XZp`9I#-gRv+nuHP zq)L)yO+U4~BjTfR#qoBaE>4r@H2*#7zh)%7b+E@b&~4ru^%Rr`1QQ{MY2?S z61wDtBZ+n5{_T)5HfG=Pe?8;A?AOn6YR_+DGxo!X+$daeh==iVuS0JO$a{uRG@}Yf zTp+4B1JYRm>K}}YLU&zX*fF<>;0XSaX6$m>FQ=}LU@ENA`)a~T6&MnXY%(DA*f)${ zHKppgB?fc8?edQ&RMzOlD+Fbu)+9IO&v6L6eFcJZ21>+6Z{8BsF?;zOT%B-jBmQ?D zHGU}L1}5fzgNp+9q=XtNm+wDuB4+#i(f&6GU_YL(g;}D!o=RnSFlB-5)jusGM{@bSu*TVDN9zA(p z!pYD7kedEiY<_EY?u`c)J!yfkz%5@?#mlI=J}~S8)b7E{?Iix`I;$3ojD5&Kv>o8+ zhmS>^{>rS4Nqk(5v5DD^K)$Pff*(TwPtazLJRzN@FdQD73^M(rAA#}dX zOxTO%G-JqKtnaalRcJ|aGWehXLhAC;aw2D~n2apko8+~H6}{ZgQuTi!q1>&%#i+I+ z8D>xr#cZ9u@gZc&hAuLBJdF=P<-oKvCq|2l(U}nO`+}0<>;wJl^lF5W|9MBz1+Zs+ zuCv6aZ3$vfD;)!xs0Dpt1a^AZ>;6J?%Hj^ZOLz50d3QIz1dZm@4QCQ`W?@t0-d`8lQG&9_Oi`) z)v|2P-o&QjFTb9Lo=}b1>WOKDLX%I2j4ZW3(z0v&wCqxZ4e>2Tu>^T)&@>EGTO7`u#Ea=y$ zvw8~cSmb`lr{Tg{zXH!QXgsbfPbye6wt0ALTB=s9!LvP0hnj2t5QHI>`Y1}n6@+B* zaO+{|mPH#)qM^(;$^_W3dWA4PNZ=*{uc2H zdo8wpoF_DFqeL~#hJ~9|Uh%6rvuf%`9}|pa!~7?Kh#rT8<9D5eC3X`1d7>|meI91g zG*|t3`s=nNSrhEH9+Ic!EI%vCH8Rb@9@O}5C2G`&-rE)*mQ&RlFtf+h27Q~(unl(< z#y-gvZGjGl2ZiEekJQ_Rqb_2%XY&iltOi3i5t|zo6{{v+33qHczuzAuk>My&U`%-H z*(;Eq6JFD_n(K<-s^P*?M;O$=03VS+lj)8-cN=>KXU~COKr*<(hC_ad)c9|Sx0;Vs zG5bo_as7ZT7@5ep+~rm4e;1mCIsHi{?|MnmAljCDD&N22hNQCdGA$4c4V!)BTu~X< zQMGT3UgDk38@>f|9e;Cx5*YO@@m2Jr$1wh<9S38JZ2OcZmz2ew4hlqu?sqDEgMc1AR?)?LU!eCK@Fy zgn8X(&LmO0Zx_n#KmxXcv6b)NdeP`L+0wPpe})s4=eDQcQ2m8~2L+NmkFvvv4qNc- z2$*^FbKQg`q*Sg9uyI<*pY)Amaj7ejj9vVxoNKYonL5FMHL`X)(#L-831;WobgZT^ zKwjt@q4rXu_YIZx#CNZO)qCk*PF0%7baju*XI5ny!ZP)U*DDB%vnCHosn*;WGM37B z)3p|Hr!o`LMq_&|-UaYZXn&$JQr`|H-c=KZ8!n)peZ7$YvOm{4Ru3Sk_oHn)d?gZC z<^B}5c@#WXbua8DdRRoZq1hc=|LT_Ju$6Mnv4(H=TlDwum`&ty#?c*T#D04&HSU6| zfU$O%7sCOwrI^)89?o{0UHq}**X}$AE{Bbw4Vg{mzmU>5ZwmjISV2yHrfCgMrUm^c zdSX*n3p_;E0P2hWl4?Cd`AokD&hr)^EM;BUw%?dNMSQ^At~2!$O`Pa z6h}hYO+D8G3uZ4@YII5VoYEPZbC400pJ!)9UseoA(P^>C{-^YTC~2Eq8=T%DEdJ$m zfN(4s^@(VDo&WyzD{U1=szt8ez{wftw&}}fWrfBLr;g=xUerqDnj~WuaT?Ax(An$s zju&81^4*>Ea?}9JpUqcqy1Z0R@VyNp5dELz?>&CWkeaHO$lEQv)$p0#;hC6~5e&~V_ z_V9&SkKUa+J-;1$>+1(L&W}f*Y<@5|$Bc5LhwQQZPojroYW)Dn%{XgPLe?0U{lA(C z7QF8JF2G|7Apu2cHr=?71yMOTAPopGQBiw-8M49|bQSdRsGgU^tA+R)ipqVZ^P_-h zS=rH{w)|6=1HV)Yorq5SJD*)rTHw(~;UN|Qh18}B)nk0}5$0a_{yd#Gw`U<8%{dHP zA(}vT0X-&s=XA%Ogf!1tSXzsxqeCbREcjZ+!=yl0wp=Uf!qmV~g-sn#ixa>GN74 zh`2P~>a;|cIY_N6`ufTRGG_c~1`Y7QZFXp?mak-=)1%djxOrrmI?&Y5(3r=>M842* zyn1C*M|?!`9K`D7jxW{Nv(#GDOI;_o zGvJNJBB&b~fe2EruYT^_VFk~?zdGRkM488)*oejkXV>iF{If35o-d!ckD>O6q4&J+ zvs0#gf&GB856KHm=4(7(CYydJ!peCA@CJ!86?}9$H6ar5<$~(0o~&U{P#ex7c@#eueNji;)SSJM8SCln{DBXu3o%Qpgfu<*^fC z{rP#8(O*c(I3w#_>(A4nHvzxLuy4cJz`Lw74?NH46c0n79U_iW?{+r_hiO$|9&g@^ z#Z+GkEOy)usVZ=z9*qwlpBS@k;el@~2JmqXJiHD)CqFdYY?yZyoq3VSO-hdAP8U7# z2nF~~K6mjl(pR-0R(!B3B_wW5z<(wXc^|)>?3vt4cq_IbYa4+z=*jTrd&SWQ6*}dX z>Af~U=0-0ot!)^fK}9~gy?yznx*6_d0n&|*(xImnHo^{m(PaWI6S`&==KjibH)eiK znT0#*>@iPc((@x{>1wp9M8LYlQ6_#Dq+8Y1wLp9;<_8#Jk8DUh)yI2UKS7$ob?rEw zwR;DMtWddCXiU46JvdcuthT!fS8mh}{6yQ(V7PgRCM+?2;yi^4;Cm?y?|s!a{8dyz z2O*pT^!w~1h?-Y{bpk@+UM3xRNj^|+vr8@C8;-;S4rd&G_Q!;88!H|<5-iu|I;(+jJ z;Q@SXN*_LnI?Kth#b?I8m%JYcew_p{*F2bea$IBu{=Q?*o?R2lju)TpKpeViTE{>w z!%3k_jpHh~s=w9-`!xqfh?N1=N5)C3uqLt3eY@wd{vzsE(K=O+mcHMNt+vD}g@DB9w6`EGj!`t0>F;-Fp(db1J!!1Kvr&>MY`Jkvz&yN$BR&SXVU* zys{m(Bl!~nP@y?VySxGnuN;nZ-fz5N2Ud(>(Ii+K*Qs%2|jPx(Hlzz-U_`@e)yw0WXlIqIX zl9}D=(&hNG^Cr6XJK7I6=BK?qnx?u;{NY=Qy@cN3DflZFlcE(`xx>95lHOf#qpOTH zsUY6k4NFvKndP#sE*_^QNl~-!zF1u`!lnh~9ZB~26ZmZPu;B}U{m%jNxL4~1ZJY#V z{)M?pPA*Q)E&?aLJ|=w_w?i+3=Xr*eRD-sFGK%CQ?;q2l%>EN=3N8(Oy=%>{#gXC> zKp3JAw?sz>xdcypcH9=l#yf#9i`J2R>e0nND71zc6y8_mQfc*`4zaEB^lCdWxi`H2 z7s4QT_~r8Xjb0Ss5e9$W=>@{1`GWv|#y$ukIJ~z?w-!si$aR<)>NE?~mX_Q`<#m6Y zB&~n-=sVr|g7(`w8Z<%JB|f$9c!7~IQCw#^oH+UT0>K|H??i%0bqf_kaj@ zhdoCmzmZj3VO5G+Y@D^VwtmaI&>VKy2pg^`7t_f$@&OK|NinO>(KV`lEEfU;bY}uN z5+Nt$wgAj}B$Ykg@n)L>^cMZ{7ebr~L;We}#hfToUSlh-Ya(_&eRv}zE>7rCo?~|* zF26UAORU__zXK&7S3{B9Enj|0+!4p)veS_o2ZeE@^L<52^SDhm%6+FXe2^aOd9w8U z*h@hxAQcV{4rLvV?lJL-$6L0Q6JjehFj=PA@-B4ap?gdAV!9!+ud#1)$fezg*EDww z>pHL*(p-H8Eue!_wWdTR2~5c(1L zg^5qDlsEpf#ICV^XKQ@;;yC((33iAg`s!o6!njsbWtC31O$-*FwJAI0RcT zf;g;B^V1yev%;A;cuz7Gwy~lpmZ{Zx8~os=cv(L4zhBptyr)EUyH8!F1rclF+-~9| z9(pYA87zQ5k5n6LlQy`=C2EHs0xRRlClSDTk)K)ION&q>*}=+M(x|^U;d88F14Z88 zp0ZErkV$k(kwD)YJXR!y2Fjh@dz!|FP{p3>Vp?m#XnQC!@F_Lukuc7p1p=dD?kwN% z?-nq12*))-5fwJ8=GLe=1<4_@a`N~)kx7GAtJN$1@D6tR1hCmrZb=0eN_QkK@5OXw zcx_l-Md!=IUF=+*9>x^IlS*eXEb2;+Z3;uGJXL)C9_h(w#_lk}I*v;n$*kYZ-3Y`M z@Pnchjl#pLX(&AUyh&UjM&cKaG(&|u0w{Y+}HXb`@igomz@8&yti;G?E>lK#RY z^dw5EM0ZZTz~xk?U;*eA*JXKvN!T&Pp3H8o^fm~%t0qx0ldvJXWNkV$2^sdd_a%fQ zlE3%q@uxQ4-YN@S%x&@dc^Q=i%(fix6s&!FP8-T}LcW{F%v#Pa`vG?;C*E{2l?+BW zER~`qbVR}h@EcAsJg6E!%4rH)+aHeDH2O$|4ssK9nn>1^+yUeS$yAD1JoUZ`W)R!V zMNIMA@(~uW^%l3pp9$YWBlu zQ-m*?oGmr0F1|Z|dZ>BC)UdDUvai0S%OWmu!JhYX{$37il-f%Ve+eGzuPjkhbxe<|Whi0o3_!YVuV(D-lEx2- zgiQvX=3Bi`EBxLs4?~29;Wrx-YHRe)m^C4ww%~z0-uK}prJm#I;FfA4%XdRHxf)To6BTkm4mD^mXW0%VAGWU7Ky@?#ha^G5g(=i3Q4Cn_*hWC>l z8JYK*Qrg@#NAok(#>-V-)Q|D8&EXBJt1F%ZLtdrTrJ60rpNc;CaCWeKN>{S*HJGV^ zxePI8E;Mkflhc4aAdM0A&=Z#WcHIqiKd!RYH-KLh;=q3L` z#=)85j(pqKzQ71yp$f_gqrr(k%*drQBu31J-&RFCc0I#Ob(^6vtBpPFA$7iuv%&{9 ziHQ{<$ax_i*L~x#CC~ZC9n2y0#7Y?8ReGRdjPSMHY^ww%hWM8J=;^)IDlkK4xH0PY zhxMyz$I~wN7fW2@0(K8Sl;h;DkK2~|O4!2l&A02(3<6PET?xb}kYLXgZ@PVO%@n0_Nm0NKW z!~3pUbMVjIG))^h&W`}aCcyc46;X~AHnc;k<#H~Z=S;Ec24VOSEium6ec6bhPXa}< z&4Y(9UUcDUj;T68EG2frvwG|sPRTd~o}l$AfY>zcx;3r(`l5H`Ct7Tc?CR)0cM2~Z$_L9((qqJfQ=qrT(k9g zz%P((=v(_h+z%G?L=yf*r~W26=eyH}^GrTD)$Py~jWO1+x=m?rRQ$cCZ!?cI*6dPI zX-Un;=qNG@f8a}C;CL38Qh`r>sM=Wfl49)lFZskaf@Rm!?n!EXt7VoeTjC<`Fjw>FJ+uVQ6p&Btu^RF(QkP)l%iJDPJzYX7$7gxoPa$d^jC=cFQfYH~P$2At;u4jt8oqq1>CXCZEGZOqkbdUTF`8 z9K0SBrky#AA)+vK{r1%L9*h>ia(rDbGh`DpG-7-I^_mN}rh1H?|O>{_E-S#$2(8+|;K{-^-`OVgrYa8?J0ThEgJ>ANJhwYl8zsonMA2`ulKmv(F`2e&TfC z1?0km0*KXtNOA9nb6& zBuab;b76rI?TkQ3H5w!iQlhu)-?@gE0xDE|DGuEE919!wpwGi zes4YCm}1!vyry@>)(0Rf{F35d-s}5fGy~bRgRq*&yQ8Z&TQ)Q4cGNu+x;?>lyRL+a z!vB@MzqXXRAwDZP_8`@d!Dfx6EVM$Nkmpc#BpLhOTtPKs|3b8F?s0xW5DlsTj11L^ z_dRNF^3Ho1y$3>Za}?EdSe@F1!ND)+K^F&*TYo~=XW;|WVn0tx2QnCT24cdUcy@ok zg$;(Cpbyup3W#I>DAgP0k+@MiPWew{7&@oTx3T?#O!+x@$S)XsB+f@Ca`k#3H84%& zdl+*Dzeg(=`WeKRqAKGRYr#glybi<+j zRdNGv$ayGgbGJb(y$lrKs=Bjn2s9pW$c!~`x008&ye}Jj?hY#cr{ZDIKPe3MgKY5G z`#*u-2%5M(7ZD57PYv%V_-IzK80Le#EvcKsPWLkifZx2h7rjmVLmz%+^Sx7Ir91tz zZ*Y3GZ501GPKF3*0_(Lkf86#YLnh@kJTzBSuR8HP;UTU$YZ zhMq`0XKSd{mbchkdJ0zObmC}+LcG-pPq}kB0H<_U==^?LTgQ?wb)jYAh0y=D33kdb;bXV zJ~)5;EIyXdpdvUJ()bK=cmGXzdouwSl>uk$|J)lI_@JomnMazG6#|0`N$LP0rCNh< zaQ__tUM#_6JC6BLX3yBSXVCua6GU<5XXN|#Vrlay z0lrR5RsWdEF}yRiSIVzK!*dhI^Wx@e9n&b(hiKXA^X~X z{Z()m1_i@uLd6G-H?3Hs-2m7s$eS3nYrXn-ttQW>_{iKr{1OP_7e=!>B{IPU*|5bh zwLhQBWDKYM!q8Yks5R698aoMG>=Uvz{3vz;gTot599$Qo$$_iAiF&{4Ls)Z?(t1@d zrf$a5;Gz^DpAALx`sN7hgR-V&R`^&#SVWze+mBU-_%4j=G5$w@EF-fd@#aOzN33x5 z=8s;)q~@nx4-WF17X8)tCR->2-DXo?&eTIM78TCR9)kVXhhP8nvp?|6(M7m?ChDrE z=j7aZ?KM9FcHDwrBVf{m?mTEAlV3xHy!5{nqPPAHT5px!oJTsbomuvrkTG}e$?kR= zKhWgy#1(iO-3sVkPk;9a)SVJo)ZSJL!&n5|!;wt6^R z*nx>A6}yX9+wJ4)U}D{I6fnt(CFmh5^^N*fh;0_zn8#e1pyKa-yjZ07yusO3I?0y567qKftQJ;%=^*b zz!V&b$&HQoH8W8@C5zj#jlqf*Pvhh`I%XpDLf_1#&`Yn4hVTlTs>!^}J*(2!aT;dV zxQ75$@VU0n#t3oV6>h`SYoGR?4nf5K^RQ6Ts&D4u@OijvI-0YG{d&y)4;HIeWQTBv zJ1otk>Wn~~vjM!Z+)rFr`F@P}HfjV&Magmex_p4(cs9Hp!ca$z19I`&jw0P03z1d? ze8^2^m4`evxIs|5Mfk-GW#CN?JdamHX+yenufFZ0+pp3^?&hGsAO%Dc2L_)~rO zY;GUu6Wnn;rV52?X&uCp-XLC^c}}~89Y!m=@()VFrBu^R(TH<=2aFj!3U znNRq^r3`sI_~pKCAK3QX)w7XNbY7K{*!^@db@CmU;v@l z^p`qR>24Ow=SArkz5J0KH9E4d)Tb5XPJ-I+Avn_mQWB7O%2eAz*vG}Z%yeh>QYn`o zZYlXBkdzDK6#E$QHcVZdV`wpT&SxR90l#i!1uWCA%wA2TF_`-g zOBML{2!dUoVlJ^#Bqd}Haz@tkF?#2iE9H+1wHp2xyw%W7iL%3IF%7>A^!aD2{f-Dx1#rf`_iw5y9Tt4hEaK}or zw?tQk0QEetnWp`Hix&xAC`BTv0+yGqe`MH+w1#b}i68}5>1^*(wK=oQm8Ea$;@oZ4 zVJVL;{2SM~?t5GW2WvduErxGz!ex>#RD&?U4%(WxsBuJG_(rFDMTpG*bR_H}flX2* zmyepPvj$UiK1WZY=$c=cI2-;d#Zm_iPYd(%MwWm-_^Rvg+62UoHNA5NgD{o&{ewsbydodje4?n0H#pWIZi~!weND zL(HvnUg3Q#*rYm;qo{gjYe?$?*cr+~uA5UKQNJ}o&`IJA%??js{ci3*1C?ukQ`L^k zK(d^Q>15o4(Opus()bwP+nOej$zNB8dnyQ$vr4|fc5Xg9ft=z2C4ArsXYheM+aF11 z**#0tQPVSNB?2MLh9}0ebXQERWMQFT&T-SjJrWgh|2^`FfBS=KB61lF*%1WU#(1rD z6w~2|^Hz$4aorEWGR+6js|h*nY9-42Im=Jf79s#1-RnvHELTTtr+cX^VURWFv{3XH za*s2jdwIC+`5IwEN_P84vZG*Q*BvV0EBRJWW}$Z)&lICMXP6vT%Xuy<&Yd+Oax5T( z02}Eg*|?TGL-4@%%^O=8xkHk(8N2##^pF@%mziTA&0BKio-hOOyOsJxZ>bH8l>jjh zk^2elqG{P!z1v%Ku!+}9G=-xJAfY7JY%!8u8)~dm@1AeL(?FNeJ9ZCmJ=y7%xEd|l zC-e>$eh~E>oZ}RL>0cY>zU(cq*sY6tfDOeooK#4sU-ZxTVz#K-7Jp$Zn;glOcSXum zE`%JP#vL^Bd?C56p52Wd7f8wzr`|dc5+tS`LfFk{08D)k)WvNt;-A~ssn`vu*yLH~ z5}wE#F*Tw~rdLNxxuf3I2JmD0!Gx%p03Hc&$FWr=yt<(#^(c|6r%FVTqx$Xti@$k{ z`=G|^DlkX3%giX$XOai5&6$qE#B&QOR+worHX6TpAo0%FbAK$nGE%6{u5Uy^V)hd&SvJ*_}!lTI<^2oC6N=dF9-;?TQ7}E$+7v7g#qpZ1HumU|YUs5)GY3-( zI$oZT|5nMjSz<#G4CEO9UjWb)FY5>umwP0rMo)5}fAy+gk+d61%;f&-jv;fErB zy#^14Q0@(LsW~0OMi=!Y)|?&y(Bb?3eCNLTKfnqsKWP)IGQ>ZKS3Tn`K_Kwt=$PFx z5sdmCzo0d&*zCCa3gP^Da7@;=x#*@s4_vP${dN8lzE0OJ<*r zd8ALh?V4QY=qWLwB>S|`hlK+qo|N`~86vOfR_5fT6$~u!wMRKK&{{URl z?Ee5~pQSckPfxZun(_$Gqeum3&*J?C+~Kd$kNXN+`3ghS<9vT9ZD!saU?drT{7FCI zT!VE0^se(!&~AKPe06I%;!8OcEJjViusA0e_02jjhN+NlH8YPyiyx^p8mT0#a7r_u zr7E5Y^{-5ez&bQ1FD1;rp_~Ew3cm-1G&pcl#x}?I$#3Rp4``9(tH?EC8#|ki^)}N< z{^Ao}#}1oeZ~msz2>$@wj0(7as0TrT^rFG-e2*s4wA;-$Q?}G^t)+s_2j3))xW^oE z*RCtCpU0XcA8}`!{mAkB$g7?;!gx~i)a)Pl_^%^zxs%d>Ui!N``Mx8(gibFd!qMMx*+FW~j@o>T{9i z>K9B1hAZ9D3*JNMz3# z{ON|H_b;t;-ZxP%g)X>%KPw}DmCb~&*58Ac`3OMK8$htVz+*7I2FhIIJhsP-COlB&z`-AAK+_$vn$^O)f}?iY3bC{ zMidiLZ3Ehnl^l^ki1+^hlTHnR!Tl;ZuWao`XSjkd`sm<)I?bQOdL6OD>Jc&j0H$EK z@)Qou?1b?o2KU3a(GYXxmmgL6hw`r>#{#`B>&Kcpt16`Pf-rWb2kL7g&%mpD40k_n z*$k>36i1R2@;S|aOE!b$TAVv_NTwWauTZ!6d!;J_EY~ug;J5?y6{Q!0G#D5#u|^~N z?9KemG$&CWIC977#a@Ea>gNUA5n1CcDHqVkAra54{nBmA200st@tbG|pz*6+hp zxLiHC5`&LU59m!6u)U`8=0BB02dznv2l*7q7tTT0 zkHVO4lyp-{SPp<^^Qf829y9q+2^oGTv^u_pac-%9hf%!`xaZQmf1H&g1Xs8i$v<#@ zCcLY~dQsB#xiGkjW9BEPJxAwK&8fR+V4e*e=k=mN+;^lNo|GCAflJqeOhe8EDCMe3 zLqdSquGhdisE+DQE@B9i=ZkUvA=G{&n&U{x_o*%JCAGPV;ua|^Y#mN}ifNN5-B|Z9 z4l%|9DMEphw%{Lsd*|y-+D>@>RN$k&KLJZ5u)v$7WJMj>fFG>@Mk7A|0G&Hy_5<;% z6Zn%wwgkzj+i}?>41Xb-&6~%%93bqHS%~c%NBZKHgS4MRlkv`m)*6VvjWKUyI?yTXuH+K@pA_fInR3FgN zw_{~1FL?8nApI%BAhP~d>#%q;!`9$p$IK(UyEcDZR)kt+nQFkpV{I87)+Gju3)-W` zZS5{@8xY&gE`PX%zm;gi;hk!Kxu?oM-@^X@I`#x9*kjtBG1+M44{ZA$T?c^mwkrPs zxq*QM68wWT_zLNDe-&T&f60R9Pgz}%e)(m>vG3Zt@V>aL&k*RbYkE|c#{y6{MBm+R z--SC{VmbMrypspwF@IFt*+q6Ixzum&#%H{^m()C@{{UL98=RhKVU9;iOnXo}56(FJ zjZ0~9HI3wVR_(G_n{t|j0!9yB)GHB4XSL{hta|2|9n@t*;}R(9t=v|hlslU7zYS~B z=vtVQar-QoSy$WF>MPeGnQkFjQcdXNDp#QuX`IuAnKzdGfJXdl$-GZ>_OB6Lw(P1m zmN@B-G5O}ZIQ(~OcX=J9rIhb1t+97udHl^+kKz5JIeWYL1k1odHv){`&{Oi~viWr6?jZk_jfl`6!w1w?Fk1C788r;MF zJoXP)a6heFx6>!^h1@!>ps~uMF~=Nj&f+?pj+oEqUX~Pht_R{R!1L@aLHnxGF#3=O z@-$c!+?|F`@fvLHgHJ_1uO@$x6`ePZ^@&N@_ISP4e?0#HGHaM4EXVSv0gTfvMH-WM zr(B&|cB3-?0M{}T`C_xBy}P*2pK~;%{{VhM-_D@}jCRE+1hC?Pq%J^z!kWW9x>5XQ zoJlwXts$Pr;phxL9Mj_f0puy^>NEXoOhh}HuWk%h(L@gjfkr)rNsfN;{OCE@{{Sg7 z&J80Xub0gC7m4Z!B%fAkiwHX|4nCiMOhfPg6IN%j8#3TqSk(r)C_v3DNK25Cs# zGf}%`z#olG+|nA_dyHT|Wq%=ZvRKk1}^R($>|(IDXJF){xD zrg?wmng*}f)aS4!v-OmB(QnrP?zeG|_zA3;{C}iG#737A`>FsxQ&~5jKS|?gVz4_O zf8{LlbRR$|Hd2JU97aA-QMW8dwR&700n>rZvRujSkO%UuJ8uYRP_{*avwFx`znP&U zNmPmBt@njZ4VB&35L(SH5Aa4$@~>`-O4F^5V6(T3j_DGLv=KV=_7uqWhmPC$XIYsS zZG@|V{CHpIS}^z*SCnPEnDhPSB>sZEe@|-m6yUh+OO!pcJnr5ruK?N0aN#cg)arx+ zP$2-Gyyw5AQ=j4%uHcAawvRmy(n$QxbzVKU^L#HPm>;>38}mDVt$9h$T=7FH2}xa> zQ+U5zoDkRUp!P)z{Do%Csoz|NS+8y+8R+tpRXS#l0W^zA25`Xo)A81tS2)E#f2}4` z7&`tH>z)j{`%i{#c_rfA8)LQ)AE6cGEBCN{Yrpt;d;5#aM&}H&DEf>aD`{g>S;0R<24w|bG50!WB&lHRAFJ@0659|3OwRJf{p42Z2Qn$k8hx$Lt5ecMt>Tw za^GpTmI-$Gav@d+(2P`!%*Vgte`%W;kMPnhBzT>~FKKrzyMwwmE6AuDgIzC;tPP&N z((S_BC~$rH8s=o=1MAk8Q=vPnhBJ9E^+}GhWBxyYs2|e$sF<;WjxVe;+dNf0a@( zs=AuNSFTB;4ne+0BmQ}#H|ho`1fN4>M0*e`nDN$*Z!}YOyvu9z0K8X%{!bsV2WsLo}7yGy#vB}4x^<( zd|{G7D&(U|enZ@RxanO49vsl^NAC2<54*>>{{Z9JrDEMgc*3hYua>2W>;`K5Iv%TV z!^+d{TRjh!K>W>nGNdr5SfWHKledn{VUQ2do4IA@5kXyMG4lC#WkL#;JpTEEaywK^8-4`8Nvg>BM0eR z#m|nl*&F4aI8^qIG5vF1vvF?~)wGuKsA%L;tO)82c#g5A%cbg97Bc7eY<4&Im$9Vu z9X6%DJ%oivEY=}M!V9)^Yp56y$xyZ-=(+R^#6dEEDCGy1Rft^<`MRMz)W+1*8R3zU{73<%?z z7J`&{k?$fg-VA_f0d$OQjGdyqTB$^C=&D1 zoyB58Sa!&yF2l7(T$9#~%zudDkXYe-d!X(g+V<))Ftey!XVJfwro`#qolbz`$f46#0K@6-_l;jcA8cEnwjn$67!8Qi##3?CF$pV=PJpt$|)OLEc zaQ^@g;41~)#t3F$fxU-6&bvHr9OV8rsm(pfHb?DB0(w+mDvp#125<%_BE;W7DK{`Z zDl;MNicQU)8x&kDNxb?2UR&c^lX2o%RGf%WP-E$z=El7^fAz_7e+u!vO5k1Uw|5}q zNh>n_GyeeUq-#xTQDK9g!jPYok7`!WPg;zVkEy0D;gpDgr8al zKOZ$ur$i^#Y@zKW=%?{vP@bdPn$z&CK7Wer6VZ$QN>B8pf?6ZjSYUGB(wpBosREwn zfCBZ!GnkBwf1aO}AsILRhi^NkPrFk zQbT2TbDtvCX@A^|xAL!SgG|%yNA7Iki~Y!y8nP973Zgxs<4|~8Teu;YPm~TbzYF~9 zS|0=I(sKSxS?U>yKcKHs3ci`AY|mjytB18{^SJ&U%E~wc=1f%_02z(COAu(>QtY_y6oo${gqE-RbS*Q zI&Dt&<#9FK@&nnVCaWF~UrJ~IfIX-+vO?sLKdlM(h!l&1PEqq_frD_gi^u0ggXN@N znWfM=p6zchn{5<>A36rfKBAm|-vE17Zi_QZf1%hm(n+_EB!9Xp{tpC?)~e?-R%6E8 z{o;OtoKDfg=j%)a1C#oiaD4RX^q`RQWbB#zYBrj0?txBcIPQN+i;{Ye#L!YkXNb34 z_9eiuU@ApW!i&MB*%gp<+ii+}pZ7C-bND>iS5Q4jd{)1-0hB!PcG4J)F#B*{J^ zX}k2eFGFRZeWyN+{{YtlyxE8%y6evzPph!8y|jUBWp!CXmfRO3kaOGVU7Q{d&|o3I zv(eA{Y|cL-aYp5-a;r1PRf*>vD%>^~mo5#xtn!ccBPaP+w85w8_J{o*#(&-;>XE3a zjDtKbXs~-vBgkOzp1D35H2D-~_{dM@Yfdi!>hfWo?c(+>Ngt4}O;S%gd8ZA>pv4@b z_N?Hc_;A<;eMEbNkNW1M)U7W36{By`t{LN&U*7q^Hqu7~eqM&V&Az|Nsp}RCsp%J1 zXE~NK7mVQb9ewddiS~`XPk$u2@ou|00reR|{{Yi46ZrvI(_dZOljq$}Fa30oxAUl` zjnSGn8(ucrN4+<{)}-jN=r7T7rn_bf_vLw`PRF0#}1pZZ-KaO-LLB-R|-jT+CsKqS@XV~8;%sUFh@h*fljWD8P z?J<1OG0$G(@vN(lh}Mh$03P-;$^QEV{#mTMkBGO={-(|dv;Fd4{3$kzj3$moL}YeX zQmm&09-xYWxPNR{ZQ-G(c#8hx`%2jw`J2pLq^h{@#(LLrZ=z||#57ucx)Iz)x%}xQ zX(^?l;*r{1&fmDVmQ(2(7XDSE2ZeRZk~V3x0ob?+kIxnDN~jkY!1Nqae5Zj`V?Stl xWxs&6i4=LJ-Y@r`C-fDk2gA2G^Y6Z)BmSiS07~>Bv Date: Wed, 10 Jul 2024 09:30:20 -0700 Subject: [PATCH 11/15] Increase tolerances to accomodate CI on macos. --- example/src/systemTest/java/frc/robot/SystemTestRobot.java | 2 +- .../src/systemTest/java/frc/robot/PWMMotorControllerTest.java | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/example/src/systemTest/java/frc/robot/SystemTestRobot.java b/example/src/systemTest/java/frc/robot/SystemTestRobot.java index 470e4299..70ebcec1 100644 --- a/example/src/systemTest/java/frc/robot/SystemTestRobot.java +++ b/example/src/systemTest/java/frc/robot/SystemTestRobot.java @@ -79,7 +79,7 @@ void testCanBeRotatedInPlaceInTeleop() throws Exception { 0.1, "Robot close to target velocity"); assertEquals(63.9, Units.radiansToDegrees( s.angularVelocity("ROBOT").getAngle()), - 2.0, "Robot close to target angular velocity"); + 5.0, "Robot close to target angular velocity"); assertEquals(0.0, new Translation3d(s.angularVelocity("ROBOT").getAxis()) .getDistance(new Translation3d(0, 0, 1)), diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index 383ac9f4..ad20bcd4 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -162,7 +162,7 @@ private void assertShaftCorrectAtSecs(DCMotor gearMotor, double moiKgM2, double tSecs) { // TODO: Make sim accurate enough that this can be less than 1*simStepSizeSecs // (https://github.com/DeepBlueRobotics/DeepBlueSim/issues/101) - double jitterSecs = 4 * simStepSizeSecs; + double jitterSecs = 5 * simStepSizeSecs; double expectedEarlierSpeedRadPerSec = expectedSpeedRadPerSec(gearMotor, moiKgM2, tSecs - jitterSecs); double expectedLaterSpeedRadPerSec = @@ -190,7 +190,7 @@ private void assertShaftCorrectAtSecs(DCMotor gearMotor, double moiKgM2, expectedAngleRadians, actualAngleRadians, toleranceRadians, 0, 2 * Math.PI), - "Shaft not close enought to target rotation. Expected %g +/- %g radians, but got %g radians." + "Shaft not close enough to target rotation. Expected %g +/- %g radians, but got %g radians." .formatted(expectedAngleRadians, toleranceRadians, actualAngleRadians)); } From d91b55cb57ece973347e9a134883798173e92bc7 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Wed, 10 Jul 2024 14:00:47 -0700 Subject: [PATCH 12/15] Measure the actual time constant and assert that is close to the theoretical one,. This should be less flaky since we make the measurements well after the robot code changes the desired speed. --- .../frc/robot/PWMMotorControllerTest.java | 37 +++++++++++++++++++ 1 file changed, 37 insertions(+) diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index ad20bcd4..ff134686 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -215,6 +215,12 @@ private double computeFlywheelThickness(DCMotor gearMotor, * Math.PI * Math.pow(flywheelRadiusMeters, 4)); } + private static record Measurement(double simTimeSec, + double speedRadPerSec) { + } + + private Measurement m1, m2; + @Test void testShaftRotatesInAutonomous() throws Exception { // To ensure we the flywheel doesn't spin or accelerate too fast... @@ -256,15 +262,46 @@ void testShaftRotatesInAutonomous() throws Exception { "robotTime = {0}, simTimeSec = {1}, speedRadPerSec = {2}", s.getRobotTimeSec(), s.getSimTimeSec(), s.angularVelocity("SHAFT").getAngle()); + }).atSec(5 * simStepSizeSecs, s -> { + m1 = new Measurement(s.getSimTimeSec(), + s.angularVelocity("SHAFT").getAngle()); }).atSec(1.0, s -> { + m2 = new Measurement(s.getSimTimeSec(), + s.angularVelocity("SHAFT").getAngle()); + assertCorrectTimeConstant(gearMotor, moiKgM2, 0.5); assertShaftCorrectAtSecs(gearMotor, moiKgM2, s.angularVelocity("SHAFT").getAngle(), s.rotation("SHAFT").getZ(), s.getRobotTimeSec()); + }).atSec(2.0 + 5 * simStepSizeSecs, s -> { + m1 = new Measurement(s.getSimTimeSec(), + s.angularVelocity("SHAFT").getAngle()); }).atSec(3.0, s -> { + m2 = new Measurement(s.getSimTimeSec(), + s.angularVelocity("SHAFT").getAngle()); + assertCorrectTimeConstant(gearMotor, moiKgM2, 0.0); assertShaftCorrectAtSecs(gearMotor, moiKgM2, s.angularVelocity("SHAFT").getAngle(), s.rotation("SHAFT").getZ(), s.getRobotTimeSec()); }).run(); } } + + private void assertCorrectTimeConstant(DCMotor gearMotor, double moiKgM2, + double throttle) { + var targetSpeedRadPerSec = throttle * gearMotor.nominalVoltageVolts + * gearMotor.KvRadPerSecPerVolt; + // Use the 2 measurements to measure the time constant. + // w(t) = w_f + (w_0 - w_f) * exp(-t/t_c) + // Let w'(t) = w(t) - w_f = (w_0 - w_f) * exp(-t/t_c) + // w'(t1) = (w_0 - w_f) * exp(-t1/t_c) + // w'(t2) = (w_0 - w_f) * exp(-t2/t_c) + // w'(t2)/w'(t1) = exp((t1-t2)/t_c) + // ln(w'(t2)/w'(t1)) = (t1-t2)/t_c + // t_c = (t1-t2)/ln(w'(t2)/w'(t1)) + var actualTimeConstantSecs = (m1.simTimeSec() - m2.simTimeSec()) + / (Math.log((m2.speedRadPerSec() - targetSpeedRadPerSec) + / (m1.speedRadPerSec() - targetSpeedRadPerSec))); + assertEquals(computeTimeConstantSecs(gearMotor, moiKgM2), + actualTimeConstantSecs, 0.02, "Time constant incorrect"); + } } From 9fdcb6efdbe60aeb05fbdcf513552cf10465410d Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Wed, 10 Jul 2024 14:24:01 -0700 Subject: [PATCH 13/15] Change flywheel thickness to correspond to a time constant of exactly 1 by using updated math. --- .../dist/worlds/.PWMMotorController.jpg | Bin 61662 -> 62956 bytes .../dist/worlds/PWMMotorController.wbt | 2 +- .../frc/robot/PWMMotorControllerTest.java | 17 ++++++++--------- 3 files changed, 9 insertions(+), 10 deletions(-) diff --git a/plugin/controller/src/webotsFolder/dist/worlds/.PWMMotorController.jpg b/plugin/controller/src/webotsFolder/dist/worlds/.PWMMotorController.jpg index f1a50ddf18307f30401d0f09122f9c00229878e4..7a279738df773fe87c8aabd65c7a1fc8fc410447 100644 GIT binary patch literal 62956 zcmbTeWmH>T*ftmn6ew0oaY>QlQmi;Zin~*Sv^bIE!KY_t=l;#Ft#52@ZSU;v?Vp`rTwYz@+}_>)R~H(p z&j0iHUxocY>LNnb^$Y_89RusXy3n3^px)?27?^ZC&tFMtVtsZZrsw^R{aQLEr@9M= zflup{#LRi(1t}x{+S{}LO8cM6{@)e$|5suEcU|)UJajbF;Gq)%K!9Dtk*;Vi z{NKU1`CsfHksrA^m>b5ez~T8Y>=>HTfI?@_jmfql{*gUm=Z}lL_aT4T8&CVLBeVAa zMs`G;@B!a!i-b!PzR4ykN0*sR&AA>}r}ttJ*RKKOWeQSqy6HEK9TviJsRr8G^aPMH zrv5EBz5(Qf$C^J>3tsi<#H|w~ceqnEJ^{WJBkO{_l3S8~PW4=m6fc_OcMFrf44k(R z-b+W=THFRhp8y=?N73$h22TJ@ut(~bWuEG~7QyF#7ZMFpJa~2}#9-%kbx?vYEhEsc zE62sAXW3l8CxV$_Zp}j4j=+cNox3kqa zkCx~sK;6bYnt{Zd_rEDRLivq)z7DFy@+?YUql@z)Fwu>wK16M~8nYV26fQU%H1*~q zEp&@l8-MyA|070BKWp<=CpzG>b}w)lyRl$@ENx4gjk6wY&3FPVN2g*QF6{dVOdq-@ zPAVv1>O|+oLJ6)md2L17H%|nw-KN?i3}SH588@#hR?rs4oXW&|T9dP7W@DO8K`OJ^ zLtge|yo=pgCr!Y=-+d_=hBi(!+qsvfEGUo{Y)=3_eX`E^*~GtRJulH2+w#8O>gOm| z?ePR;sEwOH)C4@1iClo|;73K(la+makJT}h03Dz7m?$iMd^I`Us>sWBka}ZX*!;FS zlYr`+F8=q3tK!Yui2N*e73QVFfy?sVTWI;vk5PN_8)s;AS@ffD8|c6>NBu@4>onW_ z+mHm^vcnz6C*0kSp%uHn!bJy~eWj+d3`Rz|gM*dQ5#PVxnbm^VHs5ugkCimQwFbUO ze#M%p1+7WIV+Eq9AO;gUY@0ltz(};bTY_#7)-KTnA~PQ~7KhN3GUc2-B0Twm1*a!~ z%D}CDrt(IH+eOVf%fJH<_tmIwQlH^r_A%TN9TCBO{u(#dc*LLIE!Y_1Nj4NE6i+_B zYH@*(bqRyfk?Vn^Qm@7c4Q1a4Tf2EYQ+MO|ylkt(*Wg9LoS95gR~mX_4)DR#puQeI zGq`NM)4y>Sg!Q z+qexx!NTMIro@Zce2_qD_7lKP78&$yD|AA!6nr}+qT8ZqL%_)Uo9d1Gz!ShEkvr)6 z+cx+v{RvQ$1MM%domZU=*cNHXEj|tW*FZYra@ASp{3zF;=++shSpa5 za|hpxd2+w)L0ACCb_?jH zVyr_eb@!N#{z}=kQBu0|y~LGMmW#*TUw5-I12|Sgj9C>vY8kE_|43t%IqXzeTN&}F zU9{w_t+DRI$;l9Noydf32|m5>UXK_0W+ZyLG{V4*RJ7lIgvxQ?sn2UyRI=B+Rkzc^ zzTn)xjQI#_M4uH>y3J2FIf50W)J&V^!;9SiyM~$@aWbDu@=B*&YuArdPwGNrHeQs_ zMJII8E_v(lJPN~;1Kw_-dQx*ocF7~{`L336LlJdi!z6viIV<{CF~R{*fvft4>T|L6 z)9NRH)qBun?DNe!Icih<>nA|PG***A$NiO+y@)!dtp{0)-`G4wSm-OuJEwFDfV|jr zsQ(+A&NcJaxZQ7r@ENPT4L=FwUohyG3PXxJUkZRd^U+)T)wWNHw&#tZZ=fgr6TlgC zHmVCHgVY4HYJ3I#(>2{>FA7*2jbm#|ji_OzzgY3x2A{D9Egoe3 z(Cu$~8F~2R^55%qs`nw}d5YLCurQo13x1_(yUXWCeD5sIPnP4okSBiv*nX>em8RL2 z7V5|aoOS()8sn;_>i%_A(I17bhT8#REz?7jxq@Fs9hb2Fl&UjQTa#dz5YC!n9pZJI zh`_e(ZoXfc{(_iVx`b2)t>h78&9w6>C+BP{Zb%`g&?L8*$;|((pOV(I+$Cb8T4dZK zpYiiFNQtMYVoTz&KuaUWI|G9)QQ|SX-M6!sO}~*vHiQVb=e5U=y4i{t(W*YwA**F9 zk;yNiFAQ;0wU)@$&)%FfOg;flN;*1qg(c|sIn|}v*AHU_XmOwV!Uq=$jjwvflgA*i)uwpMMYYkHQl`Fr8O}c7vu? zinAzR^|mg93wY&DI_&p>9Z6!3p&7wwm-o-fL|ZV*ZT6v&XaKpXjBwFqJd*9cE{TfvfnOR`z-o$}yOE22>`6p}M?WKz?^#A|!H}fWl^!SY-bQvR zhktyD7#^#$l?KLAK9(e-4J&N2g9EQ)?3?li=qCkOVaJyTg)||79o;P_*b9&r-L;Qj ztRG%?_zF^~7nAG)(xHI@5n0Rg;(K$W@RsVa#oH;_dUqMI%Hglla-IUx>LK2r2BYSW z&h}qJ4F}IMgUY-c6J;&Dq8P(?aUHHYw|{*;{o5$GH01!evRruFd!0u`!@1Lo?ZCNA zT;LTWH2)#?RDOzt;QLx6m2oW}qIAtdJ2=q5_jiUoeQoZkUMn+LM+ylqL*P5um=Mjn zR!EEHXa1918*dh!9Y2#?VKd~@;zqMkyvfT{zu5v!k+_3!cHf=zUpd|+H(m&&mEF$S z3Rc5x9lGMYvZgN0$>-9WYCLvrfb94BbT0qy!5D&SN8!33M<4tjw-H|)MbD*W5vy8m|IdBx-5b_mZlY=7m4LJlmDexvnyWNlmQxkG`KXpLr|bEb60xb(|f^gMdE^ z$DOb2caN)B*!T8c;=ALVnEv}dYoK0{t0P}FhN-{~`)KbWE+^)Q? zL~dKK!Nf5?WV}U4*U=ayQ~!KeYNY|_o!Z^Fh0g^ zACs?Io#nC!>~3~&xlz2=E#~01W*)9>g1UvIs!Yf-R0gcI_psOskbh%fFe63gR>_<$ z1E4;|N-M|NK=`Dm(v5ztY4tv-2hb9IGX}mT-rfgM-4G{uZV73$(*BXlGzbdGlcvfz z44e|9FfTBw7;T@Pi^sG6+C}@*?3b@*$!(H+^PPi+Ve=hh6x|*5&hx5~Gb}~zpJ7MH zu)Mp}zi=@xYcG37{DQg(p{`d7SeJQ{O8Twxe1f5FCBLtWoW&DR{gthVE6+y=akY7F zjoONg$%5->fTjer$2Qg&S#O9ke)mQ}3Sga-l)$v3SI~CmTQn&LC5|02zV$o)_C$~7 z*s0t`ZQyO#WwCYCI%6uSBE#nd%T3CG@UDA2gT8N$HyN-C{v&z$C{>;c*FDA>r(yCm zbcyxMerKn+@p&%ET}%!5+o@yD%w;4P${Nhh_)R~0|10XIaAIDlZWEqV3)AMobpb9) zTWtPT*A+QEq}kQB`d^nhim+n_DQ4&Hr%*GxgBxU_13VhcyPu(~WeAQ8YdOajs=Vp( z=i_}{J57DO8@EyQu(F{@#${2*M|bN}E_gpw@e=x55vdEm_362<3@Loy5e9Y{i`H2M zn$I^bZ(}F%s#C)BKCz|GFUOFJUWv*Md}fQg*EJX#R+mYgX)`a`6O44YH`2^nvo`Ar zF77i^K0`O~JyJ%&<)w(MZAdZvs^i59n4iqUmiL;S>J?$}8+}6i?13`7Sg>u<1TTTc zSiG4;@^*}q(tNJsBe-HoZs_gmTo2|4$PWby{_1gFrIteh>dJu zf`!2@eu06aqdD~bx`dPjjSk`+d)SQI7|EW#997zP%DD43C$5=$YVElp`IOzi2YQqC zS7}hD{g-nOmCq^sgW6_IPBV@pQzZEeuVdtwfJX$=YK}w)+Q2NG=ADNc5~Qvc_@Ma- zFl(&JjG96UGdwm|P+~j%_mnz67D=0vHf5y}DfXR?Oe|8FDtPYr7jngY6M>WMGCd*| zsU|SW(ZuGYo7hCgXm!V)yY2dU$@GSat3J)xggW`yzBNu~ss79j(6S})54`qP4cU$E zRa`1#_tWd=JF70CRf58Hfh%R91<2Au$t7>Z6F_8J%us;FfrZm`ju!ICqb*EQPaH5L z-i%-+EnE)JA865SQzmK882W&w^D-L%BGz457rBHf|A)NKNrE!5XY(1}pABT4D0NH; zICBT5w!XB;oW`mpMz98EtN6cJ8D4u+U9V^Uy{&rZf@E@NO;uDQ?I<;@tx>BqMbh~- zHQF~UyDf)0v^8OSH}>Y(-SRvOob#=gABtn>k8HO7493I{W!Pkh8&2fwpR?x~Iwr5i z&BP3H25wT)?ou0RBlBf$_zyIrkXlcGK(B|}8-uvxf>LNJ1+p*=vfl1}f6Z>0PRt&N zW)8Tx%oct-9eGv(cZO6sI^+s{k_^W(!A5>YoZmdvNk4E#&6p@6^%>uV!%_p z5-xN4H{T8Nuzv+@C4c>9N73Mn#lA4ze;|zNyfnI8KyT=q#z0I{?vrkP zTJ>QB`hsw{t+szQ(qo;K`0Y<@27v3BHtg^B5*Hf}Ue8wPaM5}abL21|ln%AAE=L68 zzU|FA9zY6J352V+XFV5HTtUnYArrj02@YN%mfmk#KMd;MO*j>QI416$`TfRfiX%}r z*41+9O(!}vG9fdI;3W$7!N(?0P>uNGJx!S>Seq;rZngYAG7+@?w&{>>0hHlNxPhP) zJ5){qEkzJ++q_-!Wkey(sn`D3`$xY6;1xML}mQg%YMbEW^sQenxdn~)bTs}(^mB!aRac{E{ ziP};Xs8_M^JBeDs+u3aS(+7Di+z~hC=}usFS&S#Ulv+b;$1)0thZANpC)8auGTGvK zCkpH?qb1}|FyT3m2vdl~zGJuJCfJQeEQu^`JPfto&0=nRlo+WzaPcx)TLneqCp{Uq&Nv(f?8?=YX+`z(hstbE zV;SL``g4CeHYC%WCa4)f1ogzQ_s2_E52CP35+?~NrxXF6EZOiUK$Y?9-)s{(5A*5F zh{eWp5;aq5n;2N)`bWYC9^gS3KY?v+X3N=jo;}}!JjC%K*L?9IR7mKGM9!2J0_zqd zg0{W{jS0Bka-Ha>TwzzfiCW%^m~+#ppDzBZE?9?D%wwF@Y1sjv0q z>Q&7*qFz*ZB|{&yi$epY#F+PHXjWL4`WdR@&C&<*q`Sl*ANfCKW0``kQlWjTt2YVgxe`Cxjkb+>%Jzh0p z?AN!F!^7nfi-OD_ZIh9nsU-iSf378tJ<2(7%1#R+3l?Z@QsrHRwxvNcOkiDxhgs*_ z#GvIEXn(tfHElgLtj>3mjZkZ@=(CTUbH{01-`at)pQuiddt2CBJo7FsQR=uO-M6=q zUkHy~_rQp|XHS4PcHEQ(G)mj^_Tn?=Zd$SOI0T(;7#od-JM^bft=tUiUqK6&rrWmo zEc1s;aqDk;&^Pxc=$-%$(kpA42Kz(nM<%%9CM>b<$OpD8)lO74uSxWP&kmf;on?Rz zld!$iiRx3@GKdHMVDonqW`g&z-auaskkc1e&09f9^*g7P<4F{mapxwq`2~wpslQL| zLb{Fa(@G@vpF^|@Vi;94!&Up`AD`D+-bR+7`kSckc zQ4{`fbl?y>fXr=&jl*~>V-!A!pQ{5X_ZiP5LecK(SwO3tt#^9)2PC6y(F$P`g9Qde zaLO}3u&N)ocIHIa9o3fkqw?IuuUKvC{E-bmOe`{I1;1BJ$ZS3PohW|gaNAGsleEf8 zv|ex#9+)_z^L_mpx68IjY5({H*gteIaA!y97*a~udv#gpJ!Nz9KD32;f@33_n^odC zqhDlCw>zQbZB33h?yy}uSU{ZaB-dNzR@RN`Xa{S{{(c$+#2ZSvs}U;!KL=hjFkj_K zgA*<({u9m4+O6Xdd!U}zOD-x|isS0ncs1Y9FC?`t>p(!X_6cBbpexvvs-;q^u!AUMYC+&iPKqhS zEm9Qxkld_q`y!#?ZO%~O*tg1w!_&-+I;;9+A9f=@jQ5A_n-u2I;lZE0zr+GeI@XSy z1V#m{jBuv562z$<@#V>Wx{~uWs%yhecpSHF9bLhEMe2@4y&T(4=R?@@E+tT|vfXy+;8>=dTx;omChgR!MHE#ZZvBq$55gvrq0x;a+gsDxKI9>EUDaLC zgz+wwVYR?!Cgn#0B;h1B3LzH&6UfFj#{|1Ho2BAwK zg!{H16Gkyy?^TZybIg+7vxHOZ0{|tL0@(zZpKUWqV6q=m`>&nYD|uKkagL%fom#3w z+f+aMysf(^=L*j4ZF`6aE1MfhO4;@H;d=rQK-o5Y_18$-KMLS7KHJ0_B41TJ7JmX{ zIK_FUfs-HSGdfYt@_*9=KcU{)xS`BZI^q0(P5~bvwk`|_QOo*oHeR6A3bt0#fU==( z+eTAuBH-UfU*`3(!|n#bf%oP9ii8GZ9gXKzO8R;lo$Ra>7%sAv!m53TUb0nzVluCX z_(>g!ONJYhvjgsCJrEUM1-l1MW&af0h1|bA2WrRifEUJYY^xr6E!;2_x-h=Vic&PM zxH>ue%GUt*%bB4!bKEG6N`i6FWy{v7s#Qt-l0>`Dgj5*^eDPjUj!wk#^t3v&ip;$< zA8!@x8E6O9F9cFt)~V7C1}))vVcSAui*sZQQw*tz5X`sDkS;iirNub02fqOlZybaE0*Z(TE8=IOUTfIK{i>0pC(}*0XG~00H@C=H3zq`U} z*V7(lPc8niFjZF}`Vnq|T@{&2{7|1E#k?Tg4=IMN)kgz=!jmeUafjS)L&c}cJ z{z9hBPt^i|V6&AIg_R9``qPVD9O z^i%1&DXeSciTMi*+%AJ@M6fvy?bn062ySdNhuYA7jO}(yx{t3X{H}=3Ic&n#ZTVQSTKJzJeLm+jg3$)@wz-0@rQwr#3A4Gany` z+{b(ZP-1yf#~#eXC)x0&w^A1DD$ku&y^rc}>@l2vQYA=oMj33BR5I(IE@!PR5FUwo zZ6>Z`$&g3?5VZJ&Bnjk>6xb0W%fZU+&%4*aclqKyBZ;IGd;-*lou!D$l#j*ECk#FT z+@(8)OGlty?D#h>%?F9msa)I^Zb7gBVQ+_vO3R!3 zUiphE_0u|M=3tI_N!-D-5#pgS^(m4%zN>8Eqg=5lAU5PY8e02L4ipN98n%)JUeQo0 z)GJR%avm95eyU0o5<|P4Ey_SNJwnpXLSt2*K|I4%Im)x;fq%Y|(+2EGvNq<(nT90d zA}jmXU=OnTk9P4{M2kDaQ?H@zJfO+ukVnz-zda6Vu2^MqI{x+Uz~_*vCjb{%>Ufd` zSw}KLEQ_SGqv)(_(D38S+5ykI#}wX%4b$i$88~};wtGm>vB*2`^+ka_2s5>h6>*3i z=DQaij_VUIjfdzQ{jmntqA zG*7Z+@i_g@mh$K%2`FbCVwVUe`{60hG+<-KiS}=(tSqoTS@x&1Kyu=y33-zX38~H1Q}*YB00>O4!#U zhnww&7qwPsK`A6jK4o*B{R;fyHap*!MmTC%-n_)wB`k#eh%}U&4;j6rsHk``b3F^L zX?Y(PVjl14Lh+*1lQG@34}DY7n1%z2Z-&LYueLn$68I;zovf#w)9JTQ(G%c%F*2cu zJB(k*|GEI@3E;x{7^s~zAVTf6;KY%2EC;P*-Id)|2L9kD9~gBwL0(28*kjM+a*Ay! z%WSXp7%JN<36$@|IZx zLgOzKjz%+hz94k4aJ6w(r3*BCsiY=CYfsoyp_|5QG+%tp0WE;o{(japb&}mq85>Gx z--&%I@o&ugF!O`%NDB+i+e(SBpGe>Do>gmi zIEnew*IJ$(H`3jiV0SD=K#iu`p$f(>hPJL`K?f{&BUEU0_ZPFE$KL?7cS-!su?&;$`+u>Mg1 z=O!+4*XjxIVxsoe)4q}+>p}Bp%r8q;(s%M3vdN1%5SlQ#kasbqFiA|sbOKPqSCO3v zfk<|p)RDvMo)Hjxykm+FZGAX*l-tfj5>H>&@rRCC{$uOI1#!(kQ7<+Ex-i_T-k#}& z%}bQ-mxO!$_WUJ8n|E4VaHiHOxB@Q%9%pn6m)n@U$y@*j`AK^@&^g9DZZFl*Ziox_ z(QlB^sIX+Gnm;sUjOCUH_=^+krv0392mxIVb#%99e0=dN+n(V~Kv&Uo%}0KNEXbx; zQt+ke%RTRSea*d-+T+3U{nn%oZDZY=h|3C*wWBSv=Q^SvKNu6P%ewkIioIAD^T(MGt4aedE)}RcxGfxJ| z2=l{&u`-37JIae)U+#*LAE~ax-jQ=g{%*@%6-GAm9Qf) z<#3Uv-J4}hh}Bp@BVBPgxbZJ#=V$beUA7vFCYzZmt2E9=m#$hDhRh*b3h!i|gJv4q zKx-&uZ8vXc6k@zdtq{q22R`jn*H&(-P#0Ou)*Y2VZm6_H9ZwI&5N?a(d)Jwej^~27 z($Jm&zNAPue@<@I0EBK}4Jx!zTx8~#d#FF@mgc9g8g)j^Bu8Vk0r4Q=Nd22ect5H% zt#D{*dRBTrlVo4EH)b<|DXuwNntCoS-MyjO>H~>qrAOw$HJ!~#7^Vx(tU`%U+;;&n zjWThYvxpD;X=gaURGB%cCP z%JH;<97!o3v%MeHg9xccKyZ6#8Iok1h?M@!XaO_iMb&Qty~CEkUdr4V5)bZFfU7WX{m%{D)-I^SZwWeuH3JYU~N!lJ$V+%=a*iMEn9p$ug)}G>)$inMq+B zS4o~WM)*$91m&+P-k7H};U6v|FK_*+79zYFFB%_;Q7E%Y7Nzv586R7q8Uo4&&S7Fz z!>4)2T=lvwGv)CB%eZ>l{<0p~*XqVYVE%^m^P&2A)%!G)nT)WJ65}5P*sn+iR@th| z7zpfPpE9Q%%xsEuJ?B1^o#T6Dg|>0<|NEK9%kgV)j_5h&I6^dRhq0w8c^e#xI+@=P z(zR3JlhmfOxGa0B9H$%q(Ia2Q*pF2Ee({eeOefMo_QUNT_L4m{6eU!T&)fuwL7EDp zidO}fqTEjoS2m0X{WmaZ*TapHgym(%>Q*oh=KUs(x;z~5!Vxpf4C4{{^5q92QNdPm zLq)iO17nQNtE@NVLL?pS)sx8^f8^vIT76o_VT{;@6=w} zL@_O;h0fG{h1l|FDf;v>90I9FOdbinMsZG3{xyB{aqXMpav84r!adPr&Rn=PtSWX3 zhqj3!&ZzteKvdbqPMd~jLG61C1`cN&T4XQxrAW{hI*}$1{1>w+Ha|N;^p23UN4C_y z)4;J31|@vzS-oN%E+1)?eS427yx3IPa{6g$E?^GEiSv--_<;DtG7+F+-VJOmF4N>-Ck7RB0;nWtYP?*_>|V#95*?YNK{ytr^z~zqtgM z)cz;K{60cOHr7WUM@@odCqIK)r;enqLv6s3aQO&X$G3gMGL*5$T{=Fg*I=)5*9U`& z`F#w7=r@19dlR}CAo(+w2YRYrYtk!L-7Y^v&E3srVvzQkL1n9CB$O zwN$bI?KBcRFRj?1!Jzi5&-!QXcv{6Uc%KeG!+UQ7o)b?M$I{f^fH1-opN1jq+fvwbQ*6R-`P*@V-x1~s$bAIwlUz;oKCl@(&s6u6gi<&?A@EyZBAeAs=bBV z>pTqC%|rw<*9fCRZk?J2h5@D3u4*K1TTJEq*gWuN$6azOT zX?HKmmzjP|C#r(fQkM5U|1mJ}=Dk%HmdLO*62Ay?Bsn0;?Q-iCD$W`Hg@dt|CL{K?ViRroW&MHi5$+6OJH{F5iDv#q z0!QA`@e_w}0Q(<2Pk^W}#r^lqgsiY`@5d(gA_dSg9WJCH4$NX=5^x>0-b3aPq>4snOj$k?PB_LRwstJ&oUdMOH{>1H%-EG!5m|fK7P9 zefQ)8OTnQ(WUp^Gl=8_Ja=ZeNxymfbd_4ok}me4IIgng zL^{ZvkG%FmZpz$m7x%1*JFB<;U)SXL?7%^8Hy4K3!@3-O+pHHRcM_Nz&`Zj@Z1+pv z?Q2au!NCGxgGO{#{drQ6G}P_$m&|n%l3~M9=I^d6Y)Cpjm4~Du2gF5IH%eO!gr(mZ z+Fo-D-oBu>W?UX{#&C*Ydqdlud}tB5G1qGF67n}6C0+9%rZY+jzy5({=u3#qzGdW? zkR3by0IIaD=!r@HQ#>Ks-?J^pX8ZYJ#qdg;SbpN{reTQ?RmX!&Deoo#Y3P=gkGNX*Ay zVDFP$z!t!tL|gx-$?i>JmlW@ZF8`*Dt3Dh%X03aJvA90N*Ub3EAE1jPD4Q*7!0?sd zKdU6fU-Y~(Wu1+`s+<>ZeH z*^*KZv!J0Wf*(C|J6cF<@F&n%0fcJp#i6`)%fW?Ymiv1%{Xr4i6G@hAvE$_H~TV7vsq?YD{*>|nv30GN8)?-e)&T+r~#%P)hb!&zF{aN3n*i=T1 z0VNbj`n+v4&n&zaicH8O>+woM_~+)$e))*3Un0nGk&^ZU+!V@-3L#82rp4%rK6YV; z9Rpg$_M`^IzXR@}Y&%&4EsMb~#$}P4(2dmN`Z5Ua(t8NFwTXeCjVzvv(0tS@otA3) zm^_&yKLM>X277LKH8VGMvFTrhBIB8RtDv#87${J$HwYb@iBLL5hmEP z29YyEz=!jyOQt$bB+xDr#_OYt;=(-0_{6PcRvO13Hybzmw{I1unP8gS^nj=2;|N6Pk24;vh)>vsSDRm@P`5zaN93mIMrygQah1ydP_zC2sF}2f`L#X8 z{O=TrI4EcS>aomugT(o@fZ-C&!lu^1INl60V4W%0;G>(BpvK^PvaB7RhltB6y^y|Y zl}}$77#sk7M2pRe6=NhY1vrY{>lZD(yADN#xPbV!{%$s#R8<4dm_xH|E?h!cMy8#i-T>0-2%+g{hzG^YIKm z;@d3TLS%!f_#YfVZD}1D&i=T~)2?^^eJq;u&qMM^6tgJgGBKl}4I$0QQTe#nLCu-z1yj$s3ZzuU73N}4p;un{1jn|!&;oO?+5Kg7bfNp=i2oZ#F+5Vi^PA9?mU&1 zVJfi1dbP4p^f37y0m(Si56XcbJw7m=A4mI5bT?hz&!&1zjR3BTq%RQh4J zQ>DD_M@oGHUv<3UT^VlbAR5cI(|@+!?boQ%2|6Cm^T`yFxEe%HO^{PJv1KmF{b86_ z+IZ^){Tj}00;YdA$fm3p*wLdwP9dP>gcyY0U%}S0NL2Gh7L57CV?f%#rt9k}^@dFL zWGx%ZS8^L{!_L@6ub4KY3_-z$C?B-EwaNTS6Tz-@paSQpD+rc{hqalyF}_#`E>v>@ z|2#tqn1IuS6faKRzz}x;WZhdcue8N;NCy!F3F&i!I!6`ZWgjw}_i2hGT<+X7CZTd$ zbfB5m4q}(ig##YJvw!p;h4Mja|#UT*~{ z?##4|;d%D^iP{%jTh>#vLtjBdieyhuv_Jy-?eI;;a>uMaBP>iB?=nWf6d1Z?I@)0;-tLXv^LFoNWWFu*Z_f#Ox_{&ctT2 zf~v0UeLmv4`0yF_iw$W|KNIDqEo`0R;K&9w*M8?gMWPEc^Y_quwS)_VqEOb7PU=J* z3d&@$7cH5K`R}5Tgb&MnUIbzHcXsP7^z$5>o_Shz^Sq(LeZ58zIJdn;jYVyt2hpGr zfsel3vhW1SZ+TRR(rn8iiT78awT9{36Snihdq>^`q{IdTa_p_!Vv?CGtZs{IU3vyQ&6t3a?`x6FhV8uWbO zKI(A&t`L#9Lwz~=UY*Lui8w73NE6G1Y${AhNps#cQpdL$Z;(qv6CV4+_qcD>F!g0E zR`=I;X;$+Pxa)t}bzDW@{*lAVe*smFN7*L;j!vyD={4+2O|QpaQzzY%e$mT=<%DDE zs*)W+L3}5%IK`Wck(Z(t+pz>j`Y5q-M-6!3aGd@?V!CUG==jcWFvg>Z%8q62g)!uD z!b7)&I)y6pI!TuuLsZg{+e}{`vXbtIjsKXu9?#h;>UBb_gYQzed~G*vlk^hr?ZUMN zN8bc*E{fo7?ApF9UWC`ldn;8ffARAy25bNNxvux26>SZvb~b&1XxD1 zIjZG*XJ2Pgi?($;BCES?(Np_lq8Fatt1lexNp#M_SNsW;I>uAm?8@uy?j{5UEQ3e@ z8H(-*_^Evfb;B*XwoOLKBGa%=k%O3KdlVG)H$8n`XD>m$57-8exD6p+f*)BchTBwN zI0{GW3#9JWW~L=$rvl!qpEG|nVV&0A>dG~61@xBj=u)kd79X91=TVPM zxP>BJ^X5{x>^1j9JCQ_pTID}8(MUFHJU2|@Ga40vHF6zrU6*xZyU$5*>#+yU#ygG7 z+-sG+-wdRlhazhqFK#y;@xPve$Jp0dEdE<$2aiNhabz{G$>7xbvyp9=fF@|9H>J~! zKKgvfiF10hKI?kSu6J)I_T@;WPjU#-t;lf=-&v+FfcxPuYFx{YJ1-0GV5mu=(MVQj z4YaP5S`+78QHHOj9bpGnljFTpJjpVe0r@|o{n6eA_3E#G436%*cQ>|6;9_eU(!*HWK- zPi=o5SFH3;nJV#y=shTb@rpZ^mG*o7t+iC!6sN=dxTrE^tK|X(Lrlc|OfM~PA`irr z0=eP|KuJeE^XBdQ)s(~!fzWqfL}s_ZHBk)66qTROx3nBXfvAsQQV3XjQisC_z_HpYOL-Q=$xVA@1=&4~V-@cEVtL7J4L8lfTf3 zhgNp#D?USjI|2b#N5|d2&|Li2loxk!a$x)f=s`GQ)`dDPtubE#XR;e_AucnPPUT0@Q}o!C=|0@(S8M;VVtBB_r^%(smT)f;?hc&nBAKhJ6C0^@!6FcL=$A z;|9Z((Z}olArmwnW#CJ&Bzv1IT{CEgxo4bAoD5vWfC)#!CTn48pPiNqOtZ&1Dr{~~ z5amd9P!mxxEGPczEwZ@+gl)Rl61f;{*U)foJh%{R`_gx(>2lPW2y8S4V_VjL0yyDR z;HqMMw3U%5T4I0pB8#Jv5IzZxpKJ)OkhQb~(5mKRW8Kg{t6&-zde;14@1P2j3$yoT zYDlK}8MxH35*1V`*h@pF_DZxwyc_LtRLdH~Zml($uuIzHNap!vc&zkeFFJu$q`c{M zAjirp`|pUqNeqPg@!aRnOFMdf8VAGG8ziB>QBTX@?CY2_ejNxn((3kifK;4LR|Zxs z{Ykp+7Hxbx{Ytv}*U9%xiG+V$YvL~mn?Ix6NMDrts7NVX(7e%vm3g(`$=3^W*efzg zv>_x?@cMV?*OB1yZg<{7Y{1;E2rivlDHk*Ftu)&Qz@iBc)loI_ciixlJF65Mykxrnlg@OT2)=mP?kdO2Haar!c?5{Q=RS4^+8nu0F2KYBf9EMKJOQUQ4ICwoq)cw@jXn9CY zLlI+f&znAS0IY6vq7$Q~1K&ZcNw7Su^+9DjO`mZ9x*rp&&^ zUYbsXaA|}xk^QK1Q=hZYQ|Uo3c&sjVDR)uQZ0F9LKHfvHqt)GI3CnP9+-;$q;NZ{q zM!A8V5X1~{16=JZ2&YP^$8{YuE(Jfbqk@@j<_Q1%lmAS2ZB;tqzTLlhiZj_W_88Zb z&O)9;chUEht7V=i--b1w^0+Fk-EWza(R{pJAA-i7(}ua3VplZtOrtOAEy zsDBW?na%UG?l1AFnbPbwa{cIyb$?H(x!8Qcs5@~r3hL2Ng)lmgxmrj-`kyaGy~7d5 z5^tR@k)V6CE-nmvIN!K?u}Zs>o-lMjiJM^FT`kewsKznc(>ym#`6p||l? zoAc4K(qvi2k?>!_*4J$8+ns$#Qqc1G=Z99-6;$LqYY&X11p9I833@k^=DwBC8Wy$^ zvmpGODxAwq#Tm7OBpRjLvbCyHEOcpJR;e~$yw^>xi{xc^Xl1v!m(H!;I{O_!>*RXu zN6LiEEm1rpR4{FJL>VimB*2-x6rvG^DxEN%pR(w4X4PV*#hh8eMUs+UsNhSUL_1Vv z7R22f5|4rh=EoQ2_qq>0P8*ye?5&g66YRgDSYRgq7-7XZii9y0A9pOixhOU{L#F6Y z^};&*g$qDO%1CllVjL_TT$ow(KR9+O1Ap*5T8L!97u2A^?Pv;cdi4rQjAHh)I;sBu zQQK84_y_hskJ^6J%WqnA(9A+Y;4G`3T<*7vQg|K>Y4ey0%%A%%9Q@}|>7w%4uXZQC z&d1CDm)5SLeUKCv)Hi znXadj^|D@GNTDL{hA0-Qtynh%Ni&}crj7q8yi2%aqRbt6HOq+G{tXpZ7649`4y_v- zY9_%^4F?AssZ-e+{;zh@SD%WIz&I{b$LV%9sUUExALD)85ONbWK>r6*XBp7s8@7EA z6%+&kk!DDTqI8ZCQqoALlG5EV1f*d!GP)ZC=@jYi?$O=7?f>3B&-3B^u+MC4_jR4; zaURF-{4{wwlgqQhSVJuTHZ>I_3={=3BHfoL%VNe~%NyC7A8wts6Oc`=y~t;Lz?82U z6v*2zv`_*hv)*6w?$dq5KAyN6oKqd*aGzVRX{EdPYi^))DSh^ML6d3FFDIS3OSYp+ z*Ci6Nm_V?}Zry!BydE+3L1`TJu&Wi%Qv&{`=t^ZWR53DQ6q>wx-qW)zi00BmvX!-o z%;Y_kKL%7aKrh_<(YHJRuX^mPPq4f=gaq6S#7bwZ;?&6@@AJ-Retn%$aQ_rb8YzT_ zFLnq%sEv@De6!6?X)0R!9JXiZxc>8mr`3sauvspvM&s+->NgsyHGqokrgl5oc?P;g zEdf4i$V7fWAxrbF3r;NUUw^Rwqx43ZPa9jeKXS9*&^5&`v4DoA5=)#oQ&GzL{=%vk)D=v54mFy)Czp@x1L6vW(1P=O#%*?e?rpq?qxa? zp3P+WEKTh5LIw^OCkR2MMC(?34Cy1Y{@yBd;@n`dwuEdFdL9hd0L@e*m93wQhHz{I zV^lD2S5A(GDa|W>w zeCz}R8WL@+WAwKc?}Xy?{MC68>ynbYk;F2LIzDnk*mExr=kbv&{ zrkg!+6=9wBOKj1!qj$gqvT>_bjje{coOY9&;=<$}9lC+IbFWJ ze2vnrM)# z#hq`THB@GTw!eW4&6e%gQ}A~G=&tR_{q{Ii8t)I)^{({@?P+wqCz1S%pB{5&MnfuO zUeR7^Rb@2rpFsbfc0ciJ;A~1umDHa%sl%-nnBj0Ezn6~r2sV9vSe76ey?I%GtM>bS z2Ds-ITj!e{NFlMO-_N7ki{Ej!)r%H;q2U1%5@zcN2pkJecmE7DWcn}t3VvUmytamG z7V^eMPrLCCAn21mkDXhV^K)6sJrrhLZD34N@R>}KY@U0}8pVJv5xHc4rE~8!1VzM4 zhta>)nrR~)S%E?D7@N&8(l*<-Ql7smz@m=)VA>mYVCYJdT%`1;)5Mh)vJ?ipEa-O? z8BQ^aopZNfYPJ5`v|x45W3x2+@_dV0keUF&`fb2HKx7+)dk_c2dA=s1Kak!{@3s(B z$Ufbrhi#z+WiE%kqSgPyz(Kp5aQbqp%K%;JKU2s74JgTSu#@K<;qqe}r!JQsX>RqM z+wk#bI!n_Jpz{g4j4tEmc78DXaEo(xgm>i;y9;Wn_vQ~2_a4oY`b&Dk?{wae-YP^? zqdW&|@(s|=3KjXdR(@L2?*&x@ZXw>GIw@Qx(VC>~mMVi6eJzUKU?j1X6YipmO$}F0 zBK=-;?S7MwuJfV{IPE1)p2~npBtCohoBE730=8#VnaA0@OCB5tsuM#=^)v3zjKv-4 zKh8zoAYTxA#j6P!P@m#}Ee8gKw1nSB@!(p!04AhT*&s z#kVD3+x6h{9)WDFevi3i)m7@EZJr?0X#F%ADKM4AqR4FFyvO^_Nxfc&0QsNGPGzRF zgtx{uUrq}GG4FWhlpi+hFPK8hrT6Lka*|}t7lVwKGN- z^gf3!kd(fTFX(`={auDEhkmX&vZ*LHT=2m9xbgVQbD}CDc(TMZ*K{_jFjsaJ8G9a! zyJ=PtgRGvVeN5N`PVe3G3q^P7WSRDF+Qhg-#_=EzXp~v$6MHYYeXZY`U}<}r-TuG0 z#n6AsILSbskaDOiA}M;oYjA`?MUuacfc&z;(z4G@z?Fe&Cwl5%{hJh$C3U(m1g&gO zZ(mYr-_Sa01AVLF(_ZR>F2sZSo|mtKUO~UH?cGd3^I86B6@%hv-Z@r`s}fDl__*<( z;~tV?5orC`_EmHHZL4?AAG!B(z-;SBrV)wZd~DHR_N-2t;2bC$1g@hh1Ki5EDH+s` z*FlLJY5m)*o$T>3Rsy5EyKV0#FAXG?E9j=m5N+bUCt5dwV;A?c%x3Fg^K0G=Trp!m z$&^=*AVR9+sTWLE-=QHG1UHKeacz|;gQlDpP&&SNpwDdR1#c_L~XBUFF3eNbn4 z-Z>V1m54C#?$Tx4Nv?bR9Wba4#9BC9_MaT7X9AV(a*jKryo>6cI@esUE3Tx7)mcL) z>#lWw{+V0rhmI*zqZ<;fyXSceBZaJ8O+O}KlI+kZhH=B;)C}g+pr+4v*C|QU(R_hP z65ih7J#}NXmfALxc5^i7&zR~8aopGz#(y^XJV|y9NzY0Khz2#FD=u>Vf9%a~ZnDAh zKK<^3p-51r9PIK@+wnf6{9DJ`i?1X4i!zxfvcRX_OHH__byOl^Il6mp#kOr%7P(ua z$oBrq%e6?ffYu5j{upaBnDL*M69I{=p>z^&!S|(?SS?pgMm&vfcfu`(tkFWb#rfie z;`xMVc{elIr$+KC_2pu>x*ziX(0`x38g_$2BTQ!PM$#=U-g3!Cg+*ZfGN}M!c8{U> zZ)NTm2Z8C8yA>eRh^y8Z7N+7`u3^Hgu2_7Yi4>Lj9-`^TnO084l)4+ZH*C6ux z{el#Y*vl4w7Dm`}u=N7Zf$ZfG*UDTPPVRF#JJj9%41c(-%QAE43PfLnQD&vv}y`3Ea>EmnbSL1)^-PYM>_yfQe49MLGMUsI3yy|M+7|du97Y z6SB-a3LU+9yaqg)Kf>4F9c{XPfhwqv&u%F z=u%b^|8;o&r<@fj04gTgUrYt>G8rCJ3uw1dvh=1DHC`>^Ls9_5gzzLO%B*`b<39|* zY-V7-lee^do71O%e(cl)3*u1}{?yp4ot{CKGV2qx`Muj=;x<(;;fYYfx??2kA`-Zv zz6#fU2e)AKza1(f5jF2|@&J9hs5!l^672G_?Z59)_p51wOIr7p^W{SYy8swVEK&`y z;p%PEZf?$O8seT|#iD=w@@k1d^ZF5lG<9GN#m$4AHi5$L`F2?BdKZ^Rys`?H&l(i7 zztW6Dd>6uYk-NUBJWSmix2Q=naQqhM;3(}f2Oug0p|}4&{tv@50{VlJka6f3 zCUt>xBx}l?RmqXuyD*h^_(AG_;zyt3yB7}oFZS^vO90D+btzFU1BS4y^Kb&n^ACy0 z+e(_bVgC~COEU6`+`mmxGr0(yukDR+1hb|vqtjpv_ZW(Ol8`uhHC%e+Al4g&N6!Qt9@v;3TxkzLans}^2rTQTj7=&)KfLWHPe+@ z&+Kh4+Gd|r9kN^5hc*F!zVvsaGkRtkT~OyE&k(gfEanJfY}SgdTJxG<<*?OR9z1&! z{ZYsm=9UbZC~oh1r+TrqxBzI7n1GVwgjG}+c&BEQkCV<@8Foc&ty)*rmPj$^vBkiA zaoP5cbgRG2P>c|)0=O=X0keFpXDPb!vn?$UVJV{!@ zjK=)NJR`QLwGb66aeqg{WKd`MJI*$}M$w8aC|fIO0FOY^0;y;@a5TL(^VZHCu+6uY z|5-tNB1P+XOEue&EfZxR$M)x?Z%Kk7(2Q-WZ!?PBc>5V;Sr_;x_A*n$`R~4y`*{bncOclsjcP9~q{c-rp6D zGuFPl(35ollQe=VzUf9)NV%AIpU$6(EGt-`Lgmorm7PGc(fQr-B#-Y?Y!XU^Kc}SUIWxpX3$@W|&`=>$ zj=pys^HVXBY?Y97i@`HSFUbO5+(8tlP8;9&!lWvCEQ<3<$K5XhKodQ|4JRq^Qb zmgs&;(4Nv}QCly`#tYmBq01G$-UzwHEcDaMdo2zRflAqF5sUSQMe=gf`X;#GtLT?_ z-sfI3qOohCwGppcA~YWHp$YMId|_ZK8=HKy6RPm5opM&p#$)ygx?9IDS)R%6cF_6f z?PJrsK2LIbL_N&oQFlN{mZ}U~rli%eLdQo642}EI5pV9uGOujWPg_5jRJ<_jTvx=$ zvz=ULfchk%%^NeR_O$AD>+9T!Q85_RAFHWk=3atX_hVD7oW_o6v~&M;Yx_e_RFiea z5zIqVN8;2n@Mo2;8R}OVb{ct>oKfGl+2=hovMa0&NvCS=-dVKbIeg;!*j4Hk7`}PA z`ebGQy42Oy{o5B~G4ppB1dh?{X(zMrrPI|=i!pnC-vb?iB*;E^PrpJlDfrUp#nvCL z{ci*hFXNGYz-U6S8iJ(Ox$4XVmlkD`4)K5EKMtHVES0qcuql5)G``2(qc{$&B$xdBcjuJ_ji)Ygs$KnL$9*Q ziT2}{)|wYxLbV9n#uiU{W=0$`h{_XpKjImla_J}jdU}g1Sz8jA%}eUJnhUxa7Syd% zU7mdBeb9LcYl(MQS`AossZQLe-2vc{zxM5{gJ3FQM??OWCX6n$^)jvpA}GoHhKqGt zk_JSjSMp~UE9sJUdKb)UVB|F|T&x|MVhxb6imE(XfHCGHx8C5|b&;zPekL=p=CCp> zN%Y$*cTk{LwC1RleQfR4*1Un+Na+aOhoMn-DjH&GcRph7D)qKIzZYvS-0l6s$HLPa zCC+($tG7z#qPqBgy9f6`F!<<$7ox@gHdQ_R&6E7a#YI*+fk_bE&i6F);=yt&=QE~k zm-$08`?D;i7tOyHbguD|Rlp-`rTa;ob+c`CFLuqyD@iTlWR{MHpbLTp7^AcrYH|V? z?mQJVLznMKI(!jWwy#q$Ggd@?%QigME8tSLKhWm9CD2PvlBEM34Wh{_rN)n51jkxi zk^bDk*mU3b@}6GLK%|H5SnAN&6Lk7YH6&fnV?PM~%Q*N^vS7#;Re=t>VFw0{_F~ZI zk)`!TNX17xu{+6!A}@+Og-pT&$aNEjYh$3|4#{&`W79(J_TuMYy2XIX@Y$LMEp*ieA$D?c;!LQ z_s-|7?9L2RuFmE!O~=T*nb!{q-d8i-MH}IBDT`cu8VU6 zEIp!`ouEy5vvrdBa~(sPb$jSdF^!m_Gz{#?S56_d1~B&1+L|W2Mw0Dp;)O*z{u6Vx z(zp+T5Zxowv)~`kXjgLyQC;TfL}dgq>{e!@*K-;w0nPXH{KI3zlW=8G1aOz6V8T*U z?Lfr(g06V*jBdyoKb`%5NBkoV?>;qrag^#Q?mGStW1SQFQVA~pOZIEaSKJ2Qp{%oB zYHP#yAq#I!?Mb;d{>>&Z4WU_7Kz@__z#;Ie(wz2sJLn^7nJ|hputoqj_!aoxeCOMN zM&p~VKEzq6mhAWqiA~@^c(_~~X9`mkb}1k0u7%ruTqx~FmMXRY&L1l5e=Ecu6n`q2qwtZw;F6M@v+6oK9@Um`~;CyJ`2Mb0SDaiNkuP4-C84Er&;gd2W`| zJ`$6oPXm;fVU?5l3zmINxhg(l^=~N~_ANnytFa2y+RvY)zqV-ws+cE=)cIXIH=5`D83RF6 ziM9lG(He0)9vz(+GGvIn7xDd&bSE^;^v18#s}`@{xPrz*R!mRiS$4%lE;mj~i98m? zVQ3@y%#VP%w5D+YF%r}!j7}s>k{oaUw3UAwmRq<~-yCy)r~*m<9FI^JL+{8lxV`6q z!x*n*kZq zWsn6jt*h4yJO20tsAj4KK$!dG)^BI{$@Scyest?o|2k!n^|YDQ6-7sN2Tv@d7E2($ z*Gw4e;mi}^OWs<4Wc_4nk~Sz*XVAAf$|VJs&a za8HKna#;)p>?`MBKt3COafEq2#pbCn`YmH!e!DWNF_~YD9`cQIai$%}=)%+d5#rC2 z+AM1)bu?8>7yJZp>1i_L}5LM z{)cgtwC^`4I7;>x;&@r9bayd&Q6f~E-ipqAS3Vvoy-`Ydp3!93Jjn#ZWr9yz1!w5`e<>}3Yx@5%s3vW?#am%& zZ|`<3<9dF7JnQ>D{vGexTKGA+k6y)arxh3Q-o89ROBDB)TJe(;8|k+{0P*4)!Pmvy z@?C~B$?{V}4)k)58^6^>#(*KuM`2>q+X4|vP4u$^w0<>k^HRrrE63#?d9KW#oDT;} zTE8rt^6QFCsHcCM={sR-fIITS6Vg<-VgVZh*Ae6^>+v}Yx;CG*^T=3Cq^AzH4=5yW z4B?a+&PvO>o#%z77Do)u6t5#nZk>8uFXGNcUduc75cm)u>}m5u2wk7VCJE!v(XNHO z?SishzD~UGU(I(EeSg}yY(I6lfjZqbRlPx>YanmB3s4*Q_B4P<-~T28)z^D9tOgK_ zH<6;bEZ7e}0qiSDtIVfYh`ebjx-BCaY&-Uhy`htZ{8OHc7W1`u*c_U1f{=JZxKJQ`#|Ld zIx7W^sLpY$rUy^zIDmu;%%*XrlpCK+WvpYM&Eu<7)%56xj%~MU)7Rl#aoL@$8ze;V zeG&1>Jug((<9Ruoj$gBw-)-AATJ7h3Amhih(XMTc=~SjXW@3=+d=m?HJI@u5!jC79 zOBs|@r?#}IURqBZpK^qe>gh0uRygm9HMQ=-c`;7vG91W!qxUs6<>7kOyFuF?ndK8SD9VZZw%4Gc|G`=sOs@jDzgqQh>d2H1@Ks1nE#_w0 zn{}oIV~jYeOEtP$#69-JQP(s<_YLbu$V}x6M*rOlDFTk$)^asoGSwPy4AwQ;V<@py z$dM0>HsUXQvw>bY2HGM4n3gn+Pf@jb|3s{0R(+>scWa4Qdi_ zemr7v{aB$rQ97%ULQ}pf6wqVsy=^h5+^2|qT`c5x_jiq!jQXxZ1+NkU#90ZXhcxrnw#{SM+!3UTP?ZOojFoD_CV$$pL>#tq!E;B z!tVzNu4ZFoU?;NJR|Q{7IlgMOQvTUxr!XSi{dInyhK=fMzSB^?m9Hrci(8p+hkN4B zO})XW+M9`hC1$uHa5L+yZ!UIdM>>>$34pT7T06-qMj#;z2_am|dIeswjj;1lxzlMU zk>$^#*>r#$Fd;iX!m?H^s=74Uhq2wt1PZ=4ehJ{{1ZmcwpIS1Wj&11kaI74?$r&=7 zU{nqnvpqfN6Ce6r1rozR2RF44PR%A*d;J(mE?Kr*uw5F{`Ln1du!`aEZ0`i#1xKIz z+|7OlM5CZ_M**YH3tLU~{(jfnz;U(ez?RTPJ3;$!pI(oA(g|fdtI&4M_wnbH>OF)> z&lbYE-7GEgK5;NatI}_hU|`6ofe$DkA@H&w`-~aR)oli#{BAtms$x9FVw6BP0%Puz zHj~B6Y&!ik7n#iN)A9bHrW}}Q1Z1Y>%dNd}I1u3@Kp$gYR`d!`g-2C;JckOo0cPI! zp6k@yGLsd&xc2-ADl z>fO4`8-7zVRnJih6+~TKbpr7scF=)Fk35l_;8g*Jrz^i9tObA+u(^mlsF~z_fZ*?5-@6q}NO?YrIeYw8 zj3KsfBm31j39l}-!)W2&Cq0_nUF(>51XEJu`O)!aZxPTQsOR4%VRi`_(NywZc54hZ zGPu8JY_jW}n#DRJS}IE-#ZC*6fYL$AC7HW?PbvpT1&j5Z#()Ys#Q7D*LxVUzHzU99qxReHUksB<#pd zP%6KtT597P%h~f9`A22@=iecg1N=Mg%*ZEVXxANhROQ?iWvU6lJ~T50iCGoXlU?S! z8T}61CGwG%aKumYjR1&ffK?{+J|1gxLAUUsBlSKUF@iBHOugGoQApF9dkg(IAtD8U z<_&eRo06n20-D)^N52ph5Nzm;dss;M8-w{K(T|&fR1Fm0UJQQSu}J>N6qNlR#=Lbq z`LG&i`eYTAkZT^+jpjAb@O;tm&-UouQ(X^%&cOXtlgzND;HGxYe&9*;e0D_W>`hX6 zd)7l?Ac}pEv#vGg{z1Xo^Gjn}je6{->Y9kL@QYWcb)`;nwYA)mnQ;aKSkYakQ{dsf z=64E8+(+^~ZnN^hRqCWM_^!q1q#unjy(>zw`ueH$Eiq_GZFTgOc7;cpm+Wbi9Oc)s z;Lp2K-qJ8XctyOuM-VZc&tQzha_^3Q7vx1Y=%5w=fp%dbtrXQ(E;_s@(%IHmh~J-x zoKl+m3b_|l)YI9@e{`dFV-areucS-u5kfW&Kd^ukNdTB4k+oOe<{dn09J@Yk4(+0E z*q<>q^wMk|UDs%U{=zVa*}aWhr7`iL4gXKeufY(Va_WPxSn;2EyqR% zou=#@SK7Ur-BwQ~M?sC>%UR~0VelWwDgZaM+B70??R{7^4+Wh7!^NkqAo;1BX`WpU z#2(!_w#kylAJ5ItvLR|R8G1;*mc_8jb)y@V`ipMMc^^@EKv##eDRq!y7};R;1;@PWph9`Rhi*ar!>5$eEiTSN%1%l9UwkmZ3y+ksC|i;g`2A z)Lfv(LS5D?LOkG2H^p?mT&T){N$IQP^e3uMm#M^SPiB+Hp(jKxf)lXRx6j-H@g?_J z9OwU~xChSKgMT2IReviiNkhE+eXp+W!!JH?D%SlVV`a}M5ghXC{55>#R~3Wm2v;G4iYSDym20}$FHfaiL|BI=_>MmC$iS2a zW1Q}Qx@+}h5VjS5K9?6qszdKoQONe^{DoIx5b_gmv&oZAOz)R>!G5>s(`=n^%W_pG z0-W7nvGs~U8~>aKDkQCc8gs@+=N<*B*5Jar$gs9z+Xn86qg zenCr8Sh71SWbmLnkPp)^BgX?vi38=aGP+c`2`WKn17%BaF)CJZ-8ip^=rm-`luVPN z=bjh58*^25)G!8Ebxd!Pm0fS#G|=WX*{ArmEKj;y{D$t(5>YCt5t@?##ztT^}e#owW5o}O#7mh=`mb(S$tG>*)XwS zkiX>-JVT#F*|bsaSgrUrDmixUK2A~Rg|n5nLQ_Wizi1$nFi#d#H~)RurNIA!12FA3 z+54~s3r(ytb+sr8U@ED-6l{15@dMB~!2hhT>6W`riLzIXL+d5{VCd=kqLb+O2h5&u zIvmzMdqhXiMmc2X_-DH{WSfTwH5^R?2|k4m+A1!h`u?B`0G8v9tf8TGF*xEo@`r06 zU2HToAcbnE3n0b5GO%?AJXe5Nvxzi3-Cc;}gNyNn3@o!td^+i0BNE!czNnPsp*&Uezr5JxA5T7a z0)RrONUyHhGgaP>t(SsSv`p-Sae@9g-Xn4&I)#Ri9O(j}qZjQXbuO~7p!e_--KZSy zk7^_ef+7LS1k~+9FXi@3z4(W`KL^X`ZkXPN6}-PMwFY7*PmB(LiZ?+_R4Ivju4Q$S zMC-$5>~cMr=%=yCB1qiO^?jGEM#uTlkqPKH4w|m{A4bq<7pXg8H}yjA_6HRr#$(@Z z_Ut0ruIc;>SMNRXk-aon!G?MQamLk=!2!&;itwAIat zFY-G*)q1MFH!72j>K^BuZbx8Xx-2RQH$6qWZt9xcd9_AZkTocyaJ1?+umTmyr^a`= z*oD7>M4{4yB(cy~3RNDd~lPi(iqENPlcjfZiVria^O|7~lPe0j8Bko7`*V$`|P@ z?hLoq1Ha2!T9UuF83WLlR{f$$uaAh{P>R@mz?VD7^h)9WWHp3vdP3X7o*(hYYjfx4 z*HCCZEjk6*EyOpKigMkmw)mgunkKKa?B**wjOgj#>vCN*tiOyM%C-m)IOy6*@zZG) z0)90>O>}w-{j7yJeUY9P=K5mjNQ6O-=Fr4p)9or}1mPT2=BiC!_(_eR0zz@F<6~Jl zAkaDoCIXzYMT&?QhS2t6eKb)lvUmw*I%*-fuOoI3AYdt3{B+)zkKOb5Q=G{$XPCcW zn2`0=2`hk*e!`w@)>-mLDCAP_N7-Ri0e{pd^Aw8wtYt&ADIEgB(>x1Whhe3@Xiut=TX7y1iz%M|ZR@!l;}k*=TVlpU<-LKc+x z+0rcWf+70uct}y>A{XR2dy)TOis^?|9-C&8zcN4{~EOutS%YWjKRPb&2Ighzw<0Y6tdEZ)g-5OGD_L*3EmGEf( z8o9R?>E-*x^KCl`ukmU_b+yzbz_XBG=d%xOV@#~Buj&F5J*K~UTBj{kw&el0sA*1f z7*?;vg&g5ND>q}vD^cH^4IM=c`>ofDR=VLkKQumv?h2GWq&^JxEW5gkY~CbEtd5j_ zVVsV?>Z+42pR%>&iBXW~rzD|0L+&#OhmeUPs!A(PpVXxk?VoE~adOv0G!di~EeS;n zZ93mlz#BMZ1(}_#JXSpOrXvrLISJ9uhP?zoYCQaoQvla$&&dvaEJW#dJ@8Cg0(-<_ zzw3*X9bEUVi99Q*EsNLD-?B|3Cz4)QiO!1u^R$`VM=G}?{XV^tI!>(jvRp7b*n=Th z?73{dwl`t;**g=3_)pX3H8G&&`hnhmDr5;GBcGQIuoewa#gcns?imzOQmXL?zL@s? za=WyLk|MP0w!U!;CLl$$o5I905uXywB0fDP3~V#n3lHgRqZs#*vSi#y*+?FullNG9 zqU40JQNSKdl?LmnLvohYMU?f@3%))_#%)YiAz9iT9I9`W#UuXQzmkl2?Yw^u3^=_& z_?90w>{2Xy6#-AiOt4e-cRZXv!2{`yg_6GBlp7*;c@OO4wQ$JI%jc!#mMYd1>UB;I z+GdmwWkM8nI;h=2nk=*nuE8j7b4}8~v7YCwO;z0t&DArM^|*+0HgA`tdI0CPH0K9u z9dFRzmYaT0d_rnZNfMB`dn`)_Z!=O&7R?EW-0Hrv@zfkJClBkHjr5nOe31N7H5|)5roRdfXhH z^LzVjrIGco;wz(LX-LJlZPMQsCFxx*qf@hRV1#e}cfIoHGm7H#MGP0&9xZGbK9PJ=2m!`T6sDX{6t zIy7%EAYz$<%VX3qA@lMmqn`q{r=B;w=~n2GVoolj&=6tkeS!A$EJ}u8|rv& zJMo!CD0WTdP&nXdE3R#V-qclIRY-P|t}ckaY5B>?0vc3^{PLaz7Q=lY+opbH0n|H5 zST{ntfpaZDJ`s=^no41DxZ1rBd6_%B-6$erA3B4KSh zvM@Sv^j}Q1L#);h!8gb~9J@{9loXCN2+DOE`trEt$O#AY&Nwi3R~tyzUp}iiI-0$y z|ImxR_-<%hz6Z~!sx(+y)EQ<_TBHB|!wdsM930K9HlNR1K0g>h`U>w0eAncZua%!^ znjToN(>}>-_dbN8^o()11poG}@_9~A%kCD&Qd?qnw$#pTh*CsVgM^YFTO6UTDGXnP_Ocfuq?}l;nWGc3cRPSWVsuCK(_Y@sB~I#?5V6L zi0k%DXu^nqwUg>hXH36^fpO`d|6`E5)6f5&$FWz1m5aYSDsK?AT_OZ5acf!;a_+9e ze)rp!kX0wErw~4t22^s&qDR5NfzdP~RYAG-Z%h!^$3GQEU9o8!4P^~2xD_Lw_0gQ@ zB_Mj*40?2=jMw8hD7$mjds&g}UX{&}<81xWv&`tl72kgtdhRxXsJLO&lW*duv)>*W ze9SbB0L?UaL^_D^^u$C*L)rf6fYgp_026vfek#M0(cd$i%)gQ9;=BG(8{cf+o(Dbl zzeK!N-oCl?#Bq-t&1ctpt?&$@{5uLsgJISdsj|_VEB4G=ydTiS&vDxbx2HN=@yko_ z3c-CgF+bH4IXDCTS@=mCmBM4)AerCve%|eW8@RY(R)=V+zNgu~pqm^`Bn%)t2eGAc zkKI^QAuZJ-y&p6@?aP5uan?Yu8;$e_e2vOEl9}A<_4KIVW#n&7XB~LtCO&lu6Bj># zHZEiJab3S8m&*s3Qn0ITwNwP(&xoI8cEE74wia5Pv&GWZn`!j{m8{n6f3`Jra7V2E zu?pDFQn~Z_Hpk<{)&2-);+Gv>gnez4PJiCdhq5S7OX4jik?j4uq#b~yD zh1J~!-#imA!`mIucajcO-LiKiV?EmN>g9CX(XLEFCFNw^);4b`9LW7^YoVPUL%Jrw z5LPnOVsaw}cuBLqYpZL9NAcFE;^(cZZS_M zD#iIs>XpieoNyM5y!^a8%+ET@!zP|DmYZ#pNby6KD1yUjvV1AO`qE^7eX`Z~lr=^O z&HJTq1%QHh04STc@Qqg+wjPkQhsI6^0YHb)L<>8ur zxQ+0BRjKw|_A;&N0FFR<=cPtyU$Nw(HbHNHQmX)I3+L+F4TDr+JGJ*WbVdj8?DwHp zma8{66Mc=3vjsG-XZO&*4kovB zQOT$-V9Cob?hMw0(V2MjaP}%UTMMa403cIOdZIz z-JfQB@OlKL`2Ew-4fMA?U2WS$&kBnBMljgV(1oUI7c>Qd&SMS0xY1m8l z;w|~lb%(g4RUbYaT0=xO;8z4>GCBLY*3hn=F++)G5jUmr=+UuRYV3fk#XKFNaSgIZ zf>Myw^lJx#$kjXZZDhndccOzo594e!WQxAy9ja8_QHwy{7?p+~o( zY52h{U8XLDRA|sZe9W}4wR6rSlDGum2Q7;;mUPn&{Fe0u`Imodqg*;dq4S>u+e(17 zWI7qdXRPBKL8N%YCaibK4B5`U_C4X3z@oc z(Y)E%zw&S zr*@{-n&TGkw-1ISgSBE|Tce+@+qn6Jl8g}8s?1U}YM+N;ffDJCD$ZLY1-zMueFtp_YlDcahP$d-I%*Iz(Gy#mHO{P*74D&SS zns9}@AKxhu9tcC7IhOnQ@Eevc$F8a@N)0g#ujl6=JU!e@qB&`=XZ)GBILpXxZ*1jt zp7BJPF%@TE8XF%S^xRsAc94tZ$|Ssyqbjd6lV7bCdvX}K$Aog(U&FO_%Yc<9XxdTc zYu*-x-kmg1zw&MPTzq#MO^9F{p3Ds)?3^U5R6@k*S2~@PtgTKEOn^PkG1B!Ck}l7| zHmdHq7~cbC!HPAQGJ286%)KAlmi>nLE>^)pO1ijLf8jK2@%(Uv)J z{fA?Gh61Ld+^0yHh`N8xEt+IgyYF5t#tqG*ZxsjT+UQx(IIoRrA$=zQ7G{_>*KxHSu zf)p_yUIJwQ)v;OeZ7NqL82{o$p{Wc{lw0whWaG3!2~1D=bNz^T#)&)lIv5uOVxG6bSZGXv*+zRXUWSF|Nk!gtViK2z>Ad? zLsjb4|GdnS6O7B}qNkY>i~F6~J4DCnA_JasAE;`uO6nPPJCiY|#XyWE8XeUWHv9^u zX?_>Jr!OVzu_VI_E{}MRYt4T>K5B2#M6NC*7%Rr+iCu0b1vJe%F)y|kAUA25o9x}c z!EN7e-g;nboL6j4Y(wLWGTvrHExDec*vB2PKkG9lcP=(?&}BX-(#P@P;W@?!fX`W7 zSIPIil(Knas_I^luP<>f2@_5ff2-w;+xFXAKHFD(%0$;v0Bl~X-eef-1S$gHQ51!~ zI;aOhKc{&G2}6=tFKDlAu2pfUyB+*Q#x><~+G^M?s-7{(4f1DW0VG#_g{B`{e}-m1 z4?q`VGItc}8scX5*^BgSVn3LPBI3=YUkERah5T(g>Uav~@&TRrXO5EO68K-u(zd8{ z9<-?dSfvSguS8;2J=Rm!2Z| zL(qCw9IMCD*jK#EFEW=O1+2NyMXM{<#`akg?)$wO%Rvuj4%daQ5A~795OFc*~ z&TcdCKD>VjEk*wDLhdKOY~f<@SRyf_FRG-Ny|m;pP?IOz`hUpES>^oSGwcsK?4Dh7(<8Og>50zC> z3m4OZ#)b8tVi`Qlt0@#3c~9Gk=?yU1M$#oUP@cl3jtL?CZFaRbn;o2o>$KO1V}AH9IpkHDQ_Ky z%1d=+9{xc50!s;i1v;L48~I*Gz2TQQ=QJq&%QqT7L48_yF5b4@y6HS}vBnP%W=|Y5 z8pt-)!I%7jZodW7=XgjvutnS}jzPiIRYUjTmDL}W_hn1ReRwC6QLaaWnb&TWmpq3w z<20@vR9auxMu}0uQj_+XeCJdj524eU%Gnig0?b`U3_Py?TNi??Clk z(v9hZqT$Z3VMNr^)sua~On{}>r$LT%2Xtebk` zD-HhkKTfK)dw%f?-Bx|<#4bLs?;SVsT({Spf^(RnD zSnF+*Egk!Nek_TfY+{ctnZW@zw~DdzcZpI0S}fldU8DFzBNz;;wRzb(k@GeFFKi(A zS@Y8A7?p z|0EJ(O-ZmKbO#&p6ajjLuU39|lP>8T2vh-F`Un3Lrw_fqkOyhWJ@AY4QV&AMae7r0 z%UtqFIe`uajf15uhFPfURV8Vv;q(?rG~cy-g&Z>ZUA6l7i2jPoR=!boi2F1_`Ovahk``&{k#3MqK|;DalmQXx z7*e{syGy#en_=jNA&0r2%kS^M*7L%5EEh1tT<4s<_h$?JNj+m?BZiL4U#$lf(w!kI zY97sw#IDhB&ntNBpH%3bnTcu#viYMCzuJD($$$g0%EHy?xFcyyx%65qg`(8#skCCu7+f>OUK=)aL^^PUmKnxN}rYk;nQq$s%tZg6m6AIm+?>JXIaTyo#PhNChV<==*H3=hMH;wTE9jbM^`P8_0oZ`tuAX z={XL)eeMl_#X1XHn-%&#N(zva*uHv|uyvfu%Utvt0d~4qI*a*|3n-NS-CQM`4{To^ z-69%7)rDqueT7&fSul&eHS!KUVtxc`67Uzp8jup@PoZl@mZzM*laIsT>w9 z&y?*SNTB-ZIq(ly=GD;tZ<*(b``eQYXSTmD9PaEn6 z+ENH%^Fj3E^5IR{DjifAX-=RwJWv<&)5D8!-ePGHLrv7LxwMY%vd{iIE6dctBJ2VYQ_5%eL{OiJ z*77{6A8|M8+r;{*kQ+7Z0+q{DL7|%_w{`kxjd#NS4^@nISoO!~Nysah^aqu%|Y381~-Vo(x$CUXe1|*S$E@%j=T_()H*I zLxAC@DPXZ?DQ)WANK7%V7Js>RZ-DGf?VNhy(qleFtx?;v*!})8uPhJuyTz2%NUO4o z3~ObnzO=fgHsSz8OZ;=Yr$yUDP#Fa9$l{;PMQgpTin{re0oPx{I7e%#MU6H>*8hUt zRn8d;X0(kOEsFAEs<={Pt2(>S1{=`%3dXag9_7lI+9|CDqqugqRIXa_-7Cz?rRtN`fcJza^!^H-V$Q2qt|&~ z%5K0$9$BI1k$y|@RqYMp_SqmlOm<+HNZi(-YEE}yyHs?ckKCR8lN?ns_j@0DJ1qm& zi#1Ul*ez2q{UMs>Lpcf@jraycqN=V7{Ri$pdy$^XmW_X#bZg`-6JR&l?0?I6qd!&a z4_-w-t014KOR80pvZo`@v1J2}YF$6DWYk3C z<~mQ-(}WnOL3%cWujKWtR56`L{S`<2CuH+vpX+=L7?biU2yNxKSL{1kl&gup5WKUP z-Zu>iN{82pJ>hWUPHQ-^F#LH)1ZbgCNg;|wDF`wVP zfkP%rS)O;zjt1OIyEk#L*-Se5!0jXJz(uKhsR#ZYv{g|ZH~k^?j{f+!1QK)NK|8Z` z@a;*A&g2i>^UvMc`<13cmGz3Qv^2@vNV`q*1iqP4&6KYrl~F31gnGGVE8pny5{)J| z$5V=yon~G<0Y?{ed&0UWu3ET2k`Wz$TZ5kpUWQ@~Y$bB~4uU>?!_3TG?*|QKvvild z(!gI^(vMm<1WIqmFfU7*A|j2ps4~@68mcgpGJJ5_64wuG#&rBg-Kl7%>qK1iV{G*0 z-uY|Lt4wepNN*U50A!)NuO3M@a0mzITYH$F*P6KKS6fMZI}^k{+`M%ttQu)Z*hlTX zM-k>=c5A30ngjT}kHc{fEGu1d{Dtv*y=A(GC8$DphtVJIBG~!N6r{raio~w?Y1oSjlBAAan8wZK&pAfuXWL2L|f|gmmIM~H`N21UichBu9|*^ z{f{@PlDZXrY@)mAiHp>r26EgYQEQrdJf(1%U5NBw(_A{s#60}LoAW<3Gth46g%pXQ z6+V0ClNe=AsiAAj6NC}Y0Ts>6`sW7Em?bGArh$H;Pn3Qlmx^JVwc|i_pVbi*$byz1 z%o44Qkq|>EtOL$Sio^h6{a3Jy4}}>Rrxf#k`7j84vuq#T}2)ayV*3QsI`O&Je$asCtuQF7cUlP(^bgTurQ-`YGA;^#+ni8Kb%4--V$` zbG#Tpa!7f=FK&|gozCQ$v*O}v;}5950=x4ortDBOW@fAZf02$;l|ln<>u3aV|9dRU zV%bZ0(H9PX;9c~DY++P9Mm!I97SCUN_UX<`NM`l$xPQ|iO}#qyNU-wR)<=G@#5AH@ z_=~9JDy5EIYE8|;74!Em?WPAKx(~>8(_OE4?_jx@oe|ya$0+>gAL}Pyt736n$ zkv@}cq7%V&(j+og6I^M3t+MvWyl9LRxKI9yK9_htSi*%7ANOMx;P>_lI?cIy{9?HS zEQcV7N?*e(MJq{6k>|9rvS;R6&q|nI@l&6x?(#0&o=Vt(Rf*3(oUr4L);a>sj`QWp ztX8|<#Q-V|IKHM9) z(SEWPYmysB=}CT7bLbAnGQA!2^w@AT&-%?lvaNQs8GS&sBOi1|8wcpmlN&!RF9T{T z0lPk7OMxX>P~edRLv52nA8X5i<5y z|82DgQXF z>m%R&E5|UevbEo-YzsYE92zFac;DW6FS%KqO0!S^Vm*{a*&=2O8?@HHS;h=QzMpsE#;euVjf z#kAaTo^EwZc)GrTH@LpL#$<#P?&i4$`jHM0q&)V+l?T$jM8i zW-?k!zP0+kcGc=KAEgRi&FhW%O3S6y`kJo|d@#(Mtb>B7R#jPQJUwrs2GPL6_dQ;g z`XMHmr?}?@M2eekE=wM%SE}-6{puP=74PdnJi&~Ae^S1kMy6O)Vm2g`y&*TS(>p;gIZ|zzG8$Ds_5I1t$ zE4mTPE5hC6{FH(N!GS1=rihV62EL&{(Vj?a5VV#4*xYo~$Bk>pCn*>3feaS$gh>=0 z)X%l$Mx#foP~Q7!%8+)JcXX0@rKqK!$JdLe5L~Z7?$^hXS(FE^G+&TClfusYiYADy zI!-b5+~|UN0W)7ocjyCMJ{Vuo>WfbWT$!_q;3t*f1R1IKT<*1=$ZQw&akwAnOgbiD zr5ar7i14g*m>(9Rkd)!jVW^;CrG@L)0?RHpDTFs3O%fB?~H zFfT^@lXnpVC%ZrW6bPe8Xan0;Q4@xKm>E@X2udS#N17Srt~=?llWKYxMIqeUpDfViTxg0C;_`9c07x zVeGmJuz`;6u~Y=my!9-fi2aKJ+=agcawwYQ4do1eB?i6ky|2~U|m zN;Voe3eHLnRfwTXJ&bR$pVdyJdaKjNFwJwx7mCRBs)o=+Q_Tdn$EUH^|=Gk)2 zybuHDS&YLdpNb}$iwm*YLh=BH$oR*3eDk)#ioBkTd%V&wtEfd?OGgJt3(C^ID@gmd#DGY@K9)@y%paCLM_51{-RDs`=PCcyILG+U>3K(=QsmA5|7e9|G#sxA2YLM=Cl8& zEdSrJIVO?k*A!ZIvYFWI{AK=+Y#JmakCDDPFzG#^!D^o%1~`yo?e*aOOf&S0%+Ro# zf@+wn_$L9w4tWXp$9SvXULZJQKo?12yiT1-oSubP?&^=?p^v7Q6$9(4Yqgv8>FzzB zoeOi&RJiHBRF}))T=4*xQH*E+wGsbW9O-+%667 zX^T*$>?&&E{TwnodXBFb9UWrx=1B7exCp3#1oUCt6je9OD5$2>9roXTex62j>hxLz zYi3v8GTujVO69eKtplI9hzrvM@gW(BF5V-p*nSTy!rm5K7O7Xc-rB#=WC&MpG4WwL+Tp28Rv%@jr0u)H1d-tRYVM+!igvQ4{Fet}YiJtCo*#9l1Ygj|*$3 zjGvRMxjdxUm{C3a`45d#cj|WCF!5xy)MgJ_fxw6~)2@LYzNLX;*JDF};tCML4Vlgk zt%x_vX6j1&nK0j}+}H?yfoL_s5v(z|#x&>`ggEI%ZWa*ArJ-?J3goU(P*#!sPIN$U z)n0O17sh*0c-ILne@T@mt5ICIP8?>-0MODuUgH{hZtTqSDgbV~z-b?^0?=3ycWXq`VwiVqvN)~)30+~n zg~(kYAH8~do24!pspe#8rGOUZGctn9QRc3VDW(JCGtoM(pOd{r5Wq~hncPy~`E&lS z`?S@l?fge(X0B#Ff(FIcNK;UnHx6RkoezJd-o2O97sDI-Y(Fg@3Xg`T4L39~)Gqve zKkibUxW%^nD4l{0X@_@Y7IT09G?%Lm2kx>;Rl9ew2AvxqJxg@E=gxH2D#SK50Ue*C zaj*Y@4)fSc3Rf83wKq9MZN*0+ioZTBpsJ<9q}(Tnktw)+Iy^X`w_nq~CGOl`xdG8T zK&k(S_8!cVm8T1_*yl@VMC*V1`yQ4tSN8Kq&{W}$cS{V`bQ43OC1nSKAsxX>rzSlb&bWj2+Devm)Jp%>R6pqkN6>h` z)$Sj!#~)GjX_Y_~AcHdAn)~fY0<~GRxE13x`;<+)E0sXzbUrWI#XtG7ggCL&Mc(17 zen|O@EnfZ8z%ggp(~POyj4dg^%&J}>o_+%FNMK$WQg!x_$&43`BeY*2gkRo1=*Dfn z!h^I>L6ZK}&DzwwAyR^$N4^rMY>SJ;kc@kj&zninA4Pqp#yY0;b(V*-7jG`0iXR zSm3%KV2ru(E`lb#Vk0TQQ*XiIgu4PItb!;Ha1_CSkikVk-`7CVpv}gw{MUMi{HMv2 zwk`@=rioO4p&_7)iBJq&au)?SzT!_JcM-}6ubW;H%GzU5n7O;+=Y~wyjK_pF3UN$t z7>WUFzH1sJ;88kBs3xs4@}z%5=?k$n)NHmUKqewt-Z+_ab_P_&u__J*Hd?zu_JUXw zYnH0Euu9Wgb)2(f(4pFaOyixdbNHNBTWmG(g^G|cP@qB?-bIZ9k9l?Y6zI-!J&hyA zJ9Vb{FdIZu{4Lzg4HUt#(gXa5rAsVdJQf7-zOP9OaUz+2U%9Ky6-_25>Pf(*Vm<#o zR1egVI!KmRlWM!{uxfg4Sx7{OpcOrWXNg7M)?_DCo*AuH-9-vb(9ertWhye;k1=9M zu$og#JzA^_qdoepy`Fdc^`epeDyuY+!RwgUF6ps1W zw~j1{+%@?UjtjC9-x?E(G^C~?tY4Q&p#m7(+k@9&)g+FoJhp+Mr@L&S; z#mNB0+6GWleF)|Q6Tl6j)HDhF-Dc{Mx4gPy(ES7|W)}Z9UgUn7;an@wUe->Ui0&cD z0j|5oKS6Y(@L-FVQLF!IQ(A%1>Ct8w3)q?Q{}=58UNxN%EQ`d)g^r%ktdBh@U!5>A zSbbXk0ik)!8^P1c(aUbGSAbuavBmpfF<9LohMEMFJI?qgB7U=&sQgOX!mWr&*S|@SGMR(3?@NN0|ph%zoj{FEXJ~&CD@x|IkO| zM3>OL;)4BT9S~Lp;=m>ck}^$Y@7`sbF3*7Syoa4V(JxAmjikeLDr1%mo=U5>l(_SL zP?r@|?+fl_aP*|mOgR*=wTIWH$q$mhf%N!jszN{8%jOhiB??E@`fWUrsdoEJG0mTy zw6KTxR@9f8Kg#j70Rozx82N;Pkq!y*ek?Fgxcy0K@NM5A@^B{-+f-V zfm=FoaLmFzG(dlnI&b9!I3VM7q--ohr8zpQP$n6hB(9X^x^x{i;YLL4#7?FtLCU_t%!R1>R-iUsls_(+np4?vy z>V=*XKv;Z2iX=O8;sF_Y|=CXk$fb`iiPtfeP!=8;e?yJ3tC-D6_qz6#ew7&r4 z%=ihe(0Oxm_fPKIQdauTme`7?6lkOUUVAY{Iz{!h{bnWil&1U1^AGDg@LjT5*7eYa zzSAprtrOxVa|^vws|z|7NQ2e@ZHr9&Kcs+7qY|i5(J(*14tpc2(+Ir3&yfQa?6$iA zm(wj9c5Qhj&`$rUD^a_ zLkR~`tPyl$?bItFZnvr~bwEBq4*Y1nt&cW$8kUQ@zBV>LsZ+ zZkMQYY4RLIT8gKSTuo$TG!;CjYb-5lmC6RvK6&jjW_IhtywVPomK@=w7sE$Tpv$5q zCnG+MbZ~!^+mv&siM0Kl)t=Myi0%xaYY_o_X^1vX6r*wo_v-e0q+eDo?+eQ1-r$9J z3Uot|$Hkhm2)*%r@;*S#sS(2JU(Au_w}W0r^&}s&0e&XlR`vP}g6g5H)l{NEI>rEn zA7M(}F8$iiX8+i+Texg5D*#>;m5U17Af?)R(B3uQIi!gMG*lYA{unL71jn`ZoS`D0 zGY9wwfRX)wY|ai~#2E}4edgrT3OLZ)jO+!W%6BqOGE8kX{H*#RtvLC?4w?D^-0<%O zogjm#JdKns#eT5GG_ANGadgAQ(~9r%r1jIQ-k6RMATByzA=n4TPgYUF4%diZoK-r< z)N_7jvP5(6Z)()7zU?qfp+S(M{fA}@q}WT{NuP$lvH&nkEbm8)jmCTC=eeE=@|4P4 zmOj*8zTa8Ns*Z?QxeN%63-^;^euqU@HIOAF6rioeU(BtN&hT?fHszF#kZy%6ig!Pq zq$xX=$J~!7RB`gtOR0D7(1duBa&s`J{D{IQ>)MzD|Hfbm5TGF^Rqxu@%NUb?JSTdp zCm-hHJ@xj7lF$j;rZCx6j?#(@`JE2FJDhoTK}fuUs~RXt%#Qo zrqVIIUFqO-x=2_9Os*vHMeaDcZNQNwRdxn^;JC`vWCMoglHB5uWj#;Axu0l8g;GVo zEd0p43&;4$9kAArb*9zE)K!BQr40zP02-0XIubL*$u?ji0X!7{#|7wj;rXKVgz`S-yRYnVGOMJTB(Wl31jX62!1wo0{B)J*b3TlI`E8Qnvzy zQd7?mNuh}RY)KAt66+i&a2S8D>bbu`B= z=9z%mCPzM)joT&I=wR&UM{)?YJV&{SJG{00{M1Obo*xCX2j_Wa4caZzXXt%a=06Zr z9pRO8vvAr)qRO2@uqR9ptk=$zoaVNQ&b9w9A&f(b)G3so2&LW%EoD!Ml8Ft|R-u=USw z1CrN_eK_O=SWKS8-H@deV56EzY^J@Xu$|6wxJmT5EF-afZ%h)pMA8ooNIEObd6m8h zA$mrJ@sH>IfxRj91s0%tp^SCfs76TJRXN2|evy)Oh8H|a6hOy@aa<%;1>Lz!(7I&% z&{I1G`ku9nqvSF9z8UxrQa>3dS&3PT^EJ*NcyZ-x!JN?Bs zA1+5(Id-F5($ADSGPXPoU~l>^C>}Y$S1brc=%lh}{I2(C;hE+LPTt7ckH3``(HJz+ zg6=?dxE944+q^w@hicsG3=*s9uN}2h^7r9fqpF;VUs`5nN)CVvN_nog=B$#Y~eHugWKal;rp1Ne9lAX!WX{7t3+xhO|OJ$O0n*w}Jh5rlWo zC$oj@LbY(%`_> zCLn!5Ri9g8gfBsyJh_gdwPlCLN~?#5pItFt?EDnf%&f;3I8|1SC%wuZ-&1Ur9T#2TD?Cknmb}XTmSo`(3Kv;|-SE%al=_6ybm8eU ztBa^TBy%2tvtIFN(f-_aNX5Tkcrgyma@8nO^2^e@8Vh=ZC)2Ykx7sOWR}OE#EF9Kb z6~m^QGMzUtYh#TwEMLU4`37 zf56#)TKWs4!i{JSLjr%WDf zjfx=|)#ZIdAFs^O*Lo{=MUU%SAlR3N6KuQMa1 z-Z_{icO%EGHJrzu>{%UtbKM}U{}Zr6Q-Zg5bJQ8^9*$t+f3!BpZunO0>_d}Hvld4i zIlH=yWSu*qixl%Hc;<-p2#XB>a-C(tsMl3pu?FZf?<)|i3QJvXtcxmD@GO};_DRE8 z%)bt}eS4P%>%##tzooF(V|Ec`vh7r!YM9zz=!KXE)_KCgcr6%t^C9xTqMmjliW{&L zOKRWhhd(h=klI{*`+`W8$L5)VsmKWy;JCXHIM=-oKj|3=^wSOt_@KHtz$oX_tHY z{G}pIQEF%lllNcJ>2lzy&7^|8l07tZ2{&(hxw)3pJ_S=YO$ffL^21yeff((|X~cS0 zrjY<>-RybEX*Pql^du{Eyq}Yw3T5y8_0SzDo`l+irV;srJe=(N=CU&$00Xtag%x{5 zMM7~w?o^ZEoGQc?>{YbM&`_;Hp{qsX@4lH@Q}lWjwgPaig-iE zyswJ9kF1Ec+F*f3W&DmhAbEt2FnVU!aKG^GW0MoIN_+EcEW{q-k@vU%u~PqTCsGS+ z8AWO6jHy@iI>XBal|SVLUI|aWE@ZQ_n}4$;1$qc3zSoRbbblK8$*naKx9jvr_R=bQ z(X$C1KYDF9F!SjZVU`nY^)=DoANi&SMg0d-ZtBZYZVvQs%eR4BKV2d37TH)5V2U6A zMlBHWe`oxUu8MXai30%WCe ztBP89uATmEEfvag`nh3?bU?x_2S~Ujg_sr@q+a9t-?^5SzHyP4o`e09d|IfoHk2%l z_Kz+2aAqhUn$!P7n`%BT_t|Qdkehus#Vh;4L^!J(_muen%yO--UwCR~(iEyRIg}L_ zuvE^zLr7vwPtMb zXK$Jgd{@un3oGWL&8Qyo5bsBT0*$YDkJ@RbOy*pR-v2>e;Y@NKt(NrX|CW7cnI|4Y zNBB)7xHPxaP26B0Ec{%db6cIn#IJ`!)p*6T+Zl|fzO<@j>_Iu(5+B1IEu|sT4Mj5K zA0qN9Z)9rsnsWu`k|?*IJ@s@OXIbqv9311m(~iD1(od9})!1BHGI^_E^oZpXiVy$_ ziSU5-tVLz+OW7u5iR6ik{Clo7fdi`-)Q{6T)wk21!sw3MjX?k+X{sjwHY{HTN>cCMFo1u{ga)8}y+kU*OGtu?Q)AeDAr1$~n4D zG#;6LA9zt*<-kgSHeSHq*gDzlUh^uU;pHXGW(&uWlttxTpetWHjm@gw3%5Fj5~p~Y z9HVF|7~ug?vU>)B&HJ*t>Jl`~7!EGc+L)%?f}uKLd2;fmwFFilxP#AA% z((_;Ou9$hSFnu67fL&%u(Fn#^5WAeeRFMet5y-z{TNe8_5eDA~(Bg;!uH+xX5H@Xs z=RB__o$v6bhhdNQ#uq7`F4JaSD6?7SR?V_89ljhU(2+5)8+|jh{Op~Kttz{IcGYm- z5W=>Vez2v1+ZHgOV=V18KGkMRa~xP9cQ-?!_u`~g@ zD=NE58FQMqsC*@*&HLWj`PE4A5C6_bw9W;+Snsk$Tz}?A zTjWDnMl*Vv-!-Ey)qo+T8BjJ8tbeTuPSRqU#VVn;E$+99cLl?aTuJCs@nt{a-zc+2 zrfi91N3G~8|A%&3X><;V5;DzB4`Ep9k2mj81m&Thp?jE)6ix;od$@FMCEV2dFaHfp zl50Y9aDMIIG^ie+QgFYO_w8+vip{DjU1PMYhQsGi{S7eb2OODLEw7ZT&Qmp+0>c&4 zftqxKj1Az!YQeVbJ!EG2FMx5tyeJ_Zm&~Ge`yNFS^f&pqliYPb4$=^aGOwdPW3Qnm zpCf5RF^*r1dKY#c`Xh3_o0f#y85qu{JAt~xnuzg@q%%%v0Ca8ztmNSt5rS=R*&)_&vd4mMLN(tZ^p+E z-jv@$b*xd@?dxz|nS0fAZ#5n{e399n3v(-Ybo$9QkmZPIB*=70mc#gzt1aQtHG&yx z>*2u$KA$#hmhJz{+KUw4`S51Hhe~m%={^;rcm1hAK!DeYqonaD04a$gI1_ooxb}zO z5lp5IT^F5|7Eg@EZO%DVt-Xjmyj81*P4ld?&Zv=9?RMbdB_9lJ?7ky?asLKVRL(s1 z+*_rG)!{Z~d4#Sj(vkZ}3{Xh4Q@|>HStqVy54l|WT>?1tOuPBIVnr}b%{vVyO26FC zxbm8CZ)YW(xR|#7*J1<{qIxyYBUb-LG0a*0dtyukb(75w3|UP-K`p#Q9!MW~gMXd) z&Tod1ayb{lGm6tXrs~@bu8^ZnWJ>2}?lJZEy|taAtimS3AM<4lh18VJX-9P)GnAlJ zYcfE-GuuKaz(Jx3bJFr6>${;9%+i+`(*XAZ%K0{lGQB;5eNraf&|(F-kEY zk{YG^Ch|YDGzl*&oYA0s)cW3d)q8#l{?P;i;Y8dm$qcCtXZRr+T= zJ?TGW_M}{WUL4HKNU=n4kI>$F6t|em9h+i4X3IXZO5^@s*s)Wf21Z42Qu)o0!NtmS z{f9P+Lc=*38eBk=!QxVJVXQv`-l!j`i0Y8OhSF!9LnAY2RIDrK`fp0sc+kfY=Al!95H`CY zaqJ9nCKXj)H`BF-s7-^ZAjaEIrN>lvykBUS5Li?u-@65t0OF&zz=>y>vI4#XBA2bb z^+7}5*%=cq>){ScV+{;>i9S(p6MBwuXFZ-+F zGKx@5|6S?{1PlAv?r*A@(Y3mq;{9qXz3@3_^oRO8m7Bz>(rYz+Gz-!AWWfx_SGc6v z+-cocC3seX;kz6Q28|+f40Lx|fgJ&eJ6Yp`W=Q)`$H;VLQw&#>qC4;EchPzGgvnjT z)K<*93PkDc_a`O%RHn;)A}?cPwprDNHxa#cGatcA`tL#lDiT3Xr^$4#iYt0`W2aV! z(qpXt^TNhuK#kQL1FISHjgj#?|2^+{@W=4FegAdeArZWP(8?WY`4o%tc!`EX&j;>BdtsUEPoh7hS2C{kJuXI_ z^kxJhA-sTHuWC1H9IEn%QXYe@5f&Q-H;CloK2-jfpW9>z9FqHYb^51~hf*}>R0eI% z&ivtC?*^tZ{eL<9TPssPi}tkfhbP)do7{=I;JPw)p+DC_`?MB9dbKYo7f_m3bi@J% zJDF#%1Busu%c+zMLGoFZL9Z;&o>c!`kJ4Cy=uN9Nohk!a2`qx6kex(lrqZ&_FI9ho zMF>BY)AbvYYf6+X$%H!zMyZ@?yN)xR1RQ>rAE)IKcooheEf}iY9cHz1RxKi^?)_-v z(X&Liw-jW9eRzy7K=SDkE$_lKi2GE*;L0nPD3rxA{LPNzVO*s|(3wc*I(5?gmKykopWG-#vt(K`gQ-V_zG$yA#U2 zVvT81u5acEJ5Zvz>?JqEsO4KD3mGckUl@?R+5;voncCR>TkS+Cn4SFGn2^54PyX!B z!SXQ+l-y%rc>r;XSga;{oCl)n$UvbaAHLObgH8mpnE6{ngbUk1!0ZCh49v-1QMh7% z=}>OqO{xq|(|A^!L?647tW8$1<3qoMig36=kVCQu8&UCMt-876O!c*Y289dEzS5vO z?GN^P=~I}_HGC(xXBSrZ$K`VkT1EqUbBRGUvQt5wA1`9eTYiG`bpUux2WGdW0QUhG zA8=$g+EMa&{#y`smOCIaSYRem#Na%E6q(Ec@J#mafWDjli>H9U$u|g-)tDS~9Ri#H zEMMWq`ML(?qTgc9{q)Lkt`(FD?6@!CSASgSEVtRh?tdMGC51huOmIH)HDiyp$SMzY zhJ5arfyYic_m@@!)$J(S$vr-&Q~tIBSNT$l2Ms;Ry0zcM;mZ~I`!7&J(oSU+DwePXf0W*M z^2qF5c?}i5REZs&wS|xIsgV0BvM!(XXZFv`p`A&G2FvU7opF_psqpS3dXE(^ParqXe}0=O^E?oqPyxcgx~t3Vy-`I1`Orbk zHqo!wh8E?+u(YSVLiT#wlr{`~JYqtbw*m_B-?UVLtGtoEqMlQ; zb4jZAG4F|dr0XNS(70H)e+rPmmg=%@Az8hsS_7q{e^`Z97=Yz)vtb_GWRzxH;28Ds zb49&T;sqQpuF^cBL=$D_@O>ygYR%~1Vbj>k0hK*O67+!Q|H!ibN9D{U4mj}id6KmTb?%ASXcstFK*BX^VAjR@XsY(^>4r-|NX+_0^bqTTTP`~FfVaKM& zz=Cxm04gNhT8*%HKNf0)^Q#XSIzD2*{EEor7@vY>ZnWZwZ>!5aZjcs<>^*ZgdW}FQ zd>joi4f!nFp?P=@nreFkYZ`|ce#kO{nBV>!I(qDl1|o>fp5U>zLU{92(K@Gv-NMpt zItpy`hP)>(VyY9V>fCPzRMe%9B6SNF08(?jRyykMa#&a+-L)6suJXU9fbt+|f{tf+SR)Q`ubGeL{-G8YBLKC;k_nuLLTrrg{0@ z-V2g92KR);@Ne7@s&W@*h+o4+Fs!uG-KWv3P9QAK8EV!ewsO#w(3gFJ9fzvXX-=x5 zYXe{w?PrlT{d$Vtk;xyZpO@P;bz<%)!|vx3zvA`!#P+wz#}7e&3Xxqv@b`A5XIC}d zyFQE)Pd6fQBwNx5)+KPy^3-R@Y<^-|$4U&h7KL9h{pXG5eq)s+Kud7jGrKz_%+4&Wi_0qspIP27LM&dQ=@SNBnH zO(Ih@5#=6MZ_`8NZV#Rn@Quo@LX>(`RtYDGvr9ONV3NwmJi%sJNOQDzhBHc+{v~qM zLS<_d$VFRoG(5Vz1J*Fh=e_|5J6cM8<(N6yGua_g0j(pOeuvV6%GQJ_IG+M(7v|l3 z!6?uM5e5jxDWH`o&`2n}&dyZ++_1t1zxzFOtlM!x05g;BekX4+xjV@|5}eiNRp8p~ zMz~*zM7KH=FEl;U6V1r$5)7tKgQeE?KX2Q%C1j04bF;D zxgkitwsbAydMcbIx{7sD^$LJ>v=-+CD*BS-L>n%x;!;&k@@_XqZcX)VzKdv}<2vp_ z+DzDgSHg(3vR|spJvSIgGLw46y^hIW9?dKw&GNe@XZcXiWl5Psg$Y*t(NuHTOrkIs zA;SomI(P=^r-4E1$It)JA}q$w86KM&{y908xq;1{xoCf$>>Dznfwf*|Tr^xnN|Qok zHMvmoW;4e3n4gexM%}rwPY!7n{u#GLk7DlKB^{^_jNN^1o|({2*2=W#MLcA5OAJT^ zRve7Cn41PFQ772_Ru&npilyB9ohbA8;cz#8dn}9;`CT}gx`vbNg0tCmL19;Zx%loy z0j|1S+;5H*;IVt;OSMcq^MU;d-EcS~=ool>9n}q(KAX?|E?UpI=b}=(V>O0#f`)## zlT2$raPTt~g2%H_D#Fz5L4ve2mn8MT28_~lq` zp9b8|I&JPDzp5KFChMD}IaU@vD|{B&emkywl>v2X{j#`=GmK{S>2IuI4sQ43Yle~E zJEnW5{`XG+fNTA~*6eMEn?Z*i%PQYVDv8NYy*i;&JKwSF;IWTAjCa~KV)+ZpsomdR zK~5wwuS!DwTt71bDBTNT`wuvW+!x8NF!1`9j_12Wg_>;8t9}~pyDsz`pdDv{d%~s`8Y=z4 z>n7{NggyR#n02f_Hm~xWn`m8QJ#W4wMJ^iuvbY60^mqZO?~ps5%UT9m#^UbFjKI01|nvg;|YLC93ALyzj6Fa3-*Duoj{1}T$_C_FLSoeLPYsKZ%4R6U_1 zh>&}Mp6W9N3V-4;kiNMnuxK|~BrP;0%<(B5OmG*WS_yEbcc>#eZ z=MbbUOtZO6OoiWrhMJ0yknF#Xzr8vRQ-PUrqDuD?DdPv}Z_l867^F7Z#$nBlqra!j zAs)k3kuYQiLb_3^&GlV9YSrQQ7NPsV_0ae9p+&)!>Q@49QRaR#B;+`E_Jdu(N^PFm z-2f??ssC|kVtF65mDeJr!@zqAYfa_}-kgp0`~?9hY2mrKdZe)|U6c1yz|c$d(fi;Tq7-skZ{Xeb>k6E@XF#8)Txe! zFjhv}_1AKVVsuzFm?EV|5ANTU*56mHqK8EByg)aQ6?$U$4b}!ex-VXr=14@}>Fgg9 zME$9d$5t_zQwhGxo4JzPG)MyYBf!A}JjTo|Tbs0vGc8&>hIObS{F4*-sq>$N{<0s$ zpGr%mP#1ioBB9V}t(Z&FZCX`6-$~XH>&B4Cx=DYxIf!D1RXB}01(o9{*s)#Ds~YI< zjz$Dz86ZIN_zeH{HUkfaMEKPJ@{nP@hs-sBW8BS)vNqB`nc0Aq`QEL##&f#+3_Yxy znKB-DN6OFbeq#k$-m)8Sw z@2W0k3z|g6t&g~NGqWU}3#WyBL6|nv6k$YC;B_|x-?|(JVAgVZ7%VfzEL@QTMOP>@ z(}*}J<28c3GpO52_(?>`Qv>+2omS{|fU9Gv@Jr)@)qWSk-uX1rq52KZJM05@SP@TV zWRJS4Y@(XtMa3H%L%QiY=F)F726h6{Qkp9TSp$S)3dKgNxa(^xatBmuQr;QiSMTO{ z#`*A4h8^{U0Zu3DAa=B}G_KR`l}W>DyS8#_8x?N{be zk`qBS^ci9NEy5W)aLvENqrAVbTK{RqZRlY`Ut7&p1y)^ia^DGSiF*&UUaZ1oqRz6e zj7zA{(>?~soHv%yo*1hUdGJd5{eLZ;gM@_q)WP_J4Q)&cen53?|A=(9nbFjy3g}EKj)b`!qau{qEn*w#3Q%JM^ zXI%;H&#T{Ts3<+<-o1(+!Bu%DF;RY&*|ra6k7yNWOt<&4=+1Cb*P2niqTV z$7J{%AlO<`>n7Nq4^Kv`dg)MEc?*?;fXd%za1cv!!&Egsh2`0xz*@VtExmM>1(ctk zpMHvaXKbKc{IG2%r~Hg$S-nB!O$F@Do(`gJBVO|ze!tUP{Y9w*%p-p;_56`IHqfqE zArxmOVJf+1|e`5=0FhU2lOEU_@!qYKp6)#oqi z=OU*fVid428Bi>98KDx79rIf?K(5{yP5ia|fpzTX1`l+| zvZ2iPC|@Buc@VUTdR?m>)55m^!!%$mj><)f zF`j~@?%H}rNaV!>!7kRp%SVj`Lc)b}@95DRL$D~3dp0F8=o_ag(+p z6n@^Na{Qji{@C~1I_K5q$CwTN)vs{$KlxZKr9+@|n8S(}m=V78A;uyyzwvlI4&Yu- z0vB|8Ai}tI3l|AL_I|c~b6lq{WThiF!#S*6JtQZD=I7`;P;oU@@^tg-g9VS%6tI+@ zz$O#d^^-C}lMgOz`q0MlUvIUXG__opPU&1B~zm{KBVI5u@q9yU>TK zAH^B(?NihPp>a-f*$k_|RMX{C@FSX;pprT={KIW#ET;+?)%&i{-fJM+cIZpBU{qSv zZ}Rf9YFaCBa4gM>S#1eXI$pquW(#0%+OlAwJ@=xyVaR&(qD1T~=ks*-VNn>as2?0B z&-U`}=a5l%Y`<~R2b05^B})fvenw>9fPgw7oncnposzRJXCy z$uJQvs3FZ=nbFq9uXw4R<`|wrnq%g!DWWDgZspOb;`nrCuHT*&Oq5`s&zH}^86KGK z&PSK3BBZV&MPFjoq4`~l^)|xtGf)fyJU=8P-*BRfwaXiNSUF9;Cv8PKi=F^Kr_tosK0s@=bWV$HLdatv447t#-5}pQ zh!^;#a(eZuBWC!%-vn55_;_j8+VmF8$IQzhMel;B+JTDHsYDztmpHoD2i+vnZ~}{8 zecto(v(f3YWDnwviVgA|4W!UI{_LS8_syJlX54aa0tJmcGY^Gs&Kbjx6K$^N2DGec zWZO21XYV*0%?7(N9-BNQ7uaux7cNmN6@4i!FBj36Zl!iu&3O2><7=S8mm6oCn(D$A z>Pw}a{%GaFgZ=-Bn*LRUNUpNA?-*m&|~!ea0BBi zpoc|I;*7s>==v!D^7}B2nNDmclCT$MTN!%gpZVXLtnu_nyTJ8?*E@MF%3X~kkuYko z{AGXWYJE-I!Uz0+F2EW0if1$OMl(-1HTjxyU8Hb&TtP``TYjhWIS0Gajujr z=LcjcA1sG;o`EKzuIIr8v!zs3_UVmC9%JlJF|X%C?IE8u4p?U1md0I73MS#O_hcm8 zYJH7i5B#{;zHhx@OXJ$Mz6?G8w5#!Aq_4;m@L4{PcBiI7~Iv^-A(c0!sn{FMo~}M*T&^vmHkw%Q4{;sgs_6L zlKgKy1wV2IeJ9SU3%YnMX2NyzFt%Mq0Ch8N!-%%esY*3kwJ{%erOU6~+||j-xdgQy z!S6pvPa8Mgekj*o(C0mPYX-oR`{B$j*k8|Qqt%s?yqaHJBMXTJO@wa3r;mnOSVPWf z*AlD0uP0+~$&8hXEeV^6;-MrB(wpHi0KA4ue)V#y)r$c>j+EmfOwb)aT>XsVjwRz@ z>#IQFHQ@2^GdJXs@|o=BAV!wJQx7b@3BPI0@0xYxA&wxJtz&x^l+VDQ8 zWf%47TJ!TTqRO-{b52pfAqgl|ZfxLNEzcwAxy)Yc`;e)a_4a0@N$x!F<$Rhv2zb4v zpa_2P(lA#4UN;(ux&j~5HJSEwr$4G?4bfz{|8@O6noj&*nM%c!lW%Tv`P36m_|K{^m;&!nRzYkR0WSR}$ z2wWe!C(jl(nkc&~t30`QZtD^aWzRvt^7m;T?IRy%ohEKm$!-*C{7LVf<@RIrbNa9~ zyS5L=8tjnslt>Rx+hJ&-wAS^AMjvhPcj})KV>NHRiHaLO?~k#%0R-g9R0z0qk><<5 zYuF#Gmf!JMKnbb7foqKs0Xe>dAHw!`Qv=?-G|RA^H!x@8G(u*@*M_+(ABFY?F{C;V zdEHEUKL|{{f-uAY=tY^dO{7~nq5e(QxcJTHF;|Gy`L=-|Z&-CQFrr&=Zr&%(-W7`I zHADn->8!=0O4fiqK^W%@;{?~Nb6DxyED^-(;dLFfdxLllA8&q#tK{3eAP)eFUbK>W z$7*0vCm$!wceN|;A?f&LZ$P|&#ZSo$>PKNoA$NFOoA{Fc{F1RYLTdgCZgj3F_NKu$ z3WyesRL`khiV(%tTzO;{+9g^igEJhkw^+nkpIES!85x(zT>eS9M$YxXy3-7qL=76z zn=MUSvL)*Gfg-w}`iNm?za`#?Uk2Z8jXp54o}xj;bS( z_e{i&@?cbFGi zD_A^zH+ox;ke1Q&P(6LEb5UeZsuOm{>f5+(vIwLWQh`e`F(R^B$gz2uCZQ8jEc9p& z3%bQT-yHRG&d(TKl1lSca{BIA&8{!v$DMlpFBVtUC)Q{_`*IJH`x@1IYiV!@GKGyp zUyt@M0C;#aYnuEc5TM|=$g#CQi()PU?aaN`&#mi1mg^6m*ouW75DG!Y|K~@ zsBR4+)|m1uKFa>!>-Xz>0;b)FeC})9GSt}8A<$e76wOfBXq_@Ve@=%h`jQQYoC<~S z9Jj+;WBm~8Ce#QN{RXxC5HaCazE`nLeE2>77nJ?6jo>dRHx9seaO#|1wTRXj7w3z2 zKO_TETMxzYuRSF$L{jW|R+4WoO(AcGFbz+K<6NJ>XA_WbHsH#4bn0JI7#U4B*4~4- zH?t06orZtl+Y^qLX_2j0Q#+P*7m!S*Y8 zx0IX~pV@miiEngHe~lIDyr2*Kr{zOjthcPbC8y3Rcal}@3ruf3ed<2^QxXF(I^lEO z)v^rgqblpl;BNUWo-RLlgYxXIjKSGl+F|%(X9Hn$^PlC7AK1fIzm;pRJt3$228z;p z!l9cpO&cx>p{Bv&!U&QTfuJmHD_+v*XU0yAKqF@CsNA-3e(q|j8VZZi>vCJo z>KzUjL2y=Fi~RF-{*4&0oB=uE2iuZJz(E(#s@l5on{Y|-YL#2aav1tol4!u}1C~D! zq1y3NaLgHSryq;}CO&^aLD2xTB!wTqFUtQ=wLiVZgmXr07`uHnk%Y^@w;e9NS-_WN zL_Zea$A3GW&hCFj7(|0Xdko^C!d*NHH(J=t9{^hem1-WeMfP4e0(vQp{2!^L85VtmZXN++X*qX2IU#Nv> zjTtscbVQsoJ&;lnTu&sI+U!f4HvkJivq2>$oxU_r(<`?N*OH!{64P5aF8VJvc?23R z#aX44ryAz`G_TNiuau~{o%t$r-wIqfHo!ZiDiqQ4?q9zY8}^Qrhncb^wi;L-W%j8e zY)jo+P9m*xd%))@5N^jENLwNOd400{E7J8^4ybRETm%06r;#R;@$vs$i7e@f%*ij~ zA06q^1}W*>FvKAMq}%gM&xf&V_6en+DSf>(@R=>|bm|2L;Cn89tv)W=&S3PO|NW?k zGpfB(Loz&UW^1eYeJx!)%NA3e{!v0kv?s=u1{q?;{G*UYiZ6*E2pG{)`6_X__wYJ*&-jZfpdKzb3}pwmTKi z>y;NI=Eisz9apdiFmW(X%%{%y%mM3l)gw!Q0{+4H!#Fjj|BzT-bn3X_jrw>16MN=N zR61Bp(dp6Jy*1kCh$fl*dSDFRd?Io(Yp%PWy?m66%9A0zJOFi_{kksl>lzrG3j z9$bw10-u(n%-(b2AF>tJ+!z2ebHI0>yR6~d9ITBE`TWKKJDo&}Po%j@Kh4bZ?15#J zme2ZX8n~{3d>U~70AFe7GS)!Lfi&n|$s&+eBB4N?g|CGRQ;PaGsvA!sTXhDU62g49RQ*(xn_8H+GDf*( zo$y>qf66$L4R40$E%W&fE~jtc8tbwB)> zSUKncqA#^IZ3S~%(f`)RFUx}Z_&vuGyvY7{x(#>*x?@qxVCXHLDzkjGiU&>>2oUyz z-r$}R3Q+7f)5WEDy1fqIGl03Yu24dLGF2m-d&tzx5; zy8O3?$56Z&t=Zr$DZVG%(h>>~b=Bu`YmR4~+9%!K?+IjbFr0pM?q~xYaLp_j-YVW% zw@ZlIHLbE!77g>=-Lu?%Z>J z9&%3&Dj$~IkXDMl{qM3yko`XJLm+Z2WVvZnUnO50m@-fnz;4O6Wbb3XSi~Doq{D3; z$yS*+f7$!TQ{M^UwIu%{J>K9<@pLYHM#09A8?|+#ePhIHVGcmcbQ9>z|I~Frp!>=O zAgTl3r0a;gm#iNK%@5mdC%?3zvO6D3Dg&yh%&7OTe#cjtL=q?uT0yzr;@4Fd(}BF_ zl|eE_uc5$BG;359j@Ycr7~5WK`GcWWT-p6nC+1&JsZ{%)tTFSeZ+Q%+ZRTHqC1`6a z@P@U3eVE%j*y!2SDsZqS#*sdVYCXMUFqs4v!J=N6tO1;m)p@6nvkU?MGV;JMF=>Nh zoH(#k-{(DP6zsa{dQ`C)Bf5icN&`8{StY*&`~%g4k#_sXhGK+ttA63wCk0OTA=}}3 z*#>WiqCWF*3_oJOSu!i}K>Tqp2Ex0I;>SmYwTUJ){)eCa{!j&5ldv(g7B$9@-go0;HY68uA9U=0T(=22kxo* zh^D=BE~@-FA|YG~^Z=ly(~2?bZq!~ov$(4ck1n@mm7l>Dwci|ZSM~8~{P2gg?_H=H55~1^LiTGOSRNcC*7ZAc1 zZU-(a?Gx+WTUcgF$6!rkNjBXs@a-$aX^Bi6`&2dNd5){vS1(Gmd%J$^C*=J&fSvm^ zjyss9J`P>+>JP)%p%J&rjAS2{kiYKoVOEgS-uH#<$bVPcuH+@WJ0`kc9@olTVuepO zG7jx107b+`#ubuniA{Nm<3QYR%Wj#T@SQB#wThz_sgb6@{ENol?&KM6=6tyx!2j-f zj+%2X?1$>NFb>c)62b9uB4ktPCAei-$ z=hyemh-o*7f2lSf{|xrBcJr%Iz_mUrpx0n@e{kvl=VGG;E^zD9)X%RPczj-mq3c@xZ%4&H@bR&VW07>1lpa zOvG=BbfvBW5>m0Xt6X?xx5ZcJ36Hf0@}IPRdBQNEv9I0sJsOAv&k3D#mZzVtt{MUW zEcK(9gCYAa5gLJum=EGX-Jk9NOe0xGwCmj=9W14Sa1`Y{<6HfkA>+otW#O7r^jd8wNg%(zCU7Iv@aZt zU6)>y0X@pmFWXxD#+e+9-VGP``jUs$yB6-&ClIeF<&=W}>S@P-@5VeWhsRb$I?Z={vl%J`sU=Ys;Q!C^6W+?)u>2uJ}}kyUnFB_GMBb@`BW==fBg6o7pt zI_-64%{K=o#?rQBC0r`v@~H9!alLEg8<<7xS~v&33jU9Y?wb_LY{0nvuk>@EQW?Y67ece^pFJ%hY__Fdop=*RM=b84_&`!E zEN>?wpuxjl}SCMHtb$DBdB zUJ~OV;MZJB(^QbLEY!u&xS3Zd-Cs~iG?v-$O4GCH<#U{*zaX?w%L(zb!M(4?3{NiG zYet_tufKq3T!);L(sn;;;@Iu37bs-T=~#-SF7UrWc2^!TFSJt+&;F8N4w2G65l6}J zpXGb**<$xq^SQ3YD)P-60KVL*oaPgqlF!0z|8xrZe>w%5k#VHV-Pu2eYIesCebTu(Pt~#WI=0$y zlMR{eVb$w#*_o7I!T&9d2F6~G(r(FkV&~=1i%V^MFA>XyVq=aaI8D5I`N+@lW2xU4 zRqAo1eg^@NgI~Rq$iMTPB9m5WlCyVwTRfokyj;h`aL0L0T`^gDr@J2H7>)H>b-sl; zC)bL=s@~>B3|<&9(Xhmv?-ytAJe<&4J;8NE*!euy7MlL>VJWK_hO6@`{P8?J^Xr2F z(7k17q_ht(Ik|T4VXuCG9y3PR{1>nKYqjE^^j-@%@v8&r77rp1}nU8pT#q@U@f^J1kF$V;l}zNkr0}wOkfKTbG&+ z^OOx?Cb5{0ihhE()vcTG6N;Kvhlm5u^6&!sueAVOcNnaP5dmR~KG^$n@2JaeiTqq> zMoDSWb5Q=8t4?ZPb>-sXJ1>5y?Z$W5ocLlNfPL+%hRvZj$R8eFTu+s~RBor4prx-s zul*~oejC`TJ4@nZEw@v3XJm-0ZUtXSIoph#WU(jorBo1=7E!0PvMGY4_ zlo}uub2ygIc@-93k*2D8)+zO;B79G~ZruK$%e<-X`?wHrZ0nXbq@pa0qGjY29mo8q zT^&U4qLj>?g@aZ;>aok2*!D?@Vi*NZRpWL*JSFBX2EiH#eKdW2WWKkt6tzY}IQqn& z3VGauZ+&8+n-uSO`zA?8Yj*0W^kewv+Mv&Jyjgx9N*#5f&Pa!KQgUYtx2S>N68S3Mt6Qe#?t(=!%5#P@h@WYQ|`xba4~uR{NgZu`CO-{e%fR{ zeePx|J7u|Y7jc^BIiCOGbscIK$z1xhACY8l_o5H@lF)^dOq z>(`8J9{J1({7NtH%W`q-CUUNg&ZE!eyq?MpqCVCKcX;`4PU{Aa>Pkb@Ko0=-hj{Ks z=;jrI$F(glGfgWV;35vCbR!3{zupQN?9!<0C^0|eAO;ie?+)8k(au$|1i#=SPUNOkE_lbIys8{S!Gc0EM$uA~1N|$OO34PXO*87jgWamGd-_ z&P|`-*7t2cH@({KyT_A~53n&hV|u+Xp9uhpT~s(6`k#<3o~{QVdoY>Dr{7@6RjGX~ zEpK04Cn0j`@Y2d{TcYNA{yA<##l{boXstZkc0>F&*05-yf)u!j7zSUdL8EyWs6LEL z&(BkdS##CG+QgZ{_6 zp{R4jDbCb37%3T<)_i(brQ3jL;K71M_8#f&j=6qmGebkJ$nA%E?_ihupmM` z8v5d!FFqa&hS)}b0;+8y}bP1OiCBU+EQ@K7wn4H z08N9(R{3F#W6%r0uE-=H3(#B+|7Ba6lDA{-s&wmGl6NuPTe4?F{QFlPeO{dL=Ctl* zB{jBjZCgE~YxMU$e$s@wJb!q=`j#@4qo)OdeT{1^ZLVqn^>i~YyFn^?)(%Q@%W^Bs{%9Q!FN_O(W5(!@t4!*n-BM2stO3KiVN$8wr_ zc)e4{Z;n)mMx+X5pki`0uD(9XJdIFlAJDIr;sML3`7xbQ@U9gG00qIECjM;RgYW%LXx=C{h&0;a&cF z@h{nqZ_NwbSwxWv{A2qynzn0{|5+cWGLuZKs42g!lCVKiLk`p0&AIt8YgNRUBNNEYuzCJ}>KLz|IR zvSVh)Biy1dy9il)uJm~l! zuz{kf-ucp89%UglJm3xfRH&L-N*vZZ zxh=4mK~CjF6p&^G7l+S${J4sDK##xoL}kaivTJ!rWmPv7Jr|ShJDv{Bk>ttW7L73n z83(*kI(roFj5(IYK{K6=_h-3WR6E||jAR|fQwKP^-{g9NNS=r!!wMuaLb#;@inK674aOgn5JI zm98|o%I>?MlQH_PY!f0so~P+lgjB_6rga91&&$+s7c6Ug{{@j+Zf|w|1-*jaybsW& zpGtP%x8GJeOda?4Q37G@hG!)q$oX6Em?(w)a+Tngc5p9eJosS`_G!^}qfVyY(M=?D zhV9d}8g+6$rrVPMN-D>zDPDkRKqqu&SEdQuFSj2- zrs$8#N$H@(`N{u+gqdY+N)DXYbO%{)V-p`V_D3v{KKTPY4pI+m^7uNqO;{SC7a@_e zS6X_t?eBiP-u`j*X~S9SUrSoOj4X&f03=nfhb71t|EAfeVy43VtaVb zG_XlMyc!-6=ZWYTqmcd-TBCpE`@m?E_9_%}+zIy0#1~Nrylfg_>yD3# zP8DqJOw4fHV0+~b$w(y5W~s6zPCq(?9*N5Une_9ZL)J|z`xI!^9jfUPk$G<2fnDA< zDp8p(+tFM61wk5N-<+op=P0Uk7U1SPliz(ZzbW`|2HsFu?kFaP`~txmmEJvf-CT$i zbeX}z&{28Q;#d4k)$Q404zHcZN}SG;zuPb~@a*-NetmBh)E(}kAa*;bJo^B;9exl* zVn9bm2*6_Joq~PC@V>f2L@31@8GPGG*Yt;`1>mXg~F-3Cqtu;$KH~RDq~P`F+|W*FX&X zdsH-h)(k$9`eEjlg2{=6vzsJrlf;hlY5(^p3zHr)w*&xOVJ01Yb}R9KFaaLGvJ>!c z%BGwCNPdZ#YZ@4^nDXbSH?Jq_zJll)iH>NcXiPHqa=(xGm#9T2#1Ac4t~ze9%h0{} z727ItG+%~y6MFd{^OVg>JZFV%yT@$`risRI^hOlwl7h$@c zflZDs@#9pQtkPztlMCn!&$&?aW@r808us|-r@%zksVK7NIkmIH*_HqEF;xc?mYY5kBM?S-4NYqFL%4QYXSQ8vN_rWD12yvs&~m|5EX%3ZS;hj zdbusHdR?WRqOzz+R<)|3<5^L3DHpYXT6`=Lfl3R_(b}9wm+5={Xh&tHI!00iQCfe4 z2C9E~>_(h4nZG0Sv>5n4TMSX6zoujYlpnR&`P^vbSAb6k-J$e&ksAIzh7Mw-pNX9T$&D96hPd>CK%jjC`82h#TXPzKh~m^!2o_l0d>rsDF*1bKzESshv=+<#}69Gu;{ASVvn{r>}6MBiKxyGU=+Q;9;QXh@u7)O8i0aWNA}lVMF0o(j?Gd8Z1Gjg@0==qBQ7UGdLVF@ zqoa%?EJpIwVY+0tT>?07@4GL)RdAp3CN;=uI4(w>m#i#GqKnH$ErG^DN$a$sTz0N+ zl2t-#f`ZAjm!v0sKJ@?I#k5Byb??JeaALBg6 z#>K(G!NbGFe@aU5^vRQ_l+Q_sNNK6SbhK17G%p#sSzf;4WT2s86=LIj!^6+d4`z8Q zF3c;&&BxFC-;ZG6;o&`f@|1#rfP$BvhMxET^Y!otM2w5^3k!sW@d|`VjDbar@z4bV zgFqPAz}^0L!~g5Tz{Gll{TK%q5B~}9g}P@TObje6%tu(**pD6o-}VPS2R$OjeooIL z`Itn_6z7!-DQ{qGHZFry)n798u~SAqGuI$I{1@aDlvGU2EUawo`~reP!f!?1OUuYY z<>VDKG_|yKboKPjEiA39ZEWq_+&w%$dwKf=hlG9&3y+A5i%&>QO8$|OnvSilpa8wQ$?*90kCN!gTe_HbWk&% zn04;UJ4cIn)GYj}TPwad)fF}Cn1#m7MT~h9p7Yd!pKynMYPeWt{7dWd%&6s`k2U|! z+0o5?b!~&>?i^%Ndw4lZDC$$WBkaPEfGiYeGee!(%w__1X|xjW#zaCydh;@ zWYQGH5_6S|ELeuzn2%gA7ml||mfJNayl`+k?^}7R2@0jj{BdMZbqj_@CHtljwZL~d zo)`-*)3inK`;RX2k}xz3NnK+}w4ya_F5i`p9_c{Gry{64>U}nQ@K7>(-=26ukB`P6 zOCLD;H_skd3VyZ|5_Ou5*NN!J?F8;G)Ri#uL^ebvCjg8YZg zasF%eeD|KKLUCa4m=Cp%b0P4_>$UEz(MIIU$MW7dSf>@&%AXaYY4){q!Asx4TY57- z!xi}s;z`LKJ1cS_vR|Hw|C8&*O7$Bev9fH4z8rjl%VpNk2xG#u20i|BFr6E}j(@SW zmxrufLD~IN#k4z#8Fma_>PJhJcb*~+A3)`8p^znYSVxq!_!xZSplyXKf!_bgb9+ZH zk*+;)Z?SRDk@x^-bV(O$-)ewX<}$`t3S+%1=J`n7qi8~$4ZW4q3_CWeUV^rgS4C>y zd$BI^9XlUDc+=1|E<%ZbKZU3rbClh{ZnKg(@m|tB>=#F1d{6VjjzgCV{MyXqAhnz& z;;LA3sYn3_Nnx@DheI z$O;xSPe;q)a>}~(nkbw+4fF@yRFL!xO62-~O8V6=9D^&NpY)f}N6mMa|E^XD+#^Ec z7X`d*bEkdwvP`jYSFj}z^d|EJQ9=%0n3pvwXn<>PKb#3eb@aNdqAA-}gv{F>;t#@1dZfUO-)kY@I& z0b;0C9Po0XSVB9C0oL{sJUTw}Q}pt+%&Iuk8-2wvL?7g5@z&`yykLItGj`KOwye9^ zq4OV$&)py8&oI~8r)4)RNAJtl+SO&biQxZQ3s+A zj?h}_%ChGl{TBLHPX$==%>uvxCUm7_@*Rgve%$C|SAw0Tjp#%aE`jlso5( zkCPWT6!9MiN^@SGGq(6m#o_liF2f2*p3V=T;_5)yQZ&(?vGw|Hv;;%*om3e9D$xz} z>M=a(-7Q=$UVkDRi3rU>dgqiVuD4M^+KOahi|Q+VI`Ql^#9vg$%b|tKO6@JR8NEoJ zcqmt(B&}>=0hnxG)i+-OPN60LG^7Ie`d~a8zIL6{Mag}Xj9MB-u{+_3r7|Wv6hoQn zT5>YZ*|40&h-NM;0`JYUq3K3R4*16RYAEC8^!VT;_rH!*`pBI@~192zaBXly6CCh zLZsm31sCYaXjr-HGA9s<++^Gn(ZTRf^KZpj8{!~OBk#_x*f0Eh#m}IdN3MjFdrOLAu0fjfd+dmB8dYM~6+z0MmEb4)+9?m9il5W|E0O%aL*CgqNhGAfGV{p`UFUjhc&jL>R@ldF4!vs~i~E8w zueTL-C#jiThAT|aBa;O8{iPMrWVVmw-ozHs4Mv{t`8iZTmKwhS)5hdL%i>J1PH1`3 z3JVqAaHlrV8C&zdhl*n21U-Xkw(P2cb1LL=Sz!ZZsDCbKe#oaUh?u(688cKCOMXJ_ zILDFn==17K>Fm;bZ)>vQ`W1GWzFyMf(Shx!^nFMO_y$Ilu>NvP} z`GkU}tNqM#N|w2nQuOG|BVI)ZEwnjv;DZSc`23edoW=D#A3!3uuM*V8mc7oYqdtf1 z`L4SJF(wB|{3xmg6WAb@QnHRT$|9Z5*ubv~)rPJAYj8?dQy*Y;><^Kp=^S8d#A z(Y(~TcWa|fqG8$VF(L$WT$F|6f$sbeUS$^KIe0I!1sv+m>iq&AwrsXCH0@Zr!IN(+ zUb5sED7oxqBo(0@@8 zJHVy)tF>{$$-KGFwVHlo6bZJwD!LSZCH85e{HwT`#{K@H=k+i6(qAfbWDzzwd96`2 zibKC)vi7RU`drs}e}`IiV?Hn5Xxwb=idya4@<+%(!DN|(hXHwA<2$ux8rQ-}op`%> zX@tyy!4R)V?#5TT+E^Y1Xioq7Fb3W*dSkb$3Z2+{Fut2wckfi#H#*E=CL1f*<3HjI z!{3&5yOBp|{rKd>0=zU^(FafqrGR#oouEjg1g#m0tqCS4 zjbPb2a4Nl#j>AB)KFar3adaX+;6)v&tiqa+utd$|53N7U4Ei@m02I_rM6~N8+e{-q zIr~$7 zJ<6HieBRfNI%HIbDd;q%#rx1~SFNK|62}ecr|~H$xSn@7RLV`@+oBAcAm#92(_bLU>einc z`V?mr6a7Y0wvpkyoQPl_A?E9FB`&cjyyyG@{I6W*bblAVywdf%g@Nn-Ovmij1GhH~ z#sO=g08ftnT+FqnHGH#B^7t!7qN-FR4?-(?<0m-LV$Mc6f3_bx@qUhBlVoj5bpo?- z$z1)=p^l=*ozBMK`#=IYdz6An>b6cIDd{KMvpAcvd=( z23u19m76fTVxe%46!=K-;>DZ=$9+k9LxUSI6q-|2fut#Bj(Ki#W%AsPZ_d{7mt_Uh z9q|Xtuwq~z+2VIl*EqMmk@mS$Mw9JH&`e}0kE>Y?8Y*7&>23!3!m@m(Z82RJpfjYC zW!AoQdgP&X#W*hr`B2+x_rvm#(8{upLOwxdf_<{*6nr1kopCgbzacWx9l}}~GEZBYa!Rhh-9RpU;YJFueoXrU7wUxW6`hvE%@q2!gdr!q$5{^Rx>0eym~i-+B6 zj^9f*v)pLEsYDI|-O%7pvZ7ZNXraRJ7jiDBZS(tK17!yJsAJpfMc4!nn(S};HvwCT z{RI|eRo1?3(lYDJYwq=Wy}!J|A6~p6f+%R44s@Nx3^|q8zSw7oB*oQw{MaXJ2ch$} zrOpSj+ic^o-GSrk`frya{$N=D+xR>&vIQvF**^vO7Bsyv-A??SH_m-4$Hf9uUgBmG z+!fq)l+R~2=fLTnRmUz_9WD0_r$6sYhx{x(XN+IQ^6E+jy}?ns629MU7YtTG(AH*h zjG6y)n#{UZgI|_Zd#%W+ypZ1nfEnbh+j~-*Jl=e;F5>~T6rI{c9(Ls&aGc@HhuUPg z8yg6ep)K)>TQIho_%t;wKbGts40`H@(0X+16NYlk35X(p02vqA)DN#^$Qd0F|6s70 zGe^Htr46fxi7dfr_wX``-B^HbdBI;lt8!o_j0W45K)gNNSEO(*OBGj_@Oi?%*+Q1x zP&|6)_mZ{$Uj0gGUv_RE6nGjSnzZlrGfXAsX$1)vy>Nf;&+H4#?Kj+F&|>Kk?7GcZ z1KI9ZGJocSzwpfzu&3=K5_)fvZ#c!boX#rFAsDtCLFbF@Q-6Tfs&{pXKxDxY$Q0QJ z5EXaW5d5__<9EwED~U2U~Fc7d9p!{6s&b9 z#|y%aQB5WvXnMPY8MX4RT`(+hTn$oT{)YO&#*Ox=WPcMP87%?LT{f>p4#kZpc6yxsXwpLn!U-+&rpYr1*v(pyxb ze!HO`Kny_V+1{&RLkYr`seIqt!mq;Iy2BKolJI*O7-k+9!q+COcP9S;IRZwv2@Gg# z$ZVBatF8L4(>1D(w@aM0H|Y!%TN>x1&%3ubN=RZ`USypZcNr5_8gz8d-vrwYjUvG>MxuN_$#lPEWWPncJBbj(j3n^^9f zLV%2r0W#u>C*5a)(LZ-P_JdDSH=$Cdr|SdgG_L!n{=yz2ov&_Fjn$kEm!ayPU0M6H z^1rBQU@2?|mcmJ6-fEGU;oADA4Q@qjucSWzqK)WvtQ(P8Q+73$2@XUr0050oszEI; zreETvp%9`J_xl5=cB{Q3yL!s}%(xu8pqxgYf?(@Mb>Zg%@5_?WTL%4j>NtuA(DHYf z(sXEYV4Z9V2>we9m9!vC}?ljfHF9@$Y`C*jig_{8CK9 zDJ=LvYqD;YzmP`eRL!}dCZc##yEgOf^h)A?x3U-xGn{$=JvEZ7*stNPA=S}g!iZVs z8TFu``J8P;T2W{Hg8dyZPuYthlE(dXi3Kv~ik>+h)NBGwp+1MAhYS;L8u>PKWYam| zXwWksnvT? zDNg<4G!KQXAExp<3uTnp=|dKtwWl@kHRoHh!l|ZyUG(SJeHnAV``_9MNRrg)sI{%| z2auk(D6FLx_Fl8~WokjZ3%ik?QW7u0&|%{&6sEtJ)}znJ2(J?hLxnKs*Ru@!Kki;N zq7ri=kw;%0N~-eAfCiAWrK0M(a4$~Al=EE)UxnjS#55fu&ZN8Kxl8E*(Uf637# z1qp&##d%`K8*)y$!?V0u05IorU!~=)5eH5E%l};|UV6(yic;6(ahrW7V&2}zb*Pbq zWsuzme9GU~%91U4^NI8U)Y{#ilHWE~_AiV71@V)&hJMvjg6YVOqT)|UlQBVCvhpC` zDLoHSIn@&d*BY-AJy^@N7cj!$_wp6L54wzLy)xNO za$_k>6BynwoRW3@UF)89svw89gsw(!dUutA{Huna4CUL~g|BosZ?;ljW1$j&zVP4I;ue^JPc*n>&(z@oY+p(*)l{Vcun>Ia(My^HHuoB{1|Za!3}-*4yNxzl**!* zZ#-xBLf*w9yvXMZh~1yS1}jk4$0>AUEJ?en?T6e!w49{Ubzip&A}hjA-rSd|_M(hC zET^j#866q-*6~uDv*rOr2xH&4*H{y5)0yNPee#8m(L9i)@doYDJG`!JXMSP#84ESD za9@(w9D2C%d})Lk)<(~NI1sJ>%D^Cnrp#Gklg9Kzrro7JT{+9rM8)rdSC9;cTb*u` zx%^K~Dh|5$)pS)^FsCi!=!%N$1P(UJM{cPOzg%6clk{&5x`>D3-`kvtq?bB-HGKyAGsZ@--GF9T$U{8ta34VL zEWt-2@B;%X>yXy>=AOxd=aP@2P|xQ&)(MSXXzpVCHCn?PTrvIh9jG+5T6Vnlmyi@H(BfS9S1RV2<$VHBh03uQqx2 zdAi+btdBoEiQS7GR&VByw08r))L2i9dpB0YQQY_PoMV#T#_w&h0p6!WhbW@oa0<@C z6@ey#@-i_Qhv&drKO=ukIlmbj3!_=pjF)85m}5o51hC!F;mkf;C+ zqt~Yn`bGw0-@cbz`yuetDn^?+`~IWz3a~E8iwG*dj&>Iwxre=g9QO1gw5_r?2p(TA zm2WpRHb!610=#y|K9&D;n(L^MwE1_RONrH+k`lWz{UE_h)N9pg0rDV@3A+&Vk(FWm zQTm3!1oU)&h-i7`-*OA->x*G$x#&Ydju%I@I!)ZCf!*-R+XB5m7Jin@B57 z`^CqGM#}8SIhB%Y8tTt+wzL%a&JTzD|JhIEoLYr}?^^&O?SH^n6FAIWx6uHXXzDXe zrY>?pOh^@wXYS{;`8AUpm4#cHIk&K) ztgB?f1N89*ilYgsm60b;V)UNsRVc<57AQbKU-j7@kN=Uv3K|pHo~RJN%TbdCUps&e zDoYbtMm>NkKkVy^(GkBugz)+oYy?colW*bBdc7^b6En?)K7d~5k05y(Zndo{^Ow9T z4;zx4p6iE*KFteK@fN1M%sDBV@K<^(=2Qk*vSIii$j)5S9wpE(vQiy9r>1j88p^!d!=rYPru{m3``J@thvn zR()pwqDxpvYacz;Dr&lh1Rqg*Z^o^YYfyX-60-O>&H0;WhGyd^&_784Jf2wjOTZtl z*$3_fQ1mAqcz@;og++a?D`e?=<$1~Y^3uScw#k3~`cgJqW}6}-H2nhGxeiXGsw|0= z=5_L0@CT57Q^FXqByDH7OJ0RXUS>U&-CH}5{cgEwv=y*D5IGkJr8eX zspykLVgdV{?IcXU3H;TAfPQ20gzWhfYds2%t#3rYW8breIYOv*{0uGPrIMCkjSn)g z5*H3Rqf3x~4--ge7|E>zWe^}^r6K-+_aGO%DM9Bq3KpHwcJhBPShU2uC!kaz~%tH-tbcvF-!092}CtwnQD@m)^SN`Frf^YKR;LW zh-1kDtLZc_Wut{IvPB8+o9W)+kg+c)^93AJ(jeI5jfcrH62SZA>#8^ASP0FvSSUzs zhz1Q6&Dr<#^dU>vX;72oh1TUJcKqs9Arfc*d}b9!{urf-EE&EJb)gfWJmWl?OT@je zLUE)shf;^J`_xS2pY?>dmM$uy553S9+78F%=IeVe#~tEqXjfbZUqxeLh+|w1I~SER zm=eQBwf{vpc-xoFEvD&pv9T_1^I}#?$@eO0*wUZpRk*v{zm29DENb!PdmUiU0 z&}D^cSHlcKrDXbrj+>-C)$642*^c%4%`duhD0-D2YR2T#R8~D%lp_YTEbq&$>W>} z?D+i7E`b&;E)2t*{hILM%g=C+{#+L?D!cJb&#MP-TVgE&c+7wmHoam%e`%|!6IENu zV7ZjGm_EJ{ZI#73#qXhi{bPQ*ffFJ8ZBI{gaO+J+gShueWHC5Mp#SZgUI4s1s-gH4 zR|l`FXL7@T;kk;{k5oF%z`P;NeGEawPbe``S0We>ls>a?J_@ z*1hg!tQ9xP?cSfa^1zxX&`qTx#|h2L)#o-&WYZrggWgc9R;U_I*|g%7HQsdr-MEbz zmSkH>cARK&rrpGwF>_9I^Uh?G!=OVX$Jh@3xZuUMysTN=N6J9jK*&G_QRl+;1IWM| z6Mp?(=vF(lu=B!63}CWse|gRFCPYy%oaO&qi22sUpb26$h5p3M`-cM_XjFFUp8uU( zJZydKYr2({I3P46N>>Me9aA@hOy=oDZz`hPq@-O1eS%YH$o~9Y4HB72@XC^PV9>PG z>LT$wGyi!74wV69(Wc+%e4tmj1EQU|^vrhsv}q>V){!2Tta$;@d&F*B4%D$JY2phg6>-O4_x!9me$3u3lf5hPw z1$TUB8MhyNrq6BknZ5wPE} z1pwrT{}>>SB-WK6bZ-}8A7(FAkL>C4qIOjMI5+GucKcc~+WfG4q*Si=j%wBH^j{q} zzU>9uQOlG2gXUnpEa+IagAbni2T!Ny$4h(ZG+6R?_=;88|0nCoH$=ut5hl@7}|)ph526!d|R>3V(woX+O@%w$X!Z=B~03IW>pY=sWP zuPuvr7QT=7>S| zOn1qA`xl6c4BB~NrPKfP1s8SsGFyNRESq%D{I+a2N%b$;0a!lm#<0cJW=c}e{iS*~ zlv{l5L)c!Sb0;;+Whe@K(g9k{OxQtz54~Rlqc@z1@F>U9sq1JhcMZN#=hVF?^wl9G z5L-P{>F&X^^AMza+&IaV+hlOyLJ}SH6PWnXFhYjD3lAZu8?)Z4G6;d!S0k!bCM*)8@SGCqT{93FfC{QNesiCR5(R zJ6L4MhV$t00(_86R$2BMcGVCMbWReKefAmCc5ta7lq(?)>N8T$X-@IJ?2Cd^S(~pu(r=y-O{HrYD=Tm)z_V9WA*glT9d5&S^ zCf{V&-mTM^Z&7_v)3oI{?`UPNy{E+))$_(TlG@DGMVMCTZ}U;;fT84Prze%UB(b}) z9NE(X8Bpn3`MinHj*XqTx6Y)~f^3EM!NxHFWw$@@3`5~jAe29kZ1+xnY^=h5L6(>*D-bo@wCmQZVg`GJ7|6 zMspIq?D}wjnT?-NnG%MwgdzCE6qaE)QI^~}UnZo#=p4ba4WX!yRYhM5LuGR3 z3!w@Bg8SB)r?~+$^paRVv3?etpB99HU;QP7vpU$)w529pK=|z|$rDXM|$w zTmorJTfOI`aTfYerBvB?oW%);!0Tuoo{gx!k99#ExJj>$wk1Y!21Ekd2THTT$v@3T zsRqY?!DF0}LQ~gF>Am*g_iT!Ne5pgP@hzAx;nNk}LZ)7NsxysFY4@5k;p-MlN}$|o zV0_veW3@#ATcH3`=TJj;@4CvMZj!jnhScg^n?yl% ztEme?SlDJH#k5dHh`F8lx57)ZZN@LIwtkXlc0Tu+^kZxP{`YR6k=%`-+Cd3q&6zu$ zR&w;AY;SudChsIA=>m(`&N5Pa^Ba<%@>)UD9Tr`Bc+#&R`5N%G$*ygKOPnz?mb+Mk z%;zDxw{}<@A+~tmzuvjT_wHib%9rkqo-t?J6{4HVm5*|mPqP1YpPo;-Y%dQ1MlF-G zQrlG{Iwodlqw`zQbfQi6%}lnjT;zPTHLBYREmb_YZos8wF>!fktXRBZ5uLz}G4IVd z-U4oQ3F{WAbtx0PG1erGDGDSHrNKzI&ew`Jp4x&4=DSVQhQQcY;A^OhGp?m(qE8LC zT0hV<6>iK0F6bd$v{lJ&!MaQ3XAdD>Lxml2z5a@tKab@FI2t(h)SpS1r$2`wrV7cw z@b~?BZnP+Lj|aUhE4K{`aWoH;P06(nS>g~TR3V~;(kc_Iylb}WyQIlFMkloNp{dR( z{nW}8Gv=c^Axj+q?^uG!%ogG`G5iG}Fm1?mG6&PUYn^o2CQp3v1+uOA%zmL%Rm=ILQ6 zrN3?&4E&P6vR*E{M&*;YkN*Ub+7t7;4|R+A)}9ZT(qISRjlZe;;qono72*;rVJCB8p1Hul<1YqU%U24_aC@){*r(Z^SUYj`VGRlQsv&gDS>XH$$OsRX z#&?jEvOrs>4F_%ea3)_38aoP+W3HLZ+E=+AW#0sTRNeiEKY`ZUk22hPSV3k?RC-aN zPwp>t=uZh_hzIM2vQ8kk_@CeJK*`qHJ(WYFe`SCDTicy_q_$e$V*P%Z@{l*xS@{?reJ^#6gSK zf9eGOnJu@~5A?Y$@Zf5@CZLseoB~S6Vg|ICHR4qh6)!Vym;_~4lZ@L7r>k;LRhrly zKyZs_pVlZ8$Ma=x2kzX)(8$(LlyX;4XqylIYv-P`KZ@_RFl3}BmBWf}6;*13=*cEAJiW(* zzx!fhTvqrv(H^LF)Dpv*z_;5i8CLTh7b>aK`^UJQmDqV$I91!N{~&~RGmNOr;jItO zj7knp&Z=rsRcdv0EU*{$@g9>jMAupXwNfZpS*+NVJi}dBqab%*s`489AX@go0*<=V zK~S}jccRq(tcU}!`%eTq!NzFa<2Tim>6Ck3EQ4keBu?uC&hWwQ^eBs1uwi}Jn&J}v zx?*0dydwSMXFrJc{@K%=^v;LywJMrEQVJ=4{=y9RUWS2%x{XMR6RL#PQv6Uum64EC z6W#l=S0!`3_1uZh-tkS$Ba>qp^xG0wuLk1;+WC-R)YOyvP*DQO1P=#6e|EHi{NKf} ztxx`Ivr}?oi}#Vb2#nNS{@2eaJUo)M%soi6=xxz%U~yR=onl$D^S{vqAr@q-W>E>7 zV;gFFBGD`Rhupe8|Jj~=JDaV;`P*c;UrlVCr)?!tgf6y692h51Le1~S@4mR_yBf(N zD9F)V6Z{KbgI0%kUN1|MGn@&ev2=;Qg&rRso1l(LAStB*T%+W=bx3J^?9KP^>zVP^ zwm@~sN5qp+F@zP)&`|1c&*C{_D zQAJl!0;yJ=H&GXOzKk zhe_4q>>?`WpVp8C?#M0Gt~EeoeCjs7}rsQeXSsly&Q?Ib<23>e0Lubhstw``RB|xKPcoHdgTTFEO>XMh{joB;)z< z2XmV>Lmz+pVaAwsPpG!G##i+>GE7Cek4B7=yXN`zR*I!ojxF00U5uHsBqs~VU+^6@ zyM;;UX*vPMT%RqBVX^3&?To1C=To#s?VZSj5Iz0lIpVL9>iU&3r;8Sp0#dNWFo5IK zlb||NntxwjH^?^^zYq^@yuPkf3i7HjmCsI)r;aXV>*F_yXJK?Bz89a+L0L|9qS+z& zwo7|A^&-N-vTd*AdIxGutHm*n3>eSQ0{Zr8a&9}zl3?UHhTJ!+8?lOmE|HrbXR0vg zZ-q~P9x|MFTlW_&52NeP*ZylrSqDZd5vHfd`B-uSqBh5qeibn-pR2lEn_(eW%IX*{ zcHe*KuD(scK=V(RM#_+ZUhiL^DrF&6`*m7)P#jWv#QF-Ahcu5rd_gIHNT% zg*NieoOc%+gjx?;IC zIY0|^DzE#yx?I?4z;AF(wlwo5D|Y~@!`FocIUbL)ovnKeci;`BT*W_!lh_q%O*173 znyM~!k5JG)fJlbzy#T>lYepc{AgVugp69nT4(QupZ*j#s#}igy@csFLKK!UL7gtWw z6Zh6aST3V|N!@N!M7EG;!1jjG6E#+8My=@*c&njQe*ZE+bMddz`2p7}WfAoBfo^Dd z+4MVkkALfLp9GHB9c-QbjttxK-UOItF_@T+=thQeg@^FrjbGA166mb)0rUm!(Z89V z>iN5@)I{5dwEY<;4x&`_D}b#-0V2Nib=M2; zcqpXj!>Vt*LZ4sJiNod9nN=3{aUR{XC*Cey&bU`Q5{Xt2>|OimxlM_34w!;ReOki;qd_j>6{^yhyfH#tMv z{wkR3o|(4Hu+~Fec%{Iz%}78{pxfI(SuPD`nU$gl45R+c^ZM`R0m`iEWw#FR>kK;6 z+4W{s%mwe}2T;mC`p`6qohK+|&oeIr>9G6|Yw$8tdrE~)&u^797kj5d);ca~{vdF? z^S{R~m;9CfSSgCqpYuxKDOFeNrTxXT@4J$($B_IbkaDk1xskyZ9)L>OP7CaoP;;eg zdL4c#cW$B){s3x9LTioK`-t~O9A~#ph}C=|`55=UK^)<6V#v)CZ(O&gY17JMhPNNu z&a2F!OSScu^*7x<4p5ENfa$TR{U_k=6%q4phOYu(`s$!z(EMJRXM2|SxI|nLL*X#f z%C-L#{r6eTlA$O@>?jsOM@T5T&Rs(3c{h#ic?H9xRcDdyw#N?Us!?Bm*Ds+~_^rp^^BOCD33QC8agmqR6 zn5DY?uT!ndnfca1pCbu+&fnI;qG7i)e!|FHumVYy@_8wp09{n6@|RSH8Sx=$n8+x+ zLw_?j>V?To3iPT{XDM)obOO+Fh|aV73=cOyT{Vhv6fEqert|q{lh!j}e8m&LI7t0w z67FdSaWmz60R3KrCE0~_QT#BOQ&}<=RP6)0gH;7zsadKHRisZwYu2-EmK*&~ipKzR zgRP#{o0|8fq}%Qbf_~(p!t%c|>z%bKXHG0q9`Y0-IDX}Hnk#juwgPziMo;($?dxlw zj`vUoi<*nyj+EPX|Fqe=abGa$c>~KZy@hEvjJdOx*I5fz=f2VMcx(C3?axiOeta(# z87~=dfVXe z!{hV^P+c9Y7*Jzm_Fs+9h&TM_=F1r()$1H6C#e?hWSfV!z0vW_y|q?4BTJcLwjGzx zb7NF%#4pbbjz*#dYQRD6!aWj0CQE<`FGg$7P40Z?De-*W{cAt|BcEkiz`;v@o{qp; zx#;%MG^QNOMmGBcz~39t7aQoZOhKrnJUsNF9h;#_j(Mi88D*Tb> zRz};seJ^{?JoWPG(NzU?AUuHWtfga*(IHHVQZ<`YH~$H3f(aqF?zV#z(-j`&e@0>m z;YaX+Q-RZs`IGzpiZr>&$EEoO%k*0_+mySVK@gFa3-h<#DIyVxk;IWb@WO%@_aA9Udin_5hr4(lYpIXp6@NL_HzO!mS6Otz4) z`A(3&fi5Z<;7;i^Qw1CtejJ<}7|ndSYRj*UklT5U2Ps0=k%9@iy#c`+C}CGXb}Z+B zfMjf4$a=3sI^+O8{zEIeHjP<53To82Q@98Hv7ESr*omxL;?qd&OS7B}(AGttXNJYu z6Pl18RG&J{L6Pjacli3ThjRzMKdxUjzNWGH@!iguWtrZ}L}PY_9Wh-j_<3JQiO5Ny zy{EK%sq3@6aNihczS}M)3wpa7<4$jZ`H6e8PWm7P_9gXM>ZkRAz+hz! zU35;T54{64WcydmL0#_5r6ZJ0q3hpY#QfFPSX6IJPj3(|4q%{@*8fNsnm=+`qV6X( zIh(~jKP6EjkM>Ah=X$P8@`2~$55~J3n3HNznbzh;8-EO`nS1npO{ zHPIy@wdObi^=UlEO{O><$&1X534#7@Cl^7nA|}|)ht!tGp=JDm*%QaXSl|7s-vksS zh4PnYAMohuNkQCfF)>iHUrIS@2|;Dl{&va`XrzNDbA6g9-jfzsJ1v1m{QBeXt&E@5 z{htwS+q~KOw6Cw;h6(r^i3lnEhSmSQq;TW60}SW2?D7E&3&F??o>`yPFR+((dF{lG zv&3Yf)xoH9gL~G=qGEOuUShyA7Z(Px6BqYtHXqR@zyPn=Yf7Rchlz_!@KXaV+||eC_w%_nBFuYe65ODK)Ta*6g!=kj`|6QKUFLiCAtP= z-_%crWBVRdDs>KJ^LR&jo6cvM_~7^Y)C+ZP2TV#eYGZgAkS!b*y?GpZu3m#u z@cfDP>aLYZEjHkgN9AHeGwcu1fkyF**lBhdI?Pvrhrp4LH!+M6(`ly$zHwa{XpMSHqw$AEZ2%wla?j5`r}xG>={ zx84QWj}-@#7)AlLeFj4*Njlm}J{K6;*yI*&d>CS6*|HKI-jL-4K-XI5Zj~&4&zUsc zFy3uXLK^XG!ww6uhv)lfHe6#0E_grshJ#;05x>{%{rB{16G#2vE7At+O|{;28)M7v z8$QM<0ldZ}1R#LzVfd**PZ@i%UNa4ss@l6yohLjrwk#Nz;?LverQ!Si!O;>;RQJy9fm zBeG|PN@8z4RlL=DH;j#w$df6a&8q@*XFQ6-q*KRDaa~bW!q#GO_HMS}qEdTN9HK8s z?bl2PAqo>nQ5`H;g#C$kx+tykdTkhAUQz&Sdj$xrKABrM$K!WV^HE{7)_D1Qn*>v*+g%1J005!LW2tnk`BYSi63v{Zwi;Z`f3*Ut-JIA-IYTdju{tv4mk%_^R~ zK%#YL7YZRgfWlP*C|q`c!X=aSA5&GKDt@ZZJl(p?WSo9V z)&Ffz{nc5RWMCg{SexgVt%wC=zs%t~q72{$yl1{TobZ>sQV+J+{;bt9<*b&KDw+rA z-xfAM)1N)CjT@Isxmn$q~(HDS# zq+>o-`-7)OrNPign)Q?M7)@B`!f2(h#U}Qj6jzr+SiYzFzV@@{OzrjWcgF!3m9}mm z>YGKl)J;RLM>3@RlTau1+ce#^Z9ST zzt?m09M0*Uz3+RiYrU^)p_;2%u@J@UX2eH4%G8Owe|>DqdKy*cF8T>pE!309j{}z& zFUtv#{E{%=Qoc#x-#(mY$~9?Bt}rk>`Sh)EFfg)o9e4%2U())!?~3eyW#X-eFuv;U zV0AEWY4!0g0S{I8uU9_fxRf40nabWbLc?m{lq}<-FAH3$kr~+W9pmcNj>_Fv>x^^c zX@4V0uM4MjoGD)0^_ulZq|8$;tvB`B~@wc=r;HP$AB+u%JL3FC->IfrTeDo ztP0i~)b%HGXeV?H{SY62ct5`RFZ(E|s_cp2O|=BtgASeL*&SJ#G=N3(c2hMtA$H~L?iOBpU(L%=DJ*q5@G&9)|FVprsRkFh=&@Jk{2;sl4 zPrlmv61-}yBMp|9Lw(dG;dS@poFTEctOX+|~d*6b%=W^{jXehX_O0`IF2 zItq`bTEs0lCz;yJBH1gds`L9sN6!6D)Tguh&xx;@R^MHg_;6GX-?;4i)7}0u+11HA zlWn4<%mECo+u&)Q0|AqhaQBqXlmgXyOKL#Z0@=`jlc2-h+$3C)kt9#T8N2sv7$9Dn!{Cg=|KN&%G_(^guL*Qx4OIGdL*r z^|VIc9!nGuL3mX_3X)qfDv14SW4wvCP0<@qlL=Z+v^ig5BRTX5JTxW0Bhy?Mfg1L1 zC-e6xjWTfzUKk6TwzN=Uh?>m|l5dm0!5g#|hd&}kc*3uF!mQ28tQ`2L^&MyxC6g|u z#!jXb_15u;A_@G(-b)WD7-4?_u=HB`nMw)j_Q~wsk6+I1f(Qg=(8Z4Ez;Na<*HIcH zn#WuRB_(I#>{alVp7i>|M4Vyh)t!%fela%N7a+p|4P~yw1cw^Go>$Npf*!Kd%H;&C zE}v&B>}vlo|L}$WrMJ52jBU*xfe(Kj`0#Ys{)QNI4h$qQWTR@=puio>f%GpCX554w zV;bQ86`T6u6Rmpx8^tq^hcOqCGC0UZ!;Zbj0UJ&O-z+pCN_dW6ju&BHwS_dszfO$i zeP4ZS^y2xxx*VOjQf*$0_9v$2@@tws#g}tB^22xG4nuG_g+IlW3CaFF4-(&zG~bf? z;Dwl1S36Be_FRjQDvk}`B+G<82GIr8Kn}t2DEH`(#47V>?Rpnm>r?4A!e2|VkGF#x zyzBMu9RO@o(fxFMu2xvprU73feq26s3Y zZ_pX1e&AITJ4M7Iq|c3`c>WkH4b#`jx#bYVK0h9;a&5;bF;t~bFkY&2fQE3g{_*|JzL}ecsin~rQ9Kq&&)}xAg+%=US5V)F%BDLV z-_8A%dh*H*% zT|a@-1YT5&2tMs3@MtLAj@}xy%_A8)VZlDU-7O^Yk!}YHpiindDNVN@JKWwVrkhQ) z{}EE(A)3%h8Q$u!P&)b`gF1q3Dr+Y6roqcEO#rpSRSOmi%;M8UhH)!q1rktPDc8X)<=@LN{MzHxjQl^H=_nMm-vh4PC%j~*|J zLZ%V7S8O8MfO=B3bZcVp!yGyVydd7V$WgB|(W1Blx@NJU7m~Y{8PHDfOua$Z91_v>uL=YhKqGA$(zhn zq4l#g$H2(%BMf|CpUt*9E4EG#w9Rmcx+>OmAt|d2HEUCtE54;#Q*B2g#hj-$pNu%? z^M2!oWx&WsL1jCAJpQl`7&MchCT+8#kr!M`KRa;j}AgC++?>?C_!O3$ajO)~osP2nCjMwkJL==^RuOER*I$CqGQH zk=#0|RC!5*p#8;PE%%QUNLgWBdNdM8X?d|f-HSuiTmBncMB&FQ%FyW8GV3q*3i|G4 z@FQQ?EUA_ERTU(D!WNxXVSiy&gU6O_2U`U&%J%tQCXuQx_pfgg26gZ$PWW+T9k6o7 znCw{JUWsTZmRmti?cPMfnrHzw*IPEy=f1G!S`P#E{=9p-nmeUmp!n0ZWx4X^Dd^2h zyG3zXY~7UIt16YH-+W#_6kTnczc$8aPA09i*?A1~BdT;?_?Az#qx($n)h?dgRl?W3 zn4QE7rzj1}_C{kiy4O9^V#o6&RT1UqK0-BA!|qP~3&0U0W#qPl5X+=oo8~4Mr^|}? zmG&N#`4%{0Kv%uaz^UaL1=g}5<9VL6@V@@F#~+tIuMD8B5Y@e|66$Y!w%LbUuVMUZ z(J|gF8`XgkVSC^(b}B<1vj6s-kV-9hW=d9?K_+jbi?#;BlgRmE84irPqri zmpA#)6e_f?#8*V=)^h@SNLW$NNIBGPtRR5w{pH>4b3eLjWbHKnk+I2s_~?06>|9#N z(w35hgWuN|fT`{N(dGwZhFXMrRFxYipkV55G6U)_=RYNDwEf(#)F+rSI4IY?gDmoM zNO9$7_ChAgAk269vo5~u-8YLad~WwXn1(KK?k~Ngo%PRk|4N~Xrhr5+x+m>xzwZa8 zdD!blV3SqYSdU3S`{QLcjwi(_7b>FntKbXw^xI$Re`2PU2qOk19-f zKmW(9l6iP>!lvEh{+gLRGQ}qFkH4~l{hcp5!9Is_xqyGI^iQ<}I5-+dm3a({chscK zDSDU2%g}wtz?x6cqfiYnonz6sU{%9jx|P=ZaxIL=rDW2xc2e-%t$g}yx5JCu2hV)rZ|a8uZ9(=EkSZZvQP zT1age5mK3{hQ|FXDbse^?F)?!a@y;fvyc2SJrc+0u4uh9UNyCC;>pAxdGrWg4+Pm}%UXZh;@L?TTcCFrW+i;{BPxIO+eLjnU*4@V8+x*a zIBX#_``|qwm>u~)9&ZDTaBD8CuXTYfX=jBoSoxfPxuQ7Wy(&jd?=znZfd_jGDCtS9 zsk^HH-qfeSThlsWQ=S!}$G2lB`x+W-Lk#j85yw-bRJW@~rg+*k-e~D%AnYO_?0_p$5$5#w=nHTi=CX{)o5~}2CU3L5?F$Ua*EPPv#h6eVS3Ki|^%sq=gCUHy zrQDN^Nv-7Lz^m12g6C1BOe$gT+^WbZ99_h9Aoi!0Zo)OSrcSwayfids7pUBYjDFz# z{R%k#fNBPhIx7<4QAOyXVU=pkN3Lxw0hszeY_^EuK?QfhtEqp78*t)cOT`bZ9i2z} zzVA4V=`A?Lo+{9Lx$(UgllBpfo6N~*&&|Tby4us`S+4c<4M*6U&jWM_8pN;B^H*x7 zKIw`s;Nve{C1sqqyN1apqr@gBvi!(PxkBaG+raLGy}Bgyf(Ek-`RJ_v)t@R7m5Spp zt((Fcch2FF8Hu!?9>qzPZ#8wM8nCs&bq2pZ0u!;HojNLW$u8<=*;2jYB7iRq?LPi^ zTiu&;F#WAbrDgYFG7fq8m+wU&*uNN~AG{$!GntVMpm{8L54`yn7Y6U{D7}(R?ApT( zvT2}=Q^FQgXRR3|=D2~kX$OmvSTe}Nv~zIC>$&N%C~f9mDt;=yIt>QB4pq)A;v<)8 z@xYDIy!BCUF7UPZlS;mTdPQ9ty+xgm8YB8j4x%ZQRN=caVrbB9mfab$j3J+Tsw--k z$+l4_Ru%K0Y8VfH-i57Q7VejUXzu=@j$p^MQns2><({;lVT^^LwJn9wu--;*I?>

@C6@56rnIVGP`W@YZB0g7YP1O8=hT23RS2^rMdPapZ`0e z^-1ys*+YJ!F7CH~#6Rf+?WkUmtiZ2HdaML9V}h>kz9JYsPVov?c_e!!FsPyh@lZTY zs-YC77`3>?{SWW4E(^ZUFA0wL3x$7;(K~0*cx%H& z$tGVvr1{o}9Y6UGZS4Dz4j)_O1t!_sLb)%=-=mhZh6?8Ex(gS6k7zgU1Kwt>oRSPQ ztf`2YMH-`x2v6=6JLcirti=_QE>F%x!?(UrMHj$*H1l8 z1*`W|uc|rMDfn=mt;dy<`xm)A7n?W%#DEMu5?;*SV<0gi=u(M#2tw&qi>x=i-}u%m z1d5{`M>3pNtE9=-$bD}6Ow{Zpb zExd)~2;|+hz{kAI<47~}`{-)oIo#_c4$N4I%VXLMOKPs{spdQCWl{?Zdkuhn!kmoI zOMAju+nwD*BbJ&|NMoe5fTXJ$AA+6$33lZ`!cD|4L3lnM>lP3$HGc7|L&{O4OW$FC z`l{H8>hJDPq+kcF=lsv=s##VPiJJ)N>F*>Ruf+ON7q=1@^Iv^lDDtY&jBnjM8Z)d0 zYSSmIMxAbxKX zd41Z?Rw$>?qp+_$sM{Txv5RR+lYx9L9knSlSZR;mVZxy97XSu;3MDV(o)kt;Z94gs zFgSU?Cz30-@-}y>h|BMLLH30ISQS5E3?{fEELILN+qk8hO+Sj4Ntsc?Nm8F!zdXLx z3KNFrLjL)1ALHKwL4^>Z2*D?}r}rOa^+2+Z%*n}{G_l!Et0z*2HR32&71b~TU_$yK zZlS#y^`kHEf$B88zHi#K#i2Re$y~{0xB5_*YNw6;I8^v^`Ql$|-T>?iX(w?%pL;@x z!afk-5CUFpjF&pN=#l1f|7-P=rFX~lPaW6%xB?Hej3}l zO|9^=-^`e~e7_dzRd5}T@lbb>fK*(Vp#SlAKmK-HJcf2PnXXp4|6Yqpl-6n(RfStB zwoVJ0nNQ6yTm2SYPjWQ*_t2Q9ewO?0YgZlEJd>6>6o z-V#7Lzk@hVwN<0rSUN+A1`o~%VLYh%r-@0yGsc*cW_^dA=Kb!#Y(`0I&xbW%Qq)Kg z19fe1H8NW%+sO( zl7l!%Du-gCvRNyKX`>}(8b5ebV3AG>8_?9JjC)Pl5zB2B=r_Ytl1M+F*G~;y+;SlVv?LXmcw~LI#km+>C5E zGZ06?$BJr2F#w%4E=*lKBX2f!Eo3$PU@0+J0xN*YozHsPZme>H^$CaF*Ag zVkvjuuxC|d4*pR2RO%6ECi}S~e^4$Uo{VP&r?Qw@WeL0#{P6mlFoCf=dpKgS*;Y~p ze1z6Dpe4X#B)j#-<`9rHBc%Ic-zzTqDU>#um2@&5EB9X8#p^{SM~}Yi zBz4RW@kc24sK%D!OnzHr(igE0W;e;r)h5%fLcS_}Lgf}iKjAORyaOdCN_pe9CvSy% z2-hFK7q<=M-_J!Fqs>ua&>8e20JCznBL28QvE9|@JI&=7C|&Brm91uXBUg+7I}v95 zviYZ*-#1qkl-Z%~2S+sv669D<1uW?9baJ?>GoC#%ho8F#8w2m1CHNG=nHSS_iYVa! z+vU-d-tV=X?If26Fd-a|&Om>y(j*2d8A32bvsa(`LFKH{mn1XDV{jd3tT+f? zbmAM(^=sH)r8vi|sOT)bW;4YHF|SpNRfPi?v6s@-3rZ0 zm&mA)J2hlWcaf&Uz5==lOA;UoQy=5a?k_3lJWMkrCp_RSgV=KuNsLXib4Oxf0x=2g zia`Fy)@2?}a;T_wA4ZH6ipRo)?ADKE=f;ydo>vS|{Le7}P13<|@ZZqL>OE6s+)fkk z#p1}>D7n1a#*g#xFlCo}R7a7`{L6$d3^n+{%}+^}PK4$V$^I@8p>&z{RhAHPd~!9= zzS1nf^?GM9oeTYbKS)FjSg){RZD#V$cq70Ddi0{zOsJIdvs*LBceGa9E+n2E$|dO7 z)a=%*SN*`MG5I^g!a7ZWDyqXJeq~9Vi+chnj2xH%OgV=vdhRJr1R2Sn+pa&Xl%l!C z!5;U6uQal@mKFnfpj;KnJ%TKBoYva?e@)yk$~ZmdyUzm~x8b5;01m11!)z{r3Q=TI z2Wd;R*lVsb>znT~ox*JXs_3-j7)UTMg;cp}sZ4)XvMn5d7*n=Bc3`qmhzNdTy1CE}9#BL`%HMu?D!Y zq16>R|DhRqKJ`Fd`F~8c9!}AshPr>7(B|%ZGnu=Mcn5k20UmtUSrXKFB7s* zFBcm#Mx`E$Ss2jj9xOV1d7bb^h#xS%-Q$c7>>GXeLz^iO09rGynaCQH7F3jq4U%5E zJHuk~=v6RT7Z1UW`$erRghn-=FLidPEQy!Q$L5y<+SW<ADm#iE2D}g z)zp3Z8jDk<#}^Ibp5nj(q8WbCVU5~Vnq_l&6g;tFeQjGxWhYLBcXcyrIt+8?^;s$f z9-i-D-aJtdLL|>1-2;%5Ok*Bzo&dwI{g=LvDoZFJ%sA2G8uvwg^)Ir*&ktM^h`(Fs z%4vH0oR4{O+k~PLYG_Yg=~ipDZhgz-Wbcm6s8Ob>7v(U}3x-azK`oPcu??f$5pTaA zUln~?=>j4)+Q088D?@5!vJdrN`Uup>JW(7Dx&H)HIK2EeP{gZ>1|AC@+_7YL-(cmF zn?B*eh4CHp*3{Psi8>5%z7V95adh^`H%ReWjQjn|(0P>Wywhek66RNvD46cD3fjf3RN?A6s}v4?*$651eryb9Ex%4@cyqH0&HwK4U7S$ALSwFOo^s!h+X z`b=d z5{IUB_Um(HWfwAi5`j$2GcfkBvN~@st;i#A&>yXTWD|<>hbV5%?x0d~#^W+;mRGo9 zN~?%ANm}$+7=_`2M0W&_*3U)XSS!I?ZLIyT225d@iuu-nwL{l{6-t+cDeEyQJMy7l z084~R0?L0dMxULQ(N3jP)4S0@0ctDOhy9x1c(gv^B?W4!vS4f=t1A+Rjb@UDm85WF z>qh%xF#9BzrzvN@wKBL4>M{3~iO zp?z(d1ORPY6ENV5`o#~w)9=H#RM1BGUpR};5bU)+3oEz{QAJI+)q`AFqINOewD7Zj zftA30O{QmaQD}dlb6sZ)E6BryTX(Og^GSFs;;C4BuxtI(U}uRRRjE{hz6BUJ+Ghah z@J$;Hx9`31htvCM)gjK29Ipfk%8b((7SX@C5#Pb>4YrS1E5hJ?V}nSYIujFUr9I0l zJ|NPVNn1P4iy-`x`>eCvLB64pODa3w=oc1s=wP9>;gd5y#miX+!307ap(|r|uIpm97Z860@{c+0n^ksm#YO2!< z%4XzYYREfq3bhHi3?4OBFMp@K$$Y=DO2mFDyiRH1E9hSOR#{Qn4a4o7&^=85 zLeJ-OwPNP{QU2t=5SQGy4Q0yNT& zt4tRo>dkD2M_7y`f5_=$cOVv`1v^QLn~I9fyP=8kym-Z;KS;<7G_}RB4->Y&1p31| zhq^{)2RZ?8=caS~6=3Z~eyf(5=6Tm3B1l=%DtLiqwygEb6Yf`kB9$(DzqZl4v#bom z0aT-)t}JGi;f;HJ!(PY7{0~XIctt$8c~S+pqR zNuYFj=TuSSyDb8upCevno40t%^APjD@!JuwlK{A{9&117dpl;lkT>1}S9<2Vz4>lK zsoU|krgRilr`Bq3#$|Rlt7GxCj*A2FHlNB_!*VC5-qjC#es1XSL3ACpwOAN78oZxV4i6g*~C7ncd@x6T(#x*2-z3A?>av`BBT>! zW^g{GdvZ?lH5G3dxpWcKZ-ZNEnqfCX)d-%j%G*9_y9s^8qR=fiPzwDpd-GCJ}n;Z`_7^l_MGdgMC!ZFF1n6vWv zV(R&qu-Smx7BFydzW>ohPywJZyg>Kk3n=MPo|72d?dXG>0Uc?AQEc-NAYof@q;^3# z#Klp1y_^Oa_xrl43WT;-;~Kqbe*-wOdp&*Z=~ZfFw~bV^zQHLF>^Qe^uI2V`+@D;( zzGUKG6>EP-JguJx7bTp`rL#*X=)W1X-__Ze;=X-hR?{eTPy;$Ey^z>fY}w;%^Oa+- zUlNfVJZ5{NNfh1v6s&$~45_x#p$Zq3Eqt(ji zDw-FN%S^+3uYs=o*@TkYOU=60_~redzu!<1 zyk>zZshJJC=dO~%oaG0p0{n{FTVXUdPLKV;>^Fb~fNGZ9N2^Ln)K>PZ*IS@Q#<~8w z->$xam&$&%ccwbZLU&hvtMeksorp^6X)XBrWm=N0?EMDJ+tZP;PEOgChVa}}@2IAW zZcv!M_*NvQ0ekvmTZ+DD)?!hmtwotz+n0f({CJy%#sWEFTWNKFE`Ll1nh!Q2Y~D7? zY}`%BP){26#L&HGFhMwdnmncRz=*H>sPT@iv$Z#UYgQ(RaBb-|b()%3r3PRYqc`zZ zkKB6j2a-nN`5DtS4a&?<0z^3NDXj)R#H#`xPg5XH*7AUcsB^C2IeTG?oQBd@SV*j9e&ao`uKs7mJSQr_6u zCRHQ?9U0_m20Ws9WwWfXG`7JV3l=}TiOoY>fU*VM&NFY$hd^dt*H1~*Kd$cU6YBV> zqQ%XVJ=#ntNnay_JQ+i)Q1jKs@)>0cpwnBAxlMO- zeGvp_iI+x)9PP4J;nJlcjIpXx{q|#te~cly$o>X?bJr?SAoau=xR)DSolz5NVwu3L zDu8w;_-Wkq5~ie46GJCdG`QD59v1V}7t`}7`y~Q`HQdx7f!b%ho3+1Ha(!so3S*lS z;|TDNV|PAzSEGQ}JNt$3V7?Y3b6Nnb+*ew{$iLH(B?j6jaG5@Ko@e_ObExyCzA56# zyUj@0Pk+tk$2?(UO3J}s1o~tDC|1Ba&R3y&!@b}CFx+%E|MNRW2irCn)hc=23CXfz z^P##&ToRFmI4q)ByHD|?q zS5!52q8dhqH8|D(ugU@Ncj=j>l;cV@?@|E$qW$2k@S*#>i07$mqw)J$S0fc%<`%WZ zWxiy38#2moTjYmEKuqIg4jNk~^glEVabVz?tn8cC5Mha?l70WO+PY6r9+rQ1lnvqP&tQ*-mkElzFEdimc zv(24U)~tZr=r0$LsCz{s8!ZR-Uq-Kt!BwF>mkA^avU~@72|-jPfr1Zmp1YFT-_Z3V zc)Zxr7xe~`KP;7h$~X`2 z+y6s@skeyzgUbkx{vL&hD82*hSF+`Q0Sz-8w}NG3F^t*iFO_~5B*H~2dZxjV8q9w) zja%|o4i>jZ$I@Rm2TO7e{6bqGCl|}!(%L+uX#ym485A;mBkk|4yT_8ft%?KAKW|Db>D~d)`9+J`oj=y{ zQdG|7kYB)Q(HC67MNF)U5nVlkM(#i;#HD(xX#Oaz7H^WC38&m?)=|$iDHG)_X!E^R zu+pb0F^XCBlIsYNjj}zx^fE!Om&rFC4##|+d_v>DKLrLCJ;8JBr$F^*rp2V!s1S+rsH!d+EIdfimjj(FZJYfQ{1gl=KPa4ZC_sj zfw|#@j6KQ>&fEGc0ykRf$iq<~4O8H{7uxTnXVTWK&ygS#+D4_6_=s$DQ11%A~s%VU=fY1q$ULfPQrfZP+7>>0!s^Ss9DX63(NSzNZ zfUe66`~v!6%Pt+-uRK6`H;desdO}7J>pU0L-|&pjwjat{aa--NR&(hy-$vv@MI;9m<-x+;~~_*UYv;mD2J*L95&s7VVz{#V|r zbkh8u#^1FZ2{W8vw;0#F3x!)A*o?NDY;>DB%+HmgqL}VxA@_~I@ux?4o37u??X-a^0{v4%c$Bu84;E-n9FSZ73 zKI#zbZk_F{E2=0dry9H%BohJMYIpvJ=6t8w^1|+cM$>*h(@Pv`7Pptd=@v~iqaapO^{G_!vFQOP2xfh%f#&1U~1GB zCn?Kg3w->6MAir^GK{ifT=|1VhALd{& z^S9>joBqpxj2QHt(}j^d;uF>$6KGL-0}w-JT$xT5GK8peu8q4d$`lH&2Jdz1Ai2;F z>ujjYL0*EmFcV zy{;$TEu-%%Y#a;6@K3-){w?LRDcXfJ0Pi{{Lv=< zoagj9xXbf{sTyBWD%me%W;$BSxd_9mj|fXg#vV6}8$r{+h4vOyqK0ayemN)}SGWJ6 zAbZy^22Hc(*LATuaLw~(y_-iUE38i1lX7r>lOrf0J6)P;tDkU5X@y?5AgsE{A%kEvKiyoo7a`!YcCRy9T8dd+?gj(f+dRh_imbgl+uWV)Em`7((4w)1 zhS1Ogys0cA(lqs#cbr}k2U4Z&(VfY*vA>C9~ zP~&4Sw6b#ayhmlfG7}`a!eYGB(E)WQp?S83G!27+<}*sF`=^J-j1B2@dz0Evf(n0I z`tt#ro|{649aU*}{(c2)o^5B3C8JnmlOoxbT=IQ*K3^yzY-xAK4(p-1=}w~tz=-}x zc}0FCTwPoW+*tvP&SSvFsAPA|rqe2hgvT4kyBR#cuj-~9sf!+YW4p$)`RU544S!<4 zbISgzI*OO|awkcB^$jr?!+Q>h!$8?GZ?gWCF?frAyTJK=>t07b+f35b$wu0<-QR+48f^W59E5IkNn;6gF}Yh*%;%aNox?pYbGR+c0d73&;QJ zG!3T3i}uFZDFmn{+RZarka-mBPY0zYCvU0?r`$#Qolayz5civ{s-4Ky*K>>y_fg}> zXOdk*rGw6nLKrL;@+T+C;sR9Ru~g`%5>RZUY1?>+rYWl=*Wb7TZYCi5 zC#ZWaq&l-7a6wgzt6Bgs)3sRCJ31QFtg*qNA`CIld;T9<7cHPL5n06oGr)Da$KVxY zDb=+_x&TH94*@4lB#cPc>2^z8;zyd^|8aa;Or39_Wi8=-8{-cKI`?Tf>b}v>P#E^5 zMoa!McjgkXq;+lY>#bq?p{54%x%;gL3A&59Lrzc6v9*){uC*cbJha&6u_KnO*%0+ERr7lph&P*sn>=_|3f<)d->xJ|6SEJ2jZP zJ-BK*v1Og`5;eFZFl=D3`uRiWFGte*iY5!>D(4&neMOD52;m1T94BmS)I&T!oju#|iXX1!r zVd?p_nV+s?p3QrdJRDJOpaVJ^J;h4-fn1hVWc|?Q2?BlCbtq(=91~ z3d8^0n+m5ZhKVglrd?B$AK6_EupPe+Bbgy25nuFr9>IiNlXqArz=eCL(}@W^6_L1iQin3rl2Za=)-v_E=BKeE{am4*hMV z{c|a(k5Zfpp(2W={@TJOTGMZ*s^JYOmQ?xIpAYr!c1iYE*<)m9>UYEzc>^w9Dw(t! zW?%ay4oIx8xb2fl*Q-UM<4sjzBllzvbo5iKeW5C3pXT*mb&qQKa~kSHuKtPiXGj5o zk=B%(=dXY>E%t8H$xF19H>L#Q`ijV&s&dIi120DX$R;CXV<$~) z&d6}^2pi*0J7SM;Ur_pdPg9mn|!p-fHIJ5115;`&El5Q zplGg3#S5Ge=D_`4wY1I6^^-JDdXbwJ?(V;$yA6u4VgpAWL_6$M0n^!!vHfhdxVT=! zTHSMxiztUZaQ~Mu#U-%)AUVTZO{3V>&V`o-X9gjpdy*SJYa07SuRs_j*^qbZ=-6~~ zANdZpAh|Y9lDeTvNKLvYCB&sC=l2D*fgm}E8;kF&CY_Td*B+A~#?gqkB**G*qlJ0H zfQ4Vp03ugUdqxulUX=&ze_l#379Hgsv+1+^k!KNa1mI?h8w1DnEtOZE#(mm%fy@c< zBF@G}rOM^M-5DAXqvI(dc-3^^;l+;pk$aTuw@nyGrgHIAx!jZNaR~sZ7bf@>#x)03 z4C0-*&D|Ib`Pr+GtgNlo zmJ6i0D>33zH+PWvmB`Q(iuv$kbEAt@hB<*|7^un*=ntvSN%{hvR}~>*?J?8K-t#5> zr3>=b$ z47oRiE3oE-N05Zx^9W_~iJ!f9PbkBWSQxYzB8{?BDVyod9Ob*t8>Ibi1*6 zo%otBYINc~Szg)p3M_n-)?=T!sr6w9FW=weZjxe|da9TJ+yRbAk{GJPU1sRUWGEjBKZ3oM|EUqT z>;8(UX?*5)YI{YfNw*4Rkm9F}d#^9hV)bkm4NU~olQGz~w?B-9PULC&IP$3-%Cy6~_$*CntoRd_Xjdi^ z{~lyp*;1O^LWZWoQHx>rDy446T07_7Ghb{hkaJq$k)%rj4#eeTFI=B(MjWPQ`g2x^+WRU5>&loCfmAE$rycK_BGe`#c`vmX7V{z(}2cC!73TSX0$5-89 z&qwal*h}QXQ07_-el!a}u4*zH1V~KYv#x@U#fY5tTVuo15bu0&0RwIxu-ywzcV}AN zym14YjB1 zwWU0kiwl(@+r=n0oTD8Spig@a?<}qzuHKu7S+#cSl8Gg{*CO}%vT+;pO8NDb?h=xD z(0|}wHOpIE8ti!Z?aJL^;W|`k}5MtD^k-ZkRQZt?+ zmg#Mu;<(_8`6RimW>DtrMp3m(1Rm1$9t$|0ZW*Oxo-PUjQaR;4#oFZy!32rqXvnSv z)fCsp*=o!S-u*eGyE#7c5Vv1j`+AjHwkepuajaz_*Q5Kz?414J@tuyymN@v&jjq7^ z0WVlR7Jw);jh1fn!yhIfbo&Y`?>T!kWsf|_=+cM@db!+;e1&FHj(5{TbK}Mz-YdVw zZm^@Sn38(?kt34v#&HZry;dlitIT=*gs~++*Hklz@U_v1FaH$@o6XX1g)8+9Gm`QT zdEv|zJO6HG33(Z^0^sL6w1T{FwEy3oP0nqhn~Fg~?*K8=b$eB-$oyOMX~Y`YnBd%_ z^I~P&(t-Mlbfgs3PxWP2WUrIyK2zVLN(HN>iuRs$q#1YQGbx<;+Oy6&-zSQgaUA@3 z(IYu8y=auJfp}dDalUjbz`*dR?)$8eW7xVO@8jM($Q=x~^W zfvVPb{H+pGIb;bdtbWJYEbMA;emd$3?9gce0-3+mU+AyMIOE#>8(J-Euzi58?tB*|oo9PtHqH1O zb&HEU*Z*)!Waxw|gD2Xyjdf?y0hXKDn5}QNfBA^G`{8D{S%nO_H8?L)t+%>N5v5)O zT&GJe;G=-G4Zx%A_zKxLV+3^GpaYv0O0iZ<%wKylq>PJla2^kYD$brG%)*e|Hjm#~ zFxUmFNTfU}xsL+b6Wj$@^BhTlXJ?eDvH2=k21FTEQQ%6l<#iqNHmXei>#vmYQKGmg zfU2I$O;#EA9e6v(BmbN5fbS~^m|k6sYOsws9T_ZVOsHVeexBxzVqrJN_X2%umnMhR z+S3cDqoR8d;FW4o?O_rT8M)|lx%i%5bEy_!b&tQ}4y4UabCL_eo$G&;_p_a=3Q`3v z>yJqJS;yX0y=Cwjq+rP#dMUgwen!UhlpqMqHaPj3e28vVC)z@wUVoV$FUt`M`#Y9Fy; zCO==bVIH8U$7k!g0BSqI(qC%4_54B)rB9w3C@?1r@P}o3USiDX=xwl*Wb#)=9THjh z!<~VJ>f^U+A@ozVg1YUPxiU9XP}K(~@P7CN;64rkf`@^V^vT*-1IaL60Gf!PW+2Vo zo7A8+Co-2dN?@bIPYCJ&U2paE*>+I_w26si2(&V|f8<+k7=+rE?q&=EC!(cyoOr~N zbDu|^8<~Sa2rTlXgH_@CFEv2$h+BqdYajutM;FzgoK`ABML-pAGuO`bsgVM+;;Wd) z;f|O9{1QbHQhLj$GF3l#ng-3xRsL-lNwnbSIySt;>N+;tj@`T$SAzOs$9VeHs~PPw zPy&P8^woJaMY_>!Ay_oud2o-O?oNw|G0k#?z83f|p<#JF4_u23UDG-A%D#3XlZ8)8 zRjc-=dRa(c#i@D?NOR;{I-7-GuprkYj7Px)Wb)vbbzvbJD<%EuB?|wcozMd5 z#Amm-a#G2Bgs}EoV69vrZP6+J7B_Ad1a~t^bi7+TX&P#6dr}Zvb=H&Fyj$JL9Fwd& zv%9i$@Jb0}1{kV3c3oJtS)6B-c1a;d#efrxq5z3rhr@Dkl&Ji8pcFBhIh z=k2+Ff%^E|8>SGTm~P{fS_NE{yH84#H(5yuE)PC{Zw&b^MxSZ(MEYMBCEsA2S9zI` z?{PfQ*no>2$*#?lNZN-|0LQV`KXl343RM(412&7C&mK8{mbZ3wwsrBgcJOz#1PvC& z_iAsRE!t)?wqA*glU?%h4ugn|>)61Xx)nKJTz@eMWr~&p&rlzxd(Ewf{M8OqFs2p3 z)+5N1`Y-Us=}$y-FDmh0Ts?e_-r-0i>&O%Knj!Lh@yy}Zd<}19u?*qe&GlsCGbsgh zaHVei;v%yr2_XZeDjND?yTV4`vO;&R6HH&CU|cV`*NYhKq)V3WA$$}Wqy{93vA|sI zfN`;t*!i3G_ADmxWe)LKZZG0B0#=t*(fQB4{q7@;AgVAv{F!exUz@uE8; z(lI(mhtzME#97+;Mbjr#^7DV85jb!~vx&{Kw^3w|o5R48bOK}zV1lm-BISkFG(Fte z@9O`mIgKfNho2>ZwEE!WJ9M`1<=S=M25_?fvsIa6zjT!VOgKU~QB55CF@L_^|Zyz!<} z>N4&bpJj;E(B)-;MmqdoGyU(j?qwxL`=Kr`j!CR8j>*8vfJTBpBI?56jUeG+cw1G` zmzg;>zfo1fR{ytt-zY*qb`rS$Ff3yLhZcv?+$=z;rkx$rso8@(f^mDt<5lP}T4}nr zZgH;bMa`}E+?nwLKu>joLPO}s^&?yIl)GrMGaZe^rh-QEtR3H7(%yYp6wE!nr8q*f z+ajSJd9#BRtOnRLw0>O1+F*FJ31v}6YC3VHO?OSPvGNEU#S1WSwBV>Kn!6qE%fAZY zi3oh?;N4xQB>`8`yEIyo{u&@&f5uT#8^kJ@)4B@GBPoxh_dtM+UvC^IG0v|I+ zA2IQX#zK7vD)GfWJ`kUfF2dJ|`sR=CuBuh~b2po09gH-re(cQfnqAdN1$Lftd4jVSF&I6BG=|R#c9&-icqzfreUXdWog%R z6~2?UOt3Fuo!QXR_Ub!Nc@U=UlTtWo90UO*6$;E2ptWDu#N3354K=lcHqqUokLeD8 zTJ+uTD0@>?wWO-~=eVZiTg}8V9Pt0+=`G`;`o8yX6ahhHL_&Hf>Fypt=?3W%K~g}v z84&3h2c)~Zq#LBWyM&=*=!W_HkKf<@x*q~h4kz~BYpv^gU%^ogB(CDVZ#edqt$I$5 zRg^pv1V9&5pe-XO#MEWp5N;%d+1$CmtL`K%J&n99zoqV)J>^65kY7mnd77%moZT@H zZr|SgMy5yaLy+VHmd)iX{2az}Q7+pn{KAHR`)-xnJ{!!B#oqpCqf{v7DvFffO5B#G z7%So81Dlk+nu4V9l0RDU(~(EZ^6^Do+_@gQ^B>jeE>T^HuPOWh|GHQ6BsrF|{Jq<> zOgfvIfOmoj!@n=v(-*n|$9ZfAl>%?b3rFG=GN0dl87+|BR`*7bW z^&(f~tACye-&#)X8Hcd9W_O7DDlA3+k?6Z99aG$j{BmUxas#Xie|G; zHkLf_NJTT+HfQpI2NcR~52>z*5u~+$qb2^y#1MLU-~|dE&%*T8khzkpdKk!@7@-Xq zqq^cX12Q|4K>jXPH*QS{^9|@1ggKxeyn zq64iYPuB4t?K4OAiGX=)L1yDbXFB#qE7|&G7EC&MJ>c=7z+u7zxmD)=;twnyYSumt(N)*0B0r!^`LDy_aPby z-9`jxA*XRhR0z89O8)YNTNqoe*4c2RbIp@^^fli8HuB-+k-}_mR`dVRxLF!%rR!^g zF*apMGaoRS)tr~kb3>iI$-hEyS!M5*4niP@{_W$lk(5s-K9l#cW*o~w^I3BG`>?z2YHU=zGPoGEtUf{&@Xj@wv(KiG4h{Io8q+2joD6Vs zV{Cg!!dQ2Tw&A%P)AlM}frG_I#qb~6G}AX(>B790dVdSs#LwWP1_JWj?(afar-dn4*?fGW?M;*H;7WlTR8QWt6Z61*r8{1 zPjfy92BMEm=YGAC>p+>0TfZG@+$jbrc%?qIoiaVajKUQlYXn-CSZ9QOpyyVOE>i)0 z*9$4P$yi5kL=);~^J;MuIQv6~)n|ey(t}&$fmc0*(m3O5B9hh+h&ZUT%VN|SQsaU( zF;=E&&5xz%PXcrpy&`>%`ef|?U2t?DuCpI`^Z*&4f7J4Po8ZnXd-LwgL(~T>eXPTY zy=tHL6WJSr_CN)T1}-Y*evp@dI_JL;{<76~!M8KN48bw`u;sGg^>dmQ=OuZH41d0l(MTil&k*19UU?Mt zwChF1hf$y+Jt?u?1cGkYKmV5L{I%2S%^&AYRFL24N%Bmtkrsf_D-%yg*K-8MUbic_ z=|XY+@)OZemmK4pQ{0$wzkFvN4zPMiJ!f4)elXuoJe-1|s=f6uzgmC562n4B%I6iW zza)NBn#=h&P<@AQ-s9lC9Yp=@DF>1rG*a`e0+2P8Yp_`Fdc()cU3pV_wKVKl6{5ONqYla z*Z0NNRmPG(V{j$=2ED`A*Kgbl8y_!cYRn!}s{n2n?-9D%Nl(<~Yyy*8kGtn95;XX- z^BloM>ay|hzNGQmXo5X5kZ}7g__b@ih=zz&b>9$4{{zt62WsN3G|9QgZXg*o;vbrG zRc+MyZi>#<<5!a92jlxhoKvCNC>1B46{&p*Z{AYb^WwZApY9m%?eB3Ao}yFSAcDII zR96gH7ANa?7fnn^yI-6!=;^^(<%%7-;{I91#mMLRl@U{Kik0SHfWq`SO6#ymrpT_; zdSa!wi}uS#X8RO8dOcaYUqcvj zsKhaR(6`zBL_Es0Am%GPX}`mp*FZ;U9od*~!?UMTCwzG+ zk}^7^I78v|3$;H@O^uk1FG$TG^qLo#VWVG%+>9sj1kH?DtvXLgV;Z{hX$+pNY1BmT z&vf-r_0!f@U6+u_=R41PIxYc+h&sUKnk?0R^f_^aK%#oESWGuSg8XfyD9hH{=~7xU z5YLC!_C>-j_@42IW0}?I(|6N$)#ETu@VHL;zL$MQ;QH&!lmRIngLE7=;kY5+x{U5%lG8=Wr)svs2#QxP&IuM+6z395tfsNmf$n zzUr5p6%{!VGb)gV2e_z$lEDVWw`VNk3H_Z_U9SV*PGBu;6wygvy(uS!fNTYxJ--;r zD3ST-S3_&1$C4BXS2cW+yc*G|zZr-*VK(Lthh_mZ3i0XXz;`{rL7(MOANh5-jZ~B# zr}Rl*RV>yXJa>feun3GhLE~J%JqYhy17K@7^m1QJRSwn(e_y0GJZV^cE1~p6{ioA6 z@m~Q0Vt6a&0JsXWK)88!Gi4l?_@X0X3Y!$R_t64iSyr`cH0|8~ehpEu@Eb`V?vxm+ zd|Iqnxc8F_-(-mzNS{%A_o3uhD9e3;E&NJhjcVCo4GhE!j9!+ z&w3QS*GFi&lpE5?h~qXQo2mwA(O2t-A}=9vmbSkM$6cQS-44p*|Ijj%^`HJqSw6iz zK4#~?t#|GhIsTckZBw-?f2<HSoM?v#` zC?W}T-vQeCw~R`KZvu5SK!~?F{?p zNV8{i_=rTR-?K;0977-OozTz&YuoRc_d7+jW$F19Txx_C8M9lf`~Hn$-vHYi(Bln9 zQ((;giT%HtQknowLp@n({ON>R?J)DVFOrw0>ijuhAzOtHPx#m!4XPI63ro*SBtTEb z#&N=G0~X)-m1!JEy0XN`l$m)1FAdk~O@GM|%`lU5^=zgAmD|v_rJKO#3G8u>$ioL+ z*WZ24!Deu><3}736?Q)ioz<`Ft1YRDd}cHU&}_N0Fn@=#iz83Ft?yvwW4z!mU={!- zC;kY*Gw!X5qae_MX_NmJOV)av_81nYoI&E^t2F+H7C>#XW8@x!S+Jh+qHf0SiveB; z88HuwizxbJb0*rpH1`Ivz1`;bFWS-4%pKR5)m18a7gh+1o3MQ9ZvF%nZwG4Gb3Pf9 zFb%{t>1U4nvz^-~hUr!RQ>5t)WUSQp_uV8^6~7;!aF%|a_Hpg?WdR+Hezyprl|e`DYKS5zn05cL<@tiQ=uWb!%9 zHQ^g8A#pUp8e%MeBxu8t4;W=>Be^Pl&62UVumdTYT$jdO44zp9wQxveGOXa_T+&Rb zBLU5Agse46$}nJHgzD?Wx2o+nfpNc1KZi^h(Hs_Aboe9S;@`X@y&6&IrBL`|Ae4ha zXNVqo1jy@8So1c-?C_oCnln&#*UC~Bl$68S=mo-q}f9c5XouhWzy_cRgn!q?ll^XM`cU; zgFi6OGs`>|-PDP@$>}P~UBj%`n5`zy7h?7l*cr%1LK@r8@I)}G>U0* zd*Ux+%-(@I*OW{c(EwA!zwD|oTY0>pWrdV64hzhsq~1Yu)!f}u<MERWBGBxMw{;s`VUJP8owTeb3eSiAl%>)QKnU- z9ugsPDB{cdVUWIK#?dV_b{8cKuuFW0pprm^dR4RU(_Y=PS0@S-R<=pIpfW0Sg264B z;dHh+1}wiUD)1qr$tLr!MIP`O7fx%P6#3j`+jiq|Bry;%AY) zEUPKs5Ia8MsGH)3rR2xg;Um+u#uroxapC>p`wi=iZ#hO{UE0$<68WkxjGiJ(I?_)M zWj@)M$5%88+#0I$z4uPvu=wb-1!Dh0E38RZy{2Wj)grCqOyxv#R*)FARaooNpB`(l zp87w52j>lg{x6?@5oX6Ik|I+V)ss7_yN5GM_)@y>5D3-kC66U)(Q-DhbwW3p(oeKu zP)qjA&OggJUGDmkSsq1em~koW!-PZ{+aoF&8F^9y1Sk-xcAZ+uAj{a)EPe2O0susIY+H$mMhw5!Mg4Mz4m_10nBco{&uF};Z=o#P<=G;y!?QG zUE_+g=tKhhF|u|AY*#YTS#StxY{u$}K_)OKafV9jt33#6b)=}7!H|8hecPr@muHhC zdQg8qm-)u6@h$vyWPHwb%(8rRPX|h>@kIuaZRBW%!xuHVCwQ`8L!IKfW#%*MWa>e|o!OL(RG5MXtzbT4 zn>X02{(Jtbb=xmv%a$e&9vKG)_W`>+fPv!VKeX*}I;^9Yg}snnnwaO!VFIH ztEIG7OFOtEc#>JJ70B{avY+ar!u14M&gY9WdF-}_gORY%_v-HaX6{E&e>q~kx74my zo_B!kT8HYlw;*^LH2!fm3gOo$&7`j_CfDza$s~Zk4EmFqygm9P2}v92)f|L!m2r4u z6_41S{sckt1Ciy1?!uFYpFHjr-V(w0)ymC7wi3`|3fk9=-Tt%+-}j1xW3Z{|;tUn zH3C59NuW|qJ-D$h46-7@q!(CRs$Mx)YJbtdj$}9W?{74Z`}5QLGGBS43}^Z0Vk9ec zehA7s>mGH1(K?A*dS-b<)Fo)F$l&;BI}|#`%dhk)x7_O&N_--ljv<5NzUn`;Fv1Lh z?ubv0m>DeIEdkJY+tIu0y!BwlM!!)8OGvlD)mZEopu?RFWX6=I6&c(_m_*t-e(>p; zkNlB|RVjLI*grtf!wT!93hX2Z-%>PN$O2Ra4pB|6RoCV(q5AC27f5? zpOf_V$BO)CKVh{}{0&$!B780+U(I80XULJ)(_R59P+`N&{Xr)G(|-Ez5?~iKx!=Te zQ8_{_`4bNO<{OQTX}h_#H%Za!e#L03D%b0Vp|kZmFc^hhG&sE?%Ide zJaXdN9t*@df}*(0Jx8f^0#1u6dFD}}5X41s4h_7K`5Hj(Z@T7ceiwTs=)3=(uSKL> zG25gxC2^_!O(s&zai3-OXe)aASvtcxtz)B}<9C*>DkFzLQ5nGgTVNz`$6Byy@gG{e z9SSqq!j*Q0^4F7tjy#c8XD#~auXgQoYfI9HlTU!sKcy%6B^Ibqrti@ofOnQ8E+h}< zHLGt~-Z&dh0~5Ck-4NvDwh53Pe+&Oef0IB7ow%4aogZKX_mk?slKCLcb5dRCtI^9Y zJVyK<+IYxiIfnnJZB4^XRMB85O>M0-E%7IyPs62h@=F-Eniamb(903=7TxhVV&3v1 zb4Gyhm|Wv;bS<6Z028I**OA>Ez9Y`vWTQ6GH0~L>MqG@MnnR>*BN`*YJ1QGHvM>w) zfiPL)l7i){KY=u}vLn*6eg~J6z!Ht^69lmA?SxS+w0NDQAb{+;=|^ouC+u6B{Fisq z;S;1O=RxkF2$YdDKc4~&*~rB+Bcbyc?LUioJkDi8DZXz2H?!}Yrlqr}#jNbf;lwVF zk4%6nk`;(C-hA=+N+V^1;sCb1(2;Tc29VF%b2FI)ZNL@qgh_lH%0{j&!T~oSc#dyn z$-}RsH`ZwBJ>OIzcXQ$Av1rvDW4+v^#{#Wt|H$JwNy>$tiwdikee=FnG+tk2G1AH! zy7{XZ?yG`|IuLPanwY9Z1v}s_rQvTL9a}*HqoFQlH<~14rgtB|D7wCS%e)fw-Y@L+rs046hBnbyWXaDEd0dmy>*sG^kvoUTj=$F-P%!H{hB4 z4`rRf_HoRT;;tUz`27J|&Xjs(DdXhjtTaC|+sM>L zr%T;UB!CNDT5O-5A!(yCo+0 zy$0HL#xuAn)?XnLhjttPGf~Cq;kDmWd8tv3pEigJ0g`-W;lI$9W@ws8NGIuL*YkwjhFkM@19kGM+--rH-7%aW}Y7t-N>b-!jpW*DQgCo zax=5p%R%S02vg6FLpTO&Q=tfk=R7xXM@aIwV|mdYCXy|z1~RcMBB!{mGO>VPEpql% z{rh>cR7G}$?`2HratVt)!66ad2uU#@FZd75>@xTM{T;`abmF1jKu&VejvO@NB0t_q z$l_tQQny*SV}DUcOlF(VDprx+o`fqjf3wilm!Gpt)>y1bod3}7L( z>*^GBTN)NZNBzu_Yg!`b2+Djx3U7b6Aq>91azmlb`V?(W(fiP4i0X*}$N<}L+HZYc zzJLyDjQk`G=s_o(XX#2g>%OOyw+r11>p8mVw4k<7a<(sO6X zD@=|4lOVBhw41SE+_nFMclcAgS^o~ zX94XDibNqhS5vf{OlkJp%LTy@k`rC;)|i| zezC)A`gsTBx`ohWjL8+AbQ>umsyPW|n7bri)bok-Jhb zHq5-6Nox;hzu?xddU{ zgt?MIDvgFv03S{s#RrVRrO0E$$4lOJMG%;*?c)!iHiA%|CF34sQZTZdc+LGYKrys0 zAOrc4k(u{WgoEHP@^;g#Yd!4^xUoQL?U?;|M_+Az@edbajXLZ~4X3KXmnpB(?~>@l zIlpIL)B`6QMXksOdMrq*Gz$ITqMYifpjgRjJ~pp1d7{U%>96SL6?CVNkhKqOgHLB; zVm>>lUMVY%FQ!)Ha6U&ep@WIc9h=78Yw%v)HMD06KgPb;Di%OAkZ`e#!PP~{jtz52pTAZ3j<`h0A(jv zA_(#I(fS^HmrH(g^IW2arOIptHrq1STW{xBek*iqH_k3L#&8Q8Y?aS>9+XsxHo%9_ zaWvl7j~nTBs~$9uOTh`M8dG7?oyFa@{VI6 z(}eWf{97QVn;RMJKCdPtQ9cL?Nho-9-Nep7{xAIKLD(N!(H_?d2k?iYleiw&fcgo; z;15ma>0Db3ZGCBkK0M^DLnZy{3>5*)n~smU4l4>cn?r=&*;Y7R2Vjl zKFX*G`y`rdGQR6e`RI*BpB=wFyKLbdngbN|{wUXt>V1JZH0)z`I`EO4>Sb}kF;Tv1 zwOG6f-mcru_O#vDeN^+UMd28Lpg?mQVl9}Ufy@zZ>GdvZsdCN8zKh170SuX8K7_8N ztBQrKo8M$zR&AK1hKoJXE_Mh-ff4IeN|cNxpj7<#kIdN;M+?F+<L zRw8k>{AjXe^A<7Gurn(E(R9pBU@cJQbrh|fa$9<8YIDXT)`K;7mOJg3<2k;9?4Wo} zS>Io#=2l-TftUD_(sMs9NRt9<0xwd}ewV@}MnmR>EJ@G_k5 z67WRFNoKOm?}$^EyBJuE$~B;$YXZKO?N)p_uZ<5rv8>9cb`75aaX6(hOTKEzKF7hWkoMXKep#tGA^#oZFY1 zi=Al6o)y0p7Tp5%*9hJ!dv%LrPEe!yrlkU1_1+qqlWq8OGM9Uw=xt8b1BGD<-T7PO zB?Km-YQY8|3Zcz>UBEBqvjT2iDY}n^-ry78b zWIsr*m844(#1Uo_zOCDNKfNZ#GoJA$^9!@wCrJv)9Ku%k$Y+Nd=RbZmyB6F^g%VGq znZD1i2Ww+L7yCn+&c=Px1SjH@eHTKI621~&G;kP^J%hGGpH3b5(vEP!0BEz7)5sHT zbhG%&j&}bAQmSn=Ai*yk+qKcB*#L^l7sbUXBgHF?L(j$DoNUCN>T@v+uNug!i;v8c z%f|A7g9&P&&BjMtNm0D@20dNttnk!_vu04YB_Vr@Okw|N>62w`?Yy^lQommw6C-BZ zf|Os#hjn%3>6I`IRt7jh$hB1?FD4u_gsPm8LWTUB1Kq`#@tVgE)I zdusTxB+n=|kXU_RS4U>eeNWl&f)A{lVD{xlh_)Ghm!5)DGRZyND8>8CtTwn&2X4BWEtSAat=u zkJK=Igy?^b1wujM&7)-9zCwj{cq&V~FAA^Tc+cpyNM{>>05$xY^e?W5U|Vqq3MSoNPlNKW3{J)9KFuD zO&*$f;LG>OR4u~Z_UA3|ZF;Rh*($dq=B07L7vX4p+Ql)OF31YX^Gccq32amJ!pTaYVF84zjm;C<+7_aFxv$byso@9Ldx9m}C zYjMrv7-k-Ll7oLx-pkZB8L41rR-wt2@B3-4?XpNA`jW}nYQ?9xEvnd)H{e8^*oq-Mv%xJGMYW`YptA%KR(TPolk_bgbbf zwup;TI<3YA+M)+LC+v-``SA%+mFKJ?mqxxSG*>`ZHraCsuecnsT=odmX&mrXIY=L( zR=>p=>BQp2t8LhmnAX_!f(G!xeGAB#8k+)dU^*rydq!?^VyDKmx%)ADq`7aaC;?0G z^{-39!}xmj)x{oXf|Q)N_e@x|yu&s!!&O`4XAhcn&>CeKoSn4;1;fBUQ#{kLK}T}; z6bhV!@bAwLl(@l}xvQ$DD`WA0UZXBadOx?pMXgjTS${wj`R%8tV{nf6%~G0xu-Ug`AWqLrL}2HJi9f)rzPlK zmlzZW9F3$XH(C{pEERtEU8~h;Mm|ikLzzobCnJ>VqrH-)jOhs%jUV-#wPM`9%y)_gLAO6oRubK4s^?8hvT9FX z81IiOmK7UGaOd*co}n*)ZWW$VnL`j?l`%$mM54wOkc`EEoY5UyX!e7lUkjn*a`wwj$2&@M^ zx6$X%tp9w+)l12z@gDZxs7=-h0|P-}=;snsnI<#Jjo85W&d+wZl`vjyhjlwc;zzT* z8OnPDm}l7@stk3}Yk6PpOcu6%aGAWh*H5I#f9^bG?ujy=Ve-)|Q_%&Q!hnGM1yCIY z?a=#!G=Y~*pat^os%%41u%M|S4*mGk84cgm%#4!f%qaxs6_m9^XWq#&j_JBP2hxA~ zl5ehdjwosIV7I0?1shI);gY4}PCLE%oBid|-atPOr{*Cp)-J}EI&0cI7HU<&i_E`n zh1X8N30P4<3_}EC;Q0V%xiy~W;?WPme(Q0(qXvs&S7LxnB7+t7btmQen~Ywv?7Hlr z;{c+Z30I$Xwtq>EX9^N$F|wijW(5d;m4dDSY}p|`DF^ahIQnn-JfL9Zd32N<%^vmt zF4V~z=!n7(M{M6jS>;?4X|~@VzJ0KXT*I?Z_1pOKf71$p`Y(4p`d6?Vyn)SHC)reF zb_=8jl+ZX(*lMJ*bOFT?KmZzXStSkgd0$YwT?k*6BQIRd41hWG{+#x7wM>R6;a<{t z`5xY!vF^k&+|bgumXon4nq2aq6aaj;hvHu63F}N(Q5Z?YpQf#jTbI3G(0ZWZS%ei( zn}oJn+0%C_4mA2^FtH3lWn{qHpmzDT#xk|FRQcrV zGm#7i5sxtkg$rk1lU4c_#gBbgJ^Obmz(wQbegyMeM|rlmmMeIq3%14pxKh1y514LR z^pOH$7qDq-tD}Bdrek2_hNW+Bc=E8G^{cu&LDOWGpNue)Z^uY>WR?f-1SWzA^z4zk zP(*&~S2&<}j=b?5Hm08H7qieBn?~HtRRswREL+L&2~hlmh9-MZ`o|tC;rL}lG4&s3 z*jRi{_$Iy&E0dWT6scH$Z+`@r-|`B_EcLwZ=Cx@0-5@j|Bjxu4yl)%f9AFGT#au$s z)tx^-F-v{w8wxaD&Mo&Yc%%M4P6~V{k>eocx@3N(Oj=wqh=yKCFay*894wKpy!^az zNI|FP`2lA$iLCZW0#E+`eUmdc0CmjpWqukb_{hI~G&kQ%Ac);>ZasyB+o@Uz!(`$F|A7tAF`LDEhAxo@lLxgFLh*mEh5zFv*Kz`ljh)75^{NU+pVU+8uty}?q zO@qNM^H8PlXi@Ou zK8#ZVsXKsmx~KE$#3Yoy^B%Wzz9k$|=Dv#ECeTI}B)>xUthYPeS9Vw0#Q=MMK8so* zN9mlnjnbxkA;w#`6DW0JAPPVM+a{Et(Jv;|1KYN3IZF_&=Y5PgR{do>lllV!a;c#j z5F1Wk@<+v4ApXoYS!B36=F)b0Rq+pqc4Zhk_u1@K*WXyNW0^_AMb9il3~hx|Z-4<~ zf#x)c0XW_!T`{&HMzyF6`eyGxw1vgTX>iBbHiOXLb3F>|5&6mH$UgLGjiMcJ5L2(S zf?Tho#B;G%u6`IZ7}2#?^2E0Sv=ld{la1=y+ZS($ zu(H0+y+s_+j{R0vVH`^W4Ka|%T|Tf>J!yRBj?ggwTXv9Z zSSU&>%VGVMmj7 zNNutXlJ=2q$B`~shh^b5eE<@AA%`_qXb_7UvIjDt!)HyW9%Re<9$}(>KH)wc`)XVi zedMW7=FKX2hQ4cUcYHlIFS`bib6qL+ie%hTX?jvKWBaC(luyXL>{S_AMs3XA-tk~4Kb zv%)hdl6g1%rn!k*=w&3QjBvP0SA_NQ$saKc-c7`8y{KZgcvN8q8`xpKK{vb0H6Q!Pyl~_7hTc0$;!tboD~#M%K3Ck_&VzF9 z5ZHGH%lGE{~r+}w%1@J zFj;5h*>o4PMV~t>%#B&)YSM#al~jU9TkMSt)EZW{*9-+OxMP?z-{lU_rEgAxtIx%P z?Yw2`@9%=zDdLsa1`FH6FOoKiuBu5GejP?Wqp}wh60Be~i+p)*(1u(8mhxTA;Fj46 z^;L)9qoc&_8{X^_!iNGLBT29yH^5)t6(^UR^_2m#Nu4;`hm((nUb^(1tHMkoPhlv@50`|#CW~MdG5QjX0 zdVL)cX#tYVm1qj4LC&^|u&DMRLGtZbQrc0&xx5>U@ZC4&;LD?EvG|sG+*e+(fSkTy z8hbx$auh(pAKs~&Ksq=o;Nr^XY#|{$3ZTr)Zfp&n$Y~YH-JG+cmfxPd->HOAE*OJb z#1~+A1?6n)(42!T6llPtd86~tHut@ux{=B_EA|l?-XuxK>*!IMAd9T|3j2~{09k<_#Vv!MNbVv*ETVi`&d(_F*=pB(R3T>kGSHy7j_fgK2fc$v{+h-%fTGRg#2~ziB z*~&{Sg+%EFyYDe89B|V<;!EI{_eAKGR?RG_{sr8e`kzZV(D_ZnB zt#;0gzdel3t7(zQUSO{_BRFYm&!hf=v~CW$PEL$A*dQ!OTi+O%#V@ibP@I-$kNj_c1)$Po`T(_Uuf#eo9l31wH$FnaMdeKFLeK@l36e zU>SAtaytEjE9du(r{CxH#wu1v=3|rM%SRBP6nDE8da&)~WjQ`v@f+NI?D+{u(waOV zqpi7HO)q_|bJDY`@oC9%)OMx_Fh($Br5u$4UjDe`weR0bjtZLt1SQtThiuX8?0;bk zo9K7rlp)loI34n@>M~PrEr?w(c|kQ@!*X>P)8opMRHL%HEFDj45cAv+ZwoD8VP|GF^Y!~K{cd}Bi7pz1F!1^ zxWN`$;K9VkiR}q~on_7b5wBrNtnu~EdwRtF85gQH2R9(ELo&K|*{mVbA}-Ne%Piu? zw}h2`N3|i=+~mN_LJ;kmGW~LXY=eSy8J|ASo@>rF81l2|xTeH=Mch^<(hmL{Js)Iq zs+i)*W=~fiCl|xd+;Q5Ue?h~fynHGD;GETqEx!p2-m8GT-_nIP+6BhPp0w_ei9sMa zc>BVAr0lzTmE3@U6E`45Z0f#u9WuHc`?M${}vWR$pdZyL`oZ`QrRe)-m;wQIRLUl{w zoL{zEbCjmnr)zfYH)!9m%OL`nHDz4!ca2#KGDn#2jvlO2=C2`fLaIf4GTL2IX-I_HBmvF@UgC@?3$toioHo~pFXE;W!zc(K7iJd-}Dzrkh!Hw!6dt~ zottC(=Wc2DE*a^gKP)vU0(yU=Qzjd%HrNA%H2~ljZNUoJ6aMzA5|hK`1bPoyq$-%( z%NJ5q_dIIz-?zn9VoRzMerc<_O2QiL=9^XN1d@=w98s(SFz~yZ!jvsj zO{PuZ7xRAPd&~qQj;_>KpPoE~T$T~HfY)z?h^YIK$i9maB9=wk{`0`}8D8zFVMhXP zdDKR%@epoYzJzRS!BQ5*EOo|~PTa?D_~2m1Es&jk2yA{g`OHw((c0`=Opd+Gm!-g) zxlF^GH|BKRPOG z7vqUtIQbnTR4`;+36{&bVxXjE1mG@hXWaxJvzwmJ9u;beCa+crzP3bcaXh>TytAm$ z#eV?DIU0*Muu$aX`<-%gjuoKaChM?s=?F$Y$4pY#@yDPE47d1Gu4?0fMk>7y(EhBs zvLXc_lg;3e*`CW6L;iAS2<*OlSwN}eMBK@@3kYD3hP~*f?1Yk?zl->zp*%B_cB6Bt z`<$#h<#JvMNBZ&d(7bF8qRib0M57Cw9mur7-c zT@yDQ`Sp&xb$i0=rfS$~*c85}>1n&{0xE~+`JJZ8Xn(d_#ldJ+aDH&)Xa^L6gGYKqFt!&Fgq<)FOb&md_<3gYl?NN4p zlL3tG%M%~`!IKfX1dSJ#ngZPh??~#Vw*1!q_pGxZ-QIuZ>nj5wYoCFluIGtARxOJw z@kM6&2N!3LbHk+Q1=AmvH#C3@0Z=F%@WgT3=#T?LiaJ1-sV%Pwn~e+R0vauJ4FFS9 zDB06oyd1b|!dI=V36o`dGCZUilPw=oUwY3~TXDA}V?^N35~4oRFz2Y6fj4r`B=@IB zd9GnQiY**wlF_*-1n%_yQm5gTiH&n~^^n=sP)P@=X=*gNll zbcoY2JlU-qm^%1k0k-Y@XafushAYajV$-Li7Lytx)okSC$Wgovqomnxg8`c8Q_C7& zPp559xL558|;o9mM5+3Er z4xtH1AWN&JUUFC7Og|YnrQjxgRaxa~UTjD~TQxP{C#E3feC{PLtg%FN{SGmkOzTPh zOy;vU!l zn|T4GuW}n9uTF}OOpWd(i$OO!zKnVzB`}Hzcx2-H6xq1eqLI;e zx7@gBw+=p(&Dd79RNW}Ehqe|DV`aZ?A0qrI3)Z)nb(EWnqv^h$OCTR}7i~Z8H@KaK zdS~c=P7U`U2Bf{YoRppwCMWT^d|*(=ururXK_^uq3eZ;g8KwqhGZ4tjhMC6~;1J`w zoS7~FLe-z;hbA|PF>bniAqXV7?>iyr5R)rFbM7b>IuuQ7cXhtZ9H1hXfe3T2DMW?Q zK6qxn=IaiuB;58BnL>>fmtELAH3X%ggExt7&&S_3C1UXp%O@7o#uA#ot z8PQ&bzU8xT);m9CAa~OpT=HbUKkS6NeREXW?MM$!@SkDLCGIktZB|9IK`Bosn^*jZ z-HBkhX^w6^h!PLZtBd!xEkv@NZ})cojJyOZSjRH1=w4Hb#3}}%kWl@B`curbcfWX6 zjAiX;GcCe(a0dO-Y)V&oP98{l5DKziWFV8pI|3}ipw^CDF3Z(Mk~Z2sIBa=wx!>EI z8EACyL&IWYK9Jf_9~x_{Wj>9_DwMmxd%J$44JZUS{wV~ek`T8W4AX88wjuwXPtK;T zhvQ@a`NKfzQU$?50u^$48+~#)+G{zgeKZGmbz+ z5g1gf18GTKlSC<4N=6K889Ah!{Tr{~UvT3*gc!DK6wk;Hi?d}SCFpA;%Yed9fYR0jOw?cT@<#9cv<7^u9(yAK z#0NsNDjhXyaP8Gx$lp4)QL+F52#y9w%no+send# z$TP~!xn_rsqZ^$U2vv}0K&^q?=qaidZ6DIAF;OPuV(D9%VS15!=Hyxa)Fkv;1q3&J zCuBd&cUB7ZtT0G2a?#Uel282m-Y2SapF= z*P;8+b<|`k2{FByh$jQM%echW@>MA#Jd+g-V=%G`soMJFL`;<=LJ5ec+XTU8^ z9vzG>3BCX;A)myx2C-W4RxW>vJyu~Lv(`oP8kfHSeGW;Fh z$$5y!$9H{7;~+mKLsmJHR0nX7$7s{i!~4RFI}hmN^SLS#PDfZD;l^ErXL8zR(*0B; zaDI=Xx0AQg5Oor>=1KJ$U;Q=uL}Q6{ z(2>O>9DYxsYwU$%R3JJ>0_^q@stXslCM)v*;lt9&K|uhmF6 z$_&A>t%gUi192oHZ>*ZzeG98W zA0og-d8}Q0Qi_{Dki{!?FXhyRS<`4g&mASX$I&jX_eVy;u`)GLrnQV|%Z>oPF zbG(A$FBL&pJ98kR{f`ovNi6v=T~^S^&Vhv4{F57vXMHE(Zflw!opD8@4G8|^fPLH1 z75#+A1h^_yBV z!!cZ&Nn!Y;g(BCTkTf+_D{S4{Hpy;leZwj05{uA;Rxmd@VE>!6Xu3x}rGIo|37)=@ zVLOs->(?C({zK8L*Og=cucotbi>mwH{-Ee63W#(LCEX=Gguu`#4I(`t-8mo z3&ViKfPjL4f^;`XcX!u-zw>;r_x%_4IoH~2uXW#_Tcg&pW3SBXNk9#&rv@Z$r4Czd zuyi<4Ep|Jf%?Ic`o$kDXA@>|T*tluF0a`)|xcLKKHe*u^U*o zY%n}lBoqc>Wl<|4&cctFAgBGRKxd|jNbky9K$xA<>TqNd5cB` z(-`L6TfXz-zioeVC!7xsJ!QK)<$c)z1W0qD`O)rBDy@Wbl3k^mpuV&~i2@mry7cTn zP-7-=1uIGzGHF${QWbCB!_ftSW!PUrRJcB@PPJYB1HB@&p+n(Xc|y4Im0n9-dt-!| z2s`CRn)a7P_nlUMB;QwJOtuKZ_bn<%ODC7~+pz>IUTJut zFujew*waUvf3QB~SY}^63-m%Yei2Rd zwq?*uZe~3x8#}zO&X5>@b$$^AyA3)qRsXX8^P>`O7YMsE>(QwNrIO|Kuu2MB+W%bs z(+CifwYY*eIk4vVLvJnqbekd%s$ZT6*T*A}(#<*{O@2kTt39svKb`9PMD&Mq^`dMm zfU4v5Q2KMd+l8L4v9gj4#P~re^Ivf%4E2$~?h*HO=!jbI`z9xJQbVv@BeHEZm)JbV zFX{J?j_v31^mxSJ1}uQ)0_72g^moR&f08%mMrrH|VJp;bXA@&dfW<)4!psv6&k>hN zv+V==?!Fh=KyCtkU_zam5 zRQ7zc+LWzWheST9qpW?%R0lgm=r{sluG1=jcH8lzQh^9GKA(kEhgCyhQ6My|ODyl6 z^wFCQ^S8_RCWfP4s@Wo(SBZ}v5j~)PmWKN@PV-@XckPoI)a~u;@d?(Q3^)VZlG*ca zOc}T4wZbeBoI3!&L&DjYm2=gS?W91t;gxqv zv~2}dhRu)?(pG(&G*9;ghy-zJnD1>svyo>IvIR0#^hHG|}3*R|8iw5=+y zs+3rJcm3_qO)jlVgoHDdHlyQ%z?AKp*z|X6=>o4-eU&!@vnGE~)Z$&_DMoRQ>Sk2Y z!%2d~aw;g$FWR3SThem5rP1LO0|L^&a(_&O4f;E4UbOSm zOd^F2zWe&2Wp8@*pL=!o4*dh=Ivl$TOzkR3kMEy+F_mW)c-GCB{C3wD^Za+MhJI#d}D%Y-v&P0ON~@RdZbz48eRa_n)oI9nN2Vrz#(bvKn% z&SN23R24}szKmf*I6Q3@Rq59UGfXze4Y@w#Lwzr()P<6W#Vb261l=g zC|4Ry@-BjK$E;{UznI7AZO&tcWcmLt&44iFWO6%?R-|#vduX!b{N|+obdnlx$jei`4wMzBY*a#**V%bWvJy2 z>Bm6vnVV0}Na+AXW{I#qYqpOl#zn6O%^10PpeL+tE?>Jt6?lRfeE235>ioN4Rgsv%) ze&Yn4<PXw7sN(F3xKC?O-alY5kYaC0m3+Zwm9XDT#YH_4?bd8>rMq2$OR}75Nlc>5^^t2b`q$0omI0rYoZ3D?f*W z29m#dgMPGA!+|d#IswL*M8(544LT+1r03C`XcB2<09~LsK}~<|&7{-mPcv zuCPBRe{tsw8uTA)=_fc0kFP!)&$DbPe5j9qV4UPYCbDrc8LzZEfP1q(u>XWX_x5@y_h*HHi68uZo^ICz{{|)sKM`~wBYQl5fbo?R0k%`Q1)w@ z$#2%Y7fLI#vFaV6m$&RIt~7WuSDOl=4~6wpD8JZD{u5IIQzWj0LPBO5$W1M_Pa^4W4r50hirn>4f|%#)Q!M_LzYy}f%2`H<)T0fuYxFWo#1$f-WC=l)N_@nrpDTO1Qz zQI_<+fL-|{P@1;7e=qE;9i2qTlqjKi_c zOZQ)uC%O&g9#u>e62hN>m`3;N_O*zwCLqXircbR^HQHZs>vWG}ycs_krV4Z8*VmRa zf&%9>KuZ7Pq2%($dQ!;Fc#aTFFjqyrl$e< z@IdDB>t5t(khJIkVy!UzcRXpU)fy9tPhMbxczR<%g=&1FJOQ*G@WeZcYZ5zLyktMm zyfUX<3ADm7^5~*>l`RX42a2~uh~NRNLNB0@Z>ELf*{i6!&1mp(iTiEjRy4ZMtb8EW zMnqr`kNB*)-}D4>)A*WZV8t62u$)_UYyWhv3pKZ+CPO|p8cCN-X)O)R-QhM&A)SYL zTz;KxCfa1RE}nT#8MJ8Hp4>ymx;`iDiFxV~-c0|nMID}xJde2NQ)nCBiPeyv)Igde z5r1+!V@SYRAuI05e8}uA8=Gsh=|eHr69qoUgpY2fjIk}>`!v> zUBC6>g0FplAABO*>kFVHl*c_6s#^V?rrNZ8VC_#CREq=r;p}sQ{eN8@7zJ}tUX{M& z23a<-jphRz&^+M+m&5Tcy5K@^F{~PRe3(w?L~pw?R0_UQda8GU(TrT`NT%$oHtpVi z0s@8=Dhn>+CRZ8WOw-JM^xd81<|E;I-%FhQ;7&s2B%!}xz1BXEWPhx< zaClXpNW3CqN(P#2@=Ost2T6WG_WWzEJfjP#eM;-|dB$I2>V@BOc=H0NR7#2bleKKO_Vp@6yUzW~x9&^9j^|nkAXNdVX=f5wmpRAFGX9bA z39t3u)^Eb!hz_EZ;hePS5aAc9C7x56AA@~A-W_gp4!e^7-Z3YJd%ZyQ89b{pVzlUS zoc8Qj;a1g%*niH?xEhN5d;xsPGOwRJS04@quXHMQH%K9Ann#2KS%n*k2=M~W=gy$O z{!8ukSK^h}twM&2YdkC5`}@d}Jbju`Ila=r<`|+leBXbdXrcT<$LC!33N^na&07Ja zgMSNC7S5$U>qk$-UJwUtTsa4tBM=k>rAjR+lbY}oqitsuMSn|vLGetsgHS7ogXeYC zmNIqKwmTpEmV$`M9>ZjciDb-0&#v~mx9 zGZx$N(4O+`g~<_`lAyULQMOcL0?*XQdmDo<_f00Te~ zgIN~~td}?nk$a3@wuX^McpHs2#msax*~HXEjQqLslcx`BGil{kHaR1Y)>;IOr#HT& zKa%oWL>QN*D~e|!4oBHdmt=}6TpeN+D7iC&#nu!2Z*;43^MK>*zJPy?48PBu^ZA^T z5wofP59Bzx%LsaAr!RI2;lF(V#KIU<*P57!I&~~peaYJ!vMk$`ijXdPKmQ^3PqO=5 z=5gM}JCR&txKzoKyB}lraa`e@P@4gVAuvzqXVX0QyVkWCJH4^`h@p?U77Ec1yyG2m z8lbwR_y?*4!gO`$(9|nes*WN@Ryg#7%fMzAZ9A`LR%#X+B?CB!mkp2fc z5rIq;0FAg)`0wjX7!ZQ$&d0HwNBa;w z@(KLi49PNFGt>W4_xqSjIqLlYc!4>tt`kh-wXNWFa(VJ9Y@h1{QBMa=C-vy4)5J6P z&kp+sf{?B{zZCG-da__(hj`iM`#QP>Ek^sPi~Q=o(J@wGY${FO@m<*W#Xdx~JDwOx zHuX_n1uPS@V&)Iji6UHFPuLg`k4fp3t>G>?C$|+!6UN@TX7u-#y}t#bLNNj}dhC(H zoP%a*a%?g6Rq1-L^*i^H62mgsD6{4E0#df95`tLLb9gd1ve z1B7bYOo3rzqm`!dv9m}NesdR!wuv961lS-A4^4{@c+*MU>Ro=PRzTm>aN>`*az|rI zKD=LkowhM(-bQ#RJe7R#-XYG&S?F{dUV!(wL?m<%rV|(PY&yq--(pL<+?p|} zKabYqzV?(zF2>N7gkEQKRUdN9x6%&Ie3$2lR3KUnmyGjJ&Xhea*PyLu)+KmpP;7#g z8c7aKaZJ~AHO0Bc8~N0d@$@N$VFA(Yx$T{82Egc`5wkj7#>m3GJi_p6zPSywu{34i zGim-1dp|JGv|R;qSd8Ew3jQqY#_?U!o%iXEAg0@j9>{WdjP3Ul7slQ_8OFvMgBguf z71o~pU9_fCx)Pqp1zF&21iGNh7b4KEbph@#z;s!Vp$zV~0UCC;mZpI!cy2C5DYT!u zkwb(#M%96GToq;w6+KR}10`<>|O`+#BUZ=zn7lrS5n_xQZVQFh+=kBR~!5(4N7P$p)@ zlqr0$ov>NAgN*vF&EMIs3xu_5Gp6w4m;AW`(lU!@w{BOHjty>ItjAx~);_=M=9^#0 zmI#ONW53c%IjDs|yNY1H+zHx(Nm@M%zGUb$d)|j;zZx(+%Iyh(^&Uy(kDqdW@=_Cz z-3;oKPF}&TmQXM@HFqfAgdGX5nRAZBrIvSxx9LLorNp+O;wet*GxE5H_8ZXh=YTPd z{`9oa9`+DE=PT4Ex%}CEELvVJq|Lx_kycO1izSsGSNWv94!DT7p+x;|h1NI!d3C2} z+ufd!ric)rrP_tMKRcHNq=6|`Nb=pre{-OU9Ecn;-jT;Y{Rk{C}o zpK1tAZ{ZEf1K?xy1KOiYJfjy8xN}U5Z2NtnTl;(blo!~o8Av50Rx7tHgS(PNU2!I^ zo8Ic`>BPHv>7gaCbz+~A{W5ftq=vTenkF~SQ>1cC0So^W5O!kmKVIpM=_f0(ij6ip zvC47Jt#^vK{K{a0T^!wQu&|H%AsN!k4u80zE=BAaA4gB#T|{yNHM>zjXI2S#OM~)3 z>M_PFtR;u;$9*#Cx3qIp)z`~4jH5!m`h6lI!wGYiTK1JqUnOnlN7k3B@Eb=q04oQu zF_fm9K;L8p7TjWaPcRm8*%4ADE3_$bTIYjRYeT+-CYBX}X~2EV+XW4&NHsWm{SOq0 zP2=%AOP&HBq?mHj-IijW>_qn+5qu*10eHCNK8DN@CtR3d*{5fS2K#PTU5T-;#!)Y< zBBpueYpQP5Z3kEI{g+_kVdxr%((BNSPCyUOL&vUHSjDfeyUiXJ6P)}~MBD7+z8CdP zRr&$Xi!(xY=tOD625Sa|Rl-OTjc1-WB+KoJDrIEZk-BTYe8##;WKH-HZVX*hu|8w` zpySY);aR_cL~&1K2ebCLNnJUVjjpKCrPcWKCs`r$Y;Z3N+3Ry4KkTfl$RtW%FUeoD zCwWuB*iLB4R*fkbu$8XPv;Mp>h^m1KwplvIDl5{P>$OF&#B%-7Fi&R z{Eu`}q{WZzC+EzjdllXG;5BoO>jSe$*qE*M+TU4`fGaylb^xxn{IfQ% z@@Lo-7wEW<>?D;skJ-MtUYA2~>3jb8;X`?{Z~Hm-f3gsIx46G3PzsHfPw%@(>u!q!W}YV!AYIDJ{i|v20IhF5*x?A8D)5OkF5@ z4S2$mS3-g~M}E=so84omqnYKsdq2M3W_1shIeMvh4|GwG&pL@^FVkFyzjTNHZ9v-I z7b|pFRdLs{Eg`&)|z}s{=nj zaD)3H)-oPq{*G-_vQ(da_8E2=1pxvC>yu{a0jQ?;JmFCOyH5{n&*G~Qf^v$9 zCB&U32Y4COoDCK9wHc<6#TbB*GDnt-Hlb;;bD^Xic|mH==(V-Wp0Gzq`{Qt+T7YNf zvBCYz!`}lnZx4AeY`uQ`8#jH*Kpt(*_%3^k+jJ^hfUVzLqk%b2b;{Bov)hvKN4R-% zI8uIt2o*H6joYl{S*sJBKW$;cRmOH>fXn)&xiTNrgYo6gkL$_LS!aVJ0(qa4r)pn* zI_qx158fuU)&c+$@20cQx@;@rVLFV{?#Kv%&wA0ob}#@35;*$3?% zKv+`PSsF8D#XT^A#zEfIYKKRLfL2&H*-kVs*yi)R2b&&ronPbO3RggC?2f)(aGz(w zEmB=l8A&aI9<{^z`U37)(yM^30iSV1>Eo>2d8+$NokW3UV{~Yp@W|zK^VH5B&n)+! zNbo{_g{_8+bQ9c5ocL#*mFPyflpjgUmZoM?sPcQ-EGoyRB5?m7LWOo=u=0K={=z?y zt?&B@mqpv-g_y%xgrq^$VqCd7fugUZZ4|hIOzf*KnHt_ngTni>lJ=AlbcVC|8-Uwqy4$?n=H zD8s(Asb|G|LIQj5f(w6Z@Z8EQ;%IlI%K3}r+t=BXy*h2@_b{#b+drO4mP@Zy4_#Rk z_DxoE$m4}aGb_+0$lU3jz01+N^E8ygB&_lK@|vbcIHfRb9}{k642La^-yj#}W;*XS zxezFSnL!)$1F3(YWMLB3a;9iUDb*JLrz1uKsqpoOUWtMq!0#0aN9sT2(mH;7*(>Q< zvPT1?(lyyG&vTZ-x!1IYyZ)bz+DbiDb*zHRW^n)SuFC{T)50n~3niMN8j^xOq#scncKAF0tiCz2 zgaw0Y^)1A%tiMsDAu{-bF%7Qu5i@3az&2RK!PxwCIh0qlT_U>eL*-rq%q-F&rk=H& z8u%}X+Bw7H$UA=$EZt(93z(jWhj#=~UmJjAm>8Sp4GU6O<8+&7oNSor!^|a?@o7)Z zj8y~qKmM}MLN?YuH`9pL`4!VW7sn41-3hI}V5@*{6$0gXAbpB)qYT z58nFH;%}>)OJUmOXQ)``~4O8)4pdfD>tqt;jyh*xgE7)sCt&J+Y%W~ zl_)3ekx=>pP&=++W?Zw5vxUE&t^5p0W~QVF8?ey!JH6NVqvHq5O53**v1ecMI!B@X zvHos5iK}-&E?9DN!?^RlY*(Vb%{4&e7?&*Vae2*8sI))9A8ncCXXPJ~@&;Pb#l zS*H^WQ#)%}u$)v3Hy>_>_%B=au07>~Ys0y>dT>cts9pZO-)7KD|YBe z;$wTH+1t=wgo;bxIv~u>khyo(E|~U~5;!sWoMv5?-!(s=P4yAbi`DyA6Q1*&!%mk$ za>RQSyx0DJFj@RK(F$k4*01JwJhA-dLJQ|Qqd#+*F)PaRWY^p@I7G{UtKs?O zZPcg}6RTKSZWrXJ0;gfpr>G~;c_dbjFJYRLt?Id8gIM=JP{_n89no-piwGXDyWqYi zh7Bt#80EYY0~Sg-$;=`KK4Qn*wyC#Wy$Fu;E}?$uvEcQAN55x3%9b)1*EQ?}r%4j3W08ox&~)G0HreRS3g^f|?-O$S&VW7v+mI->!wT?HIl!vDu~P^a*Y zd(uwy`tFJ#bySw2vd zLbsICvOPPKV4F!rAT)?rL^H9C(5(yL06ZB`2nhVXZfGvxYeRpuW6r#7m5>lYsjPdc zSMA`<$ZS2NB<1e`Q#8*KBk5s=OoaHg3wu;%jbJ?H3u{>T&W11PHcfmpM7#e0sPW6& zC2VQV#Xi2#$N{wa%*5o^P!H-?ddn^TqjYY)y4lw_OhVi=0Q~fyZBXFS6ewCyGsd(XVPDjbnSi_cC3em;3g(x$-ivq`;FTzw`s{ zUiZ%i$_!hI#ujA(k6qC!pnD+#9)K!Qh|XU?N|X`vlWP#%jI^6Y`G{D30oCG9&3%7Q z?9}D1j&!|GmUPnGcR9!`Ja(_}i52J9-kR@+^)z8Q3o5&dhrwYu__sN6h#6bAE8^%U zI&1oNaizoq;;-x8@$#5b2N>`G4L?W(LKUzsn|xPaVBkDO0gvmg|KNqI(hJi zv+l!gbXNhiLk=Nm?B)wLNP2qULSE$#!-o4iB>K(ti#kg^WLqPzwR=F=8qqAc%{0r5 zm=tC~!F?9Xse_YU`)R)2T@2uSPZVW3J{6vKI=g$VX;^8d3Hw1I~FcetKK0R7E1?1g2kH07@!rmri6!vi_4y%vAV9K5-UwtYmLx<7V-$GpF)5lAPekB=;k zilSI0$LyrQV>+cLyYRm}QW{Hx+A3}_R3E7wlcn(0$A|!lJ-$O+LG#ba^Wf6+$E!0= zp1#bB;QvCWG_4^U8HZL05&9g>t9+vLlNeu3!@HSbs}!aFwl@uFR&@uL(KV-hCDam` z@=x|IwY$YiM6RE)(+=ZsHCv613NTsR*5zwgk3x;nA`L|**2=}xCA5vrnrlW$mm6{) zXv`%0w`lCHV|0eRgJO?kS}V(-&o|`_NAXysN6Gt%Y0mbcR6PKv(*F0+ft6(LLFJpZ zjNZD-Pe8k}?L_|xx&U|z{v_Gg{jp!QR#dX~;^=Xe-F{R|9ntPRPetVuh1rMJlqX=) z8{4N Date: Wed, 10 Jul 2024 16:26:39 -0700 Subject: [PATCH 14/15] Rearrange for clarity. Co-authored-by: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> --- .../systemTest/java/frc/robot/PWMMotorControllerTest.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index 9ebc2564..bd1b17bd 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -56,11 +56,11 @@ public class PWMMotorControllerTest { // i = (V-w/k_v)/R // // Substitution gives: - // dw/dt = (V-w/k_v)/R*k_T/J + // dw/dt = ((V-w/k_v)/R)*k_T/J // // Rearranging gives: - // dw/dt = k_T/(R*J)*V - k_T/(R*J)/k_v*w - // dw/dt + k_T/(R*J)/k_v*w = k_T/(R*J)*V + // dw/dt = (k_T*V)/(R*J) - (k_T*w)/(R*J*k_v) + // dw/dt + (k_T*w)/(R*J*k_v) = (k_T*V)/(R*J) // The following w(t) solves that differential equation (where w_0 = w(0)): // w(t) = w_0 + (V*k_v-w_0)(1-exp(-k_T/(R*J*k_v)*t)) From fbae540d912a83d7da536c282e538d02fdb94280 Mon Sep 17 00:00:00 2001 From: Dean Brettle Date: Wed, 10 Jul 2024 16:27:02 -0700 Subject: [PATCH 15/15] Remove extra paren. Co-authored-by: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> --- tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java index bd1b17bd..66b30d0e 100644 --- a/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java +++ b/tests/src/systemTest/java/frc/robot/PWMMotorControllerTest.java @@ -78,7 +78,7 @@ public class PWMMotorControllerTest { // // C is a constant of integration that we can determine from initial conditions: // theta(0) = theta_0 = C - (w_0 - w_f) * t_c - // C = theta_0 + (w_0 - w_f)) * t_c + // C = theta_0 + (w_0 - w_f) * t_c // // Substituting gives: // theta(t) = theta_0 + (w_0 - w_f) * t_c + w_f*t - (w_0 - w_f) * t_c * exp(-t/t_c)