From 17850c53de0cc77121161296ef7cf71e9bae4853 Mon Sep 17 00:00:00 2001 From: Collin McIntyre Date: Mon, 16 Feb 2026 01:46:44 -0600 Subject: [PATCH 01/14] lay out turret outline and add javadoc comments --- .../frc/robot/subsystems/shooter/Turret.java | 237 ++++-------------- 1 file changed, 55 insertions(+), 182 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 149b1b8..8566c7d 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -1,233 +1,106 @@ package frc.robot.subsystems.shooter; import static edu.wpi.first.units.Units.Degrees; -import static edu.wpi.first.units.Units.Rotations; -import static edu.wpi.first.units.Units.Volts; -import java.util.List; import java.util.function.Supplier; -import com.ctre.phoenix6.configs.CurrentLimitsConfigs; -import com.ctre.phoenix6.configs.MotorOutputConfigs; -import com.ctre.phoenix6.configs.Slot0Configs; -import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.PositionVoltage; -import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.sim.TalonFXSimState; -import com.ctre.phoenix6.signals.InvertedValue; -import com.ctre.phoenix6.signals.NeutralModeValue; import com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState; import edu.wpi.first.epilogue.Logged; -import edu.wpi.first.math.MathUtil; -import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.units.measure.Angle; -import edu.wpi.first.units.measure.Voltage; -import edu.wpi.first.wpilibj.AnalogInput; -import edu.wpi.first.wpilibj.AnalogPotentiometer; -import edu.wpi.first.wpilibj.RobotBase; -import edu.wpi.first.wpilibj.simulation.AnalogInputSim; -import edu.wpi.first.wpilibj.simulation.DCMotorSim; -import edu.wpi.first.wpilibj.simulation.RoboRioSim; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.Constants.AIOConstants; -import frc.robot.Constants.CANConstants; -import frc.robot.Constants.GeneralConstants; -import frc.robot.Constants.ShooterConstants; -import frc.robot.util.Utilities; -import limelight.Limelight; @Logged public class Turret extends SubsystemBase { public enum TurretState { - Idle, Track, Pass + Idle, Shoot, Pass } - private final TalonFX _turretMotor; - private final TalonFXSimState _turretMotorSim; - private final DCMotorSim _motorSimModel; - private final AnalogPotentiometer _turretSensor; - private final AnalogInputSim _turretSensorSim; - private final Limelight _limelight; - private Supplier _swerveStateSupplier; - private SwerveDriveState _swerveDriveState; - private PositionVoltage _positionRequest = new PositionVoltage(0).withSlot(0); - private List _cachedTagFilter; - @Logged - private Angle _fieldTurretAngle; - @Logged - private Angle _robotTurretAngle; - @Logged - private Angle _turretSetpoint; - @Logged - private boolean _hasSetpoint; - @Logged - private Voltage _turretMotorVoltage; - @Logged - private TurretState _turretState; - @Logged - private boolean _hasTarget; - @Logged - private Angle _targetHorizontalOffset; - public Turret(Supplier swerveStateSupplier) { - // Setting up motor - _turretMotor = new TalonFX(CANConstants.TURRET_MOTOR); - var currentConfig = new CurrentLimitsConfigs(); - currentConfig.StatorCurrentLimit = ShooterConstants.TURRET_CURRENT_LIMIT; - currentConfig.StatorCurrentLimitEnable = true; - - var outputConfig = new MotorOutputConfigs(); - outputConfig.NeutralMode = NeutralModeValue.Brake; - outputConfig.Inverted = InvertedValue.CounterClockwise_Positive; - - var slot0Configs = new Slot0Configs(); - slot0Configs.kP = ShooterConstants.TURRET_KP; - slot0Configs.kI = ShooterConstants.TURRET_KI; - slot0Configs.kD = ShooterConstants.TURRET_KD; - - _turretMotor.getConfigurator().apply(new TalonFXConfiguration().withCurrentLimits(currentConfig).withMotorOutput(outputConfig).withSlot0(slot0Configs)); - AnalogInput turretSensorInput = new AnalogInput(AIOConstants.TURRET_POTENTIOMETER); - _turretSensor = new AnalogPotentiometer(turretSensorInput, ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MIN_ANGLE); - _positionRequest = new PositionVoltage(0).withSlot(0); - _limelight = new Limelight(ShooterConstants.LIMELIGHT_NAME); - - _robotTurretAngle = Degrees.of(0.0); - _fieldTurretAngle = Degrees.of(0.0); - _turretMotorVoltage = Volts.of(0.0); - _turretState = TurretState.Idle; - _hasTarget = false; - _targetHorizontalOffset = Degrees.of(0.0); - _turretSetpoint = Degrees.zero(); - _hasSetpoint = false; - _swerveStateSupplier = (swerveStateSupplier == null) ? () -> new SwerveDriveState() : swerveStateSupplier; - _swerveDriveState = new SwerveDriveState(); - _cachedTagFilter = List.of(); - - if (RobotBase.isReal()) - { - _turretMotorSim = null; - _motorSimModel = null; - _turretSensorSim = null; - } - else - { - _turretMotorSim = _turretMotor.getSimState(); - _turretSensorSim = new AnalogInputSim(turretSensorInput); - var gearbox = DCMotor.getKrakenX44(1); - _motorSimModel = new DCMotorSim(LinearSystemId.createDCMotorSystem(gearbox, 0.001, ShooterConstants.TURRET_GEAR_RATIO), gearbox); - } } + /** + * This function executes automatically every 20 milliseconds. + * For the turret specifically, we need to ensure the turret + * is behaving according to the rules defined by the state the + * turret is in. + * + * If in Idle, the turret shouldn't rotate at all, + * even if the robot rotates. + * + * If in Shoot or Pass, the turret + * should rotate to whatever angle is provided by the + * TurretDirector class. + */ @Override public void periodic() { - _robotTurretAngle = Degrees.of(_turretSensor.get()); - - SwerveDriveState state = _swerveStateSupplier.get(); - if (state != null) - { - _swerveDriveState = state; - } - _fieldTurretAngle = _robotTurretAngle.plus(_swerveDriveState.Pose.getRotation().getMeasure()); - _turretMotorVoltage = _turretMotor.getMotorVoltage().getValue(); - - if (RobotBase.isReal()) - { - List desiredTags = Utilities.getOurHubTagIds(); - if (!_cachedTagFilter.equals(desiredTags)) - { - _limelight.getSettings().withAprilTagIdFilter(desiredTags).save(); - _cachedTagFilter = List.copyOf(desiredTags); - } - - var targetData = _limelight.getData().targetData; - _hasTarget = targetData.getTargetStatus(); - _targetHorizontalOffset = Degrees.of(targetData.getHorizontalOffset()); - } - - Angle requestedSetpoint = switch (_turretState) - { - case Idle -> null; - case Track -> _hasTarget ? _robotTurretAngle.plus(_targetHorizontalOffset) : Degrees.of(ShooterConstants.TURRET_HOME_ANGLE); - case Pass -> ShooterConstants.TURRET_PASS_TARGET.minus(_swerveDriveState.Pose.getRotation().getMeasure()); - }; - - if (requestedSetpoint == null) - { - _turretSetpoint = null; - _turretMotor.setVoltage(0.0); - return; - } - - _turretSetpoint = clampToTurretLimits(requestedSetpoint); - double targetMotorRotations = _turretSetpoint.in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; - _turretMotor.setControl(_positionRequest.withPosition(targetMotorRotations)); } + /** + * Any logic needed to specifically manage any hardware interactions + * when the robot code is executing in the simulation (for example, + * update the 10-turn potentiometer's angle based on how the motor + * driving the turret is moving) should go here. + */ @Override public void simulationPeriodic() { - _hasTarget = false; - _targetHorizontalOffset = Degrees.of(0.0); - - _turretMotorSim.setSupplyVoltage(RoboRioSim.getVInVoltage()); - - Voltage motorVoltage = _turretMotorSim.getMotorVoltageMeasure(); - _motorSimModel.setInputVoltage(motorVoltage.in(Volts)); - _motorSimModel.update(GeneralConstants.LOOP_PERIOD_SECS); - - _turretMotorSim.setRawRotorPosition(_motorSimModel.getAngularPosition().times(ShooterConstants.TURRET_GEAR_RATIO)); - _turretMotorSim.setRotorVelocity(_motorSimModel.getAngularVelocity().times(ShooterConstants.TURRET_GEAR_RATIO)); - - double mechanismAngleDeg = _motorSimModel.getAngularPosition().in(Degrees) / ShooterConstants.TURRET_GEAR_RATIO; - double clampedAngleDeg = Math.max(ShooterConstants.TURRET_MIN_ANGLE, Math.min(ShooterConstants.TURRET_MAX_ANGLE, mechanismAngleDeg)); - double normalized = (clampedAngleDeg - ShooterConstants.TURRET_MIN_ANGLE) / (ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE); - _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized); } + /** + * Sets the desired state of the turret. + * + * @param state The desired state of the turret + */ public void setTurretState(TurretState state) { - _turretState = state; } + /** + * Gets the current state of the turret. + * + * @return The current state of the turret + */ public TurretState getTurretState() { - return _turretState; + return TurretState.Idle; } - public boolean hasTarget() + /** + * Gets the current angle of the turret. Angle is given + * in field-relative space. + * + * @return The current angle of the turret + */ + public Angle getAngle() { - return _hasTarget; + return Degrees.zero(); } + /** + * Gets whether the turret is currently pointing at its + * desired target. The target to point at is determined + * by the state of the turret. + * + * @return true if the turret is facing the desired + * target location (or if there is no desired + * location), otherwise false. + */ public boolean isLinedUp() { - if (_turretSetpoint == null) return _turretState == TurretState.Idle; - if (_turretState == TurretState.Track && !_hasTarget) return false; - - double errorDeg = Math.abs(_robotTurretAngle.in(Degrees) - _turretSetpoint.in(Degrees)); - return errorDeg <= ShooterConstants.TURRET_TOLERANCE; - } - - public double getDistanceToTarget() - { - if (RobotBase.isSimulation() || !_hasTarget) - { - return 0.0; - } - - var targetPose = _limelight.getData().targetData.getCameraToTarget(); - return targetPose.getTranslation().toTranslation2d().getNorm(); + return false; } - private static Angle clampToTurretLimits(Angle angle) + /** + * The TurretDirector is responsible for choosing a target for + * the robot to aim at and communicating the desired turret angle + * in field-relative space back to the main Turret subsystem. + */ + private static class TurretDirector { - double clampedDegrees = MathUtil.clamp(angle.in(Degrees), ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); - return Degrees.of(clampedDegrees); } } From 8d33012f369c06c02dd67226c955f6bc4ca37b38 Mon Sep 17 00:00:00 2001 From: Collin McIntyre Date: Mon, 16 Feb 2026 14:22:14 -0600 Subject: [PATCH 02/14] update documentation to include diagram and calculations for turret target triangulation --- .../Rebuilt-TurretTargetTriangulation.png | Bin 0 -> 432359 bytes documentation/Rebuilt.drawio | 145 +++++++++++++++++- 2 files changed, 142 insertions(+), 3 deletions(-) create mode 100644 documentation/Rebuilt-TurretTargetTriangulation.png diff --git a/documentation/Rebuilt-TurretTargetTriangulation.png b/documentation/Rebuilt-TurretTargetTriangulation.png new file mode 100644 index 0000000000000000000000000000000000000000..5a93e1d5c73521ef5753b29870fb73f5ba56f67c GIT binary patch literal 432359 zcmb4scOcdK|NnI^6>g;@O)6c=ND;Df+P4S|dvDpJ$aZeIB`XQp8f25bN!hc6jF6qZ z_xL?u=QtdF@BQ5S`;X4?e!pJN*K>{fnCZ>il3bcNXnkv7geEUJuvBWGrr_GZuxlwMf5a>iLXX)?Z1jGFc8k+(24z> zOy}@_dmCZ7G<__Xo!SefF1wlW57br4KSugwB!Z2iA=yFl?}yYRUtak-h#$Rlx5U zmk9d6^?;Ln%jqb`^nW|Z4dPa!gPls9tEOEQhqZG4w*URIwGB+agtwmkn8rgYoq1nJ zU6P|hPsRPLNqVFSvidh5!!B!lhxcf&bN3+nLOn;n_z8-xH``5%gae{ARi zIBtuOFmJTTP#cPv%l}Qb$cO8l2ZOtwz3I`~OLY~=JlE7}Rq8*>7QLsQA~X1;!oUuJ z{}apZk+E$!EfC_y2W&;^i&KfK*+SFz!m;t+WwWkcxO&)YYPh;9QI+yA;^O~pyJ~#Y zpi0`3jm&{{m%jE3>gQ1IkM}HQK1f{I+|2!GpE%45* zWBVx1Iby3RW&Qr=mkC=WDq`OV$~zW3ei>W!BTE;s&wpOPT2{5L&PX*Zw#Eef&GOsIq0!sK7wwqOQcxM`1}Z_`lua z7e5fNfQ_2Fs3X>J%NYvNR}sDYKdhj}0r`gzOOBhXZ^fFE+5NnL^`l(VCM1I9!(eg; z{|I0ENAv@hgZj+=e^~&w0eSt(>RNK^EBPn>t1b|%z>XPSTHR+ThL`Akh~wk`8Ttt; z!5hD%2iVQPSS&xOYp^@6YW%O;-HP7%URihMp$6T*ei_nLd}2meF1bH!mG|l_@}amQ zTACgIA{wM7tJ=}G33UG(B%bT96h5wMxc=MU8Y+7JWDJ%APSxO{^v{Z?cP@YL|BM1S ze@LAblH!ZrZ=s10A!8v;WU)h(LUUbS@2Ug_E=JytQVdz1e4EuBO0QyTs#SS2a@Vh$ zx48xwWkxF0r*6SD(V1}l(^B1zfjoD#MZF*{MQO(<`|3$aVm!{y>k7@Zm^;0&_^S5k zd|pzJf>B1;Xx~2lm>sV#yRo|dSXDS4)^^#yQJ#cD@bvtb8?!XGBZszO$Xj=(&$QZT ze0p`s*m8O9-e~*#ccsh$i%E4U4$4;D-Yoz|0A5DzDj4~{5!O?zAvn9(p_$IRB%gk9aWn@XAG(Pm z*kO6@{^y#Kpl+BfMJ0%lz$vc@@6R2qa86ZZ!`#gOU@-Kyb) zicmo+kzC~^5UN|=;@lg&yyRzeC_d9ktCI4>vk-EihW zQImeW(wcSj-^_pce_e22+Ky{4hSK7d+ey@lum%V@)=^Z0i*pm5%L^l%SfkWN?Nhe1 zqXjRvt!)y1m>18lBK=$4<6zcd&O0zu9PN{&9~`O~p+LJ%sy@44E+=)LRe)itbGNTb zuJs>TZz*CVhzGHHqSuY38jO)kQctOqcDWh(B}{*! zlFx%)`Tk3j^w_l4%$f#*dl;fS`M23f1RbbS$~bc%Ns5lUyo-hw?d@V{3TuM!y{E`Q zMBI37t!Fi`o>N6^Cezta_2C3)_DF8lx%<(7x5=5GooYQf16cfSDb*~CqA(F*>&ZS@ z^GY7yv+oc7{7rH41H>}6<|`cd{)MF{?nn)q*i;$TM339FGriMY(3->lI&b6AzqT{B z>Mt}thOa5@96h=AEy540Np=2B@Kh%#iq=2IS?@B@#=k#7_tUG{0hJYb$FJZM%jk4` z+2wXBWejIeRLO$NrPenFPkDpYo79Sg*;McSy!cMcl+VfLu`R;qemc)D0ge+E=Tw&$ z=SU(00-!uyKX@ErS~~HMy@N7wG?D+@n+4aG`o&D zORCN_+!zVrsoO$hA8DNmv!ba6htk@VWi4Y<>YqTM*j02FT-olLe>5ykWLVwT`B_#a z7rL7w&>6`b{)`{@HpD*jN>qOC^8A2lZ;<8gj!Ml&DQUT|li{nzcRJMZ=?0gIvIzRV z&B(YmbILtl-vWFq!GO$?^7OO(gO)8fw&=L=)Ia|8`U-uKK&@PY>bZ(w;jGcVo&aNp z3xEA~d@Y9J9}p@{L5cz4mN~%G9P%7K%`lRAuInYr?nG#0lXY(_PQ^QLT+IA*d4Hi^ zbgcBA0kPh(Vnz?0V5{)azHNeol6?b{8IHeh^kN%gn-|DMkh1p_;h4d14X!2G3GBGJ ziQZznnQt;Lp4Dl|Kx8hE)e)F!b8yI>ZqoO@vUxkhfdGTVt6}j3UC5NkzqUaTuufF} zU`J5ZY-cV=vW1#9ijUwCa11-|_eZ|%aApZU7PCBTnU_^FV$kcOV02vQ@59h-N?nqt zzzeQZLfDLK_;lvc4$9TDB`Rjk0%lDC-G~Zkud_csd;D63KTq`N?2A(x>R%JooKF28 z8yzFRNB{xBx$i=?&p2}-ewV_BRj;qx#J%557KYO3tFnsr>3{6|^m=24(OKl?LMJWz z60b%$0Xh?d^}i$>I3c6QJv}+FnQU$KxWDLW4x!&BH{%*q9E6dLo{!jXn0zB9wMozE zUDaLWY3>ha^ip}C{KhGF&0%9zsK15~)Ot1V-9jVlgVg}Hz;=G-|7b7`O(7S>Zg$z4 zS5$-H0Y>}SKr~z-`qh;-BRPD#IplBq`Rf~{fB)eD`ub zH>ncz#pHK-h%i(OO^AIT8|y5lpAQ;pv1m4Qy3zpQQPyTCg&O4<$tw9`e=i&|ObS8` zr(2!Zvb%nz{5gVez@4Q@Us+!0OleS#9z>p|c(;PVjUSe&W2-p_m51@qVXbC_oSaa# ztjptcF80EuV``}{mEWqa|0_zJ7RX~RhUStRWpw)#;2LB#-1hM3-Byd?4(bhYILlx= z`o7?Gvq92z&GSZTk{c3>d&k>rNCYuS4>DTnzV70M)yEWVe8*vOV%B@uXD#amTmJrt z(Y-g=CT_H^Ucp$YZ{SP1W9Pcm2?tD)r(TCQ81D32jjvxa9Vduip3lm6;mqBWq*Hz3 zq(San&neB4r^uEqzul8zmrHyz-uHM1Q)ZZ%q1L&r_*1A6C#&7CM!dhHIgAV5wWr3* zMPWk*PTs_!dIa=UfFl7)l8;^zXXV5VD!b~ltAr*h#N%a_+I!E=WE5mh^i;Z3@;1j< zKjB@|bu!El{YhdpB&>Y?4+sK`?`NtFFI^{^^8d*h)*e8L|A#I^{Ht#hG*?HP=+h@# z_&0isQ(X@_i=x>7g2)?FpEfHPY~C?{?dR1dVk--$`=jHFCV$j+ zzVQ-&a@C8ukU79$=Y>bx+{k|2^gQ06SGKjBpPw%zG6Q=61$PpS`Qq;AweGq5P#5L| ztvq^%Fo!BBHqd|W5UmQhjJKbP zHoIwXo}W~B%UShqUEb(0jL8SD zg6Ka&UlDjNcSDtMW_BpW2GtDxfMHm3cIZ4&rQa$@w*wbP zbw7B6Oq*!VjAT!!N5`f<(T~qbt@G0;a&?w)n6EYc5$0Qj(sj<*XGLZzasoUCNDQau5T<}cz9?wZ!;3mU^6HA_ljqU=b~N!lleB+DT& z(VrV4U|3(g9Fx}6^mIbLRc}zktHeQh{a8A_*83Vru-_Q0;{5b`8R}eg!WxA{r(WQF z%w&{fB|1>;=Q%?pu$22J07$P}2jSUZW zHDz2GmdY^-{=NFPa5%v|U5*WoBVqyQVWAorZ4&W;>%uLw)T{tj+$OmD)CLo$>2tt* z+cQR=JL-h0Wwk<;#SZ#Y7K2|4WF_vJd9*}Z4+)6|M_P+*^tW3kMaj;szXEdThmG4* z{lNd= zOV;IpcRFi+b9c+@DhoiMLDuHiP!9xgWw^YC#=I#6M&f}Z607nXw&;%xlrw31mh#f z*x15sMCig)aAmcuokRfkEx8ae=OgO-T9JwsK{cv`N_GNa>m+^qP+?4b?!2BN=(4=N67Q7VnpJ?>N@D&bHT_?3M!R6mZZCZL z#mV%EsQ}@ap))gE8?t=+t8KOL4Ey9lV(lV(Wp$IU&cJMIFmdyEJ%CduLCJAV2=v%L z^8Pqp({E6GTssU&UyQ>-a~oA}t7-8;>ZRPl(;}i1Nz>hpgJ32&d$vO+B*%pRYeL}t zhH$S1nPb1Ke=N+Yx*2|($>JjMm#ZIscFp&T4I9MEV6czuScL^x?5J zCEz&P?6Y!7B!kZ$+&F87w?J@gENHpcpp;fKQZ7D`bXr7TCAhM6qazC4M1BCbc39YG zc%XvTDbP}!HJypk`ZCEgFQ|SmaB|Z6YwLdLpVntBntyiVQ`g;FrUK}wrHlL;ToF2e zktPUzEAwdIYmcIj&b0g4S-%qxAoEzeDamVBg{ODyJY^EkB-a6Am?0!d`$Vy)r`Qrc zUt^=&mZ$pu&+~aqLGcbt1Ml8%+JBL`(xNLPtkTflr$sf1yw^8ZYZe5Eix>qfLCz6U=_2bTzg1R+|xyN#DBCi;eYB zWfn382I$xZ603R$Sjk50aa9J0-{f=RkebC0-eKbN@M6m)5A*@UpuInn)utpn0I~np z%e-XqTdxdmNi~L54wT);D}_w`^ePaJf8f1C?Hfz{n&S}bgVZM^RVcsy)L@+aE8ksk zSoUj=W!{3)%eHJUDJ>T9z&+*Ho)5)QB~?~`UW}=%miDmI`6sLb-iT{O#E#~UX#yg) znW;w2v0x08F`z(d$2L76RNhT$$))+$C__TO#{NHyU%FKd}*q|_+B>C1FOG; zL~FUjZXO?x!Mk~g&$lq!HUjd*Hc12%?C9QP;sNh<%{QbxvlZFDj4Fh2*QM#^c$)U) zJGE3x)F;vp@qSf(pe60iAyl(9s7I%SyGJfd?T+ZWuw|b(s%=!-nmu4izEcd}R&l7+rzzc%R?oIcgd}zS@xsGX*=oKs*darQ&X%k0@PsWZ=eI@w!$;|v-k(IfE zVAzJr%Qnv{fE5L}a!x`crP>YZ>%^1wiv~^sM1T`FPiJDbQB0^JnLi4)ZC7A)Yr{u< zd6*;dEVv+xrsJ1g_k4PLCHF^oK*v`N501d^zcS8Z515r4{u#@N*vO{~MdXM2rv0W2 z7`H=*HjzI5v}1ll-trV2>(&k@dgVT|(?PK(&}kIoHZ#b6&AZK72=QnM;9=a^9SO&Y zTVGX|^}hbrqab~pa=0Ynd~w5c3Hu0N24)LFF3esH9)BD7+3*)yX0g6ec{w>=w$igp zleJDd)sUlnH7n=9Ljp*Zu)P#QYk(Bt3&n~(;zP*aMFmmRT!6kIn_Bclvb zo9ARb!~{X?8oo*v&ON1x;H%Va7dsh8JcT((-JBBjnT@@IWYkaHdMIrGnsgi03>v2X zJGHWsq70^-FT3rN`lh6}Fq}2w4yM8BEg-8`YhmB&Fa}Jzde4wW=n)0NLeA) z;t&O@8|4Wtj=N&{Yv2%0nZD#&A}x!!Yw)$_hE%%9ob^)Yt!l6H6&9bJe)koyzK$}s zc!N_cY~{fa(Kw2>;)QjP>I~Q49!n@QY5;ZVn;u&~@F})-L@A2cj1zlq7{zMyVJqL{ ztfz|IR2@o1=ln$+>@|OHEI*OOE`H|w!>7OiS3UzEdjVow>j)e!QHP!n!?Kh~AmTEL|8--NQ1z!*&)D>zIXzaLiR||1# zR|kLVS7w~e-`o+GHT=ZGVX-r|m2YFh2$+*x{`$U_5PTqF-FP0+D{o-ef~+HUWoJng zUaTH=gBm;sX8}|>h?=I0(`k8b9BD0y;nn>nKv#X>$o+ql2LgXn*8}u!`k3FE50%Wq zh!aQwO@~JTjTJ_25fHQeO{cPE-afw;_Cm7bk-%1J)5G1C2qN|1}6 zo$E>maJ;;M$wO!-w6vTTE7*#mZVoA;&zmij1$4~1%hvDB!e>#=Lh!9pxrufwOEbmB zkP#wlP!NBn1nIGjrm@S;zF)}{NFR@K3L@li2$D#^>Bm#}Pp^6mON_;8oZNTrkeBR4 zSya+MY?^YQRgd4h`(qu~bp3<^=v25PdE=9+1lZ~o%`3~6+)tZ@xL5G4#^neKGM)9z zW!;Z2T?ajJu<7goJy|nTEGn&!Q7?{pIJg3S!lvx7G-W1|r;4ex`l;loBMr^~M?A8!B%$+xhJhQ?|(hU=`1 ztSseu%G?qW*?xAmebJ=O(UECAkP;rYCL+*kOGIegc1a)q9b7PN!kX1%w{J=IVHZ@* zchrqyZ%#%jf<{yFo$KGmb)(vGz(C>rFsdQ37qJ_b3xX#k{FCos z-DmB|QrESlMuhw#xMN(?4%AB8$GF(OxpS&Ph4Vnaj>v+XCYQmKsBw*nf^OX_H3{} zBJv0?x&-gOv|X6^F|LS)hQJ+?4bKPrWrWs?mLg~(2WxrH135X1BG?#j7ZGD0y z3|>@nn9pu6B;JdYZ$%9I=hvE+eM)3mq%o3UYc+KzU%H!^u|f=i>gTdQ~fbE#gP;nMhvoI^4d>x5H{|(M&W@uKT2UuMv6-GTT#hb?6#ziSvimjqQH0iJ(fjOgfXl zt3kh}gU{JN^X& zF?V6$_E6t4i#ZuuD~d@yj1Bc9-_5CfAg#^b#oj%6f zV)Eh4WX*-nS1u=>pmu?0!HBo)?h}f8z}6#P_*@H1@A22S)*1h49>t)SWY^_+#fR42pV@sMPgLX&JgzTrY!rA3g>pJUbWE3B9}lHApAZ+G z`ZC+xw!9m4;?%}S8HcRdsB00xE!PlF=2MT=>1dbf{)dg-&@oigq*J->TNxn3U$thl zSN4f4{g7a*1?RMMO##mmXyPlR7CG zZ?BiFwiA_QhY>x%g`P8R(zl-I3zmq!K%gb~q}qA0*-*gs8bo64;MO?lmSDxl6p!rP@-B z;q9A#+e0IFW3=YNcEf%0{W{XVLEJjx-OF&8Otji;zXlm-z8WlL2{|z5C#rc~X3AUR z1QNnAs;+o1oj}veLZkV=I_-aS!0Zp9g~6mTm6a)#caYx~XSGhn9rM2C&CeE-aNYni zt?rA>wiaLn?>e5aNe}CE7Ep7#0xH5B0MDC$;JAml$W_Hae1VIQ*a_l#cC1Sszj|NH zw7tS1FD-88sLW>uSKtS=>7lyTW&hH|&SDRTtlGkO)(VRqHJyNo3F59W+MR}$iwa#w zmGP7G_CKlB`)Xb~jfLHVP-okBfsvJ^c-y|y5nLQzrqzNY*(G|(-m6_b5TP6OnRSW@ z*a(WYHo~z`IL&O4-2fz&?<%26gkVQ0d7W198M`2G=3ej`%GbW`t}gXru@t@6IIf-x zqGup8-?EE*yrJi9uyqs{FA#`kn;LR=0|_z4H6`toX~)Oek1S_zys$_84&d>S5=`*B z@5JyDB0UeHj%zDBJyeI^a9{Pdj31=rGM%8W z`Xf7gc5Gy!;KK!KMkMTjoS3&jVb`yu`e=PKzlmJ$kM=6T5m!`@IB7NtwIZ$8HBKCa zP9JF5M8;Y!5*~-=5l4{WfC+HeN5y_lJVX;j;VzbWkW2HA7+7QXfVYhD@tBzsCXbH- z12MG7u|ti2$BBRF2Vz>Fls+`^a^&qN(8Nt2?}M~n1M&**g@O1yduXw8doMID_sitT zpEZu0j8E#CGhYNgMMOocQ5TloPxe#>G_;2K2ykjFw$9|zTMY|2L{3_;mvf{kc4Y~De@NSb3f@9+ z4fouJGv5Kgh*0$oyAc}|*FC3Rjkkgp#z3yrJr;Aj?Vzb;gI_EJf1J^dge{~(+@}cX z!Gk>2?>JD>VmnUk6+gs4wnrS^*E}iN{6^*XDqhwYZprA@Z0slZUDVHdD;|{T z`nE-H7nvzwTFn?xHueLf;17S?y!2H{Mu}%QXQs78v#yxYL1O33&=b2vx+Oc~a+25R?0vS5IvNN?RatSoj>ie=P>|y>ToiWJF{bQQAET$@^DfU|c4x2{Fn7 zZ~sj9^IILWogSPlftp&4)6C_};?h1rr!+3}mdi*dl=t#MrEAuPk05=5IG|(YO5U&l z`d9bS(*CZ};j>DSw^><&ApI!&oc7H^0r6r#8%uOTF?u0;zCYSK((hq_a}>(`)tOFL1Vr$A-Up(HTRCT5cK1hZrn$-^a!b6`UkB^CvVOF+ zPH5fKm-Y{WXoMKi<%(%Pw3)M)2X#c)WS%cAjX1QOZt3YoMG(MPoGg1Rdp+F5umC9M zl+&4W2lH+puX+e{MZwfo>w)x<+=bS?gn+*4vO!@pFXbNruZuct4A_)4ybq%1Dp$H` z_nCp1qz-^yAB$NS+DtcdYgYxz#hqBN7#WJ6TU2{=aN43+25ETTEgb6bB4X*84{&TM z;<_kbqU!wCSgKiko$p(6q9${$GLQzn?G@a_Y;*dfqFHONh51}f_YN32ooJ>n%>^~7 ze%oH>5~?glNC7&bSKz)_(f=BKp1V91?;9Phtu+}FyijG5aefHeu%E`0Adyk3HR$y2I>$sra@|;9gBX=nkhq-c<4sbsP<{@G}OUpBPjB=(t)zUea zQtp1=&spAPsP1YOD~SCq`SX3SoKA=3UWYPEX=vTe&Q&`wpmY>rHKwgr zz1||`RSmh*DdU0RoPHGnIypeNExUjiU1EWDh_VLZo?Rq>&MX9s_bZ?SW#<05Es)}j zL0>&Gvbje`TG7yd(pkdxRp4*_`n_{z@i9jOOg;8;hu@K(-774na3NU9_sf?0Z`_|c@a zo{)88!H%)+Ybr=b}x*ctKK{Rv9c zrRDDsK(4!=E{#prN^o-XC#9tLdmIFA)G6JX&@vO|Kedk-XsPZ6owfsi%gW957div> z*NAOwCRH0_5lp8Y{dOCJ(3!;kACR*z_kX_@=U z6J-$S)7@w(hjN#k39XNhcXXGfLXu^xbMy$?cbGU4i9I?aZM2v)h9aFJ-AqVjnFv&$ zMlMOxM$$Z7=Vo9XCyw$}2MO|Vo#UhZGdesq%TL6|pXG|qGqcFs@;&?RggEDgea`FA zdS=3G!a4LlMlzt+Ak%CFrVuRd)Vf*bInw>?7K-R)wIPT0E$t)>`>#Pn5%greivGl! zI*t1!iCexic;KZMdA8Z3+8xUJ}V$7HBHSz0wEXI z5g?7cKSG?|fsUpP$axV`){V^)tPX(w7SdJb5WjLA*DzBf4YG`G!BwjPL32B4~P3@cmXs9Z_94k(m*OOL@ zWvHOal)IW{Z6G&<68VF7CE4>9$Gz`(h%Dc4v23&Rw!g9uv8rW`$JzJjt1QT8)hp-( z-8<503(l6w%OYXv5=H9hBmK)ee z!qfS`Zg-729q4TuJ(8AYNLn!BwFjouV>kgwn3~FkZaPU?pK_%A0C}bql(Hgor4mH| zM;wHzP%kYe$XhFET%}gs&)|8T7D^n$4+HH8q;&;JD^VR(`4&DiggklW7)#CaVy}n? z>Nb{(g$hFtuUtwGB0*)?<-pQtRGNQZMhbO*tdO2s<9ZPE+?cq?k|RS(Q~mBXe=#0N zva0)<+Qav)n!G7Sp!v&)b2Xie;;DK7c(!rmAd|VT4HIx)I9 zneyUE01lNYu7#!1>P|FF$6);FG)Ex9&qAQv_v@zQ#k|}kt|6!xGb&8Df7}Bv6<3jg z0y3nvu|Nfo`!oryrh8pFwX)33+Mf+?<;7OttCxEld)&@Kgw{+@zR+T>+t=gpg}-)H zwFsTFf{fj1!H>OpM^gABh34oV$~tG;rs6CMQE7{Ugzxoq>H!Wdx7JN8u~M@++}`G_pn{r3q`qaRTXIG8Yf+=jAK?e> z-Zc003aX@=sJ(4y2JZZk=uHk?OpJHT-Nc?P6>{3&h%*SJ%!5o(5!Ka(XLT?n+6@W| zELw6VuGB+E*>LJ@8gkQr-llrvR- zL+SWb?!vGOAW}(Od=2RUsj@At!ZC+SQ_YgZ_XDQjo-JU#2<@W8*B*D97ePlaG7DK2 z|0#E8cC*Orx$Myb>M?|p08M}v#^CIJ+mkRUaQKAux-fh=YHpP#X6O^}_$0a9%WHsq#t5GEc-I#@6X%s@QSHYK zB!Uj-`!Ipl2`Qw$rn;VtW#j!$H;vbBysYfp0DGR#v%-)3#O!H4oeN~&bSQP1M9kT% z;ahy#Nw!*MhRlsVf?LPC3+Yu{5nO-aQ`dr?vKlX2sx;^4Z1sVOY7rIj7jeP0!4}MN zI)Ca-wcvi;ENz(;ro`%fgl#h;kX=my6?k544cxtt`2MSYY>ND#r%3AfeoKG*nB*6# z>m5yS&-Yl`^I^MSjxfhEb@tL)GX_Q?>+ygx!;ZdE&BoP~fYElfjkcQmN1Vb#SE$WU z5V;JV@a`G4q=bCIAbcVUQ6;-pf29}@cF727YtW72Y^#YfYR!(WTN1)j5O+Yo`M64X zo88QEKo(=*)pIU<*G$xv?u@n91xdya`?Q(E9J8y|xM_-3_vQU=6x6#fN_)o#*W1ST z+kC65deg#@`t^vo;81djUM8aBo|eEY4;ec&t7Q!fgxnK2-o84&w6<-a(6l;B77Pl~ zoZX=Gj#wtDFE_=Kv@4$=#E!%LE|hwOs8HVBd2nwDt2sEr=M~SZ#RJd0Q&i$@#zVsq zhKO<#X_8;eV8b4l(c_OsC*XD)yYc9%Sfb-Fs# z*QJay8ZB)|$YN8QqCSuO!PGW1lRK016}rx4QX1PKDYB5_JK=q83~F@|1eHWAx1lgE z9v;h3OK58599G><;-H!kqb$`EoWPe<$6At_MUn+0H#hXg zF-g$-LvT;`n3!r=f1=-uTYJAiXbPqX%z00NM#AyKJ2&iC7TP?ZR7gHq|EUT^8=jnk2qLed2RmlZj)AkXI+vu zGn5efVGc39c)xM>4Zq;4#c1XUykJVbJR2G|Fp!P|;}C(?mh6wTI@CH*1W)VqrXC3U zoJ|wT3JQW=#uC7ND7iL;297i-z9R!miHvpE3iLbB(trKIy4i2JdpqA2FQA&&s9E#8 zp=0$!+%(k-!i6dGkMdClKMUCiBcQT@gP-fl5+iw`cL_1efKSPf-3H{qa}Q6$1#BIG zj0pdu6Q4tq#L(nu`|+j`Hp(;JCRpbJ6I;Qbf~k_`DwJ)8=pdV})}AYKXzTK?^S(aO z#^a}`5L~0G!et7+k<(D-_K$IBJ|&+_;|V~}@ivjg(Sq!irM4Bf==j{slc_OPXz(8a z7s@Z5N!fGnO*{FustWbn5jRuILYl9ttFH{Z-wjeQR%L)S%3=_^M)Fdc+3U~vvWV2} zqn>{X;>1h0xtf!x2R4*}BG3;jNS>(PzLl?q=9?#bK(kijAk1?o%H<}0R$#915#$;F zooz%)g~yD&7$OX|atjb&&h)&{P=|4EC+?+gP6uaTLw@TvcD)bz3e}8Hy!W^0?=oR`k?TxlZoSowSmAb7d!!Jeu+x8xd8;YQ$PkZ;2rd) zEJok}SEmh3#g|`AsJr@FPHq|yY?J6}=rJ0-E8MNHYq&cv4M3f;0$Kea2t3?~FmV3& zX4~zErtQEju3w$Z<5PDhAg@>guv5>g`G&#)boV7hmL?05QJLsO-coQKMZMF{9A!xz ziR2>$pp1s`o3&AW-Pq&HJdrREmt|q+=@9p{G|_4)Np6nC>#pLMD-jDYDuQGH4T8Hm z>Od}GhlA{l1qP>L_M9HDpkOAr>DK)@-0Oii1*S%Dr@Q8>@N2SFj=D&Eq8Go$4TdDc^PHlK0 z6uxp>PSJYBL%IJIP_a&+_eHb-dVj4BQlf9<_?GX=f;5?gtn{8l}=xRdPf#xf{ z+>!pd#wyJpj4QLn__i3WgplV2Z#FOMVz>P=KP;0yDZlvr5ky&cy;{2kmVZUjcC3)2 z!^odozdpvSVA74R_3P=|?#F5KfT^P@)d_XvF_vkl1IK%x9=^~q-E181|8fnds%gfo zQeesFee?5{86%hJ(sc2l0M>z?Mr2iiA=oEI8BAz4LSqVYz}Pc6W2Y5;$_?D1bY8mDx`{|?*4wmD) zjgmi=zWEBXg;{lSsOpGGD4>dMjehxF{Gb+OS8OtUm5;dnrVtV)HrxWfxdW<~`v+j^ z%5y~Z^P8)uEQebHr88jot-26$AB7)j^?N*u8<-G~I>BnSBE1#s* zZP!w_WZom=afg(A0JVuSO#<*phR_s%_%YIXzKBa?I!CafBGj5GS$^C)(pwT=sWO*u zJ1CIM6^`#{Pq92L^+BjGvS6jNw$jm+N1K3V# z2;CV4e2F(?_Z0>!%|O$ly|G2L>WQEa0*BjwZm-^hyhn*|u#qn2=i#knni5TKu{V*q zo~4O$KjN%ojGDILsi71&2)wKaSVf7d25=+UTl6J#@*T;#pLA{)Sv284l@v=}6&9O; zW=xL2(Q&;UHgUxrSzukH_0Xk!dy2Bjpnam;(Q)D6UZa zS=$|{2@25W>N>ai;4a84utLyfHLc?BMWhLu*H=7@JfHhfCi>-D1M%e}Q4+32L*@|{3as882s41|8S29Hm*)`FzzNXM>_o_lqPvy1lyqbuKdl(TG<^UIxa5bE}bUL31SwoNr>ANh8-_WBqkFy3BK6OG~g8?O!M!*l@M9Ge47oY)4w z-j=ll!0xarzB4QP1k0Sj07oGNJh1|RTfY#vr^kJF_GT^j37S2sf zvcjQSbG+xmcHvz>w!DmHbIdrDv(p1_2hg1dH6CGzoy-7Ib`jJ?-wwBXOUoZe^V4Nk z6N6S&)9hSuwaWd$cg3vLxqw2vgE*Di`>90OEIypA`l-&HWfRzTxK)PAaKHq#Q30n$ ztV7Q1(evF0sOe9*qM60)E6gc9Emg`ykO{b}N^xftmh6*)q;w~gtB!j&g+$oGK)rNT zz&kD1z4{8h75As1sZhcw;TIDmk~=<^ofxEHH39&#@!^cL*n9B&f&wdn@e|GR%}Yk~ z35Q720;EZfm`Wf>ojiY-sB*+eSV^9l7C;$;(#1f_R;#g;c)M5|dgIh4KsA_Vq8Wm@ zw5}b1OtJ1l6JG40&E(+R+|8zH!zrL4*9PbnkALRcdGWBf>#iLS`Ig&gFsL4`bO<#i zzesxTSo{{vaXp~H7N)d}2DB||2Lf)`IOxeXQ=aFZac2ygY?qlU@Uu}h)#MLFLmyE9 zOt9;^)H(C$7`^59+wD&xiUx5L@IxO5*#h2(a7Jhf`1(^HA}Mk5p(76=+;C9COYbEb z)XMq7HAvywY4$z#R#KbBh}QHb_AqXD`H+{iO;+MyONKdY8iv)Q$$22xG`rVWwtDSP-z%&%JE!+G zQKfF^yq=H=RO%<^Lq`V`X@hlVi+{Gj5!fe_d%KChDD_qPOB^%a%;3rS@ltZVtBUXD63K9UZM;@?%Q17C$)GvdWYlTqbv3BC| z?={c`mQ1+lKym?cW&M?d{A(9JV`Hh$pesM;ow3ZtNSnHKtD%Nvh-D8500t+t8#I$_ z-3|)!LQAY=jDRNIeVq@p(TL3a&g6RmencS?{HJ=}(zFXihq(QgiMs&m;AkIR+a=)# ztP*uHn_6ld)7|?Uj2=XygcgK+?}t^A6+mltO%A@n9jjdyQdU85cH= zB@j+)Z88M64J>r%q~98++>S%l0l#p#E2uX7x(mwJ{ye~MrpYg70mLuwQ$!$^bbOk4 z3h1%Z;Xqz!{gS$oREI7%z_MXbqSjNV^_IZl)YD2myg^72R%Dyk*u+Q+-Ox;+C;j(5 zZpRO?ZuqKhUjDk}2%TQD9NfNLCPz1X6C_W#_XGtRxE%apYW2i*FXZDJ;H&RM?k5u#T(8t`{v~q#`S_P_ zrtp8J#hEkt`K!aq(gOP(pbJ+4>BVfG5Rs%e^=G5;|A^eoUG9%I{_VzVtg&fG2P|$< zqd5tz4296zbTIf}pdP6mfZlrd#j2LEsOY#SXqu&Qu#OF3&8??5V$IBl4*b37VNe_f zc}0ys$gO#&eOIyUAkT<9xES_kA$|)8Bc_n6O!sF%kA@Yod2QDBu6Bh&<77}18%a}U%Z1mL^iV-FY?4pN})Ib%h3 z(hzUGhqzEgzo%yQ@Dp@fw&9la^}9$y87aTq#8drVTit6!6#O?=z2-md-vNJ{!>q~# zvE(-J;waEHgC|DD;I1bhFU@!W^%0JwBEGM%)`W-!1Va{N*9m>Hq4B2ODDtCjlhD+c zTb?2gxnpj|AJIioaF^p9{6q@e;&Iw~mWRF#Xp|kO>O|;PPgM^VZw8?+DaZ-1l@AQC zS?oQtRwDFY&6mUL8&(06@|;}|%2Kn$L4avli>sn;`khqRTeGU){g>N`7f4;HvVl6e z5SkJDVB%EPBSyv8MSv6MzC{SQ=BSfdj4GUK{zF?7>3e$Oolp#e;Gg;!W%-`Y6-u&I zuSv{v@)nue%uoNb0Kvx4wF|;WB}GdU_o@>KX803^rr;^KMs1a223{kVd^m4q89_+a zgEgpBL2*ks^NPp8)&eN}63SSkKSIgYJgnbU;#uC(?V_@%t_b~-^1x2*1`43_<$2R; zp&7$C&iYxl)&K5bRmF19a6v<<;ZL(=)-vtD6?T2F{cO7A4Lv71>Bo?S^CGQn6|NAm z48RA>L6HD&hs4A|AbUwewin?*wga9T>OhH@&rXhjSPy}IvXreXA^W$0lP%iceJ!zV zuF6s!CTrPa=Gp+)L+CIa++%h+Dj$Kcav2#p4M2%giqo7&Jr9_$X+#JSjyXCo*rb5c zbLPW}wU{d0p$WW##n;94Y4~g3zPxheUd_{|&>&`Ts}JGo43euMLXF6gN#ILcxYvj+ z#0uFu;uOMZ%MZ^?`^KCQ)Ts(AOVucLcN2RN`SI|Xn~K?Ph^bWys5 z{kPQDURUk$b6IykUo}NN0EpFW5?Tdqz!A6wA~__v3%Jv#fW|&sy|P$ca_w#9%Jg3d znB>}#Hv4=-2lWUBgR@83Q%JV18p)&>INlqWrAzJTsuVy8h0x&JEC7BrEZ$nR0^t41 zENZ>+jA`Sw5tx3lcGPBROwyqjM{`NV05VZ&931L$U__&!oI*a%8GfM(dw^FT>XZ+N z^=^7alXJfTecFU`#m5;M5xa`!MX&sHQwgvHI#>2={0}V9*qAM}5|6Lcl|ZB7Rz_R1 z${HvYeWF>Ivw)Rgrq$%ZFujI|0aObk2_LpO+3N^EHHSuP?w_7P?07syI{8Eb+<#F7 zHKkJe92D0dkuDH!d&Fh#G?69xb=(Ow4TcH6f-F3gk7E6L446dw@YmJ>cP)XGA{g6N z@2T+f)*+cT5yQ_q%x5{y4%}!*g#7-a_3s~SE`}S5K6AW`fjJM)0UnN2NViat5r7Ic z*}w1uNpg`H)@8sxWM=?smu{;9W&Trk z=HT<=x6}b6TRQ&+=-j|tj#eS(_ycXKj}Md9VkUaHelh$707CI6>l>>8WxVl6krIH| z8eoHcgJ!`@H8z;7$+wn;@HAz_%RBdAlhksS1t_!&pp0kG)M`4oDUGp?!f!k8F&C}? zMfwRI)m^Fwi$rAdPH?ZoQ!@TQtJFrK3K=^*idI!ki;sZG*l#ci18TP7fbn zggeV*{`kXwajaMaE**?&VFdPei~YioA;*ui#CV90fRj(LX)G1fHT)c+t4RbgdHC`a zd&Qj#?|luHU*4@XN5gnBzJ~n^t2tKxt#)YaJIf_$(`^&cu6WVs9yN`oEzzWiQwq0Q zYG#MQ_i(sNg@at#`bXGqjiG}jA;_tu5h8K0SX@XHv(qUQ-PMF={Uw)>RvV z0k7zj3N)V%C)~v?{*{8ljT0qmc_5ac)4QG^vHMGn)%MbH$C?-Cdd#C2=Jek~*k?d| zZffV0I&+`8T;TAPm7?n@YZAk~N4k{}fd;_{p1mB~Q^$U%9R<4g0Gh36dNCK@TrIL< zi)QOROH(Ro^;dXASFZ(&_?7Gm;pEWG^;(-$h`AILxdeovCJi&!@It%5VCpz3XdfN4 zkXcf$`403}bP)S6F6G@c>?qM0NeC zAVBGP5^tJM$=(wTSwMu{D+f$3MqiCrFnD)q&iKih`M%d00NHzx{VKnFqtjur*x@7a zQh!K?#J5IgF2M~28G+B`m2Ox-L&Y?oZ1cro9%#huw$XBGrWHSPI1XHVf0(?X4%aZE z9?YewoDN9i{GO)Ih-`pEs$C{;UW$M2E|{-qP^~W? z6l7I_{N7Bi2L)3XHxGJ~5j*{H6o~DQx`Ds{1=hol8r9eGUb~6am$N>Fu8(;OwBDVH z0ks`1p-OT(2mKuREnOp95ygJ?vv2P0bl=hd)X$)%4057e8H5>P9**FJUXwrw+TEI; zz`R(vcFX|j)di5B-_c;*+aL@1(-K_5z{ovP{j@r@cOI(f8*?c~X(dsfhbMgjf_>f@Z zt^^xHQ**!jDx%BcVuKk_+dB}VtG7Atw~DAHtD@{&pmP^NzbC-xlJul7{CT;4?-C*g zqA*)#=O#`58!2EHx|w3rWP6hj;Ay{N!b##PHuNArfK=z~gr9Ekq4`Q>;o;zwObL{-X+*xefQU`tB9JBX1AM;X~@SD8T#1h>R3>~-bwkvK2 z_!IA>k7s~y^!B9i&T&C1 zC2N>cSLSR4#f?&k+>{yI=lyWqxBcCpC6MLj^5Q%q$18I$#45=Z@_1bYe(I402zgS%U-Sf{W0avK z=P42rz^r*>0C;GOa{QTh4CF$fAMJsrs(q%+bD%+k2p!^svC0ELcYX{Bl+1ST<~jW` zbR1?`KSY@+7~x{R^5l{X7=I8~glKdl=yt%>5;=Z8T2piP^@|g+52&|zU_Zc^reV4a z>mg#=0wELs|0|_%JoVPvE;yJ_a99Rz@kU)^Dh<0vztwWk?BU{t9x=jnEFoWk3e^}# zynK^kt2&UiTw~Omv&%F*jPy(~TaP}aQ%&;kN8Cdg3sTh6L@ez^sJu8^8~`$7M2$=} z1Gyl?v~@o_-&gP)+UWvlf~Vl?X8|;?XaJbf|6}aEh z^}L?X=XEt#lOB-1mxWm|N&2DtbuAEzAM#$3B@ZR_F9!?nAXB#AN?e_Yv=r`^L=Z@W;<;L4@eHo=uaCTnDP;9^s(~Q0oVu2bTfV$}KC* zoE?=%Ivo8`iAbSZ%rLZyieOzF*8GJq2AeCn$Zkja^8%y+t04xv{4Pm zV-k-SnzwZ_kr>NsL*MBc^7?Axn9Q*4lVMt(1c~W=U_a{o9&7uB{!sU=@cV5zR^Vip z9rZeJh6&M3-kax&r~NkyY4G*H@IpzHrP#=qy5--eX0NSL#y*5=6nKe#wyG`ugZe0SGp+xZV)qeS$T)au^U`7_LNgrQU=?>gA5`L`~FQ z(!DbeoY7fSUg}jL83|r`6iFneYCczZ+Jc?Nh>@BCA5B|)X?w#FF^Bu6aGM^-0*i`$ zMq{*Zk`9$(&E}_UIB87dKlge`)AxdyX1wjVtdD6Pw zr8iBkR-EAn|Cb5m)L2#t^Mc$6Xls+RbMX%z=dVm0bHebQ?r{No<&!U(?t}x<{wdEa zvyFvEEs48TIvN%+wbUVMghQ~~olUg>z@@*hup$CH+RZ3*`x}QUA zE7@@~;VDacG{Y#M8ZFwffe;((Qbj09yOBcQ zF8LdNn1Sf~5z&Hc#^OmQ1sb|9u znW_r9tC~Zn<8MIQIY7tjnWk-96ptBlo`>oT(GS^m7&K{qTCY;I!rtwLy1N=)TMLcIQwr< z&m>u>G7_75>HP(y8i&Ez>mKO(3!kaSa|Un0`<3)V^c~@-%x}j&eb_-lKwxETI=UPozaRhSF2_MucTy`rnTp=RH6-asHatVUnR z-Re~hTIfTogR4v7pT43DlrWeBS@Nr9Vp%Luhv%g@UA%!9Nb4<8zXef{L^~rz(X@$H z;E5bXXY}m^(NG6{koi82eUSMH%MrT7lBfK{UuXsrVF~3xv!K_7tEzgwNE%RxNUor%0Q&*mlx)CBv3bBg0)+jdMA;w(7tb9aiC}z(z0SD9M*~q|f>} zc3S+)gr7w2hcZxaqYl$!rS_qLTcR0tY84{YJPwiZ@eQk%AxD-XUd)8dys0-Fzk5FYpI=| zchYjA1dFbO9|&z13Nx-v%t9PWw>62?*%ylth3BOHwydxbggI7N1x5}jJsScc#9StT`^`P0|46T1e>2J<2LRe+3am2zGPrw5=9}%Rc~! z*S`G&*pBHzaE;Av ztdVhY1b(F7!@_w_nb-NyYoz#$PFzK2pWDj$)gR(m5zV8iD=IVIqAz>Op-BgYhY90< zy1dv>)SmL8Yr0yRj+_fO?gji{m<77V>VPwEd7ME#14{A%XEx2i2n7yI^;*Enfy9v^ z?Yhn^6U;49v&p(Re*5#2Vg%{lXNi|xfxS(b)=-;?RW@5G5hzf&e5fj#=lj`JeK$x( zbhCe=u-oBeMm7n`D^CP4dl4deAo?G>`~-fz&SBjy0<3KW?%S zXy}+eV-C95T5`~bCL;Uj8DzTl?9gT z{u1H#HsESAx5PS4AS)Rt>lOC^rL1;04q47XU!eQW0AeA30Is2i$6yf!M?&q7!hVoq zt_mP~q`a;qf}tiM+5TE(oE7Myap0!(phovXGf#XEzvyo`IZO69{d7f)&jxv!2^7b14}5LfPd8>SMJzel;>oR|8*j^Aa6w& zW)~}W#G)U5@0KUt#jcGw;f*QisiP*`CuqX?#aAkm@vbcj+!OG(cm+9*)=qdz^MF&Q zAp$d;2!{}!_B~bRYbY8+CG!+}k;2+a9uQh2{sLC1se&qSnF^;vCoi#t(3DTA*O!#jR=&(X4DN>#&5KRXY zGeM}`dts5>x9Ks^!vl-+CtU9lwL`91;UMGlg57}0f!rDQ*uNGqxpdJ)(5d#ns^E=<(w zkTK>s_YOMSYTAf63TN7?;md@Dc&%l2Kfi6kHAo)v^2(cjiIw>iJ|=UZ-MELD0AOUM z=H(CZz+DT#n-t6hp90h-p%5sXi8@{U!LpY^$IRxvY%ncwChbtLIrSb1?v`X91}bVe zp5-V&`kW! zUQMkCWqe-Mt?xi$`TG-)TzU~G^e}G*yGSB7^JY&ms@DVZpkIVU!1Sne-PtP}Dx+M* zo-Vumz6Rp62>1@uq8OQNJO=pFFUau^-vJ2Q9r^}I5>4%Iy~TvZ;Oxmvdf=20D{7tC;>^I0L$|XSps3W`9Q<+y zyoc9=b;gMvUP8Dk0z~EDpMHuBYwX%HL}`SaF^dGRUI&t&kJ5T=GGSHXUndfmbMbPp zmr;ut&2n4gCH-v?dvYMhpJF&2v%r#V1mcWtL^xrge6MtL} zw>UE&ibLotlA~O>Zqgty+JCExBY!|AP<~MyG#}$}cY=4MAnEzrjP9&+0QmJ^>g;6o zvC&x6FCpG@jynlrxgN{FKp>Q3b|~k4S@j7W_^%7w2q`X@mgL=)`^PF!lv%s!f2P(F z`r;%bDiI}eVdbgwPZOI;zfwpb6uL*0FRfz^GhvWJd`rtjGttm(*jKw|(Y!3p=yPWdptP73 z*SaO*fkVl&x@`^$|DS+F0m=)g=DWENJ8)HLVm`1u0nHV{|2J8i4+4}E_zQYTUDim3 zd+L>;NP0{;iSbQFpD)v;4;sAZmpUQX=Z-f5Cif6IVfcn;Wjoz!xoIW4>&UtLfs24v zwd(rF{y_Req1!9a=!;448Be$n46{076%%&nCp?wSBq=y`Wef)c_FdlV80u%}PwKlcA3bQL(*w)m z@bLeEQ4n$wEb&hAjR?5DEj1x+&oBJ=O|VdOEnQhpZ6X>lvtgXUI0JwkGTyXRbF8Y@ z$plno#^XpHZK22#K*r741@Nb3R0jYX{{qwjSZ5ll(;M%XMS2T>pg%p^#Sc8EJ;iQ{ z0tW%=)5&NDNnl=FjX$BKzFCO#G50Y3y#Z_Ae|^YtD4IV)&sXyo)fo~Y5}`pNZN8~0T-c27j?+ud4Qsjs}__YE*d;M_M-MdIF zH1p2ouesvd^V=M!!TShS%ai+_|7|pdXF^nn$Hiq=_kDg@RXST_=Qk~4uWp8sGZ zgzvRMlc=SE!`}WvQ_$L5ZE^OViN&s)^z8z^$te|oxL9jxZ7_aRaI`U|-b3hO;UxD` zZ6^Nf*GI4hmDfRSnX$+Jj2Q7e#z=vgWkUiirEt;sO0T2hFoyEqDJtKnf38DS>kD=k z`Oi6hQ%VeNe6V%b)h3fd!bA;jfO2_&=Td%uu?66Haz9s-;?w7?_XnQrRxW1kX+*<) z-oi;>H>l>gh^)UD=d}}_3m{ZHo-d{$C8^F9DkI z&%EsQKytC@B(&4{aA@=W`o70m5Gm%rO+#DRaSXDbe%pMf@-N*W3)}A{4n<-Bv>Kq~ z*|L7Ni2FB|Rjm;&=Ssl1^`j$OsiE*YUB~Z2K`W{3mw3w@c?^Iqz2IR?Qu~(WoXrX} zmn1F?`k~?{iCb?neBaGIvIY|tpvmEMBfpO$p_1FC$S&dO+(DbzXV|kZj<`Zqf>{U-ltj_!A+GKS; zqzBFqK2=kEV1EDv^LwRRj5rDJ%ZB-}5g^drC=!RwxI*($oP`c_08@{7z= zH$bZG4acUDOGRh?Kei$tQbbKpZErEKb)yAiO`ecZb{mb-KsUS@;Y`Nei7VK?Y3;AHAXt6BjL^N-RZ25We2|NI`{w zH<-ROV&_tXEe^f%%a7~7otH~43uLDsb0(xTzzZCfuJ{G|yRL@2hAQ%)(k zfGEuQ>P>3kao8)rbI1xwY~ zeRCTqzBMadKQTs>dR|H$dA4NX1qcs8On0%?#$ePe=fBX%c_7jW zD2{Ulfw$WW9zGgq#`xnGTEIM=`a^FJLJbhHj?k|q=tH6kSapIr>b-HG=Bu%lr-`l8n82Y0P<@>Se+&Bgz-6zo1!UKcXhCHbuc5-} z5S}u;SS{;q;m~`q|I!lDZ^CKO_`;IHeJw7oE&i^PwQeR?0?fW-v9tWMh=<&<7e%)= zKb}0ST%Sml!F(6!Vz63Q0Q@qti~%#jFNjO@2Rs_JlDx73<|rG5kmClmpg2J<3&a+U zb8~2-0^V4^+RU;6takR@hZU>?Rl8RLXYjM$#K!^R;fTtIl6hwFwC?sim>0!{C~T6- zW)sQcPgj6X;vYYa8W680H5Sj;7nW|6JSeKdNU#I7H9z)q5n=R*HpyF%zggg9>RW;6 z`vYh}QlBrvsR9WPho%1GILOMZhiVDQ(>lp(CaDP6!3VYs0HzG0q0`RW{j?`N#U)^KTEaYq^tLZP(GC86{5w3)JAgTJ!2QJ62 z{IoC3{HDip+o0asJ_$w}3j+w2|LIlt@`T-6(VBq}E7`#wzz6Slk$rg=RbZbx>& z`PT>5c|#ejJ(ticun{yE*>XH^0#^^CSsamXoimJBGsn`Tko7)@QaHwdDg-uSfBPjQ zIqck!zLs5T0d`PCilTDi5@fb1X;`N@yQ5UB`1g#aap1C3w#0PT{U zy@ZQeOMf7%r6<~ctac}c_~Gq68t9pCu4HKOc8-YR5S^PKkEFPoJql2j{I#Ge+qar) zDNArUhis~B0QWHvBE?Q_j41_P?R>W~@@)J8+n$5dUr7hpW8#v^#hjgnZ+-R~5PZfE zP#h4rdP)FP0BB~8Bz2kYPoHbTCwb0f3crVz=A6hFQ2Q? z(M>(EfdzCkI{-?ZyyRpUyYoYx4u5o6Nse04J;G9uBXxoqZkaL0;(%HsW8XVqY%}t@ z0*UI9UaKwNRSsMR#?}o;fg)~`Bmo-&4b-IgmABY6>4lo=2yOUu-(DCP?WnD+emp@7 z27kQl7HkdU`?{t?yh_czF@85j15P`e#gRh<&Duk)A}_*nLvmgCatHy9dG{Km*)~St zK{U(Ie7#0=?Gzf>F|U$~JmWV7S}>-KOoZttB(|ajOZ}%yVaY2!NB|&k!z)NH;jAZc zGfKd+kHTAje@DU>HK2XV4`QHdREI$p;%rOj)Zx4K0_@<446_>Q@<%l%-4oO`*q7s> zy?nFEB58U$rXk^P+G}`#2uEn`!a-A-#kDqR9c8kFsf5ci5rxoF9jy}I77iBVpr=G0 zL z0_V_lSXgSl$xAF>Ak-2F(gA?0%@^8rWZn6KnEJQgDn7JN1kZ@Xsi7am&k;S^%XPOf z8@}B-cIJ1;`(?E4G9Rn}elPlD7yb2bhzjkF089J|AT|t$K{tO3UfTX3tm07=?^NO7 zBq%ln;p;H>R!_f{wh#~J8lHyE0e8L0$*bwYA*ue-7RdlPR`3h`0$n-#WCn;hUe^RI z0wGShzi-5A;^pXU|13NcU*}!p0D8Zie5<&ik_YG@jKHEE_J7uUcs{jFT?WZe+Y;wR zD%=OFoX3!RS1J%z{T*TMH*`0T0c*3h9lv$%vLO}jiA;dm3p?gr|DIxzSZ7(ksz+_c zIlwy;cXF7OznD(CL25`W0!zprsH1lXxosiI^C`03hg1(tnzGX9OL;QvM<^WgY6q7O z#n}f5X`>Iku%{>xJr2qh3q`L?$aejGB;Z>igB{diM8_b|bl!(cffuM3WNZ;tC(hoU zz7f8lh$#4$jS5o5Fq~*FGNYn%SnIlEW{19ZzjmnxzwrK9%AHJedwz^RjeuV)MGwMwMgYP(8n_(Tg-SnS{>R5%>2;Mdq!J zb+_@*S*N`xIrL;REMx5uU4-ij(o07yk|u2GacW6%GBJch8SvGFgjf3?Kt~W?7H8o5 zk<3_EsSPH4(VKwoTRs4dl)<8DJJ>FYrC~W|cewhDyDK2tPY)4PIWTs?0HqMnXgiKK z?j>|HY$~}p2Nf`UtS_GZH*XcYpbdJ0(dKX|)L!d_M*Dbe&09pz;JH0LmR6G_*3Q#0 zFS9aEJ1?WGqdCy0Y>wK)&!DX()7)$ z|C`YZr@%i!%U(ALJ`(iz)qIr^HyPMb`-SnQ$<Qode&=}!VhyZWaA@WfV4GJiNzCshhkzwZZtxH4PE z93P=?(*)dr#m8DlDSXt2QMj^%)>SbC5cTX_AX@p;Ncm@~T+4%4*b5n~KBsy*Tdps} z;)g2Pkw#+nWyhXgT3KkcPJ`$!wm3%fAbD6FGQePS6|w1-Y&4YUrIOCsqzX@Ge!RP_ za){YOF(1C|yVzDzO%_0upIR(HyEOevZ)F-)8%IF8J{1C!rOO#u-O>6o^MO|~=v8L(Ou^PR>!z%Lvvc@zlx84zXw#F1-1(3M zhY+}wbXOYy9ULYdfV3yG{W*uKOx^e_q@<5eo{5$-?`M}uSrotRz~6l`Wyd6 zn1~m@r~hcA?{?wosFLtNF-I^4=1;s^v2^hxOvOebvGr7@>lh)+(tSIUf#>Oia7_Rw zum>@L+>6kfq|^5V;H!4B>Ke;Y{U0NcNbc-70u0ZW&mN z&s^17xQ=M>kHH4-Zt2z@z5 z2857%k}CWz$K3SXGb9kN935EBLq-VM-Hm1MYCPV?hKJ8rxgoX;Qj($4E*oEhLLBsi zucJ<}Lg-T9nZsa*h*I8x-tnA!;~^h_{ZNd2H^7$iXysy`!Nkj7Nzf-3iegEYxhXpQ z&WEBLPausWs&B3yU#o-na9B933l-h#W8O|PZw*(>SG!jiosrJ&6koLi7mY>mUXNgw z0fE{9A!N-pHR)p&jwZ631o;;(zN+P?C{RF!b36>*D$r+$f@?Y(U zN6ycH-+c|@i|2j=IE1q0sa?OXv&N_EXEcxWeU@4I+AS9fvay#+8o@_T6be~_CX-D? zp$k5ZJu8iA6!kP>Rz#)y2Y493+{zQ>>YhmXBOP@oW2AF*)nM{k&)c}9?Ox&AAK_{E zkBvQ%(51Ollq31^g!;bYsyCVVIn^Z$<9%~7Rx^!9l?4GJ~({tTWC2?;Me14Eu5V02ik+73s*NClaG*iBH-$uIt^RgGmWS+f7c0b$B;9+Y+L`&7w9RZrCQdgo!I)f zj4oJm3>f$LC8%dqG3KJA)bI)^gnsvEPBW0J8>ID9a!5&-#89#vK6B?$vavW4OGKW3Z5#FI^unQmcRttH-}t+c zHU1u|`#cn_mOMAnWs?3_y$&lw>1CrOey{Jc!X7&fOFhbkv98>#28otAKy8I*e^5MJ z{6&#?&D(R(5--d+yRuMH|1}+Q z>a6AE?e>eK$f8J_Q}j-xA;(mTz-;yS5AGj+|g6QPxU*1beVGFbX@HROPy!MWB8n-l={s* zKfpQdxjs{Ordcpau%>eI>8dw@rd?s6#5pYyzGu6Lem!*u->n zmLWg0Y_}6DFqV5;_7)hMn(f@squJl{q)TU{dhl#cjAdB!Z8(Vfr~E0@)x6XjZ539ERUB z1gB|5Q<=0P;@K4j;f36LNOh{j`DbHlBsmK(vb6Aeah{NvC4_+#|-j16y@a^ z0g>^6M4}RENR=Owv#S^5l@oau=C`vQWPKik4p@nhH-x9bC{3zLyS9?`Xk!!ys1N*o zjEtW!ySxb@6C2?|RyokuC&>Eh)vGb>w#)kJ_gLO;hEql=BBCcAQbem?qk`HL)AIeY zihqxH^n(JtI-Ox?0X9=5FfF8Q5UM%__?2+4;q9&*n+5qX(5~-{1+isW>YjWSn0_3%+N`Z+!_TlYHpW$7{8XQ!jDV4{s$<$?vJ%Mo(s*>ssEk^YLKTy4 zs_|a_13jP@u!JjN5QKDRv{#1J;I+3}Y(y=rq1LZpPU`0aPboGd+BVEfI_)R!`xvz| znPvkIZmdeeo^)fyagW;o0s2)?5c}fX*`^1V zw&BVsxP{?fP)%ZjmQ|Eexpp(cOsLN;$?D?6tR-3lv}lgw0Bm>}6XfVX`7PH9vC zo9XlpeiOX@vnDyYXW5i#+9Xsz6Sl#kU%Pvga7K*g+gEt4?HjiEZ7s}%^+Dx}Vc=W@ z8ld#dTRIyYWQu+uF}wWS(#B9!e zad+}t{xR=i=Qk_%Qm*eo`Xdamx{59=An;P7UNvu|c6&fX8G!VUo{rEU5cp9YW)!mP zO{7jJ(6?Us`RT7Zwx`^7JtShA(E5_Mwys5P(XSuLw^FSn7Rvz({rH>xIqp`xIJ5oC z5cPP+sp*B8L7Q+fM_m|BS?m>MQ6LD;hJ8>AzeM35@3j0-=>E?LWX{w&I`d9HAyFkc zjCNe7yTCEBJK6T}>Az2H1=C24EjocMO4#Yjv}OH~-@oFLfBy>BRgW)iY-M>d)J!Q( z@e085!;QUfUikPhGjNZ78?AkF5f1jQu1lMN)9nKmB88_=rg;~8Fuxg3`-Q|qVh*Y> zq}Ikh4+NrBD_I~AHq!+T{hQt8HsqHQu^GlqeIOz{+njax`vovvO|4V*lZI&N0G&M^ zy^4K{lRo-xAnEyVM%R~J$s>oXjVyS7lkd$9I1J*{N=#%E$4wi16?3kM}F+})1z> z96nL!p`-5Yf6-NMdTJ_U+;+HLf;Tsz0sAo+Ge$vJi#WD@L+u&ysc~Joc9n2=8=%af zrvQi=2mQ6cQ?Wi#L*T6^1?CoY?V!lBXV0o_c?0f3*opMMrsGChWr~D86`+PN^r+3U z(0ZHn(LKYY#kPHBa%Q9{KJ?+a{Y%|cDGu}Z+ER6-&QU+gQ=xp_Bq01@`v>UxjB|bm z;J~M`QL%39yDx`|t=&nRY>3PEfG~2fr7B#!J7)V0*mAPmT|=(e`5oLen~MVbg%lD9 z!80_3Ykz&b=)uMvieMw6^vj3Qn2)s8QqNWz7bSE^yXpa`JZv86u@;{jDN?vCc7)uk zI0+X*qjTeQ;S&CXICYUAy{^Pr5;344O5P39Q{%bwg}iRpO3Xt59j)2E`52lJR zm^2s4X*v9QTt_Rd2b>F@2UEJe*F)u8Yr8yyY%)Q(G{J)0j3tQ8JxlhoGYBRVy@Zq4 zAJ#1lG5K~fmG*Uv1$jyWP2e?~WuWky?GV{>PSkcxwXW#e>=7PaH^ck{ab{wJXGwm* z87w8QZk{BqV$>*fT8^NN>$X6wqg0EkAigNO$#0V4lmVwalgZxI1f2PNz;z>LKaz4$ zfXIR~q-E6R51QOOHb#;S3a4y_xiq( zk=!S$l6(M)$b)py4q_!b`q|8yJn~g&=&6M(n2984PlXvixqxz4c6r9J8!EBaB|tMt z8>^lXcQ#Z1Q9fAAM@2*w8F8519;^=Kc{pQOUQ;8$l@GXH6!7CEH6Tg*BJO4jDGB~g zF~wUg%l(wLjXj;R!TjY5v!f?CIIi-XJ*x-dtXPxQW^l&m+>9(y!Q<7p!IE*fg!03 z%97LysVXnGWZ=8%t?!?BBigHhwgAI?Y$GI}*r^z=EL-2u;OWKCV+SV0Ze+vstp6o^ z4HZ!V+7b(Bfozg$w|xS;f=OFH$>^6D%#nS6pxH2a8$gE z$c)96FD&~62Om^)UQYMDmH$x4ad!1QQa;IdC+8?v=_hsfR&TRZ({A`1!pRB6;xD_J zwlkZ172Q9oCd~HThf=g+Yz+LGNJn>i0ooTz+dEQAr^lz=oNq+wCo3y!BcMR2mVVMj zcx}T_)1ijSC1Sr$8gQC0u&p&Qa@7ZF;7Jg9WW!nWSv15jWenOCI_V1Mi=JbG^nSyr zHJ@~omg?3p{i?k8e?%SV8-aaM!4B83TNTN3-&%!wt?8fnx zT#MPi8(h79fq?Awfk!dt^Mj~cmhDsr8@^`O(H@V(`L5tX#m9d~Cqps{Sy~jJ7UFz| zR^xC>47IC(b{>YZ?X^&-aDcws#QO`C42p|D zGjJ;mwr#e0>^RwysG$O04~j? z8kp4twKPePHq+eyasRoK)=02`7hR}0p@Lm>{e&;2-M6m{Kx%gI=L~*X)tMcD*|_hp z&G)kvHTE-Oi%jPQ&+gpv_wdND-!YFfk!eEY>6qc2835D0`l6$+_PFjVKIpb`<-?(! z`9YfeLPBcshc$fDuSC6{pf)@lmPCVw*rG}d!~F%YKB8}vbzBS;un0qA`E0TAD_w?d_^6>bxBv)q zzEIXa6LYRNjVUm3@CGxN7lvf2mF!~M@*z@A0e@jT$*0jEVe27A&w~PfhyjOAz{OOj zxbQT8crMjMyJsYt)kf_r4Mi~-we!mC{nZ{jFBhjUxBrpwWsQ{(sm`s}b@59FN z;%PJOF!lX88EHHklVG^L-?%oK?DXQoXfL#0ZacfX`{g?s{)}@T_ysvbdp9#o=Y9dl zWJkA%u`T39?qo*5acYa~?hrdj`KNi(Kugorc=l&gm-j=9qkzh~6rKk5c@D2xyQ0I~ zsiZp^h0Wuu0f5EbvJ`8gW8DEf10 z_MtMJ_cQpbeq#%YQYNmaIQ&|YOe%2ut_7{0ga4{ z^PuKogY<_BAHMhnG^rBZA5`8-Qre|ye#7fMha7q}mAHMj?(i-PJHeHHkF(V;fY5UJ z`t|x>>cy*da%bv#oK}4ewc{6tUj_${I;-=x&OyT~mDrQ`+7Sz&3Z*WG$ht1_E|p@8dJwN}o3v1Go6${|ClhvV52U7VI; z7TLyUXV!3%h)$9V0he7XfacEu^C~W3l`HCZsYG8p`~diqV`K2(n>nkZW+aNNFbv#( zKz3dRJyy;I{ZGD$n4KF~K)ty9zdYGMGv|fKwo^PdwW&N!P+-&Paxj5whUzmOHy~8 zYfB(%SRkvdcjz9Oiy=#oQ-S04i&?(&s?#Ekq5J20A-*yPFyAeKrd(e2EC~E; zbnaGdk$xq6SGRAk|F7+YbR7QUCQGF3i4CEk;yxHH5N5Vk7_L=^$(XT&I8~}zZBPT7 zG>ze-9(=5GJhhG<0*F+P3Cg|)Bu>0;`Q9D;+T~d+TH4|I5AtB1{eRW}4d;eQk>s&Q zI45&~he4o-U6N^gdiidaLg*?W!M*M88*>GGWlJ#hKJBcSGxR0#fD2^9`5-}D*R?Et zqd7veiYea81nYpZGV!7m2uRQu^KVr%;B$@9A8RaZhzexA?%35ER|A~3v9YF{J*$k( zP4Oy~6J5Do{(^dy_)C+YA;7Xi8v6=jx3AQ3yv|kG|+9lgvwetOucsT&D?i5b$#KXyXl{wXia?^wzrBrA+UVBqDG5X z$MXF7k2M*ej?OG9EgJPCeq*Lox1DQT0KXmPgZ!o`tLA^4_ZW8TR|P#wlC9i~zbHrP zktM?D=i6zuQU6ak-?h_FpLtbVZ8_#LWq{{*v(%ZNJGs{jRE3if=XD_~^IckU5c!ZS z7cLe_WHV80{NmN`1{W5}7z!!vaC?Ue^7{%Ako87}3;qItr-SGTn6tnAApTLiCQK9$ znJDs;I00ns;k30n&5-0;aEaA(afI^kxVeFfm z$wXyf+mcSKzPt=79XhIAV}%FuZ;8+MLM(dS*?H5_+Y;*jc|de^A+3nSMYOl9E<}z% zGYTO>xw)1ZBp(vZSVJ6uJyjSf9A?0wRi)vE}*BQpc2OCkEd_00YI zK5b6;NJd~f1$cTb7O}6FIPk^t*oz9_U$EG-Zlt{R+Bx0=$PSUU5V(0`++G)frN%MvcZ^HW%;mp+KEui?#jD*s9ucV5(9qB&`+6g}g}3~p=7OFbV*x3HfH|k*;%`1GQ0AJ` z^BKS1w{PEp@q!9~Kl`AU>x(cp)KD?;`|{-y8V(o*5$W1N(#>x`L=t(?Md^_S;M;ef z^Bnm%KDZqF34EJp`hGS7>V78>beUVuS*j+x2D)h40qF8%_u-MolYd)kYd`f|!BGiB zeN0@)eF8Nh1F~vUPER!J$V6x@J@j&xmvT&6lCCGJ^JPPuP!Hh!YCeFSUV#Cce2(4Z zM7qL1Db6IE8KYhHmDQ0qUHZ4AI8=LJcOhQj0gVjKt6|P759)Tsl{^zngf)I-Vmw|J zf)L@>F-nrE@^8JkOOg?&;sn)g2mPI81J%?!kMqF5kOwNMMH=MjwpNfnDll1Tu>KyVDl|eSWxlWHtR_ z!Pf5pk>fZv#q@41bV`4hUdXXG(AB+cY#f*S3@=5(S&2`hRcn^>rtY96-m*#Ieps^C z0`{K`m`XpSEU#gSl%w6G0}swNH>}0UQu<3~{_&z)f1}NXy@353=jS3sniw{s0g1I} zgBzl|53Vo7v_eo}idY#JJrguzV`EE!#X3EG829@1K956`Yjx)@Ebf`S8%@1N3RX9M^Z@}DPZ~IQh8;iRkiiMds@+D+l?)6x3+*?=15zQp-;wk?u1-! zt{by${VK5M$Wx@?UPdsHj6n0Ax{^?^i7B5|F-4lDZb2@1}Qa*tMZ>Z<;j_M#!*FWJ+f}R50-@Fz~0SRO*q&P zs7!rZPoCt${vP2ife&E|YwfI#tJ2bVSG`f_A)>&8yHBkhzVU|ZCoLpV@Ws~7?QIyC zxlv@A-bLNK771MFNLq>4AH@L->;R~=CQ3X!c3t@k{h&2)=c-H7|I6Jx0;{_DqJU50 z*7X4A{()2S+JG|RJk$4a$ji%XZ?A;*sL1m5>(|G|@Yjg9269-hI0_o=J6kUi{^}1E z>=&^KD}~&5hyS@T&X9qRE{p7dJl%w-*wSQ$%iScv&iA5ySdIgT#F;K$pRC=!Z(&A1ZLkhthH$ z;XXb(2L3h{EX>Ro0ZsgSz%jBB2}`6E<=BkA1Go@2n-vT*YtyH@s6^S(vCjQvoZ> z=61|GS(JqCS{Zb$4hm^VZZaBR1zTfgB%v$n@DX3opQxFu%xl=JGMH+J1Lm-M0r%Kw zUDQ=NdSUCBbjj@a_MKu`9nY%-^ z$Fjk(D+(a@DcIy1{HCqiApHA1J_R`0<^Bp^PuoQBRl0->9e$=s)L3p^4rnP-xnr}* zzCOWYlm2F(gzJeBB!Wb~TN+JaTy#H2do1E3{^18X6Wcbp>YU(nYWg?Umo$|#1|-ma zkkg4AOum($lWx)dE%pXlDf`Oc`2!CrxwQ&TWQ`zxGxmbj85&tc1(%M#7OD%4YN)~# zx=#Ys##lk3x_e9fNkw}iq3cXD@I&fg1#E;*+y^Q)c2%S}+VA*_hl}b$=evzVk%lsW z((*DF0mNr>Cenwdc3OJb}Bo?-U$Wb^ISg z>a^QJLJmd87aU0Vh=)NemayD64(VIet@-v@LkFL9F4lQ#B|~p7_u0M2JGjqa_A{qE zoHbUFM*lU?Fv`H2V60TH((elNe#V`GViy2#wiW8s0??loPSTwtwX+$f zZS|_3z?-BdBB@Dez1-nR+Dz!z9?>ObmpWH!*tQ2wENp%s!arFakN6mdOtFi+-twoJ z7D;nt9urA-H(1!f0z@<#Yx61o0iDskILDk~Gpejs;EDojAkz6Y`e!qi2S1v46yyd;X|| zqT-dWZ@;zl<;!sBLnk?uf9<%3*SoZkC?}|XUlDkx2taLnmc?X-8U837_HVK9ZHn;; zJYJvr*KYpW4W~MR;UvZd05^c2#p2-eEs+6zrJujQ0#28jZdmuJ?f6IhZi#1)VI7I& zCgi@=-^AC}*W)=>U}m1vk-Ku`N6+}AtNvU()>nxCO$D~kW1{y-f+Nfx7%eT5LA zrJ>dg8HL%@6mR{-TA*^vwEBkU1j9Kupr2M5iS&A$)rB^9wGCv8FTt2cco2R#3Cupb z>Qd?35ce`IS67xjmsS1rCKCZ=ja&hiVgPy{nGSVWgdjneocT5^nw}6oVAzqFh`b(3 z{;bS#o;V=^u=S1i^Vx8BBIR99{7v=+;r0mc+eg^rc`QXv>+yw=7YE}!)cm+K*}+)N z;^INZ-O2R`M$%{*!;9Mgwq9?&zzQTM=hiKzFzw1w;uWmScL&h;3V;orsI+3FAcgyI z0^#Ajrmga*kp)2EOIV=plZ7z)uHCsX{Ncz+#L%0W=<3)VG8;OWs!K%4TL9hODBv1p zS^~ak_#$rA7m%H-<;f4dyG1U}fnVTlxs8`G@{=kj-8>m2RF}VSMD*c@cyx_|xO?M#uoj0qv(um=;~#o3 z%dmW$GJgQnDCf24ybm`?g*KW%jE`dZ1EGKe8t4At>(3rz0z4_U{D-r9^SJ_cfK1@l?RX%)iIbIc6$SqO`D7UFN^*m++G%8=OagL04D%5U4}KHY0*&`xIR^qIMoz zieVj7T@iQpH{+J1Q!sh#ml7hWusN~Tq z)i^byqYwJ1dnXHQXKzBKT-Xi_8bW=#gaOS+1*bV=7frv5*QEv6%q$wGJ=G#dI!EB%>JOH#)4+dCGA^H_GE&5^o zrMs$k(RG5hkO#0HJD=k$EERAh$t|kq-y$~YI?Stm<81JVQ1=;#EyK-;!B$mZ5WvB3 ze>675vc6bWd=9S;_?IqGa>g(&b+t*7u z_TtEjkyBYDQO1OMFSd(5HaDWOHONfE4jbQm!21#`HpeFfLZCe(((K{2MZ?gI z?XVW*P8aP)$gS)i<9~LOivcO`*%t-^bRSaPvJ9UbaXi*2@Uq}%?EgWZ3ZrdJH}Xli znO)!73v(T~2%V7_wCu?H1_q#Ge#4^}h{>xjKylH&a-5|1k(R{S{E=vr<0noC8307U zy7Doox?J$oA;G&?xNJwAxget7Ay(CA+TG*OpvU@TE%DwN*hQC!4LnPF_d9xt1KQLZ zMdR%BmsT7$bnJKbCau`3pU33iYT`fIn0?lA!b~pM*E>=UZA35#bpO%S((!ks8|moo zrC2e3xUjQttppxt;0z86n^2krtWf<@I0yM0EvX2d)rap2O!d_Y|k)Z7K?6S zm2W^K;b24(hFHMBwwVH2GX8`Cbq8}3pw3A*?`k)+Vu$lE;sPn0nap6q%+t($w+Cxf z8-c4+z8(eqa7o%>V26~!aVDL^XY|UUs;RM~h0@gH zsQ4|=Br3$|KsO!_dAGqKN2~W_Rl=0}F6;$J>ID?0>W%k+K)}C$;gSkcU0AGsR}@Uw&Lfm!PVwl{YiqisuaE zHF~w{s90yq7oC%&jeM-ErP=KN7c4OHybIqYb?xPaS-kDIx()+nGoG{3@GZ0zV3>;I zqHW#R+JdGbt73qBHPASsIAmDu11WEvfXDI&^Dg1Vm#2$&8Y;I!2do2^iu$a(=y@)| z0%nD9=?Ckr0`x$~U?zwkRJ!}cYk#E)H^brM?SF0Q%H_*~3On#H!GiUQCj;MqW3mF9 z7s)`XikNWn!VvYY4oX;T`~&PF1XDB0d$^F<(C+872Yhs&)rn|#!hxA#Ggl6v7_jZO ztS&|_5?+md=+1fOzlyExiTDqDpX9)a_oOqPr2oUg%_P=A!`2=E1x|NZt5wpJcusWA!%xi!8#G}>Ajz=mg&>;c?;Ka}EC%5T+N$o)={ zB|W;a@GF3Ub99Bg0Z>ShT+tMjSjO7!Y(%)Ouvn$1wK_BHL^i_WI{W|a;R$u?UuAZKd%E z+2G4o-vWB0(Eo43>|8_APeQi@CAcSxS_$9$3>QEO9^F{K&06%e_qH@x|D5FK0K6nR z+W!Y-H7-QNcW%!sID|HIdtfK%PQ z-Q%2)A*I0(4N^+R3aL~MNu`pcIAkc9qKTrC;WSF5385k?M2M1^CY32FV?={8g^Cp6 zzxEk8p5OcZzt{DCFIPP|pR+%E-}}DTz1F%V`}Z{D<{;yd++)0RvyZyRR%*kBmJjbi zR6kLAv^Dp<%MS`94wry}Y=V=mLbMHT14jE6-Qw5dohvkEfK#^yDq^|U%YXU9Mr$pB zNmvwDjRS+A?JqEBtJ7O0B3g1R{&AZ2!P}!qG>7%2y);(kJOBIO;f7>xBv8$m{0EuU zEnHN;6T45P0+KU?)rd=0X-EXG&S9o<t+-l#5l zxg}8RsmQXER7Ig=x8cJ}|05a;9wCN0z8!3SftGI(GV>{U5<6-$_=;LT&M*LrwWqa- zd7od&;+jlSInnva-qex|C><)pr-XaOxC6HK)oAW)B>8By4Ed6}PW_k>vVV z!a{S)w@2N18_X+0*AUbWnO6oFaQa`k6<_BQK3_2|rKhdRz1B~md4Nm^I$+W6iaz@l zWUB9N8^ndL*5`TWC7FGSw#&G_&_?g>f=P~DdaoS zMR?VU{O!Uvu3IN?fJgb4fWrvyw9n@-QzgblPZuqVRP6mKg^t~;SFbwmSQm9eD&jH; zVp{rk@R19g(U1}q_R)|$7w53x8*K1wNy!*`Cp9Hyj;iXG-yQYl#an;4>W?w(IdaS6 z1*$V~VP&^Rq9%k)gA*E=u3Wk_2lS7nJ)lSGVv9DvTQ3h0o4(!a8x}?yr5v3Xk@4IG zRO#KMZ5(F)ScjRIuy65uY`Y+cKs%cHVlfG+qXjG z-L8Y98_dgP_J5+?U$gkx;zF8F3+LD1;+`PL?0IKCy7M?CE-sEVAD#trX);4*qdgtA zwSL|Us=(BcL3KHpF?IrgnR^t>ayq{q^1Fhcxca2Ybjh>Y!N?gegD+q~nyK599zOyG zcMe3@5=S9-?Gx026NXP$tVu7}GS)Ntwnw%~?jIf8?V9deZrTdp^~6YoFYqmyuq5f5 z+SSS-T|hFnpd9G^B5^oyWuL=+?aXDB5c2FoomTLW(Qh;N8I}+Dya3av=Z~@x_P_MUJG>|siyHYK z+yE{kd$G9-Nk`I~Ja2Ebe^gP2JPyJjjR&fsUZ6(Tewl{r`(cE_QsEtPL_NcwUyp)f z!;R$`)m&u@Hb|w->H`eAlW;>q`V;a?BY+96*|J@MgLU;# z^fjLStaP+NIkP#6lnA6{y>8Q{34dt!R&@XEVDk~DtvG5NzGV1SZW2tMk5d*YN7r9{ zJ#thBW2b=+FEU069?+@5sxF#3pR;Yj-mX97lbvf8{doQRFf<|OY-zU3Fhp1y&{=@V zw%-9hvm&`KfoGu9(P@148+2e>9rAYpKWjpXDqb?a?M63h-^&C@Lk`*mF3UrIiG@$R zNCplD=^6qmcI+Knwmb6PN~=W%SMI+7F~IT7t+NaL_7@Uotn z4rnb$(PNOgPZ5^;tu<5Wki`&|LrNt7Zrl4@&#Zy38y;4y^1d-+*}=7&mSV6#-7J(c zmr#9bqMX~Kp!TPx>L%&c;|Pf_`vy0X@88lV&oh{!)Sp=X0x3G7H2~tI@(M2CypEa_ zkUac7stN*#bk}7rD|Q`&7DG1h8io{Os=fY!r55XFMXJbTYMp+7P2uKNV>C|Ngn4%v z@Ehvn+fXEv(_l;G+kO{Ji%VCpN?g1@bqY5Rg_m51P8?!%Na#XDge-EcAegt5$8yxK7oIVttsb3(Se zoV~thn>U|>-WxpRnkl-e8@(}j@+SsQ`sSX!ZzTJxX@hV#p&RN}8CE{-*~mrs;|`7O z7{q!DO_PEPxQ-v>%=GNutZCD6W~P@M3atnIL~LLLg>FjcIlFEpIk~Q_LZ0vX;|A2a z+z^o7+}S7<9Z}ht@oh#8q+J9?j^ZxUJM%dR$l%$;?}smHjU-rDhBK5O$+o|y+AVLt zx`Kfh4VTsnWxBvEe~I#11qz0TCfShPmMc=xnM-XuCJ^p(o%V{^b#71jINNRxE4S(L z@!_)pTi5_S6|vu+CwTukG4^CNg>qAXj5KKXjsY!P32|9lDHc5{0xSLnJZ4MiZ)R!E zH8QaK6fe;=uca0OB%f-7uFU$~6?aA7g{jH)5}g^q%2yX>ukk+s^E{>U4YAt7Q+CdK zxMfxEYt5WZx2Gn$G!?p_;(Y~9;xlhWPp_m8q_#m@LdLop|4!252EbD_hcfBN2=5cN zG`Gg@NaN-gg{Wv0l=Xq>y6>1(J7{eZQOVL~(W}}`s<}Dyxn~(j=MD@C=l}k^+Q)Nb zy`F{n*acT8s&yQ43Z7abwuMl7Rht&@V>8(e{t&*ca(=g44FKLhVT|NwC)G!GG%AmSo|DBY_!HspntU%_&G^ynK<1JFJ;RD)X%++I zX^f0*5-*w-bCD2+pb7A5qelH48ja=x8=px@zYdkPKZdZHphL(yYXgsQAl#ALd9L!% z1<_GYqm+e?;u(B0k4&$htZ07C;LmGO_N83fIDbB5DXITYqn?{bN5uDw?EfUVT~W0w zz5tSAj5mwmcA#~1c;{9jl&I%fWa3)_!^X+ju4}uIP(%~ z9A*@C`D26J$Ov-gVbq`hDE=&B<6i+0MRTvp+)x)67w{BvGgt1ms{v_6$%S>`sCE3w zo0*TXa}(i@zJbQh<|9!kpxdwC{nprjvX%+1-8p^zXILb*AFlChckYa;LkdRY8MS?Ke@gWpVP@#!X*loay#m9>CFMVupk!Qq%S= zaYnL75c_VU_dl9z2bNJhqugtxvKqaWrV)MwuB292DJ|9tF?D#Awq&w zmtH-#!4Z6Q!j>3pk;#=|bT~&c1NvG*f|yS$AnCEbO1>!T@kCxwNco2}b*(a7S!Sg= z@5-B~7N6jq>}+NxSz|l9sI-~!pU&fv8*bL^nA{BcvBQFPl;-;CP(0k2FC?yf1sYpz z#UlBNhX+}x2|bdhnY=h@kyGgI>3!U|V;y@{sLn#kN6`S=8VP+Vx%)5E78~bFC%t91 z?A^iaovvsOraZ?!An%W=D}`nAB87OvLQJAErAMrx1oe-;yZb*|{) zjDz`4jp2cpDk?iO@K=gG$MSqKwnkg)K<2OJnl!tR5)jqI-etJjqv8IR%1!4NV)AcJ z#>7{D3>{S>Fg`LHeU#yZNP@KV`SwY!XKcY(Q*JvZvKy&J0SXulSlx`2%V9;$QhG?5 zDxR(&x~<#H(>MI>XHnT;)yS7(evEW3$-$EPOZKuq5@)PSpbK0XNkz@WUDh=jt})%; z-=$x&X|6$|iiN zGHQf4WJ*!WwP?(SOaY58*&KZkbEKZz?PnCFd_md~0y_PbBZ+X}-43#%|9z;pD;5P7 zaW&2ELQE)xR0Kuo?B6Hhb`XMe6MfYc7JR zYOPM3qGh(}L6ux5;8e=M+IzPi@!!c^qUcegUL~ObSmUmP$R2=Mpygg<_f214xOj0E ztJG&amhKs@cqXiY)f`?fHg}CKi2a+U^EY%F`!9WG(tp;qAe*D4yxJYX7>` zP5L$2M^YE=WgzsiL8#KEhU~U0MgfG2Bx(}`Q)4I0Xh&Ki3gi(jLE`df)+9HUe*8EE zOmZ!)hEOG0+2^IB9AEG>^kkt0(xYPs0?1)2>22<7!KM1Jv@&2gv>4vX2am`WU%23} z!S!WlZE1SuOXP{#1XlS=S2>DR!=iUdkD*YOduK5EN1uPP*dO5el*@we)Ll2BL@{2w zFjrJ|&KzI{VS8$;#6Haq`5#A{z17JB8T$CpCVVhXJ4vnKNta}-6}?)VaHbvd<2>d8 ziE=l2YE((B`TOgel+7sxp?0wSY=Na0R0Hd{jFfgN)@hB8bxm`II7k4OLPH%D<(R}j z1`P=uFQH_Qkr%}JsVkRDlLen~KSE&GD_qEWtj6iwZj-7ggW3rsiNmLzso#YNk%CI! zrf$D2-6F%~w)2PV8i_1q^Lp3yyZJ>FrB?Lnm_&g>J2ec9Eob|X3Reyy(~Qa1njGJm zxv3ePPwG`3`BRS5PICrjc^+b~ggZ^G@)EqNKt@|w`($$sz!AvRJQBzgJaD+^z-Qh7 z6u&AMf~r4vm+OV*qt?eb#c2z-1qB7kl7WrT+MjaLpT{8UB}sx$2zP-Z4yOm!=B39@ zvR?R~$GZqF_~M@h#fI5j_Uu?gPZlKbH2Pt-{x!Lt9x&EY!-LV#!E|oOt(TCWMzdBo ztkhb+7dz(`90&@wD=3JJC@5tYA1m2uO1w&odBqO&&OC@d7*Y3vt6VaKMBqFcfLFW zl9vqyXym#l{v{c(dOB5{GD|i1uMRT;6@U;p9D#-pb>ZCniq!%MsKLTC_9+AWd;v0z zU#sQa-c;R3?;{6w)aOFE(*-XU;T^ zGkWfDZtW@URbqdht9Z=owol+g3TuOqC}J%fpTy?YF1# zUS;}*FvHs$h-%FxmHJ5GT0T2ppRv;gCob9F=%ctjy==+bv_0mIsG7>f&g;)f%_m?@ z!6Y>BHvOKn>ZBm$4mxgj=&A+uP0W#0lsapD#C{TsjL2wViKtQr={9}K=gyxWSKJ1c zOBM(jlAqz-wV9-+%u-8ce&plpL}Lvp*1c*fP5A4+@~BhIH=Cj=yNPClu$YE~->&ZI z-PsS+Nr`yU-@jp5r{Td8qVjWxF#<#3x=5p?B~R5j0>~5@kq=~U8(;Q?qZq`x7Wc|i z&GH}Rh#aC_QF=>K@^|aq0e4_p#K&hdh5OzHe%CD55#Z)IMq$S9miXF0F#Bhobu{_I zhM{oHAE4thSZ`^0W8tRsl>AoLB(PhgY_Rd)$8I^x%U$V9Z5Kop54EWb5k3N4o+?%D zT#F`En(B_W&Vy=P+f;A2-n1=|=?7t@mVUF~)C+}~UVm;9*>_al>t&V!Sz5a%yNBDc z_Xo)|4qHn1Y2e1}ZkWA|P0`20-15nlxDSz6v^&%!0Y}s2FBVd=Y+j6~Wgd*XzhOY) zExUXFZ%!nxg~wB|9$;S$v^X#IvXy7=Zt3&9#Ab(pCOl7qc->&Y9;NM&`&fO+#)#Q} zTN!3W7sW8x@h)Lhalics7XZ-#o~U^@4(k|zWfZqP!-X1wJMb0Q_6jgQ5*yfcMN)mY zgeSTiHn4Rcl##rm@K0Qdk}wKT*lC9J>1wX0;tcxF$<}k3kF!(T8WHnTsljGcz+fY8 zsSZh0sqC|-S0v2pJDzMy+ey1Q6D^sP)Jy5&_0el4cx-T&YWg|3O#183@PJVL+02WE z5Z5^_n#d`XgQV=!nP`f8lZ0lBPWG3@|E((uR$|@Iw|KgR-@74K*l&^M)4zr(0|2I9eT(q6tZTZ)xD2S$?UZpWfFPTQfRo&Bcrx>U zs3hBKKT|-tTSJYm1^TfM*=2i8^rlE_m zsFB5#zB}!}v0q2!jdhvu8;*)afFyN}x~Aqn-jd`V*bApJ(#dkp7N{e*66YbBpD)0p zuLQU%?p69of+;P@i)NkFh0v{5YvBoHSsjuEuP7Rf5364&Ia7uE5Dt~wr|e-U5z$HW z%U$aY@@xwSCKp~2+gOrp)FrSHFKu{h6=`D%tA zo<9b8*2j0d61oHyOk#gmLw!0D@bz$uI2dlNowQ z`c?6=Z+hf}veNAx@34It@F1WX@4;jJy>h{}HQYD*G)4Cax$%9EuQJ`{P}To+>A~g; z+3-+v!A{gi>G1s_`j9|UFO#9GDCLxpZ~ZtF_%eEMWg|M=YAN>fz<0#(Vr2mV0o$-t zL_8OChNNs9f@|P~oA02I7`1PjH~y#zQ!#>&bZhDb+pYs6TF0d}{Xn$mJ==kUL*N$f zLR2YT)Lrr!%zz}Avlz&mB(@hH0k4ISdroAkE4wU>h*zABprO$26?Vu}m8Y#Y%6334 zaInL`;@yjmXYkFE+wQY%I7sP}s`HZ6W2UZPTQr(Q0ENR?Ao-nX-XVu+8)aa$?hyhd&MRglo8)t5x}}r=fz&h z^2rrJKNTIv(z-sGFeVp)ou#^n`F?95c?}Hx^pe9?YV1aWv)nb+ooBg9zqmw#6nt!#u5hRQLBS1bIz2$;urf52iy+IZ?mRvLk9!G zZvTsmxp9dUUV}IGgDS5Tp)~Lm#VYYsoBXh>b9DoMpQiSq@Iu11%ZEz*l*}F^t8UP9TjPJ8x?RY)`D@IE(4Au~c604qCse*^YG&6H zAzPRb*$VP0?Y=?SgCt#hJBDwZ$iQ@Zxx`N5aTP_sjYiGIIt=2D+Q(PsANySR5jbp` z)~;Z@=}8|rP!)TduZg%jjq8)_JuErr?mnZ6gu5NTqY9Tr@Red2AI2*0a5T{r4y){+ z+3s_6BTPng`fij*?kd^)j}WMqUgtaF)V25G^d+OT5SyX6P4JZBOgY*pee3u2&LEDI z#o`@l`>(in)XndU^7l|Ixp6b}eBGX#S3;D`=Z4LH=6;WF0POV^Fp4LNNt-TylD|V@ zB}fi~S6BBM4s%MW3n|xFBm??>Ay%ED8!ZjWF zbY|IYo(|(Y2fa%DpyCj9^%Kp|Q^-zw914>3S$ce4Z#mb-==;+Y0AvK8Q^_?I6sm?l zMckij-9KPqD`;9n*bT70b&5M~r*7Vg9@M_#xP4|7T-$TzY1HjM0jZn3wQ|lG$#+@U zpgyi)H@7BLU<1!6_>08;Tw4El&(AJ9xC@~_f2brVWi=-7kj1hB6fX0T+^T&o>zrDm zPwbhl$d{RoafLsFjlE*Y`1bHs8@oL!hTi&JE1e?0*2j@uLt^8~ZO=buM>{;zjPYkX zSNj|ydGG=G$eEAs&=%Ld*8=;BkS;s!Bwx`$?hxVN_#*Xi}UE@@5 zUZF8XOl)~m$13Q4c5Z1zKrM~QaaimqZ18Se65$p8`23;>afC?68P-7seCk|3fn$jc ze3|uGcd9%(oEORcIJ-FvY$dw~K_;skvR8o7{ufwszc3Vxg?mm?|bxThy29c0}UEyZuCPk`MiPJ@5;m@4DGo2 z7_pW=i+Vdb@TCt&GIC{e)W^kgZ?tKf`)>-;BV<^ry9q6!KkJ{jUMzLs8iC-Tag_4@rMRje!t|bJB%R(yI zWgqf9&W0&C2f&f;hpT%w80p#) zdk^ks9dB_vN0PaVq;;Pa{yoK(_U56JNx8Ivu<}DG@4={0JN4M^Z@UdA9Nnb0|2HOF zPcFIB>V2_P9dJUqSBERXcOAO!XWdh5g7~orw~hPk{ib;ny8E@q(52KIL>3%_7_12+ z?g!dTnj`+igZSA#X^_7?S!{q3f*?n>Sn0aoi|QRT8EA!9I#z zbj#jkv60w&fk!R;IoJ#VP7EpN)2-#={B<_!@PO@JJ=xt{uIb5fuPmURgQ03VQ^TG7 z#1A8pp;#Kf4Rn1MIH)kFUm6_3%y26Lm-*A%Q<_#kTh4y()KmNpVyjB_n$Eaf1unkg z>zqQHd&LNuHwD0Ptfg%*2bJUtK!R5Ys!F82R!+tPej2jd9ldI*0`A|03k~JXomt>t z?@I7O2h;@&3}3zzlJow_OIrU!liyb}-xb`KwEI?7GVziZ?&fJYqJMqSv-{+SR2bbj zmM>LXVA5dvQSHk8$X=7qRFA8~?EH5x`pq3*eOyS6;hhv2@%4*l9Bn6z*+0ey|B2OZ zUvacs?(WR*>@Pxcc9GeXpq;y}D^3R6*T`ozt35HD(l_xynC+8CVc-?4M?>DTB6$VI zI#NM!bMTK*k!TiLrf0(+1nBB)F8`<8D^^dk)MZR6$EAkt(X}sgmIjP+zPqhzQ~Wdp z8I|48(JzTF7f(lHO>5E{7OhQ0oBK3r2nZqxU5I@y)JgkY2{C`UPfSYSGk!eVJqjXj zu=UE-&r%f2znw&a>6#Wr4+T}lrPX%6b9J(|n$taxaV0XXi6JI`(Pm#rq4)glf-xq| z;ZD_)%3Cy(p{_Gp5;1D3_l5@j$0z#P*$%)Kv1RxC%-DVZDjVYe9BmGNI^bQ^q$yq) zZI@8d-=4K?487;Fy<+?yYnqk!!1NEk6K5aW+W!N0kJx}`gvI=iMM+*g3I{rqPIg=) zkH6E{$Cg=90l9?m-#f5|A=Jm}qA&IrDYm~z$HwM!V_~d)5P(cJY>+;$7MyPEU1J%) zO-U)ZrE5Z8Mc_tfq-~)EUp_VRV1SI(OTxw=Zi)_fCM_!B`?k$8M=g>z#;*QXi%>Kt z+D?L$C_|$V@;;&O&dWu4wEK12igdvYHRB%WzZWrQQu`r5{bCK_R-RRGQtlV7$o;*4 zc^d5Qrair~+aFN&D_DS7Z+C_H(ppDvt6SPHJ2a*#nx`o?_L>*WNi2knSn2WLhj>KG zsL;a}A!qKT6Q)Lg+YC%qqepQ+?nt{-NE}g)TZ${1N=r&xyg797sH@kyUoJD485vHd zv@W;usz?dC{_|^}hc!fa_RT8E9=&@B5w5ZZbeuTzM~SFH3ENdyE3#-h9j2gA69gO# z!}ugKsyqv(+WXpFtB_7gnb!AeM&DeW-s(PqX~Ck~#k6}5U76^+mD}@|HEnQ4%fmj+ z%VhrET>fS59g5(B2_C(NB7#pVQ>9GW%X3D{UZLCDLBN3Pci4dzjFR#{dc;^QycI{? zenSN`>h~4b`@^jjn7|~@r;n1t2me)S?Co!TzM}Q@hfk$huN@5?Q8d+W+@Y|qCPlWf z*BkCWNVT=g6`?*w#&fHH;6d6a zsiFh?8%mVpXTE4tBUX1Rg30s9Z>LL$lu;82iCaO~M66m=VVm#DO+SSbAMd!yqxU!Q z8+dL}R@8`Zf5#SvJlHLqT+vYSr>~{c7q!io_|yMl^8y7H$M1f5ndiVq(7kPO!|1&x zY-F4&{X@iLKsq`hcYd8jy00JKW3dBww}-0>CG?j(=o>nPY$K#lyB>7L*?pd$%(MA| zoyroDEZ==zH}Cos5nT&oE38YTF@@dOhU&*6(kSEg%ahCi_bi8t3qizyyM*#_=-l@= zyYl2p%-}9=bFj*PN?7O<2l!Oy#r96qZRn~@a5cm_|{=Tg~fr@!l4;6Z+ zuHS`~NmeQZS6>|W`nj6#EBuy4sFXk71(UymHzT68Iw%kBrjcjc&-WN}NW!%=u< zmAA*;p7FAi;yF2uZ*69HkNpR*pzAkIRB_602j#{82ys^;)21sH!kzNK*zi`LL3(=a zS8sLiFCQxb&6Q`d#G?1 z1xo$kz6uGipo1ID{c970|5&WIU!M`RnRSlbDIdH3bGl;H=ySfrAkcuIlWiFx3*{hJ z;J1vNb`*lxjCZNcQlU?OcuXBS+vC1IET^(Q7XaY_@74?b(}smf%+ifs4F!JMRgdR{ ze#-izX0b9VZK!w^YN!k7-=6aP81_m=L!(OK5h7RA)VclzBJzXUdF-Clf=MCLa9|-_ zx^fyj;d!@0(=+HTYq-ds2+ewGp5zTUuKG1{K(bs1Y^dg>Ie^z0XgX-kri zonS>m%16r`@JD*4_4%INyGq5>k2lW!0CshZ_bO2dvmZ}igpnp5w)A261Kkis9(V@9 zv$#6Kj!rl}%`bdld7iFVS;WQyU>UWrgJo8sXAVAJz)`s%WF$SSzak|#xoBF|AA#mx zU#rO#a^hudvGJ~ufS>&ZKN+7JrQ@?&+Hf!B%!HZ2s1_xDJp>liopH5XLWh_OMTJhQ z4>|ogBgA7ldUqn8l$$)ct>NMB-)luLmJr(e@6O<3C!F-Ycjoq&ng|zt28%{HOuPSv zN5{ns*KdAy)yjJt0WG~mH^Y&yA3^!yBhc7TvNZu!L1VngD)#8oU6`=XNfH4kSP7iOwQ zzSU|rd9iWBhH*zWDF0h$jh;f3N+dq!a|~Z@!AX{Nj1%Jg|J#%j0k6PwM(V*9Bb$kR z1zH0VuF(rm`mNM*@oqnoe#7Hb@)YH`1>AGbuR)mK<=A^qOF^wDp>vt%2h$|W6;=;7 z1QNrv0ZrasX}EHF2Q&z0ybelB$g?SgJh;9WQ%2?bJYtDKQ10KaQucBs2hE|>h{**F z8|d)4ErBt|&C+}0AHVsr`=c9EGfQA{bV!_qjEh?ZuHKVyw;Nd!{u4fSp7m&GNa!s( zBiGJbLmJ%I)qFRdSQvl}eTsL03|M)&bJCOK1KwvbVgSbbQB$o6{q+cXL7zX&5##E9 zt|NT)P?9>E7IWXqZtQ{ijS)S|l_yp+L~B0wJnV4w+qKp)W@?Y20s(xLg{xduYz*a* zB*gmIEx3oW^5(bWj_hmN%EdKkdflvX*u+DXWQVuy?bHUc~Zfez+*o#O`z~9 z((?ulidn$r+X-l)_ziYE@uU%q5?UmKEl55oi`-Sr9=u#Sa}#gQ%nl9P=1vcgGN%vl zB(U|F%x!D{v^_RUR*@f_ZR@ejsC^|QA2XDvUyS=_b)mxQiBrLZ-d%kckKk7y(l}-O z8>y1dT?EY2YGUF8b0Sr&9er-A6cyv3w~J?>cj(ocUllv0tUsCwm-US@?O}CvMe-=1 zYb7^a`#PDw>X(FYuzAX^v-?c@7jA!@)Bc#?9M1)tW9o@vLyId&M8uVBi%MK$#F5Nf zgB`yl|7F5S!+pzr+mfBqhFB!gaK;T?7-FZWw7ycbp;5BB#WIV4kCuN* zf0-`hE-8&tIh>yKCh&U^ddlU#qVx-?z}B+hd4= z>~GLQBSiZ&xvVT^s$_h*lmf^y*3a`^&m8JYtsRnrE$Bq zyk0qwb1^HLuh$1kDndt6M0o87f+PnL+gCh?(vM7s*2uiK8I8w<{AJ^!2gkp5 zP`neB=l#|rrokz!+|+yQ#n90CeRcsml{petA9tQ=0ZJMG`^96d*p~pg4x}r2yH73h zoK+M;+t#}Up&@jUt>1QxG&Ku&JG<}Ebqtp1lL_*;jWH&dhK1Bjgh7OtA~}VOh_I2B zY_5QqAzJB*pBLqfoz6k4_W-F3>L{P$9OM-qRKBe_roHbl&_=2D%wXwf;@OR>@oi$b6~ze&=4Ff%&R;@Ym=9ee$U$xy@X$4@$PZa}QggbhYG?%1M`))*|0@A{)x zbAw^8$KJItHk%@<*pES-ppA@am=0ki3|DAzUdFeE0dLVp#3b- zU>#dl2Op~MtLr7we2Qn!al)9zOx~kPeAB?9ztWbNRq9Z+As5sW#f7SOmkl-y4MhAI zDjtLgNGd4eNpz@X{m_I3i#@ZW+(Iyr_{W>GTFC#B#~fGp?bCI#CIx?#_NxwQC*jIHEkqGj$rogAJ7i|)=xJ|f=Krakpu&Tj8=HqD~3Zu7bhwVT>ry9kcdZap)EYzD59QFA-E{b~!3THh<9xbLs!^ z!#sb?gZlU~s&z?z+g{fYLS!S;6Df-ZcNf&d5BywzKzeSQnozP=XKSYf3BOjU1F^lc z!4*^fHB2z{J;`MQ<>NuJz}I_EZRH?riNsTyGWQ<0Eeg_Xzua<;1}~UCorGKm(ciBm z$a+mF6TfV7&rFuM?_5Kx)(Ey*<>JkrYf$p7R&^f0s6r9X9l6OqK9lC%WH{JSi-nLd zZcuZ&xo`+IkmR>y}NP3h_u3@a4o_ZK`uQHC{3BoA?0)+~Ede*~S`D0(n@ z{ULD1e~EhP7R(2XAOO}>y{l4m_ctN))Q9j{7;M}agk-LIKz;ur_^XbeRPpT$8UkN6 zz(TRaP?xO0&U1W~T0QT!7(Lo+VYQ`tCb3{4hQF9mJKx%Q;7IH@waE#C%L#t|0A5-v zyBl6-er@>oRRfL&em+h;_TQiZnMdm6CExZM_JX{!u<;ulHHE%=KXO{US6E`}yd14Q zy)o0Xk~L;6hrDp&LzkqiTPb!TRo^6Yy@*N}P^Gy6g4_E|s-3&@?{{Xe1Xsm^VJ_O9 zY}PxyHCFq1nC%~;1shm#H?Z%TUY^RpfV$7NF?)JG^c6IYl3RTu<_|^<_R6drosq56 z9VQ;eoJq>cpFeQ4MT9f`gVj^cN3k@QEf=m_*<~+umyF)fdyT}EyT7Ks3D9Av>tV~)Jv6byRr1=q%tKD@Th=zQshCbM3_n=Tr51e= zm7K0IRrUHxOmB{&#|}>3Q=R;HylI7htmM19Lo2&`%Dvw^R=&k${3lGm=P+cquU1W1 zv5QBi@58RRUm$LnaDR66`9gr5yf}r%U00>lvRc4|v$1!s@OBbY&$er<8Q(l4-1Tl;+^PBylz{p`2Cm0#8{^lr^6!MGDqDMdoLGy0o3@(f zpahPh7YquO4b6;gAST@4_jPM2p$?obClUe?_}*SGDvEev?m04Be%^L=!_F%WPrIw|>Xtyjq&K_$}@VXyM-M zHax?(%*pUKvLN}ehZ?cxm=u4g_63p|4QoUW{;R@%XARibEhtv<`I(>0saEZW`@cW> zE=?;rzt*m%`j1yxpz%9vn&*$AN1qth2?+_4rIoM!=_y&OQGf7q`p}BokHf;I_K?yPjkT9B>X7~T zXKAE%YF=MOl5XlblKr?XHoji;=obo1-+iTo)c1}%Cig&LUo7pQdY4gZL~GtDVl!0a z7;}9tFgZa9vmvFUxJn9fI#mFHO#0pcYFl{@-@)-w+9#YVJaF|AOQrWi<9j1a8lFYE zHec(@&XT#OUuy)~SQC1{LFRiiR>Oo~_rWTS$M@iN?%-*1(u0p8o zZ2f7!AEVi@1Yy5$VGC@JhyLG}4$S>|T-W#*LIH5t(Mf9#lKbOfX^ zh~MkPoxYMjJA*8O2RsQMG2*E2I@l07fFOObzFe6e6>th8Y% zrLSOCNn?U{%&|3amM_fqgS7V*7(@Pf=Ae06^HoI}2>Z_vRtb*0vb!n*{J`&YOBjc}3D0FCFb2u6>CLoohUm z}Dj~aj4U{m?U(P}?lf$QmnIHtIilx%^MVDx7fjF8id1Kr=+&sG7HY>ou*>m%8N=r)%qs1pO zi(7a}nX?6Q1k?O+eG~8X$)xgWIh>9`ulXz=_n&30Yi{p0Y`?bDRoCiZWoGBKm92-! z{JYhv+KxG~tE{qbzz^wwnbmf8dnHwa;3#5vQ%)7^mCZ~7=?$XNHO4-VIeN>?i;(TM z3}mpHC^8mzO2so28TbRgN!FHR>(Lhpz-XBasZ-S>W$hTd>wJRzhmENxbnDlw-t!BK z83GZYruESQ37W7&Rp7#k4LiA~Zx=plsa4qxltg3*wS{j4rpCm(TOR-_;P%_BHxz8J ziVcr|X1h<5YSYx{RS~gEY&^hs;A{A|;HoK%zeUlnbt-#5&+!RI^~zUrQTJD@(2j$|l%k2S z9E8U&Hb|Ez$6na^kor1MCY6CzTqSLOB5mz8hHW1cdL$=MfqU^Vw~hIj`*o0AOcuM6 zEt@||swC~l17qB0Y{ly4gMp@gj~FgdgsbG>X3}c_yiVD@?!Xz`Wi|EF4*m^uN}O1t z-#Q&aLWtn)$#=7wL-6vGLf1!(WB%&1|?j3;`Q$fdy4 z)8Mh6$bcDVDlwIz4&(wkd4V$N^5ucHZ}CInBP^X5Zsn<=5R7Y@f@GP=P|NvV%g4-h z8Pv%O<}N`O_Iq&(m|A)sj`Dr(e*jo$D3|+GgA@7~aZU!DgQ2|pp#Aq6yTGtb9|A$9 z?Y^%8_qJgI_V7z(N>mKXp*GvrJ>A-iBf@>sj=bV=4U={qw&jyX=@pYVD!QZh|rbbsdQZd#h)UweYe&Q z9gu_f);?GV@VVuNfdNvgIH_=Ef1u&k-m|_7dx2_E}*5B;wEI$*%gKP?`@y zjz*_K7NN|H7;MWMH-a`9ETo)H9Y15aL(;0$DVB#Swnov$klESS*orfnyN=HB>53Tl z-Oe!Heksu2kY`1D(HkyYy()*f52>&aeQ?GsZfksSHummM%tvA9b>Yf%5hH-bmt7lN z9%w99jd@A6SGS~oz%Hs~Fd@%#{l^;{Cumqt(gjo5$_XdshtD%{@Lr`Th^g!A39M<; zBDr7vP^&RDUCaX>;T||8BrRr&R+uvdjuYta!cy0-5~>bjosio|>}lG1mT*{3 zJST%P_BdFt92#1%HkP??|4XmO-!NX_s&Itt$c#O_bgD1pV)5MDbBj}!`STSa&ku(g z0M|X2XOYCQ2~g)Ug--Z*GIXmD_pKmSwy^#uOT|1vOVC=TVgU1 zlg~TyQmMv*$&A4ztUE$PP8@h$(W%gNNG;{KM;d;|ZFByvfNJ)cPHNF_$W+3m>`eG| zv;B%ya7c)_h+=qfu%26uT;4v#*B%t?Q?Y^m z<_|PjRNn$St>cc1f_O0RVx!CE!Ln#)2E6O?X9P}!p7vp>*KlAZAHG5n+xW~rWpfTX ztaKPJe{euS*5n)Nj&8&!+CKR|fhs#6-rBnm3JY{mH3b9ul*A4oVjE(0yZz4F$VR9j zT|&=cB^hU({EzPn?rqF*o$ObDVd~teKaMnfcCX@iJh<~fh%pb!GPTNIq{9X+t^Z>A z`?AowPrqP6b|M6*Hcqn>#OMozz7nEH z78Y^^SBIm^Ax3m*oB8tV!AL~0iK1oWQgNT1Yo7LaycdgUS)Q}!YDzu^HR}O@cJL=Q zH7rj8#v6mV;?@6d8G0z%WGQ*7Zp3B`+;jK;>ip5X4CIPtMi3H-pOM)J_r1o_i0;U6 z28ED)m~ZKd^abeZc%B~WsH-VeHh*FZN(g<)L}CF7&*O^fJxDJ~Lsef$Xw09#4op~v z%7iY>+srn!V*VQPQ7k1Vd%Etz9evL zHXr;MlJ^ph2CLr-O1TmjGs0;iO(H#Wxge0+rE2aS@@F|hKOlbDBa6ZREQQNyIH|#t z;J6tJ{yIF47*w$AM_JFlb2T-UF(AE&*%o}&(R{&>8u^5Wc*G&8Qv2Hbx?uM;MO#MQ zhReK$o85gVOul6uV2+6l zkXrf>sbvB)^TNR;e%Zb@#Jlp@kB-mwZP1f(*Vw8u)MV;jBGvOLn-$?BKAlWbzyD-k z?q5AMg?JRkO-OSHUQGreH*eoV3nn&?ca7sdJ#Zw$Z@Hl+v`$0E?r7$Q7jWhY;HrlQ zGbCA??!Zj0xrpS5)dL!FN#dmG-q-K0}PLh1{*<&ILk)4T3Mo)O0 z{Fn2g+4w?a0^nE{5d}5yJpQ*Y$4%Zt4hWg0VNXNy>Xz*6;*tV1kDEu{5=|au5h%4! zIoO#F^m||=M9jShyd@GIFc^M`X+Y0}mGQ`<=D@55bZkCHcph_|ebu?ij0S$=1R|u_j!|hY@L=Qu$(LG~y4uJRYUPIO%PJg% zK#EHv1i&Wbe~XpZtzUncSljH$_4C$ykNa#rYIo0=RbF+OhvF46U@d(RLGRHRmjFF^ zoH(CvJk=uqh~?(-xv4iZ|)hUFCZlmti3}obmt7mv!%Rt>?%m znD@ywn7Jw0@4tSY?ZiM{ii!Xs!!CkR4-w6zDhUUBLJ;%?^}lPa+~HN$pPrpPWf#)( z+PWp6K1GP9aIT1wNpEL^6|B@`Y?k6myA0;7&fwqI-i4?N0$c}0g_A8HBe-^;U@B=L zeLjdp>9H9dRVOf_*@)Rwbazo)uQxh)_%iqA&Jxut> z#z;Jc+cwh@p0*F~;mgtl`g6(&3mBki6LNMFFeEo|VcmLA83^6?4FSZ8?{yTvsa>a9 zn2S~d8O`YMu*?Qs3`C$q**cmbQJbqY2=&PiXcQxBC$ra{$mC0NegnqF0W*>@$LHB8 zQq>;_ubDHv;i%=5YXV!XpPUqM!KhQongI;1I^pn2QR?pQgH|y$wyrKN*H+J!m94?B z5O4s!^KR4t44GiGXnt%=do`ZF&*9 z(lc{A%Avs+|2`5m$9(}p@aWsZWv2`=O`gHnNjIvBxO&xrDFkJlTVh7W*g~BD((vJf40tC-)z?2!aauXC0Gwi2%$Uf4|L!1PQJ%i`^dS*Xj4!N+fH19s1Mwd zlNbauj_BPL#?{Xuljovez-|`~Juid?dp7UY39M@}Y7JvV#ZK_V!Hwe5|I8!0iGSG1 zu+)o#DB&wW2Oe8Quw=~lfV*C_(Y?R$6uW|Hnnnb_N7G5=huMJlYKTtDlOQOabUxu7 z#9Eh7hAg#V766A@r|g8^$#4?G-V?)vtUy~Oquf@d8~9xdzwd;1*Rn9<3>kiC@poQ<1`b&wC1k&j(|y*91t)#$0ppYi`)n ztE?88hVhxdrDW8i+XzyPZpQd!=bX?rYeKUrHTB|5O}An%;$nImFlC3Mj=YnbQ^VE1 z!6i{)pX-s z!2!WplLikJ-&pY;P82g}o$hRtT-1~xzJKScMtjK!sc932%wk4>I@i`f0(D?~_Z%#2 z5W@G1#__aK638nSJ`*`M0Ag7uxz(?GyfS#Alz*7L(p(f-!G9QGl9oCpxccJwg$g89 z9sB0*;xg#IIx;4lfLN*PG*=coml^pIY_ATobs8bEOnou&4{PdH2yZnp_rs~aDY)U< zlKW-tq^&G?Xl>$1)b+i<^_1hnU|t=p_kLv~(xjBX2RK~=`H4LHN-EXT(h{B-42Pql zzbh9^=R94~xOSYyS$moN<>|hpYqYTT&G-$Ygz;4AqddryQJSYljxHbhSNr@ouLTIn znnK512q;N$=M`i<3B$+GO~tI)e0h;yWX#w|3iq|QfKLR&@QPBNr5H>TeK`Ir>ApXi zn@=5i1FWCe@$c{k*c1fT8>X?R83LM{K|egh7I4vz?1A(K4^Wwb%|t|Wn%){ll$iMt zYZ=$@RP&8m81m1!q7Lc53iy~0i;kV0Ih?qZawINfapkE# z^Z!@1Nf!GhX}8m?n65SCA25`REEpeQqTFpYcB>#!|@eAo8O0My*2l zd^2ek6%}byH{?^hLX^V%F{gmNT}IZQ{KR4PgTug6Tu>uypT&F=|K{Wq`%LOdYg(?* zF$$wIgwto48|F&BXW+Cz#Q$wd7fBSN~U=B6G2fkIri9$NnIO~6V7z3 zTfGNHq?*!M&ct5o&Yf-VE?xcak>uXuBgyek8IQMvl`|-j2TR z*UQVkMD#{qBFsfL6y(nQpT|HXl`MDrJ)4iLjgMt)QfUmB3YqhK@4;UY-%Cuz9;YnU zo#sUv>A(kb4wZ1s%NTi&&u(&=vsx}3Yp)`Bl{?k4ZWhZ!f|+d4x#)SY2_^=XQ?)0P&1E+UX(dMKAFm$AZ)GkZM{&+N=+c?wSw9i+d4_S&cE`%la3lG=ofUAqRG zo&RU-8hbIHUEo?j!Z&8#ZBR=9WAsxnTb9b6j6(i`!mB2o0`?H2g?8hXY$7iUd!OyV zu#jYoc<^1uE%yIweMb(3EUt+o>r^L@7fOxfQerILj>%<=nJZ+<>@I-iKl8^-IJw7} z&(D*4VDM#0$)UwWiOw{ZW1kA&TU<8(Gk3)6!gM40IcW5gkQof!LTib_7irIh{gjOFs(L$^jC_c)U_(# z$%cGy{<>hI?;7rddqXH}EZ{d2uJ(DvqbA}~oxDTOj#hsYQ)*#!QX#YEnox7^TBJA8 z4BFD{M2MysKnK|}odU_TIS)MJlSV!_vYTvy5B>`5?S&v}?Z$In$Uz!Y^Sv*i{b z3OA}-4Re;N(oabPyvr{)BG9njr7SC1XQUh^kU{69ZQ(FC!eC@B0D`!n#(<+31n zwbkhEDRX78E19Q(b(YEJfWn1~#H@p-tt*Oa zBvw9AM%GxpZpG3_uLv?#!(;t_PsNVO*3$pygR*1B1d>0~!(WOqADC&9NL3SIv6@dGeJWe^UCva-X(t8MU2=n#BVSad3SWB8;L}}-cp)mF>T?VmTi85C#oTfVR z5y$w6M-EeBS~S?njcLuS zHukG#{_^F@qdGb(a$VC*lqnlVT$R|Nnj`5VfAow_0F3>YYk>Z7#ti9T-jOUuiX)3* zd`A)fktbrmzu}sL{)xObgEPbPlc??d$wol>wvfz|Fz{0QhwX$p(>OfOjfvL(9s0+- zpCo2sF=z7>C3C#aE8DD5X57v>Ie0*MfyZxW1l(|KRibgr3g4Mf?81?ojeavDdk+I+ zaj+Y%P5o@)GcX*UPw^8ZjkpPCd<}CVhL)$gBL(PiB2x}WetxZ)-801#Z=Ss$?WhAY zH>WNTo3xaBIF@j{^N}IPzVq>MHmz>=S@kzC_8`3JKiInj@On5V?!j^h%zF^H4jn?cUNjR zP+~SkD6bDz#CSyi1nP$KH<%mT^51_qID5781-SLuKeO){e%Lk-&9y!;^5^C9ku|%# ze}y+l6vc0jK21zjh`2ubx*!;kO#i(w&Mb#)`Dfu={p42PY1Mf1%#2CId=!m}6m(!0 z?Qw?6oQ#jL-%!-&_z$C*V0&sGTJV)~I(4Cy&(x7`SxDF-wC;399|+bpSK&4$(sdQm z4oi>k4?mSE#y?JBcq9YSpYdMly+F*!-B2DGxWDwNDf{a{6@T)85ghN~^WOw7j)GV+ zA#-TPw-UW4-t7N~y%xs)T&X1O6P<(4=Y6cI#1XCpn-hDUA31Kj^?39H%J5y`>WD5U z)XT84V8lA|Kh!%0*X66WyKV%t3TA`LL;wDrfhguHv|xl-%Kk*%2x|HmyXbvq68MMz zJ@UIruq5%@t2a*BmX%T^ENAOk$QW)z1Ih+wsZM<-Nc^23-B5-(&LVie*a`%zvuOtS zDzXCmIkSXKKqlJa-oLU#j(d#a&rF<<67vTO=Q%D9Si(Gi9a?9hQbB-`V1n(}GY{j+{j*wrw>FI@7|Z^OUKqL^oDF;N){Ke9xyxqcjV3b}$+e%^*+;jKVEs3M0-YJJ? z{3e0qQ8wm`e?m@>Vru?bleVJeQ^s&6>(m1j47>^kp=1lXS2D!8PIP^8LYI{YMJ2oI zIA~^)E7Td?O#j6yCTv&<4c2S<#0DJ%%z371OXid^Q)}dWilbQGB1jQInS5vKjG={* z!x-Y(eDv&zz9l#Zt~#H0RXL|BQjQ!s!u>b}+~he~&NRaevfVMe+YY^2eqwMh8?s#| z*_p?A>Zp`lXHugKYr%bu$lcUkkgUl3gPmJ^wu0!lfC7Ur@#D59E=C0sG;A}Z!w(#0 zV)y_O97vtNFB_H!(GQFLK~GPxL{SrdC@AQ%(F0JuaYQEF{WLqD8hN{nDmQx`_z}Gw z^EEjkXnKmE?yDY_HD%MTUAtb|hFE-MjB#2hZA}X{tvoxMFSwXdy~K)}q8~v(?@JL8 z`x3UEu#LbR**Hw1DYx8i3nwiEmrwr^_Ey{ta;{4+&$tDHtQj8d3(5RZB4KMWfpj4Q z9$L1w4;)=c&&*ry6bKH)nQhvFHGnT~gXzJTuz-KRLN?b`kuBpG8KvyKPMN>QQ=;qr`QC27>kqdsb;j%UdOjb|$G8vAR}VdB zO6J5%em(*b>FQ!G7LU=}t4?GSOtJr!wdUNRgHrwGQJGA=|3uUsofwu7*!N>pJLtdG z!{pWYI1#L!EOwcqn!`s2dyL8%Iw~*Z6UU_Q?BX9T?kY)<&j>s*bBXQ_P4uGxLWq+6Bg0|yj+?S13bzi!|u zP5u=JCQ=|$BgxB!M*d46rnCm>S_^PrPnEVN(gq^tDAGHP_XMSpDG&$@<;_Yt>SKb3 z&3_FL@|6HSw50hs@8XmU7|16uIsAzF4hQ`7p4FDqvBb{9sI`q5zvQP97;|JQkTzou zJa_t7NU|!7~4Oajm7W$UU^WPTOxQ~Y4fL2V*fI?vJt~q(|b-=8eJYZ0(Ll}tVOk&=J#!Y=)I~fuZ&uX4{59O4McUtq@_Fm z5bM1sMSww073=~oWNVvw9p-o-=5ngr%q)6yCJ6)(R&mj2SSoT7kP#!CYR{BbY+C>y z(H~tf(J#A__s%~Jf>WgR-L1?QE$WE@sZIliEH{#!3i|7(JSm-r0ltHK3trp}BWdmB z*U`v;1d5g>+4bdsh?Jk1kbSM^A{w0LT~HtcO~wdhEzved`=Hychf!Ke?Y5jDGNP4znefzi!(z~R=vV868x=)I_L%n#v+kuA|y+XXFyrE>`H?U2;?Gi^%h{Yazd(!XVXC{#Tpp|~RMl@J0RremBM=2tlAlo;G z*|w1q7Lh92=0o)4Z7{sYgB0GR~DlF zYLCJKV0l4aoQ_!u0gIJZ+c7~{a^X_rg&KXe&-j3z>kzZ6$Q(pU&qSGDZ{|-gK12U? z38KA6v(H&i4v{M#{Cz-&63E_}%ub>UBQTDNGa6N>sg+roeSYXde?xPOqzH#%ow`db0eRFlE(k`gvaXKsHHAWib?~_$4No>7@ z#`OrYtQ!VMso2&R81t*O(aag)2m}ktFSS&s8IXKDSe7TR9vP2gVg!N4C?wo&1iRr`F_P{FPnqK`CSRZ&K)jKK^H{$_3o4?@3gpmO!DzOxH#E2KTZw^Ca|A73rAdAO{HMly3M0-qqEKX)u zE&y4aS7S#&d!xp5*jfo0&FRiIKXmiIWv}kkuzF1H7{;Xh_73}XA^>g;q(mLf7-$Y0 zEKORwO*^tNPxa;yio4~NUNlm`9Ry@3WOM{m8o*iu#=p~3RCkV4b;N0n9{Q`lLO6*% z<}?H#KLNxKcQnqb;X)ps-b=$KcmUj=G0@|?8tr&zCyl}98!(3rhH%eBelPP%?<&Xu znTC6sfXMYDo3!G&7aX9#4cys>QhT-ij6^wGJXHWTdP?Ned^;SjTwp+0oIIIi-#&$p zNkt}aL(NJ^#rIX9c~G-*iR!;~Sb8ci;E8yr-7iW6w2tKLSKQ+X0Xvzs+;FwTQ~QG9 z|J^L&HH^J@JKYESE6Pr+jC5}C&}{Bpne4{;a$4+&qX|77q!P3Vi_zb?BL&BcGkSxa z*>C4!oodjm-yx%A(_E5mMI`0CXi2X4>Z`@T81KVv1v2jkNcI@t6z^iD@!77Aha%6J zKhcvZj{fX~%*LF$D7Ci^mHY(#5Qsrfw{Yufd&hPGu0_@fTg6*20zieapH8)KAXW*lH9b*H_V@1GO$MYUVJ!8|F$v`-KFYUl)>ohh#b@{q)o9ODH*rq}``&$zjh z_a5b2@CDbZ`4>LA*bm8U9!Z`M2fZ4%9F8`H2$s=Ph_INICx@@k=j>pnN;z(6*FAQ` zC4SORz9hjVpgH%=(bnJYP;2W-?HneW7LpCcOK@y!{P-#)x{C zwWp;p_xG5dSig+lrJ~{m!VQdhqtor`Urr3GzbDXu<5Co-;+-v9KsWIzjLjb5!kW)c z)51}tb{`Y{OWK?evRf@YuLgjlA>wGcyq-V>JR`@!Yd!$0 zxciiW-{5(vI^O)z-|@CkX)4R-b)ADu&3fMXuk^H0$esoERt#g?faA{PJObE(%Rp9Z z+`oKK_+E=t%edP4{mjJ)(E&!kACaNYhAbX64GAf3q!fJP2krW5p|z6Fi`p08E8csr zl?EP;jfJs2R+QVcg_w1kicr0y{w#jezQ{~oZGv1foluGL&U;(KW?P!U=0Kx9MTe4u zVx;Fx!&zfd>l|R#3+}0RYf?Yk1`%_s+35(7R4AIfJSvT6MB(-EAOIYN>en9L1 zFHd+fb5Q#%%N1*epyh8Wim8H(f|O5rv%mmtZRWWb^a$`E2pro zYkjPIqEB0LjM4X6pR8Y%GDO1$1b(&BF?77WU_W88(46QU17h3WIRH3I8j^*!i4`QV zF+6fj_SF-<7(;8Y^|J}ZnMu#oD=f{yek9kOLh{)QKptH3gigR4IOFGM0sPo3NE8BP zN88VLKR`wvXwbs6RLwBD*j~PdtlKj2M}q>QaWWEAPcFtp%d#TH(O*x{?4BIJD{Z0U zA_h1);VSbA(bP)3KWH&CnDx}eK`+ZL!v+{=f@bMkHP zPRPrzcl?;_C0b}VTrdDcbbSE8!y-wAcUZ0@4eZ4h&=&CCkkF-6;<%8ZZBcU6-$3xn zwkt|XssK2fQf`VMaDJOVc%v~t@U|A`0aa=P)!4%FJI1 z+Nr-PmPgosO5~M$ZwtAs1q;O-s@{V>J~Sw)lLF0T&2I#`JS>BAs!v-FRV9B%x=D#C z0&uR~AHrU2t zX%%gi-OIpgBm4Egvw#UdSi`JYu^9hO3|` zvjxJ0UC=0q3MO$;8lcIj(L*x$@>?6`kJUz?(m2H_g-yoyll1o1V&gw9uI%`T~{wQMEB=y-zm*W@rS z2=AA}GE9820Pz$W3%1bAPAoOZoh%IpDK!IlxZ6X1plnESKXu~&HuB|eL0+_zGg1vt zzZMx+bB3UN3@+@MgyRcYdF*xWf)wAwi)V1~59GFD0O|to1vXbs)ko)mXA0E|-Aelc zY6_!jsO}|;O!77Bv+OP*&zwJ7sX6ibb zs8a_snrcV35&@DL$Ty;0y4Z(EY-p--BEZzD@?mZSX40l7T)62{2 z{idrlG`tEvYvRH|To}lHT|v?*5_8T^16hYI^@*2c0_<9=5hz->OdQO0cNH)||CmXu=Dbs=G)8)gdi z^OVSqK@Z$LHLjzfH`kW5-1jXGi6c7(pp(WEbnIF-l1b1N&O5^qJ}?iq9oE2{6cigl zE)cjM&4+h#TaSPS>liH&8XV*_xB-{Tia|Ih(#U&h)=thMv+Mv1v?;G#yKmu2gd^+N zvwu@h{Y3oKGnS%j+wjPc49o9i``5NfX6X6+>oJ}JdZO4si5nwCH*QS5tZ z_qkRj!6Gy0_T~algDYU?zymoOBu<-y4$JZA@bIg+FfE~5-HID4p7Rn~uF&|n1nM+f z9_2wNs$i;;Z!|to2A8el`reVPU@$Ri1i+%1(b3VDU+IV$F0o#FcWI{?j|h9P9Yft21g_j9@qHXFP3m@$ zf}uxBxBTZ)SNGU7R`-%GKn_%dxc^;G7B;`U>q9zEzgMV~fq%H>M>g3wYrE`XJ&|;p zb3X=Gt(~FZAcUub&0&&p|JqS%mK_!R)a8z!N4x`^9HR7yS482K$ywnBYR)0V1*Bnu z$I2j;EhtL{2h%NUmkN2k4RA$T0EQcJA)P-H@^g~x(%=PkKU*bMMe4MG-dp)i=_cJ! zVB-^($RL7c4N?o4M{sXkq9<;=mu&bI2IXF3Mm91(be8g7h}Hl8?19LBA2~&z-};xD zkv^Ec-c!Lbw`xs55yu_G9?*fgEn7oA_5g-e%my;SG?S99eTg8tZRe_2LRdZL<;>|a zBw;jgkpLnN4N$Wi+iU}EvFs8!)e`-)-n(jF`xj{B_P1}}&Vk$&seX)jFZX+&BxF>| z5yeI|VwgqDbwMGeQnU)P4LwlwRVaV{Yxf1K8JH!&?u6BwtCl5PJ2kCw4@`^Jmzx+} zhU;4RP^5z_u<@(#(R06kaZ$%7a(|E=998VcEY!HOQhf1;RiiDgK6BB|7r6T~@vV<9 z-o^fAqh`jxfZ$3217qXe2J4}SV2`!S`@ToqM@v4%4beYX#O)SGyQb{HFQl^mEsH@Q zQYxugPJImLku`i}x>+eGXS4Yd&z=sv&Q`9UYiElP*-?(JAbYiJsHwe2e^g^%Igj@l zGOT4(!S@9UY)Unl7PO9&ESYx?gnH)v;<)~!^ywSrR#D2`7X3<1OPXQ37yfraDqf}T z3y@0$!duj!PQ>iSiu{40shVeCctCfk@U-4P3_`4Iy8q`aThF8_clRj&zKv_+K0Tn8 z+O!yY>{*9mnB@Zeq|I}QczG5VCcw)(b)oam6Grg?mEZrtp~>~pWt`l&k5d2=G2jpl zSWOI)B&ll=tRX}JC~?71OsM1%K1FloIwQ+hVIp zpbnbm{TyIT;<{*BXdmw*N4q71Vf}{u{<;+&)PFcY`N*At`xLb^{PAh{8dEfTSCOWi z8moi{_n+UxM`1#AILju{u!+I2989#8sk6#ngL|_sXomQLQ0rQP{hcP_|FV)$jkLP` zD-dNlYiXP5(%O>`V#lO>Vw8ZIZxjUC9IHI!IUCSMckshQ;2PiF31LaR;6M2U%I_2t z{~s_j^xXfshMtO@v$qJ7-nVzLK$N6=D@OQ_Q%()~0<p!;I>8dH^ao&e0J4&a;(U)T@Yf&j6oshREI z-uQ$=%07hOU-0+smg9s|6QOE@j=`D>K2ue?w&dVM`p6IgDvvxMbtmmUf(}k-npe4w zv_7uZ(Eg`2`oJ?9h742yM$_SNATQ%p##OoT;$MF{wOQ?dQJPeQEdQ-@mc^ zDkKOnIA}oirA9_d?pqiywSl-!A+G_=6JCh>v>F*BARe+bjZDUBjtq;d$#F(ub*0vK z`dVyUZ8U7WtsG|!w9Zws=sq~ZjT5Dbz@it(HE+2QiT4u$?#~?*epIDK-qOYYVgawLN~3b94v}H6c?U zsNSk#3ViV~-pe;(t}+dqYV#qD*o=(&nj@?y%Hi^CDuVX^@9mRI-Ym5J_q(C(y!yT< z9_{sm6?c@gVPkp54gvNeb>6yk>o(kKjnPn6Nl1smtwUB72lteB=oW`RaWWfkwIOPX zQV>mL*uxKgIv&G>9xT;c`&ZYXgO;^Os~Gn^kXeMw$`!?bhNpjn(;^Bn1|T~8``)iF zwMfu$TnlxvmGA&kh22zt!Q|xTwq#tUsXPdv#+ywNT+A5M+Xd5yHt6Lpec43Ma>`ZD z#P81=y$Snc{ha&n2PmFJnZ#uB(W}4j66ZsjwWEbE4W6y^%Hp&uh{yc|^Xa6mzqbcb zBQJ10?x$|3BChXoVIYmHf704>j(|JP>?*%Ii|x$nb)$cL@oWz?bA|Acsi4iUlRrw5 z{C9^rB1dYJ+BkH=JP6c@*V-bnr%+NU?juoKW_zEV&t=o$4MNe{=l+UJ>!14^KJYos zYJ4PA?>0RRJM<_9$Ven)LW+8;&{?Y1Qi-_@GrcnUFe8wNkhSa#h8D*3pWVe|H6IXd z`kx2%JH~KQ1N?xC>hb=yB@5T|M6ez-Sy?3XRa9&nlRmrnf#B-#Xwt>DQ&8lyk4QA%I zOVZYz5hrevjt2xcm4n&YtE~-}neQ{`W?O~A9Iv{BGSu|?3fLa1e&bopblxsmd!6zV zIu|43O0Q17jO>+2?01k%-QU>%l!v09XmYrPDO~QPlnG>c%frRJ9+dnMiADli* z7A_ixawh5%+fa!62h+56M>rdQA5YqU98bSC?@8*g-*C~*Ap%0c-YftF3hH0suP1K8 zSaN2-?A;xCv_U4G{-({YySQ`4FnM4LWwhfe=!?IB6ucEp4j`3%1TDcD`shb4BOqGN z=q_XJuNx?s8q>%4xf>N2U4=JS4_eLpREJk%aK$OuE+Ui3q;<&)s213Ox1ClB0FW2p zsZ>{Yo$^2XLD8C;3w*iH?Nrn52D!uj7U+!wc#f=0a65N=r{4jXl7IR3keeJF^F<FZ?+Kh}I!?-|gDLiF;w87`ZARzk{*y zdo~1}67aa)CKgI$6X5;0-lcKzzM(0oGm3I&mi#y!x+$VL`{Gk3C1NkbtM7Gfg4 z8y#N7~U>pv~KO`1~NnqYOL9)>|I9 zU5t^>9#lD?C9%Wm0tgsc$d|!ni0;|L^DUb*)YfiL5)CW@KI%w~wLl|hi5aQVCh%w^ z>VlX?=UJ`gPof4(de=Wu;|HZyWfBJUlxho3*+(L93pHVhG!9%-pZ&+Y_Y`;L_y+Tl@A0w8ck1=ZQ4! zNddFv+C75CYzD+f2Y&YgY)Gf@1g+9Ej9XC|w83oA@H~0#G*(ogPV|?vLZwwZ`EJ{K zX~oPl0Se2lfRVF-Y7RPg$A+OD2n}0-gXGE=pOj1?Jlg$AB<@qz5{VGa|Azy$u!#>N zD3By<4hd-n31F&bfU}{3_@p&AFE0rwthd^IL%}zs9aJEERl<_^Gw$PX+f)MnD0%NA zCW7L>0gBW^zeA$j0UAJ_iVg#Yft7#wkq&e+i?h0678RRJ6Qbt|BZK8ZfP()@J$}HU z1u;gM$<*`r>wn*V&1@fxuI$1{R{b$pm}X!MhRY6pb?xi@!|j*uviI#n3ho^s2W}F` zk0>HFc4OIxdFgCOzP?2_!?N+~{?b8@;5(Z4YF({?Pmpt^%W#ACz)5O+m^36QC->PW z1pezb*LJm&KTAtORP~V$kAneqmi&WD|K4c>neB~o2G;8*1s}bQ67ywdDacGbz`MZn zbvmi-{O$4Cb`Ve=3(N+4paq!KFS(iR*V8j4ry5)Z&%$lbj;PC*#mT=$3nx;bbO>Ge zTZ9IA_^@{4;=ePhWuypK4TT4G?Zt&HLE9QHyZB{$5m(Mpy85FH&_QS}PrupgI#6E* z8DewWDh79FEA*bD9)0N0HscTYm5Xw+VrR1AdnNiLHtmCbF6MdSTHzkhKos|Ua;uk( z?JTtjsJja~MF3*16;i|$2yoiK!}8{s&&z@8f9|2l;y-`}==UlSbjq-oQht7-ZC|+~ z+d^Z^^0zTWw?~sESBO0e3xQH&5(_o%tAkWv2k?gX$5i>Bz2Qn7P06YyK?=Q48_@gK z`Ymk5&*FAtpxEaBCE4pbzH3E4Re2_{1zD;UQ;Noay5^g^72mAG&I*hxP+R4GzV;B1 zy~7fl#&7pH)v!uU6{DsqY^|CO+p_*^$Zb*nIwZJx?&(ssWs|){SMihZpriPGDUbV7 z7IZ0Def<{_pWvR7VH7n2qEF7_SIdvTm4UQqp$OPnFrSxboQ_T58Ewld_X5`80=dm` zTR?)?DBtjnQF0zze~%-y0pB{ipy}>)Z|mB}AM#}@r{_6N#BJTRq`#xEA7(7$ z`y|tg@16k7=docsI9fe*QdKCApBvbHsWz%{kTqoZ% z-JLs}EDUE9UDscgn>%0u-`bkquObwm;(Ikv;_JPnD~CnsQkDhc$3x3@ALiwjkl^}b z;x$f_?5U%ixvOzKJ={^T7cys&zKiA~C)c_sN7UNz)6>&_s1d-)jPYM(bfT#GjyorhV$KKtzcG6DYUBY&@sOGH-pEt-@e6C`UpNtDy$j;uD8U>|An#!73#}4FOvNV zbW>xZn8%QuJsOD}yMV3rDv%nhfqLrFt7ooHjUe-xgXZ#lxgZ1sfWaNnn7{{eNROZ% zIz_;w_(WQ)I(w4%y@(M-4oE=N3>o)Ssu-vXt&30CwoAGC$48XDCS|!DOTD zMk3h!p}bgYo^I39sQHlD`XX>tkfYp8AAUJ`EbV$U#jx>*8wYL7xN%HndoeiojxB*q z$<+vcU+U4PSz}i^>u@q9(2iE77?b)F7c?ovF|>v{t^`V(=g0WI1=|MR{5z;=Z4v%q9tMHK#qtN<98_yqO0`aj zwJ9pLu6J!VF8QcrZ;zr9lhD$>`wt4J-qnMGJ9Lt{eNOq8&EFO|OF? zSn#!KrcD7jV%Plh;ELFuYby8rerG=fe#AzmJ0h$Ea_Y&9JtHWv=g@~R5}&oC zs@OR@9Oww4a-V0R-ZqwF_eMw@w7=Uh_s;o%gmRD}0m2)~mG((~gm|z6=S4s2e^C!g z43!9>{co<8`cNmDrmFSkGGd3grw3q&v1qH*#>yUV`ZxRTMdtXCgEjQYh3K$H#xj`; zfnGBQrM`z~D9dM+sgmyXd*D9M)4t%Lf<|l|{WiTZlJ5hC8KVD#%xy1Xk6@Rdfv$X_ z&j;PWhY2yloB4wD$S+ftaj}iklc3-v#Zao*;@IVdZL}QKf7tRZJ3L3r$2>;HQ<*w2 zlS8BZ#{KqJ?s>xF-Zcv#Ye_<_ZfCpZDz^cS;9TDiRYSxjWD!$zRJ)D|e#_mM^_*#v z_IsG9o!-K%Vat-+{NSsou|U$i^$HB(ui|LBU^bn6?k4x!i94)zLY?WEwMvvX&$s8R zx+%z=+bz`>apg0AN2S~7ta@oO#xj(;#rolAt3_b)*D&~uk7{UZVLPmp(*>>(#SOVN zUZ-W&?#`3dUjkIJ=?FLxO^;(QxUmC*MVo)3sY4vbI2t_-4;c9hxx9&-M9?H|2b8ioF0JWo%7WB( z1_qCWls7Oku{V?t#~EI{^Y32@Z&!xnJByq^!0@g7Npy0j!sVsi?ilP4OfQ<#H;mlQ z_=9n)uqM?QDt;PxXVfyfz;o8}G5PegPJMDq{9Td&FY(H^kH^wcQ=fr`DKGtmOR73K z3I1#SQW^C6!kz|&HbT+1d@n0^fFl+qM&w9_k40Kg*Huy_i-zaSfvH0`ny%eSl}C^lR<{>I+L5A4Z!?A8} z?)nDLwljZz)nkb*;mr_g9Sfb6V#lhwyV!bD3cB0C=q~wk)7`Og$jMe3KJ!<6{ba+@3X4-HCTni6FD0(<>amfTVsMcIL{ zksNooOYsHGW=ZYsMV5cJ#)0a@vUKVa?%uYs3#ZUh3|5tV{Z2gZotrBDQ41xqVw}$H zxpim5hjZF{bd3ay9?RaSJ%ziQNu7kJr9KjuDHrf8B2xxkrsray5OTGJ6gs_f0S5kdXtpL0^!nd!f&Yhd{ zDj4e+XIH2C-e@}4%N<)q$Iy8E%?0}z>yDh%{I|>;vy%;W-%GuF)5G-MwM z=54d{q1jqKF{GR`wBx*+RogI({0XK~s{p-x@*INaOQraVncV!&n9Ekh)cM!Ep74|* zlc57)&@f*{-^pQgpZ8)WqG^OZdEuq;}he>dip9AU1A1JvZPsoX0CQK5GPnZOdRD zVjB5^0Xt|KF1Lg@>df{i?9rOk7rORMk&=DJ={VT(sHDf|({@S6zoe~bPM$*8y(b-ieJS1GgSD0G`;k`pLQBgsgv6 z*B2FIVd9!-as=uc^5!s=IJ$o|4XHg}#`xlAH__yNDP`)+s=RY8wqoU1XnvVPm4*6% zBsCEFqqQ?H>G{M+Qvf^9RHKRHYZr36xnocwfR(LRqPys$#sY(KGT_)oE*fpedJfgZ z;LQBPm@mqXKZjf=ky8h6)qK>Ad&eNKBH{7iZV-mE>nJ?AtZ-(I!06Gfi50i}0Qv@YxiL>PG`)TpmLEx9gZKMWr&lw8_` z+TbSHJ43tM)ju*y zU+?my7(EPI(xV0r9OnNPB>9bjnO#Opg*lK>T#SlyN2c{vE9bkL8e zE2KaiK{nH#c<%B5l}E%@!sj=f?{Ly7tEHRsz?WC|Qao*uRH=rhC1f zx>r4vEPg+P(T3wV1tvI8eP1$i65X}B&(4~Mn96pF>z8rq{(SR)&I8;-mfPLBVV}e7UGXKyGV3eVBOI>`!GkV z=e1WY5~?dPARM2MY_;c(cYtPmWS{mKagCl4XwsbQWS}9MwyIqTIe+O=98XehM*?)+ zY}=cNVeZ802UF9uY7^tYwi?k=`pippo?u_LZ53gbbtOaKISEtZEWq$)g#8t#8McV0 zz8(@U$$%?QtAL!aE06dt-!~J~D_Gmp<;q#@3o~^~^^+P255_1Zi{Awk^VpN}SJL&f zD`%t_axZ=~ab8NETGkPY@?}ygICDVVC)c-IbB^P2nTv73SQX$3TZ#Dwcunn$*IwIu z#7_Nu;fV~zGC7yHje~Y6hS#kXRtkjWBBd4i?zoznu!Kb5>IeZ0)zQ(hX&_wDKT4^-X>mg8BHx@c0u3v65nNQ&K z^z*k2Y=1Z3Yw6Gh#f4zKpY0ZI5t={8bBEM=Q2ArJBN1cK<+U(+u`afh6>DHQ>;e+) zCG3vxb{aQ#%fP`J7dWKN882)s8PH4NNp%3Ryf!FbIfkYH)YFwn$x}Tm2S*d{ukA$LS=l7^ftwh9BG;9i?Y9i zsbLWEgfcMd15eBG^L~9V^RU->svIU7)qEG8=%o!Un8*h6{cE9Tttn?~W|}v)0zgD2 zDa|%*Kf-m~TOF!bAGlkNzmO-ZF(1ED$aEkeO;?NhX#)QI?3r*f!jo%t+D_C^+bLj+ zk-h2xk$)-={b<){p9tuU@an#Xnn|4@k=piL6RZbtfV=|Ru${O=I^p1YS5>noSzPWE ztq1RfR(kW0&L@TRz_M61Y=p5>jp$KnolwsiXt!*oPj#UYxu-L0UAD43zM^kQi0S%< zj^~^f3SYX4o@S^hUXkUK`&;@&IjXW8+%j9J!g3=9){x9UsRGt8T`-3SdOTWgwE0(RED8E5Na z>lq}v2gO+r&kyD zrR#symTv|2mz71ym;mO)A9W>5 z00o!m-Y`t`amRMK&ysR7yXf$bcGr1z(&Zn%eEfqW+c1#6l87xtcabLD+6R~bM*k7^ zG`Y4LCL$qUH0%>8AL>6d7!EbZ+s@{@11;#T@PpywlaMO5+2s!=*0ZvPOwL^|Sulzu zq@$B*K+~;JK85mlTa##mQvtM7#DIa_I2_`eoPEJMxsr_WG(jj)ZF4T?8m;X{!N`m3 z^h%s~%zz4`mjdISnfW5;!A~!%<;W92;>r0r-Oof<8Q^*nYjM{4!kMULdNoGs`S;|L z>uBnrHqCah6#- z@OaK9m2PEDKJMflDv})_?l|{kvc;3?JvuCAmQjcNo)F>17ilnLy^ZgR( zcg~}JZ5)gf63`2@zn);T`i#%iJ=0}!hvgUErd8&RQrTGzwKU%Xg+~dRmy4LrGanc; z%4c%E@XoU*cN2H1sD4hT{q^$f`yNLu?IvkwKC0D~_1t$ca`yDKef%A94MI|nw=P2q zF4DNXFb8~X+JO40LMSvgc$0bpan0IY03-dLF(REz0xz!u=7bfXdA6b&yNmJy5Qqj^ z#d`+awP2Sh4D%5`!GuMP33~`xt~Y6Gg`P5Z(Gt7qY3~M+L#2D43;pal3*!tYOY0`< z%&wVTBaL8lNm)qpeaSaf?lcEKSk5`k!24a?8M#RM{Ure>Ik5@y)BL1!K;fk0Ow^(2B6} zs#!u_ufDy(BZMIKR)g6p9$U>rw~FonpkynkJljDmxM>&&E>!OUP}mZVH67@`z=Z zai`;hs}JYqGB=PpiYap0@3w`{G)VkcTSU!{fUp@egN;kQvq$gZ)*(f5=Qj&&SsN+J z0k{Frr&({E;fIlr$C~iysuF~aO|YHZjnO*W?HDIsQXNfKkw1<|J|Gr?B~{-9_}2BhFP`c?4i4C& zLXY6z;5*MJX;)ZYB{)^wWNlSQ$(`qGygspri)j8)mSgc9%$PofXomp&v(jF01uZzaGB(TfdaqrGpW#^}2IkcfJ4GKWL3(vRgo$DR8H%2`d(HgAm2HN&X-(OBY>iQK+~2wcf274LJ}a1^hN zc%NS=BO%)FFDk{813eM}3!9W-IHOW|ZZ8AOsnvXV0Dw%QaRaXa9Pji8ozeu%$)fyR ztpbd3VZLx<*x?(Wq+}R#uRgz-2$Ryrn0A<4>+uJ_a4m*8MWW43-r+bo1FZ7v=!$Y+ z5!(V(I>G$*Ozo?m+#NRH$~Kzu?=~mD?gM_cg~c{I@9D@zK4YvHV1E^>giW~Vk~6r! z9-`I4;014e8H#;1RD|*kdHU9eH7|oop`y4npWxj6SBXzkc}GHhQv?p9juo?M z?V+ur6^Tb6HDF`Bn0xgfQJ0Gba`N{5(M|!f=di}AQDQae#Mqt~z)mC&$c99Uh1uL% zrnXcYfG+=nNWOS8%qH7m4l%0Lnd;^04Jhx=q+)J|322&Y9nCo#T@)a@d_yB+3P!A> zz@Ozg+H2#WTf{>NkQ&PX--$M0Q~DLa&|Yp29WXfCWq~7i83S`1lanzAG*kYfx8%uy zS(8D&v!%t@q`3>4`PzWG;PT!|J1>YL?VuyRl%tD7=5k2}KypxSvqP;f?r9fwb@c&7 z&u(Ssu+jQ0Noz;~DoiHMOkNgHa6JdIPW_GzoR48FtF?!vXt!}m1|ph28WFtDV4h;O znLEp7V*B^`&1dl8D(?jIf{&VfNb#Vq-2kKo83V;20%OizJ{gjEc>H%S;P5isfJlr& z(H$5?efE`q1KoxGnR3P{Bu3o*~@kD+CX*0*`3$68a zqsAQ|{B4D*NF7o9fR;l*chD_gsH~h|D*1t7s}w@yfVpuB(B~4KtH__Kyog9qA?<>U z*LipRgmFgF#L^4*(S0jF&W0X2YBaX;DTv|op6b@5z^i1Z{5Mxxb@EGrFC84TV8DC| zgu4yrKW-aoW{pKQq;SxX3Hm?0vn^xhZ&4W12W2Fnd)3K4|HAzeB&57t-yd&F$GXLz zn{ZF;OA(Jhggq1>A1+{E?$&$v`n}$FG0j>flmawdgKklm5F`z}jY~xF#vhLo7@Edm z3bS=qV(e{i3e4x@a;7wA#&_2ozLCq z1L;Gw_jom)ksUy&(f|&gBCAYWv%WS+O7(>QN`9aci=hX$NG3`G4-WLlnsOCEj1y&W zNQ@a}v>4tO^z9^^p#Y|H1^!lU8?a85zMneI|72WagYMvRbf) zZ%gN*m0_2(|IPzn55^!JeVtAb{V4L`HhD0OeUjO%@7tT$xU?_&dPYiYp2D`{hg!|R zQ(;^4mDd9aeL+&?T7geI4!rIKdP50m97rbg?6>le!%flQS?G`0Y909o;S zWPAUM^}|N+i3;vBY}-XOV-LJa_7LE%b5YN*sYm_;iLq@sp+n#5PvKpfS;f5OvSM!c z%|OZec13KnXqcM1oTFKeQ_u*%4{nVokA@B@R; z8u(!~exW2TdCNPoefX_Sb+3W{{H6$OeeJaDXFT8>hL9qmI_dw$YP(E`p5Wfi(9Y4; z*z?XbMpGcys<{&QPNNqt5M*$QTK@tS0%@@E<|FhZ5N2Ww(vk&n)sisS8v%)&Z18#L z0F@+_k}I2Q&r)Z>SbDqIdqX?u7AB>q#ryty@)2Is*zoWxZG;z9=K zwCz|~tXsJ?^gZxW*DFoy|!V@u! zbp1g|qg(baDav*5)BE(Zd~5)41L|9FeHyaQ#G4=4%I*;RVrw$a>p09MmGx|a&SkFT zTKbH{x;$}L_JqUS_;L)Wb1yg*Vm?DK*6=}@mS{n%;mqX%plQDu6*KW@U5RCL-HY5!V$pl&$1&#xT zV_MC81e|$WA%Pw>Puy0Eh*hqTc85RRX=s1v-qx4oD4cJ}Fuyf>Wj-X$(5=h^ha}K< zQAtmiOoR2{Y{YPknD=g~Ui7}lqsH;d0B~o~-F88LUs2mZNXycq(oAluCX@RC{Lbe* z0Ho~B>UVJ;xI@8&E}~1Kck~)txuomJfL2veGpqc8tmoFx^Y2zlb8p%}L%l<~!G?y; z0a`v@Yg;ntIK~*TOtUwL2XtG4O`|F?l_7DadP_S?qxxYMP;q4VQU*%TcX5{P`1KON zeEFukZ4xHB5gu2ng-=v^tP&T6ELHcG3ag4DV9a zy0nT1fgbzvJVSjFS)!=r=OaAB3`;WkA~u>gL!*SKo?&$^U4aFJ3dhBy4;RMGez=F) zUksW_?ppXIuTLH6#gb>r-E1ElVBpCc`d=Tea-v9HYmd^ObpqYPCon=>F`mI9VRPFq2b$j0{IG~$387bx#&Q(WN?O}mLb4cRsD;!jLt_Scp&oqJZV*q znqanBhzp}92+;SIZj2>;tnB$=j=4RLR|oM!fqcfSzhM|Cf3Mzp>)4(o0G2<4S^P4N zVejkMIOIWPuMw-25m<8Y1!UWL$9=2e~10sE}+j zczE#m!}Mty@&$;L2yN>Q*%(qQk59e5qNzN=1*bZ7#{<%#5g@xwCFAW5ij48lLH6iU zb>fKrT}8Utn*c;xvI$BKpHbTpikWA4t93EPwBUqaSu5_tJj_z;5e?FnFLM#nqzK;? zUv^cAFEkIUpRj(8@hA1Zq%4^{xi9>f*C{dAgxn94?t6pBQ%6V;$Vyl%M%ZI)JK$K^ zLuXF5jy5*9oO#bYiQG!~Yg5>bx56?!g4U6aXw7S06T0Oe<+5Q<@#Lr^kxqMp)=g-R?R++j92n(V{?90*no*mYDLj%nxA8 zY$+F4GbqJ0s(6HgJyXgrzELU5X;NcZc(de$=pK2+EkR6bM2G)r={p}Z87qo!@;C)8 zmogjvMC`@?%aRGA#z0QwC_B_)PzkLMj`_FW5ht6$XJAy&mgtjG5yN`MfA1ICV_}S% z38tN_c5llVZhe2IAbZvXqz|>3BYWA(9sTaI_ZKL;T>vv!Zl(AXgx|Z_s5GGcp)7VE zHf%7S94=^L+;@{f?&a{FktDg^DX*=$kn~a&m`*(PjhS_d!`%1l-x9{CI0p!uj*!>F zaD?i$Z9nLJ;RS!@{N{O*FdY~>{p$s=13j}G`5Gg=V@gu?GoFmrD*X#3FGGh_vhw$o zEkPJafppC?=lXb;sZ&yl`xlfKR4fQL@!Wavd{chyQD>EpN8B|20mN#wT= zkK|YM)y0g9p6;xifZm=UtN>kX`WYz;NQqG(?|`y-u@l#a3(u%o6|$A?oJ8?>x+`XEf{Cb5?d<-QoytPfL{b$w!0- zT@yQg=6?nYWxjFB%hLKWiW%0_-IhgzFlhYj4}sSytnfiov7f5Z>kNqsN$RBohTHAG z@b2axw#-n$6988l;k!!QyO4$E#j;KF^nmr{l*UG^i&E@39gCo*2>RC@U!916l_o1+ zwtHJ-n)7N+G$INBbo`!s7vd`SxkaUrNOPuHY@l&#aw^)L8 z)pzI%S-1eexDT5GcSPT>*Mmtds^ax2I%S0K;elB?+4vz#^gtVr1SA&;%gzivGk|Ap zN)LY(+mjt-m(Sxo0Mw;k^Qxvqrtov=y zQfyBH=gqfc*k=eBPmitOlUskb#?bb+5zqPu{^^Gdhp+`2}DnB?KO?z6m3Lr2Tm;;jbaM$+7Dw~6sqs53|TQQt3H za{EgG(6oLkps-mm&PTuR`g@Z?0{@3_7KnV``c)D zs>oEacH-v>xvzd_Jt$h~+jCcm0$+^%|0%IDa7R9(*~l;LDs-}bG8E9s_# z7L+u}f$kk{!M7{B6jY7#4s=wERDcI*&8eKD-`O0#@SJUTs4)Guy+WK;CfKX*Su@-aTpaTC&Y0VNe#iqYF;)@( zWdSsTzM3;NUS@IWK_xfLE~_tfn@i}-1uV_QJ=q|3ZABek1# z&|SfyBrP|sAgyHVuT%x=2Xpzc;+7V+4ZdE)q3lw};)1iY`7g*!Scc)*GuD%7_gk0^ zbJ^a6k%aZF3ws>hL~gOoEH-$0f;n9T#@NsEtH5CqV1UH(b$B?ay7@gcj`y=QzWL>! z+k3VqHal^CDjjC6a|NFJ`>q>}kV9YYmio#ZTnzR4Jf?cp#D{Yhu_24B|M6dg3Q!S3 zcGe4OFdidb|9sY~(3B_Gj0vN~wMNfUl`A7vvh22rUx#$90`&hz6fwvn^)gQn*2Gq- z>DZiQrpGNtLuJ8ZU}mP{Y4)RJWyziutdlH>frkS};;Als-ntHYf(NhvUBn>}{9H9z zP9NKp936W$^Adv`7n4z7#k0yL3Gl}zt9WW^8<-*N-HOv+MsTcAWmL#ywlJoo$bAH$ z9+T9e8|+A=vGP!IFT)$w(Rn7;feuYl|N?iX{SLi7mE zI-PJMQ|-xCQMDBBbLKc#B$%Kq|M;fuuA86_I@G=BZkDs4Ws#*92s_kfZ~Z1Uf<%0Mo{2dRqMe{L*LTbQUES z>6!VP06&a+9+-UA-J%=7p3M1aEDCy8M9tq^Iq#k}G(Rj;FZqV+5hI&|{f8E(u9R2qoVpz%m4 zl?)A(@>}{F1l667rf{o6xX% zYr!sH;7jGwhIQfUmC|}Z(GMxkeB++mkeB74Lq?G8hiTm11Fw0aqS4g zCh@6!GC*gqyxDpYCoa+7V+`rM<&&qGDtiv|cCQyc^($2Up~@MSf||?<9@p7E8tk#_ z^s8*O9v)uVFr{Mz=DZYs!96q%=UCMIic2(IqMLZNT4*p(`6{)Xu@+i{Q5IJ0tt8l%O^U; z`l$uX@!Q6f5}lHg6{bcF1%n})N0}g&=ePjEe8_Y9>cFP^q(SoekmjR1EBxw0qYSYp0it<-Vw!YmfWr3&68 z<0j23Zuo9cuXv%@`jxQV>pptx*E&LJ+NIL`n8}yErBerh8pJ*Oc7811>LRoJ;}g8@ zE>cacl&Jlb5&7|ci*sUjN5ZF=f%TFri#~OF?J@z_7suipypbwu53Y#lu@AM0TRY(Q zb)ep@YyQ`xoAX{ELT#@+tbNVz?b{$9mA@5dXYHu$#i5u4VqR3Mwph9JPiahH#I1ca z{>Rv-+w^ize)#G8R?B;4>+sa956mw-^sjneUj#zNoq$opGYTp?mc;>!wmm3%eocP% znJLEX`K4!kcBEgxq=V9;g(2FKLyv@>Yl2XUj?)37tG~s%?<+Bpf20yJ&FAA+S1uNm z);HSGqo3c7%8cQ(DsUe!j_$HcDu%Z%DDG2tgnB1R{X;Q58VZ84SV%_-Y%NsHMu(ek>Agq zVLuBuOYZ8*>{_8OlcYYcvutPg!&o=1`V75@F`^CE*%c@_%hy8GC5D(LbNR>7B3t80z*?*ho137&?Rp*1Z@z<7BC@ zf`N>M$vlJ7&Tq{{gZ8nyp8eLrOz-c#_A8(b?2^y~y6dk)1{JF1s@oE8_1l|yb(Q=C zM1SF?mAjnOy_Y>?5b5(oCuv7<-59s%u&`VL@&x27ZOzwN9I~tZ^4?g3tltiZm(ufjqTeRh)}JnK4R>VZHKOPi4q5$b ztW9)}cXqSC>8gRI?8;eJuH-)sTAgJoc@j92x{cEitdx|}*L7vYH5Q|xeM6Gh0~q@` z@5-Zkkp_~_H5V>#@U1q@cb!nOAxBEVe%$i0*_Fq#C3vsw@N7as=4Suq&IXewzUjM; z#1vQ3_&(J`PxNz;$gIi;nU=u7ZR(p zptqYigjZqLv|hP=>k5$nkCpOBZ98a!4gd~JT1VO3AE)|s*FXH6h7r~t$$=Fn0sp?# z_~3hT>_}14r$Vi>7yFs3X)sUQ{5*3|?<`Rg(F>#n3sHXtNyhD#=q~mGhV0jG#ekYB z*n|oC(2C&ojZQ{ROO(+w-(OO6KrNKI_f=?sfbX;)ROprv$W#~W z8F>v}_(^;dQ+)D;> zU<$2ScCX^B%SqGfY_~M2bo*JuMFd**uzZVZDWG2@36Jzog@b}*?=f&NKy2-#QEWQcXAWk^<^L` zJ{~OUN%QXM1_<&KAM;He*ORA>yG*|%kc{EOP*`x3eV=uBKZfj+hzr9IchgrsU&#|_%egQAujURtkmgKoO+@DigS_O(;=pJXdn)1}YmoQ$&=Cmit^JB#*;TU#bK-L763UM`EVW zVKmp%C8IG`tJXZX;4Ew9=$JA(LVhg$7;Hs!S2y2!6rLZsnNsmv#K&iwAgH)L%z**% zp(znQD-bc%hL0hxbnVx#P$lB zvR~RIO)R&Ozr46<-9-)-zzw(L-Te_Us8>LjX(KH8kN{ENIl1oa(?%zYj?86#0N;~C z(nOu!+@;#)qPFC0B5OhP4~Z7m-l7*T4vo$=1-MllQ|@H+ew z#vh?5u{!g3S}xHy3M@HLTUGDcKEJF2U$^w|9Vz30?boeU_@BausZ0GD%`8ao)n%{~Tw{O1pI=siBlUZIdDXUQDOtbKwG01A`A+MX0l+!!c= z3ZMw1@zEGadQsO|;LKCO>530uCHHA7tj8Qq;h`3`em2>#ulelOh8a+DKZLoq0ty@~ z$>sm(*2pyT1<3rdaLAQfKcW{V_&~xnXN@lR*g;OxAr=6L!)vOlLh=uAEHDo{xXRH$ zL`Rs%c0_*6euCT!>&t1aCZ9BKOn*A(e=yPM;ptG5J@Sn%J#)9^QoyQWWZ@2{k zpTY$-5o?8V{^c*Ica45OwF~k$XvRQx)+2{>&4~;OMEb5k;$kP}qdRuw^!pJJ-`>x4 zLH9T9witdHte*@rMv20<3mdyh{5Dr(Lhl@nbXz;ozEQV%XNFF?_{+2UvwfB^9zR~C zp6T#q95k|sD4cvv(Vun?G#WZD$8XWL?tT;wRG(VUKEk~hbx#_K zz~4;pFRGLBr`xO7AHOXnk_kG0u0nBn7dk4bW2Ya_6^=rrN?H#75%0_MzELthhBPHg zetUQ)$S`PcCuvBmp6Ns9;T(Jn9XvY=&a%jVzQnJk5m~ntEDcvOA-Z|=%uexT zS{PzCMX7t@LNYQg6X^JMMEt#giN^9%Rd4stzd?B04>90_i_4xLRpwfA1F^H5#d-Gh z{X~v%Y9+&jbyD3Q)xJt*B`wd=#Hj$?m|_c$!J~v(a#>^wCY;JUm_L91luTM7F}z-V z!f8q|g?vP;x-4kZ^+i`nlM#YwOH3b~JYn{vt1h#W7iQE6uEuLRSawcY@~UK=VS6 zeSq;5UHY+X-+_s_=Vl*ZPhIV?ZAmZ?2vXjC`Y1wH)gs6`r=ZRKbXvNpgUnPBxwW1g z2LVoC;tIxzc?OC@HHMU(1aq??DjN&z%>VlJBL_b+5@m2r$HxKMlSKxfJ>0NlSSeSs3O>}mp-&6YQF!a(>n-&o`W&o zPB1IS@x?0WcYJtpy-2!+%n~5yjx)|_Pspi9PEU}d7L6@QgLz}}4|NnTew9qPUrWaJ zyzUahaM|5ie@NXG*zrhELEp!YBntBjk8@W%jkh~L0eZ#BRXQf3N~R9YORSkx2<`iY z@^a9omn#rBytnbwMv*EoyirA+>m@*q5h9wNX_g<>%R4e$q^Zlu5G)l|9iy;#@5^L} zP^*<5PCQOz__O=!?LpjIQ6-OlIQ>u$K<>)>^vl^bcI}zfKUrIGiA2 z52xsIAEi(3;#bS8APe_w=t~b^rYV6obDqvFLpMk3(EBwWCWWncI+#$6=*H{xiKi7y zan5IYm^A~lf)WGOX&>t6beVtxk7%~2e5HxmYT@Q6AVjWL``cWQpq*c5WLu5-T?H%_hOS6y{#6A_wR8!-qVbX{vQ=v+ zT~s{w`$nD*NXJ}Yauq_gIRrplo(QWOZ{Uea3Ux;3B7BkWvlNhWlBQei&%sRAS>|H} zIin+2TuRdqH4)KCq0UdR^9eFBavC?T^RL_2f`aUU`HY{I1YQ;tkY14!czDG}g^jwv zlBx3fN)EQ=?5W6Yw#yC_NM3+5>IewZZ z7^j0{*h*cjL)hmK4TVM;IY)?r;4$R3AK&3=7G=ML9NSs%x39`jl?$g#i+%e0C|X|O zmbG1{y4+Bv#qAjlI%CCj^zZcCKppHv397=Eb>7AIHkmJq0V&1f1A3$mM2meyRnN{L z_>a>ZCUOUjIseiikdBZK zaCaEF#es`E`*MC~YnP$fQC8lf{&ZW_qf?ofC0Xda26H5$lkVKlt;Y#Edr2zI)-O-3 z{CHS|JI0Zh>-B&BU9=#x7`{d2T~ihG-gF6&c?!Ycw_SqJ?Q+1Gv72w*2Z)TZ_2Nc+ zv5ejVY~iA3&sQ4G$vwe3Fbd`}$bk*{@T;3Q*~Xd3hF#G$OpF~G)j8j7av_LW+%J4c4AY|4d0XR3!-4x>y2)oW@csmDGe4AQ_RU0b zJzuRCqDT(VPYZWP1bv{Gko877Um)d1+IGy3QHs4V?K|hqaK-iGD_9>NTu}j+;O9^BV^k7uzjKP*1(cn-TZXDU;mly!wZrQJq-=Fv$;5- zVu3q?X8NIPn?wbI;-gx|UE~E1faCvYiY|qjt)oJ>akgv9;QPrriFhdkO)$|cd%5hp zZq8?M*wF2Px#E}mpL?O>q+;{%sN%^#>t~SyYn}?wMfVZc*{SAAk;C{u1k43|oz$>u zm>B0cH-7pbalSy7Xj9T@L#z7=qrIOMv{q{RWY}D{q|!MZ<}3#rC5ox~0|5=DFedYP}{#As`AV!Pw=c)}zOa zOPs2@KMLr~I1x*Mk;{avRO|CNh3}fL@8v4G;Wy~32(jL>a6u+aTRdu6-W;qgO1BX@ zxPo0L=-l@_tvBO%BM<32dW2$qWjNi5X}zag3`+A1{d1&j1sx@BPw@o4?+WdmWH5-h zpve2|FtIu_+U^mI;MSMRR23|RtDFhU489yJWM7|;Ag!3o=OFK#KcJ-FbQDmbf-yW5 zEXF$2TIGx>2{&io4I8U%6tD3V&bZ74>fi*WG=pIvJ_S-6#0_N#BLXpd(YpXE>*i0# zW_dWOQqp~z&S*JRfGebDdn|uxz&~||BAn1`-G}otl`LKizgS)Ut!h`Aiw0P9)ORnn z3owQt{QOxL!nvp=wePtwf8jzbiJzSs+(P0nQ%mfK$SZ$e9-xo+8FgjJWVS~0jqpF2 z-mLHeW$fbMrDY4UySEdusm%LiTn*F#(QAyOpo*m)|GMW`t@Wv;I1@KZT4y@9P3jRt zJb6HDi<1*hd~cynTPeSE-qt@l$<*TwT&OokQPwhbW7SgPl1VLt+ny@+3L1%^5kY?L zmd$J)`C(w_Bt(ab63J)gI?r?5e6c$E?LV71SisCgh!PTr%&|VJde;|B z);VI5)jfOGIksk>g36kU`M~1d61N~ibd(>JddHh|jA7BXA~_RzSGXo+NX&2$x2$8Y z1L|q`>_;4kd?&tp1;6#_QTEhUmzx_#Uujcb4XHW#(Oa-D90ANd>wk^RR}g~*Y|&g@ zbCq@$qQ&ae7LLLO!;=%9^g<~+T&LWU=syXZ@puYm z^SPktx!XQkO7m_vvBZIlO8LvuFzq$h&4FJ`W#JdBa2EE92JU<+;R1CZaT<;X!QUoG zYi!rvRUEopt8`B!-7tHD;XuT45}Ap}x;ZR3!<*n9wP#^=_cf%fM-Hs3MY67voRfS> zrPv)5ue(Qg&-hOcb;om*KAnzdy^#TUfpz&lvZ%)t9ylC4jvNvqLC1dcPj8Be+O z1aWTiK&gKMNIaFAuiDNxMVgyKfmS1`7xroNgk_eq*IoYdsv0_41oD~lZ7;DV3#t$P zc#I})yoou%^$Q>}l>#sshVv_K_gNCx*! zXv$MnFissw5PT{_pG;+4&KQ+$gG9!st%fV_b7RIuIXP3}wmEU?r#siTFcDVI!W#wR zO{7POQsZ-%k&)Rc&0?H~T0PiShndv&#fC%a6@Ab_E0de2eJSGM% zjykgAzkxoLDwDmC`YG4+lFa+{Guvn^eY&wH%;02Khar|%V9?gX z&ZhhqD6&=`Z+Scd9>;JH(Q~Peh?wOO&FY>|RLD^bB~d-gtzWL%6z$DGgYPaaSeo%c zu%kY^21D?30g2!Dh*)u|zY4`!yL;i;hJf7D%&G-u>B>v?fd3SS93ec_SOH~QDp-Y@ zVpW-#l_JwvN*8LNLwW!$bHScLG}#=1CQ-9ePGe79D#4oj^#t?}vVpocsJYMPV34c; zm@7m5|6gl?I2!x5vP=nZ$4}+Lw0*OY`?wU!->aH=L7IwmA&})+G<|d0VS$5sg#yE; zfNzkZ=*YebJAAw_vpu8JnJ$8Y};R zBLd929kQzmPBLT()G0f9F~^`6$S=q)X_Lf?chIh^m?FnrkXW2CLNHroIw|&6ZgvSi)qz!b6pAG5j*KG|J`$AMj1O)2)15%OhoU%(;%XEpC*(J zzgl+IY%(jXp7RGF5q^j3BU*8;}saoE1LHk#D2ahPAOX+NfVVAEQl?Ftun zHNc`dp~a_9JAZry1SOdV0uce|gkyR1o~ru(21o!H0cwUPAb^Z3-loknI+} zoRo*4+nsO$kBqYB8wSVd9TvZhjW>}TR#%LLC9GB# z*5rZg9;0Kmq}MCF#Q%1`oDQAwU1@v?^Y^;W$P8q?0_V33KS;#JlF% zWY01d(Bnz(=Wn%|0a zH1o>K5Urr;d3m4|O`{;%=<>tZ+nr!nrlQ<`wmgk!-4allX!lM-tNCu|g%EZq@>#=k zp1Uwa3UmO~EdIu1%3*&Z-7+fLw6}<}A>56_|G4vVk1)s5Kpd-t+>1Fu`)aWRoF0Z4DP#r549u z+dL0Y_eAWPpG+_3#up#DvT;RCcy2XP`xAz#(ek;m3M(zK+lV~>Z(SnKKjZ93d4A42 zQxh_PM5VCjDNI1c!ELB}fOnzD4l>034)DzZWLXtJ%^e~Yy50@@7I2rW$}XARC~MVr z`;OzJMuBrh&{2SdND`6TN0p)Cm=QY`Lg#=cKDcMueFGdm~X>x9g9X=<`%$+jgNRa`r1`ySGm5a0`B^kt}K-7#Vj|EyjtpO$Tuh-A%IG)eNiF%{=%f;kmf(yYc+Et+a$-Vd)OqW zO);&T~38^Eoiz%?>vAIE<)C9osw}g>7r_k}4L>uAj$*D|+8?v~7uVj|v*5qu~MUwXL zRWU}{7Oj#kOPj?!IxvR*RBTNRA^~Y1RTJcvO}TjxcrJw<)Tpao#>1}5IA24;Fw0m? zZy$NpQ&s1&Q%Q!w)f!=)cXs*Pj(QgXTAruw~SZU49P@4z&SeH~6Q6 zIb9TH;O=A<16@o)fOgTjhH zO8|>2>UI}mE?T? z|FL9o>9R&BES|cmkb-HQ=Qj3d%kU9O94Y*w$Nf?GQFrPKis*=oV1=I%n?ZgyUSFY^ z;9QQ4O5nWQOCmZ>?A1N_^+=yUx{NK0%s=rv!VT4yt83) zCi0gE@k0qRSF2jaA!^CLusQ#K8Y^;N1$m$b@xaaf+E0CPpbUs{4U9XaJ~Ui13iJHmueR;HfkoDt!T^`YF2Dn(Y)`Iut1 zhi$7Mle&yWDCl&7Y9Xh!V z(aSj2stjks-3y7AII>w4aH0f=wPl}5!_QFF2|je6Os?4fd$VHWc~*ZbJS2^$|7a9N zZ`(LA0Kf!ze%eg5YtOqvEI$v6MxFC?r)>I&!ZlVDFwO7;dHIxkN(IIR8W=UuYpJxwv>;E6S`c_hJ# zF^Si1IH9D=*zmf1uHA<;7NE95cWIXx41x9|olGH8>_)N16Z@tDCH`D04NAUFkhX_= zZPP*W1A_D|Z0+2J?Sgmfs^zU(# z7%#5R%f$G?ycz697rP$~zcX*q@%0;Wea2l?<{3jhg92U#dhW)MG&*;K>DG5ZUB?CX zVlGWy>NijC9Xnpy4hW3*z7ArN3?0}hp9p=bEJ$><*N943!NjwSTV&Ys79XC>T9Q6( zG?Vm4KvS0r?I^i6@vp5Tcb|vl|2%edW-yd)wV|SgD|Xz*OOFwcEQyN;d^)m6^y>`^YL33q$BN(81~y{CY^4dmsX;mREM|whJPD@IL_-gH%b84YtSm z$bToD3u0LDIp?=KnY(-ovtsG|uQSk`OeU0+1os|AqM*`Qm#MDr|8is^s&kXD_Z(3H zZjkbL9kJG>M77fQgg4aFA4={&Bf78QQT9OBASDNhR`znv!skR3*-f}o>le?p7pxy~ zHek8{#VE?R#up$x6Im*_BML~AuFo7A!S-r*&x)b#QFnYNrg^=e;?3udo{-Ly0^zJw zOcOmcV?02dO98-~?h$+}_{>V84V4z6b?p4h4X7R{CMr7$P2%l#YHv)Ww4~DStH(b3 zUWF05pbahnBwXOfHs(Synejo6GkyQxvBXuWyX%YP07~sCY;6F<+zt^-zv26nm&0Zf zv=ECV`Tw1?Q4gqCu5*+Vb2>ON$LAnn+;jL}DuX=BLq&-rmOC*NU?ddkN_8a>m!xSC z9VwL8(>5-Q{C;vHKYR!+QAw#e)n}ES9l_4oxMhns8GmpGL9PaZZ2M3_eV;%Yc$?u^ z1o;@!uqlt->I=Qi6H#8n)>YK@TR|&^^c!)*#%bK{%ACqwXpA)i)~y;i+U5PtT>wn^ z-@0`xTrvKg4Hm~puGnIaKe%FZD&P^cA0bPivkO=zYt(`rry0(ZOYf=iHi$*_NVCW} z)5MDgiFdlW`_Ja^Ch>rnQFX*`Mgr93JQ6C}&sod^14X29?LT@ozH#Qcc|d zU4isZ;p=z8@K_C~7JB|W)2=RLtu5J=o-;?DPhk#tMMY{6=#sGnDSpsG6aL;lmA8p6F zZ`JbJqCM>jE(IIU79uS z{(fD1NV>0t2KnFn@_(sm1f0ILx8$a{gMtyZ%Y&e7we;J7^457evxbn^am0|nwZweF zvM-*H#kY#=1Q2eI17ty;K{s^q@-Cjd9YC`@lb7BwP~R5|yd$sdXEXSoRhSAJe8^JC z&v8%8-ND^#oOMkyf`I#|`6560aj3V}83fw6T{@$jj1(Ed?~Hz#xI$BYs#r9?W|PSp zs&AQW=Hqc(&vDkV+!Z{s`av;y!Q0> z^+F|a;#641iQ{Q%N zAuy9vOi8I>$Eg=NeA}BVNrIBiY=Xq*$SuDmrUa|5O*vkx_V9LpjU^MEy4B`qW?O*D zPfqcjuQpHF#=!!xfX|dHy0P$K>nwFe$1k2hGhY+w155p=*ehr1pdT2udB#|&{b5wK zq!%$ti%RFO&8GMSD%O9ULbrNIpnJ?Bo4_8a_j0WbS!>s>4WB)!XI;|LBP{{-Q4-Qw z5CYw{xERv-W#!sced$f!4?yr9GtxeB#0V~<1A}gAnepl|tY$#2s802KAU1CM0*r48 zLbvfI≫$LO?2T*ujU))3HQfg6!yX>)I(|oZ7s3^U9}hodXl|F%zasYp&r*f`)}j z)O=&S%&n^=?Ivh-D9_f>l;d*pL<$5MzB@l4J=fK~qJ&L;>qfm9ky;6YK!WMAa|k=t zAbqd8Ap0J#@#*2nHjk?_##RD#fUFau{_)l|gk7q=WD3*iE76Fva} zydmGHntWT@59psU0IR{-#Db;pWwSc3AmQS{qGRmNVnQmwiS0}sUIw9_p*Ql@H-`i+ zX60f&Q%6GapSJ4!evWpbTih(C1wmTJ;@cXY*M|w}#T7_B>mKa)Qm;=Ws>}pLbuvB{ zQ=DF?+-@}M(Md!S2rb^%v)^!Pbx0Hv^2;>N4RQ7+9X^-aHk61Ne8E&Y(cSDs z+ILwqm}v;1$)4&#y> zXvK`@(Qr~`5RKZ;u<+FjY)nSSL`#@s&izth>Qs$+A<;tq+d~9iM!4Ozb~?X|$UV;? zJ@bd=hn|T? z#+rb8pq+T{$M60hRiypt(mLUH|Ls#zSGie=k0sCf)iO78A;{K=i|9Gl)=mYlj%Wh$ACV^|_yA4_!`ns8)ezr&a4;uq<0-aF2u6;LJyjIFf$l z_K;1#nm_T@$t27p^j)7^%eda%jP0&wlhpa*NM z8%oYkI)jKWAo-M@dMMYEXO6p>eU#NC1*&6Oj^DXnry#rP8AX<)R+Y?88bmG9Amwpk zC~n!w9|wuo^r|iKTMdmL*lu3+{F3w?1W>{`bo&@`tngP_Hzv?xqoU-NJO$y$30_Ft zQ~-jD8nZ_fIQ+bP_xTik$@08B(Q+ngNEh1DrAvF^TbxhEu7Fm4{

HgGpr0SxPBJ zcT;^98wda7Ai6N@vVPt+Q2QrcTcoIA8{5n+`RYl@7rcs7@fGm$RA3>}TR{?l00;Vw0lVAK9jEVzT;(Y_Y2Bq_str_!~ z$hO@1oIDa9p=Z&$S?~`gI^IrNGX4p7FA7Z5fa>NXl`WCu9&3sa!DJi1yVY7-OoIH( zQxU!`L~D43IE=!nDJZu|t3uDz#?ZITW$4$>@Uj$a0x%FK@4r2Ap)q*@x;m29bx`BL)+u+vA19W8+=FhxM*?lM{_yG3`A<)wpSucQ%OjU3Wq@xKw@i z=d0_dOTOD>WP>v>Qa%2};C|Tm_N%AwxMH(u#{bN0jC)7`9aOa(!%A_f8@IsZrQjD)kICz?7+x2(fn`ZPRs{RVH=x7L-M#7TaDnjB)w0 zRkpwHJ4n-~q_o{n+GQClUcII98rzguQ^j5=Bi0At&sL0hh@{v{&dqBWbGKV8P@2{z zlPk^Hc8vRz*<_blAiF5r5c-tt+D3#vXKkjcMmmjlx~EWyxODpVRA}8}<%1aCAqP#^ zDw;G!p49XAJiWyU-Qb*{(+2sNYQ?eqy=Kxjz0@jb#Lrq%4mT0&eqS%R>Re*^n%02- zIG9~{DMnoygRW&xf8Qn39Ax}Hs-4VCfvF@sGQFn871{N9APIMo7A6%esueZLjy9zc zz51${vXq(UX||uK;)X`hX%g-%7S}H6sD7~83r7(XM5D9saAvYUiysN=HU9+5GE8rj zgS7fFbfu&jk?VNzBf}b^W2vxv=v!8QgLpP7`ez)K&W}%jFG#YSh8-sM2^lR@Yp`(} zjEq(?GV|0I+|O~J9tGmdB@C!=4lLGBQJOq2@vNQ!QJlYS6-U~Fir#a=uFM3}d_{kG z&`%soOwG*Lk9v}(HUWcRnkY6I*o0cKdaS{EIj|{vIaSSJ%Ab2Ag3o{9t^?@Js_})m zS}C4shoX7*{#9wPiNDC_G3Guv{Ww3C#UJ_5((;a+v4R~vJ^8zGuC6lTCsdkQ4@^_`l|3J?)sYx$to`>Igni>l ztjM`+cmvv7Ao_3(ex`#g@ z6Je%V#}7rt-6`ZS!9PRd!xT|$P?Ot6kr~7DaQN*TTq7VgZ^=IDB}E9xMtbQ^zj#RZ zxg0DP7TIK!&j=;K(Sx7w7%4WPGvT~rlZWk{(UpC9fnxQb&9rpyDtuh@Polx|( z6mD)e3NaSnF^!h-RhW1(?lid@UeXS_zUq@Aig zX~e_)@mYZ(9b}aU&)Bf|F*=Xvz^pC}?q2a@Te5ga9`YS(`io4sgQ>F*<5o*j)=H^= zv)Ttbu64iNJG)c+kl2lKAP2s>-YD_rdQ`9Yj}aANu0BjA&9L!@+4v!hV4vU5PTG3 z`9^|?t>eVxK79$sFWR zC-*`l$Rf((Y9UdZ2Q+!vdv+%R_ugu~#xB^`K8M0g-P_1|%ZF2SD&0sSam zp6sjbZ#FF?=Xb_lzzCrLHeaGLYpJ;Yvl%25LE!}Tt$>7=l}k9?#ZYGCq0{;MmgBh# zsGTb;Je&#Yjb4yS-TA2_Vlb8|lXuEws&-+d13U2wx;&a%)!R47?3{ZA6SMUIz^`vC zE54aQT1Xbz4<{-GwVHZ<6;W0P-Q(t^efb|CG%j$SUTg|nZBotx%QBLng%|I!nYBjTV^*&4b^R|>j1E5MXory z8*Db9i(RK_ z>foVaZ%kTq*i;0MZQP~3b?7j0BLY4gC znE~r;1rrr8sP!lpfo4_UGAcQnz2V!dV#(9AySQbn({V0$@z>&F#_0#cktl1wbX|=E zmRLov6L*B>kt5Eby_G$Z=!tfMlk4<%S{VH-vCMun)NlWN=m<`3XsyJ6kWl%->8KMT z)RTnv2}8h#`r28%gKP703-AQ!sr;=CX&kO(@&|&u`r1Gqp|9bY_w@irw7DFBgoYo9 zGs}2Gx<&ijVL9kluV=MX0i)50SmEcqgE8of=7myuck1}>mn2g_r{2&zAuTA+E-tCF= z75gi!^6imV%hf+AUzKzuVGa`qSKi$i8FeH0eXF~nb6JIK(9AZ++NCt;99P+nWh?-Ml4dY0k5M$Hk3DOi(-Z?P}pg_ciXP*GA;;UG`@jXT(Zae&x4L z!K*hp_0xni(U1%9c1GsE|HkE!F8>P8BVFLTlc`~C!E5Yryu@WhhxV_ zgwskp1FjjnJkKyM)pmtTuad*Y{e7_i6$-ZG!y zQ}LI)x2Y-O#XOofof!T3aj9ZhpyCo5fG0XpJVbxd5SO$h764Cxs8Q)-p(*sZUTXh7 zslM9b;N>K%{GDIQq?5Or>{UNd8?|TEjFYb0S1pxPvgb3_U?nue`|34`ZlAA(#uXC@ zsR9)S65VQY9>jb`fFnlgmgt zXg|sxJO-5S25l!(Oe)r@?81@ygx7dH>zWPal#hS0EXy%hY+8hLgKV6fcj!~y94hHh zmzI;pXc`#_8-4fbuLSim?GvRtadajXs7Jv7V13>K0mbia8w74!%dp-)R<-zW(33U8 z8b5noMTSaI*7EIHZZX3xjT{Yq1=@CJUAAwyNk_8Yfwh;6xzOvy%nkasjSiEiU^qq| z+L@)_w^VN;XSr%p+#a66nY&DO`w6IN_z_AVnMoOw3D4C!aExcwU|_Ij?aDEz-;XXn z(r&e5DcjYah5E&?Pf?=xpwyt+)55BCJH+ z6g^@@P}P4bantV9M7uXR8~T<6^QiEcEVaKT+ptr zrz6i;VE!;YFX5e$^&ZMu+R6et;oT}1E=o9t|&E*dcTiTF2H+3S@NJgD^?OgXN2gQ4DZ;ew8U$e(dL;oUriwaB+`@f7&)gK7~F@ zLg4~n1kN!*Q<(tuY(qWkr-XGd3w2uK4zQ;iwx2Z3baCw4i8+x%Vb5$bd%zO~C@DNp zF)Wp+U%-93tS=4G?G@4mTkoc`{eA}9=Z#I#S*lH( z1y0^OVF%460yZDgRTQZGd5sUSye*n&<3gH2>K^wtn*4p+0(NazRDjxUv@(l*6unRn z>LKc*dh^E4Anb2qWG9zSBrix+XbJ)v5^=en$-ciN50CltU?A}j9inJnPuI@BXKI6vy+pL+{gE{i>BeUTi9hr>NF_dTmT9`V>YR79+QAbeh0d#N^8lxHsbHe#9&i6SF9 zhI&$dKlu3ly&5jh7LmI_mmljTxj53;rJAfNOk&HgPvYo14u8S_4giG$2AjGsPoXSH zM=`7gk(cKa@$OQ2vZz2*!W0hpxk?m2SLgf);i)Gq1^^{IrK8F)xOK&1tA5+nPZq_j z4;$XM3_Du#h|q%t1ak44x7PEqm~?oaZ`?*jLfEgZeqdksFohKf=eU5+W|bB(kM@Gg zCDcAw&yUDMM!lrCpvfr4Ss`WWu*Q~T1rM^Yhj&h{xQu0mO(QjQK!3;|%g&5%9sqDv zawr(jvWj;_f9q^5%!YM>_aQJ%`9Q5kCI%OvmGQ>V^TfR~1jr|h(u{vioDP4TuMB;p z^1~T+4m|-XkYnDQN->M4Os5x z5=CSTV*$hC&5c#$ewaKD!`?G400U7Y*=rc-dbq|oa*!spldt=k@Kd-rQsHq*#HZgJJ492HCdUB*Q z`_=wiuZA2H#6>k=!=mUSvmT>2=lI5qn!Rifr!pk`qa_3`pK)#Q{1QmNd_dqFykGwsyzcRDfY$2I-%h!8NZFYKN@53yr07+=XgqDoYZkjI3 z8k_s}OL!julACj@}mY#Ao0pV1}M~g<<9uRJtW3v*Yh4;k8#ANR}X|9FNZGioL zj)v-Ma3jz?wG<_Ei$Av3wORCgBZ3R-9(@LAv5D4rO`BZ8saypW3Q>0fJiDPV77Y); z&$4&BoLw}L{t(jT^_TL>YBc^eybxx9AQtI^nZj(-i9Iesx8c*Ez{5YjntMmw2YU#a zq?EekSQ(!KJkQt5X!E($pV*5tIh3dz{R2t$PN$_8`jH!&BEoe7Qki3?_VMKcp+Z{* z)ZuDM!&eW^F^JpwR@mS1&7F%QMEL08yO3= z4L}RXb?^_Ci)49;(v@g%Zu00Ld#bE>_W?wLeO=t06`v24EKf_LBu-vpa@}- zY260>k_Of0kBH^v}(41o^h6<sVeMCz%EbePBzb$n2w7HMfzXJ8bRx^G5jjMe+Vq|-Lg5!My5y=K_JTlD;P!6Saz z^_Ey@2Ov_s+-){G>mk6L#^4e?>Ei`kcW$Y4ewbRO8XDgdQDngWn1}&As!JO6*Qk8% zlA`XJ{1tnzhV3EgN3qv!){BwbL1#=T{IL@qXRWq7*U4BLC{PCnu*MuA#T41Nboerz zWBcWtWcZ#b7#p2BF)&G~eZ#>k^nMZuEph66oA)Mc*lv6)pVe<8mXo~TpMNoVl@L??w8)ndyVzOK7pAbIydZ5`Mv&%DHi#} z{TW$+GQ4XXiBFW)SicOMDE%X1$8|e!g*hyIEUdS*hiYZ2H{;(rm-t6L!#zenQe79( ze;3HT&ZSWy!&3?D*Uov_qZraC{?yiQku9PYtxf_RQk}8L&?6Jx&fhl|4O7Y?o6y&4 zNO}))Z7PwORrh-v>G*E_fPeV~T=UdTHIU7=Nvm@Sy7ajOC|pC1cHZ&$G1`;n(YK0= zPf@n?6rQG8uAPO>!sqV~5RBPb9HT?LR5dWZ#M#T}je_&$d-hu9O>H~3R-W|B9#Y&V z{f-kH7*F|2|1&zu{{cystfhZGb=YAZN-X`K^HM|@QstD_f#ev#h?T^;F$mKl%Ypa0 z^tausfeZigio4$$TyU0_?3Er=hUJorf|NKqBJ2G%v1LOFX-rL1YG`zMiR>u>3 zkc&3@=P`+6?}dNddu94^YUohLk9PSSoyO-pKhj>sJZNp^Th-wB=8^Z{t^czm8ghWP&ya7!2aNj2oY`aHM@w ztDtj9q`kWNleV1;9%g4f#HW2)eQIrAWx!OecUzYK<~63Y+u0A4wSLJ{<`kkIh=!*0 z4p*u)DHzRTBSB`%|Bma1k`=RZmq%TRtf_-lurRsA^1a=9UU5sK1~FM*X}+M=cr+aS z!Yt?U6_1%5(ZL)meUP4bk&IKrc3H6X-KI***U{}eH&;45bou+h-)ZqH%5U^vo*t8= zdcjVMU94d&M*jZ@>a6rnYmP2S|L8JOyf_{97Jd^CZimUUU4Os%spU?I%O~1UJ0nrM zWaSZo)NSkVumy;hqnMJ^uS=gX{Ck~8^VB_Aui1;CRQTbhXMBcpr?}Y-vOpv4Q!L$P z6@Jn`Wq;Yy1*UJ+zz?M->B&3+ z*`SlSccsi@Mm$nI|6H&)Cc|z^o?0Px^mK6Fy-_&N$O3kT4k+qPjxBDHg$egXaSS#LdB|tmWZW%HP?(Ht^T|cJd=@!IsXSz)}J^WL6!BM^cOVoeFVBu z3Ru4VR2EpCsfasK0p&r@OO5kZE}2{+U$qW0h1(ah#h1Nnar(7`JvHJ5?%Y&qmKWWA zQ@7GKFV)(Yx}7-A?cm;RgcARY>ToigW-?(GDpJGRD*XJUUmvNoi!s*?=;5`SCTbe~ zg@sEZ7a8^*xOu&$&#XJm%jL^S_Nfz>bGH2N?C#hg_2lvsW^==gX{2 z35b7j+VO>wy^@!t^y(vTYEL^7;u967ku_o@^1tD64lffrTay%tP9OQzNpfGVc>J1O zjv0wM5?};V?nXo`Qgt~P+gf|NhB${Grj9uj`#oc$cc$EzQX*X@wsN0M^`oS`FL-s5YvNF|H(F0c6bJkESRSw$1H1l8HE**K#SFi;j2ISeKSR{5eAm( z78P2!(b=J7^AX)<=_x4ui%H6b=Ga|&7H9a<=447w zGd)r!eSP_YL0mi^uLh^j!-=>f@@eZ3EEbbvg#pxv4E-T5QPi2*kKS?$ipF{6{)LyG zS4f|>TK92E?K(-u8o|;^G7=o3VsojX6ojz$y392844O|i?X|t4xm(**C3D3$RX0~3 z{M9ObhCDz{3}>sxv)>NuY6?y@N#9zO=jdr9;lN zL}f(oKlv}Uq5sAiGBvnhw6;irArImAT%2_L_h26})NwyX&PX&c$`kIzge|pOQ2zs$ z@`+lZAE?+O?Em)rOR2j6Z6iHR5?(H+ZlG7N^`^p)sR{NA%-!y~twlI_U$Xj0xmmVm z-%o|yhr{cW{XRzKkp^V=wNUUdB|}5E;KxLIcgVPI7SC?k_^~kJ$ir^{4&e)JmdilpFnh5@|}Sn=a}w&mWAiS2xjR9I|4(W z@V3n4;>$UjmCi4{k|q|cWdPd6^fq|&L*Gzcbq$a0TW52=mTw*TTEUj*Y`5SM-$mUc zXXOY}4lt6m&>oUgT|x+gb$k@&QG9YfOdvX)0~8LhQ+%a7yv@|n{$mPAH0`PSWP zI-8bXzRz-AzQBww4V%i*7oHn92Qvqb1b^ub&=l_Ypz%)={@k^(G~klAzKe&qX#I5k zdyEk2c_*`)e9b3FPt|{YsPOZvLyv2$J|&;UzpuU0^mNB>WcI7G*Ck}ElF~QB!#zHD z<9)O;RZ2J0bZ3Zs`f!_r1#lkKa4=<;;6cED>KstAOa9NfXPW;}O->oA*F{O9t} zrI}1qmMRmh=FoDnx*5Cza+w{z^7@m?rRt~`{8S;={g1yR3+#{gjlZ%ceHw?|{iH}L zoNReTNhAtwZaaT6-tp&3n?tHV%o`lpw>g#)*N|}`*WIyxuKTN2v-F`&S&RNZ+TJ`K z%k*ypj@&Ae7Fvm>&61`NMWM7?QuaiOTe6ENvQIVBf*NE=DA}_wAzK^WDEq!mlAUBL z>wBCxs+s3`-uJKfpZWZjndZ8$>pZ{9@jbrBvF|rX@MX-bD$FGt@@NgKbg$E&WX(2o zxXeLZVRYkq*j$4*uu#DOOwbTJ3Bl5IruGcW*2A~kSN2PM?9>`BbE<9MIPUOK%VqtF zfrgLWjUVlLjMr0#r7;B+*ARPtmbi03XlAE}vfA`!({hc0hT~mNVp6Y+Rb^9$Rm;S< zSA2LDDn&E89d6#MrFIs7%g+BF{ua)LFozXa>meEH+Nd?;FPOaZ4ZgT*wG;m%mRGZx zO-6?$-td1ZP+S_$Aj+p-)zRdn2T4~7))tm`S;By5=9L_5_kW+hQ;aeFx8R~g(o#Nn zk{gO;FwME@$WxYa8^uMM>2bA6sd22d&9VCF(scY&sekSKb-xpzUV*XbU**VG0w2DR zY}>Y)L1ZxsNJkfpYQ?QfAT=aAY_0Y)L|)oIC$w?fl}ZFWXSC&bJ@t^RNzh8zO8>psFU|ROe58iy$B;yD? zIWVn+jUpi*Cj0^&;UIqsoeOS(8c6<}Z^50~(;*I{rm=Sh~ zD|T9Vpkc?>U%qalva{xo{62FBL$&a-t%F>ytq$5nimyGqWITs$T6@FI*gHj7Kl#`D z{YZ!9J6F9u$XiWEl5R`odugT~@mQapsxqTBrR3@y8)Jq&S@Q)fO z_Q^SfwLUT?+p zA#d?};7jp%%>3#__VnMRpCU6Ao?P-H1 z`oCo-ny2H{8hMRRs&(^B-)%pVU)3O*ukRr@1833y9!>t-(EoW3e)Du=NV>;)Y9>g* z)uCF)-ZUZ&vevKQPSmNSB_Oa?S#Lr9t@lDRFJb!*da$8`zxx6HiqB3Y@C$`ycy}rP zsiW7qR=)atlpyqKd8aSi@T3MI#eH-T};=N=Jp)#w0L(t9t?6-ox0`#!vQ0vD(jW;#r4{BeeZ>A_@u z_o?x-miw1sC!xKp!RJmQ`un`>U0aKV=)Fv$iu1+)oXVdV7`7so;&yCQoc}ld>p_H@ zs6Jx1QsH}Yxnh!e&ZJm{&z)POJ<5imGrd1@kzZaAmX19%=tQ_#LGm4Bf;q(Vlb>^J z3fIl zHiT_aOoTagdAUZO*{-?%?Bgmv0f9?y)Ky@|@ib&R*o$YzG|K=0_^Rog(w=}vurB7@ zGz++_G&!NK>0rG0E@zLrRq4ZjHAVDKGjpwfR$`v72zvSD9rYq^LoUwVQjc7Wc@5#o zzKHv=%ni&~is;A2{x^aDcFCM8eqcb)fdQeP1sh{RjD>zUzY7MFGMGZKHVrct)sCjr zuQ;g|)TO1zG+xdn`he`ie_Ww!{=dAcpYZgILan|vS=l^M4E zX5?Ncm=1_Vun#|#dXjHsQoNz=(dgxQOEF?4A_64vaMzN?7TO%MOWrb$taN1JBt<*A z(_f+5tkiU%s`BR8si0E5UAXP0;WIkY|5rxC1IoCPVb~77Mtbu5^dJ`({p7at7^bEx zt!&1%iBE|LUszn3s@7g{0(jmWyR|;L=sdw=xG{;_g1CdJ!T@_!^%-RNdMsPlm zDjvD&8}!)8MwgJ4uC`m}>1`Q*$JSc+h8geHEK)rgWgqlM{T*nk{;*t8uUr)P? z4eJj3f4@+d3iRLs62^yFSe3{c;-$kfn%Tsp%!(_##vk$+`b57RYq2^uFa@py!Qhj@ zBW*I$gt1jtWQ_dz88B_lP<}$`5?l&6x<09oK-zf2#0+r=7GJjY&;AYjxU*hE2UkVd zZ(!>8+*oJEXO)t%vV50cD@wmD6=8QLW`U=lmFCa-31>$}jo?w7;eQ>YxA6M0xnX`p zM0o@j8yc8^i0?Y+C}7n_^vj7TN5IuoC^V=&J3VXxf6U zaFx@um^x!k)_ZbjFrOi*k0jabT(WqFN+Su3ob=mZXvVRv5q>T7U_`cBpTMuDkBxWu zD^}ZNye&_86#HFxc+4DIv;-}egp{)>oNrTvQfppL?(l8h-8YF?Z%#zjiMN^8^|a98 zGExWr0=E5+-|X2M?Akr#FQx?@m`)>B>A zo&$v?Nao<0_3mo>uuqVL`>!f3QPHtPny=9jSH&|Ix^c3@_XU2y$ZBO$oEMeP(l7F@ zp=E_T;brGGi~~rNCG*$Y$FQy6TLWqw6cld4$s#wJRO}%oS^#>Xu(84f0yO#I_{4z!TXePF}+%!iHb6Z zfZRU&b1i+C(z!zS)3)Wi;moFx$0Vp0W8rpT9MY#Cr=()R{S~5K8*`b2d#eu}ICoho zaX3E;E5*Xfhj@+Y$o{+y)S|&HjWc0ey?rK+*-{8kn8*q^0KE=5R28lM0i4luaD=%W zv9IdZ%rIh)c6n!=V)d1bszR@BX{x7c@E7T+0S}D_svjNk*;9xbK7Q(U<@DEq5F2oz zEwuRIF!>|E|2TR_6OfJhnJ?@npU!1s`4#Mjlj&Mm%U?u^W+){CG<~ADkbd@Zw26*D zv_gHd#|WWaJMK@Y+skpZ|Ner-t6P{8?UN#YKw)uz(c_H^7bg*ugVl!(U4?@MzA&nFVpBLJW?$5+-L{juJpyY%1X2#y{mBKjX# z7Wo!GvU(#=FO?FNf(eEOeMLet#W1ND&Jy>pN9)oSe)9Q|F@%nPP^B!ozLritOIR3x zLTwS>^Fd7O)0&;8_lfpH7^{%Yr}1igploltiXUjufl!hbv+ZjrN#x+O$GjnPe92Unr$6xR z_E@gfWMX``BKQJUBc3}8UlG#IsOXi^%)qGNBBrM{-4pn*L+FuXgr)68NEpE^DcXv7 zcJg{=GSXr*-mKL6#;Woi`=H?@$e9XJWyRvnRvbjC5H%dSqTV zeN+iF4>Jy~u1s_t@I(UJjK;KjA%i+$KLAck``XS9Z`SJA#-Lq&^gwe-GZ=cL^iM7q zL-s&c?|d1XJ!X{lC|Vjk0%Ib(W(r5Xkj;Ge_RPwCD1=qchT(NREW9_McNje`<(NVqWU&K7XdZ=F`%}Dn;NteZX8yo|l! zQ6>8rZ|IaZnPq?fT+&Aq9!J2xSr_r^Bgq`1>|XLCSkc=KUZQikMb=wNaC`1Oa?F=3 zg5S&5kV^0fJ_fs@xWpz>Ma0Re=RcFgtWs|QI|KC$7IM$M|J?>|2Sg#F4%pX3iiEo! zk^1Mh$YpTUI>eHZY6^yNhY~eG8~bJv&nj5fk+`v(uEl3=08V;N&X7Y2!>fLergTgSLoP=7g%M~Z-4jD%Son5Orw`C$%I+b9l6S`Z_ zlY6?TgkD3!o{*TYVcK)u;4J7*X-#&~rs-`y2#RVPJIKB}F=Or_D;7{c_m$#PE1jZ$ zZN6hNnu#RUK*?6{qR31M{MWKzx*@`^r{U`X-VgH)20wBo9i>Nh(S^`O7Zx?jcjuP9 zEP$IYfteHdXcav1|D#4v-|p$uy$(w(4mhwO*Ml%Hr?U~Yr~(M(DLjtf@{n&&mM?e> zYPY6e-)^#r%crV~v_Th`25a(o<4v|-ZjkS}xwl7-C23yY!2ji7w@}<6AbPYgh z$ev}h$CQo$kimxG3xfAx2s`Iym8jK%4VpyVEdxC|3T+p1aL-VZ_;xmRn?^rN6{Zv+ z=kBsZXshM(%(v>RjtdHSC*iS3V^)4*?ulfw7se~nUrQ*dgGEnE%+M3mUC``Rk+aoS zjg>yKQbs>pos54qVTwsR+%`;f&d_PirR+=!aUeRf{%R<3udxB+jlk|n_WKw4Pa=k% z-WFj3)<+TqHYE3NEMX%d*N#}X)>NvWHDz73U4F9V4%o(vRt3wF=lS&u0z7b$Cm5OE z6*b=#Bp%7AvC=={^hWpHztN=-BA3lV1-tzd3&~#D%%MMeW1d5pj4n<*skg^Lgl{Ot z7S^kqznxi>1V(Q?2=~)5rWwk*mMC$>RlgD5jeexF&N!s0nv|G(w`sGK&yw+68kXvE z&b>H#&YIP3PLN~+M4#e%D z1szRUk}fJU4yL@B6rHPWoP<0svZuj@5cMG9Mb)o)}Kuq^I z3POUjz^0czv{6L9fsxBIiIKKV5)?=$hncYWE~fo&CGss2PZ41{q7GDdF+9)!A5zPZ z4NBcf=o#0=4I3coI~0VW_8_Z@Yo|%iSGy&C@V#V!FipUsDj?HwRRfHoM(}U7Q)t+z zls(V>*9cBt<}4HEJV79sH`)Be4>50fNjCzucuUmLXW<1;WyWpHF4vY4b}3ojB!cZF zm(ps^v)V(Axfd-WD&45-scptoNW+Fatww}QMK3%v806JrQk3Z2gb|&sVFu(^5^!!` zyEgMJtJ`pllhQeY=48pp{V|NFbGCa2Xg(rxJe6BQ;U{1CCngJ=7e|3qCSGM*7^&o7N!rpqyRPk6WdG65nx zbhdOZ82uI{D*k%-4_HAc$YQ>O*JZI}m*You(VXp~`myaYFu1NsKH3|m)H)-lA(!8)#2MeH*MbUY4?>{y5T0)bgz%_$9=q;1oVw8>*_%? zJ~8ra|L$iBrYwuq)NCgu3+vVHjjMdW+6v{2?NzYDBgtQ({cS)}>{jdIlK6A72zeUU z8DobT6!L31oV#}i^g-vYn=Ow%ZJaq(x9D`)>Af3`_ds zl(ph!CP1*`0xni+VK{2s6Bb~W2qu-C!m)I9F|En>S7FU`zRw9&7~vWCx}UT#+O|NT zV;HtJ39vgVgUa)=!VO`I6Id1#p(8j`UERq8HqYqmz3*XCVzf2rTB53`p_r;8II1@D zy{S6u|6nx63e`b-98CcZQ7xTmlNmjbAK|lL6+;z5S}hS;5_`1k^Usw}CHWRyeVi0# zaX5_?+6{FqgM7w9hB0#APw~a$r)c2-%WfpXLu3U&d7i2vS*S;td&pU0?1XI$+3sxaCkEWhkVkyJd^>^cnh!BJ6u%a;9@$nWnb{|P; zN;ZO?H>p?0^X)0a(Y&YcK5=U1b92I3wW@T9J z6GHiUrfzeHYo>MB$H>z0qBpgk^wg{hV<@L>qz^7Ll9xHO-xoXesY05Gn<@yu${=Ur z>usVD3>_{Lh*nwUv>os>Yqsy-XN-c=a5@JSFy!S{8?mar;H?4{yrss3r9joGYt)Th z$|AqBIVT6>8QZ>ZPEc%=9fu?AXqc`#buGK;LKR@e)KXo|bYl2|_;cKr`{}bI`;!n; zSccSWcB(qEh-H&CrEd23NB6%aOZAjennGGcBNDv=KsRmu}_Z1`h&%_O~H)>!+VN8JaC2`3(J6m1` z+SEmU)3O%%8#ZLG&nI(3OZ&!MfI zhSH+wq~y`TQvqf~s&L&<)TN=Yo_KmohHkl81;ysZBkrP;^~YS2rfx{HtW|FnyxkA~ z&VeIxJ=5W3CkCq*Ty#w;x8n$X0i2FGpfT}6b(;CvwD;_DftUWecyBZL&a7rJq7YV? z_nY?5)V4`ExFcD}p@7KWX%_%x-t9?zG{aXlTWF1|Uf#7ovNy94!8%$&>utBT|u4PuHa|0ief-$W4IRZ~2_H@7<+^n!@S1>kjXf3QO7&pW!7nxOGHvZ78ZQ%T*EZ zNUu*84}2K~d<^HG^q#{4mW=?E-bIPD8~3{0zuSF$f1a+v0J2)y@k{Vc*5J!D0Tn<# zFNiwaZ%WF&9wGx4)z%bFGl$AU*y5zTMF4P|1b5E2u;B3?-ktH;-&kJLMzwtgdxOhm z$KqehVqrpvxwCJV{9>Y5|90lWhMtx=n-mFI+~+JlMCfalss<9?W*C?jme@UjHVyh} zbgYj#scc+Q*RFJYfr!Xygg5jSm$aNKH-KeN3B`@v%}#j^;#DzSWz(vG%FV;}vO-*= z0>gsXYnSprRf(W$~&shTW%Z2$r*KT3i;4*$Z@c!X{`U zgXMHN;$hfhC*`UU4QXh^x(8z57Bc*e`w+`oK~=}G#+4H?e@g9*Y-uX+I{r+|xav;N z@YAmNAI@jUO=L_>?p?tlLR1-uN!&tDNnWf>)4ASX^VaMrWgL32nM{qtbTz5PgJJZE z(5w5ieabwSYaE7k$&vhqe9vvDVvt!?jpy(CidLmJH81XBcCZR6mgmW0yIz zzkOtF{4P#mT*blhZCHZ^H#`MR_f4BXV1JaP+QZeKcDuh>=bH&=xn_H2&+@h5p~tPa z_5Lj&y{8AlkZXm*w6KQWi=^p(@vP0ybVYv!IK(lWx*r$*fw;qFsWekEgUJ5i%%#8h zj|O8EGc4}LVuRh08XjDzf!Y?$SjHR#j*GgOX#3(PRMP5 zwjK!;+=Hu|u8|Q@oYtt${^&gRV-wg^O||YkWgFl~+-~6+F3G8v-RX-ok zano0<%GM}|H|pm}yHX28{g@f|Y$mGMWTE3Et`r)cIrb+rCeWRDx-=pSN!p2VET;-v z_|)#(OkoWqCP#;2kZH0M*_h?8+wg^d#mlJs-X3Hw;nWnXWt!sMc)40Tj8`B|h=0_Y z#B{IUN?u&G$^@JHfEIxdS=6)>&L0BaO@k(ZLS9VM6iZRXg5gJ3Kd-snJ_5}Ye;xZQ zM{8;5yELYYQ=QqEKS!Np2p+iePcO^~G`RbkId()(WidNMh_9B>3RmQ=2YoQBcxPjE z#K~81eG9)ds^HyB^A;2uGnJ;fYV|Q~lq?8AOuwfV^)vlnT&DZO7LJ#KQXp)e-v;^} zyrd;__VVfp*)!+_O%YS>UM=lG3qQa*g#KyEiAOy=5z=0Qy0G-3V;-LO7+KDrIy^;Y z%7HHp|l!Uf?zd}{!W+EStUPy1ih5degPhVrw7j4=T^-N#ki); zj4@Inn{d=a(28L8F#O%FJ5RrF+T1SB$d1@>&Bm(?d`0mGNcgK z6q5b^4cK|^n^9ed*bvfR>&Nq$b&#X_l5x!FABY@&yF2El0R4=a4Y7wai=|cFCr4>y z(Qg%JI(-}ut?fh~xEQ=6GHt9=X&8Id;C!?&@8I7p^8D_lj}$VEAy&dYP-;vNP!*UG zD-o+V(Sv^A<9%o_h&;mU6JF~{ggwr}=Q)i!D#g{+Rq4c7%iE#Oa#>TVD#sbr6hcl9 zU_e-pCF@DM$1HY2WW*UESuFBxy{w_$W&%8mJM4bh{So9J0>{}``u6EvKI$E`g-9(U za|VWAnY6y+>N2Uwrw{ds|CsVWALZeHKr)CEo$=*W$_R z#|vZrCop&VxkCwsZVujLbVoO~R3LQ`hJHd^;ga5in6uSBIs5@->1YN%LWqj8!Ob*4!QWUoYuy;FyP%V$PdY6+Y|Xr_9pkGf(;>ep3~mP zwpw2^%oi5$fABdCF67F&&!&2ZU>WW=Rs4xN%p{dI)>nCXx_Np^JhtVOL+ef9@~)ah zv&f-x@d;5tdqM6}hTl{VG!lFo~fQ9vUdw(WJ(1Df*&uoQ*Tmqc6vE8GVPMiqU zY=N)GqGFjfzss_zTsq?H9jYLcCo%TK+=B5xb;Kf-$Ww17gI_`4sPlakmMz2#idM5S zr#xTx?cPcTiU|Mwki;$sJ(m>wN3?8f#H2wF+?WJ_EfoZ%RGw#gdds_DatJ9DBGv^! zI9N4KXJ3VzPU``-r$ilR`f6P9Q z;HV*!)(;&o+*m6Y$#=U4(6hdOP}*(B1>K{u>Z5%g*nU;A=))x^N{@a0^UQerjtKCJlOiwI|f8ODN}woXnLvqRo47qHvg(diW#&$k^n({jb>L@j6fk>UsM&kqBSmpmuh zT6oeYh$sTau=5uz5v5KpvI)L(W%DG%?&s|E?HZS&rAnXoQrM_(O?(fzFN!DmHCTlK ztk(UH(4h-m4oVc`^BjIJ*`JKKU1A0SshfcizJacCg;J&f%gYJOO62o0V1=&qw^Mn} zISe*hs@<-mRm`wrOD%>>>`1edQ~AvW5X9tc_~i2dsx&Og#C6`3h*t(U8fK>ft-ko6#N1THJ;( zx{K1=bh2~wUi6oDl&DZF zY6}%1|J~)<@)DjnsC>wZued$6&NJgIa6Gv~aR09R*_S4@HH z{$Vp{?jJ53X0$hF=P4pP4o*U-25k8sx5UJ*d@$g(;iJ zc$8OME%{y|k-Wb4q65v@33Q8_BTxS;ULo_9vKpPWFmbDv-?O5KE{Me&O_8waF{EYO zue@F0_Ra~zls+Cw?yV2m-dcW)239x{Che(XU3!R2HoV8ZAD*lu3I5zo?v=EoMCYOw zMdOpqx7s{V2kT@{a8J6b@cWA|2O1{zUoz0PMGs%Gy7(oZ$AmcDFR?dmxZpBR`5zZ#531c6Gv8);v)KZ4T#%do(Qhk$9CA`)9guM9$|a@4Oh zDao-+ZU*GXWnxoEV;o1PmCZTwQELy}YFo$DS0x}@{WA=3BA#qMyc0aI+x9l}j@q+Gz3agVQ_djjE#>A<+g zcf4u0>jX~u!M6f~`S;Q)XRjkn*^dpI@OKz*=iIUGVcfsC_s%kO zRtVl5?>G~JJWNhX>aZ@pheS1BXaX zJ}+@tlE1YF6__!R9vu&nPw}=TlPvjsR6I`n=IXZNpg$U$zZkf|ZyZ;@G~YwzdnGzZ zkRv~h@!vMNs%(OafC#CW`Lui;p-Rr)$WIUE&3aal?^|F>@S5?7L<#b|Y7FSV+bLpZ z4Tj*YD9|KG_#lo<`%up8q!bewYDXZ9C10G8{QJgb195=L>><{99`Dn*j0>j-rQalAY9)y|4v9CEz$&Vzs=h<7iu8YqtKjM znsniWF$90d75JM%Sl*(8imcCJyqW`$hlDM3*3HHWG^1#C?XG&|$J1siGMxlTu=-qN zIsI&1KgNEg8kdfFH=_eJBvuIak2sEY7ayVqZltn3LT=-)si}Yab96;Q5GEDd=$aqF z9C&?lE+J$tNCMm?IhnH_d+-RM+q?RmrZb5LZJYbDV(Vz>y->D{Z)l~}pMz3?+2{He zM?@(RssKwW)lM@nkt{NVYXbKY*HCkcA6_RXG=s14YGV2uJ}-o5Z*v&lkFo5aGq!o1 zC>b`rU5*P+@?5DfMdKF6&Y-3i3UDbEppH^ANL=oj^&|$u9Q7h-M$_^F zQl(~FPE!otHePL+M|razRhik_3eYAth>pTJtOmPE@@q_nO@DK5Wpck02S9M0$vE^o z{9>|FI&_+EUBa|O>q~Q#aJg6`?BFjBIDQdPb^I!g7Nl`7`TQG}=@-#4R-yTRcb-1o zWhiv|Z?n@+>f|yzHF{UQ7{+iix$)wOsCj|Ea)4(7dmrm2$LpX7HPL$*@=l?6?e*@k zpSGKFChpvX^h3&YjjE1jt?N*wKPC%{Z7!hmj0a9vgfTa#5xZK2t!VkPsd-$*pI7YN zQk5v2*yZ7$H%SBmAVhpQp8rW9_E2pwU)vg4lnBj0`a&ih-F8!pXf_vbuyDH!V~9!a z@MbD4M(Sc&=wkoPbd{UgSV)hGysQ*o`nEXzx$&1!6@+WAOCpd?yTVAH$waR7g?M-X z1K;jGB&Ss|Z_jLp=Kum@5p)-|>1?!o2i&Ewgadb7Xo#NM{5!=?YU*+>1#MM&!QrIm zB2#}XQIvfO>Qz|W+o2mUi%Q!d4`~P(3j&tkr>GfoN!pl1G=nQvhlY>C zsIcNzV&9V0J9s(1M8{3_fv*v!=y!Dk{YJaQ=VHim4ux0>jB0L*@ePhbkgDg;jqVFm z{(A%pm>E9LJ=V;le@a7b^W9-;@WOBmv0#(ojiZxqSPB;Z)`N_prlhpgBuXhANS+!p zPD#Sr-z%0zY!YORd3z_;GA?W6c){BF85##Pl5w zhUZXDhcIM9#E|eLFlD@67s=~+l2M*{HWK|jt#fPb^rz&6a!#tN1=sBGLV{^^(s@Sc zipK*Pzp=y&YK?o`R~SVfrM|hvxw4oq6K(K=8dc$>T%Y8(fXE5#E%#7v%dV9(4o6m} z;^#JM$tgRdp&NR#3HL}TMRuZr*&Dq{EuBlsf2|5WG7~F*KH=ONQY2Bo8U9QN zM>sog7^f%Nr3pEg&h`U7saslPtob7O;iEAixbPM!IQs-%3&cfA$Imr8Y7C&*V5S9E zxW-#eb3Hus;p&K;qxI&}jnpB9_Cqtv`R%pfG%M#~6=lOJiUw#)`VlfWmvA2tQ5G8^ zXLD?*bA{2bE-rYM*Sxvg|9d?3z3{b>FkXZ)zCzUs1d0O1(*1y0W@w;c3muc9etzkZ$FAy##>DNP6LgQ zZM|?F&rHt?VRtY$5-KifzDF1ClR3pS6cS9hOud<){}YQX$&Y_-Y><%t|G4|)BYe6g z<9$YRVK+TA9Ce+ieS-;^Nf*mJmJve!*M*Yr9Y4H~FXA#Fp^)?*SbU~7+SC)>Ziwoa zV%h#Yeh4eKUCp_hGuml7n>96c^Z7wDtlI zWa~uew~PpcDa3-!1yR~(7;|_dBGhuKpE*bR8h+0@NurBLs8arkp?0Qu_WN$QUfy>D z><}(;Cqs9U))O~WDP-!@WhFRn%eEi(Tgr?&nKCM&v<`#an~g#JQ|xHIuLw@7f*p za4#!*v?IxifpX$L)u23UH6v@ zH;ygX`n+YgJIu6&^Rl+YX8vT_NkV))6QvF38BV0E>TSebx z(0IIl@4b!J#7*E#miESnijs?(aWnd^^eBoWhyz24)wTw z%gfY-CDuRy2*Sy<{?lvhIkyqP*jZ(axy(a8<(l7fndrF3FHwpv26j%7Ffx_H|9(UN z;+y1jVV!_cEKANfK9hkp^9iTNS9LV9>{2=#HoJu&_z{P;dWzjagErh z7{O<&{n}Re3~XmL^me{u9tIhzYO0h{GhBKBD^UOUCzvEE1c;@OXf7J3(x;-L@`<@{ zJ6z~^Qo*bQ{e4zd6a(=v#Xuv>WOK;Wv2VfN<#l@kH~fIee>~~G%M!fvHfSqoZC@ri zbCq;QKyA3W8UV-AsPMFx9ZwelOU*Byx2|D|_-MIG%BTHBW7H~J3tIg;E~<l<+w$K#w+`c`X1#AxFvp6T=Z|i+s3%~-xUllmOmlOY}hM1Gmr?+1szhh_8?Y%sL12A_isMc z#%xva=QwSNEbt60gOJoR0osmnl&tmO=={?!j0H3LA`^f(N3CtwDXc4rL(PHAEds1P zX!VzM*U)tCYvACI&1=a-u+4%c4BIFB{33=MKiUTqxG-v<}-ow51)v@WH{a=U_yrtl% z*Fg+;slOd?eR{*0nkXPKN=6AFnD&prHIeB0_f+fggCF<`210%Pr**=#oboTR(AKVI zW2ssTP)Pgzy~xJB7A-Qj4IaQtHw{ZI+f!DY6D1{JKDi8C25X$qGRX=y8U&d35D9of zDGRXy&7GVcuZ_6||7U#uT(LeMd@$%0%=W$?S||2Jg-rddi#TuC!q?QUh6u zTZU=-rI(Ag)}S(8Ro9ET=ML)nCA)l1u0btqXuQ|YOm@Lx0jQ^KPd!YPCdRrO?Ze_E zey&q*BHM<3h|odHiM}mwHwD+hAVaP6rl{-fi)gTkp^5vR&%U}MzlsKZJ?i}QfBQPG zQx7m2=vkfrefC#E(jWBG8pK2n|I3Gj{fUk|v5bm7MIEG;&tljs7c;W4aYP`5+u+@$ z0S?X8;S_|8N+BJA$Yb$g*%g}pct(2RLMdI%Ppmw#Wo$(#d8zs#xu8WEqI%p#UC*v~ zmS;@q#sr!brhxxNv`dU-$Lz#z=7vWk=YB5mIBt7r0ZBHOm^z3$L&TrX!U3_k1=1=m zaYPyMtVg&7l+aG2*gJ4@G1u-Aj`+1k+d@vA3e%z#VH}Y3M^>w`{~T--fd-F)TWJHM@Pqr)^ZO1(G@hy$9NfNgCrQ%v&mvKJ;R0G{KV|u`U;?8Q<#@SSSlKb&TO0yIsm{5>cfun$-_YIcp(>ngFfR} ziTYoUb=0MwdHiVByp8|cfrx*(4PwY*awoWcu=vX;L*5mjg0b|*qw!P|DAd6w2o~rJ zLZr?*ey5Iup&@HpdR(;J6ruAOs@~GZkFmd>&2GT`S}S3O_9>A}I<+zc=EC|b<3`%{ zfMaVcCf}XJ{~&3FEws5-Yz|T5fyflp8K9HE5ZvN{+i?QA`_20zx(%7r*8%3 z-xsK?rlQHDOkEZ6N6wxwvSp;tWz zC`itxpl3eZ`JJ z?|N$~7B@g_rNHGpWc$<|7793sA^9<_CXRRZDArQ@_gH}xR)-?#vs4w9OL(fkHNA)5 zz~6*QA9TA(Zk?n}Oq!oPQ`z=-Y_*h+KO?wc za8Ip>wIf$}PqlD9|JBU*Ny{~dP?ZuklU9cH#lv5}j``gSrw)deshmzYfBkYt$%dgb zB~}}km3N|fjA)ks9$0L(VcCTTQuJ?gUr1?l?feqD1Oe`L=n>waBZ0e&)e?&0kY}Pr z->tdu@Z8wOgYi!Q?Iu-7-|_b9R5S0Zj8xuQbLct^wAyW{Z^4p?JK(T+j29a0QyWgL zxs2+*!?NQ)Ovl`9%8NO2AG7HvY6(*T7A)txPUl6_GI$!U z{sKc(aSinkwB-4H{im|!Az%9g=h25Jm;OVnvc^ijA*1U8Uwn=vDzJ42$Gi!eU|fw* zTEqPn-RG8Zt|+m8X6JEof5O=3-yQzkQ1kcl#T{Dt5O@$%et(G}@Pb3Rf0LCIXrqnh z8krEpGp$XeYGx<)1Y|pgci74SOt>%g9ao}ORb873^6lla{PTn)M^uF&QMTzYu&LL( z%jPsI^*wV5wPk+{Zc@^|(T1clkqREJ$NM8+-DLmWr?_g}QS;A-rZpm@hK`*z54zRl z1iUBg4olO(Sf~T8O_otz-vaE=6N!SmaVMs?{-(R9g5Ueva@}XYmPDQuMnJ4Psb0t5 zs!R_CP1k^iWdwno;MaNdZ)e5@ zamWbDGPYl2i!b^s#=Kftf1=-kf9bbiwdIr#Mkpp+h+wzsGH?!{2~m!9UC zD!Ca5@|Iso^VR#iwoK06e3>ay=Z{#upUqh^yrskuc+us^n6;=io!sQ#yuE%cy%q2*T1JRS_TL>$V_4i08u z*(j5L(Cr8Rae`B~ZRYiTN_C!6h$zx~ce)K~#^yl(HPhFKw0{WdH;7<+FWY?W<8JQ{ zyLW@lr<>-(&!fYpaEpZzPJ^CW`>8x&js)+rzeUrJFnL@$I+l2WQY3nk(QX?Mx4}0V zWJ?+LR*EpCkyWP4Uc_K){>{jf4U>#{R!;{x3!lZjUUA$%u}78Xt7j ze|b|qE8QZt*rOyWP7*x<%gjZ zk(~Hkgm)qTf5yR0NCEGs1|A6wJ+D}ZZTo0U3~!-DT*WDV3t%Vd%@twtr3p>ej>8f= ztUF4UpKT_CP*U?Nr{8(OCD+c&$*R7kp6qRN%I;(a2sI-bCgV=}izi!ssPqzDMX?3L zb(eJH@?}{&d_Z_c$?Epu^(pr*|RCME-dd9kS@;Uvj*wY;3sl ziTJyHPr^-Y3^&7q%_xhBY0%1v6CTaj-OX^ho;PBs*{@yvXkR^hMWvNi|DHpmPuyjq zD35dWysm$Rtc37pzN5ouR{x&DXm@rR)-2X;Q{GoaCB|S4W=ul+zqwr5GRa8wDu2xK zyPOtw+-<{#Pnn|Bcl}X?cG#Lvl+vbad4pxjf}E!Ih*loVPKXolc)xeBNNJkpHTbpg z_e>}GFJgQF3W>svs8$6z3VP`vNZC4xwozIi6jWH$MwroPXYuRKt+_7^aCWpM{?=qP zFzUQ$#g-bFbGQ1mPUQ8?#Z*icXGPr?-6ak->Jo)#(bW;$ zUa!}(f-MYE@k=GNuAVGiU}TojxkX&h#v*TQlB@UTlNfij2^?Ioho0?#vHDl%ZSEj%%`4qUhfPnLA2GhfE4C!vTbyGDofltEB* zG0ee?v!263tM(liK6Hp!^4zw zb69{u@zBVL0+vy3E#jkpPR&ih zEwU5|=5VgbR(T@4DzMqJZGoWPUocKBR5JJ#Huc&N%&yY_x_=n^6~2Ov&%1$&^gH(I zg52v?{6jj{<<4@l*-vrP80M^HQBiokX}I!h*N1MoYB{`u;iwRMs-K+NO02Z!-*`)` zZuz0Dl@P;Hzw~HAF2e#Y-7(w47B$GrH6)GAh{)-CJKq;2)X0!MziVfZMOVCGdczv3 z>YOK{gQDV&^dWgV{KQ+yI5z*!sc#?eM$hAPxEoAQYhtWmw&PAa%3>LOu5l<>$FTDB zPSWA~3EynS9-Y~UMce}c)uuncBDwFGE-+7Q z^&LWaeK6K5^p3`uX*X;H&5i?x`)Docbf`Ll*YhG{`$H@D&Mg0y7jy+dy`A9-{vY+hz1@U}#-;wp~N#K=^>QV1Gie zgKK+m^5B!^t)$o_nSM&|SX_I;!xhg|J^mruQ~JR>v&bG~F9>JJ1S%!Xw8n$ZzVNH| zlN~x%w&D{5vV#s#tZ&SA^Uw}lu`in@vB2)mUYLns(o$Grb;>FS8!$169(mGX4^pPP z-NcdG9=+S~jmta7WcbA?pT2{Xk6mtM&DRF+Nnu8)42=1W`OKm7Ntc31J0#9#o2(rdHQ)0n#^=sV9kV?grh9$i2vdLL#Y2Z)wH z{4v5N?^`z*U=-jekZJN;wvCmtIbF`_l9nzg89>;L?FmA|`U9asP03%O2*Hh0zvc4M z|238@e7UmwHS=C^aH)fzKrdULj1g#0Ld``e?@m(QU6zc6RV%zHY78P^0xq&Kodry< zLm2}{(k}ZU)Ez=D@^7>r8sNfC7!7J7Cd4Gd?JK~uodM8e>0I~Xg&D{5P^WRj07jPK zhSI^)AI!~z^c%Wg{e`vQz|Lm%G0*d;_~i#nuDP~G#*Q2;K9RkE+uDEQ`1U-{NoYhDPX zc4>L2#)*)lHndyvv#*{BSRhSX#C5gW&+_P`lg>-mX5aP~+@hmSQ-eW$3$%vzH|m1( z<997CzXK(nfaoFaXy=R6xCa4?-9DVWETFY7ZpdXmC9P}VaeH8@>Zh>wZ)887pxxvC z!Bbg|L(d1^mff`AXyNMrel)+eJisZeQN3j%BW{8Bo*X{|&v%2zMyxjcUHyIr@fALS zSXU&uwP;4py_k__dSHvW1!Zl=ay?p_n^K%CE>PK2<{giJ_8XP5ia$y1i$?KAjqp1%VJv+1WF9=(N%%=%$BX3X zl)5&pI2G@ApY7n;`H+d9W|sI`u#q5v@mJ=*qG1_RA&$cGaWY?eYT4-OrU?$Eh+WL% zLU9vV<)(A#(CQG1QKs;70cR`FOU$xf@Sto=1%l?wIOWRVN#zcAvNuvB4TolCdOe3m z^mo+0TMfiN$mP9zClS>5N#MI|PP7;2D3A<+lyEYw2)JAL?hna+|6{&gj zj!La$V_s++%W}BVK~tQ2WBC08+omZ|MZujILwtm7wD@)e#mO5)Xutq0Iy;fQegJ`EmuuhRX>}X~>K7n+2A{>%jh)$R4^}@zf#ysLO%U z;C)mn`GYGp91K-lwly8(xE4`#mxwJ1YwCLJ8?g{M#@rqe#~f$k{LuBlaOIGl^sbt; zsX!}mhKcE0OA`lIW}A-|v#n(z7`WkC&PER8a(aCN{B5>hICfwl6-D9BivKl#hw0(bx{XXMm zsWJ_4JCXtR7jhKz@Ms+P2S|A`bRaa2tx+OgxgghAm?nosr0E>tTr7chb-7(r#ilfH z{^};hJHvd6rNM4JBCZ!z6*6q79gt=wz%TL{Dv4{Yf_uZB9G})i%cdM0^|s>Ki+tCS zi@-c0xuu|JW+tX%eiN%3&BJ9^@2SHr@levv?$KMR@PR9kEXt|gnOOBav3k!J@hQ!c z^ix%J_t&>O^_}|Ii1cR&;M~D5K)ku^?WvL;(9wP;4OcH3yRROVdsCQ;l}Dq-*G+FL z_)L_Uf>MgI%Uf0AxbrlDyEW3r*SWiw8{dBDnjaO@{?tTYrLI-0dX8MPZ%AKCYB(dRTHUXs>ba$!xm{n@BM+ld zvqVdAm6ju4(qnbcX?I_3#KtjE;_Gg^TZt~+Jjp4@eXyHdG31PkzVs?u;Jn%Kn35~% z@6Eyb2Ub|kO!7UPo0zbec3t{;_N5~XLUfci9ugg}dGtJxmuOcmMVA@{-`JXAa@kdI zz|_FxF6WUS+V!WMLnV*Vap_w^>3q5VGlf@y4FkoMX?_+*FnFKy`2Rey=KGR;LrTi? zPM4sxdY@1xoGCDPHW6$f)CzeQH82knT8mL1wzt-73U<;vIRDP)4?*TMd5zMG0#61p z3B17adT6W$0HZvEU(VE6G%;ZTL9M;Xt5!vitgozGTvcwRo#((Z_I0czD?6(|Qf>bu zqd_wk+Sk-ho&AKsm6BG=CZYPJ6TnD+TI84NoT*ASQB@`H#E)GXjiPDbyk@Sk4cKKI zrac+Jc$T14{^89UhxgY~_pxUwI$#nTmg{7`*U#`7L9g~i6yiWMa(IScI+h0fOp}Nw zG}ZP0?)3dOX^DsOuA|%^Z=!|S74NDxTs0k*&c9H@Mb5D`h*B)qcTzmgX`jxE%N;u1 zWn-9&4qspo=p$=@Xk+rlR0X~#0rnjMVLQXPEM0(9XK>i5Id!B`Pifuo8Ko}?jMHxWr1USH^<6deBV>1kl6EHoC)cyr-y!)q7J8;}A%6zLm}P942e_DYk3XrVg*=UAN|)4i95l%H2o#dAkJWovz+s zC&gSZCs?TLA!J%TE@f9-amM;C>NqLFC0to(64QQPN6^~jSem}{%&9I`7S9@CZVzdH zQkNC5zBR9Rz{~B!WhzDe{F44}WNizZAU!!t3}19~yUUkbI%e&;bT(T?IEb~)|8Cvwn5nK59K#s(2(94g_l^{Mm)km7iK8qMsyp=Jc_>=@ASM~M z?M9wWT+eQI?rUH2!iM>7hgZkiQwjx3RN6GmPlq?@sii9CFVZ4(*RatN`qn(p!=bT? z)nm3H>K;vkH5$gOsgSA28o@Sj9dxJGf@aNf-w~WsGRQY;91qzkDjwI@D7f*W=#JzV zI05W@c4B`REvkF?i9OXn5cTG*HMYu2Ba0rpc-mbPFn*qBWcT;_o#+2p7usHVIWGSu z<5@y6lXzgn+C|7hP$VN0!&zv$ zWlBPt$Xa3pIG}2ILs}~g_Y=-h*t}}MJ%5ZTA6hdx#93JyENzO2XEI28m#xlwm$B^rz9p04vd%m8mMMiD zafqm^SFh#v-dqy>z$Q-K6U|3*j^_RgEE8YX31})g2e_`tGDAgdK&On`eM<4RiK~8w zJyC&VP0i@6#rHz6cf?^GDN}B!bjI4&K@JZUc%T@qn!;bTCf>cLG=F!K6s#GjGmaD5 zX;@zWVP@%T+qbFI7v3Q%wftF=71P1{-Cji5$C=!18;;{1miPv~_8-Ddh4Kt0b&oEJ z@0-GaTDdRz)00t|tZi`;y7Y0sgdm^VaG4o|Cy?NcXd`PIK+9^{Nm;$1o+cp3OZt}I z2NR<6PwrS3UL7Rtw;tj?Iw>_-jDLKP=#Eiprmf|Y_f+Z$W)kJo(9-PS-kQq0Uwd7F zR=Wa2c-~-0=j%(R!FMuB^V1l^I5+8l(sNn4OF=PFMXa(#k=77x9H^_MNgWR1?M@u2 zMJiHQLrpO-m!>@Gc3Y^^nEBz4{BZFH*3B1Qepg7_FLpPmqy2!`v%qwE9MXT38;0sX zV3o+snj>fvcCV;JOwUr1a8s1`^9E6dj@f2ua*4ubcg~Ruhe%k{d1kSb#GyqTN)~q+ zC6?Dv6JnQ0bnq&#)S@a1rVe~yrX;^v@#1UyIZi0E#A;vnXp>fArK(XkEw!I*jRD`#GkA7~vJf)~g(}IvW*r_27JT>V6o0J#^=(KqE zVZ>Z2r)){rN1phESC{`&g2qL%Na^yx0Qt{J>+QY4O2)mb_}xC1Iwnp>Mi)I$zwXhX<=QR-H=? z?Uy8_d-u%`PGGKLHS1?jo{NeUCZ~_DznEGWGq)JsTzt2`=ach!Nhfbq3vR?1bcz^7AkzxLyb^7d?RA!VzcpZBTum z0;Yv^XtamH+ku#s-0a>acy6@?CN7j!R}~a!O_h(#t|CnqGRWi;G_n6u>NO8j)S{s@ zBAQ$L!1hzG*An$kRfkWGf<2M#XYfPo?ouAq0^nUuQ|Qc}*#uz1LnqY)gKXTCl*!3X zAsMzj6$VT#Pz*K=Gze`$*IC)uRLfSFv9bz&XR{;XELFOI#4*jlD6V|q{HYhzt)X9u zgS#qb)7jm^x&cyzjLOv$oCJO=dq>wB{Agd#0KGWvl5U?9)_ppsRM13od8(rOiM&8b zgUKKTUZ&Sn!OEv1Yhpcd=tIpwJsr=cZSB&1AgUJs&9bn%rVwE!$Gw|y(h<8!z}-}) z(i0T1sf?paMnqxIo9}P;w16zSOYEPYh+W~UM1PTd2HNof%*rAA6PVzIydJW>p_Sl%V9u?O2t z(?f>AMzK=8ADf2YkkAQVoa!IW(%-N1qm6fa&84a{S?%4455N+Dj&ju%K|(4zyLZP; zJbsi3HABbb8R6U%M?EEzYVYo)|IUD`iT(gUr3UWfd$bbbvmJk0(~==2YQml~F@hm2 zhQ4Rw+n;5lNBg1CIs>3N9`SR_1BYjWM=1%}K9JRo^IAdPre6LRSCg0k(-yVIdW4?g z7$xJkaA=q|5ai-@K}FgRw>$&lk6&!$!#VT87k%T(PAUOe;3#65V788$>fh#BfxfuW zMFEoyv%ofm&nYCij8!8g(1`Dc7QhLsXBh*~305*y7Uwo?iPN3S7r9H^&SiU*P(#-D z>xG-e5f7|HN;vNL@%4i=xHUg{U{>hb+yY`rnBIfk!N z#ydD($|v9XgnCJ|pr90K2KhR!_2z%VoPTY#@5n>w?J?c(isQSMAa|hY(Js~aPf?fP zRd5N2!9#WPscDjivO8uI)}shg-NPB|nF1n!4gfK4ZE6d1{P|M7tH@hxk1s2V*FWNz z{t7KJg?_mTwzBW=q!ogIRowX%t?(jhe!$ma+8~7tZmlZ|?8J>KUg4$j+dNn=39Me* z23#J=>^T`nLMZ93ws?aHD!b<^)RK8HC+dNM%mN$|_v5Fb zs|}{=cEb%*Ip2cI>{9xR5?>#Zvu_qJ?fl%?l9aT!OzJ8DnQTWl_TWZ`rBa?=WPx4? zprxp%4B?*U^z{+-2ghA|HV{k`Jy3XcW*W>$R{Hy4(5O2nu;l#Ibm`WIL5;uwr`$Sq zLKW9p)I{Ba>RGS&iz{J0d$dJ{XlTB)cbbXSjcFE>t7;=9^t5f!^iQC}&8vHs^=*}q zvaY-ss!DOMa=EKkH0CG`XvHJeKNP_)ol7325QdG`SNuopXJ?m-*Fq%ce$(^p}wxhH8h5{qXkIrW7M7+CmY{GG#rq z5?W?KXFbmDs+(E}m#)UZ9j_B6>a{)K8ni;=xj6qkH-h^LUO#q=c?xngd!5`LUQg0+ zUQ_K@TnVb3ccCjapWc0D5dut?==Wfm88G@Ea-z0(L2zYv)RL{g*wA=lMrSem+Q_Xu z(uPB?Rix^_H@u@hrRuFew8-5?uqGH(#uDrTk<$lbEieHb*U-4CP%te;gvWOa( zuYaHzpnZU&@u;KHwz^XxtJFFJu4wY8S@?{8=$#|*y(%Lbs-#)zl#`>8f2QaPjk631 zuNwRP^I-vcSYFGWAPKUx^HaPe0@|0!}lGn>O#<^MT<_p9PP6TaujJ^;sH zhgWm(pY;`mw5D`4hj-R zBcfnCe7~4r{G6nH%FvJ$B>Wa86bL>Iu<3z8V`Ed7@^^wQpK|KeTHeP#J_{f~pzKri zcJcci4E`PdS->6d)&PBT4iO@?SC?7~6&(vr5)z6n=v zPZW32W`QLjRUtz!c4LP8m4LZQd5Bt_F=ws(=UG8B%&qL7`)Hc>Y2Bn&2@L%i=E{c-W7elD>up*Bqs~_&Av#EtZS) zS?X9PNw2(e=3-|0_~U{fCV2m0geLWy19FY_HrW zWRwcPv3Q~d8H|_IfZ&sUMKYA4@3fNg%148|SbR&Mu2b|R8@@+#Xt*3)I{0(Xlyl4? z*#{cu6XolmZhVxQKK>D60U0dhjZL8N+|4S8!%VTM@@ycX4sxW^LE1**h_h`Ya#V-f zK~BZkHli(|`O*7|RyX94mPn&)%^HbCuyF8vn;^JJHuL~fo&1OX@dzXg8y-w8m)_?> zJV1OyW|6duL$&M4Xc%+P^x58h~(HP&V3&E7wUcD6y#m zP4H-5v~5j!j|2iaAa~gNK3@{djqYqs{vKn=?cYY}^p;m5D|}nT#cdlzBS0{hKe5Jb zD@M45)hXvI(&m}Y`tW_e-0$4r_=674-!%SGd~t{KpMRDxKW2cq=|H&z6HHRb`&)m_ zD&Dt%C#R;*KNpZDd5RS&Olq%t#lxoTi4OpxLKtv&0dF){Ns!!xRYm*Goy03U&M!RW zvQPXed++N?NlW<=v)q>2y{ZQmu35Hvu1}t$Yct$`S z4>OHatJ-xc3c^F4(0jIt$5anMbv#h8D%1P6`o6@_^!)KHyqVY6L!P;72vX6C?;v2h zF4CJIuid=<3_g^y5EeDzQF-$hE8zq1M`-TLz-+UIIQ%M`xFB;6dIjR#OZy0H8N_Xu zHs`092d9_M4?S;fvm_<_ctDci-Kc$`Lq*Hau}I^q8L#n1olSFb1@s;Br$%S9Mjfiu zgMQRhjbGw)&m-LvOqdXbQu1hb*`W#bpS$8mWfa<|g^Xrdpu~fD@*YCo+l{<6x{~;1 zD+9*YvRl0iGr|yh$mvVvyg!AjL_1jO zkzl>**QiqMhx`GVXw(h@N5WC?9g>ka+&_iWDzVahkt=+_yNHOj&{9Bj43%2M0+|!9 zLrvx-ch-W~TB{NF07)*=m6HvpZtOT=;Jin~wZpSJ!0>)DMVa9S^oqGscY>hXcsY9d z2xtVr6>H*m9G3C7Y*f8W1j^Q+w&r)YcFkT?N@#}@<}N^Q`3M`fr}cLh_?@SVRj`ru zH3%6jf~zlCXlP&>K@>BlZMK0R`W9y)rgP96rT1Hi)SK_JR(RnXTBVIb%tU(jtyIj!F(438P(A)?u zQN%HimMir+7wv9ljK}<8@{-S*4_~fvIbO%E9Q^5RDH@+pUBTaeYcT!=?t#&)?-ptt z>QJ`Qer{9XUmyKZW;Z&JU07aW(}gak#zA=e5U+lV=(6wi3vHk5y%)OqshIo_W_t}9lm2GI|sKue_P zy{T7S-thJ(X20$93t4F6oWBtXNePuC^V@Q-ef$(1Nk0llSEhQvqzB}Qrg|-p zG_M;xrQd;U@q8i&RG$gZ4sJlhLO?gmC zFfMsbvbvsR`C{c0Z=9hd%!HvI>z7O~PhC#}S{FB)u4}7ngJK~woRh0E+5ABg2MxuW z`?+aa2>G!O=JvM8r}{9=|J@{vkCq}Mj$kQF?qUg3ct{pLn?{6>iEl6IQl|>IZCP2b z)lVEj&^zN2uTf!;Az*vq_?f-21hwP?{u5Vx%?1M?y5{e`slj+sA+s(CL60roqrioX zc!P5?kB{)WH(~O)G~zDWr(P-CeoxLwJ;R})cF$jeg3?MgAyGn#(n?+{GVpl%YcHRx zln-l+KfP4C3BHYdw$CQ%yuc0aKzxS8WIfPzZ@}V{u};|)utn+LtCV+fD#Q-LhQ4YlOLl?qZ4$XO&h+vI*89k&C1Cs0FLE@YX5Pwd&?a*wm-N& z`b+d@l@Yuq?4+Y=_p#n8`mw)y=R@x}67aIkcry5~Q~M+4S11Q+U*jDk91CBTzH6d* z>z9A`O%NP%9%nFBk%}7PUs&&~#$W$Z+c0qKM-?cz6e4}D>~Bgn60+(!W+msMsgI)ci0BwnrHwsonC` zkapWl>A(i!=LfZq?JQ$bNGU>>y-&^N7-&}KUMV~bZOuvWPVvvG%qe0SpnfxFb*^~r z8+uWT!K`%@*Pq+{{v|zsvw>k+49RmF|FpR0N8gZ{s zk3ZHG&2F-FoW(yJs;Z~jQnqdrO;_AwQy$y{|C6HaQCG*kokWlbq3E`Zex;t21jR@Y z;ckjca0EUGp>`)b&n?6DwJ|IJGU}ZYHE}3J0aD8yAy!rT1kGic4Gw!#9&#fyqf=qX ziiLcZS1xkL*X2bO(=AED}RMSTBCXw)i7Cj;Rmdkdx{i8O4Cx{A~pKJ_-NZ<&s{Vh^bEg&!p#jzV(nJlAR}?f<$VK^PNO?=hbHnJK_LGK z(^~unI6b#4)QkynK*eNpcrKxl&>f5J4exNPP}?Xvva0JTLXKO0-`o@C1FWp-Er}2z)Pv+TGH~sgt8ofjd3Akxlz+WaM*3ZY$ka_?=|^D0Y4@@0 zdQyZeB&JkfDB^|*a`@Z_CwOyk;X?bXZ=hT^z%soz#DWNuJwc5os=78AgS)*XLDTZ+ zS@R>rEr(Np(I6a$+83xLhUCQ6zV8E)xrM z=2r!(nc30X0ok^!Dv`8+-GfUQIZ$o+Y%x|{5D^3xmAf$1_D2nn_o-=83utbd)RJQ; z`k^f$Ar(sQCd7AWRo+=^@l>Emqb$oD(Ih;D5CSB8w~mDtTws^NiC*)581;Z>G^12; z6{Fu^cZzZ_I&SsJsryf@p(eDsm*+E5<<$l!Uq2+vjn9p5wQ8JHt=Bt9@0<|LeA8Y8 zHi&H4lx!GKQdeoEHFR&fz^_@G>x19t5Z@f#m9;ttX>*r4euJRnN1QJem)5J8VnK1L zqN64rBy-tPwaCdMR{(hrvDUvv>fh^0BL4k-RVVAnj2*ZuL^Wge$ip)Dg&)&fHn?&8 zG;kFRUmj5LD#iEmT~s$!By|6*Tz@ytkKPmA0B99x2lO>9;@wv?Ra-UlV(-5vSn6rF ze5~Uuj--0;XR2p0v&vGnar^b6=awt=#)W?W?wStQQ>FA`XndHnwY;gy=#q_1!354g zi7WDD>zJ=k=Wm%*;-84Ch-rFYPrYc*%zi16S+FXM7g7^DI590NMDy@~N;B^7C%izM~+i{!kG$ANW zqxmG)Cz2Ig$Y-&O?vUY;eqvQIDBf6{`di$QgN$BYk>1dMBTG+W_+wQ6sJ_pH`B1KI z{4>%nwzI*ckfoO`H0W!2J1<*8_Y|ZSOLYa83P zio?OLXYx>UCH{6h%%0&%SER9&5#3Q%=84j~D!?#^1QwuMooCP%+~LlG|GqEuk)wT9 zFBma>I*Y<6#nQf$63YeLxDvLIMW7q?6>&!?p62M8R8oRbC#WrTvr=1v%3we53rpr?S`=f zB9B0SNo(fbMe|dGau~%MxHT@pPn>2-3B?i$iJbFold=ra7(M3==USO1v0r`P%Dauu zMYcS09(z->*OlE%3(<6If%6V_D~R$HvhcNi&YtDP_u^KzP~as-SHh*o>)$_xY!Ob7 z(nHiNE$d!87XTuMc!>6%5@hRhRUYLR20uqFpjft2jw3Er%k#)gU>xC^~*x=ka93u3TsI7-*Tm=<&Y z*<=}DG?NwtV(gKgiQbvu$S+rL=jHclBf3LQ{ z4en6>E`6xjj*e8;ykaErl+K7usdX69M`83VW9CU{D*?)PR8lEbsw=aY5MGr0Rkxqn zRBL7B@DPXBG7Ne62s_lj&*w~&xtk@vmKq!pW}hy;+RY$m_*FPCBd1C`lRkcZT zr&OPZ;u_oY1d%hMR8#=Pw^d z&y9v_bSi3|pFGZoUJ&fxJ2+Uc!!73JtzE*$v1?DH8gO6E`S|)ykqjAtuy~Cz;b!)< zWq=P_>NPccA>+qBn(Q-4Yh}1&?-G#x2RnR(%z#~!Q%Qwq65Sl<366)AZVFoWy|Ss_ zqWFkhTm~VuR@7Fl2NNM74UuwOCfifq^U1L*y#}WbOxi*w z`dtT;QT$QAp+DD4aTwF5dF3IyKe&uYJ6z@3@a#J~b3GrJdo<*wC&X&7q^(+o{T_KK zf1cMQ@hE+AU74BbO&2jBo29M|0Ggm=cM}|{8m0J^(w)PRTlNM@;+;so+wl-xTGI)b zQZnM!P9c7_kuRbWgR7AF86XaOR;s}rmxkMxD`P3kY@f5b&hMYiGOC*WF=(m3Ho2b& zBSz=){l$B|(dxxD*u*OqpFViLFcxgyzbqy)`kY?@v<%?HLN^e$RuSQwksllQ*Whe2 zfd_iv$^CBxOQ*Vw#QKathtIkGAbvyw3g|+xtv83JXkld$7GB8d}Qd z-ve~p?Xg8Q0RA&;SWjoXMW~H&pU`tG)`#pWwHIq_Wh>Cpa@bGRssGCfTxVgz%uVCF z3=AusLeqesC{1|-8px6i|OEpuhq6V9Q=bgDrOqRWk)CD*+Dj%lcvaGd2}EcwsW8XwSGs*jcH zX~nm#ObmQ;54^nL-xc=0Tf6iD7Uu~AlcY+jEDl!H$Xv=$8h5v>Tqo;pkM~E48D4ZeNt@F=MnUddi~PX;xiL(yu3V_%Mdk zd30K@CE)T>&UoeeqRsqfbJuTp{J=a@Sxde=Fu&e5-47ED6Om!!@UEJQE4Ys7?7rku z2TAIr#l*dvv($C``Gbw&Uk+REJvqjaUfW;OU}n%U*P18;#yRg8YJkH+?{U*{D&);> zFXmVO?rBuco?z(>t+7EEHV|~sHfW{QtSH)6Wi>W6O8sv^4cp}Zq_ab1{{00s?pz!S zG$9x2Az}KDQm-0W`S_|;ilt)r^`h6{S@YIGtpEq0Lw08v^!~{-g!OWfEf2=?s#F9f z1Ii=WrPoZ3uESmIufyZwnL57zQ_e$YX_Zjp^xj1?ACewv{mC|VkJIllbr8C9$x`Hx zIm!5i)PQQIItyFn3^MK*0sg@DpTqYeJCEbkEz7}*;%XT7CsNu#7p_FcW0xZ-@vk3)j~PDlt+;;m1frg=_*O2R+NuH%rJ_)k)!_bG~rzTzwt+?`t2JF@Tva^TE>h;c~p zKWZT!{$u|?U;i4567w)sBj!)%kyrrmnthk)ykjU%2$%&g{~VSq65LIU)D0)JD|7T<4Bo=e{_ii{`}O~W zkUYe62|m`#tnCMPFS`o_6X0|uJHum8hX=Ng&|!6`2eUyi1vI^pJ#^)L%@L>!N?{V# z3n{Ng5XkcBM@oU<-tR6@_0rsHtiwY4`*i|5FYglkJ7W`S;;j+zi2ePiU@Me63Z{m8 zF|a9X!uZHXF*Jlz3eo62ypbCPwB}*kemwjC{bb#uD0#yN1C`UP3-1O|M&gDACRIt%;WgqPh$6J`RKk+?G+CwKFDRSU;XHoO}yMWc0`sUd{pA*<75q+U|37?063p zYqLP2D^82UG*Bp==vAQfjyZnf4_r|H=Kom*K&LQkHuHvNatBISf?4e0rbUo<5~G}; z|NYXGQt@d2&x=?ab2q)2 z0Q72uY4Gh@4BtIHo@j*BD}kfC!iZTUYO%@NJ;_og@^k+hG=fd=;SjkeIl%|m#@0q) zf8IeDd9=ZA-XQ&?v=^}e>ROE>f7kgxpUIx5AAGnh@aG%SY4$vrvFIQJmsP60$nyZ; zp+ayx%$z-j;R1N!uO0*}w~eqDHjp_(b%Kl@C`F;w2BV8mMs(oL`@iRylqoR}$Nzh= z5O{w-&}iBxF_HGS7x0ES5)w0EbqyUxR8-l(Q#AMCn0+VBe2_pkhkZm=kp@~xG)&;|e>ON%Z-5f_!-+HQu>pf8%9>$|tQ;%o z$mb^qiZnnH$mwX&2Q~v7m2mNu8SVZL=?U>6V6a27><*)me(296RjRZ|dn1VhxHraI z*LFNXa2Pp6-cbKT4Ral^jU<|YUaE)Nv+|@zN1L<*7li65-~>*Pdn@8^US@0|gl_yf z__|)~h{_K8q>!$RUzBeM=eCR#ZBCtbk3Ae4@{&bKLt`TT9L|n28cQgr#bBL5-dY?n zYK3XM7-&=>DF1z8ss;S-*m<&EPm%TZMU|GDxZa}k;6m!x_j5yH)Kmx3*LjtX}MRwg$gidyMl0C_sJ zr9q<;jS8ibCc%E^rdn`J}E+PPBM*JkLv1$1`a2{bsD#2M?$4(Tu=uTm>EPO*>dLz8UHlU&QUk9 zyXmf>EoD2-RSj*a-vjmvLvav858kABd=dr$@9|+5Vdvf5Et9g6(2p4hc=6p82b#~E z+w$ZnYGK*bZaH~8sXX)VEb`b>V#LY}eb3St_jDaZFASo<|3sAdA5Nt(Uo`ABh92Zi zz_75c_AEFdPB|qdtKinEA5p= z>4S8}y9ORdG2gV$AWMLr-;&~OWHz0AD+eiLM>KyIj>Pa@L2C)-XsyzOAXCY~JNaaH zt22&}5-=!%fPvm(JX3!u8Wi_Yh%$lzGPqeCx|Rx2o*uD?bR3+6j~YYhBiTii!Wv@G zII#O`{~VK$u(g`+L;N-8r>K75>qQFWcPx2-m`8)Q z>Fq)X-Z@dY?y`4a{Ywzv`h>euXiC7R=S6hJOX>~565H}f^rxv;UYcz8K2v({+kXIw zC^mmgaL~K1&cy~dUf65?dkYZjzQWR4VuOJ^RpnbBif=BE1GXMx8fW&=5?&tnTCymmrpu#AD?p+Uw(7=f4 z5+`tig4#q0ICg=he4U*tJ@FWhffDhWzLjqu0er`dJDg()oVT6 zMZqRKh|B0spLyFh?o}G_FHM92#U@zPlQsvOy4Y?3bdMm4Y#Q%}#H}>=&_M+U^4{RIQ^4}drC4;YXG z_T^&ODtH`T`H)d2&{}L37VLpb-ozIxJ^)CqsOPqukkMSKp3s&REC|-m6RBz*V^Ll{ zci`qf#hnHCWYh}N`lVeI>b`;+n7)@b>DX>v_A>gE0!(@%0-sgcx zfRnx{^_>WAs*$7A3-funIZkKdO!T!g89qo<}#yN;o14yNs%@2GQ5EAkV#& zEb#zHj|A^F$2^ar{To#0&3W7)>f-4<=%`nMWpoxry|?2l8Rz>!jZeA0$nfkLQ38U$yXs1x(%G;WFc!o@1u%*IY9PE=(9bsgC8QYrGg`(q<{Iyh-yZ)!RTNDP+{BiTdm*kHK= z(R?MyVlVW;HevU__12;Ir-TFBuP9UzGW$r%%k;X?MzvQ*Dpl0M9ybfNqY|(k^;LH} zegkBooMb`_mp)|6m<6HabhJ+@XKxf z@3cs+N9pALQ=rn~E&qtK6Aa)IS`&vcoz4BAiTwGlkon&VtCrGL2ZpwXMpaurjaWY2 zbfhh5 ziu1B^dsE>TquW86xL)JqSd+Y;1$u?cl``1*wre?-|>=bIL zm!-*V<3Uf~gp$FA+wH!Irs+w}4^3~1!6f6oUPQJ18ZepwYdiRE$<-OAJZdj? zmVV!lQ4BJ|^)9(yX(@iWF1KP-{F=AAM4_5$VJspWcWG&J;*_(|)bb6iD`u;swiY-@ zE?-7(U}sUQd~(=)XnTI>VEokz)B7<^Thq~UX!71#yKi(>^2NsIOIX^1*6F9CR&kba zgHpr_VFvw76lNnbhaF9tu5Kgd(3S4jTlRSo(MQz>djEjURUvVcl9PC+!bU% z0PdzWz+HKY*GTLrmJT}U>K`CAhohu3S639+HU+urXiVFhzwT?zGir4&*+*@&*@8vmTEjLv?mNH%)XM~3Hv^@+*>e@%5#z7WjhJaZBOvRDhQp)o$ zNtsG@Y0%kc2=ljcG_WnX^Y(zJ^Ooo)tQ`COvXEtHpn5N?miNOOxX&oKPj7-dZY>qh zFqV2_Q8GZtecfU4L)%73Tlc8sgPdQwFdxZ*8CT-y@~pPVK@>j-B+wG*uRkhrgIy+- zaR6+8l+|Mgnn3@^pem(ER9T^@RoaEc1>ma#%jm%Ucbx}~XepY}2;3xO z!;rT}Eor%c7(FUCqH1Nr-6Sv~g+3(1EqD5YE_QaEE~y)n)1e(gZ@(U!JS-j+qNB2P za=M8*&Q-i+`PG-{0{ro0>}Rdy<`lh-B`xI_!`-lKUMvGCey&E1%~_k_e#cttx(_`j zaPr~>=U)a0Yc#NhRE#*vBiT|?bY}~Z?7y1oP+%bxm#eFJxw9S1!oPn9O$Ql^t1U<6 z;x4D^9(EbO7#2imt1vjdilui&=jNxoZAn)woNR%XQ@jP`kDVlA22K%TAu74L7yz?Y z2=dd)ow)X&R=WHyxJ*yooAHianyJHElrC`?cjj+;L6X&a6OJ-e7`plOPMu|uV6#42PLU+zQKBVD`ql&4=nwcLrgdK z^jzKw7u8=^-vmSL+gRZ+X=uS8$09&QM0xb$_hTV=XXE&oo6a6E7ZF$_%4i>bE4C7NKLl(aUrKjjA@CrM*9eoYVfLlk8R@ zlxURs<`EZ!z2tAf2+V`3$xnmZ@Y)PBHveSlho97}XBcI_Wi2Wk*WCKv{wh90g6g-g zJWqm=5fH%@lWIn)7v5yjNP1M6O9n^Oyjcj7jrzc-ob*tduy`2Qp&Szf`Y#uvN~8Rv zLI{iLinE@NRW&eGU^!|VCSTG2v_spKQ!Qi0+KE~D)OSB73*Zho7xO&r=E=%;UJ!H> zaITW$k|Hi&cAPi1g=sTje3NXZYGJzXD}<^CPWMT_5%wFrEoKLRK)5?1$BxvVKfbUWxvzLLO zeW_w&+?|Jbd(T(G44Ly(M%oPY?-uq=L2-Z7Cb7u` z-|c2$zPfxh%_Zl(kQLF#MLmELlsw#C=dRCQ@vr6ddnC~PosfTGutcZ)K1+W1ih6aK zZtG?x5M*aTgUVebO@v2G_V_l$-vY2kLse9ZW9~MK^eg&T)8yrGT#=SU>P0PCwr!YB zQX-a4tj`B-yHo;$d1ApNYbG)VCpuX!Al>y=yTQQ=5RANXKlhTSes zJ?I0O_z=c?NXyz2kWG4D^dYXSc?lnD`}BD5gS*w6)6CFrT9})8UtQc6T&KL@|6#Vb zcnC5Q6zT6?ILg)MS;WBBr2S5P`B~{*4l~`8i~OB9AD<6ep}JLp5QDq{z|aMg&bz7A zYZ>lp{ik1DA9rvm>JraLs4jX-Ry+(s1P`IAElne34Wd3zBfpX`wSfi0$V_+Lt!Kp( zCvuIf@5QrORA$7%ZKIpseMy;6#=k08-XUX4Vf>J8mJ7|P@fK>u&@nEsKvqV?6cw*f zS~J8Rtdc9PwX9XI>RZ;lWlq_QR?)CoT$b&#G>hxwI)?(KxdqMi+g*kVKl_&nF(ipqi2*LX z2;mQxlKdm6bf#aOYbnTYW~gu?Tb$U=Tzssz!Z}rOw&w=ln~E-fdJbRCq>abjsexfA zO&N%tLMx+W!bg6S0rRR;-X@YIpMLo%?BeU(~o&zEG+T)ZN6<`FY3O+gLNKgL34Jxj-9u)$srg=gujO1t_y4*H2?Zry_(r{J6G%?rd|1>T~a(@UA6@NPNh2^_?c?Eo(UO6>-wm zt0+AA%T*T>)g7jFC3@Qz6Edshhd28C32Mo*Sh4CiEM1P=iiIEM$I{u-`YGRfm};GE zodc_oTQNOIi%I85>U9N<%F>CL)3#s9h-Am3N}iNx=ehAzL9h|WN7t;e`#iP++2wRG zcNe~KHn+Jg9LcadFdLPH@-ioDo?d=Fr12$n<*eTs=A-isPZuNa#%ZQMFbpUZ7`vMp zL`d&@xog3hRqq=WC-~rSkyS_KohO=ZHXV0KjOd;)&bHk?OaGohkRr8t*G5xQ~a7 z-=4KxkYYb~Ru7XR7d8VjS;ruMxo$E`{gnmk2RYVh?s`8QK}i%SsxZE9cGW_)-wsfd zKtJfK8O!;QQb5QxDbjT<_*B&mbx%k)Iq_h)-9-lH7I4-7&3bml<%c3p9N5yQPZlUj zg3ReJx0GXuuB|?I%vG+KYW3hO0ZDs|OWcPa-bHy8)gGY^ITFs}ea4NQ2A&Qc&mFg0 zF9eO%{R9ap8)tsbn@KI7Zj51~ zr8wP=7*(H;fRICMuKm?KeX!)@O}-*8GP$I&D7{g*o+Od=6V_pAX^*8tk)8W|K zwBlpb+=tqMpXbjUv(&Dc<|Bof4*kgTyH)?p@#@eMS=5N~S!~vJCX}f@jy~zhb0XRA zU(G=`-~^z>D36va{@rlNVY=~@m}Xh~7wpFVrVmERI40zo$Xv@Fb9tT=Ff$;d0zYX6 znj%=`Z!YWG^@ioTd8RN4F=5M;?ZT^cub*mzHkjL%%JhN-tF#Zn8_WcEG!;=S^F3wZ zPX8WDTJxiq`&D)vB$e@-45A3Ar|etD9xX3;ixo{ePxK0uAi4m(^T&8sNhnJAl~K12X9MFwOl2NV($#(d{+7};Vv zy2{JNeL_C=n&W-mCbs-FeGFmo-5H)_?MI zOxQ{!D7791!rk;$AQDjng(sB5h_ti3;Jlt1xuOjdQ**Aofwd~TJPC4M>^t{-%oTg;6t()R|n~I)j z>E*2*G7(vQrbRO58Z^zRPOqdQr;CQi_*d(udeXxem={KXbx2t#esA1zJGQb2d!U7( z59gSZY)K!he!<38S;r}bBmVBqPLWvq#01`nA1CRO!A(E4{g`-+oK&2)Gvb6pz_*kf zz3Pfq>JJWaPq%HplynxWES#jR5dK!yCHe#$B#FK`Hx|Z1QWpuyJ6UiWMLJ_E$5~ZUx+b0B716lbRP!) z&vgcmK;;_a6pg$OKGC|Ndz|14n`|h6lDgwisMTa)KD5e6HR#eNimU7eq5sHqFW|=u zC3>6hy%~Aisj78}2UE%RF~50M)hi=)iNz1kM?CzPa=*CQ;v2Hq&x?`N-CBm1#Ld*o z%KYhT7{E{Zh)TU5-Tf=EE;P&!*{<<$@R}=SCmbAGFk~T((_7Q9Od+Kg6aIc(NUi2u z50gr$*R8m!ss)S`x3)6=1<11>IuDi<7s131wn*_`D~537dd{~*NfeabqqHT zw9Gv?Tc0;7jL<7lr<9zX?82y}Z3CTG+I6N);(=w$>>#H2TGB7HyGAu?qhgM9dz4}4 za7kU0Izpx5D1XKtUmB(X(@UBR?QhTTL(68LzDsmkC~81)Gx z)nkDYPGRX=_Gu**{6nVla={C5wN^Wp5Q5H!f-o<7n+a3Ahr93ZQrKglGu> zzvf-i!Mn^E$>{~CKQ)=S0+&>M12uOol}m&8{7e^-Z}EEWizz-ouPWEwP`mTj^ORrR zOMuzhX{;rg@28HeuEb~Go?mNK4ZhlMMoAXkoq7ASkS(M|8u}e)RtQNuFF6|S_3+ig zP&u>4_Z^UB_k1_W`uLp4H250t@1%-n@=Qzzh^dQ(14lgw zJFm08c+VW6Lq|=hvyG|w)10&HyOuXyd z#eO)kKB~n$9n<(FoV`Xtp+h)*s}JmQ-*)}kC!gF6UhRQ)m`fWx0=CshW@w6acUDSk zU6dbieGPb*Z(}^o;6A2VRU+%JW4=R7|M>^W`HJDJm+f)!QASf)>ndN!fG?VkA(rd* zXCuR4CKsx>=AuU9auOV&^)?t`=rh@O^Dx;G;bIDh8vy@bReh%}t-jn4u~L(3k{Ir6$gDwa5>HL!XhR40l1!pd4=OQbSpbMB@g^iH))VzmJmGkcx zdDfT3RL%fPpoZ;*rdE zhe~LU#M^zKDS;rCgNnRw`<{F+JNqi#KEoq|(3)7DAbXsg*z(08)o$7O7|A8WmwM0d z$NbKHbj!1Vs(L1I#Xs|A)lyifL5+gA+SCbqu*=|`MZEFwXGOBogtsUfg_cv?vZ z9#nt%!2ADJFeC&_;Uoif7X}$$8VHgob`Ze5!TTW*a$!H=<5fv#oaTZ z_*?j(vIT>GnEJec`=tx4b`+I&g2c3;3j*_!< z6!R2O7i-?(+fRPYyL_F{l=1X5k=fAo)^U={+{{js?eG0R=*Xv^SjJ;Jp8n2>_b|ns zP#$Ic_h$;qKY`!Ccenpay@GmtyXlt&F;It4EnTCQdw%&8E+6eXbDJ-|5y~E z2;G(}d+jlF8RAY3q(W3hIpudd;lQa)&P@KP>zaD&OcD$H)+7^EJT430b9f73=ZgA( z6%jLX$d1!pJk842=G3{e40k;LlMQKkR766cJUbroTV}2J8Xox|)+pfWZ0Ojg!ux!w zQSN54HWHx|#o+UXVrH zpZ6EU=3604!=CMK`*!x0NSw_?44ZONggWj!NHblPJ!6}V0`xcmdw5WR`^dz5Z*_h5 z3zOs8B%Bzxa7AuHb8QZtFGpyCh|@#`0c@Kr z$6McSph|1$o*KRFsdHWZ-H~66*8e@?8H0)O7oIT(c`Srac5-toE{u%|e=3*doG6Ue zbM?z+)(I9?7&?Y<93kW7&^e-BFE_w?_>nQ={raZ$c_V>dCEVe-Oy@Wk9GxW~1i&bF zU6hsD2pGF@PlHT$4r*^{)tY-Svq#YohkKa|T%ms`Q{sGfo)~*8p5QK^tCjOwnc43} z9AngL3suh-W^&#BY?-27+eOAOt@?!+S2^Kb^NMisX0#v|Tik75N6ejKW?MtOs`TP2 zOIbqJlMh-CM-!+>C#Fw@CS0DrOjT`gj6!?o*IUw5>-cMQgg-jVm>E~wnV$vFyN0cR zwkK+=_Kg^t5BLk=$WSM)6950{bP`2Q~7e_x> zac)Av??k3$wsTz^H}6N8Z=am&(yz@%?Qc3(HhKxt)Cn2ksIjkF%Spk<{0p-zZ$hJ+ zT99NR&9Lue1?5~Af=AT&5=WQSJ&2jEm z)x-G@H75pM^KYp#k1yT*`suMtyvj;NUS;S#64E~1FJ>lb>UKD497D_-4$0Na(^LRDd{L6C-^Nfsm4jGFc^g~;`4>i z81mAMecx}Tmy()fpr&WAknb5?XGi1q^J^W2A-&$_ZM*qtZ&tWEaP1E85p}cc7FOSO z%4@chE!3hgJBjUte;zYW*qc*z%Dg$EB|LiNZ*G@bepS&D%pbYaC?D~ZW&cvn3coob zhBatEtWB(+1+jyzkB_)Ssp}>jp%^ve4Bj&E9j|p;;ma19NMP>esh`M`jmSK4;cYeZ z*~-Fi3(zNT0n}aNZE}>&Q^^a_2IV2chAgR*n&&cGtT`S`y6bL6AYxjyn}gzjA;rwfh5s=xVcnkuIT zKIXiAAg(yQLx4Fh?AyzX58Rqg7e8k7q!_z+MUE*BeDSt^oEXb!uzm6Nfv?F+nC3dY0VTditBaq;ZkX^MsCtkthao8woq$9*xqqCUYROIH*b zcSdN`^?aaFcLx>C_D40hu^qx&UH3k`qdH@_3hW72Ek%s>GH0!7Vskp~C%NgY`g5+B;`BXUaD5lJNVsC z&~a3holkb5S>dM8D$Jsw&CsiD-Qty8z8~7_d-Ml2aSCESHL|nLV=qU7dg9HH|E}59 z9?&Xq=ov@^Y*TdJ>fnOoAEXtgb>R}qDwJ(ATl_% zGL+aBZmt1NgAf4<+%2z5rGWBU`RfE;@AO4 zRhdQncfA?4ebZzK}wtJhdoo_(?Dx#j_*B^-T>lDPc^Vk^$eo0Pdao4Tp`(tNE8-THgbCzi!*PMs2Cynk z@b_FdM{Mf>JptGD2if5atdaZPAi{w6p6}p!J{)juXgagJsc}x1?>fv&dAA$-E+n}k zMb`XT{)3cmzIcD*<0SqIetQljgdM3@mhiZl|4LoR%fgHmjeiP~M(7JW< zo#@-9kZ*ns^0YGzF#$~100E!l8rVHv@D!gCb;C>JDi~IM70@=WMDlWa&ox2p1j)yF zoTzw`eAT2)VXND8QMC8W*~jYKmeBX3?mpy_vJm|Kf^veWmZ?)HpI}VSajGxrFoq)+ zdkp`X%5k;c?}yf=G<>Ynn~U3!#m|bc$B&VH%TN!j2zd=s)OWg9d}nHW7xqxJd+f;% z$k?=D4$~U$YG29Dr_%rp76I({Vt%k1`rL|jt->Jkdm&i5!0HK=e1nd`kd(m=5`X>U zRmIq$)tnqsWdCIMiH!-1XHek@eKqX6c99q#CDAn=pRO}FME+{41zC#&28@pQa4`QB zp{Xt?=`HX)R@swIl0KUBEqMK0?NpWNMT`W%xX$zJ3d;NIN@DhZ27*VK%84fhK=ZY# z7IcRCpfV2&k@<_=o)9^4FlSs%)+PzXOd8GT5&Xax8evQ7uD~(T==r-zL1f7EkwTu#h;8=F(8-ogE@ z4H&puOCplD$=F#*{7oF~yASj5ZpFWHwd+Qa?X?_1kPh@-%#jepyH?wA8f4eg50fJ5Q*&N2Gbq50(l^801eV$>M#-sUM~XP!d5 z2PMo4=TeS4h1J()H^m3ubjDvn>ZsL^loGbl*5P_@4R7^APKo8mV5k5zCQ8SvucX`- zeF4nLiwt~t@v&3WAxE0Y-3L#+c_2ORzgihVIJ0b)n-F$`B?_DX&;2ff+X;YDZWek!V$oI87` z_`YcJ*26uww^logengXf%v9naKRE^NpbiyAt|Jc3DOby#Q!H_>SooC-bxP;VIw})v z1Y*1OpwMysIthC4$6Ra{_nTjLhLIwrI<@J;P#Wr24n2$(3@yqIcbuM%4E-caTUOyL zYB_BNDU&~&W$j2qjb$?Z1BVu0gR+M^Cv{3uz8}~2_jZZBu|c=sb2l z=__18MTiq>YY1Zjf-AKM?YC99O270$aUoh-kyF_l9Jo}Eug;>&vRvdU3$bHe99Faux`6^`B1lDjYWF_LAzHyCUH-R8(T~PB_95HTPC{jky>Z zE0ONR;Xx~4_)gj_11KVQz;;13#fPzUgv~Noj(?iE7|UMPjz!`s=NT@hm3MGn&pcIUSZDW>IY`<4%PzaEXs}4bGi|OGnzt4K3Y2tQbl~6K zw-|d;ysOoi7jJLbzhyE~<$|8CPx15TeP;aPES=GwKS3~3xjz0HVbcEaS9mHC5N0XG=yebSSdd;`OX&%N}XlfGAQ z^7|wE8)hN0PN37K$DduaXtYAbE@VHNHYOD1-y=zv=g_hxry1P1>g@D|cNX8bWEA^E z+P8hjWGc-)`|VBP+!m=W*&Qd&F55C@I=rL!sg!B2*=cl{aUpacMglY9P5yj6b+TfG zB0IiBuXm=*X1=M+>WjS~5P=JyR5V3dUkjvzr0%E}^!4M)i@?X>n3_FMpLBCDw89Rg zz5ah)KoPnapez+3O5(O$0Ck?~9bt)>4dNh`<)XZHIgK@iF5dXIQ|PlIm}W_yTB?C- zzlt{h6cc`HeStw6Pu^WR>8;i;amr9Jt7SsnjmC{af@E#TLfULlQc>*yo&)m>nIT8K zWMS(l?uqa@RU1q@>6*E#@AZKw4XKsx`M!vHesc1h*~xF0@=sMw_Z1bCmy70TvnnU! z%N~in*OVsk-kWe{mq?(Snmn0!W3Pn7CGzvk5u!lP4|f(Ckeub=vbz;s1+1d0^$a(i zRh@JZsaZIwErwq}P>SYyjp7uu@#`ZFAVM!--bUZC&uWmJ&WXzZxsQ9-4}u=q!Zm`s z%BfkxWBah@)u-ytx_31dSh)G$S(Iu`i)N2#y)Dy&?~tD#?(Iq|c3~Wp$2lf|=u&i$ zUb)J5xC$HC&NS8j7`KyK6z23?g@Y*R-ILPSaq_-%W+fF#kEvE)&n%z)LL>GI)sw6e zhM7NAg872y_OV{Pggqa`iUJ zD!Yhf7IAM87Rf@sPXHPH_~#L2T+1-aG1^4gzyLWG*U-A^u(rw9skbL-k80kmWoiwS z(B`9AFwNk1+1gdge4CDOVo5}^4mhE)t&pPLyL=VjCe{o+yc5IzYJ2A48Xd#$l3kX9 zXd&q+TZ1xrL1P6oX~|ho{ATKWfQ|jSoopDVMkge-mzg0YS_(M6A5@esnE{QSL0f`+ zI_DP%uOQI#TS3HOjh6YN<+id{J^<6K2&q3aGqXRsMEfE_!@jxc@$xACo10x0lpa7< z>h5%US!Aw=ro&zy#s(DyF$V^W;2;VchlcR8%X+}g%k69v(#AD$L}MByT;2omEW5*G z>|9Q$l}4eNM{ma_DjnwUuie9vtYK<5?IaeAf>}2Cw;X9cFwItdrB_JYXGPgmv!DAr zqi4-@-?zco#6D$~f$qwo1-St?$ISUb!>W!mBG66AGCT8i%FNYe6qGcbnv9nY)iq?h zi*>l9ZH@fV+Ptk6j~g^%&XP_Or*O_V&JFupvhS0c}kra5ofOeBrlO{graZ zai473Yf@2L9PYv`$gsyq_>*^!sc<)ue*o=#TX}orrYTraK1jWT)Lg%9-+Av(cQE;; zzFPLV{H>0teLTJ;-PvHgR9;`?%Pb^=v-SFKj>knuAIA5}tu@i4vU_i+Z~OOK#YQ46v*XNOK4sW8q{4 zn*y)#k&ZBaF6A4ujR!KN27&Ou#A&|WcjV!jJvw4WF#4l7$jYntw&+RYoN8{lp5D0? z3F?niY+rx~-3McDlAGH%yNkWqbATccYz<+QPyS@PzAEDvY`mP18I{Bk<^*Y0Be z%aXOsGQ-Izc_~P$=jgj}!vhIdZqe@qNWtWxoy?qqP-f+}X@pgck6gf=_FgpC)YI#V zdgEdtET{v5jOuxYr&`sg_lO!EfS zXQw93&MtB&FEtKvBLhqLaeCkD<37cYHF&6dVx75%?G(T1eCbnKxbW#Lh#{BOSSs*l z{e;%_Ww8pk;;{=onm}JHseo*|{Xu3>^y1SqJqn;Dq#8;$=$PdIigPh7AL*m zaBOvBJff~v!`dDp`gZFa%fap!QZ5=hqdGSKKqT(@q!xvq7iB<*f!mDR)=%QIQ+D3| z>pI=cdtkwtD}D29i+bQh*jc1- zmA3D=kM|Z@1vF(GUMGa3@ZQD2Q{9IKU|~FKH!I6=t~-zM8 zZ?Q8$X_DIJNj3AWI5D^4l;l%&&yhZgUQFAy-K-Nj?NF2?aZm;qGktwBYR-O+guI!h zXq;v8Eg5A$q;JW3XDf^J2<&4lw>R$=ddB?fl?Jot;KNXXU#xCtEiVV4w5vs2B<#z34Dw%MsW9tD_<(eMc?KPgCPP zCSvGSixw*!78rV`%`4NFG?|o}+V?ruWL^KYN;RpOcI49aj>^<4Ksb%yc%L%oc5;Zy zXEd=TyxQI~*dK2q7&@zEgDU?_T>~^-xe!xo@1$D%}cwloc~_@ zXGq@LjtnRm?eZE#yIAK+gwNV8W~9$yT>=Y8=AJus;b(+7z~b8sG`~G-^6~dwEL?@s z4;eIkIX%?X0JswSjZJbqBreMBK5Byb3wMI0T=%?P%&&Y90+Sn`Lb?spj2oL0y9nm!}*P3Jy~!tS>ODa9xme9CKQR z0X|8AQ}df_p$!8)ToCXMS2iDIVh#M+6YrMw}ar#;rB%eqRkU=gu2}oY7d@f+xw3`fqB;U5{DAi3!jAT789f_u6KKI zw+LrDFS|u@o>%M{5T+a2BPd6@&6d)AoQvfD`BaoIri+8dID<{e#r|x6 z!zHG6SC}ouQO(D8nQOWD(0~k@7z}}@6%FdqxkS0nx63Gbv$aOODw1XdP4+z0q0}$J zOEk_sTuME~8*}>D_{CMw;kM1I-P^4F`U%z@DNkn{T#$3`SgF-aFkrbv3*8RjXRxX9 zs7rglMHXWO<~0758l2U=b>?- zZrNO_$)Bn2W8jg^_gOQ|{R0qVcR1?Kq3+%+Jkpq7n76Jqe|x zZM(5o!aO}3wum!46r5y^X>O=K$_`l15Y7tng2fh*&u>7-+0fOQa}Ujd_ZAx)(36l& zZXl{fK)&gGE*H6)vuh#1W`qTvMAIS%KM8%jX$KHfF&InShzsfIg$Ayl)oeG_QA(zK zyP?z2yStF_pj^1|g+{$B^CYeu=%{HoYX%6g*IbHUOIfw5zb>jto$aK_l(7ai8Ub^8 zH_bg&BOl>f)Gu`QxPIwS2t9uk8E0%c^8;tV@0C^_0n6*H&hWeQ-i$6L_IJO0Wtx%4 z*J~zAZV6B4#yPyq&rOln(DOGj@>kfw*`7NoRizlKA0C7nXI(mDoQcQSE^bI}S6cJ}nNK-51rW5T0)2 zzvcF$o~A^LNr$P)ahkaUW_Lqd%UpBaX?x^5np|^v{ckwlZTl)|e{65v!LDD=Ht!*N zbY|?EHAr+^RX=d=mjhjA9?&9%w_U1YpV~ho6nqaRTSg=IbkiQrJULO$)>?v>scQ^Z z5(r|0=+?<=-NXON_iV3DDb>LfS01?0rsh#~`6Kju*mn^eb=WyA)l;LppPs3TcD%=) zeTt;R?o`$75%Wg)h+@j~!49M~3VKd9gK8yyalChX}$r4n17RdLl`YMMPCHL3Tg3+`LC!Zp+s(s_LuEQz|HyLWAuBp|%|xU~{(r2PjjJnsjQM zoF_YB%ym)P@T~u3TDG4dS_4I$H}UHFDT7G1v_au+4gb=Fzi86dPfwpOVH%;X9@#!* z=-)m}u9nh-cVs^MW-_{5;W|XK>|0vPSKBrxV5$1_G<58I4|7KDyEL61`snPz^Wr1T z%5?47Pe%`iZvr<#_sHlj*e(4?FY285f};Sh*g#PY4f+cLav(g)0t+m}62wQ;v#O zpRXbbn6lk4)bEtg5_9CmLVm{5apm%(eXMaZVCGio4%g*Ox$1#B+~;_`RqyV;nLgX2 z?jBT~zl{4>y4}F7TIu;ETMrlvDqB)A3T$p3tg~+%Y(H`M6Y?T_lHi}1mMnRg8 zZ9NmSt?5gzk+awD*^8&S^nQ8y{V$t=AE%b%gWVg`Pi2nmy72Ki)jjcrQ>SrOBk$Bc z?d7dn6zQ70*Xl6PVb`Y6x>!`3V&n<~xslyEvOSBPce{#0vqSkypaVsP5170_uvfJ| zTeaD7^^C^**S%*f?oHO5({T*Sv6Q7Psj%DDJNYDO$S1n?Af|yeM6}u}-|e*fT7?4} zlztly5qegx1)Ve*+NGSB5NgnUy8zL`;UYHXClUU$i{<@2YgC~Ur<|O)s13POST~c{ zgYbRH2Gruee%hZT&(agvF{%Y6ZK&Sl;J7ioPb=u(F{tL3i@rP;B?{E<1V)y)9W4y* z{<8hzz4wJc6-en@vbXg^>jepGxdQHjR;>qKLwBx-f-XzmT*k?Ch1NIk}ad zjGu4fBQmUATvq`-+3T>cmu34^rciO<-po(Fe#3uy;dofqvy2)>03wg!a!~uIztAFF zKXHlvVwq?OqNUTY9cef63Ze=jqgA-P+?lQ0Z&UfhG+xj);l236`RC1O{`FF4hAJWJ zYy5HEN3;{l$>N|R~;$5 z-h59)&|zl?nM(gzNxHfpmcQ<_)P1NtXeG6rHK8J2R8!hQI(o-X;ljxaiTjjaR??Zw zLZ867`DGE$8JB5&_&VioueQ(JG|aLT)t!9VHoDPBNn$x- z>7mQxxfDIVHaqq=;?0M2o7fXe#(vVhI;Wy(Bs`Ynqo_CFsQ0zeZQ1V2H7c?03}wTE zk8SK0CSG5t6N6IQf%9y`hq7`(lpJN3~X8>0;%~)#$?V+VrO^ylK@& zzS)la`;N067wo!P$Zc)g8(x%gvRT!ZV>~ZE_bJ`9eQAqh^-2H7*`o=zOi-@o-+?zU)o(g4 z)I-V#uK{u;b_$?6(}IqScsI03%M5#=TfZbg1gpbN835U$_}A)kKll@y0=?y0{-f0O ze}*Gz{7u{OI(o(cHu^4dl(AUDgdBr*W<69=rW(4Akx0B#Ia?*!o7S;Y)#L8kG7;#F zNZZIsDG8pI$(Uyb#F-XTSgMYlcSqO1?NcDE>{T>)egnr^ZN+y}v;DWy5OP0&XLvW-qa%B+deKepMfqsB( zuetGk0Y+&bvNJ>a<84!ww+4U&8xlnNdjr-RV@hW}USJO|A#=Ztr{C?RgYbNf60RZd zKi@=_OT@C9t4bWcs-5k`@>Z0AvXa;LRe~g1^%?lhWpMAK(aTk#VgFBP27KuE2dwWK zc+OObBxvvwA;Q(Uo8J^Suz+|d*^$`KBk&^$Fl!b0EZXt(=^cpDtL7-(v z^9D0J144&syg+oRZk`7=Q~zD+!<*rI%HJV^z6p+SX)dU+ah`uJ|)foLR6^pR#L)yA3b|W8MZiZ3Mm3q?3Ufx3F!k!;kOoR z{@CO7ih<9pg+_ymdVc;5xW<+@nYOT|u#wf{Fv#8rs2u%Bk#FcBP}tCRba;znA^S6H z*emT>Nql_58S;#?sR83#=AhHs4o7?WNnM)TGt`I(0^}TNAU$acCI7w2jPY>TxAz`o zCX#1C>9xQDqjZe8@*&qS0R7J$rUjc&pjcGjp@1zxhBN@IP`5_|diEm$CUdj1*Qkld zoQ2^sNKR-W1`VuP@}+sk29TD@lnZBN5FuYX$?N+KompB;;nF@Y>*C(pGhz#BXcXOQ zxIXkMKsFbEjRjrkFGfwUkxMNa!3yReqVdWJEo&&7a zwApOk>7cbu;}t=M1XfWqJIC!N?bTf9)Bdo7kG00kUS+7Z$~^?yMR_o5zfI`|Vn$KM zKSM_dSoK9)Dl{MGAI>R%y%NYWc&*()j)^30R#qwA?fykz-zk*S%wgUD+{xxX_@n~q} zihv@}by+Y|bb6T&MdG}5Dpk@&;)Qn?LOW2p#GORp4Hv+h)oM);dna`L_e()97(%J% z$910G-#Fhh!2BD%rk!b|BxL@}LMc-xX6pyYA-nqK)S1P~A+?Lzp8!H}U;{y>jl~JiZV*HeBVRG0;b&yb^qvc|1kN86L>~ZvcbMVeF+^6t}>T7 z)2bi9?mIYO;!Xn_@*Q?e4F19TR{4D%pDKHj{~i8_`{)b>fiJ!zUU0QKlmguc0_5Nr zte8NAggSnQ zI&s<@6TNSiI_^=Cd!!yNdeZnq$;#B(gW3Kfw52z%kl{oWy9ohS~UN zm0D6hoqs(DVtFMwU<<}+7_8U8o-^bjGQGgnsz=kw@uDvIVk`3-6@c-;d2+nXH6Qe=YLH3$J&_1d{#zPP8OpC8Dg@ zOL36*v68sLjT&LS!B3=Y0kf7#XnCx!b~1Jy9={DKi*ST8V_%5Z?=&Ozw5Q+y`iXEb zy?fujul@Z1UXjl^1vi7@!v32MWz6my?k|wjXGf z_fsN1;VxoCE!H{Vk?k*MxZ~;n`n5Ke)|2p+^b5Aw`7Qevuh$HO$HX%bLXI76xi=YL zB4|4>^(`HyOr4__EYOd(GyV1Qjzz$Nx`Oo#bH`Wa2m+S)h8pQePH%+t-{_GwqRIIsC{z-(e7dg}ECj%xvwBsG=cN{+th!Ku}L#*MeD*pE|ybSHHH^}P<+|^@F`w{Hrw68=Y$-F-8p>z+JyTeq$d%8ohCA08N@c zra3jMK@)wuVRkQ23w**9&uU3fU`AaRr?dpho0gbZ z;h+5eo$G%jwBQX4Hoos)KSb|m4BDiVh9CA2?+Ig05@2`Up`)G910yskJ4P~Dmfv?E z>)L4>S$HFehqY@IC8=mT0tV?vTN%!gwDJDyQ~$N)(1NQ_!kvDKoRJo@#t2Wxf#$;t zNVq=V$%EgI6cokJAi#mou!gj!%qlksiEw?JdFR9W93sO3)?835L=DdAfWz6jOm{?I zcW3Kr`&sZg5IMAdnRF_q{ScTdmC$I$!G}33KQGS~3)N8QtkNh-36@zHkv|!X+3~z~y#6=?U zqpLo=e@WRfmJNFxWuKHCuGBV{uD`4=9`;};K==X`E4rp&~(jbkn%%~k%q~rlXo|;fD@e3e!sJZjZMKE zy{U-!d23;3V}(F}AvQ;tbDWf8EuGU+Fo22fdROjJpzjE^ z$XA}p4v6ykavxy+r-X|8!W&dIZ$boN6r9I}$mQu_Zj|!QrqsVyWaE$jN{>>}Y2bLC zZUNPgASw7tZOfK9QD^tcZo3{$`jU0{x54;5R`-^uUIei{-!xi)WrB2%w@iTskVacRx(X{dwX> zJW1`^CA9JCiSHUxb9Q?sX+G^yffJh{hYph?NcIAuiMc?&DjNod`aswf4L4}$r1aWW z{-}kswymlh)62ydNkAqT#aBk;DU4iJJ7YA_Jb9cMa$S{kp6TMPUOe&X?$9YMIDaO0 zpCQM;7dQ8mK%w7-CX9Q^t{spG+x)_e^dFD2whK3IXgHi3hvWm8I+^}5lpw`CJ>}W{ z!1o!jO{{^S!eKp$?1g|nnp7{4l3;Tf@Fn~=N-e$}M+>cbUqdSUookFk_mw&Z--Ilt zK6`+Az0%)EC2|x2?mi>^`eMbN@*LPW27i|CpD{xYF(x_oKZHDh{V^8Q=uKy*4$}OB zrtqNajmU4k(oqmRdZB-6eoxqOySf?l9Ew3>aX1a%6{wV{He{C;p8Zw!7t z4M~Aw!X&7NTOc!zz01IXRgSrvg}fhN>| zD=GL9D%O~wk?~@exlzQEtlEvft;b&(%a3D5e_bbh$LRmBmqZ2=cOzHqH3PS!Up0Y) z;q5~L_M@*de-n*I1^j2K0%j;)k}Z1Y@J@X()MybT9ou77=u9sD@l&oBlWDf<5q9lZs)^E zHT;7J1}r|cZ#lunv7D>V0d*uJNgU7JXYZWeTLSfVfOOH0rn~REyzyI`TM7n{aS=>riGiduxHJatQ#yd-RTq5i%Lb7?M`h2TY;?Ye;v1tZJBuH9(>m=Gl^i zq=9zP3iI<uNIYKvcd=p?*j0~-Z`ZFoPxM_eL@&s*4mHZaCwvbFMj(uaEFa4s$ywa% zZ?dDWuGskFbtK&2wUce5qE$*fDc0Em)1|%OSdnGfll@=t-&+!!DE__|))(@rGW|`N zTLuC*1$m?ZFh46pNa=>AjcDgH;P_hr1$bvKJ_wzl#h-Jn{fHFJ*$0MY{V=&GCBTbc za5(HnoR@|p%805c1N^J4&3^^5;r(8S768aCmFt01Qd4iA7C?Q{9LH~w!oCBmgZcT_ z+1}WVzZ0Y13!Y?!=#v5^BKLX9u=`!YNHd{@13B8>N7kP!zM&-0*UDcSa&Jq3vJ22; zngG=Q`vBI;*M$MpEv|tgR#hT$3C#^&7kA`mM7 z&Tzc2xCjM4@m^xxX|Tg9RUx`>@a63i5Y0tC*Hw&me$3@7K=GaeDMA#eULp$QH5TNW zegTx|=Xys-`H%vc_LGg-_K`9VwEamK2P0K6 z@F30@@FC2DZ}0|iZ7KJz+w86!QhH`hkwc$UNO%7OA26mN5eC%upFs=`8WGTzJw%c~ zmVW0rHw3~H(gx7`N5;i%x0qeQ&zpvA)dZpcFn`hqQyHeS-uoV1R*-hoyVAg7b5A?v z$7+t=z4sl~z<$r~)*e8$ju9l7M(k&>&~saZP^sq!-a

MVXbI|JmJ8nI*x_?go1! z6`9Gd$7U$4ym$FIj=}BWY4f!SnSZSNpHukfrXtWYp(6HHb4b}e17ouK^O$pKigM#^ zFypFS2E9t%I|bYKb!u`cm!L+Iih;I@Sgb*G2zj*?tCj!TsTas=bg1smw{03Q3a!Bv zA07RPSOGniAuLyZBB=!CCoC*K3`xt)?1~^qiFN%Zj04GkiLk$81bR9`F+zN&wL?}R zTe4uw1vZ$*^d1DDC=cgP>( zm<5+d6{+!|jle5O`*|G~f}REx?Q|p+4znd2nxVL|8~Vu+4~Gy%2q@A+xz!N9&{+ zbnrOi2_u>N2{t3g3t-FU9W#4!d_s2-RC5}>&~;Q;(dR-68Gf??p-S)mf_h^aRTj6F z!5~d9zzZ6STU%~z;4~Y@DrqN$0X)Zl++8Sp3DNfM)nuyK3VWBn0SoERu&d`T^<^Mp z^ugdix&05Ilvo2*Fio^Hh^GqEjV%6mBoMt@4hj zb0-WQh%|$0Lcn!?OeJx63%@Zv2EvVOAP=?Of?a8Rn4NJ?0W8(sX%Kz#h(fB=s0aqZvv}LvY{<

|i*n$&z2M&PZS_lsYGFoVZruoKMf`ZO;?u*?F+80C7<)|e1&Nz7JdvAjC zAP&`GKb=Lre$0JBm($P8;34CzdIxydt3s4xFaQ^MxQ;`fOEW;m;LC?DzzVkN?h(hlNQxWuI319ykQUSA>KoxQ&CP;^E?$ zbv9MLUR`ZC#wZvyN^j=ByZmBTvGdo#kgVML2##}-4YLmYXnvDhn-MhacR3aT6C_!P z9IR3eX5K!{*1QTEz#|XR)HrNGCAwEbBC)l14*6|;huy#eY(d3sE!9z38&{qU=PX;N@L67Ah7g7W_CUAqs^Vbj7b_o=uq^9R2B87ntaF+$O`9Y+^ zNBksCA7bBd9R-dCkcDoja#cc+dl53_%YPYAGwXod4iV?g(4^J5A3z41+3iapN}&Zx z4vGVtk5zU!@G;@gKpZGzQBG(B>NM-(u-gP79LAzvphEPHr(*sr;-kIS@I_Kb;t571 ze*b)O;;s6xd=?$bkPSAAwC5H~uYv(^hLT&LyWfutM)O}%hrU_NENIzoq7NQ}Vso#K z0b}NtX#Q!jcW?m7E&!NS*Ha*kDsC1l-4!6KA77Ya)4yD@F)0@q z5V`vg0)=?zf*Yvf6hNljn+>^W$h|eN$oL@1(*OD7^ls>0O|U+t3`>2M^$UPN{ZQ)f zop?#-Hgyq>`L15P|5(RsXe{pD3r=(zQ&1d}_NIhpq$7m|ZD@t0^xjI3+q7Ut331@& zF6z;5a?8FoYi)3Zs7x{NdHi(N;1U7;fJ*vg=R+e`uMwzVcmHEfnm})Y%|L^R|8Xg- zM-4B))~c;y-@Mw1hv2)_3m&W&W=d%vT>=VH5pYv(K>CRCbLgGy+N(-!R2zuvO(Dnm zdJA-&tMXVuszZ&GUN{O?)O7KQ(kuqe6A6lokRXB*sVUM3RpO1z)XZb-ELxoIhYipH zC)@PDq~Y*@0jvZdn{C9k_03DrVpE~Q7MQqGAM=3AOAZU0GNg6R5&%C1o#lt=377VA zs*!dbyY~I^GMqY;dpC7tm3PiSeAA=qCS$k94(p=c-s+PPJ1rDP(J4KMfr`IKfw!U) zWv&x*pj~1JMxDuB8LCWc2p2uUlm5S!1^;YMC%u7tfQp)S3%ut1(*~ojVj0LSLH;}w zz%!Owdfp-cfl0gO0PPu_Gqqeai&AqgT`4eKm82KJ0R=-S&8gRzw67qXw8D>Yl>+c1 zDf3NGFW##Fjx^ce`@^q?>8Fvu?Lbg zVDO3n2j2?7HJe~iqIpx}PcaQU@9NOMiWV;}MuNtFrYUQela>HnPFls)V?5Aq5XQo_ zZU(MIyN?e5cPjkNabqsi2OujO6&<~glbg2yQgmD|rN3)wB=-RY$VD?Db85&45T*|i zz#xPT5yEYi=QIs_$5w~Uh$+VwqTMedVgsEEa+Yqc!%K>6O{^rRcl{L@H@4YtPRa(v zMVJ9lB3`6FER;asi_PFA7ywWP)l<3W%gi-Q=4D9MlTfj5Z##Aa7gXgdj9LM(w>2=Q+pBb;^d-kEh=K0k2NyZ@1E zv3@#=;nB*rV1A*Mr9AZktiAJK_kxEGoZn<;IY#_I0${4ioX~*TgD!MMOJ0VkbZy?O z2a|vf_k+Kv`s+*Vd%OzCkfB{eS!T_Yo)2g&2q7OLH4Cz(ZH>ut1K z6&ZD1K67g`nH93I@IhvanpSlFCa}e5`N{v{O8id%&_Bx)Rw%pU{k45h5-S=z42+`| z!vJjc(js^ukoG|er*rU#k=zjym*{)o@A_UI; zcc2N7^ECXQ5BczZNRUqyOB~pZ?f@%#5H5>R5dHrEaf&}&tk!J^|H+0U~1-ynS zX<(3}2;dW#qNhNvh0{=^E1!AU`CpKH0-jW5%ioVfEQFG#$k@xgd-Dr|4sf8)4P@f8 zdHX~qQTXcAe)PFq7%21{U*-d>yBO}aIOXr8l?b(lF`XB3oktEY+Mw;&{}gcaH_#KG zSxZ{zt+D2$|Krv4=ZyYMPV-V^4Y76)e{+O021+BT;$1$gQ5Y}8jDdvibBWGB%g|Vf z50I<~;QDgPW`sNJ#NQwv&n@?fM7#B)G{{US7ROlu;5N_LeY{7<2ql6*UTLSP`x*@g zrF0S95+_&Y&w(P(`&F)(cq20_f0%pCpeI?egPX*?Jw0{bXF_Vw%2!< zF>duDB@y!kQv{WISD?V42CI|+qn46q%O_Hlp=$#$I|b7%^@1tLV-aTl|AUy4#EvOm}ZrlXm`lNGh*_oNpg;yhT?596N@HJEXu2$puM( zO8H7Sp|dPg)OL7O_Q3gk(oEn` z!4(YA(<5?L{w?sPQ0thiekX=WCb$rK1%1#9lA`Sc7V;F*TLcM**5Y2%c$I_Xs6aox z0k{y3;$+8MfqZiTj*gP$ONxir;SUG}=x8d1^Cka)-KB}1q&XTaFxruk1QH%VdQ&DL z7%Acj_xes6@=tKL{xs^d+C6SJLzKHdKLQRHNGl?s=5yl?!)9_)>2(g``wLL6g**MG za}&lXo&fke4UBPqF@xQUU}-NbU^gf&@?$vM$MpHe@ii7ES=#2clO7d(B4A3W+nNt0 zp!O>|$Ua*D78XQk;k%;2yrUBeq$nOBbz+FwcQmzfBkeHIs<}T|@jda^&-A_g?;C{} z|E7|K+{W%-$1Rfr$=Nk(Ynv_;FWMwZ9EckArg$TR_9(+U=E5B~#TY(ljZ;sh*W?q+ z-GIGm5OaWoh&;P>p_`R9bS+oCg7OH$Y9Lo?Q~XEDcnXiGNwin$8GziJam@uLkF1e^ z2I7lD{$vb#RC!>F_SDh^s|zXkJBJP>BGE?6pI-UI2qm?!gL(ZK<`P_uh;VZ%vf=w` z%68~qK?YhR(w^A_dOgg@V6*JWwP;U}!^!d&q1reO9m+T`lBmNG=;a9mM0#XA&@BdC zqlwA}UV-$N!Ds#HK)Lt5@%L3#hi%|IoNiMT`hm^(L+t=cHlzZYP@z~sZJ38c9=RRMAaGEw%;Cv ztCZWukvP7tvY+HNF<3YzJb=yg_jJgbmQCr_iJ(vGa6?EhV}X4I)?qP{zItgefl9M8=5Z zC**5WsQ;{A*0K)zkRpV_OsCx+LPswD&NIj|h&yuyLDvTUnmp(;}6*~j^h$fJ6 zd?uno;ETY^+gd^n|49BO;bK;T3yJwszy=mD8ru!Fn$Pn?5L~wLE`jfWIy9@Wd$qre zGyw0UAK|#rz~IQ$QN=AWdY5+#x9BHWboqI>HQu*Y9g#!00gyBKO#l3rjck(#@(1dH zM>WLNr}xFqdrrWr6@rdT4Zw$%2+G{9eSgA=1@*Y8A^vA9Q=Tk-jOCNe<3l#cAs6+bTlCg!dvlzs1 zV}^uQQ=Uw%EPpG38E}-g3_dD(5UZZ4`Ek|n@evuN6LWn7W%I#_f*~QEn@AF4ul~Lw z_jJWrLl8Q*n^e(-{>W_qF9`YQUUKRHk2Y&slawbzKV!kb7#Xr6zEO{=+OvL-30t6v zNm*OC-G$**B+ieBXXIEo2e;Ij(#J~Pk&P+YM98Pf5R1(2%vId8R7_Ip2gETTapMI$;0 zCUP_fX>SY37G8sqBGh8f0{&;QaYLAS@!6oq;&`9WAV@!>+4&y)2u^ge`8y?oUc1Qm z4?ZwkaP`>qA$+ReQ5G`QmAGSupbJ_OGkSB>U&D9iWjWY^L2pUqTayahzq4ThI(NVw z9JnXq-$tC9pPIj8=@s`*F$D&sYF?$yS>yD-n9-0$-er7duyz2n;25*sX8t`tree6x zPRNnjBQv54_P2hOL4*TL&(^NE-)Hiu1c9**z=s>PeQ1#S%`syxiD3|3k| z8FiO=uFO(M`kpdAgLa!pBB40tzP<2DZ!e22(7 zz~53)i3%)g5}5&>yfHFk)=9Qcp>+onOGTqZQI{(zr_P1xOI`vKgAdhqJ-kOIK`M1L zz>?)!P}zs>K>S!^N9O4NBkVoEvF_hDVD9e9EN&SgNme!~DtnZXLiWxmL`Z~ekxgbI zvm~30$lg(*>_QotrHqWwdwoPt{r~^>eUHQOJM{dXNAB@#0anOjn5cvJHNBkL#(?ZZbyAG zPjE0<0oP~KBL&$ac)MZW2AJL*P>z$V#STNVf4i{usv~TPPZufL zV-IQX6=)3ZCLgo@geJi9Y!6MrmFG=wy2wqA9Gl^)blJLUfPBW<*y`aR+o0tX-tyXD zcXIp;8bw3$Xw^)rn3xtS>U{zy<7CuT&|Wyg#=HSwR7(FiA0}7SU+wYBb;Ky-qP@)W zKEW$FEScPzJiko#e~)PHhoQ_}KeV@7^G@bG?vVxvc`kxe6ae#|uA4l*)(^GN#^MOp zkK~{+piSI8KQ7%y<^W(8Q41wWnz>$3(@>TsFENo{iPEE|1 zM%ZzR;8CzA_8Bx}#NB9isVt&@Z`kA4;Pvt;*7!5Gu4lab^|Shyy>BS)U2E27ga_-4 z6|1}bg3F&{H`BESD+&Z`8o zEp5ImT@9uo7dPh&6lmuIpbj9ufM(stxP`*E#L#(_VYlC-Q)y+#VJY=B z`nYO<;-7u0zx%>0%>yX1=BNNY^Q58(aO3CRvy_|~_p2Bmtrcf*TjxRfAW)<~mIAh( zb4qe}v&D_bOL{x@GCsy;Y|l8upF#BaJezK|&7B2glyUzt7`NZ%DnN=BpLD@H7BJ|g z+3tcx<_uhDc-tlBd9a86zIBfRYY;-4IRK+X7-Y4?emz;-@BnA+@-S+z7U9`({u3PjOY_j)pp94a$EvT!3flv9UN>z@ zUw)k;rLMie3gRSS8j}vqd|9SG^<5*^w50~#AQZPF(e}L}5$<~?AP!(E* zF2uIvC5LurYrot49_Dc;0-pEn-n6SN_l?E?E9Y}ACZ#$vll^QKoLGejIemT@^?@^y zQxVL5sNhlZ2x<#@1Y?fbf4_cdz_+`q+Ch*`&h*;RFzmmSgawZKJm-PAg)uAzEu zEdU%~lS<7u*C=6nsLfWh@;@O`#v{;|Qq;+QK7T|){CAGL1-&TU;y2_uzBOo%J>z4_ zOx9wHaaqaO`*Pmtz!%G(KfWj>eeQa4BF&;<`zJnSmDqs4qyGrm5+5hIIW*ylyFDw4 z6G4WVi>I8bU)l9^IP<&XSqcDK>ECJ(N|~EVfjC z@zI-Ds(-B89^7V+=%&juhl-5&ADsn)g}??wXNmB5)TO`!_gzLi)-49hi>V!Y6=Qk0 z3!M6M*lWdc6)+Ufb3gW)+*-W(n9iLXDO|aNQC5CwFoWno>d%l^D*c&TgHZF(oM;XP ziOPqDH;P>5n`d|TuIV3akCkWki@mS?{t}aJC7&BC&~kdcwYd+qLdn56qrU&bf>Z_F1oGaPr`9liIp?)9?AH5GQOQNr(`R3OWg#j_0tFceO zg`I#>UhPg!9W(%sz5tDes2tk9bz^`P9qVN`EI`>SFRZU7_IM5&(-NQn9MhUitum)` zj_ZmAhS=~3`D=ystS?X9tU8hbKcB=5i-7j<-Kb%zJ)0Wz`;mF+F(>am zifcol!{)cefEECNS77+;DPc(%On>UFPKlMp7Ajw~(~7$E9cwp8X}C`w{O6&=!(u<^ z1tW#K94nxnorOY+xWCm>Ch<&KqRe>8adr)^zz~t5H}OL4V~>A8`YJ$n@u6qFYN_$R zjg&wG)0APo&`~Xre&TYqr8G9&iK*5h!FqRM>RsduYZ~OdKdbu^Q8M+ccS7Z>4H{Qz zLfAj+^92}9j&QjLpzb|y;4OX7e+&=b?{|m%_pb-S5`rtE{qAGGaW`WM8rYLPbMJ8< zr83{uZP3}nb?rkEEEpIKv0;Xv@F=(j3LZ;{G|zMN!85iAdebXtNy0-Ad2i3J%)Ie@ zes4lhJ(@hzp?Xb(kksbG^G;MUArHSp_OJL^=aS?zdUB+CXAwkNKa>PI)7z3gLsii0P7QJ>I}os7BrG>ZryBIrarA75q-=z zV)uSDKQzB5djnZ3<->q3uEeLL8HOCG+5y{h1cfj>?(J{UL5R|ZN6L?wYw<0JIi*205aFs_Pk?Pc0G>8R@Y#;* zYeJ0aW|o7@oHL_+yg$*dJ2&QIezyUiK~EiyU6G69$Y;=t7^BJuu_w}bO=qDy$u(aE zkM06ck>_-ELL+`;%tC#Eg_k!^YhwV`DNyieq75$4_)+jsU&OC8cLux61NYU3?iC+m zX6n7qvKX`6-xx$qt>uUPlX=iNVRXlg{eFcFz)Vz1ILN|?=Y5vRc?SzX|H=gn>?B#- zT{!=hAJ&AtllBr0isZhFjt!D3-2r9_|8I%zfeW5p%;X(DZ9u9hE1tSs9s2HsWtZ*0 zV=;--gp=iJh75!yW#*l!Mn!6MxOKFU6}3&5exX?_P^1e%h1ZX=efe^V$kW*muzuAD z^?UJhkMZ8xFz?!h(>4GFeY!Pctt~uN{mZkm)cU5#01#@nc9>Enc!^%rk3}Xh@Y3|B zY1vahBcV9(=8hoONNxuHIp{U@d0&AULb2PA{$|*lab1Pq>5=?zNa5c*G$!U%6iQZW zrDOMw235j^vRfiw{KG)Q14?kAyu^N5miwfk2FBXXBZON9bx+wC_lw(9eD^~Gc}HmQ zUku$>9p>PM!0bWJxP$3>o-+czu|xHR(Z=FLP)=z)E|hCneyhkEx8?vY9LQ;4^y}SL z;ZTZO?gCU7i~uD4v0VLYkh!n|ETQyxt9@fvj;kBLfg$IwgD*R)=jn9|j2l%CJ*-$m zON4&_9@Gybh$$ES&?nMR0TnMzcGkZE8h~Q)q)6gsIP$oFP^Wz6-(YzRMak9}kO8*H zVuGK(qM!libbm?c;-u`D%)*eO3n=r+&9Ph5=aN~a-DeXdu{uTOmm$HtNoMGz+&N^0 zp?HV=>ougyZj7HdxN!0G6f;`D@C7nM5qy+xO48O{(>+!!23u5~xrfj>D1J!o z#0eR+QX&#V`OT>j7k=(+;LNENz$CKYm)gJ_!M5D`7Cj* zKC-1z;DePwJKYDiC9^P0FGZ_sn5Vh3Jy0VCfA0r(c#(C5_x=LLKsi5&JSWga*^4+2 zULh@H=#QpM_=HS=xE-F>`7Kg23xl4j);Xn}z4b+Qh29kb(zU;S&hG>Fl!cKu?k@ce zxr}?zw6l!$pHLG%E5pDI)$AoYh}np{4d$jVw1=zQ7RKpM-^_R!X(1?S_~zboesJsk zRi1j4kh?d}(B=Uzjwi`!Bp~;yQM3GqHk*tTX4x(S@o@sICpO!BQ{{o`#W_1eSnA3&5LYN2%)(ead{;Ichfqr z@`nH+#%EmhV6IMaW;gumT{3nJzQ89fnfbB+mT$JZt55)(iR#e&vf_u`1#<}#)k^#< zXF@Z8)?{~Y$a*U}Ka3_@fMreja1-Cd=I+raSB)j=tegpdtRY2=E=Vt^LvC;E&|q45 z_czZA&Tnm+1h5Z^Pv1A@%rIe>#=kI z&)^KS!_xI&B{5+Ig1RHRc1$?hRtl^9>;d4@Tr6PjUT9^)I2rfn z=`=rc1xO#!gPjVS9!}(x4iOP1u!KhM)vk;>bdd!o-+rI}XkzxU*U!L`OA91gQr50; zzEYe-$ek@8p0dBfehnIQ>F+mX$3CsV{4XB~_8$n@d?ktr@#K}gnj zM`U(BzNhCwl0V-|%%hwqcFFR02IR*69vWRQm>1{4oVqV>+z-Ip>d|*>yLK=*C@RD0 zF{Q)qFG%Ty`A$Wv{G;l4D<@G+3H_;57C00QPs8pOOXLU+dqV0;S!lz1`(Q}H5TRzS40ybh-e>U7az9rdRg+> zKoe?>{Hq?kr9$xp$b>vyLom)6p(?p1uKV2fa)xVH&<*x`a!nM;K7Yl--`{#!fs(9b zMK>^F>(9z~_|9`3AvV0)28xS}twGOtbisuJQ7XjEU;9qhU)B!hS1g-y4 zTM{r|a&K{M@x0)T1uA;}UPX*x3IUWC1^^+Uv~&PLGwcPYi(Kw;lJ!Fq%%h>gb*Y%1 z8{@70a3L+h3g141R2C?PS<%&K+xsRYi6$1SF5)y;SVBU0N&VhhR%{R@&(}g&!PEzM z03C;z(>EhTl_dTWKM)iC9h#vZZLk3VI+R36!Y@k$UbtUc@#FSFB8fvkV~o6hu^4OU z13u{Hu7i(z1=qkZMW#jb)iLE1@-*{Ty%eCN^7;|79#$J!8sEwIaHsx_aqw z;-It}lydH_h5+`Y`n+uU)%XQhsyx>!}FMe|X0$hs1;)u6c$UycvsugWn5+e-LtABa40Iq6*1?M7-X-mdYX z_)g9MRp%+RJubfL0F#PU(e;pXys{VI4V)ya49b9a z@Z(K?LL8TNUrbQQpJ( z&gZQ2E1gOg2lK`GhDUodo9XS(w}2kyuS?r6B_Va**>MnNAM*~{iCm~i)l}y6N~@@| zyw}`^MvMmRTYh>>DtS0UL*5s&0-8<}{oXS`jd>5V%0q%>OD*W)+|f3 zQOU4dT_C8P?*px(k z^YbR%Cwq{^`0hvwBE^+8Kr9|q)bAm#f_;mK#R4&aOl|a@me%OK`zJZ-dRE3IH8I0R zqEq{_Has>LlD>W*D9QOQXx>pnnRwg&>_Q=wyt$0pKUKdO-21!$A`fc&3wvfreFJuo z*1z-6Ppqn7-Hl_Jv6jDCA0!mv=lmgNy&Jnd5!Kvgo+*PKCv8!VN0TVFZ_GPSU+PN}jgHMQ+jY)fZ|f z8(d$jeFj*+yU5Q$26t%AJ>4*9s4n&JSm-9Sr+Crw;Kvxv2p~VnpSZx|ww}S=1gjchI;Y&SCJFX5TbXKgxKF|5r z@?Tj%5go>_0IZm zM#2EIwEZMLQ>fxyA(%XpS-~~+E};{LHk8R{7{D0H9Jlquw=Q1zbxhG-uSaCzeRg0| z$BLhl>qC*FW^mdDCQOlRYR+5^^iNti##9zzhF1!ydrtQAl0eJPNf0-T7=*Q5GB3)* z&Ey(Z549PjI>0mr^^=17znXRL%`3Q80EBQrN2a1tXO;N%^Aq3E*a^8o24>#6_T!Ew zZZ30^y}gd(tz(RnmVwszR4L4?+#M@jg~9(xoPjg}+Or*T_j>RPBU*u0y4=qiP%lteDvfHQjp}S_p|AdmE(gzf?n4Ai zNaKZp&?#jP=-u4bHiWNY$8uzoxR3&K;|&P!Yd5$a*|Y@U`FKjK5n2HVH+D*6zh+v_ zet=dOT)#<1YG#H{a=+5j7kD z+I-YNL7t*}mv%M7h&k1T!RaGDa!S^RV}1Q$Z3*D#S5YE{F=zW0T@cdt7C647u8xYJ zF^5ZT_k@)#UTTe{sP+DWjy4k1!EQaUX!250WqEgXHIV+U51-gGu6~fWGQSw6K&|@r zuTOjxRtN9p5o9AVy!b+9NRmZi>8)zPb+|MF+LZ>xW5*A^qF_ivv5e z&);teRmum>dqx!^GcWD_x4}p)jjCo=%>0&_U-gNAD0bx zz*tL^5=HtKKMEse(svx=e+01>CJc01Hw;_4<}L(~!sFINJ`(G)26|6`^#UTAutT;r z_*9f4tf$oiZrD8kwC57M4@67@$h8>Z2rK}2KMtLHO|+pf+_Hd zv*5nQ%F`p-y%{R?Yv6et=y<}hJ4JRQ9&8(*&e2MXILIz!e1Nq=v!R!ko*Hli7+VCh zqb_CzhlFZu0*s$YLdKy+3DuZtTEcyV=3{n3UF)P!fv5P$?GDMkaShp)h8y3gLUdEd zk;5{j%DJrYQa#?h9-Kjtu3!?irY@4vwh2Cet?mdyN!CwKVl_>o26bWI+%@PXmm-4n zf(q7hHm}heh>qy@t#f1>Z=59&2)t{PUlkFxKlB{0+U?O!9lMZA3+g}Z@?Y20J)ooY znf?|dvm9AB%|?nb3&ivJUzBobzBc9-XAH@27q++OBpB?WUnyZPu$mjH{B7eyNTBC3 z^*H@*VWt$u6Z*&(23IMsZWnd1mOA+V)tPH2QAx<7T9Qz-6_t{35Z<0+0DU5_zk`u^FU^@{0>O>SA+L|m^PwN!2qo5mqV;w+iu|O zKFCe&8my53Xm;enKP$gvcWi4lJhG2?#%^kxl}D-Wj@ z4IB1GBwpJ8zC?&r`=5a$Bx~%0k6>YjxeG>&3B19!3Dq*VPznzx=rA08 zsi3~ya(@Ad1Cz8~>Gg-8j}+?)1I^rfm^x5A^{X(8!mIa_U_wrQ;_elOkKi`s{>O!5 zRK{WAZn&v;&;SGMG92t8z`NeVRL&g139q5g9$rG?0V^?j@|8c2~ zu}SRuD~j)Y`=9F11INBR5m*h-tH7486q-KaG|OC9Z)lo-hwtCRH2BJyFGZ1+FgvsB z&6$TZMZA=@qq^8~6!wZBbAs6&km_qsBX__^332nIBwnga63z2&y3SrYwBHRk_w8ViRP)RZg?N4)!S zM;~Db?hwkcpD}BV%IB9afYAPbSi;;@o`HgksBx=wV<$v%vjM0WXW^nRW=;LEZ-n-g z8F>|)0jeD$%w_&^aC{LcdbuAy>mVsTlxCJ`A}oC@qgahEc@}-ZS!Kl}_J{ z-<`|@T^M^c6T)uvK@`tIHJr&q_4|hY|7ft$iv!sP!Ik4T>pOC0SrFYi@@nr#g6n1D zRGQ33=F9`QV0co9k{DW?o&AQn+zANpL>pFl10X5te&P*i8eL`(0X9PRBlP|^d_Mpa zqJdDlhYZq2qCP1x39b2@F#dF^r&v6s^y-wrhA9khSZDhj;0A296ZY{4;x zAM4dLh#k|`XfA&l$#$F7V-Wfc=nUp&!LX?SysHP`jb62Tp;K;`p-Z4{qj-ldL;_a!QLibAXSw$->4Q7>Ce;`0)#ef zn%!M6NX`b?+sPYaa*-=cTHj#z6Mr#f(eC;z6Q^=(6sdsBfLO>8QXf%KNLW$X3Jxol zu;S`RYPNmUHYMs@?<0AN9sAz{auUWbA;Ri#%{{8H4L=;8>n!kTO+gfiCAQoefbPpa z%?szh1Xw>?lvx+~mlxR?8QXuMZcWeTSuK|f|1{L&#Sr(guOE}AgL-Y}H2($j1DP4^!4Ky-nOzhqMLdT&ASl65`OGrkb)r7cYhmytg*8(nyIS8 z`tXQIcC5k$Mh@C(xQ}y6d1J+wq*-w^B2KpF=L&InSByQTD6j$nHItobN)uzeRVz$g zpqSw3gPHR+fYo$cE;MjKoEfYAg|;07b)UOP8-R_i!3oguSW^~~MuoSgRiUS+GnCzs zKf}wQTPJ^?LR2~-nzz#C^4 zNC9B(@=m!Ern$Z&wJpH=m1Yo+?#Wc=%mEjwo7=X^5kq?@sle0p)o-!Ry!YgZ;Vpx2 z7d|cNWHJnR5#2?%evDA;z7m7{xael^@izny2yKp_kOV{bHa2q}$UCB-a&Uyg#(K(n z@|#yYo8{tdXBCE(Tnml}3*!A^c-97lW&dVW&VUHH!5E#IYw zz%=!#%wY728H{sMPSc*SG=(h&2$@Gm2t+Ktfti)zN66y%P0q@hs^sXLKwK@xy^`Sk z=Gh>Ee;RON9T2$D)J<3c(C(MG>`F*gtL#`)vy0yy}3v+AM$|q=ZToQ)@6EoP}8>A?3Z5 zM!N(+uP$UNMOkvixP$1@JB1h<>Bzv`!dZNVVJ z$DmLCm@f1>+ua)AY+pf_{yfyYA%UOHJlH=6+)!a1tp^4n=KoUr-ymvCF%^E zX&0t#>DiK+wRyQ?*h*kZy>~8*fw6~$F}!*bOx2~D!1q2%OZY%$xLgxi$9LG6D)|FC zgEcp_F6aEV*4JNNqL&U@x|}2pSo5^Z@(_k}eWm37N{ke_d8k8OHuFlpWz=jp3q;W( zIB*SLoxFSCvJE3cJp@Hog48E{rfQF|(bD7&7C=hNtVR6Wum;5{i9!P9-`<@6hOQlh zEB4!P&SNUA-}sl}!l`?Zj31PG72U=q5I6cME{a^951*o=AZSsv=DQ7*1J^;Ry#a#E z8TZI~vOJI@7ffVbIy+9oV*tUF4$!!ySN$az52A_9B-`W2&OHvMd$we7@GpM8b+$PQ zCSQHvR5S&4ER5F(9+jod3wuBbQI-RQ?e|+kz|r92AA~)K*un{WHPL9i5)xBNs3R;# zIDK=HtT386^^^b*9F_;rzLpCQ$V!>rQn~&ahTwT+v(@1J{r0yDf2fuSgMlxA$!~d} zi-pW@iI!K0XTW}Jn8^S;VzopDgDZwr1`{bvxO>3yJ8r5d$aFbxZ3)W1yMZO(>w&ht zguf2r@^>nau7tp*Qy{_k6e}oB{)&~-qDcd}lk~nY&i9$;dJm_3i`At};DuHvZ7sC{ z$*(-Uwwy*p39cn-CJRwepqMTFG2Py+ef6OkK&NZR>kPNN!TtwTYU>*RTYjU9jSN3n z?;b5SJ?Mp$zKBGyAeN<@t9R-)=vQ;Vys42PK<2X+amLw0=V=)D-jdbzx|j3 z&^`_DW4h`ERla!@(sSg^gVXa;J@&@kZQD*+u9%jSth^wTp~uA8x`DeW?N2CtqzA=; zZbY=Wc(`>tS?+ukb`vZO(Ac&=*iO(z#&e$JSB^uI)?cwSdAknF>@*2JKd>aImlr|2 zFUBGi0VyBWNT^v~T|ibmDXF;1)1jk1UxdHsjHf(@~E2`31vON}db}u8UR>ly2DEp;Fs(2CJZe@YM7Td7&2yI@IIG(RNm30(Az!3hqcP zD)Oo@1c3s_61`I>#+MtzKk_X@qBDvDi5tAU|LlOu&Y|`|&F_vAk|P| z569izz?>o|9vAi~nG*h<$3lxJl@DRW1Jj>8)B+_$ZRWyUdCxw2B-<-R3+fOe7Z00z zrx={`k&{Iknxn1X$kHv%jbDc4*+f^4B;aEO%&J~qmIKsLdZ7x`-z9)xk|e90e8Ko* zU{5H;FS};D`H5&F^=3~~;z@^B&S(h_FeC~^fArPg%)ZB{(VX~^>QWV;A@6}sam}Sk z`GuqP?WxDHWN-EyK|=CCB~R}^&z(^rS+7fi9#bYKVUss~_XkA!Px~*5ckCsl9UBr{ z3~3~pOmBeFEl|7sn=$gK<;;Cvw`7%0R{<;Olu~x5Cic-c7r=;`O29t4J60UA2DT)IEh)y z904x9{>YD;ue2eI$Vueo1y8YzjA)1jc~XmY9ak=VJ&lPzgt&Ign{AHeK!3t{IY@^y_A~$4{+c`a)i(R^ZB1p zN^A_ZkW0dKTXz!J1!GjDD-Q1ZxSW^Hb->z-`ZjlduOJH8k+;lEVw*eVnSn=5_>JIz=rGC8`O9veC{+leFwZ;ijTj=jO(( zl4wjp*?RV;AY{npHplrwdZnZP!#OhfIV3ZxSUrJOm2)}-uD~O31P;sqM3BKB2**ZX zI5_e*g|LlY%#O#QLEOt{*4g9m4jn2xkG1o>n8i)kA(nnQp)FE`T|Y@Vu5waK80r&b zh+)~2eel&;q#>5L2isw`e8H-atqsU-&o>_!mV-e_lxM}pO(-@%L-+-UR^&{re>uAn zDToj#$|b(|B79YHNDL(ed^$V*py~yQArhaES(r+&Ud)oz6{y3FqZ;C6MrO_F#m9n` zEqX?Na&-|binHMUa{N@NKXX~<4&V^kr?ULgpY2fgrD(L5*73yO>4um@sG z7%v`4T+*9=SsF3(ls0mO^*}nsP#hMdSxvtxbCIS;;5KYy+oaWTX|;k+W2@j@P!=V z%D4bHB*hs$S+A1nbs#7D^=qrCvJgM#s>NUoevJ-X9s0gmb? z&5tG+pu;bimu6TR$*A9c>aF6P9&aq`g#?;lWEgM-S9k3;OQBpv=BQ_4k~$P)Y7>w# z4Uw~*REZY(AZO&Q>8%tRu@s#SqL?n`no6L>ZIRwY*%k!ATPsecfVLgls%wF_Ep)Oz z0C2%D&%|@)53}j%QHj?mpx=mt{HZroZsux*3u~oIb(g!%e$z+Urt!?1B%$4+x8-|P z+D%|kQ3#{$X7wDAS7LyUeI>=@d0r@y{ z4~1+DGL8*WZyBb=1S1?kUs5NZ$L-iFJ6!dI9*8(V-5-Y{JL|=~+S5z%atxwACFWW~ z^h@zKfe@3zOgMyyz(6Y3(lc-zKelN2YfZCCtcC6iqQsQ5N6+cx?^oy%oylOc>(~AtwcY_K#w$4Q z{`*>dSI*!MvPXTq30U-|GH_kDOt~j>)Wr+1ULbFNP=SZdl3PrdfnIwyJ^nh;AXmrL zQlykODwg$|Xiu`4SNLdllfD^Q3T&Bjld(sjvQ$avu+Kr3m~PV7$pD45;=DkB8!vMC zRl=#`g0nmL4{{zoKQt~KAfq6|7zrRyPPL3r3LjR%7cXRc)&VcJ@IPxF!AZ5jHn~Po zt!BIPZw>=f_*0nV&=F#aR~-6=oVS7KzAivCHa^}D(<&RpvzT;$_LfK&azC2jI(Dg? z^DTt__iB0`xo@z{+p~<9KF23Gn2Qtd(_2>H(8#9QdI3=LXfFo&ymV5L;0;cKZXo5J z+n$|?lfo&Z=W53GusrXzKNT>qFP-248gr9*N4i%$yw8!QY^smCh~j^=LgDOC zQU~CUdNfgVgqfko-8GXfHkaCd?(vBA)k^)O;CNiQS3m4Y&TIR+=0|tEWg@3WiT&fn z#Ynl|o_v@aR}12DL5Fbc2xHg>U<_UJ?3I9diPCSLiCKu}_32xX1;*rAgdN=+m52D> z2#*FQ$Js^@n7&<#7P~}CAHyKmxS-u-6jxVQ?*6Xr66}w(trVZq%8soj;*_TS-3=ta zA~Q;cbn}Ly4-{{z4Ht2g(^dI<&yQpSpToKHQEu9@ccjDq68IAm_bVGxgSTDa-lI20 z$S9+b9S2%>bOx$)Z|%{2LGdCo)4Nsj!k@Pm`1B-(ICNqW@j3N)cFPHVnl@MkfD)>r@csv`(HzIdbCW&ERi5P<~i(w{Dp z{i%LTT+$#VBnc6cyPDv3fuvqwkc&V=I{{wI!G7e8qNJ3^<92oys++KxbUUcz(U2Oc z>as$&ocX1YkO7?J#KRa?McJ;vPe5cBLSs7un(CT!&g(CDIBAxEUF?rV;(U=g ze_YaZh>Kel%Nq{do0wPeIM9gY1GIXg>n@0jc6=2lKU*wXFCas%o1+{W?p7$tcw-kG zAz@3#Hx#P0_txI5BWrQM%- z_~{c`Y}gZGdeeJ z3=H#D6Zm`n_ocQA|IRHg)e2xeg?vHg*swUw%%{95wFD+w;xVxkmJJ#OEe9}K%82xA z!t(gU9^y#gw4KrT0qKFB_yyh^GbEh*#D4E#U%=Z?u{CpIZ$=WK#r;fWP%H?=fWhHZ zOc4*QVzPvcr`;N|qO+%j+NV_Cwsv=nk~xi8>&UU#g%JD5ytI|qdS=n;R*$1K=F>9! zlN5$Owk+|4%rKBX;Jb{8Z+Tp%{1G%EApv%=y4O#^B*0lMcH!IZM06#0*K<>4o|=32 zd=D)3sEyIFe44Mf$;fmrJk;<4Rz~8VFIoi&?|#3CtTor@UP*%pZR=J>T+TVJ+uiD# zlohFoh0`}I_9^huKxACja>%|9hAvKAJeTm=Oyw0zNg}Q&WC@eA->E?jr0at(ukW1DE@XCwe z-d7(RVYf(X8($5)aP+6nYu8e;9G=O1-+j$63hbotr#-;1EbpOLEI&LGR=Uk5Dy0xK>hBnYs;dpg*WF6 zSGW?M{8DF=Fs%#nJkrd16+vQ zu2voeNsb}|%=tnPObRG8FYQvKaaH9Dj5>#X!0rX){J#7jVz3MfX$|7pecw91NJz|^ zT#ZoVv49?*bg1RX4JG&Md;@W5cP};}JMe-oy<7WFjfHC^V3-*H`#ObFE(|>K4Gznl zIZY(N=(^JMAYXtEBmhW$aE%ZL(QiRSp+$5G*eRx3MGmKEq~))X`~VuM(9j9Jey$H= z54(H^V+3K1t7EM#0)3DOlVrAU(@&OZ?ey-i;2%kB%esWE-(DL|v%Wt?09AeHB2ObKhFR?IO&R=;| zT$6V?#}@+v9DzGS?)_XOay(K-Vu9E0B!${1<{jTH`SF}kU%MV%Pf?Qlngv=MZWVH( z2Q5cE@m$30z|OnNz+tBSP^f`9qjx_BpX2r@#Yg+IaIHdf2CnR$fn_YXeHE0?eB<`8 z^gyQ2z1b;Cr^ijzh}O$$x$hCnFC+^(kBx}wV}FvK&U#NllAJvOFRN)owFg!;inDw8 zlEYr5iX-=z;zP{(!IEW7Wj;tElGPR#?7Y{|weFrId7!YXb!xShe}dkqaKN|!2hh6! zkMR?-X_krmWro$nGcy)#^ev{``IXVR^Rhe|{_>k-ib)xGHl$xB?<~*(PO-E~H1U%% zHz@Xu8zBe=(ab{13yZFtN{^>Cd0o(Q3Mp9zz#sMV%IA#H0M z*wxio-j5&^d@eakn42?hTh&Q5vUE?$ouP9g&NXg&2+siA`1E|grjgSaf+Osy4LCxzltu0Ki;ksv=|7+ zQKu|VBwZ;3u+!RWHWW$iM z@Hx+$O1F&7KdYm=hT+M!9w(RJ3ThDc;Df&wJb!_eWEwitE-P~9?$U`)>QB0YEtu_;vc=v?auk%T2F^I1aGAIy7Mv>KEAij}zbGHaSI z#Bp=IzA}x$G>wV1vNyc7PIoyFOYAj$A+qRZ1&F~Z2P5nqD6Bsq9}uoI2W_Q7!LN2I zUzj?&2&38-qCM!f{2Pz6B~dMovRz0pN24(QrwwBf)x1+zBZ4Qoluq_HM6_FL@iFij zNyt;Vvb=wszw--ANE5Or!PyYQIvHG`6_YdJqE^g040OuuV?e%1WJww{A*7|LQ81m? zt~z3pk80n`A&bDOE9%zJecd--^-+je@iD464^yrkFHV6eiJzSC`DAexwi^Da{%22C zgP63*v?r;*v6mLK3mF+Vi~?=7nXU|wyTKSJB-ptwUcoe$e^q%8J!32D4ZU4t?dQl( zIX(YsJ2V7K+x=8XsQ8Rd^t87+tR4Qfa@P!3%lf|NRPBmilA-%{4#?PtnfBfKL=wg1 z;YK9`q2?6R`+WjQ=*utCcRCn+)$XUqO0tg-L&OUcnI}+h(7PdF>*o9^MUr8m1?k};nES#y)E~-xI&y}q zuEK^M-`XTrqUAq~Ke6!t1|W_$oC74KlOnO_yr{U0R;2z_rI*j2Hf~&db;Pa*swY4 z0?zf=?rM7)(oaIObpuyem9uBi)47VAm$KhN5^s(H-hRdBJ5+kMlA~J4lczZQ>iYzb zHm+yEgMe=y%zGC%P_uFtBv}(miOj1ZsmSvJ?jn53eHm=D7pd_Hv9R5s@B<5@fy5@Qp|_PJ>6GqI4? z`J*vQ;(3j8hYGUyyx^P>&MaP~SOGmpHkeezSR6UO`S{qm0W1W1j!VN@S~ZUx)7=Q% zfb}LZ>Jpf7k^o~Lc@a5ApQreA{!yVYVU}uKtD4?vtXkmCO+gWK6emY3_R%@6(cD6d zsUf@u3ZFwWj6s9Ouo1|3M-&n(vp%lJ%zQs98$@hCjo2Ze4&p>oK4f1588Ku{?Dv)hb zEr<%qct0G#AK$b&oifa@isI|vUyO8KtA$^bD+r>_cp;i`$#{(JNuA@zNfnA<-z*3R z6BXin^z2`Mqo{VjOi~yOih(eq4HCUOiBZ2g_Gqv?(aR3ZQpUKt1bOlGt^*_b?a6*q z3hJ&BZ-QXj6Rl*g)|Ae21t|}QMH*r=LuwYM-jQ;OA;)9seWx1oB`#UJWiM_D%C3XVB@7hQfWensx$sP3+=hLN{K;Bk2*C)IeIk@1S&9>p>(R(+>Wz9v66 z@HCh=_~uvurA|1^;t@c=XoWO4YIH#z@A4na5^-%kZV*>CjcBYxMQa6MdJ|`?uS7xK zZ9UEiL;6>5qbkzk?CXsM{HUhOV-Vi_11^=2#-`4-97fGV~QBTOs% zPT{6(idmp6bEV|P$R5pyG)jk2)wmH`_XYG~1y!cBQATDCTq^kZcS`-8*O?~Sm=2fl zB-Un*P2BoWB~=PC$l(N9P4HG)#&v&6pTWwr85e1 zb4R(I?~9xPEhT7Ql41^Iy?L4|`OBHNMp+X2W|GSTFsZYW_9H1kv}^q#fi^A^m~a^n ztwyErVO}ZH!?J~wU>TIp7;2%T5qT^>;Y}$JB0^YYL-R7foe5$Z3m|9z;Skn}7=sHF z{{Gi8>Wx~F;s+71*geNT3<3U(9Oa#<%RsU?@$lTizYl(9oaY)VW?a#zYTo*R4t%F% z1mm!MdmCu(+wyR?5#&zXWpFVU{`RT$>KRyc)#oYTtsx^ZtN5P3Wnv&Thd_=`_s|5M zaX(;^XCKCSY_5j9m2;L!ZY9vOYozq!TZg<9xJ2^FX@0@30812=AWp(D|B=cWEgKJ7ISv|#JezfHHGJ8uZEp7&{EMi4q!=rE+vYn zd5E%IV7!9SBEuFu7sLSF?b)yO3Gsr|k|CEFt-k$65AXTjsNiG_l{K3BA^xpq*QeAA zcVc-iyl-VxCYnhJX9omglht=*jpNX{j1tan2ODsJLT>sEwE6H8y33S3WwEIELaEPB zl8S0s6|c7)s9bNJvy#V9;FFt|W4rACOM>Q>ko>GI&*^QT)8Vy;Yz3em)wV6}2t z97@A)Jb5LCRa?kddw8Cx8OSz~cTz5Bih99hnl3UHf^SB5FLDLUf5Q{RUfjVh^-oI3 z4DnohM}Q?WMCE7Z!Ga#BYOiPIl;|9Y^}D0CR z*>PX%jlW)Q@#ZzDca4@@6^P4Zobz>VBV$HnXxG?1p$)sz z8y<8Y5IEJ+F0lzLJ{v%8oQfT^H^|Xxon}ln_=6FuiQs1&Gl2D^-%6{)9!0-k$>+8@ zy4jUTWL_|$Vd&;CI><{ECxsUjGY6Ycvmb%!@q8(i>!c zzw)rm*2JoS3#@@Rh4L~B_+IoG2aQLw^)@`N_}aPV}0~+0dH&N z+H_Xa$ez|$jRiDJ1m0SzP01$YyRlW^LkDD;!MeP2Nb5z$LZK;fuT|#)wu|bYLt}1= z!M!>;kFUH0IaSHW)8!Z@L>{kzi%LkJj^@KzNZ;i82_;O*+}Qk^h2RX^Tn;gZ&O}O* zD%wQrz@Ha{-Vp|$@)$-b8qbh*8pg2f`8P?(?k3)7Jw}DKQ;B|W*g~ZOoboCe>Sk+W+TfxL7vZ8DI1SBk;YY}Q>*_1=_jci1wKOwF1tsKRIeK*R9n zmb=huSLI9A__0WliK53Ps;6EaPyL4Fh-8#9I`Zk5xSS+g*Z4{kIg&VD`; z_}Q>cE>=%VLQi@SjXe;1*S8RieXg@7jIX^k4)BY4>bhN!grCHZX8V0Y%OEi3d@y+u zvkhTLRAOPQV@7ag>`)pz_mUS=hRg832@7_GSnbTYlH#QKhWaQ@7s>uFBscRO zo^d-kG`v6FE<)ju2NnX3K;{|15Oa|=KAu_yEA3eX7*m!336xqk;S6{y>m*4$$<-P^ zwTG;N;bwwnpj7MwDFn*C3poqz#V^#}BR0jns0SEtc6G(~ z()5Z_5uxSJ1yzieHsG7a#S>ctez#U^3AR$R4_2Xw?t?&{sOb2!&2ZEBT28SB*B5ZP zA+5c|RfvxtItLn!%hg~o9d(8P1Dc2U*FeHmNf7y`=wrk@B{PrkmE(KQy#K{%?yYCu zae#nNB0#I>m!KgOoTRl@mnN&%`fd_(K?$F7A^~DSKUmrBAx#$=yd)_~?RA>KJodj> z?Jq%#B|8Z#K3klA-59qnXrzL@zkIroeD&0(k<7a#KX;mFpLfm5h(AKeAlkhywR{d4 zkA*0PJI=A-ek#<`;7pCtK$%sa!}LCaxD=(4dZac z!(%<8Vq@_;{G)(zll4hhLm1F_B3goVCgt2AhbXXl$v4-CJfs`yy8sNJ1yaRyP_9xa z5gdvU6@n78W4P;=V2{K8nR?_eO7aWrPpOF~D2!BgQAKTtXwA7pXSI=$?Vf8Q$#*e3 zD4gb#XmwI{+;qQ}awS*}Bf9p3pVU|{FaT(y(zW8Jew>5Oji3@{x_IXRNuWwdiS#ki zc4g@`zqR_x#Ph8Uxd#8r&FI6LU)_r@{!`ze=L}!TB7{b}!+ishhap`b7&UyeA3{|Q z&6|mfVir))Uj-GSDi`s{g*(1mGpYh)Yi`1l1N**qYqz5o5}BEVM4tjCw6r;W&?}rU z=zC14EalPS30N#dJ5(`<%=W@XHQ>1=cRbKF(qW5~VcJq#O7?1=v4S@=ec2ftVk+v-*0I^IE0EV=VY z81*s!XsA4xq0A*g4`$;kS`1sc$}0k=Z1(4rp>LGcu@Ovd5bWB4pl&7qU5)?$q3kW7 zqTIKzallarFouwplu#NK0g=W)(!c=*X=x-xK{_26LTQu|DUmKI=@3xBqLBurL!|NB zFM8tM`~APQ{%hUknse5<&dfW%*!$T}NCZD7f0gOpi!`H1>EV9k)Gh=e^udKs$4gG0 z4>GRM#tFtAxV5ce?iOfL-^%AkP`rb-f{k7RuvYU=S7>&SioFMr0i&hW{dDK2!F>X3 zf;pq8Ei(@uzo*WZ^Ad&G;>_k+ImVr3NApa!EbcDiBmV|ma`NZdshjKU_zD8{+gHvX z^J@i!$p*}Y9%fl(SABcYysU02b zFb~CZ335y+`swuDBFle>jotnCgG1IFJ#t^i%Im%h$+Y_YbnMxMz-v&u%Y;5-09JO} z%UBD-U#k)Ud>Sd#eg0rAHF9k}u8mDGrp}N4!UAZujsRLA@n9ZDDftTw*AQeF|HUu0 z9;={4?3;mbNDNaEfG6Kpo&;+%2)rsot$bVyt&iaodboh{JlVcABc4TsAVk&(%1AfC=#@G6wl5uTXTfn_ z@-3NAo+etxZ}_vRa^8TL!K>n^J5nl)JJt*(5?~ul<#N{i0^}7jR>@eCklWarEeu7B zNS!#=V2dJ_IVQBa_nv?;wVH-2*HIE3KL0|Dr?9p3dv*e!VK>ep_*lP1nO-`AA4n1Z z3xG;`ND5u_n`X@m(BeQX^EO)MSc+)@*-QcK$&iQjzQ??KdE}TWGGs_xkL2IVy?w05 z{;bwt3-`}1o<(QK9_I4wEP!;mpHM(Iv?3MiVO}tG#bQ#Xz;nzLG11A&LE>wo&@({g z<}dvUbIHCi?;?a0z{OA>I0ttLg{7K23H~!;1B})5HA3nGzAH`ljnP)+-_xEe>cwnT z!0~o{1{7iWW}Aqvi~jT-g}JF7VVirPn(^_j$AoVQOd)}Hd?%?dmC~Uc`k7IO`|YcM==~{Q>Xw}6&=n)S zHN^X3Y;A5uu95}i#qxy}uAda1Rp=VewEJw5;b05Ny~@LSuYM8{4bDrnFPpTT^Wrcs z?Xt5TWoTR=%xGOJ?WpsFw(>oaCsXh?;P2Z6U`0F-;-?))g z2n@Xe(rpgZxYur?3gFvR(Z&g7_peME-7rn3;U#IyzD+*No_J~pI8YzJQB=G>MBNNI;y9Pm1N&t$0y)FDVTQ)y zR?1&Ira!)Y;4IWm$ha;0A9X#(i%Ukoifs19Q@-EzCyTsFz=i(|QH6)%c>QB%mwD_klU!Yi$~jS$@{&X<=tBy2SGl9*Gr%;ndXeS@zPwJp*#18^ z{GSt|k~G7SU0oM-Y`! z03xHsxSq5vmXSrMÊY{8inR4Wj@a+o)5Z~S3xzQ0S$^tcZ6S)Wejq)eOvY6Idv z1tOlt&1WU+F*7XfxhO*S2A_Jy%a{3xCl=%$guNCjhY8tF;N$iKYy2)0cLhU-{yI#P z>d+Zw$OB|0iIjoosU)Uk@nWx7BJl#VM$ybjVsWk$$!O=+5Tbp6ScU}k0nMvWov&@! zocd%anwlWfI&lPwa71&w1)@zuP9r~KaG7uNHMDy4Pp$d;E#OZTZz8!h zSoC7ayld3B{*#}CmocKqSboSElfAqzYaTfuW#rL9LVNc}0gUUUXf%^t(Lza1Fd}GR z_za3zBa#y|FJVwC?gjO8BXCP8-LEYJ$cQhFB7T_l-q4P{M1JowyZprSuVZ!ZpD|ua zTzPQWGUx@>Db2yJ%1kx7oN&Q$`ou%B?hG8*-O&!JUBNXE7QI(LBC;@z9(GW%sE?UKv|8m~A~gmg9Ou^D`9@|jh^ zmG+Iuydo5)4LSWZQW>rCWX*I%10P>Po$@52@us`XB5bIT-Ng*)4?hu$-K?*losn$ApciZMH0l%7in2E z0_rC39pj7BNx!`6Z}P@9ltw`~TW2aohtf_{9k{1O>-wPLwkG14k?tEsAL8anw8fHB+{!P8S$pTV!fKU7lEtk zYuJkvPQm7Y7W}maAJ-tI;=TiiGHRl3DTRMg{hvpS{B3{U~(>)Gv7VT3xtN zxmSV9+(w0Y_d=$_RHR-2K~4YdV>U20c$<+76e2&vUPy909T@)iwFl&1vOe}2*5 zkNSUqZGhWI?+}P?Dk81C3>%8!^a9dx06GDc7Mko{cXI2{rih4gVe93&S19z*~AMl!2Z>PP>36ufs|W+uvf z`JwLJn<*YKjYl45iaZ2L!y$ba?(#%{>V7Gut4D^Bd4bi(mjVF-7Qx3=Q(cd-lbBP{ zL4L^`kY;~EJ&~eY)QZ&gU~Q^?^Y4xN?-&1ZcKqH-W@N}@gY1%)8?{$C+6>{BC}P0+ zScxYp9>Dd_U%?5C@po4M-|g0IXV^b}3Uz;Ywon-nsT)Ke%G_t?4|MNSra+3VnnT-Zo zC4cs1=Qk9R$cf}W2h#~BYwAFZusW|Q1-uJADbKZkzV1KY@;|@d-ybI!DGV-pel2=+ zW8wEZF0=h>Klb*OSTkxz2eXe;c!{uj?jMJ>+mBT1mhYk8)JKS#y1;44clxKg%8d5} zc=+!(_~*rc?VAifKpiL$Jzl z=Bu0nkovVC9RT(^;K*7o(1y-|w2ROPGxdMoXYchfd6~oikEe{62}cg+aPiO68NW}5 zRAi{=YNp$D_W_Krq2jhd4!}+`6ih;BXFjG9kQj%bFvM=|%LlNdA3#z>!VTZNHPllZ zj`#oh2>&0~0`hYgTF}0mruz$xZlo*)dd2ME1OJ)ct-r8VhxYyQSyEi|e)n&rLupB{-P+-NV-+oMh zp;s3Y2?bF|V`#7({{M0JA}7o=x4PGb2>lY0qfdV~UglIWQf?3X6f-MH&;yW52XRuR z8NOhT;BVLqjyDQ+%aG`Ysaak^xKuzyEkI<^R|`KMLGB$M3F4do`xC>z`LAV-oLFAd z?69~TkE^X-M15pWvVV#pRV=@ur|JuBxvv&43C+AdBx?vsCfht4 zib+{$K)jkYfhtg75zg@MZ~T~wnDf6U<$FKC?{nkNlLrsZ6EQnfzM{x_?7XoTPCL5^ zEM_Z6oqJBs@gsd41ppGGJT%u$K^gPVIr;A`vE>s<>5?}VSmu=7`D-RCL&ce7^FNf*V^r(F zQMZOhx(hTymN2^%7N9|S?XSfF_}ZvD#;GYxVFsCix zK1~Yz(8-H5&>iN_?b$%wGju?+RWHi1TM2_Zg09Ke2@kkAOJMZsYkkPOtnTwQ2ZWs_ zd;o#o`d~O`15ndzFm&jJH#ORcg^)BvB6)xO$t47ZFgnQWlmrGe7oxbjk(@$H$eg~H zH6$za`j_nEEgFL_09_dXRV4#q%Kn4_+W2Q*$k4gy_yAlLKop-Iw|wmU2asDJ2GWE+ z#Mc_ks&{Xx7lZmOu$A0PAs}Tnd-dz`Mst}Qy{u3!t}jZB zUP(uiq-E?hFv)x2;p$eBUFX>gUIDyDM6$Yx6m^24Ees!o6vyl~AI7frp z*wSM1db}EA6p{~M_(x1>8nK@r4Pu_cpWi@Pg5-xHT5O~@&R*Ui8-`(<5h!8Gv&*M5 z4f+tm{}k6Y3>!<}aXy+-1hOtnuP5E!w3Zb}Qb_^XVv^+rJeTtwl=fHWhq|vi>ZwU_ z*oRKtPShbpDxq4#i8}Pr>prY#+Ax@uU60ysX0pe;tLUOsP17h9K`&aJ2Qf4p`&Uby zIM9>FZ_Niw9t6(IOTP2ru8+{(HOxRnDzLKT6eX(yj4n7LW1Y zXYx}nFCYx`Bdk8h1h07HTqA1>Kj(G8w5B}k7s;RVoe`HL5-78eROoRz)NlQOlK0e5 zMyUM93WL8dGr>~=Ye<4tM@)vW*$5k9Z&cgLS%W&q-U*$IuL=WX2szFVi2sQG#G;VV zvi9qmo#Kf;m;vZONLjF5eu_+qlq&j03*p;$=uR^Povoz3aURNNN=}Co)n&rJ>Y0b^ zD)pMSo@u~BwXb?c@=^K#%H{h34vT#I*zJpP2oLAc9CXcy>`om=bMegZQIb(t-#fjT z!vpIu{X9fb3sf~r1pK!Kh$*wi%UkgT`QIq*E$m z2v+!q1)go~TMIy_Q;0IVl9oq5II4_c{?@>2eQfkIz^SbvPaq&n5=Jmhc6fG%7N4F2 zN6-akbpTtN0T_Ak>t`m{;f6P55o@c;9rz*xaBon{zI*C2N=e0YXc~SoGxYjP7bxb) zY0r*CTT+uKW=EJ#g7Z5&j;ZNF=z~MmasJB@ zk&Gk>njRg5A$e#KIjd;A?R)JRZzq&A1k_mYtjj-y@m?&gKVAa~r7S$;7 z_}Q@3bjFKWNR1-puZz$zqHy6-^i3TObjkpiOGNZ=%-7fMzSJu>=*GVAUR&jT2*BL7 zzJ+_A&)XlqRH_+;7lPhofr7~34Gace4T1s9VHzJlKk6T*Hg~cFZ-ah9<9wc>uSrdr z3**n|mR&&4at&fJru;(RPA1-C&Of5mJ; zaDN70F^75$<%2RoeA331oJNTSiu>?oEpNn@?|GVAy6|00N^m`;Z-DB0Tc&2~*3Nxb zgn#W7Aea)|S4Rhi@?=!$@jEPTKQtv(9pTqDUjmXDpakLjo;!CV^;8v`WfLGbtxw376tWhht!YL8zML+9#!H?IqNrJan)rX^6~W$Z`?pv!8KZ%5Pvqnarn6_c1r z=J)q<)|Y#&Sn4p4NPa$XtKZNLRcmFgousXxFW?2=zX|jHw5;4Aswb|KnCiGc#oG-& z;LPx|aNdCqq%nN!DR&9}R?34VT;Jc$} z*fH)d9b_hAp4~H)=>H46h)ZDRY|J01rnuF`gP1e|kHfj^M`{mZxXH+VV|r994xBgW zwF;$gJ@Pzt@@@Osy8_=aSA_i~;IMcYUQt!%i|@@7`(D>4DgYb4Hc+U0qsjUvg8O)_ z+WKb9&H;;}R{)>nw)c~7@Y@HcwHu0Oy+qPX9cdTlCU`Bd8EydfSN1r61()tVxW}w; zFY>yY-uQ3r>tF!8YrBiJKLJu?X1+VWx}uahHzrm7;Uc5r`53CEI!kH|!=qz6Kt%e& zzTN~%3)*t)*{z4m^iOv6kBOm;11M;ooIT3l9BAY<%5)+( zW7NDDzq*KsJ-{@<6qh)9vW??L>q^3m2u<5gf*$BQ4-~o{U-Lo$@-T;+xEB;|lOmeI zCR#Ll#@aDni$OD_1k_J3A%#4~33l>DC`=0>C$2Y-y4`Uj&Y^v&f_hWyknC5X#}h}r z(_n@w(1&Q9T>#EVwtaa44!65StcCzZ9@=VN6$`!}QSY_`$B;<-gKBBu)V*Yh&_kUH zBwCYM!@Vus2;fej(@j5>$zfroiYg7UA6lkz_+{{XKS3IyO+8wmMtoEFVRYjzvhj@0 z3qakW5bzDk>z348+I=TZdGVW?58yrhtX8cjNDgy*VredsqMtaK4|x3Asi&nrK)^>+ zd0oQ{?;rFaGV*-PXnk^8^SA@Zzes9l2Ra9;@g`a$=g*~7v#aAsBrmVf%V;)pTgoYH z0W+7zO67!>O;ld;ADm$i=J~6YOePg7*~_z;-sey0%A5QlL}ZDTNkto_pn&D`5~P_w zB0i28v%D%rlEw7~>gwlH{zPj z@kHTW{1k3y6dniTgDbHs<2YGK6`gn&sD@|Zm%d-C-46r<21As`!Leb=nGOJBc?8NrR=sI$Q+fy$43DWc8oLfQJktF05;{d~S<%bL=}3AeDUlMf#P$E6>jjql!l znry^h>9=hViqm}{c-{Iuz_*})(Au6_CX@b+1(;y$N3jv3Ygc#cNP(CKl37B6QRmYo z+`fgntAg63Cc1g3LK8Qq&!rY8h8qgphp^58#l*gaF(2Kb8QC5LiJ}I2ad?#W-IV!u z-gYBrjgomo0oK;`?2@Hr$gjm#$`xJtg%G2Ryw9Us*BokM`A9@mJ0V=X{Bfpy&F6Hr#J6?vyi6lw zhzshXyqB(5apFZ&I<5BBMuvnPQ@tjxQ;%-m1$1g=?^G-M)WnocZ@K(%O0fA@<;0>au z7&L5jy|r>GK+Pz^mw7RE(g`yn1sww7yEsuS#*QX2BCbWmMd=aFzshbKoxOis*;-FU zCAhYBPF6@KI&UcTs!JOQRnC)$HmtNmXC5aG&l|lZp&Z^dk-r;Pbn*6Oy~tZAB}Gq5 zItK?N4h_rM5m>3`OT1$)f_C9*;$6^V#1j2#mA1T16yD<6vc)2(+99%JH@ zYj~MV6d2F5{ zhv`Kie-$qLH-v^z_t8sz`wjcTswLI2Go{-}8GG9ddwT-no zx`2XftIJt@9{t@g(wSJ{_#}xf?)}0@yJAZv9DOoQbQ3z|j6v0(b3o z1lAm-v=S=2?cJuBpIH^wIbu3<3RpeAAv79%Ujb;>u_`Jm)KTf?m|<~AbnAl;CZEK} zCI+t-8ADYI9eOu-RZdDIUTLj37u+uabG7Jdi@V+^Cw0@aI|#iG+8wPXHNCvP4X{N# z>Q|VB8UDnff{8508I!pFB*>E7UVo|Nt;G}3l)o8MYgR3qrEZp*q?S^;n}(A}H2ntF zc-d;y%dtnZ-lwfzNlSZ&b^Et8eh=MBQ}XnS#l9LJ3{yLeD8C)Zy=yR4LS;S^uUXvJ zpP#^oMRr!fbg2PjexP=sge}H+gh$gb{JR4ww<3pb#rfGb3 z1L}|Pi7rKniJRMbEA=x_m*kJTXFV|z?@zUS8|6@ez-w8EF|Ngz3GO6VbauF-`I|F! zjbE2tYRt$9Mj3>kae!C9{NMLMmt-|g34V1Qg+qJ4~w2=A|U|JVr*Ik+Z z0NQvI_DZ|)W4-e}39kHKSK?*JIoGS?y($)~U7)9N> z_@N_`i#6(!F5sg_Pm;AM0g%s8-|$AjDs-}5aPq&nc7W<#P(G@5;NE(G5sMsyZ$Z%l zkS@;fEl`BYuY1K<#5;E7Z)SyueSI*#+L(l8Zjdw0=Q~vrT;q?z2*L!iHTP> z;N0hrvWmQ^DJ-?aK!AAlXW??{O%>$Fgg%_{y#f6z`Pa7yH~S}qvnU!2`8+<=5;PWq z?NRH-NGpf$;J`p?hL7yS^F-E@wkvC?bLnq(O+CaPgaWF)crNOqZk`Nkw$}$| zSp4gvbaS-dDT5@G2c|twsPU#>K25tGt$?wP>Y8K1l-Q82hc|16No3F5CrwmqED?Ed zXHcmq`^QUJ3w4b>1;b_l3*Uby+)UST5r5Bz6+hqN8z2peow^4V@}bsmiG?9U-J}*m|_FbT`V-KOR1q?bltnHcu^KZr?Ca_Fzgu98(~A3&dNn%lxUA5*<9go}o9nt2!w4tr z%@Y&-B?^vT#dbdES+ts&YHLmu9Wox|t3-gR7iLY8*a#-Yx8bK@tn6?x)i;&9^NfWt zCXCjF*?Z427ZiRLj&aWp`Ct$u^8Bax=qK6%u>JO9F3%{Id2*eJ%{tTr9u?<<_6D&( z5k^@ug}%uy(m`7}dzsk#(hA*nCuqJTL;Azt|MQX{HQVF=;bl0fz7_QNZ$$*hC%y z?sNCPsmrTRP@cZ8!`J4coKoMTWq}AyECPIR=coJIpPuC{BKe-~P`OWv4&gR1m-&K83!?o?)nyAukzUbXzC!*mYF3EJop` zLlAjvTrgQ{txrrVEf+h{<&^=IK#xz<#;03?(O(_ITdWld1!nJ>w#S)cKdz2plFr=y zIuIIGeS`!@MPH%H{7Iq!q1Rh~QaM)~K*ik^`7W&apaFaLx^gUrkzL~6mKoJ9LYc}U zNRXO36s5vN(Bybhhe4XT_FUaf1++kd3ymBlt*QgLX;56LNLducRNaPEIIcw}3wqNi zLH(oNKTrfd&zc_cx#s<{`nYpTTOme`afAx#0zov%dFXZyf1nwWJFaIcFXq1(k?+_S zS#&BPi^KWoaQQRk>p?=*R6)XJ4$+NraTS1|yMO9@xUoa+u9sW!({+BP#Z;j^bTj1Y zV6kN``pgkxnz^O8X^SCPr}*yQ86Q2Gz=oGz ze#;TO-_c{Me<;Wy4Qp*bu}LUIoc^RZ%H0NroD-^ty~*ox74nFp9p24#n6#BOZL~SZ z&0*`jtLpvNuFwo@E-H&EsU)o`KOAtkoB z2`WL!q!Wy*z&hxGEo+`tb4k(#hAyT%l{Z9k>!6njzC7HKnXVjb*y6>QWzHJ2b2>nj z9U^U%z1hM{h9j@M54(}6^rt8OyFX6qBRx~QE4<{Jgf_S+Umm)8dilC)+BR0|DF_3s zXv5`Y)pdS6DG~uF=@~s$2R6W9lvnd|6p`GuzIv2Z)Cr9<;rFqW_7uuI%#NQmUaEd9 zFQCW}GXJi#^g=)(SwKZfN1?%8Yut~v%VIHoqA8R`@2Y1|hS>YYE&Ows5?U~khn&?+ zC@7Y84(S{!>htDg_pnd&Yk`>aXe$s!+uqwcDXFH)>~J{XnEI%v(Q%Zl(;Kw+y%Oc8 zMsDZc&$D8|fw{ZMwQXYC&;Vs(-1baT3cVG^F28KwzF8;ceh%#*Bv8+7{*rKSReXLw z6#h|n_`7Bn%Y)?bUZJHXC%>nB8P2G2YrpDI+b=e(QWz6EkfpHYtJ zDE%i}Le-AH26UkO<_}M`$a#ak62u_fT=>U&NUS-!-DBN=pCX^9nUj`HU~bj&5-upF zDU{bg(NB`jz~02@m^jtB*V2jn)r6GC75Vcsu?Z9#18|uR4$7`#zL`rCCX4#t!xiQ6r%%t?6!DVqq|W{XtIr1QhMSVZE`o*vhbh5y>*Ve%8VN0 zD@|qoDm~qH-J(j;sOauzwU+X~u>dIxnhv?LZJXpn%f8SL9v1!vOzfk?2ktvLkJO@t zKLPXp<|{i%Tpr8ye!Qu(`I=serHQ&P%;L2$GJNNenK%C-X11t_2P{Yz$jM$~+PWU3 z9gunb>`ghD!9SP5-?svBB2n@og$wRX;gQ(eiZu;lTt|op5&0(e@XDvrYA`6^fA;09 zZ?f|4<0G`FUjFWl@0Z)s1zv`VQeN~`tcbyxgkgk_$gyP2=MR-3qdx49*}B-0AEd&8 zf~rO$XI04Kb8d6Zs@M5Tmp48O zuyfGf(ZSb?9P_rX4myMC%>%`AD5u8^;s^&g=ZwQ{%FU0!z?Xb6+@9KfpPAUb9%mZX zT@MH+o%b`4DV^PRbKpmm408aS9m)Rkp0~En@+1Mn(-!(*7m#haL4aFF?qAYrP^eNo zhq4oV^CQdv>u-62wCt-x;)uJv8=j+7l|$07+TmR~Tam+vvQBH|Ut@B~;dbvYjk0y!E_K~ulBQwPU+wIufUz-M zSLTk`HXuc3^{`i&x_l`#$L{hquRI<)5K`=+dhCTRQ#i1JMMi6v#K7{8(N$o>db~8^ zliTrxmM!9_ed0qq_uB+XCRCC5B9Vq~Iq{Oxh95rred=QuXb|CEn>CKDIvVoe z@YmF^@933O{CKf6nxwv*cPqZ0^1*W7?9VcOLZhv~Yzg9+o#j?;o5tU<`lDrTOpA)* zIXP{?#Ae+JC*efc#NzIL7BM6!2Adb5T<>BFmQulf7h2r#1d7oxmS*om($MqR-zebrH-U*BAd|#W%=m@p(Zq%wgSXLx? zw`}Ff*yHcG@#DW>eEF)ol+|rY_tBKbt*ZWOIp?E<^z9=0r%LbzNNV*;$Jy5%)-PXt zb_K|qhEOh==LSgM^n|QLnKNvs_+~jN3LajP%7(&ZYJ*wb2ZP77BM*D`?F+!ImpZe> z9Tzda{Dbm_X1sm<+ir!(`44)r(<^OX^+BaoYt1}i1hBmzG4M}Aw(uK;VbQb-D$7*5~ zOg!#C|9V)?K$;?P!q~nml=pLJV@68kGn_(-U)M8!X_7L8VSb;ZeP#cv{CJ407+-q1 zH^a)e+W@ydr~vaeLnx+L+ix~bsm@RxEG;@bxU5r~8S^aSqO#wyPXDOrlPuxW=ubOt zOfJ%KxhxtNG$Sw{Hk|WWTTBT%VpCIVJ~4HEz3e4A=Bbg3tzYDkT*{-(MLWiL!ws@g zu4h(;=!-qg;+2qw^=L{mnKp!KsU3;Lx~K&!D>me4_c)BXD^7e6Jy|!oEdjeQxbY~{ zbsB10j}fW*9si(+`T_bxHLh7EcBc9B0&(U9G4HZ-uR|Tu=*HI3d>?OPo&@j)ee;=7 z)7F{))v{&s9N<15tl9#&^g6lf>cpO&h~aKr!u5x1`h1^(Vs@@Tv@dEZlr`pDE>L6+ zy?E1Th3VSB_*Fo8*|HXCre}OoEFQTSt1VM8^ut zsGNu0f$sq6h>a!S>1<(8-6Xf4iBOC6T!sULp`$IuF~s!pSD(_MQn3>316>&EF8PO; zo=YIDmx+?DtX`6gA5f91!aoUGt1tR+)W|o)rJ4oW$t;ZYven4clqEYbH>y9}p7y6A zcW@F^@U4V)YqLe3yowKhrRu>_yIIB$uER7!8sBmRhE z32p3*KQ$6(j&4(gZGNXH;aYgTyX(KXvxLeSkxaLn9o%^9aDwDc-?xMdy1Gn9zb@&D zl}#|IR9y`}@M?xHEEV^F?{Uk$NRh&6HJY1 zyGq=FXx7zn`J_UU2C40cX`{ft*Lc(XQ*A_61sVfMPD>+ct?BRRWG(~g;w461x-FP! z-yq(E9%E-c=0#h(r|9@+OZ`Q^+MrOkpfJOcD9Z@fPQLb5JAS92VC*B{;;u_6fG7)` z8em`4w--6&NJAKPmm71`$7jLQU0_C2@8zEH^WE+urF+|>MvbGC{t8UPv8(#4P~ z`8l?m8kxw&cK2-Il*k(|IEPbN(6a~#$U1xsnA|aHIqwsz6LhF%t<3-gh6a~_? za|@OkEKY>1v-ke9i3Tj*;KS(zK>Cb1CULPaGSI8x_k_{4p6_D|R7K za&@e=u|wh1RHWt6>fWM;8#&53vjNVCp_s04VOMmtdO(oBw9_|ROq9hKqM3!ZWMe|+haMwl31?KxKFv6 z+uY>+gly>uIT0+b=uU4Ma`gJRa8$K7t3w4qp55n~rgsW($8FlmTp;M6A**d3@OjPa z*T=$A3Q`kN@IJe&Jv`$Qu>qF(?JgnK%MzhIoO&`v^tEJ~uHu@myW(0GtKD}F&3Lt} zD|i1yqEm|$p1sqtHken8yRPcg?09;k^5*5l)5jN@Dsvs&E|pGh`o=t!sz88PQWWL` zN6cz}tBW5?!qnZ;P*eQ|KX+0zS1#D!tk8;YZo$z!|Gelf2yzx5^g{4dkmYNZ0LNRu zB!csz_Vc(i40W7u0m<3KB}I1{A+DiY$?*=718vS}@neU7tyn>i((kt`_bYGs=u(E> zk)2EHePs?)wjWZfk4lq28YVbC{3;z#UyCMG?iL5GUpt?$qh&lkePP6xYR{e2YC#sV zOGGy7L;A9jOni%9QRz+nd{;?D~K0zFG@I03@Vkjho zvY=8A`VX`W84t_!Qp!Aj%H(1kmR5Cu!>ooqJ@Lp@fmp7gn4r~9CWW|5=fjeZFB@n@ zb%-C3b^RFZ)-J4y*u<9UztL$B$FFbuBJ@%#Z=AHQlsnfl=5~3D3fC+m?Zw`0O^-9y z=CTQ=GKZ<}{b}~PJte;KL^tqb`nPJGcPZD!&be7O-e^g=kAa?}tOBa4fjk^u{dD+; zK$ze&c*`C#P`@ND&NXBHS}@J9o$b9SJBhNkqv8+G9uc(t)H_EKHbK1+qjrwoi|g!s zSu<;%j;DO1+;96bMa(rv_Jytrh^5Zu9huT;6DZPK9E-D?uw}|un5^q9!Kn?;{^Y>R z_KeoqT;14R8hP#4DENA4h)c0&R-UQ8xU@?6{-I9Wcy2X;BUkOJSiQFq=+i0wEvHA0 zIp$W%8&>b~a9qHc6ZKeS$G!MVKNwJDzq(*0@||SI)iUIHw12qIWP+Gz(1*&VS)M1! zHT)4>5>d!_{=OBDt-Up1BUFc9Z3^JNiGEtL0lEng4RSH-b+NtM?ks>cNQ720t95FK}_gFRI1(Lio=dCaH7J(qaPbDU50u zJo1^6m3&!NcbLKb^$uQg=RP7Cc30n(KnpGS+BS2_;(H-qLtA;!{q@A_c2k$Z)p&jf zZJX+TuF#|2Oj(5T9h-gE37x8%e%(LO-1_R*Yz_N`gu{dG9&Km+6psqzfF}Fmd0jeTYx|}6 z{^o%SL0>BfHOqc*C0aC*-})h7Zg1ef#?U6G#SfZr@P-*@UNkyk4RVZdk|CG zVYlAje9VmUGT08P3a4#e(OD+Y!rB~SAP+Qu<^USQ`)`bd1+q)-tRViXG82^gtIfbH zWFj-A-+uo?zkc7oeU8{T6ZK-W&&^13b$(heN{l`ygCHvBl;)Ks&xyLeK$+(#Y)ea~ zvy`6~reAu9j9=$3t>tfcsD^_z7dep|&_c34to5PBqhT#Ya5i?Nsm4z)wDxx>@FgB~ zqzBrm^oMVCyIpFRTrsGo6w5Thd-+2TlpDDEwWGzR5$&VL$9%;4lvBC-o!mAy+dw3Y zROeQ^#--zOc^3x%!U9Zsvu4W9l-Y!jjQyqWn79rT_A}SD%p1O#q-H)| zrYINgdX&n`*Cz5r=dyESD2W`>r3X9)z*Q@w=HvmKgZ1@&D+k!?YTX5b_24 zewp6uIxI)-!QGW&VPOH>^chx9vqoCd$JDZ7OGxl1e670*XL~q9kB){Z8#=V>>Z!~7 zp>H9~kjhmFzUOv#?Mb!1JyEIbC?5QEjma4@0`+728ms(Ef%MW4Sj_7E^F$fVOl9+_ zZICZzh&VPo{y+fdrZ;8L-6m{e&bhLkUt-ptel{4#vUYIon!X%qGEH@OmvFt{#0(S_ z+=&$5i8^e0r3BmE%PL8E#AWxE0)qg%l)YhMcCT(fgDuj*V}; zHuELn?A z^-bT^-XJr6+9yCM+@L~up@^=F+^-NDIWZY&b(Z&n7IA%G9TFOV)qSk|0(^I6%29c! zVErz^NaA}^{gcftdIG3ZxyOMFZ(qtDVJVqyy7&O{$V5tfC;l7CMARQKC`^+`{@u(6W@OFNO^yUZr~_R5iiQ#d7j=Y;=Go*SQ@hz7FF=%*u6bF=8=?$#*=I&yR$^ z(D0p-eYXi?H7DUaFbN|Ff1o8;=@St%&@k;tU@X}h-rdm^9LgM^^KOd{e$}7YMe{^g zn2&Peqg2)r;qM7o`!+waK32?nL>DmDka9sUI@x1&!us6~wr%v)y&^UM8zfBo3{SOA zKA0gt3|5ZvL5&+8VBSs_Uaj2o05n(j8~n!Q0=7GEfA-s$F}@OKNxsJC&bfuZDS}GG zYcoIm#q-n#)<}B6bS8U5(>wZ<@+;9degop=L}DCb8Z!M{V!7FN)vKKrT?q z`Ze&LWQ8@jvTF2~39;&7d@JK?n*w{%ZB#mVeICkd8a_Z`2$*@D_4K<+0;Lrl|6Xe7;M``znUub zq+oAW61ou6(`mBp2|J7U8f{6+*P{uiY>_qgs79r7xUj*@a#wNV zGDV`uee(<-(Tcok6YnTt7TQOpqT&IQKPM^_zloT2vW^i91s1@7)dVjbEBV0A&nkAn zD6B(}gYlNMN|ig;cLvLAV%K#}YbC>EV)u?v$GF&nSQj$kFgV#JNJT+OmFLREBu|5W zv%Ryi{&EabcJ4;(=M7YTcah?xGo}PdAUE(hSpcMJ|5V{^^NMlTec`3}$kTRQM+}&} zFG}gn=v~UA3=sB)hw*Y zVhi`9Fk6E4^liH}LX@)13{M~}@Q1w;SVn~RECG#ZOp9oQS(xWk8;@uP<~*0&vs@Zkage8xKU<_m&R?XiN*Gx_nK)Iw7bfCoDp}QI z4}3cvsgPXW_5B9N`dH5E>lrOKW=bun6zywv5wva)yd@2j))~_jYLkmH?_VYoz4}H+ z1nQBkpkuLn)@sUG+YJL!G^Wm-BVOs6?20#z5i`3w%@>85&*W#mzbU_lct=zAQ~)mPZo*2ZSdF76&gTO5{o@)I$p*Eqwgi8 zd7x0s#Xy-%gFo?1CCokSOD^K+>bPs@Ou3#=C2BXEO1es53Yqdg+`+c&(c z2VV?~7sfzJbo%$0xb_pO%7J6s60~5%HFmD~EYLR-gxXzxa`5#)$u<|roAdT6{>p9K za=8qXTqSFa=^R0ymQqT{a!1oRj#Qd1CF{E`_NpW5Ptk1l`h-(+@_{?c9TE zSZnSXD4Z<|#GWR-jF|V{x{=MlV(hN_xqhKQvrdwOr?7{d-R#=Qj;(P+s`)o9`wtYg zh||#8Rx1#N=D9;9Z(DIlRPw5AXdwHmnsDk%OH2_Zm=HBrhxmJ?SRvo_7C&C|XKFfb zZ4u*R3GX-jkjxg=2P9|?itga!=et027@}@F1hxC3I0Xe~N1K^ySa)H$#c)}>$Ir3& z5X;EKM-NWX+%6S^QLsxuVzem{YD?gFe+s^9!bFcPWC~lQG!pIQ*?V+q`q6Q6S9=w` z*?U+k&```|3m6DD2R!ga=)Pvs4=JnEYrPWt3p`Ohb%qtn)#H`+4b0%3y_zEk&|Sk+O6eoDs3@(a?kSNkpTLi$?amdnL5v=k;VG1fJ5GKZUxb*W%Hx#X z6@n4RyzG*`Kz)lNUJP<)t7W(pcWlpYQoP=zdZbJ;Wf5@1j!JJs7W1t~==lKnZSdY0 z@Wa!x#q&lx&=S8SPtP~Gww6o~2n^f=CAx*{OM$@4AL&?0$-(?1(A1W#-`8$4{R!Jk`jRKh(Hh;*raI;bGCz#5+TBhiPkEAgQY`U88+S zx}B6plmjB45ntlzR^{7t2zA(cW!F~7*o~>a3y>7qes}jcfD-0WPNEa80*>cjIv{!> zZ_arFt{O_qyL=cUVycy(6mv7+=g)h1`B<`%XjMzj&kZ~X7!$7_JZeU$UMJywF4-1# zq}lK^U)Wgl(rmpq&$h|9h$yG?(7Tun{1Y&U_siEu%-^zK)66$YZUG72X2fL)Trl(- zotm;++{HI|m%qoTI>-fU6_CXOhlnYcF6 zrZ3OWs3mNE-?`Udq(H@U{`>KM7h3=0S zRH;Z0d(+#S?=C$o69aw}Vud7v62w;BhFSC&>FyymP|l=;2Z?iSdtB`9I}v)+a1x5O z&q|MOiu;Q09)XE$ses4w)8@N;{m!0ZXs>L&+a+5eiD^vS>|zW|vFsM08|Z2hkA)TBXd!nh?1S{q?i&Tj}s%e7FU z%5^N46CfD+Md^ylkp#mXJGuY^bvjN)m?e<7m^``2~MUQNSo!pbhSsoklWYf3^oLu_5{ z6dCL!S(Cd6#zkfd1J`TyDeeU>l1@0VzVL7C1x-fZ`k`wg!F7>WhCz==I9rJoY|mGE zst<;`ufFScZ}>9qnSOjyH0LF8rqW-&3nh1c$}zeF7h;nPMp+l+BL5lRsmieZbzytm zKep-K#r z5~N!m(g5Q-i-wxQhRtS`z;{F0&+i&vq$>Ctp8A>bB1EJLK}}VZF3~$Io}eA6J4Sdc zZv3A23Unos2k5M19!K4hbv%JIn}HlHuJ)p7v!~cJLRJVxROh`snZaZaVWrd7Fx0Ow1MnoCevlOxt z5=CT_l|8ac*~+{rva?6O>#h2X@ArGo|9_72IX>g`x!?EuHLmMGvyk zLk{f{`SeV?EJRgH9$AGjP(nEf^<+7Nlf{CphGW#`26~F`-F0K%L*Jp`9qA=V6Rv}8 z#cd?3L|=-N;7yvrmUOVy^q6zhE{~sYDRBgh%D8N(Y8Hq!huhgbJ8pRvKHZ53+%~mt z{LG@$G@u-6Nq+vP)LUZk%Ozyh+mBvf!Dz2`xguz}JC6|f@cLX{4PE!=5&t5bN;9kZ+VMoh2DQ18>YF=R zl7xrgm-oz#KMwh{@-bI|Xlf$1uR*#YzAKWG!9FS)!l&3W(c^4=oWSA>xx2&6VDQYj zFRmi{gG29}%uE!VozzNy;Apxl2`A=dPj-1Y4z43_bT6M0#$Y-d_)q z?xiq(pD4qD=`z)h?M`JAZ$B2*n}qc@e*6Il0#TQ!a+wHn_Aljb55ia`cjl4DAG9#( z{2E{1&=g=&23IDb?az~lKfZnJRSKDHQI(cy-9TjAe`nX_QmrX97Ufe7P{wQX2uARW zVFBk8yM7?U+F(VMn<<;`Jd`@ocGrph(N%VtHjtp@$U(oa+PxD$(q?&r+Lv{Lr^Yyk zXKUPZSJhx+;qx#SHMimlAXENZ8YFeZ^Xf;>>W)3_ypnEv_2Qe5m%CN@4OstE{Tfm& z5iY?iFmJ4e7@b`-p^s&Vwh;7tqvtp$S6rJUEg*lWmFP#%(L&MNXp8N=8o0J13a&}=dG`QVs$Z$Du?RRxMBse)xIjJ-Uu10xX#=s-=T% z`yj!IDOz)QkTpsg(47zM|2i(a8y%uu`v}mQ-WslVj9RIbRCb)}*<^_7R!dMhM9} zWBz2{A*nigJcT*c`~z_~y)HxiH^vkU#|g{2AfL`L?}+@!TM}_Q{nkU$RW4N*x5JY* zuMiTCxyLQ@d^FVvIdq=a=-IGp3#+wr`tgp^S#@GCT40sBd8>N&O~Pao!;q+rUUmRGm4xTVX5@IDqm9l67rFXS;6$4vDS2;WD5W9)43AkzNWQ`0 zF1823FqtZU3t|7uH!%RLyLn;`IgF!AE@kH)qc%SxV+>0ty#xlAZP@xc;~P?wIR(Qx zJPesmv`CJs$+E5vNK5ZzJ* z6J6d~U)32;5%Pry*FO!F0{zDFU7Nhi(~e$Q`ZQ8+D_*`~h-6V?dpqQ&x^kma?fp(Q zoH#$!P~4QV0i4quIccN}8x286X$nr4wewbLs7~c4wUvm6Wi~Wikn%XS`kK7&QOOs> z5pneWEh638hP~#<_Nkfkb)vX+C$E>Uc@5sh&K*uO&0URY@C$*GOm3`5h?jMRb2*~t z7W{~#89wWgg&}_zD1EUpvpi<*<@m{a8>G1>d6N$rBW+a(tRd(F$3h;q%5{hMvoqOR zjZH1f`3**X%Z~W3U%G_wTzA%-7A?F#H!(-e+=+PC=hJ8YNV;_9NZk1po;@S8`@*KW zo63hwKV!{F@fS>JU%Ff>SGS-@t=PjA;yeQ`5EE?OIkKp~zbZ06wf8wRg(&X%?P^N2cYa}wYbjmvSdLf2nFnM-LHO!@Tg??Qbm zg8Caasfk32FSMLQt@n%)`F+`gSfn>xWXPz5emG0oA1)&xz*tQSU2r{Czh#X(?z@e` z6u*~k4s&A{U#Q-3U^Oseoc}d~^N&&hbV@`nSTbl=O>VA@^ zEfZ-rI_5rvP9eZ0pX(AjK2xe%xHCDRisb;Wp`q-%fB@%eNZ;h; zzUHH0IyrM)kMbLe1#M9=d7sly-F4=U!^dRLlP#=VYEumNZdY48V${@gPWBtUe1%hf zC|%|HaX;f+N2vt0@gYKVCk%GX-9-~VJA@m`vT0#TH}h^iuI#|b{h7Rxjj0$MvG}NPP(Nv37 z>b&Q;AP8~#_T{a(VF*LZ16wSWX7G_`r~B!oi29EXb{$M1>r^vr}=q5#d9XWP~9wzLTc10})s-F&oF_#Hq9hKK~^~ zD*29O$CQoHy|QF8r)0iMOjS>#Pw#e599m#DVaky5eoNJQmvC*e8=7Ms-Yb#};;t&_ z!AV{-6{SMbNw7$V*`JiuMiOac#Kkg+dwOq@mg&V>T3gQ(&+eu&2H9y(y7r=4P;qXc zDgl9IPkTwlCY|mHpRDuGH?2j7hw?nP2V*`$!WR=+z0FHNL_lJh@BGB~*mVU+aq{Gj z76D3e7;&iuD6l|I*NWhjQNVMOl^ANosj_*f2zGpP{ZT3fJfVG(j;AG*=#CUm zUtH8oRE^ZPmY#mZ0V3QIQ|+-jT~HQu80|Oe*lZ1(8UB6iA+4a2A z=AO(BDqm`i39>ztrs#9ZFUCMl8Feu#jW4(5Qr#;fH(u|BlcG@06~+UKxe7tVt}d(a4{JRr-sU3kKpW%KpfY_w&ON6M0TrBZ zae;Ym9jkH~{`YYL&sgZ6N;~6~LK=Mk%L^MDyqTY6PLnpSq15IQ@y1>{^@DouXV_)` zZ_L~~RXhO-9aEvj*C*SLNBX5YXda;n*u7L`$HKwxy+?G-#w?2R*~$HF1~Xyr3n82Z z$vQ^Wvg<-7Uf^1Hg3>MKugE(8BlOXk0pZ``8P?hrRkfivOEF_svC0{;zm_(+r2$}G z+kO>szGA03t{R^LL-i+`^paAn_0ulaz6I_2itCg}azutA`IaR zq0T?}i6Si85yHF)skanX;izAQ&uxj+`ir#XfR_i1WFkx`zF=LbmY`(jvg^51?57nfsd zDvfHqU9WTR7GLsNxjw&sm0gFxP-HlEhbJ60;=QnZN#(YKQMLZUDGY<-7Elwg{x!tM zUGzye)~1A5_HcCdI%j<>p$`lw6acw%s4yoaVxzBb8|eI`3) ze^tp4x60rR6GKfjK8IzDv98c2+%4w%_;Ft~jBLO6j2)Tuj9u$(*y}i-+#*Z;z}{<% z?yl6~OwV!Qd6POKV$-F`S?37hC2dN%X5N#F3s1#wgUj;pfM;}gyL%pHDgpCdi*lQ_ z&W=)SVD=SiN(FLq8vg5NJy3PyR(OKCT`=B5lgQLEf#L2y@lHQ4uHlasfV5LCqxds% zQY1xJY@;uqv#vUrnV>@ zsNNC2l3JHDIM>2Kyhn7NhK_?LwF&@;&F0U!{afFwrVPoaD|zsq)F;%mb8*6on6h+a z@WhtAdmO10(=B2e*xUq;An&819UP1jhgE6t$J+v|64y?*%i=wzA}aU_ZthD;FY>q} zEV9*}ipiUr#nBYlISYQ8H%k%|t$P~8CdS^A5OHfQzp2eG*9&Ull^w^=0A)%tHrD+F zxoFL$p#X8{Z@=$C?;~J%CFz~qoo70Rak`c#8nD5m4(#*f&$pbaQ_SwY?~1&5>rqwL z=1%te(J@}OnPVck;MNC7|6--e;I0>yLy9 z14XBDcadOmx9>Oh-zIuuo#dASYIs}9Zv(WmDa!G>`JD%$Y;DYV;Q-%B&_~yKq1yLk zG{net%tn#!VuN9FdE7nqOLD0gB1fai{b{>cE9lgWjst@EN41`7`zu?0Z`u5igWGcBREu=HYCH*HG3C%^P6j$qf%=L&3 z+My0tYLoPA;=0q_v)+3SDK&wu0A8^=e%<}qDf5#7D`g>-roA}-IBXe^$XIfSO<8r>S+gq$U{h{ZywQ9A5 z%hK@D@H>_$CeF_;zDBp%wt=kO`258=E2h*;Q_9*lOrNEIc%=5ADmP^^;_VHkmwK5T z1dkNOUK{>d;c-er?LdK|kpKD7KZiz55~Io4;(Lin_eo&T zABfT~QqI|!dn>X(AD;U)pm zKX_VT2A?R>I9)k z(Trt3>=NY6VK9Ym0GZh3_FJXbl)(sIyyvnGa!2I4aq0w6`8$V#IZa3z8?_K?sADn& zt>kSiJc{+H^fR`aq$wl*X3xWnyNHkm?N*>lv6PNKJF&WOp4J*t|<6{Y%>PETe= zjwbRIVtOI-OE}21etV8UZ-YqO z9ypH7EP*{W$p`mBwdA{HWSZ)NMuH?M5CtlH*d@h&Cx=+0PK1=0*MMB&s=&-tea1lS zezj!YHHHQ_zBkNhyH(gyP+Bzj-dFcaB3F}kj1u3D?I-L$UGnsXd)>;*XVQbZ^GLr2 zN6*G^qssscD}Gb7_)(N<0x+-8_2vC(0twb7dN&iFc5&qwiQ&fnE}|aj{EfVJoSnb=_?I#4~$<8elvyKbIqY zXuB_XGh)xu7$r;XS9~|+16L^Sb+%r4nJ8MUy1>|U0K~&FRE_h=#r}Maqw1{Y35ecjF zXX4CJW4|nrHa6Q@{23aWj*VlTPxU$GGaxRZ^l6+A-m3WHts4E@jzh@1L0=1fe(pP5 zD{dlSA`#`)G_Us`!`tT-<59V_OPa4X)n=h`A>s+E9$QkUiNFV`jr_28>Gq{Rwi;P& ze(=yI0~Iv(a>zsV^0kc1YJE|XJosX!N9B@YzA@0Ki~7LSjq{$;J}&Zv1;y$ypg^491;>s0Tri^Pj&u*aOY15E z(uybCD@Ih8FJKjZEZ%Q~UZNnx7~4!&v?e}0Lf(>yNrWDB!FMC-^}Dphyy)vDXw)P} zl2Q8jz;cA2uypbz5vx$M6qk{g3*|G6&r^7Lhhv=+jys3bDD^`VP{gX-_x6?#yp8s` zcFE-xw-=Mu$+I%-b9TgL{+g*6B_}kL;2@OQy-h*56`1gGz5THff~T=k4hZ-58nK-4YQ%(X+hFGm~D`&%*?0VjAqy3fRD%Dm_hR!=h_8yEK z>kk6)N^)o1znm0$tTG%$^Ia&z_69@C6clNX9-rH?U`m&O1Vpy(w2s+$Qzgdpnt_x2 zMb){NGZ#X4D7uwQJX!aB*$8gb5dAnp{52$6=;>c0Kcl*bF{C#AxlfH$b$5zRsw`xT ztcw10mmI@Rh+NycYyjK4z}pGqq4UlSLmz(AxsHlB-d!?8_&N->cU+sfK94vO_+ki0 z?w#g~A2E&t0+=4xiPVM)Lhe0}{IRAYoiv3A<5b%IkjtExdgI$>T$JJ;D0U<;ESn355cYi$p#CW{OVQ$(g3zdP}IsBISj48PY8F?z*=p}``*$GbdYhMm zq4&aTfpm}B_Y6yF?yn2!@4td=8+&U!MrHj05j~+;h+4eXQ9q_)lGes!ewsd49`9W< zbbTx!IT7byOO(yWo6GC_{O0ArAD=#^$rD3&rQGrA8;@GgvLBjj3$YMo4>zP^FDw|D zg)Vqi1q6ON=oWXHF?n5djy1Zm5L<#gdXNt`Lp2~JgDiT2KgiY8c{B% zxxCX!nupPv0?#gqL|-h6p&DUk#O-#(NREoIUyG)U!WzpaJ${V|(5v3Wt2-N;De|Te z*D9PmdYt7(bJDwpEl;SKOz>1pzDc3778*}dXi_ydi*Miymz0E#cyFz#6n+!gDfN#H z9?4W;>AK$KF-~Kr8b!7BnPcZMOcz_1b#Z)T zM&YVfCX0BImp+R8gy~TVT|IW*xXFItOReT{8C1gDI%}5~&?hoqd@zWz)jM{{+3Zmp z;6YAtC(osJ^OOp8RIhgn3hHNQ{V=RM07`I_o)LrpAH zO-GOiE$hAR(@N|UPn|wxYBnEFir%4PWgzr51n^yu^f_Iry{ttBCbC7Ns*f+1zsP!I zI4@w?M>#T2jf)r&jbkVBRn@B&-7UwSo*k~lSo^0sZ6cnk0^A>V&taz&pG-Nk@*6p{ z#+;FnmVvz@MYL2O5-4|=(?dod>i9oLgl;x;25KvhgmhilFfhC4_T@|SnlN=8OLiSC zrVOad5p_My8P`viu*O>8HLe}bZEa=Id0dc28$6ofs-I()|4KbgS25k%EFflV%CEx;C`9<fD2Qyu!n)WU<#t;M zHDeqf9O0IidH94g@Q!DAc8Hqb{m&g-=e8r`k1nfF3A99q`{J>GLp=2~BqTUgp6@Dh zYDI(<=?1IzHHrFXBqNSFv1>KvLlyO^lB0;xatV75bMIp}C>q5U%LNO+N~eVu`q`lt z(dc4Svy~-Wf**1Q(P}$pli0YXw5xq29^Z|9B`J4!+Y#9;A;O?+&)Q-9JMj}2^3<8D zQZDF-n>!xpjIA1zb;R;~I*6bVs9cQLbFF*hreY;{ zKSf94jC%TUWiR<17GBD{^IN8X>K8Jyn|8sEuPeds+iVEgZKv+~#5tswE1^-(B(3oj zjWttg9ZS)0ljjFuMvwa)`{L{+kLobRKWf5z=A#hRjxx?zYj$TFh+G{$3aZ(8yX&I; zAJ3@cLZqt+`;2_NhQWm{%?@Q5O{|&r^w^IjNxxYCK)rGrU$$$>Z?Nd*yH{3{_h7Px zj@V$9n~dBD-8lNeJy##BMrS+Piq7>{nzICeOw7lZze?Zh&oc&D zTPsb$0J{{CJwfP;n0Sp}6NZVYS;STRZAc8XGBF(|ka#CB7TTnn(VAv`gOL^uuHkP$Hq>?(j2e=mZQ8r=o`OZ_})q=W& z9erJ%lLfmmtzzacoD+p@Eolv;-1zk!vxPE)mzg(k;A>Nh4o;snQarAI2GIMC37~dN!23i+&47(^h~m|sP{-e znr91#JJZ!*s$Y;dpSug`0v*kcfq1lmp(ow&={HkO&q#anFEzi$YiJH6VHTkdZC4KjyEr2ac(XStg6I*^?CH& z7dDc%!Uej-=5nHVLLB#6i*eTt+K{m=fvZpGC|ZOl>uZCiv>C~j{PDWW_lpGj#iwJ4 zxhvfq7F@t3yTqh!58-lMJ~!A{cDpjh;4j^>_u1F@8eR$adnUVXy^cPtQUGJ4we(^% zLQ^Z1Q(nAV^ph$SmEz*4pJAIqmp{!YC35VIhw z(UunKv%i|s?BYFp|I#z*?S`V0vBQQw?v^tHl@rU9ibe=`>G>i*Q=ZDzQ2ilwsjp;v zX+A%q_bc|7?vCxnTH#@4S92eEp1Wl&1mo^no>1?0Sv`&}8hag6b6<5YuMvi{xR*1t zI$1QD39;mnO@xOJBa$Hf`N!riCpsjdJbo;^2x*WgkUg95B4!-vGxR6P$hqpO&5Mr- z=4YNdocfI@+k?DgqI=r?Ykd!fPjoZ-8x%lI$^cx?cALw9jWECYbG6r9Grz_~iWEg- zrUYMYsq6a^M4aXSdvNg*g0>8K6|ZV~<#DSvyKZ!}nrgG4no`9!`%|Ts(*-UO0xYkT z-6Ae2$>l+#rDx720s~NBoY|Zbj4o`w6J^p^2cEIJvMHY9_JUrb0p!J|C)(D8J9#J@ zw$>jln_^xIK2!B(k1sHoikoET7JV5XVRdB##H4eWj>MFFQs73Q68H92kkX`op?~wK_Gj z3&HX~H!gg(=6q~SZ>;UMzMPYH0_sfG@VvT9c&~Cz?u)URjUZ~lpKroA8yCfEJ|hD{ zNZ@|4EVTCC>Ie17U8n%u3?6+rym+&Kv1PMTJSgNgx#^B|;TE|e3-2wD!Rb4@XwhvP zi{Fn1+*ftyj2i3mgU!J>t&3_Jsce!;dDfjkPr)rGg^pMp_Qe7uMy{P}?N$Z1w%^+eHV_)t!9syTA z_m>BM{8?-$*?;^&9<=lO*XC9(*dT_DT0i{BBxwz=roAI!jPTp4A*w$S)s%*Q<$T}N zi6}PPa37g#j{mC$th`B{otco5nhc_Mp#3suc!%b%LeBT<(XHw=&}K_hS!#9XdRNQ_ zI5&jgCW(`w1Le+(bou*}p99PSma~z%b{{)U{}OMg_HvMf&-2Gls)N(cB*gPMqbXpw zOxKcJ;j|h0JTD~ulD?5w)sCZT>*5GBY9$EJFY_MLUwI^DHbL?zaQdaxkMR8u>f0*f zj=PLl&lUoHOym(6?{3E2@=xPkaposKDKe~mB<-p2+_LjfwDiqvZz#f#y=7STs#N}a z1YwbUKz5pZDi@`3i6of-^xI}gkZE3GtO{5ki1|yU+2}fmO73? z8qvm>Rp{axcF5x;cLN(@C#UXmtP6?vUDp;!kKxKNFp;S|~`=7(n^pw&|CWCQTOfB!zTF^T@_R6xiA z^oWIJ(#X|^l=`QdMCWVDfE@}EYO_XLj(OpBTkI&WspYi0v+gYoziAq+L#uk#V{Zn+ zS&rJ|2tw!MYSe12b1m`a7Itt(55ytvR``nd^1_k%d|ukHd9Z1x z3dFTO1rwR_qASX9uO3F%rc2Toc$|0($fyYXU~_@^{ZnUeXxwn35yD}|R9|q((>_a+ zE6QLpEO(8783uI6_62Fo@WWuVj{GFH?t5H|=)3ZFvy!{}l3U!7c-beBHuKd}28Mjl zV#3r=NUDQpkW~5~2}OgA@Y6BmTF+D_z?NDpXU{RDoLS?kEOWP)uO+WtVVd;pT44%b z0KZ4s=tE43O8VrSrwCB7j=A!vSTGvH`N0q&4*^zi5&Cs+;Kx3NFesKh_eUV(4{(}a zVM^jodI_G3WLp-reUW&Toe*7&%u=i)wgEf{pXxK5Scsu|pvm5W*O?~@u_ksy zPB&cz00(XwEw+%A&5cv1FL9tB_SHKb-*8ww;qi7P-UJwCT>9lL`tjRzxN%O(IGV^ee*~1X%e0n*pI$rC1CW0Tl0j%>G*-uP|=7ig)%xloU}2? z_iS?Fq=AkM@twjqXl7Cjeau3)a+(N1rntetq2dRiR+Q4n$(@~oFADsUVWu?BoxJwZ zZAfCynKq(ax*s*R!YVpzPk?B61xz0`zk-#`>w;!F-c0*sm^kdDjE}lTgI`kWNt6SB ztXt0|juSKh>Zk-PRj7ie*BjHt2;bRsIJGUCngGE#i+=(aO;*~Oq}t8p$zydn zqsJNxa|V_tk1lV(P*@N^3WbG*OTxZ=cpl6=)#ss0e0fmOab64%a18*vR*;N-X#GqY z!1@22X<%5dDt!Xp74nZ#wFoz(XpCZ<){xH2b$CUUsiiDvicLUW9*}9E@m7T7HnbXI zu@@j*2|idToazLKWnzcyS5W!wDYzfc6xej=m~776^x1jB{OZL?#HAkG&vx-NEfe2;k1*2azSxFOZkwSZlm^&V zb|=$BIqphu`bBJdKZPDUH&BZ$pp;LavIb@AK2Qz^*u#n;)C#7FbG^>q8soDGpzs2h zF3}d)w%F8N{T!NqX5bI{fIw3^OM$Pgk55PgV>o6>J;JUlQ>}E0xA=>X5%DL8-guw- z9!p4$oHWetKoVs`9h@ivzSP$YKCA;CAQR~UDC~sc*`w{O1elPofX8|ZJB68qM$X{Q zw~W$S0^)$*n@|>I9MHnkb&)n$`hiuuY@61XLblYPQ0Xp0boZ*-H$lWOEM463EM4i- zJd?o~734+su;qj1LPvHFMD17K;YQZY_Jcl=VE+i{5+Qos^#wNiI=rl2l7Pye>x_Z>|v1yOL9n6H`_xK41uRcfIR?d{v_JS}!m*ZqI$I{fYGI zbmv9lI^1Vv;AJSwORxQ{wEg}?8b|pR#syy&_b8hv!bxm_O*r<~HY6wp%n{rymf^6@85&14=g1FR|w&nQM2GF&n20I{#aYmkP|;QYJOU%UQ;sv zxxdG)GZiG<4lQ^c0DLQvMW5ZO0y{NScyDpW^N%fI_*esIz}GeI>|Li}Pv z>ovAoahWDWjF*5~DHZ&%`T$Usk3&(FH3#GGStk-!UFSG1#~)nu>57U6*A(Ky=UY!? z2aFImn7#oLBs_(1z&4PZ@6z_2f`9o!@!oCKH&`o}uz3U6Xt~(=t0Kov$6v-z3xh9C z3C8hmLleT-`!tLW97#{Uxv=MSEy4o2;k1qb`Wfjy+FeGzk(Fp0@P5od;&bTiA~rL2 zgKjnt6U~Wou(*9df8N2txNG#l?oBtoi-=~=r_ycS4(Q=vHMXJW>g2$Z^z@v)-fJ)9 z|N1|Fd<{^X_u(Zqpdd-Xy2~g9-i4vU`+OZ|bI#&ku@mUqmpt|YE_$;^U96+)5Cz{Vdc>wY5Sns7VPkR8cfAd`cB@d#4=+pZk^tc2 zbRtg^xyDIqRq4zB6BvH*ZT`ol?pOcfF<-V=Y(12GziFgKYWM)UJS(v}ixn1QIi)dk zKZsNmhQ!#a=(`KAE+;6rz=}BZ{3zUToQHf7D)SV?(#*h!dK#zs>JLDDM86TC%mV zF%^zHDSmEOf@*kx^iY_>7;NRzleb3%3|h5|m9=2p{@|lGqB#H5)BfH%$S?nw7oaKS zL*vqc0PSj6J$r;Jss&Kq8Xl|jzc~IKn)a<=2iv`-xDFN+;^2`g8(wtW@YbWt34$3q ziJmO^Q=!=NDH8V|pW{lB8|cT{XMMUu{)^-!Yrw5qw3gL|0?7aVeRuTNi|DO-RX$JF#vCDOuA7OFLvO}ry zNF@ly7snygyryTJp?3np^&4K>KZtm`lA#4@y-R%YlXA4J9PCFPE`?6vn^`@b$rmbh z=!Z*euf3YhPD@7m!Jr{aD8!;&o*@+L_G<&)t_gjX;z9+7`w+jZ&lT1sn7+`1-mGJf zB)yMTL*#>aaWvA4BHW|@{qrj2-ktwWk^g>FFTC_2Fwv$y zYNal;?f4K;*@$xdo5D?CgA<}>M?s9D#tyxi1v~9fnD;oSUnrAVfV@V z&+{eL0FOLJoP8dgcIV(6+B>0=Wcu~}GZ5fCswtu3M#ep}THKgx2oSet29(1;L2}h9myJ7R_%XR=;FNo~|)#w~d&sV~UW43(s-$V7Oh9OMz1pHPe`c*-l~g zrFST+a~p9|d?M;%iD`kltv!sAv{5fg@d#7?PojnduvP7Lr5gy|;F44m1Eba-4!j)k8`K0na!H?IB}| zK@|s}C#;5z3Q27?yPKxx{{g3K?RKX)&lj^mXdxhB&ZgRy*USEvk$6xU}uT zjPf#ALkpNGXjynR!|DRQEJfDkDY7-Cbu`zGNLC8m+Nq< zjQ@AUiem!Fr2Z2F_|CGWCjU0)mfj`=q4ej8$y~UxA&P$Fedvtlzm6sF^;70WQoqa5 z_hPgzua;%^v%EJ)yjc56;V9UFGSF3%dz+4%OXFEF+BcY681LpF>})p#d#ZB_Fr_bL z!|f=xZkFR{5I5vc{l7fQi{*MX>)3uUC4zHWr3FQ&bG7rA*nCmyYt$`_YG)CLic-h~ z`_v@2%>A5uWu^E2^8|k$2)T((2GK|sC2K}A*?hkUv~ws&@IEQcV*Y(@{_A3(R%7a( zR^flb!OsRuFVlbk+uz7yH+13aXibf#+YoMA|4ThFpB;jKK|1}wiP{)$;~Y?^ zo6FB!b!#RS8Jq$Rj8k7JNu>=wyBKUq)w%xlL&NFB*E{(O5D7lZ2nPmq1Co$ePy)mJ z_v(eT=I_$rpO1u7gPa_}7Xcd9W#AL+Dmo*7VkDGj`9Cajl_Fs=eJjwq1P}I&Lh1F{ z0AFP7z~+6aV_C@5_9EH5svdV4GK_>ZMif%njfK<>{Ua}CAmg)CKhK44;Fw=RE8 zdcA{60sLEO+nMZ7PnGWe&QkvzS28EW6etF`E&!P5^nd?D5 zge>z^Qi372-~X|N3>+?nA|y5lq`3gaL}CZNw*@>pCvy#m&?iIN1`sa(bJsy2^;QUq zJv8HnH7porN!~u2)Jbky*Q)iuH`TxPl_vp0X+aF8nniL>)j+*t0E$)%imiVfYybYx z)N<07U*CcYUuTjg?Uw~_O9d$;%5M? z`1?GzSz$^93tJl=m7=6J*DcM!??caPp$KbOA+EJPt zPf>?pUxn)&XT-Q)VqzjECh}j;h^&scga?IC3wYfxNVJ*|b%+r^r_xlnltIo1*YluR zoDQeE3VVz)%)+W8o?JK|^ulMZgPdtZ?r@U!r^^*Vy)Drm90;EUh9mKKHMo_qJI3_N zlV=_#n1u`He=keva!PmT-m^zQLeQ}%+V=_g#~&d7w?~NY&o}>A|8Yw6Kd<>`q5RoZ zEE-}+IQqb~iaiik#}&4F(j}17X2t5>FhO>;GkTF`DAK0Q2U!G&Y{v_rWDHe%ZuxYg zroq+av(z8H!;$e21vJR|VO(lu;<2hz#$g~@K<>f8+Ht>C;adY}(W63jmO*H<7dkA^gWg*2Lu z3(l$gcz#*|Ss-C_#-@LmupR~vN&46OSF{bd){MvTKuG%n4zu;}`lc0yxqJ-M2Ay{= zBaGUgqy3-r-nWA2#-C&KG!awCQwfhkgiycUNU0uR z<^W%Q`Rn}pqb66H$46w{SV}>mKL`Gmzn3-qVgZR9CH%R*HV6T#@cpuc&rC)q_WBVEnVGzj)(}NQ=_U{w*$*W+O;-5*Q z>V-d1AA*n3$42CaEOjIZ*&~DZNUgJEXc+o)=%u`?5D#cjn$ub-(Rly8hJQUNc)O=E zzEEO95g^&fJcPfcKp47h|?Dy{)<^;OoamMGk z>E_{E%OoTS*%K^Z_*|*K!C(Nfn{1tZrC2G*mpak@wj|f#mLxt@b6@i|TW{!+P_(PA z?%DXeR9nZ^y5TYgd9%*J;Z@t_4$MFeB1CH})w=#jj;;`#`t9G5e(1w9(2@Jw?OfWG zT;t~7tL^tMsS+sFcz$LZl#Ug&e)S&gSD+1oo8*7~%T#6%Ywc0ONPXmn1i>p&1>><= z-%?O%0|{zLPl^pd+Qc}VcW)3J-$@F-gLgP91NOv)i4fMbd`H|{T0k#T;#(Mz zwu5$b;h#b`8HRx_F%YdT3CKA&I+=qt{IAud%#?Z#ksYNEQEqno?3;Pc-vIB%QpC>9 zk12#9{0>4kN2Y`8m&1_5((mr87va)w1Ynwb@q4%twC(3sZ^xXBTZfI6E_ZL|%wb^! z13Fnz1hpH5jWLKovNB=?7rK#!=>?`)T)jhQ!?z%(`L`GRas(yeYO;s>;UNff>aEfc z8+dEkD|s%gsak(tt0{6q(3ZVASi8k2CcLJ43~u?#Hk5hwKqDk-^8hhOOik_$2)F2V zmbBBD^O4eQ;g*XPbG(1{)~eXqmf(ZXJFtF5w61VFulYX*!k>dJUC|g6rcww@TjT^F z=uyt|yQ91f#JPy&a)_Okvj`h%WrNkx*YL?X`+E7_gT*}hbI&OEvPJ~~%Ja8rd}G%zAP@@fQM7Z+ z!5M7^o;ue*rS`qne<|tR>2U{~H|2KGb>K1jGko?|GF&44u^=&U8ltCuiUWUvY6#K( zky6SKGOQQkXLz#Q4p_}Ff^lMUr+g}J>TIj+56{)kgB*F#jjP`!yFmQm6dj?jlM$yv zrO0)LH%vDM7CBJU(--AJ9}3S0vZ4gLC009@sw@8G-CoU{y5`|%Ke6u#uasUV@6rzF z1Dls-f5267VBN0R9}PD^f!#s^nZ(k)t(LE_m2->uj(rw&oz;Te`XyqHT8bzpaPYv@ zXx%LIz=*wDn(V?4jZM|!4#D;T(AaMz6?rEb?7{4UNuvbHZz-{>$~I;=)o={lC0fV^GbMy`LU;#0)bla~S$rM3-Czq20%SpU zu27P=v5-V|+i9hnbxf`Z&V*H#nN4VOASZS2SdPW{URI`Fo^7G&n3qoM8>7PtF zU0FKtch2x@%^)5enZ6d+Y6K1hZA@ZH1^I=QLzy5B3g_KHw;}B+h~I&3wFmhej&-HA zkDrhifENju-P!D61lzrl%MonvyxyEu#~X^wPS+^kv5KH@6HoYg(Za zA+fg4L^}8Jr8<^3_DR9_szwTx0F$3&_J}RuUgqH~@*ywKAl+aS2i51X#ToRVt2hpM z3?5ZyyxBv2QAxF2-tiE1tH4tC5fXhQ13UCsx1*yxS-;8dBCiEUc~tP+`QhTvP-saA zBSbobbHqC6mRz`8g6<{n*hqS{(DC$thQW!M(@|4mZ$a;p(?)Er zECg=XdonYi?|v+UY!@j+kX2=g4%CN^@;2MJd%t_>NJIB9&dqtmxiefzbSv<3n~Cq0 zT#HX}xgc#kGmgClF4F=e1!Hl@PCxj`R6}Cd87J+$E3B!0a;ct3#&xbwMCTo=%~TOb z)xa^(DG~gT%EuT2lItt=lJG}l4ntgX>~*^W`HK1Jdk0}+ELEqog8*Kfz*Sa7UZ{Dl zL%ud_8qP!Gy*>lrpCX6^Mrp3Qk1IGNy!v-Go=HMrlW}n8OJ`8JLyU7wCUEYE8396W zB&M+l=L}p%1)ReS@uWu~v)FFnWLSma72L<^FJaR6&966BhU6AYOI>3B%sOom z9_MgBgS+$RWz+BY?K#$c4^o!_@IcB#S9;?^y#oMk+e;ny!J}TOXf_iQP>A}XE;1gV zr-OMem(1Z&HK{@BwLF zA6RxOoRTk-J!hp+k-a_9YGPb3M~w|FgkCy=&^===npplKBUbMW=D{Hj`1Civ-t3S< z-A+NUfJBf5>smdf?utX4)=eBjyc@C}PLw$~SHW(tN{SrJ(JjJQUyiks$lW_;t1@qZ zxsHWGO8rSF=l(X7cM1*!8=K#Uth6p7ndXp1(j82v4HBJh%J=LF{Zv(4NVbfr*Ohw! zmVQ20okA=WA26J7jZ<$oF^u&s<1FOzSoxk!*~wnyq~`R1ZL*!Y_Ne1YNM z_ogSmIYo>k#l}A9P1Ey02QWC+;*0vohY8Rb+39B260qJNo3!5d`#}({wNB`p-qei5 zwE238N;)x26PLYN!JtrQ&5vn^hPW-Ma_em4&&#=B*5Dr;r*W_RZ_Okf~*b5!93I73~J^pPs2w*g^%R`!z|(yA>@K z|MhNU{tQbCObPa4`XW57fAfs)SkNFJFqNlsf9ss z(FL(~9xUYrX;x}a1b>ZjnT9aA^TvQVbjO2&n3^P)6%r-t;EluR9QCV>Jo7G6ljWym z{c#M!VexCzvP3p9rx?CA#GvnuVI!ZTeJXema!its;gWq_YYtVRcT8ri#yp|k9`yc0 zs1;G=UT+zWQVeCeS1nLB3jBQV>b!%3h-|dR2SYtWIYR-hfr3Qep^2e+hO9kZ)Fuc* z7;;pm(*F!9l_;d&wah%-+cZ5&M(zhLw-5YFwUv=%a%@(smBUX%{tGzVcgcDG8v z)tr*GcTi-$BNR`TIUm|v4YAnN73~=I zC&5ljNQSie`eBg3D7YR^c79cgD^_&}jV&P7+H1Xh^V{)yfgBTd?#lHc+t<8KqBsto zTP)Zh`@$R>5;8^!5vt}oe8sYn?S#eh-hufUPfYLIMVQ_>n|s1Lg|BSPZ$JQ7Ha&sX z7OZKK@Hb-IxGI+-wf7_X)YA`<7P@kY34}>Vz1&HCQu4qD5_&?8^BzrQBFRSj1cEHS zA~0vbtT3dRkuHmSm^})`+gO3Pk~gfWO@i1w4QeY35SzG6d^;$jp7Ps0o45=i5S@-^ zw4e4t22Unm*bq$i=D<~PZkK=1nhtp?ZggUP;s9ii+0WbP>#LG9gjTgn?o zZrA(|fk^~vXYA<2F70`TBx0Mtbs`N52$6a6{(9Ai94FFh(A&63mbgkW^!Dy;TUew| zx5!0VVv(S|#HRPmt(=J*p{s`$%%vyc1BB{zDPP5q%8{>3sisoM7m40hBl;)3PhCc3 z!ZP*!X|;$Md;O}X<|oFMmXf}%?7>rGzd&R00YlV4o^R-d$)*PduFa-|;sv%5bp@6B z!QrM6VLa^nM%DCvZu4H<igqA-5rYKD-4r%T5te+gBm?CPU8L!EQQ2?_{&^3P}%mjf)tB9U&K$?T1nnhbBq5 zzx(yEZE+}xu&-MjeHe5*`rGn!1>zn}PkdVtx9aq*=`i++gSGW?W&3pDJFa5SPJzTl zuR^=~H$M4&;`ZKcB#Ba_$#MbkqU;XA%h&3^+P|Hz= zlpw?DY%`N{=nM2=m+DQ`F42oQ3k^+WUFBcJ(CfsS+KPU<7)(7|P98A*iHJXqOKxSW zq{f?NSMb;w(YIVJS@1$S-O}(!=JfRRD4YThqbm@%hiPc?5aCWU_;R6Y&az=UpnC`lF`C3-hg;cPfgcLZK~`juYqhuXOz7P|P~^}{V9k^A%rj^+~H2fJ;N ziL!BQ9Zw`y>*5c_LI)B@+8rS5tbHB-n%xyklAn-N5a^|x>-xaT&T z^^(p-!{iypawfXr6Mgf{oRy|via6=V)f2`Togk-Yr`m60lE^08*s3oQ(&}Lw2pCvi z(97vGg2(Z{H@=m<{~O_ zf5Xe>I5lZDD7lkMlO)mVEzDHO*1Gk0-XqL)~LT?=%*{ zC6q_cofcx@kubK?IK^SA>pitCQr<*4CZc=_tiU1)p#MR8iguihDn;k$YXz#&J2+&d z@XyZ;2ZGtRzrz35MuhB)V<*{Ulu^k}ij-Yu$V_G^BP%P)|M_m*_vilpf7jJ@U+(L^?n~#qU+?GZ z`FuPd<5ZTX;(CWzgcTI$AICqKkj49W)p?>ti=`T)iq@F#SWxHZ+pMYt&5)UF*3*v zZ9(HjuUvg~dUeUtLU!unoXPt-#Kq<(;DyP){$PMTvJM?i^RSdUI;ojL)eEh~UapK) z-GmA(LTSo=oioG9(w~CDxSBQRvR#kp=;gw!x=?R)dHCcz)<}GW`rW!W98nWbQe&pK zkf@3=K69s$=X|Yq+`DYFnamrnd^VG|O>j(S;J}Tke|O7p_k<%f47n%s_aogV zJN(2tI^3BC7lgZZzl>LiayUO@v3_Iv>)A7&i-JjG+1X8 z^kX*|5)N8Wq1!?A&lY{vBp}hJrL58QxIwE(u$@G-K>t3}!ePXR9_hKio#W!Ut0{Ql zzbPVr>eE+Z@v}$J-WlNj-m~mK3b*uo1-J%teYRk8Hv;%U;+rV+{o@1L(IP)#;BlU!Q`&1;ZLL%A`#yB_@e>>7nDp>g=~7S;sW%wRnSA0<`L=sz z3r-#$!z&}n{Shc3(;uf><0QuwW}VNFFH${843@#~X@KuC;UKNP^nXo;FGjRwR|@mPz0Zx{#86I1${Z~)j8 zwWrENY?xj-6qTu2v9UYNtiu5Q3_7H@$fENWd#kBJEA^n=taoO*+n&taA`pnXhUU7Y z2BPGvL_OKmxmpRfA#Fenr-@aV&n{^lJcLvOiyIq3r=1 zjmY90S1SsZrY(>MTXURfz2T*;y_mt|(q-tiZ|nPbhvn8yQo@0^+7Ul1R>E#xI?lV= z4H^(ZKfez)=}tu#Ekrw&*I;=@=w9ER}KJOQDgt8zB0nAwnGul|01RQ8NQL8d75fseQ;8akmP!VK>i%&g=!Ps z>=L}zBG+hI66fc{-tEKdO4;lP`8@Gh5eh@A1CNWruEU0lP!2du$J#wRo>>V92~O}9 zY?Em|M1}Z$#0;s6FEn;eaZFgmt|l2fzpZJHCTV5Gf#ogxCzWiv{L_InVJ}$;Xp}Lm z0K(t+goJWBhEf}pnk*sF5~NW%%!Z0FM=^a_mDRES(sLt;_pT8o9YP>SsU2tttx-0a z?WQ(7?IEbesRoS|VcN{9E9sr(9{HuUdL zQB5jjHmC|f^8)&rm|feHDy$;OWvt7sm2V&yiu>AVFVOp?yl+m9W8iw4M#%FME7o5mY+cp}T7vadaXLDJczi&ZUH(vo@d%hj6anSSE5(NU8J?X4vmP=DAyBmDC#CFUJg-Qg@S!L?Gy(1=aAhD;i!*!F>PZu> zU8*!UC?2zby>VD#wPV9^%oB@#@uFgrDOt?CDJN;ZX| z+$2ZrIM;CxJ?Sq{0JSt5@t=4&)JBx5xH%;=r$IH)vkyenCS`rOByT7*Uuqe;eL3c$ zbUWs%q@Vd#AE#}9fLLdmG#wM`KxYcLs!W`VldRcZlw7JGPh}kZ1b$X|yq1TU0)W$( zps!Y?@Svmzwc87E*`fpeasv-b?pj7k(3aO1j(zp33-H}|x9duAJn2j+9+k99>b`%s zy=AvVYf!oCDeM-LxmFQycL@40=5Wo8mBm2St78GHT6f~m$(w10CZ`5pUBwHO{bcap zh`Xu7YE9xCuaRj^Luk^Wx(stSCkR)JVb4y&Q*f zoQW5(JuoS>Wn{*))I?cM-i~l~fBmsLh9EI5Qjch1_R-eL&d737J`jPW>A@%xx&nhN zIq2(MULG=Zmk^jBhXrUjdhFvukJme51#pHu6OB?k?V5p>-05~z&}~h$r7(Sf0oM_1 zHtdpeZJiaLzLQsbyx-@aE+je z<>4)_0z`wM!Gxpiy?PBgtXF6x{PtDgGF#oK?K#n;?y3?hms4GQ(SkYnGR@F#KF6rd z&v(*u_hqi1A>bjlCtpw7)*KeLafNgYp2*iDS0&i5`P9BW>oeLlDs`nxYC77pVTIXq zh@J9b+1Wtxj*qw)>V-jjhdz88Vt~$RnqLRU2fLC1kw7EdPd3Z0%$M~SA7oZ}zwk0n zNMzGqvuy^AajRvMQLogJ_eYe~(F-}`H)$IMO)mS<-B_8Z2i=*nce5h|U};tcmCe@j z2r#{m?3h{Q+IK zPhL`{pyC#>N`=27Nv)T{n#FUDcSA()Ws%cj$ATP{ZtUX%WK7mW2PGxZST+#ob4?i* zg;#0CwqHDJY;0`hL^J95kVZ``aa^B?Du2?}Ipwa^DJOOB$`UyuDHbUOmqto&@7E#} zEgqldxXGz3kT$8t3ZYl8@(E)?D?dC$QScriNc_vd__OyzekC;_em4yE%4l|wCcX&6 z3Z!%Qn~%Zpr2F|*V;LO?aM zL%QIX?pPi{K2Tz;)K2jgkt9Vhp=y?EmK7|?9&08G^(f3`bi#Df!o(kZ?_0(v#L(F# zhO*#iNbY%0>k4#7t)ZPMbb3xMN1v2G89SOX#pP_6cgYeZ@7xWSl5$GDU7LgE&vI)J$HyZy)m=EXOi}$q%Nb&r zGqyE64_a?RhEQn|#(nAT8b|LxwXOdmvMFM=bPvG{a+>WWA|p$uQ>v8 z*(1wcY+Yxf^3!Czmqc7DxsRs&c{ef!+AfLTNVCsBhq`2Fe&(jYFxyyi>4Ap9dJe*` zM-)sVWi1+rrZaW1hr4NOZ;(tsnz5}v>qVYD22=Z?0vzL@tb`ds>jEr$zua>B2Vk2I zQett+;E5C0;P}Nuc=w6Oh(~t};X?M1TVr^>EexLIq)@qoa-irUqZe&L*=k|)f##uZ zH1YyN)%R3b|9rmCfUgJ>W9@MiV_P+H&y}ps<)Wg;2-6Y`sqg8bYH>7f&qQs1FP6J2xv$@az+c72pM!M3#z z(9$|%6~9>!DWaVHswssQm0eBw8e~R%eryc3c3$tIH=~~3i{g}Bu`1WXe|E@EwV7wT zylaXo+>zU%P-n8h%(to%(dVm_ww!2blv=i}Ri+SG4fx)dMQM4)#MW_uh)wA)7JxUQ z*hcK62R~%AJD=!hN4-fyUeiTsPh^{Nv5rFHDdjiI$4?K1}RW62Q? z++Y2^#g#R`5cYpX&53=`iM5#(a5qU7s-7S;Gg)*aoiUN#6bTC839M={<&Y z!DVUEyUn<4W~{TO+Ra0%&#R*P;a%IO=SNyLZiODLJ662^Z8&`9UyMwt41so&G7wL< ziwS}Ak0=PQFugr`f#-Fv^0{#>q6EC*OBYXI1p8keHc{9J!Ah6}MV~s)^R3Mw;%Hmc z0V+edh9WAN4q_Qwv=>o?MP$geAox-_hIGhVo4fAiG zdpzIkt2e(qgOAXoS~X-c44DJQgouiPg+Y@9ioc=y{2uBac7-vi3|I{e!Ogq!=8STBg{u*EoxwyG-Jx*9{0t&6}W7Q%kE9j`Q~~s z6&*M_J0-bT>i5?Vmij~m-gW1B8RwF}dIeb7F|Jktw$3JJ&WJD!QpRqXIOYB@aqyE- zsh^adp5{}mRcmwu_Uvj6mGh~%jq`C&R2pSb@7G^;-&g?1u>wLj2aa&k_B?jK&_zDC z=3chgF?Fm?l$OO^KPX{ekB5XR!#&~5+x^roYZ@XKR?U3JJ@oR3u;|py7ceWTCw2K% zUzF_gf})m|2Md#*;7`UM57_S96XJ!@2sJ*vqXaX5dX*p@PT1%d%u^{AqWpWrvQDb0gl|8&NZE0UedTET zTOPS%eaEK|k^^a!g9Qss#0^J}Q(C516rq(ZPJH&>${sbsa&u9{($&XJ*F6O7*$FNb zuC^2hIX+E!MRAIG0g3@?s8*bQNIjNQ`^1dbQ9%g~jz!p_%NSnNF)Gr|g^$p?CLPe* zV74~Uet13I`2}B(NytM?rLKx6dP43kSH}XIW_=BIC62fJzGq%*x<+aFyva=qw%te1 zU5mnV&kz-ZqO;}_GD{W;%q#h$?}%M zc!AdR)K+4ns+~Uo?hG`xtG4_J)1rPtmim$xM$}?&)dTur`_ucV<|}Y@ax$!m&Pgj( z>e|rSDiGGr+mj1Grs9aHWD~b@(=QV77ynKTGMRx4dT~Vg4_nn9{}G}+J#%0ZgFAOJ zgFEA)2mVAmcLvhclR{fbjvFR8csN9V?Q-gY*3&+F6c;S*C5$hW&X?}3wX4^76E_y@ zYdjUAqR#)r`AX!@?)}fRV173e*zyzjp2|KK(T{QO1RCXSjLtcvow~o ztY6VTbYUOf_(mJJ<{swE%b>!Qqhe-?m~)VIq61b@6@Q_teBoh{_iSow638l55`d>+ z*!XA`mY`ShUX-#V#~ui7TYO2j>SlNI53ur2|krO9|RW_=cT3~_Y| zlGi`KBYR>|pqe1oC1q*&fb7elZ4wY-b_SH#mPsi5L??qQ|5lURT~j-H z>=Uvl(Fv>$-!nJ%RDX>8^A<3KzZQ?_qux*>w^RQ% zkTh+ygx2}kdD`|Ap8wn8Azhw5A^&euT(%n#m{&P`0HK;-r9su)y_*b4GMVn&m!lJ3 zg92MYzbotKw}R*a5~_$cv{I>l7%q}Oc<1RmoTYxKR%Zy>2KX0G5ymE^4VVbkR5g;x z(ygDmkRYCSYs0*Vqd+#!YX!;VQ7P!q#Vwu8ET%VvOMxRH;PjQp=Qt5tUkmk(d39uRRRq8 z4owjYgEczQrk$##pf&wup6ipNeb4}aLXl}kLn55Szite|jWC^oBx?!2O4)@qeapUIR0znDfC0YwM zjx;UCT&|D=09szLgM&?@@;G#eOHhfQ{n~+1=!3w^iO=DMH z`cQKfHGWn$`h4Rx!4Yh}dx(^mYcb*iUj@`Ou6eb)VNXW@TNngkM`ke5OlnKI_aXo@ zvij<_hcet-YB7UzT28NJgnpPo?AKCGI7{TVwMH`ESMWZGEV>lFYXBNMVY=PN-bKki zj?FP$6ZQ{ovVLr2fCSrsXvs0GdA)Rk{Vqb2ggs#oM>Ht?n!Q(C$bDeeTzrtABN}^f zYyq9s-6AiPbv-jaY(dTLZMuWESBc=|^zHenMsh_a>bVRtqP>|b2ZDH$SEKkJ1}P%E zZda#G?fRjk-QEf&e90oDS-VmO^n)7x1;4uWY!qP|wCH+=Vd6{rtULH4P z7tWO?K!%#IO*y0j$N>-7Q%KwE%NIde)4;nUn|i=9#*RVKQA0g!+*bV-X~QkzMfwV=r&SL5C;+Dv3A&+tj-Hgd{9G>; z{Qe={TA4^6+37ezAqbQ5gl>ynvoeN7eq_7BP(-<0i$*3Hiz9x_Jt;b99n$bke%>Wa z5g$j<@BDIOKmz13$M{CnUHwB0g1@YDL}7XrCO@TIWk%{ZkEG=EzFO@TVnIY>)T<_* zLUT7LmCR#I)!_@eoT6)hS7SKFn3v;T^q2I#=+@zK3OCz&u0O7D;48 zXw#HQHW10+V%f3w*6b<+%}d$2j^}I6Ovd&C_`IsbJ#0lIzo@}i14C=-Tv2Dd4?5oB zlJxOmD~${qA4~S?yu3Wq^G!EkvuMImXWM-*%;f|{D);T;6UpxcHAONhW3ppUChxRm zx`$zh!q;7;boc%ad_51`+h8_P`6bi@RG&IEbQAUqB)pI`$P+v!yM|n zUAeii9_o?`^WX!qc*y)8I`rUZ2p=URBcBkv+H|2!6Biw|cM z2Yb|NwnCS2pBEsl$sx7)@}edZNnU|Ckzj?Vw~&weT*H#Sy|zc=o4`Ca;qZEHtd4eMR<kDe;=cqz?mx!;oB$Wd?fPCXj+#T*2^!&BYg~YltVXht=c;V(2kbp1lpqAyt}- zex!Kv8c&a=*(2&*Lu@jE!glAqx$(S$j zUX^y&c80cM9h;9lf*A^JJ6yQ9H z4FnCXg1b#6;v2JKt0gWi>K9{k`V8=kPAs4MSu$I8CDu}4_&Z+?yu&}Xr{gwZ2-Nv9 z@&1*`z7%W0VRspf4RAH7a#bl6L z&`3RGpV+cCpLq@@g$h^$+MH`SgCpeLV~ioPXwL)o_5FTi`i`uFX6k zbnQteL;hj`=^_M+p^4vqWbN20_U6W5d8@};5g6c$zDkpCj&sa3oAr=f({vq9OtQ3y7F$J_a`_LSxp1lFL zh~f8L?lK$vodD>C87<1=j2N^TpbXd@fRV^bXKx3D!M&3T<>a+(7E^!QV zLEq(HXo<$NOyLZM)v@qXV{RxK!v`YfuMg-oGcNmqyTvW3jP}M2Nv&Hclc>ikeJ*0Tdm&J1<;Q`*@QBL(0*H9C&Fk zDIwLLMSxu4ykZwkV@IplBDz&(gAw%O5bKHq3<8fVGWM2;*+xe|#$YLsk=hi3J!mD@ z_gswF6@6KH@F!FK9T#32WnmfMpB6-Q(AmTaIc?k)DG9T#izek4rqs7g39Y;FrI$N; z{#{&(kl;6j*g$>$FtyZN^a7SwNc~Ma?Zg^IpEbj>Dy`}J&*U?M-^0$POMA84Y9>!r z@xe}##$AA+dGIr}0k(cwry3SNUo^4OminJvDQ4$nOl7y~O0DyD%Un8fk);oCL{UuY zh_V{fwOfuo<^t3ZIubQs6Lq1%5|@1lr*ZgFc5I7w{uSK2(LcvPYF!1}0lID~1kvom zp*7vfw}`#3ys1iQDBx>SEs9L^&$30dL7-OMHdh@LcOY8AK0B#yJ(><&7^C}gW2`-_ zUKTmhrV3kny}MqqoGs1a0y8?GGbohBD1LY;lVxX3mWE+ucD549jmNAZ#~@;i6+wbFpiqe{r9a(-qMEof0zoFYM;eq@y`*E06dY*T|9nnVF4 z2^JSWshiLqm4*ud0T_0B1Hd0)2A>#b1`2shg4EzLx#_&Fu{=iYGfk4Aw&D``!U8Z$ zsW~>S>qPwg-5}MYV=&Ik5ySwxTB$;&6cOzDz;Lvwe z1(KHRX*!ukbLGBw0Yw*SI6X8F(D{chIe)u34zIKmBB&ajIZqUY?At5pxP%ZwJ;icWwF8;4Iz9PN-E1+uKs-ntU}E*ED?ot zt|BuXuzlLx|2e+zU`vqXH#6G1#ntq-_C7|Pd2}Dkc0B2jEsc1H>vop+EPaO8G>e%~ zm1_>Y+^8&t?yf0T%GLzv28pObhCf((AtCgRj}I7LLbwDW*-+;g9)e z|Dn+RrYOAUBp_nOs={QTIXznfEMy6{wQD~sC&YC04tGNjWs8^c)$g*VW%(|iR}Ey^ zJ*+yy@MtWo-TR_~51pWG;S6pLwxiU3K!+zoR`*?@xAy4Nv*RL63u|G__hvII3%};kOFE*{AjIPpZ<(KUpv-G)%D164r-F|rHHa(eRs*VaW_FzckJ*yVqD|hV#$DcP zc8;D_+~3hX^M*d@wDEI=a94Z9xqawjvhY`65^@Btg>Dly;{+1}n4f1bI}8Fr7{^q6 z_ej?lcWRPvIbJVPUU*-=j-+vQiz>Ww?}FXo$?5GC*J`uolsr;Hz@JfDEdJF%H@})%| z2u{2oE5rZwlz}kCMRty8PJxMYQN$EgY;PVZUDA(7@s!@CgNy0;RHQ((?v@TI%_19% zG(s{4GV(Q!lkR*Zm{KK<*aK6!?{J*1sCJjAVRWSTWJY%!dIeew9jwI0ZdzyP*4B7H z*5zl?V>^}Ci<|7DV(|CH3{gL!Va@Hn6+T0aW2ecX4(7~ybv!5iHUm=1`))b8=p+7Q#%PBbi_GNx=l)2 zeeRF%R&OFes(%W{4RDu|z!a+oar|^4WA`~$0eRM}JpvpTn+h$ibiJxHKQ)>am*vn5 z{E~ZT+dRBM*s0NEebhyfj1(_5=UCAx(SEmbLW(Gz*2E=f=MW9ByOY^dJi4e&407nv z;cFdKv(tXe1J@g?m4CqfQ?ojHd=?aSC5Qwb>f)S3*jTyqagiPJ!Fzy7X>DHms%TK} zT|hnXI>q3{SgFFlq_#)u$P7|upzWcn#EcG_r;tny1tRP9N~JVtZ(4@Q#SW<4I&{oCsU{Y_NaJ}X?3hT)^{aZZ zziF2T(Gw$Gera=brqhh(O8ti@>|_Y%e|t75DG(vqLT5&Ipo*%#HI%yvdl!1MBas~Z z-{t^J5uasln4+j=izJzD`(hi*FF3Dc=MH!9ac&{&u9Hrgw>NQql=<6z#zsV6OuiU+ zlpU@Gdo%7wFThUcl&)AR%0OeC!cAL;;YSt%eLcIc2!{c?*7)6CM%M@vvLR0t{^j~` zgMHc5QGp_J1YoWDL`of}S3R0UJoyTAv^-K4-0{r>5pOQC$&aCS`_^+GVlpWaPme{A zYjiwzhRU(G#Os>x@J&PD$=x0e7kQS2PM76rFQwZIv0^0RYfs&nXV?8>1CHfv3k!Ly z)Ex*Yc4}q5QTeV{?2E{|o`Hd|XA`827#OZK8>aX|^=$H01r|vpyROj~Y*)i{)?XdI z>%u35v!*H87KJ*%dg~SW5S#=|I^};D!~yrOsC=j3ao5b;s+-lms-W& zYjS=+w$7IkYw%2rqIYEEDi{Nm@~o1`qcpU-Rb~;EBZGOBl?upBUbhQD5)e@{yflZSC z@*rUm&l!8RlB8aQW~Q8&v5(_ylX{*}fAiIkRUe$w?T!$#g(yY5;Xxs&QN$JhwYMic z!BmB3s{9aL-?!}t&DyCL2^*@*dCkh9SbQg!L6Z?%t4r0U?3y!QoPIDP+OS%9{T)#|hqbM5zL}xEktpKbtWkfix5|bRg>n1JE}B>To-!FTTH>7ka$`c z;AYh+c>_a%3l_+k&?6?~zW^tJ4G=_{5X}grcxS&L>ZQ5_?Vhs-B2$|L)QwO9rx66 z1e6FeA*y`kNn9!%JV$3@^wz^4mcs)8R!7$cz6p>oo!KOijIK49(*HmVDFLV% z`ni_;iffZo3gPNj9F3)zyV&+f$jrN;*La9+b{5EO;lht5f8gmUctV-2Gtiwl3aM!F zAB$&3Rb*Jnbrnu6HC99EKw)<@sCIjejW8-7)~Io={$V)Pww4Brv;4K4DrN#xqtBPg z+C#7zO@T^7WJNqk)QZK$Mcp__S+ssKE+;{>t;|($nr_3|^%$%($C93$RA6pcL9Rs6 zq={)MTR`chS))h4oqECP8X(WSkYNm`sIft!q0>(3#J)w{E40910#=>o;a@DE!fLNu z`gR=)yPU3Bg{U>++7~k&*UUZn6DVB+US>hU36|2M$(!!S*2jo@yk6+g?3KPr_vzi~ zwb&L;o|%>=M~8lg@}hPf?fhNTtHqq+1^MMh>q#<_U@r;cg~mso&;}gSEVA(BQH(k~ z@m5y*RR*90MLYZ0=(BW;~s<1t{?MXj1@@! zR|UWiu*Z|5v$_2GJV65t>cx$}1{mHSQiY^%eec^*qQk)AYe?A?4T*?TYk_CLJIPeXw<7T>*90)x2i;nes8l*x_c#^J%YD z#s>K=yOxB2)Nch~Ra5G?#eBk#kqP^+pDrlE~a~z;+s+jow3;0Bb ztP=@QD~Roj*5VXP1X>Kh-oPOmhs}&57L-k~qv>VA?NgyZq!O>vYa3eaicsal3vGeo zoKvWydny!B+J3gB%X-`G+D`ioF(6-N5w$wYo^*EF*PeVy21v~v$(^`}*xCNxop$;$ z;Dp6A>wOXRmI$Qn79XXhSIi1)mX|xYifNMW&d3^{GsWz>F{i?2*zaOPo?J1z1s9=d zn|pDkZ98~hg*Ef+nM^A$e8P&gJaXlT|91!`RfS73j6ugk4XR;0YNav#?Uz#BS}s)M z#^lMOM7(vXfEt0)G)ErWCQ$ZZ2-Ym~5|8)Px5g^EcxaJ>aa z0aYl;PNP)*iN#bCobvPAZg&lSF?F+{AS!Y6$;)1ddj8Y>IWJn{_~1B1Ce!(p3)efsAM~+L$%6wfDFOe$ zHXLawXJ{PairP3Z=jQ6~FbCJ1A(Q6PNFQ5ngqqe=a45Bjx`N&49EmD0(`=C~O(b8j z^SadBBJ6XjDzjtBK0>kWq2s8#?%Y;A)f$P}Jv%MA##y9h{$<*w>@3|;0SaYT$I_Fd z=qb@L3lnyl^Q|$Av{6rZIkTqIu0O3rcoY%q1R^Jti%guX6yyb8V+yR5o4lfphsb8j zC>BCpxBI5GO{67e+vxkww@rNy*|1U^XG!vyNxVD)`8O1Pr#nE(BGdW>f!;a@!tE(| z-MU}`hO_86_4Bu=AnnW8UkOIDUJGNZ{MIX}Tq5!$EG*==)M>&#UBHk~Vy*7*2`Zb> zNW0u)d*snYpQKzC+fI8-5pXNdVX0V(oRi=zu(W9%sZ{HYu()c_!(&R-b4dlOgHEEi3mYgkO)rTrZI^C#)?w(R#JdY72xyh_<)zkbHz z>W?Hf^m(^a%re}2$V4;%KBD@yQI?0>>*Ve?$FD&jWW|=vixk7cYoKqrvEJ{4{EM9l zp_%V$C_tq?vjKAD!J>UuzMK@*zxftJCz{H&azkA47>WtD>SNQZocX8iZdHesR<)s} zfIYfc67b`(2tnGi)%pA+;jrj}@j*~5)$$_5P`wL8@9E$M&PBO&&yJaB*@TpTQk9Ad zOd?g>^4@eE=gl|y?ehNzJm8Hz&~1q)h-x?W5yEJ581TJ(u*uCrzr!-i5Of zVgl^)#@kMPksXl=E3;wB_Xd8%5`;;i?w5bhbZ_CHD(*L7t>Eb>J1D|6U;-K9WbIF} zEwrJ$tP6$sZNE{NHl4xR7f(*JIkMjI>}--?|yjZZh8G@h|>@rJH)OeRD}td zNBn**n5FvsPGXY16~K)cp9qQGrDG zIQy_pK|Hi#LkRpzTzB{NsFtAZ+cL5?gkEQCR0UA2aAX4|s4`ubq1J{)&qk ztC&sn)2b?l2E(r#)uWP#)70Y0r?EC~N)-OtS0XqQ?9OS=h@X#%v8~mUYTfGrTM|Q! z^@`c%$O3m}lFNQJO?fCz#Jan2?Ot4WE4Ta(`Urbk#|d(hq{i#0t+rL)rS>L%{_cK- zXp*_>FPkL4hrM2drMhIuMSSSm(lW3IuK7kXSQyIa@D%uEgy^i+n0ygyHe`cfgE(AX$w*~9w6*y`tt^oSHXw! z6y{^^mf*9|^6WN>hxZ_vq$M{Tv1{QKxJ-aZe~Ysl zaL9~H_zU}Ryh}lrP#s{*qLQ6TEN(TPdYkuKtKG|>*X0;Oi*aXvIS7nvE{kjbR8?6y z1k!dEV%y$bicaBS#MtkfP^beQl(^BBLk|W93?l9+v;CG%9YmYQYkv1Ji*;ttov5pq zXC)A1^#8iQIPIOyv{88MS6vB8Z(X`?(s*{r`F6|lme1yc_} zBtQBI?1-0&!jSOZFsU_IEE-p?q<{Ow8Bn(YwgBD{3XKP7c4oU1$@Cd>6`M3B!`S#P zkExBuy*a{8J*61ZgSh!vq>3&IOh;N@!OU7Xtw4&bWYOnP``Q3NcFN#uPcSIm>UpqHI-Jcyekrs8Q@ zoOtb>DrQMQJYeFky$fFurN>H5g2XOPG)B^iueD`$c7ZRvU8KE?#IkKRWp;?HeRgP$ zX~JXz4$=e@ai5psAa}8DT}f$h>Nx9*OxGeY9Z>39)W|kw&Cc&6HENr2_D(A^&s1G+ z+lX^(jJYA#Ma?6pO5_a?(+J`(#gxTV&=hJJqLd^85i7S5y-e8lJ-IK}E$(Ug$69}# z&Jb8EFqzG4oF7c3(Zf9^UQ8VoD-!)u*GxMy#0D}!bMPGEZK zIB?T4WpMYoO?a#7^S#usd3WV;P52OxVX!JTtcyzZO`kD{3FQAH%nT~0L~LQCE~WfN zdqjxtfuZl47mg{kz%-%*5|$zr3tkA>@4WS*(5~8xT=peIO!8t}j~RmnqGI;xrQDhah>od;~S0W_6mXjdGc(DZlM3J)O_*_W>GXC@ z3xh+`$L)Kc1@o zwEam+)nqx&bQBDLRiiGc#WLCB&r2VUv>!! z7rp@tu6P6LH~L-6>#Oe?3Gg1b8yN`f7r{o@Wi5~So7|cIE9M?8Sc+dDGu%dsM+kU=< zpR(}Qqw9|S^=$oEsxlM54v|(B8gu&*uwAkVaWF+|7(cb<32ZjU5Lt>O9|s4*r@*`h zu);|q_+K(&S|FIcY74)a$5|5>BJRPxsM7M}?t3A5r83FXg%&1t{zOvPbk*YtUAM3_ zImbNmw@%&M20m5=Bp5Il=*dJKnjR=Id!@1w%{iU)m!b-aa+fE%C+`#*gk!ONh8~w6 z$322U6X=H*%l~IRq2z(WJbiz@3b-RJi7#PWlqqwKUQ*@Wixb(FkH3bOK4O0DGY?1MyNDjgegrZ;|50IfPsuzu{%1*eTvO1Zr&?{1@U~?ceY=vP`i=ERo7u zFTecdYnR5e0tlp9bquwosf3XEqa&*`5S30!u=Kw0&1v7aZTeNb$^nZY zd#Qv$@gs}(CyEc?@F$aamgn&;dj!X#O)r?a z`XJ@xw-)U4tz5gmSO9d5;P81L`S9=MfAE~IM+SXgV_SCFrDkb#;@Dk3gF1m0MVK%i=Utc|>U4Do^Axxiy16rQ8u zYhI&YFJ$%_IQDV$emm6(^)nuubm@gc@$tbZ%idrne>BzLV(ze6z>ogT@qmC2;I*^_ z)X!MGaj@3+ge8UA&o0Ow%M;uexpH4EW6yG+&5f`JTa#Oe45lS?4N;w3DF z7jFc#(44P+zCRI!gh7%4dubO`kBlDX2+TR5as_1uRmxwBP+Jj5i5EkryF_Fa#I0RTgP>Y}S*~0gcRIhUv z5n~T9ZnnHQh`gwrYSE<#fOvG_UoS6rWOMwy#rP${GYCp!TY=k)VZgev+iqj&gJijo z@x#L$Z|Yx|yzo^?@f{!OF2(CeIEcvF)K?Z#bUazFJI$InveSPj=n!g@bs@qcO?7k z!8hBTpV!xR$)e&AQ; zC2e>c-<)O>ylrZoc*zk+gcXQUtk>iUaG+**b5=f%o&nP4L#BU@*qguM+Kv&mrL85_2AP3-z2^5Q}sdL!6aJo|jl z4a&7)-nhEN!OI(ezs31fC9--)`5W3!zbi*CfydiEGsOFO8RRe`t$;y~ra8hjLEQc+$`hYb!5qY6ISrFI$ZP6k!b{^Ll z-ZWLr&H6*MAs=J*w0?q4UF?+Xmqsa(EBclNKj}rS@FE5mZn^!&T4YiWP<0|gLFX8-OyP4zXpsH}x^Zn9< zUkrW?%iU`TddN}s7U4@75WzZDJ|^T_wY)tM7_8;HA+X0q~_p^6Jo%~Q-kX^U7@(bq^Of4t(o*g zAa`FV?G>r$M-Kb&eP2bG0*L7#!a{t1$qe0@->Pn4vv3vFkA*5E!*QGDO)(H5z{PoC z7}5Jlj=J0e)c>aR%>+%h^eX2rc}d$Gddkvljvsq>*;8|ozjAgk(Z$OD>0kc-WfA)a zJ@S8^4g+!*$B5pUM~FEesStoRT9;`zwgXN@6>QJHo150agk)=FDzVrE{#`Z)4;aFiP<@Xt z>O|2V!wB^28~~CN&V_PUl^8FywJ2G&MFM)we2G>vI{DQLB2mLsW_T&>O&-aTJ<=wc zPYfLSAsf_1^XBK+9lkmoCd~bn&dCQU=hOZlo?YT%1RJJ*3&-zs@avy49Kdx@zdmo9 zWdv-ucL#{j{vjX13_gIa$XF3K3?K@(^FFX}86&I#t?Q90PLji0(?@}9hC3~kH$kLc zdr>d@5m71E8@e40`Z!#Ofx;`3U!D44!lyj91w*B`0=2fjoNv2$Kz%qGbm^BRzaA=RfA`gX1sE0a#vgLE;m9RB_@{`c*Zot(Uz;&rX_7*Tai=|r zSw$Jwr#uim3R}6hHb>MsxPpW7Pv~7E90s=V>?xbkgJ7}hQ0;B4$MLsN1u^hs=fe>G z?_cWg&*G4TqlbKRSCO2Cr;qk4u0LN8N;pyuuh(pwlidebDVlTD|K! zV#xq=ACrC~%gHp=XnF~%sC;~?YvXp;iZ1Zi225|5-rSi=bgWp*3CGvB z+0QgULc_ZqqW6Rpg&aXXRByuUsRHAA>1(bbY4r$F zizMI-kxGu5BfigF5@mR6VETE24dW0{dU5~1x)rcD&FY?{A4>!cq;!nb)L6KiVig`j2&*~QXZ$fl>o z<8h_Y-5Qqvjh#a(|2qr<5+%hOD8gqKr6^3Tu0%Z;J5+)2l`Tv+fq@c5f9+|%fd>pa z&flzbfskrV)rspDXU*yUglqf05BKpi;2V8_CHH+dWGz6PpR1IxSKsDnBrfZ_?XnQP zYDf8LJ|7O)2}(PzAV-F2(7$BFYJ>oC={B8~^>^Tdq|g)Dzgnnwd_>#)?+_X?;t2q2 z5I-b^vUTaTE)z*kG6X`kZ#Xj9-YxioVsk;#l#x6iBs=q|G1uGNb5lU9ISnTHc2iOg zGFaf?6Yg&X?Arom=#^{6B8UJsfwINj^c|*!Jdx#EKnZ?1E&(>=IZ$4C=FfwJxMxMJms%$XNGtWLTI!vmVbS*z|*inqlAfiDl`5SmZ6fA?Viv}s`n?tHCRSQ z^R*$2vrA<(nz7|_Z`_Qc!S{Wj=SN&cgf!{G7RnsOJqM$SEvI+iN+B`1N76ek-GFDn z5TV3LV%0Y-Zqt!+{UVdiX?-78mD&p||9Kw@T?w&?s@FGR2|nw{7u*UU$2f$uW^z99 zlw=G73%HSAHpjG-_h92w1&5t(CoLxNdwS*p+%OUYRet>k^nbRxQXYsB#S&$^!_fJj zSNi|70++b6+xU^TMx*!AF!JASp9q4nqY;7cc9Fy`)R|KLc-w(AO~lb!4aSQwaO`lF zFn=8={7C2rN*tUgsGQUv7?Sp2a6>TckHEK-T$pvhK%*2T42uj($FwJTdCgL04P;^p z(dX!XCoaF239_Mlli!+~Y3}J3ob-0^MpHRp+UZQa0ss9H6bTW{l!&c}>r_+qY6t5} zux8u@yGjN#>nRfLgGb1sxAwt;rwSCoAE2r+w!ZBfB|=M!vU&qcu$j#!!&MD&sf-?v zUu^xpcxuqZ5`-a9eWL&fZ$5kVqjQK=y{+#(5euwO8_@>`S;&JI$OqY{s)bzrretQe zIE#>@DPa4c{xaA9k*_NeJ<>8y;~y-TSIK@zT)58hjv@$gIEM+6wFc%3Sq+1}-EBvz z0c&u5?W@kj%TaW+PbFBTx) zr$yx#wgjO`rNFF-D9ryr7nhWjr1DDrZJT3oI5Jj0RS%?1|J&VGfuQM^HQB#@@=KPF{9Wr!7Pb||`MBD%lM{l?x!AccJX>vAEA z*1P-n8vGBb8b)Jom@X0VnHWF+?+_(gQ=%sm&nSV!P8^?)c|O|G9$yKeE0% zoa(>-A5lm4$QBNwvO`wLNJXKfV-&}hk&z<1Y%&K6CIl1GRhXyc(L3y9KHI z2zCOno!K3R2RnGGG#W125D+>KwF$%;CdLHr2*RR{@@;z)qgd{cKYW`vRxs(c(|^w- zeWwWp#GgiGLMoN?BsFsVl}OV2vaBk|6B-#BuVO1Zufd}sA5?v2+&y9`u`}>OB?bj; z9d{<~9d6^i&GMw)b|;RlLRlNIi?xNz*QOo>mlR6=Q-`Ta*Dj5Xf<g+VRWMnamV?QOwCgAKrl z{60P}|3jno5fkQ$1jMox9sdM%7I<6M{>zq0j!pc(kh?t9W98c9KWqYp&aeRR*Okoq@;QIL+iyQb24|k;$ z((qvoqQ1lNLOJ-=k~I{+|MwmrtpTU}OPUY=u6-dE_E^#vFN=rz(+Ch0uB77flOOe5>*gy&4Ey@3J=XIqK#hx@#vWrj7Hpx6MmVGB zPy*p3#N;IlPYcpQbn(6q3=RJ`PgVWsxWh=Mjs$cd;Yel@LAY|HQS_e`Fkw~IDu2bs z)7!w{b=i#(>h_JqsIA#XlrS_o z16&5-sT5r3gd+Cu-vGA=zq!HLqaq$EE6sGMhKxx|Qii#Kapw`D7=G$K2VBq!ke_HU;oJse_sJsh-%o#+S zSiru0MBIl-&eE*wU_oa#QKL2CErpTEwd}jF?@NQOyYHmDAaq349TZVNJ^jz!CfR%J z2_nkzdmVQljCqD-p1p+HfbeKnci70$p^dP#Slwsas!Pz60u2g?qkeg4{r}7NC10_V z7PBe-GDmm>r!?jb)&YRlGMhO z?lGf`)2Y=<#`0moxxzpWsb(E=)yOowszl8GWrxu`+NAJG}YC~cK zB_4}=y~RR;Yo9u2G$l^u3%B~feeeDCih2)HUP@?wccWEI^F$_r_t5=wN7 z)3MM8Ha4$f^r)2Kr2+7Sw#7mU4P7uhEv91bMSg3RPe%~9SYN$ts~|% zO-o=cG^&xSXUNY(Yos;MI-8d((UFWtFgGGN+XaJT=319DcqJl{FmY|nKb7vF7RVm^ z_s^n+1}sS*u79;sDIO44!}xJkU>9)4ri7i1c~-r+7u<;*&$Z~fZ9o0QNV7xro{aw3 zNor&A9$gC<;9mE)*^*G_Tty-)XUD-A;7DqM2~hU@ zT58Y5i~kx#0q1gu@z8|&#A(;GW!^$5CHUJe6A&Vitah+dS|`!gGXWv-_Xo5u<$|NHWRZfP1^nw85}~-*&!Kz1Fov3sfW6#sX>Uo54rK&LE&ZF^XA%oo7EeXD5frz<5akSxuW(qn&T3 z22RP-f&dsgJjOXNgO_Bm;*ON1~72vzGcxR2zN z77MXTdcgqFt1_pc09#K7EK z@~bj1Q;+;C^DI1-0~ij)ncor(384bnilO!NmpvG!nN*uKjle|iWie@)>e2)cxb zvcRgzr27;h*uRLhUDG1{7Zxx?rxkYeeoGQIJjZZ9TG(V9>N>TcmW}XyS8z)~gNS$Y z*;k}nmUQ_ia?wK>(3P)KZ!Rn~WoZ9G@C*MT*y4+} z2JbE-Ny12-9cd;Fhsh;ZNFMWg(z*bFdDx?oiyu^7u*yFM!G~bb0lYno> zqgKKG%|L1*{jvVd8+Uj$&@{5ohL8&eiOIIIzo-!xaR@)XtgK)EyrYJ5-eh8e=0SK5 zGAB#I&B@n>L^I2__1JTm{DxZv2habzEv5yirbF(GfbX-9nOXRsIaVWH#aUPW#Oa-{ zqIGh&qzl-$(I&89fl;LkRH5x?z@)tz_dzbzZ`Vm54JU`HYi6WbOSs_1kG zOp_giK)65p(!`sj(Y?);qV4+FX<^fb6leDR0rO@ioc}GlaAM9v@zvU1!!yp5cXg75 zKjvT?Dns%+k-iQnmm8b|k(USqjsMKbdaoMZYq7-Hf4A~sZMbEClfskfpAk>5ZNggr z6S3JN!uU>rHoK+Al0x?ymiN9EY2_a{{KDVY9Guy~m~8;PKe_MG{7^oH8K%duxthZR z^IcEv{DTi{0EF!!3%bJjEF>4)x0uEiWQ7?g_CX8Z;7aIo%BT3$eg9{LLPykr1lKtw z5jg2hQIg1Z$`dcO2+qM|Fqd~f*oT2fxTt2~m_#3;S0spHc=Q|ELsk5cGn+!$C$2*y zIJO+bl40HXz)W=F&=H7;{5N>1Tsf@UQyw_fW6 zOBEh5D9v&mIL>NIEl8^>MXT0EN9PLX5mNnDjEIU>^scg6Ce2;WeV#@?c7BdeZE8QY z3guo$jwzUjsfX!K^dV@t)lnNo$B~u@{JmI(w^TBJ(l7#{74V8Jh7+s1G3r>7(%^s* zUWb7T^Z`iXUx|N)b(dXJnA@3rc7XSvUK@I8Uz53HDbMyh{r{38w6bbB&84A8Ry)_+7sAW@<35Q4KPTFET_ehqE12&u;}QH?)2E_^oJd$~DgY5|M4ne#O9T zNtdntEgF2Wu_J(5?X&W@hw?qUVh{|XJMm+EEWqWvD2RL_66{|$s&E<^+bKiH4Bapo7sU$>3NGsBoha5)aBXuaON~#kbWX9UY*izv zPfAT5JI#!nv5=KF!Pd^_dDi;D)P0tX^b%ZpptWnbn3o0K!vI}+vu1arIdGDFCuY8^^1guRh{Ehg$SQ`Z^MOw-vV^Og2dp_2HSoZP;}J&F_}SNwQ5=tpg=VdJeu1bG!FB8)qwVHG zJWE~O5*&U~5c`O|IhP6GzKLp4wvZcBG*0eWm6f+U3R}#2?q@lWs5jzB- z!u9~_+-Kv9V6N*cttd<~-12NSoQ6Eh#3x0F`GDsKCCLZ*3$fz}@B10RFmAFKOo<7? z0CTI~L6RP@>%H$b7oh8pI~{H9X($v|%BGAd-vKe*#AJuBsHJSL#)U@56%8&QW9YOD zzl!?)ZZ2UZZusurY=cU)~y&It?YE zgjKwDFk$5Ze{K*g7HjC#`lq)qxP_dMxCW&iZ?pWlXb#K)5vsbbo`#u~Y*er)rY6H! zO!DMK6%*yzD-K3i&C8sG*X`bpCVNtDm(x%5EA8eyq6k`=bf*ZSoz-k4H5N^rJ+7p4 zjum!Lc8{g65}&W0?B<+bW5rbpG%SrdeI9;Tc_Ps0K5F*&uXAK!kVAQDVmo!s7HrqU zMNk0f-^#6ka}!W$-_*Ysic8j3WBEfhfDLy~!II4|Y)g5su&WzMZdVK(P6>N2Yr9n* z{J3^FqHa0OOli|3e}Hhbp#AJRQt|fD0Q)#=RoJHk&r=g;ZM}ySjcUPPRgw0FS)dD) zUS--+LGRsP+ z;ykUf(=+!hftLOSruXLmcY0`DBKq+DK1y!A?{@H8q~n`9UyM-~s1^zvL(K2%!s1OV zvk+ICn9avt8$vDIQ@`brR~z8gbAX6=5Rh0!JYxW2ta!(J2peLNfM$a zhsOg(lk=Z5>;T^S*vMcYKs(J9-;|+S%Dq)D+O8tbp^~n#4FdF8|A1d<4^aTHUl5k%!;H< zB&zfC0;iIi#}tX)u(CY_j4NxgpRuS8@n@wwqk+n7|BH_&Bb&>0KWmrm?;P}){_}UG zU7KYVEdkA`^I-(0xJyCO_D(AunD$MZeD?$fYzL5M;x%)u9bE+Qz(vTo`A$RIAcv?fZjX&Z72 z%GHIxh<6L7WV#)&$Ue4RGi+Z}@S3=xm%ZkGtEo70SIATv#GQ}V5eo(~4>FUTmmay= ze4!71iB)&=SDt;F12qQ{v{ssw7JInm<_zu{y7rc!Po5ZLFWpC$E3c;Of&k=NQ4{5A zoaE@)F6u6^#3e5N0$G$b%A!619XoX!4UpDtl!!Gn5PQo4M)OwX&B4lcFpyy)r*e!d zNks^|dwO2-$1;)zqexWJN=UQ4OwrF;l}XK9ME-Z(@}xCRnE<{*Q~dOK%MN#5^eT!| zUs>ZZB;&9cS)cTOQ1!bC23Q#ZUcsC7GP+Og)9Q(e=O&+!=`z><0wANpf1Ye}Of9~N z?2cc(-(X>(3I_{Zc1EFtJ^h^_rx+o9uk^}&KOYn~O+mmsmK<8RnngY&r*2>J%MaqN zPew`ezjEWdUmLh9wtemSojmZ-Tqt^N8Z!E|s#J6CDoLT1nyk_opPk~P7cK_)>mO5+ zJ`{63gGS>#cF;x5@6<^Lx!{pr&C(T!aGQ33i0bOccp2xZnF)z|%%)+D-$YVuCcx^& zaOKpL+EQY9Qx&ufnhTP3w?P-1F$~5Dh;;3Gpt1k9jmjG)*B~_O8kKHVkq+v_sOqS< z%H5!XDo!#{a-)9bpfc#~+?tGPk2lqpIT^jJDfml$Mqe;Vxis@f9>b84`hbs#^f@C( zV(LEt7Pe|z;FHFLn^&!Lj7bj6^!Hc_LlW|H+8p#4)~0z*Gs(<{IWvc?kwK# zFU`iH}5bMoknppEUeNMl_ejkxNfEOsg>TtH7E4 zf^aFB3Ab9y@y(ww$j&`y{so-Ng>bdG_KepEDggX0mzLvK+h37d%17wgb>jFxR5^bk z?r_b4q3L@fhdQYSf!O=WpD-DXwtUK^YTr*LptH`MrVMLA>BA-92UjIU4zw_3bIr2xEPl=>*P0>Bf6=+855H4&(?x`ov{UE~Rh{UdBo;-2 zR`redUt7NZ)sb#^kKsA#UqBx&)mgb=qDrhc=w}VkZotgu$+e+}gSoF`&IuV>rTY(& z@=4#P$tZu=7|kT`=`@7sH>vNO6}^3cu2PNvS|rVTrltl(cvEg!#lRxLoR+!p{&fS| zsLRH%c1Er1%WwY8ETU`+-B$Yfd-dY;&^zOx?@GIOmj+AkOliW)5?YJ(Me#rh^n(cx zstILTOwm0- zk^w@0)omGirL0mL1!SnLgt18%E32oMtqosuXSJ($WilCbNYb-vxnNgriAhmIT%_tX z1Lgv%ZJovP})|DO7w0+ll@7p`zs>McO>kh;sOlLF1ar6xg{kU;#WBh&J^ zja3t3UI*(`qn~1b)sJc6kQOOz4R0`G9lo&Rkx++^l{2*A`psTsdifX-%xg5I> z+w(iFI{pndfIis;J?|-NArpfCcb+}eJk8~RDAattgQ%AZo3+gl#uh>5KaW@3Kd3p} zJQR54Z<5<7gCCl*E=4hk=wfTA3%I+S@+S_sf8Z-fSLH!|)!$taXic{4?5%DT*VAms zHML#ZbwirZlPT`g?`H~MzV}E++Z)J_=|AumG(5I~eJei2U0Xs<^EkwN-7_TD2&>rU$?*|dr~b9eFP1T z3egBx;Wr@~W@4rsuu~luwLo%UyIdDE#4{Qc^WK+l06oCZb7*CiYw@C0itJvh0;Oh zCn#9xue2(})WU*l1IWN$-#2D{x7H50INnOuEPImzM5(HYFUjM&9!=pV#61CL2tmRtY zzTou5OwCHst@<4bTNwMNK0Q=~*XVp9w%TLQ+L6UsaV+#!oAE+K-2Ry5Z)=5BUr?uU zUOV-1C+B3*h0yN$*f?dwt8TzJzeC0r*G!7@T6BCj!}ewrJj_Ey$pv+!<3`mF9_h`9 zIDbXVgy_W4&sBe@xQnVc@Ct{6N|#$bCx9ZTQ07ZpM?Hy8qegx^L$B$36$=3~v7jMQW}|I#%$rn~OW$Hm=SOG2C)@uT z>kzKYe^p?P2TzCI5D|LKVak-wv<=3#qEc!ZgAt{1=3f1Zxc(k#9h5?9dF;^W-~a*c zjiC?@6Qoe-#cAQ(rHU>=W;;a4qnzFB@-BYIHDH|WH<=m6+0ya3b4}dnJ53H#+Y(Q6 z&QTefuL$sT#jW&b|nYyEF7O=vU zDyx6k?n|h?(giR}InQ~f^nb7bfJdiam8FTJXoM>#U#gr=c{kSNDT%xs8EPX2viNaB zIlPNmW2(Edpxl!t3VTi}Tp5$lc-6+Q@sHGGE*=%!PXK@_f#46pn{}9Q){8=v?=E?4 z$2?KP?nSAcwibvdn<(CPlf>_B?iNuV02aD!EE|W6UVO5ygDo`E8~^l6p_Au*skGoEh$pEan+RKE+}plXNX<3>s5XO zt6?ud`}>s)B6AS^+RC@MLesKh63D2DiM&B(=2q1Bj!6CC`|DQxM1PL}=6}zoik;N1 zfWp(-oyDs^ZeULLLHXX6Y}dpzw>6)%%_wpsroIbtK%v3W7-r-hqjN;5hRgiTmI{x1 zkD)>?!wD(3VmjCPvVkzhIe8KWETf(o4TnH$W1@*wCC##cb4kKU_DfGoyJHu%}oz5(W^rQr!nX)4V|Gh!iFwH$CU9T=o3_uy(vb$DDq+S zI+r*Rv#hQoCE;_GN3axULGt)PY!$m7n>F@$#?9%>dL=0fB)eDYBn`^|kGv7PTL1HR z4U*+IQoN~f-ua!NqG|uEVhkc^RemzMSh|+9fnR7R{kr}3R^o&xcf}$ zUyC2)7uWBX#`)99Wtv3#uJB*fs4uC5iOCjoPF3y+ygd3`NR`sMj?o!1`jsNH`Ci8H zx)*M12tnxpC*tji5v{At@`5-{53b%oM;hu_v~gD0TGOiBW|o8PwfehKy^D)M!jC50 zUQY;jFjkLJPAp%zKis@r;?nQT=W=lBL2VPYe5*y1jTsEbLXyB|_a|>?OZbdoy1^*;UKjbiw)} z*xp30ABfRiJ(L>X3UE)z(RM_CqbFAKor9spc#67ZCAbv{pp7q#RxCeD$?bCM2naGh zM|h;c(pn^@W_@FHW%Z?)#|*}n!)<%(n=%z|F?W3DMzMt8P35GZ?;lhMRgaR`)eW+h z`o4y`7_p&~znz;w*egtX+xnn(s!_h4zVU4#M=o2Mrll2D1=b8Tm6EOc7ey9b{9($5 z$YNM#YjTIUq=Sl*U8b+luPw=uf28r*>E&vQAaR=Qs{*sZW=|^bbNZ0p=9HXPm%thp zd4;#a^22IcXX#JlA}ajyz1;Lo>IDB?>J}D<*Y0)P-3Z>BS8r`PF|LCP|^8EIawP|HYC!t9w+pyvNe4cB0u!o%+j#- zWDAY!$Cy%>E(b@nPoquDFV`da=`;S<23H(}@%M%hckm=GRw#^*Jr)CUiKVJl<7-bL zZL8R0_OffR!#WT;5jkgsae0n@2{G-6_KsEQw$W)EZNs($mr$&DWvaj1)AhgRL8$tQ zTl-dts$kEkIA^7=~{J#4uDan*z1WvA64$x-wI?+TUEyp$+wCpLCf1#52k2P7x z;1IqY$!61XN8Br4M72Ya=`)@{0aLfI4&6EA{n4p0`a$OP-(O+0jU~)(NR(b-t*>8) z{GF6Cm!ONi3Vrcm;L+CTmvi})X_5HiY9$1K+fylIG{`n_MW7yC^&!3g@Nz8U<#fdj zM4h?jr~kIj^(?)9WQ?LD9WOHY{@+Rta;V=WeMqfZ#@N);)~?WXfa+zmC2Q2;pIlS9 zNjYgl^4O{8*&z@vy8+*eM7ZZs^%zN|wCM?IoLJm+{rAU3A$}yP5ZZTlcTwlQiXv3sa8xku_ z8QNx<;`Wy6%DB8=!W4B{v%h5a3CClrIoM662@pN;$(*R$GT9IN4hw@FmE4lgJdlb3 zB$KwWYBc(jrX=O@<)BL<3${ho*1O>}>hj?2uQ4vVp7BzK(pZlXd!&Ux+8;#u*o0hL zzDp4MOs>vQ{|rPw;V=p@AlvNGmkm5QrDrq0*kPlXJ|~u?CeUv3;_~z3Q-WgaQ=D2; zEX?wZ+nyu56lmS*AAcrJI#yn!gwkazOSNrC43sD>|E0aNCjXa9Vd~AMKQ@I!EY;jXbp<$M0 z1}H|pj@}68h}E$Um|Qs z$r7pMoxGMj9)Vm)jSN*+iqTiKVo8zpQrP|xcdem~QK&M4%Zi76U27D$vgwj$Au>Wt zEw!5266cVr2Ft?u(^e(Ep{wk+ea)Ac&M#s0_fUbd#ixU};>y42_LLN1GHLtG-9{P< zX|68 z7Wn!BEotH3RE{aEs73~7BE`g{FbAPZo5Lor$qj;O#0QudLm-@%P$&Z|_YDTK*X#UR zH840P2KdPQlUEEjWNI#Y<>;N4?A>)R0-JfRP@&P^sS9-jFF)0XKCWH@72#dpHa$p7 zvqSpO8))K1u+Oq;sIRaxv2NUbIwAK7429P}oUyYmeN*>WU=`x&EIJUfITzX$ejX-8X>~G+*&ZNI{$kEH{G)wFAu<{)j2FYU*b0 zf$24*U$g|s{);yw0^Rlb=Xk=8G{B`yaVsJYO6&rUYcnod2fvdSP~pCBDN4I+TS}EP z7c`Bs9Ky)ey7VrZ(zJnt8T8X?O3Ha%`)Q>jPm^xfFw= zG4IGbbVuU{q1CNwv3Tx3{;wj=H%wK&E+Sh+N`kL&K=sx>M8Sp}F*+tp_^#qKBQjhv zDbqD0=1O%5G zL6vQbS(unoh#jxHk9OEswJQJlG-?9{gv2+3U6rU*j_n)FE?QOsY4Nlxmrc_ z4c*D)tGE9E{l2JFBCfMj>QZ9jms<6wDdQB8o!4jh*ea? zn@!3Z*f4P_k6u|R`udh;brY2gxU8&UOt;BqU6Q-c=AW=WUx-Om@t8MU9zf%hu+iLt zXg%w!n2cFAPu0EX_Hp!#%uq#_)4`+Yx6B(@K}yFVC@h~?s3XbbcT`D`o0<4{VIgZq z^3k-k4tYP|A(r=#gcaA$%m~Sb zeC#%;*+0&M-FLaHV{tX#xl3xZr{6^H&r7>*+5zPhVGrgCkbYzfLV}X(1^a(#Bn9n$ z1Wb@g&S>;GLUWdZm7Wu{hKP))X7$F>zD+5;b3f&US{M_yP`KQ7gl>tPeY*Jvo#|<) zGqz;=^ISM^m)z*?(%6H~GaHYZoGr_ChZEKv7yKqta|DxmZLyy;nx%EqE4#KHv3-OZ z>HwL(~&118E({^3-2eUCmx}7ibERM2EIJ{%xeFT3HlJE|lp&Q;KRD11h?VLc@bA z(!8uvpe6QH-buv!|DP}4w`Xec=X?7zsGYd}I0<=cGYRt+MF!PM>^srdVkACKC)&u+ zOTEdfeOYjeHRIzqmN{?+(s;JTGJb8e2hXIl-s@1#=*ldUpS{}hZCQIx67ipaxNzO3 zu*9z@gi{-Fiq+FPp83kzKR_L8MyHMLnU1I2_0O6RF(mXhOd;Gy+lFDuNqKXpT^(4{meK zFABJDfS5c)3VZxxyCClf*0AY>ce#R{kM?wT?3<{k*PZ_X(xCbd50*|f_Y-D!~PUD3cNt!kS)GQawEPPk5y0p-GT z(D}|JH_FsbLZf|Lg2~S@Ypb&0P3kHGY{be-2G=Var#t&n0E!bR-(QcX(v}=(^cd>8 z&;kZoDrGa)w|Hr3@(bZJ&K!cuGWX*7UVDSIgh41g0jdJ>m{Z@CENfSx#LxNO1ewRV zo9pVx`SABOK`Pf}5!MZ&_ToJPiiyP52=fq#QEQ-%{{>#`rjQk<&D5B;8nk{>E8MbQ zo=FS?15CWLK09FVBAmK&wpwM1-gk%_nU3_%_|8E}mAwFgE1ay(l8G^sh_189DLME= z?yw;eHV*h2{2qyrukIY1PK?Y@#%GTIXOw!O@f!qKB_3Wz(RBni7C{$vfvC=HsG&V-R z(mbv56~oZQm)A3?M$lf2bWb%{VZ#w`y3D5lKLBJ0>b{i9;kCHF2t6FqxAFdR{}^>z zR$kUhM+xwE(-Ou(0==7^OWWktd6MU;a!v){&{(_VX2fB{*r) zQ5wBkU$iZe+azs>m?c*pyaEw-z51Y=r_g@-7yIe*-OWXg;6@K5{w3#^O2X*fkapsH zm69xK0f9w;#^YMPLENqeIS=|2;vcT%i6Aa^5jTGD;h%*JwlS?xn0&-&Ytg611H)w1 z!weyEAj97WvuQf=CUbnt&tgZ_Qf)?kuo*916ku?jx$QMiWa}qAG1X-*zhZ=@#LmAm z{gC;x&P}^#x$etwEYI1y2HT__pePSmuPK}?EkqCBwe~(^(-`xC&gKDTJzrUoA5as+h5pJSch}W;FCkuV`Ln zG6XXPWL1bjxCvo`u-d6}P3c~_saW1qHRU_pKB7Tg57rTtMD`~T?Fabe_s!CvQ%fZV zp%VdJJpDRb3sM6)bB#=2NDO_ULt@bo;d#;Z;Lo7TN(|^vz-xUHZ1j^Y*F|mj9S~{3Z7djfN?@tE0U|JxSL@)b->HR^|c}hN(X}UE23P zTs%Z$E zp9oYRC!tsAJCfom0>Jf-pHRQ?*OutRe^qp;q+JI$I#(_#XJYDN2FZr`P$BUyqIn`a ztn+~Edmlu|8>Om{YgJ?{J)GKph!{46_dP$E7{%}GjZE>*LFC!g^Qh00FV*#>1p`(6 zCAU*yqbb}-oMA$TJHp*^mptc@N9>P@`djR)vWSn2%VDBoW!I_Fqf3^abn1G+ewivk zH?i(9oAf(DqT-3?<`f=4rz74J>cGHLwxEFzm}(Kp zXHwW)vPH|~*Cf@Cttw$okl8|hpBFfEvpwN49?MViVo-9J+xA24xZYeFyJfg@!S+Yt z9~-i2wviLYirj)s8@psK$b%4B!2f7|sO(#Yj0P1qL%mCUc8ILaSY=7buleW?QU#)I zG4hLD5c4$gsc!LdxZ{E^NVXrha0N0g{_fp09(C<9Ww^T|V!!i4mC2}M{p4)3ZS>5? z7+w8V_mWR+17jt8o;Noy+E~mZMlezYH)#;bra?yv6K2u*LYJjLJAU3{24tWG%bW%a z9IDlO`Ytr&t6JgTgP|T!zWia84&lXxNRR#f$2@92Og6%CllBd_d@-9T1U1N=A#?a znbcZO`*r#2U!0(O4{{P)9urWk?2em;$MqwZUNQ_tO=MdyS>F*s6;upq3cFnpMP|e8 z!(0%h2NYIj%FX=*JKei!E4D!CWVkUebf-J%`A#LWdUY|;;K3~#pRMj&hvNJp4QcIR zHYWzCQ&}&wG#`jIvzcyrdQ|?>{}dPd`C+I2eV7oc4-ec;i>^!A%aw2ukxhiGb6+)G z-QG5Iugo_Jnsk+1GJkiEoEZBHsSdoc7*gkPz^*MwW`}g=Ox(kkayN5S2h@J);8PX| z&2s1H8olxMO~*ftg{~(UWMSFR?pHN{Yao4@{PbP1!RK1vq%RH*#2?P?SH9Y%ZB|o* zf#4P3tfNq&QSkT#ZOu=_eDE5|LBd9#d35_uB=3p_>k+8QdDY|<)}5Tsohgy}y4ZXV zE~LE7SpsV@yFE(M)VvDG<=2w8heUwCVw&F3KC8Zly>#St`!7j>N}3Sq5-Bl|1rs#w zluRO=VGmpn{YdFDG_#hpPCt&t9f-Di!6$x@<6tS!;cnv|@G~VE{hBn7baQ(iFd80P z2gw3cuHaU4L?~3nd{Vo9taDePMW_`0?Ajo0oiQNwV%1^^UgaA2%Y`kBly$DvrCO9<*>EC=J<0G9 zq|nSm?vPkM^lLNAIZR3m2%O_cH;%6!*;~7dOa9I*;Y9}@;P;4Qe)1mIVndy3j664v zW@Pc#+FeEXq+$J2yrJG*%wL!e;Ylwv6l}>374C2>2){iL@vh(cPD7K;jhr0a#_x|< zdo6n+jV8`mz_m0dGIsy5TQ$_Hcw3pr*_VWbotOe^YrOHDk1#U}X>%xa1(Gwr47#26 zhzLBy>dY_*f0YS)Wkh`LvLeyob*=d%u{$~cGdqZ%_r2Bl2DWjyuer6KSq5cY@*@|p z-Egcloc`F;&*lyk$GuOFT4N;eUh?c=oOOI=`PpE)KQR^SOF+aDo>iEwl!w?gETRfK z<9xF!kc6n7e&78A4I$wlZr#Zc(D5LZAme;)o^Em0cI-ZwQC0h0Jf9MCgK#Je(r?jn zHw?T52F86dSYy<#5L>0Agd+q3Vk)3og*Ww$>btR>+RxN})>tk9ljfaY4|4JtuH5aw ztrtZ5Gk3+{@9V4MwL}YT-Xl|mqTDv9lAE`RqV>CWO?Gztw@QAj$_YZR&v5fZljX88 zmO;HZ=?SPa>|%8+5E**Ww=p20I}-zJ#2EDJiKi<1OB`%L122+d&d;j;T7X<1AU@Jq z7kA(xXs7P{m5wV&bduveH~R)898VtK+RV8xNXE2X+(OEi6j`z`Rv-8iJP|Z{pRTn0 zz2M-*ZL&UQE7ZSNGT+V+@n;>v^wj4@K=0(=?u%=E10zTY8)Rboe z(k)oi0}yqQucBb+B6a%+NckOw_56cf1|e8oJluu>2mdu&8{PZ}7SxR%bzxOqOHV_I zd#7{tR2ln&<6j8^ttd`}%EGe8qR*FbQEa!X!n^MjrStEEhEwP?lYg!YW1=bQS1Yuq z+P#7ZJ&sYI<04-gGZb=uXkFwPc=y3SSOCqlcEfF_c{ToBs2S&d8Dl~rs2xcpO4vko zK0>~(vQBX51|$(YhIT(@T`o^)Bx(fvJ%n*cKA(F)+7iWDFOJDjrlxC(8OPIAVu*i% z1(I9c5o47CGt*hsbBj7ehRR9mA@nCtS>F^qm-$?E3Z$Xmo^CGKG07-?Q!#woFayHu z^tCe2!KZ1Qy zlp%6kY>TBHjJi|L&7IxkpMtBM?&!IBQecZUpQ=(@?Fesi1!+kcf(}47gfDS@;fTK5 z0{PFrKVB)l@a$ofliIc(f%b7>1w2i3FPL#By}^t(j~EHT8g_mp;zTHJ8{=_N#J#P1@l6Ik@rGuK~WP+fK_ZXSjxUEyXC+KE7ka& zoyIq=Kjf^O@L0WA*-DtCRA&LpdTvL6;-qkh4{@<7_V!VA!+#Jj{wSZ~yI|mc+xsli z#HhFc$%OzBj&%1LtP&R=&ZePKTxS-^eyj4CoaYegpHlq;KQFljkxLjzH*yEpy%vuw zw-2a@G<~nd24dz?E)|L+{a{o~g-AZPg1O%=lFr_szUE+*?iJn*ib~0IRO$vue21R| zN|;PgedZ^fq6f{%x7VV|Ev_0C{RHOR#Iz|)v}qOqf(XA7M1Cfkk4->b0vmIqNSnw_ z?eN*-=+x^1lvl;ei3n9hKwTt|Z5F0SAI*hp82)SzUcsLbm`g62gbVnw0`@^s1{==t z)#aGS)|z=BiPsRB;}_k=Vi`o>%mn=uXJ=0fYp<3qQbf}Bf2h*@0q?UQ{Y$6RF|zos zDdFSx1K$K_N)-gRa{8QwV*Q}SXG}$XXlN+cF!Uw=ES$1%86^SpiR7NE4Y=I7<3=WGp!f9u&E%KViRO~nOWojid+p`jR1f946c*#80jDxV|TvhUWc(02pERzdY(ZselQabhD(j3CI|}| zTsdPYymeLxf{e=y(@tlzGQ% z<4KoZlIarOQ1#&$z`TQ^y9>5~?2knl)N>J6B=oTSgvBa#Aao=vR=*8%x$8|AVhx&j zrCBvB`zP&rhGz6i&p=|x2burmSpVB+oI~u|dS6KNEYWk=OmIoN_sD%*zO9jU*a}cz z@Y~%IaF%AcY-)$nzJigAeV(-YC3&n`f7O&Ze4An#-Tp;eXew^V(ofoY)*^@uQbQM> zg+A_Lc6LW>=&L4Ysg51*qf>kQTMv2$>D-G>ZvxwXW;}$#xRFv+ExyM4@Bm_13Pk=s zsqrA8iHDKd4yoXn#M+-Ggxxua0FMLU&yGz~{6~ zRg;Ql-oC!FsPa30F@QwoM~rjk0uscN_z}sK9?ziBAB74AB=6u%wIU;5cG|mGSh1Wa zPlbNg9U8qlK#(gTbGOp+w2E_M*d|<1*mM+6!O{ zByvaR#9h{z%%VWO$*i4J2r}1OyD(_5vodL_X`Az>RoN{Msn2FY43le^6u_TB1 zK@l35ZiWp(kxNCsO*75ALEEcbPpWF53Y+C zaJ2MYM{xC)RDxH{*au#}rS4X8#AENVZ>zmviRu1i3;sHpwto6urcC|6RuDS{k@RO0 z8yp)UAvleP2u5Y~NpIJc$*X83LYk{I#w)jp2I=WZkZbWjSquoGsx?a7CU|B_m0wsz z`5b14Ou>b9VbzQHg>|TT(3u|L7SA0eLx#R$)Ck_uJ|wL!a4PmDK@n!?6SHs<4H3g_ z8Pf>ZVHf{&X9@~_pxg}f`nv!lD3iH>+0=#a!7W6`KmeJd>g}nEPXc+<{aBp3TdJD< zVUOBcmCn(Q z8S3^Fc)A`#$p2^w>+~Cn6Ja5B_?JGQba|S@C(gLq@m(pHdRF+}yxt z-wY?}GN^MUWbqlQT1 za5ORFy5)x|+vM@ZS6c@B+t(Mt2HIrM)3hqHSEodc2NTUS(p4v&8=E4Vd1XdZgTMwi z^P~iYDM>zI?R&0I(-pR}@7KHYkTS>SVNv zkLZ;>T86s2g>?>GUJddc%ToApTMUV+;d4&j@Q(4BkuRU~!0H?P1u@)b3fJRU-7AYg7@NZZ%Qi2<-!P+n@vB5(13V931xf|_|^Lg<1OEN zV@4=R`q^H=0IqTF&e&y@8>q{5Nruj!AJ4N~X-)MfsB^0(I<;V7h#{wH7O74=fCpzs zexOcz^5?BE1G4!7yiF}kCZ=PIU9Mg2118)9difs>pX~qOlA9Q84MZ|n7GD@*xQxSy z-1gFKtL3TXHvu{ydV*my89+iE!`lAh6FcLiXmA!cbf(!2QxP>}g-&kPC_n|V3{1_W zZIhQVYz&Q;C^%O(-u|Hrg& z%g<{r=Q{BFeV6aa&;6@~;s3Yb?Qm;_KGX9mm4}#LQ4KHR0o+ZLRckU9ABb_#2poVU?uC@vw~cK*%us3m48IW zy2y-lrA+gl;Yy7YrqiBNis@Dd(nVIb^?;A`pSAp7|C7y2WG#ADxVE<@hs;j6rjnnp zBT(eos3q3$51z!$>PwiX$4!Qh(G=~Mr*_P2&dz7wAL)Akp0>YpYrku8xlj$03y~sZ znPNLM`c!OEB1KeR1)sHshu5nF=n%Arpe`!q#3F*5WT=Z^CW(7LcalMoK>NzjEr|^7 zhN~p>bbP8ofUJqQLt@~Bl-y6-k{5OW_d^twb!d6Vm$;{PZ(eGI9;4>)SEA{$w$b!) zPTj6rVpEB1dPXjwS&q~G5|2Dar~l_MA{fZ|ri8}b4bop_CL75b2IHsWtp#VNC^mms<9NLJl=r%ip^25>kjSKB2x+QXrC(TC&&CisS`CB@V8m3nm1j%qv1 zzMG|TySh6=epA08RYA0yF1NS~1UDqov>8V8xPoFrW}}BQH320$A;X z>IdcI7}2Gan@C|F7o*LJL}W&NQO$Y&n(2w~2kZs;039(mhMT@a>ED<99)!DHe*b zeDavm(8dxcui~;l0phM#a<%;LspQrd(Kns?n+id@wh$|J!)zi;QurfXlpYbLLA_?J zX^UW-Y?`vztevS-?$~NRnzF|9;4ys{x#f5CvRpiMH5 zJz#Y-Gf@k#ML6Q1i#nBA|ERqcI3W=b5$9-T5POrU{$m90y zh6=7Dy&k7_S3Poiwtc$4=S$zmq7od}Xt>F*E_?4UM#n0=H|7Q}G~w1?Z3ZW)Ihq~E zfjG_>GKSu}&AzzZSLH$ZO!^>UKCnioYy+tj)>ylO`$5jNj_CC9` z;V5_rm(J4ku@RcOC^SYIw{F9~^!kOb_GhwI1{Oe{_8ZIM!_&H@X#xjEwA26t|HTnS~b0b}M^i@2so{$!f?J z(x9?e_FfS}wrnXgWRJe{s-Aa!-*+62=Xsy!c;4{8|JQk)=kNTD;h<#Z@oobpI;}F^ zp0`WTX@q8oL4TklcLJ|-Ckr;K>!rg&`BlZO5*wNzIL5 zL`k2he*aVsTl0`@mHDHbEE906fPw9xrF@ zxb(Cx)Tf?-NV`_w=*`oHdCT*rv5h+v%A_pP!#VN0FqQ6nYo2b9_NSQ9J=UANLfH@g zHAgy~aon|B(ovzo?0sjdT>>X56&o0ZjKsZ8e}mEgy-oD5Sl{a;kC0E>WOu!hc*ACQ z=z*L@CV=?WZwXC}TVDqPm2&F4#L*t|mnXT~$kU@dElVwd)9`9YO{rLD$Y2S2>I~=1 zBPF8%=LAt-&k8px-*C2__%Z`5jmZ~bGv@;`B>Ng3M@nHs2H>9N+VT1I@G(n9vD1ASWLL+$$!cYHL0=*19kE)uo>NDbA2Iv<2)2^hp&B3lP*2|y+PgpOjDZC3{?QN$ zwzTv!91a%rglJ1|l1vXZFOekY+=GceT;ZSSzXoSjZGB~k?;00%oyQ@|8IHLZMi-KX z$PLq)M$+E&%v>9-yyz&tlv~fTen@doG6B&OgZksVaXF2~!tCCQJ@s3pH7LN!B94Y@ zOL#;fQ;)Q{dA%No+8tHN;|kMeJG0E4QrNgi4dO{5VIqHtIjp9%TRjnj7ekt zhs`e^CW`+GF_DL|9%&3cYS^!1Y7cP^egWxk;1a zaWIzsx1S!!!rus!XD>JmP%vLAFLX3|5DjZa->+s|mt@Kavnt@l>DSkbB<*1PZgt&f=&&i@nMx#`M2-@5 zvu78PA0dC^gnqTu_#-*8GZ|I)H(cu-2EL||?w9eyMNL* zJDrbps52h$kuj-trtL6bl(BSuDd%+s#cf(`l?bVO&WYOrebe&2JMp;03@r)3dYw4u zk7){Bi9;60k&{a+=~5OBU1DMT=j+PfnEedmXM?TA?7S! zx*}t?=bH-mFrHt*qsP>bp7mt@1>V+H@0}Ss zS|OlUu@$##+GP#;qX_NL6;^3b7vGt?+PMC@DeTH&=4K&IEz=rIFBo*nGjr-0Cc-Ss zM+mMd5U|&p~9yk1n9Y7Q~fCm}<3SvKto5Qu>rL+AZRYX58D3FbN!b2*o?$-yd zWZaFHxnLnr&p$a}&=O6P#uj2>X?gn9ysp^xTW<928iW92m zE~2$%%^PE!p{n@Ek+!NrW|E|%vg~P<5wQo&jU%QBvsO=`aEJUbo894jbv`Xd@c4_w z#CDt2CbRjuyAxxNO66S&|U zWXrZJX}&z%#O^OZx(_F^JBW-a=AODQr=4eq~Hxpg0XR1Is9V8Y|VbTok=QP+EXb@S_-hi=hXT&Mx6@Lgn3)^hrFn z#mO^5Sv*F%e7==U$~dy6BUvzbh#hV%D$jT0+i|4jLO!l3oWx4%k(p{QtP<|t-~yp& zB;LDG1iy+g9bLs02XnlgKaXv_mzW)W{XAmOUUaMiF^fgdARLRhZHO z5v0pJcAbGr?ZJf&Ft*pMoC!Mb9hqPMi$V=sJm&9Mj61qY^SuFoI&W6bCSjJ1g+@Tf zK{cz$xPff0bDBFFH0}f2btQFY!V`FvrI!JI*?JmdPd}))u&!>1EMW6Oxjtu<5rv{jlPS=q(tOVRIgNWsf(9Pl;fg{ZUN;k^33{9?zsnr zPAu(T*{d5`tcv!cB0y!c#Or0C+rCZCJd+=LZ+WM~ci)6*xh+laT}EEW^2dlmlbI(~ zOkG>ndob&a+&OA;nntlY*wA?`aCHsXLZKOapd{HXdGdZ}37&H|WTV_)9{$32o;&ps zY|t9U4wD=LQMEIRS?~&o6d#LW(RN`E#Rcs*D)B}d6g%PDO5b%p!6ic?62ZlGY1pKad zxQ`g0v%n*+mSp*yWgb`^{$)n0;NhR-W${xoR!d4~Jvz^oLDGs#vXJu zRa8WFWyzxnl9Tu2biDX-O)kH@?F(RD?VM9svi))XSzzcb-Fw_x{CY0j)pVQ&kwt~+> zPjS-|sywCld5ec9E96Zn@W1-hHQ={Lb-Z<>XnT`@4NRQdx^4B~WOUA-MW}f9=dOx^ z7mZr0jI-%X4U6w??J#_&AJa9O5W<)cO}2|o9%&V}k7t&dNjx*!QjV=H{JF1WG+S-_ z6FKCSV1WQ6`F`2%Y0=}+rWq$oD*qiA)skL^YOI}|Bd2JA0HvJH= zn~#JhSCZmtrahWLJiM~IsOx&mNKf+pC^$?u7CTiP*_d95O!7io)K^WcH%ER-J*P>Q z$SNar1!->KcIE2F_`IxE4>e*CeSWmT05>;=7EO@XP9V9V6A zqf2gH;$97=kc=Q&fMF!rVm>P^!@del(%>Nuk`Htv4t!OUQthYE%chK8w%0*&;S^vx zbBw_2wdFlhQ32-7@9NS#pRQ;xE`Y%2j1T#>c;VB0@gMZGq#7tl$AEiWu*~5KMBWD@ zhEe`3U!FC{bjAuE+L#cN{l8^O-5 z@1eea(14DYBM@;I`1y+;vd34U%Q!s73@1C$Ai42OfaP7N+n^uHDdib@c<<)I>z&v6cs$Pl37}5)VrE1tBqRKzk$44Jphy=3}bk8e+t&pKN zs7paK9qT*g#u9BD_wX`_00r^mi0ntKV}{I=z%XlT?b6KJzPGnRa~W@3u#rO==FxBO z1jCL_*1HEPoJk7fnG99XZX{>B@4Q9KR(#NjcZzP6q3>!|oRL(+Cg@ux>m7HYRT=;e zr?!%+a@5Sr$ZJ;}RwvamT60zT?lRIcvKZYI^AU?^(Y#c-(WSel2_Anv5yl(Z@Akr& zOz0v`n|#F44!I_03uWQApKLJKJz6)%*+ff#JOn#7XK9wk5?hz^-5U@jd^NDMnEkDAcya4QEotf-T1;L+R(yl`&22ehPAw*hU!d~!#ydJY8>n9Bdz1^lXSa7qx-kO%|4t)@bSZ4 zqtb}owV%TSsxq^-EG7kTJEBI}oTz0lcO7ncg$}dwY{iFer@dcdTc#v$RgU)EZ`cau zD?LStlhE!joCSUQnFuMLL!U&mSm<)&LB~jB1)_m;69O03*i4gBt5SIDyD4QqHXK#p zoP|Y?HxL*W&IJ-0>&P2bI&tn&v>LngH1*`SPK|*@=q=#*xs-LRET2BApY_A?;hja3 zq9PEtbZje+?Cy)|#I2pW>N*~BN*qhnX+sxXwSsZag?hG1=*s1SOwwG7Jt`k1qXXQ5h2Mg%4C$h@p$L}0eL2@c@X}m8yS#WO-%A=ZG~RbKE~h(N zg^~5 zphNQ?g*t5d?jxLMQ) zx+T=8V*~LbZ8C_y62@Kk$3Gk|z@2+`$`FXp2S?>isSdStx)7VTo>w(H zCN~C%&U<89_IT~7`n5CING@>r5}UDssE#~j%zG`Ibp!cXn{P>8V}22Dq$T+tusp=^EZx$`4WoX6 zcXWKZC)`RR^4Vyc2`=OBAs%r6g*lZ$&Jgna7hSym-ME-mV&)_GR<{X9!g%HU{lxJ) zAPG4ZI1QAX_SjjQGly@jS61-!Qc1h=6}KiPH+f6)CEz?(<76ije_Nsex#*B5a@q!~ zYt{H1+sa);)H>UxjgmEcUB*SKLYrzO+Zp( zcwq~qTE(E@g%_9ShMx+4W7+%pW(24e&3Tfc{)q`s8pX{6;_A1-hTE&lmG8*+ch2pl zZcBEE;G7s_y^qcRNV&lvz1%M7P7X@T^`TC#L@_Nosu>@98Ka4Z5{qJU=|?M13;2aQ ztGC>Z8*N&4M)8)wFK1yn&|YGpiy({3!^)ms+g^GR_z{GI;wWq>LrkAc>gOl|0O)&-nu^6Z_$bUy(kB)MU9 zaT8jRJTTW2m_6{Fiul}VSp$~sU-QonCH80xHjWzVl=bJ1rxT_62lrDS)R0#o%sp%9 z$ZPGEdluJMB$LbxKq`iubUR8ljaJ22#Q)K=<2n>_OB$9$iffmyj!w^(oYrBCkVxnwf{)U5G z`dUtW&)g>-AbKDnu8VI_o2W^x;HKGsUC)2uo&yB4sqhN)P>ogGTpFoR->XmW1ZjKH zN-KJ2bTID8UX91ii&v!z7&%UtlNi|KHvIVApRfZ{Rjac`Lt8$Dktm&1SrO0Zu)mHk z4|%JxZ7U0>n+rvHW@h1FP}}Ic=Xrv2O^;(3UW!V7-z#zQEqt6i4I@9+*E~+w$Hlx}90S z&5^?$>Ja70WvuC|n+Sn;d)e0C*C7tq+J@o93j5bDD5n_GGF3Y*jc^|to;aKiOt6f) zh+&OZxZI*xq$|@Qdg~*d#MC3XFi(5=PRsK!`Q|e@e>{Ui*jD|Sq(O0+&7HiV2V?!IQ{Rv z3)iqkJBG0-7dX59n=KTK;NZ&S)_HExYVb2Hg#{VL-Pac+6NAXp!1X=2Il00-Gzhh0 zX?qRbTcw~?y{XrvUV$c`MhuiKJs`3hHq?Crr)TX`lUs$^`UFNi`M3*a??#wo%FXQv z!8yxeV&$cr)5bcabO&X89%g#QV zC85851e!?3rYmzowZ{4w3cs~ZU`x_#$q~<}%OeS}EiAv}%NY2d@Ii!IUC0}ToF7Mf z^>SB2%+y!ZW!U@B@iYn{EQ1V^l8JUPqa}Y0l6`i}D^hp|3K(*Rom!7?unk^h`s@Pi zN``Se|3KfIf*mN?d_Q^ndBMOatMKNEa-3j84pA;^V_3t*u*_hSGU&@I(#tmr{ED_o z?k+)xK2v!)jahV?;OypBcbEBM@_vrk1~6-%-pOs6b(3aT13_46)8k3mXX7gdo(m!< z&1o{^Henvuv)fO?8N~%3y;e`VwkY0EBI3DjY$|9f;(4MQ4kyyS_Fkj>do1USyuB+(qabAD(#Q^&_Y$tK|Ma(I&ABQCSlxF& z+r}@oR@@iFW&Gpg>8svzf8o7R;Glip062k-iil;@M4iQP7j{H#R6AiOH8MUMx4D3b z`#l(|cR{(Oce{DJQ$gJ$8GzoqC)F{fpEm%U8UobN62ICB@0P3Km>naRbQj*0mHt-(T$sNE{sjcHT=CT zavR>-`I#oO_u)pN)pVn3R#hgc!t^dnYbMri3qTHa5B~BW7m$dXl%%X6;ZFZIlHr^S z@MF!q?wX`KYnNzdlDP(53tLH9j^CsMMAr<03+&YTefa2~J|r|gJ6L(z^&`~h~us01HJa*?|W}p^A3Tp!~Aj+%UMi|B5&c-gv1X7eX0R6MDMPPPal)} zG*8{cP8P8RB(N{rmWQy%865fAX&V6I$FX1^cBe?~uXf>n%O11huKABOe%>5y1 z$NS@v6ngZ1*x?r)NfuR*&`5)lZG;5G=5(Bs=Ni9ZmdZ$YR7>E$Zi$l(b+StwJgmjYnU7Ic_mAnx`^kI}TfY+yL zxP(g9f{Ny|CXY6;sk4mC(-(O}UI1WZ1$T{F1>E!T6)Alvy={Rc1I~*#TBCVMpBugI zAZ3$npy!S@cvJ7l*hlak9*2D>Hjn7MWx}Lb5vV`t_@79fKY2k7^Kv+}OHdv&kDPBo z!Ih@-WbH}b3PWhW{#F3THKcWL6x|Mz9k3@Ygz&U1mj$tl!jEDWh;HundQnud@1KzF z4mxRo$qBynqDxJheMHoD@MUT)%_42;9STPC3?k>ma)FHgMkeznM;izwFF+d_^4>ch zA-PRmi_q%Da9hDI<3?CIKI6iD{@#JmIzZe7s;1qsi-JLR!M(q(vZc8G-xno1b~1m1 zPyg%=ucFv1$^%-<=(MR=5#Wy3m13h?%S+MtLv%~Z_tiYblONwHF-LG*b!xa*1r?uM zX*hgAR+bXGy?qBP1c{zwWNt*Y;fHBE%_+o7U{>aOFJ;U5q~c|29M zulvUgT&eb2y*dm}Xx3zSx^jzWsb|F^&LxtMf{sW1ki85gIf`Cyfr>f4B-arWs^Zn>IR=`&`tk@((@;b@jAI6Kt5rVh>@oySUmnWY9bj$00!5Z-(;>dg^G zKM+XSS%go0Jb{V;)) z;-!I?BJOi9+=&_6g&zf5V}IpeDWFn(qiPl{IPd#wC)u{3^I{Qbu?J9mwe3(*A=s;# zYQBPF1S8e0sNUps&39TstOG1G)2@t7wKGJu6Aptv9HpU=!A7nbwKy;~p=lzOH)Rt( zip;F6h}18nXU>pF>t3hvwW4plnqXII$vur$&?qFXg&$I)|8tI(?ZrI(o$vc!PZtbD zp8(@qoJsT~N;CJfAP6>rz*chv0HXx-EZK2DnuD+D)_(%tRVP3Kq4HP;n$4}r);3ZJ z>!@XqM(KCtcriB26;1{jJ$p(h{@}q?@((3$DAW)VpB7-2$ot-%R#rPu z{Px=~fC??q+))<$ZGFi8p&~s)#B@L6>5EFA_7~lrv^?6>Kr$(2V${28K8Ql-vJA!4 zOKm0)DhFq*L+y%(ba$mqM+ppvy;?eEQ5rrisUJ0DtI-_(pU?Qu|CU|*&(v;s-0=)R zS4|kA(DsE&e)Yl_^j$}B7aCHJ_jX)Wi_2E2&+C4ztQcrmaiqqEo3&k)bA0t{TRtG( z17O^!w)#u%gknEjc`W3eo88S!%6Q{M1lN7%RRHvxY;I+`72+&&68g-d&$|d7M(y9+vi2Mqo0=0&vuKU& zkr3fFyO6tno^27s_YX5YYXIA%@un#2xB zXJBuC$+|PO;C(;9r@URI^Sw9inMOYehIqgp=7>=U;bxb^Wqs$_JhQD;RMVn4j0yx2zy4%FY=kKg%xf}%MZ?}9uwa=ROB zG0J@GdrETGLtMIbC4vlv80KCg;K8s)C2LLo)g^(@hEM6mRzy3{6D`0fCz`=jR}3A0 zkU+G83bvZPa(Mf=bbEnR%xa4xBTsbo@yCw2TLHYYG-X~i~B$^PR!ZW*q{S0Tt3$>%b6`_eP_Boy!tNw0fOVjU-z`A4?I4( z5UpE3XaQuuLl0u70Z1y7TopzWUQ+QtgtV`R7UL{DfPk*BG-hjRtDjyF%> zIug;whPw1>7{;9g`kf=BLniNmHpq_#bxK(-tvPE|vg{stoS&+Ef63m!B>CZaIB}|| zt5Y?rTfGK1JEEBbq#-|8KOQDAy%fP{N!fg{T1_RN^)6ng{dcF?&u>IM*XL7z?xBDW zq-z6W9yUSJBhM%*{}iFN3L9uri;xobYe#bOMx${&aA_+1?>y5}NA}#{hY%(?I`%u4 z^kj^#aag3`CYTcr0Y+-dmFVD)Sm6VjU6=4_F2wJL#|Gmd<0wZv!cw%3ZdO-)v; zvNu4KM`|*vKFUCDY7xBQJNH_8E8v723SfawFIW$J($K_8pL~~ZC`cPuM{c`An6$RG zCTd(Ce0Wa5L&Oc5e;Vd#EGd#nm{cOgMX!;YGvfn+qdhOY{S5Lg5N2k&M`6T3H z%`!mqr5BojAKL_pu^0M6w*3wKpFgl7KGqb0IWNECU^H>vjJYLziW02uo0U;+)&dR)D!Xh*>TK)*v7X7Ig z_M??wX(JD^JOA8;n?CxTLWh#(F^(jK3v*dzc5hE5Ee+tRu9;bIMxYyc*Wln-DBfga zxKKt5Uv53+gJVceZ*8Ue4HTy43^qCE-#){|?g6@{wyzX{E-+vk?kRo93u$sHl^KVM zpc-xL$Ro zbnYK@j@{n7vZzL6%5^=-25f-}BCnnMK;FR*GyfH3l|*=H5BP!Rt%)2fD)!|U_$TCj zf!{6YpCPz zP2`a^^+Y%n46Fw{5T?C)Q-6&ewig~9-xrbMzjWuN3{Z*QNr4#R%9VIwI~X>EnjF<^ z$M#_uD|jjsd7x7!+Px2r#<1{R0GEfHWZ(UPw_7Z|H<)IQ-n!zga97g2J@MsvP^B2JWpFZoKCac8{#Wgq_`+N|(*N~Id7>Q(-^>fu}4r#wPS zFJb3sQw%%dLz1nyz>IyvQ+@u^B(W(H`VgBQn3}S5#k8c?MNAfJ#ZmCyY1@Xj%oZ`#5vc(P!Dso! z93MutK`9?anKQEIFeRW_Jrdx-JRy13bCLAvJqbIcI$xn&ZH&^M{{a&FMsn6W)1WYn zafPfkx(#`LteuQ?FLnn$kww8@CMFaw7w*ElQ%B!SfK8SZJZT zdy^+s5|i)K6>LVqzgfrK5FYFd@z{P}Cs@wiwqR9CswMvX`7`G5o9yiOrKP2^v62H+ zM5_VQpk#}pY<4Mm%mP9AF`TjGk2OFHQ#xen3Z{$gs0;GW4 zPy}5}bYX*L##dyG;Jh~3EEH}(6ES-{bpc9!H(+?omT}bY>QuL`9&bz)NOIeEi+aiuR5fAhyRB&w?rRbv~kJ0VNA#maiX-$f&tq3kTPfLkK3!Q5R3k=)(4>v zB^X?DGwm7VNWJ?N8uh(}#tYX*%JRqf68P&h`0xwM=`foWTc6dh58xkS9P??bcce+Y zgs$yn=5NWrcGJ9JPt}lq)l66rU-Q2@%nD3M_Uv1Ity!3+?-ISFkUdfxDxx3EN@J8K z&8zB%AG}yga2J$`ui_Q9{=otUA=L0NR-D)K#X(lV!=XpPmBJVrf$+fytL!6Bhld{X=-5Jnd%D|%O+nIfHt0HFNs6X!u?!9n3$ zfCM>*#$3E}%Hr>%j5W=6sj}1|VjH$$}zv0Jz>AW=&!bKCod5emei!+jtLy*C^-p zq{NnceN3wUpwqjJ9C*`}X!==%*fuePFeiT(o}s<|Er7nx?%OLV^y6r;Yzr ztj^Ml^LSlg-PcYgy=hn%k5%9;{gyf(?==S^K2OPtpif8TzXBW7vBSGvZ+jWoH3P6t zp1Z-EB;{EYQ*PlILESs74TNirIHG~$4ECV167|}2&<<9trfD+b12ko(wdW*$j292u^#WGIteD9CMP?O<=@``N~$aeg^I|ZmyQB1 zsPMa~tf&oW2D#vI&SC!IF#mSI9w;V>>``J@}KM??epfQn{ zB1xE%gHpPa51k2;&-Y;uETh=jRIK5CJIe1SjE~7ne1Tl~tk2V&C#Nypz;}*w(&MB2p^kEg8}-SsUqbEa{TBrL z&@p%ILk4oJ!M95U;A?gz`av;ZIubuW$&t<_*0X(6=pV|wdA8iFgza1TN(;||z3{&}Ra%pW0yI9lLi;NtcjkB{X479}019;RW-Q)Op_5XzF70v= zq&|q1@vpC_tFj9;e#1np(G`oObHmwMo4%e6QMF4Ku=m+rPuT083p^`BfI2^#<~vLF zPl$f_1Y|!!I9{%S@YR-VvH$7kCJJ`M^!&VOhWfy zZ!jz##LFPU?2Dw&+}A`Z@F!6hQ+%;W5zEewVu48CRbPp6y5``$i*l}MVo$zm<089= zdxUf``R&&d=<*|&Bzm==gUeX`gChLLJm5k;MsfWS{;6|<6$Jn8?0#RB^x<$Ph6mlC29K8j;^t%}Jf3J={tmp;>cpVH z1>jg6UwMA4f!vr-+GtuNka~m2K+^a19&{h(K4-YTqgon#&e57DQ5Gkl_#il8;Oq=o z6@T^m+2ck*L@B!&BDN1Ls3UI~y19aKdid2&95RMKd2j$>@=#~}A18TDaY+x6&c#e! z+AIdra6(lQv<`!=P%};NTi|gn+~E08H2nJ7j97%xgB`$^9C51FL~r5YKnv&kV1Y_Pzw zgSSx|R{3wyX5UV@!*QiFDM&`Cs}i>Pq*<@GI<`<(%V46Bkz>*jweFee$DyTX-WG4B z%YwGEY+~yZxf*lVmjY+<4eUy$kDTXgnn9jS*n#a5wXfXoGK}Gp7Q(g&R({>=Iy8Z@ zIE0z;d!Uv6=eQ^<-yQvdG|De=(HotBFg;t|nFg_hs88AUP^-2YT1xJ~liI6sIx9zj z+T5KrR-gMpWxmMXX8ffG=#;uE1?0C;BL_i3LWzI0o!rFf>VLn93Nhw}#s!X^i|AZg zM1ZOA3bB6n61r`9q7{_J14X9yVVrePkj%f;c39X146sRvdFfkb!4Of|zz5aWWVs2D zOIt6e&Y@Vb1ZnTmGbOojucaxcO#A!KY!?mL&E3dZ@2kUnK`!JF*L5jn7a?IiG#LT> zpb)j}u?5}zI<%>2U5~kVRh958D}2-rnl+qgqnlr|g*|$sSPf5%)Da^RlYqL2$bq+5 zZ1bFLfrtqQ4JT`6%tI+N-ms8iw(5Fz=1e!tSR4qJu}#LdaR?AEcI8eX5@)6=8#S$u+%Y)>4Fm^1$+J?1u6bI@3DRb8gh!uH*+Z0V5t$G%(HO5 z-xIN#w8CD@hM&6j&#VCN0{JD`arn5Xl~5L5V``fN?Iy1y>;y}z)ZO{-)`UElyB`!e z00!Cc(pp-MAGXlP==<)uxIK0*?gOn^5iF;VS6%nuM=)p^yu2{PY z11O3s@2Zgwwr?G|o_?imV=rn}IQ7`tyNy@MW-r=nJoM3)%BY z4jRg=O&}_NYfC`zRt>`)jAyL#%gO~C4i2}oe5~&MP{K%Ct@n!xEIMoXKnRA?guC?* zZ*`w6p>ReHcaI?XhAmH!fmJOwt*A&;MYfRm$;n5gjQan~8!#Iq+qXVrTY!{pKBb%& zHL4BBXl-;N(|THQ1Rx4WL%~6kK7CBcRoTG*{_!4G!^>g@_VFu$SO?@(tEH}AlDoBxC4s(Zi_5l{O{yjq%&x!Ku_ETh)<<*(bh{A|=&@O$`wSFTUGL?xPj3g?gze=(ea!;;R=f59}J#w9GilO<1FtdYyjgO#Ff!Hm1pJ z(F*PrKrVZw8h4g|vw@nw260ow3u*ri2F2V(^aNo(co7(4-Xoe2xt}~ihRUUY9|&*m zTKi2FeN7NwU2}LBm;!y$U#ekx|ya6ldjX`k3wB6s`dXtl50tBkx?%1JO<;4)mHUM>f z(c?dVz~2>_853U~gWJ*tOIBp|mIG&f5OzV~gg)9}NONOo^O>Bar|(NxxB=&5=iZdv zEyUVE^WvTLc}oq=JUZ z^rL1D`u9`d5HkT*p9R zXcexYAw|r4b0xAn%8iuWAa^o>V7!;K8Va5+|Fb?wxk01^de1_3`o#`<>kKw9s0`W7 z#mvslEdU6n6pC2XnZSLAl9+yszzTQ>|0)8qBFMpxJ|cA+O{CNqW{)WfK&+OIM4Q1T z$IVw|vW&J@%>9QUqFiMtgwnVI+CKyrj)7p!fn<>zxXd!S&*H}QM17euffV0Ht9(=N z^oI!v;y-ct*-+JL_x!zHANk?2_oGmsMyLMvZp za;XwWeoFSYM=!bG3VTZL-yc<0h)V!)6Ep-Y06+0EM-8peW?Ll9b36(nicNTB<^fE7 z4-`b1V?(wTBi!eS=pmkTAD&wpqPM@P@NhYD*}kpM z1ax@Jn&ekaK~|RC^K3^qfa>_{dv5*X@xDcc0~BZh7L@PdQ>>@CX_K2lG7Fm=uw1o9 zs``x8Q@{6K|N3Z-U6A!qU}Yf)X51QNF!)3?V*r-0^MLdgAxlBVlT}0*A~4zDcZIDe zrm}eAB&?7lWcJ-rXlyy_!vA!zhgl!lYZ2dCJ(=c(9z%3BV0UI9jC;NS1uZL36Px)e zbn0Ik0h+@HTJw-3j5;5@@`{ZI5MQIVr6CvCvuCfW0}L)HH~d{QC}$N~l-2Sb06yz-0xE-+0A4G|x z$ZnZ6{C_is*vUBseD}Tj3~PazYzNe-LbN~mDt66E&b0rHI#*w81Jo&m)7>l%F5iQ- zZUssT>z`%9@+Aa1;V*={oFd~g@5smK)_7~IQOSuWeDXQIJ_?NmxS9-(kiwh~~ zy~*8WubFoylA{+NGTUOMTi!VQS+#SXKzpn|2S63mA~6r|=6leIaDHkg742so>*!g9 zcBi!0Y;P+EI|M>|UzL34zR#cO?%De`!Mre0DZF<7!!wEBn57_eSA@F_E6_Y(pKt@O z@b^^G5{j3KEav)PMp`Q+A!NX7^}C%EYfVEpVtxBlb}5{;*6 zGjNIBuDYe#{X?3Ltr4UW2=#QLo!tt3SqTmB7m-`JofjDfV5w?H_g?np^!1o`3ES7j z#xV@yPNt^4;C|L=5jiRLc)3mLky|w)`Rn-!H4&O{Fmgr2B$JZxi)ZCbiA6@2MC&dk zKfM{T;oe>c^rerRYDrb2NeLb=kvbubzsTK#$Ff5xVHLmgCp`S5QgErhk8i-Ac*f-7 z3#qf>v@wu^tRcbJ^kFFcRG9O_ed_$9;ohXwJ6=}v>oIduDgC%iSngw2&EC;3G3Jb+u?UV0PC0ysfd8`ha=($3({HDD8)CGZr!xoJZIZ-+)0<7lQ zyuJkGUh6Yo4_!MWpI=Vr0V7^G?LF8yr=aO&Z&xrmr4$ew-dX2c`>tbOUrA6YqvRq~ zBmsn*ugs7JbLb4~zN{eG`?slc-#q?%6Z|vNp?~}oMpO>*uM;t4(I z;%uQwC=z%6YN{!nngLvoORuN(^fxOmo7Sp~0W!>Z7}SZ-&z42H_y#neBp9F=)1zPN zT%nNt(Qbp>H(=lRid!yh9SBW>5I7rocn3~pT<%bvJH{ZLDDBD$+H0f6WB};HPuBL>beU~0VLe-U-v_+Vl~H5lMstjkm*f-|^Bsfg#~{?+vRWb ztMK?$wPpRJ&fu5sx16O}y(YF-&Nb%mL46d$ScBbpJ|OljeYv<{_&SjIhqMa?4&Hi|)SMH@_Jalhwarojq(d z;JINhpBwf9;fp4^3rnMbi%%R@iJO~w*SZy)Qn6CLO)e;;?034Q;ivS-2e#9ys*O{&@3b=6CnpGWBp)_& zagP8$M=RJO1s&4eWQ#_?cWGfA7tS)&G{o}!A zzmPv?>>FBx@Ex0-05M8G!Wp)u;QTh)C_5O<5nb%~jFpC$SjO<;vTg@a6NPHfP)L)lWL9#t`Il_uovO}id#j(NU9os73J2^FIYE=-NB%I0~^5 zSM#3Og&K5&rd;ehtMZpXWf##uc4uF0iN$>kzmC$ciu6^M zP~VD~nW(n$z^m-cOwtoal85}71DW-G1pDh@9&F|dNc|&z`P1dez9LtV_|x@Vy^O~b z^Q!3Bebx;W6~ShxJbQQ{I3L?xWIL3YDb#s(WKyB01av7S?8E6|fe&PXnw`zoC4cH1 zu)^h@=G0Rv%AX8BBBvo{@hPQ%UwoO2y5@!$l|l42(8X$N6xKMDpdef4@kKsxmR<-| z5u8&xPPt;nGve$E?Dpeoe8Cr+YaENg{*wk1u+N^=)Z&sLYJ1_#3bLgMx=g+-pKGDg z%XXj9*m1+oS8Dq9!%NM6bf>OhLxYb!eo%F^X9`S~pSUcId?`+z9?V9fDY3<;kF7^+ zx_-eHbsg@>Tam&`!dP7~=!bb}TRoM%NvFRI1RhT)-P0L4KvN{TdTp}&V;J{ILgx{4 zh$2ZT!TKEktD^Dy;k0U6YGAZb_|*2RM`Q63#nj=x5KY>SCa}Ub$MUKF5~6veK(HM( zw|6eon1`FVii7--bB436ScgXeeu?A~?qg%BcB4nh=lhy>FcoM;Z6ivkAfjdKkY`gYhkk8)s@pn@w0a8s<^Qn`^_#A&Q%h~dI)DJP>YpriN%P&t6O3##I z@_f{s&@SbFzGT%YPj!@1RD<#2&Pn@W6o2@j~u z=j>wrw9~_x`1Xs~P?ZxVY23p2eXGz9k=7Vh>ap@)G|i(fn^8Mz#dF5A@0Do zHjgS~%zBwhu!ym7_8Sru+?D4HgJ8(j@EP4ar2An z%T}AGV0fYWW0gls>Kg@^&lJ{AJlRf;J=4^zyVxgAqgOlCa5{c@8Q4{Ja9B@)v6Z)ov2-$qM;M|3tyJKfxI~6B_Mh2M}(nqI$ zlknUPHZsmDsVR59J}YD^TTJow+bz4zdneCf)vsWO@Hl>sQb`-OojpeVBP*|k+qH&} zmM*%a#La29*c?#sRkWNw*cBv|IC%w}DN35U(}3^OE*4YkUH$N~HJBV|wHfPddw`4* zm$=Df9r0_suWDFar2QT+T57>P$Tshlt)w}0MI!}2E*vQ4H=@Y?*Vt)69>K%1obT!Veh6HpZQ`*H3wZ3Y7{ayZmfvU#de$*9fqk!J2fR{as^ySy4`8yqZDy!zaH>^jc(g3ja`dU)Um*W z-l?(qE4J{nTF|2ZGJO-VpEDqP?A;OcA}vpR>?0p6yLQD^LFd<)&!UQ*`2-tV<)VUc z;Y4Rk3X%hK@3UciBk?A2-6cZ+9gVx-F0Zg}&;+#}KI|xMr|!L+h53d%29HN=H*+Rm z$H%v55tv%^{ENFh#&mS7v28_RUfpMM4DUiy)qx2aBWwp7u46(ATz2zNFH+Y_-T5hSFc;w&gK1w)+O-8?I5ADnvDDRk}l#v$f z@0ZFN=JWY~K$~lrC)i?`MI0LgtX_wIC_(%`Tz>^a~D zzeu013GN)3JoYCmHl$38vFQwUq^nYiA#z6O*2f$rgVV@#Z2_R78#vGH2>z@FV$F)r zO0g!n+rM`z7dT2ez?oo$qkPI+bbOrDh?i>X=V``Ebp9WqZ#4H;n)e@GKwWS6Uii4z6r)1%ZBXi#PQ)qD=+rCc z!6n%b)4w&~N+Kf?k-gzWd*=o2eG)#FxKjI?ad8pY;E&f0D-2pR>2P(trji1ZRVQl*IqLQtdyM4A#%snVo}BE1SqQB*{_ zK~Z`_6BLyqkrs-8QpM1@=kI*)_s+d{EtfOPH8X3_aL#k~v-fX1o1ArgkA9Fl35NzGn?s0aRZq#$LS&T1&MAp zSFa2|GhqGU*hi56h&^EMRY}GquHmy;(IFQ`0bNOQm#B5%r2e^$L*=#1lW2qRHO>LA zI^o1o#*CQH8>SsHb|})yd~QE}f^V)7{#s~UKYJRL9IPp;G@rLQxJ5yCB$2;9zbpyl zjm^F8zY>@F@LoKap`=Zgdmt^rl~=j`3J_9H!1#~-w&@KgtPBh#q5oR)X6V(~6SH>o zxuvn_{Z6_URMiQ(Y(W+ndR>SgXMa4 zGVx^HEFN@vnNHEMz=B!jF=R`zuvm8COm|LAm5qR%CL@2Kk}*7LcN4pxIl|G};S_K5 z@|8)tgISHgF>Ct7Rf}V7wN*J(vO#IICiKc+g#$T!DS2__QfK43{Y3kKavt;+Hm%ppdbMa|?Vr zAAr?JtibHx7&SOC3%&y&&Z){DhjC}C`g)&+Rx@%x?6F&0fga{C&$Dw5X)?v&BWyQ- zR!wGp=)((MydqEhzcMFos^}G4XerDmtOr5EIOuKO~$f&6*GpakVkvU_5tdmizzovk%_7zx+aI< zz(dEj)#EX^(N*-Gn`A_J0j+<*kbdR&b>E3Lrhpq*$47+_*Ct@u$*UV%pj|L=)Kf17 zOCYefuZR4eUwfOrGXY+3VQ-&zeu$JoOz3aM%Gzd#Tqkq@`6a{(q07i6<~-|fQh>@{ zQ^LaH_i6nO_GUq;OiB`1lzEwy)L(K z7R8*^r;=>`P>AYG2roY)zj?Sen!gvP8u}#w;i3i9ZtWd$2I*zjb4m$`ZO>!Fg9QI` z0RQ(ShEa)XS8H-yK9=qPoE1q4#`I80)wLxxY@A}-c9I;V@6+2dpzt*K_8 z2R=8mUOBL87&g9lMGsCbWBj$z&uzHv5ZIcnqnJJzW1D-PI3Z7RD|w;4E)fhNNxt6W ztAtXLR;0dTl|MHTI0MadWCYetXv%(sy{9Z$VP15#4)dXsEv`*-0@&Css|>E8XO>UT zS1Zw7ue$J4^yL0jDC@!ZX%Q7L2MW4tj4GH=&mHo4ub#yHcE2BReY)_guKDJatul+70C*M$JX&d*>O{N8>YdyH# zJ12sW7T8XtXJ$LV``+D<>zU9*_N`A3^9>bzH|5+q+Z97wGi9EpSMBVBjPPRN_|FPd z`(OSrAoo6shxLH~D)4mfcYT8oIVmd1$qD!Xe1c4cu844a;)V zw2IG*E)>hHZWF!49+a%x1hKE6UW0x8eJUNj#8WMjq*uVv)E0-Keh2&^1nN*dx2fAk zq2?9sD(9|oyERui&-LZTY+mZG2hzHR$h0#x?^-MwMU@&uMpb8Bs(!SHT3CP|734q1 z-Ku8a5g0-}a;uw#?ixrLgweOtCf7cqNBVtAEOK|cx~+Hf zN|bc?pN_8|swa6~O9xu_gA~z~%IzD5X;VivSAqwP#2Sg>FANlfryt%W(P&X$>yM9d zSq|&x6a5irvwUpp;A0Ueb0%CE-%V4xD&{b5QghNDnoNf8NQGDV^fl>Q@kXUXs1mCT z>@PzD1)8iK-hsf*>@mhxWh=I=fe^alDFf!-V;;9c7$|LcOsjlE=h38z=Z;BsD^62Q z*^#@3Pj;VXD>WH@WIo+HBmLA<-12J4bnml$>^#pesZEV=)r3Y_1SiVp(HeK#x{~!9 z4*Bh+7IV~ETpO@*NnyCB&C|O-$ghHNQn4cueF$y#>8ta@xb-;_r*h<>5BN-reo}4#2>tDi5lh8{x_uBJ_wU zewruWxrsWx=5HLT8C`(DC0&Qcxyg1=KsObD!0YWF%yV+cI_setmkh%gmH!A) z{hA!Vuh!J5F<`{DX*c)AMcpXm$;*#>xji-^fy_57#y?mtL3;>Cs)#2Cy(c+C;{?=y zjn+PeIJW^O(oEh4oaySd3ghjlLF=u?vVQ)6v$Lk(>76lzKUv>aPt$5*B7uC8l4DD_ zwq@*T9?n%|G0=_sVd2J$SO1;A!SVl59af$VekIfJh?6BLiiH`2Wp*&qaFt`FyI|zr zhD8so;bz*_K%bc{O1wm?JB=gD53b^Z6c(V`uka3-m_^ZbWF}kg?YA>%6?}{&l`wkP zfk?&>B=!2DD@A|>n1Dj0i<$RJNJjpI%8sEOAA0GY{kb?Xv`hdSGxz z8J4++UDL5G=PrNNBPr>k*J8ZA332i7s=O$1y}%avSx9xNwhXdkXpKO@EL|5)SmG+b zRTAv({i;eZ1ugZ@GNdnKrxWnLP*4diX&(2e`ZTv|l3b;_G`GdE?c5&(JnhQ2?HWX6 ze&w~dLEWSQ0^x+FiXkv@OWIT{p)Sl61|HG;l_ycfp@J998J-MESX62&1!Z#mvk2BA z76OTOn7&OvnW|`7eSK&8I<*$S0Wfp0v9J31~S+6LQJQ@)-e&%43Wr2?1-sXf3 zbZLrV9rD_^cns79sHvO4RhY6q7+hJOxm09RIou511WM$96m{SSB?z7&9V9j0LT>D| zCrrhhz|bQi0%xb*gNL;Gt?}K`UDko~1eHKG-t<(A;@zJkIp|uDu=xfVmPWSlaZt-A zTD@&W>)U%sXdUn`WJan^ZNvNXzZ?>p9Ad{VpAC(A39~ENX}>%Hlw0!!Yw%RgVB9Y;sH1TS15O37Ho1 zaq1V_0Sj3sep^TyXWLL%;5M3Sz(jq(AwlCs`<^scV8kX+@3@L5E`1qhcU>PGb70UC z=NQ>-fBy9YgMq#FTFEphRaLM*N%`@qeJk}YxP|kPUDh3`HbVc;HW&K7d-NQ(>MAPw zp;)z(#_CJQ4XZ0*>{hXD`y(YLAV{$+iZuBw0 z`#yucZG(f~-mD@#8V);ANsvw>!5IpC1Uv1lbDVx&T15H%!BM`J>E|X@j#lIZoY3|D^lXy0(gS) zIe#KL9PZfYD*OSe0QzOcFp6n3h!XLUCqrFn3^ zIefqOruL6#7`T-B*l%Gcl6re1vP@daYB~^N?31!W4pQgBh1xL?TG;L*dc~b`K!NXRK zGdELN@3_8Ea(5#M+Aa3FmYgM}`*xFmvhU5E zUS#wlQ(v*(T#x~<#t@QXjvRWR?-g-SXwjjoM4AHH?oN!gOO zL$pOKe}C(S%sVlUqEgwM3DUSIFr5!re2i{0Lr=`O=y0l&a0s;rX88=+>-{%d=K3xOR1jD=Wem9`OI#E*J(Q=$zed$k^PzuYJvvW~x8=SPP zXs6u9Y*`ytv5#$w{!gNhG~UjQR>m$sqVZMdc#-L1q4q{GA;uIgH~wP@dBKukDyhM6 zP=l$&ERdlq{LG6RAk^v#Z@Qi-AONS^WGX zD|(Pn)-6)d$&B7i?rq->0G=)PPw4FdL;51?i{jyH<^l8ohO71sZ0S8hOD;e5vJFmO zwh5t99^SqDB%yj}51&3wA&};(5L#WJ!;YAt3K$*+wHU64z@t>ds#s)8&X10eHEhC7j9{J$VPP_ zSdAP*OQ&x|v^>8S%CG;DwEp_VB@*Bw!4&GRRP-71bD=8M|1Z&Bd*MVmh=@VfwMdvu zVE+u-O2AZeRw75A1kp8y1+QA=MhPGinfjcKGEM{!M!g1b4z8iJwke~~otXNjas@2H zxMa}Ugx#yUGNJ6TPZ6W=#xfi$Q7o=RlaJ1HF4ig--$)m`@Ffrk@>kPbZ7VDVpOk5! zWoLUG?Hhl>x9xz(3iY`GY?urR8L)`TEf02Twnbw}FQ+4fld89WIDUC6BmR`f`qLgq zl@yoj6g#d0wzB75LW+A+wam)OCdQs@Y{I_ZywR`r3-n5u)FJ!WzH*D*NTNT-Fn@G5 zN?ET>hAx)vb4uA;or=gogy2eI==fY{?^WyAFf$XN>8sZVo>fF7l$x z4jmMej)pwE)raMscgcvp6!PY|rS@O@dILTDlY~{^J^uI7Y!f zIeV+gV9!i--4a2*)`mc&Hjr&wa-_~WI~|$+DvsOI6KdF8j6Axp8|4qC`_2Tjz?+z| zjNchk6O6AQIMD(B@U`dq+`#B5SMjo~`(^nQ!%(Sg#$|e})IC$MsxoVS+*5qu20x$1 zzYVU)I_K{x@`~z~hg?gc51&2!AX|uOuT>j+UyFax8EdgneV51HitPe1u)Ch`^uUap z>{*<3+X4W0J@mO)+Wc`ZHCm#|8RBxu#u}dj+{ki0>L&I%!(ND><`MdzATXReP=o8hx@7z>IO8nhOi7OrJuaik#;@R!cnV(F>NQ{zptC$%70N9}&<~kJ zU66P=ugx;wxF0N<2u})fLcg6Z(9tvHj=V-w|C_HB=Hvwm1UG6*e|4L4-fACwo*m~4 zO1Gy1ErW9eB}{0AQH&)QFIc6aT4mhb2Oz_)T|OA!pgwPoNQ-aT3h_xFW4nENR>72D z7$5p>3s}z-KM1~Lv#HnzMUX|2xZ+#1Y?mTveRzd!@8OuvXV>JL1*SZ`S(&7>L)?Gf z`2Gd4XAE?UGfPhDn)W&8=xpt5tb0xI{$SW3v1fw6Znp;`rF{?EFNr!R{RAKYCl#e` zP9azRaxzEw*jUdm&h>AZzuuF+4cuWLzFYWgR=pqN)r%6T+)qqrXISGd`x}L?eiYRy zftE|^A3#q|21=$6w${i8m+ zk>|&wEhLuD*axu#H2&Z_=>VtbpJ&vTLp#~?cg+Q64QKVwvx|9^Y7)9Z1QDL~cXZ7z zzEvhAKepaDS3D?apR)T>JE-m~c+Ly-i(+7C>A80seDu6K5@mSUZanG7Sao)o}?Kc_d0< zv}tVW9jEn~c2+^3bBTY1*5>NY#4jik|KfR~}HdLc71O?C`z!I#(2+FF$C{}`J-ftJ!`pD}O# zcMq;j&i02i?do#gyj8_1h88lSKTZifDp@?C+*S*dGpgy-}hbZ=WG{&Bu6f8k<# zWF$c8l(K(yxoluLL9TYZ)}^8crAb9!ytlq8NaGgbExT;59R@kyFsY}OoxKWPCz==c z=y2Boo(sX=5LSmjTq|%pozTe<+M8zK>g>%?ZI7xfsC?`*RzdWUXhuot*zb z9JqtXOj$a!K#|8$rV)IX3J+h)P+sGsW7REf*>wv`&n_NJmp!E);2Fm>CHskR_eUBO z@=UE(fn$GaedZMsY_799*DeWxWBPgOkry`s@@SVpH+8VT3q0ff>3@+9DjayH1wqD< z4qp3{wI|mBUSD3*sdW+$+E*d7?Fayb^K3n49kx1_iuQ4=7rB2!Q;1MXRV3MZMfT`A zzUkz@%=K__WonQAaD=Sbs6_4B(}&6y1(+9rY>u4~)5-mEA@8H)-TbO3@U(C3bWW7G|{YNMfCV=t=G4-X$nK8W4mZ-L&!ZLO7j zt-mG?{wVu9e>(*haX+F~g;}^)1*zj|t`kack6gOSkGUUPa|r5{I5rgmm=A@Hou;#G zqK9>p^#}z=o0MIc#!OazfybWthTa={^cP;-d871xi@=j7+CA*Q1jbB8cQ2OLsGRO> zpkce5(zY(vvW8;{x+pk24OH&PT8jqbcSPlr1#*=%0$(1-@_HB*ak-`HR?qk4h$UQ^ zv^Z%6qlQAU=RHROzA8QwEJ4gC?l6dl6dd;_JjDuvx(#SL7l}89-x5Mx1^SHlXESBR zxm?g*3=ULkx^Q-788IHQRRb7~KTE08JDJQrjLb4?cds(&#%pmG&balli4||GJGEv? zTdQw=v5X0509ES-4()U$=NWp-Y4u^$fEl2dR_vAN?!;Y*Te~0{)2PG`wt{;y#S3=5 zeHohWi6dao+%<6}x2I28^V#8c7Du-9LMTu6Q_eO|Ko$V_pv0diae?R&rsNsAQ+vy& zV|VvS+3JU&Ti4MGi1+jA*CWcbkU!^M)6MIE2Qoz{>{`^ea!1Wx=z8qzw3I@a)SWZl z+mI(_FFF3NDOZGM%W0bL_Ifu@XqS}{rTFcqxW^Th&JX5arJXp|++6*=6VWxucfy5h zR~+$LGjx*ewO;1GItKnZh+VZo;YLI>&ECp;#Ia15SacR`2R5A$=bPgtZ8Qsyz6p|A z@W)?yqRxN87Iz9Y9cmv*$g~huqsy)9kdugv6VF3R7MO_AXa2*>@{+J?a*|k_7Olt3ODZ4*> zaQ0O>1V})Ste_U=j}`fvG2uF8yIu(NSly;JLY#v?#PGcQkx5`F4-TQvkvnZr6$E)K z!Nw1BH9lYg@PR*gz;(O?;P70UAh_-NNgbNsU^@(%IGJ;s!AaM3>^cnj^pDNDh9huI z#B6qolSUIg@e|I!ve&4F_~DPiNO4#P@%Z-0Jcxanr|g#*sJ}qE(%sfnEe3>HwbvpT z94xXns@eJ6MvnJB>r28!=X#28d8XK3v)Dytp+j7;)>egf?dUh8|)^RfbDgNGYH61eL+ zwrJ(^(-eW2dD0=UZT$p;!rRBKac^%~Fb=YH$GnJd zf$sHe5zbJeH%H-e7UXY23b#BhWbBjr{YI^$278oA`CL|5m1)b<`Dsm)ELYjfsfkqi z%|d9$&0UjUQqkI3dkxp!RAfTJbCj=t>(X6GUqzl@t|35EL znE8Coquc`dU363uRCBo-IE3#GHip<I-#WAwQ&_4LHwEam<>t9N$TU5*UBDUc_Rn!T?XbC!Z2mp zW6J)6I*byDSJ;l);0AxPHtXGacX$yG_|YN2jFCjkh~?=0ubg>lg(|KEvdo|FvpZ@h zmYNz!1HzX1F;yrDNx!7g{kjen}S3ymK{ zACSXJ+C*yHVuN;F4)VtDg3A~c2cj3+`>c!(tf>@ zfCTZTs9U`5b_Jb`b||ntLqZkq+DpqD8kuQYd(R5tLIxRi3rPYGzT&3Sc-utJa94W) zjMDdkZUv*GR?q$#@U;CzAHDyt8Be<##{XbO16?iYsN)6b4F38xXl+%%wK=<3TX7I% zqA|MoitdwhTEK8oLmmls_87=ZUCypLuK>ab6w6k$qAohBv)DAZJ9bh?f`?jT#ISR_ zov~Q(&uZ-UcbMW{=s*&CY<%#*$^?eP8zkK*$6armgK)xhk4eqNJ@9R&CdbD-YRAPP zdGq`Om)U0msw;ZtTBpB_$^ebw_Q-QvL@AXGqzso&)R1V%>dyl zrFho!V31ACA>()Tl!tGTio+cjqPJ_{y}k#IBFrxyM1RdH%%6u*T7KuW=>${)SfSKk zjuyGd@`8#;i7UzXP0aejJ)nw%k5R4Lz+E;5{k8eV{t*cYsUjKVZ{qA2*a9c6S=fa< zo{Hu6jguYkeZu|zc_3gCb4E^qC(>7T^R4;MKeB; z8Xe{@g^E0R2_WBq@yGgdVGnWLNs@LwIChEIKY*-$bF9G|h59f+&7!yF4nIY;H$Iu8 zgc3URyI`pA7@>BiDEsNhJ$sdJHlmOMxPgBL<-4RJ*7w?50wFLP;Uy?;SmqZVW6OJ% zsCoSUDeEQRA}=J&GsQV~4giWtccVEjZseM!QcL%_*+D*93p~IPzp|+ zfk#DWACC}T3QG#y!xu_y@;W>hil=ptde)dRVDr(~yW+l*ldOFIN#S3ek>8=L7D!Dh zj~CwpVJ1bI&Q4@bqe>41R`;5?N2&LsL49$M8fNtFc9YD8ZpQFHfl8eC0qCNA$hwqg z>fC`pioI#YRon)O9Ko={$jZtU<9ZmjzvNJjK$7Kr%~~U5?R|cx6$&Mb6km$ME~xm@ zIX(Uia#_5Ly@HFKoKl!Wl5ww;A|(^Q%S!D+a2U;(UEdXwI8OFbIAwt?gPAOb zz2BS-Ztj2m-ng51%cDY=viS9dxEbM%>hSUCwOx^$5wsM(e%HZH?>z(JMLRonL@9Y1 zmck{pKK21CcW8e`LCgE2bt5DSk}yxRz+sY+b41#0`?t;@?wt>F)e+ns+c1>mT~K-f zl8F~?>g89|kkhZzb2jxgp}Po)@3P-tp_oc+?E)+N?cjZPnWL0i__zAF1cz)lCH z6S37-a^my6`qnqx!y%%3C4Tzkix)5C?He}kF9P17oM!N)3cePVJErlyG0=@kGG`td z9zH%MT=f6Bi~(Diol29~PjkK>53)xq=)LODq|hRhbv{yrT8FHtqNeV-PWQ5B|XW^Z(=@+ zntiJTOFx8&wLU7GUBM0!DjEck5DD^2XBP@OjHRq|i%*t-;lkV;XUwz{!;BF*p-VUA zGq7S?H5-I!PvEo`gTIglm~Q);mIJW-RM7Lm7AI>v7sYl57Aa5m5%TQ#bu$A3l>5{$ zBSdeKWMB&S^7 z_*T3=!$i2p)0^1$s$&*&0q1reG<{B|v2gb{@lxu_Bhjm^`-PsJW0PGP%os(BK-gcG z9O&si)nCxy+Zf~PQ3tl*b@-Z8T z>G_apP7IX`@BtqJab>!?8_KFyR9IVz;W#jK9&wXzFi!UO<$q~4=cXag`@NdpG3y;+ zY{5Tu%H9Ic&G_ix)Nk2};GFE;SuMwcbJENx{M=D3lC4E&%RIQgO}$P_E5Lh0L1f_B z?IzQGFt!$~&o4S&rjwom?u9jN>rfwH)dwC|`Y2^XhNC87%^Z3VOV9bF3$(dA;gaqs zDW!kp?^SFzblvhi#H0s&iN%C}eO9$M1X^b9+TAMAt2W(%lx3yRy#R`*sYM`sMK+#I zd5tymc&bQIQ&IxiGS#$Bzq2!1Kvi3vnXP&BdVZ(ABF=}V6jsQ1cirf_om!HjEaIu* ziDgD9SqtvV*Bh)G!2i9QE}r%BvFW4Zn=#~^@+9WIyFWg*R@o!^(`U?8#j5)kZCy@g z!`&2_aE$=CY=8HFK)YxPIyxm?w5`pGNr zJ!VMMFRqlYbVn>I3Y+Yj=TFl-a*r3H#)nzl+G@P}NuMpVkEvle5iF~zotMq+zd8SE zJWhBR%uT`59`AfU;cx-yAG@KyZrLclZDezF&ywye07k_*2XsOXXT%mT8#@6!Wk?0B zS5zH3`VR`bVzhI%a6#Pw#iLx=N_}VWo$!J(w{y^|Bi@2#>%dBc_CsQL zm~K7 zFqveuB z&PyLzi7>_Jwd8g1c2Gvj&V}np|t- zh{0aTrAcl`eC?y; z@;R`Ld|e)V+wR`1@2SpuY0Cg`;VClce`v{?ysr2Z24AW zCR7j0MRyJ@(^c&V>QTURf9A?nLfSr9KJtuuAyRe*%n?n5dv~sb)PRECw^Z7*^dX>H zZEPG zg66bu->x((PhS6+;yAzviwNnOSBJw(915hxh1>!vx@4^}7>$RwzLF zCcJB!u(JdZJU=dUfa0O{EvnmKo65y3lbf@4bQN3>NpH0e{1NoDWliAfsj<_ec5%_s>^DA*$j#Xjde}fqgUSL*NU7{p0y>?Xx3IOb zya@&;`-|Z#(mE%Kl%>V8x~py?GF5J_^WX?r=66ObQ6-D~iImqr+d<7j%n@boY;{}t*0u1Q#u&Lhv^^RZtym#&`Xs9V`dsUx;IvFAQ=+9>phwv zrz_-n*oYc|y@TIt%-lWr!Mk$*(_~a|^sZFBct` ze=hj~ON%&oFTplH#klB9Vztx&sr?)=VJhY2tvNG8ZnX)KxdCA5Z65 zOB&lwTLg_h2(>?A3}eu`sBT*hLD1h{2Dk&rBVIGx)EY$_v^Tfv1_fJB(G_5c{Y4Fo z{=g(5%jY00Ub=^Gien>(_O=M$r023JWIF&C0XvSxcIGSC466aDFez{g03bgz`Uw$! z57wA3hFOwcxm(`xil#&cAH&&A8><5L1qt)3(@zUmOWj+2yC7gnW&Rw=FLNU!IL^lW zOW_1_oica!FE$5T ziahwBXS~)a*g|)q-_kb!EW#r5a|Nut_MaF1|Nd;I6FyOcMW|F?>UOJ4PjE1jhYy8ZXc=@!Qjc}@wXAW0gckK>@46m~}+g84- z8tE&lmF=wg(i_-0eG0twcBSXhDD|IiHyMsfO!@5fjY89yLe#{Ty!WinDOV57r4W_6 z=0Rvo%@bbU?hsf`%vYNWTq;_*Ai-y`G}E0flwQ?EMV3xY<)C(VfErppsl+5pz4;+1 zgp}YK@L%?`z)r~!?v7rWWSGA<8FBn)qI^G$#;*z85wR-IXhCfbGPz4dc3~prLuY+~ z_I-z95mqJBhgXx3l1f}+xygMsnFoW_BO-lt@Np4Ut13Wne1dl%ZoX8BsXZUDcExG} zULC{M0)iH>nX@TjdkAeWo=n!I8lwU4!tTT~CF>CJm!p~S(v5@iAXe)@@X9(%#yoif z(bjmVknua7^U+BYEB>{r$!vZHGC;HrSdDdE(ggmn4~Hcfutk%%{^5K_X-qE9MAe$r zx1ue}IdCczoUgX;sYfkJ47ww|{8Zw5N{gBt4Uk&5e|(g4Pt5~;WdE!SKjzR_W&h7y zYQ-6W@G4WpSf9rn3pTd;_&-Yyy1)YbcLo>y42nkf8 zguE0zPQ7W&xvkP_j5qiv+~yv^r{bIwYl4y>Q=2mjqVLZ{SeP!7)h3*btSU{oQ*4)f zt{{L~$%xqLd0bGlBLfKZDa?HQKC{<~wO-B}gm-sT%@15pd5{o4S6;WBFvM7BkjZws zL>lXSZE*d>NHsrv6#MwGLV02gZeIvHiqX&CL)y$z@`DIeOa+dZnZq&KbBHO42hft6QPz&P?= z!x)ggYlEcb2MszbjGS$eUBFxS3xOD#xnx-BzD*NCa^_uT7=;5*4t??*OGGH1HK#i@ zJH8A()v`yPE3|$d18zP-N&oflz$MHHSaAOq2PEm8*pF?^+h%z{+ z`4s$^aDa$eps&zxlqKExzV;try))ZxPp;CxGz~H;EELagR^D90Vw5DIWKb zMbxMHGwygd>{;@kTj+Z5M{{leT<2G$7TJ8ei#kG5( zfb4wz+Huov6ON{zZqxeIqZMmsoZ?UL=gks*?%lf=?|JEOtI)sK;}>sJ1D`H@@}9As z|LYNF9KO8Hr=kx8dlb(W91$I0oRP_m(el7B-2?_p3yT=nUa#mFd#W#+;CUD@UZ-K5 zHc0(K;Yb78rn84xM=2`7G!6q_gxm+?FI*Q@i)T@u?J#sUD6Y|lLuEFpVvP8Y5DS-! zIiK#GyINFslTE8C_KJ({k@OXqIcGt{VVn$^rV_2_%!GO%aDN_ZQUObDy(iAas>AEz zag>gq^4>=GrszC=i&=7Xs3l_n;5tzQVS0gRTPWE48XJ->T2Xzh7rQwq_6vTa2;`!( ztX7}~^@3MMv*J?0)UYB5nw(FyR5hC5fl>ym;F*)}icjji!D`j4@G`Okg zd?3D>hP$Ef$1M&b^OP;n4fa|^{F?zpr8?3JLCycA_X%8GI_+C>4y@YoNeu}4^?V_e zZu#B_E1NjF<$GrOrHtF0D!eA9T|6fn! z86j&+)GcVa`Lq7q6+K@VnoOW1{sJ2gx3o7oY&s`u zy2Y$);8wt*e3zc>HHa`j)lhD8Zwu{choPpXI|YD^1ovZ@PIB`-n(`v#TlWgbTn{KQ z6x3X*sAVFO-iHu!7@dT+_ofQ-Jskm`Xrt-bz3Lr@ie2DqxI8mSIYl{zcr6opUA=P! z59l6WMhx#{k~zde=U$INU9idNQqHcj=2n3}ZtM-`X`RARFM|rHu!}w40WOG4GNRQ( z{cy;bQg|=ZuELut!f18lK-+2E3K@Z59rIPRgRDr#dg14;ZAIS#LZqN4xojUom|-jW z&LMF>6j^g(@AGktKa~!UeP{^3oEpuS#7)=nGR{sT;wOltpS?;~L%#z)>=~W&dcqH0 zCVVdOP-~@Qv^VJe2K*q-kRRkfcBlXOnryzQwUT62iRa?V^s+qZ zwv}Sj1Arsq+@zHdCntKbgeJ|x{hf^H?`dT2n!7Jeiv2f_2_gGm-{1PXC^JDMDObU+G>n#v8O zer56v|7E*E+UieXDq>{4w?>F}#U{OHSsvdc(F6bv2=Xe`$$Gi9cVKTmZ90Z(;HJYr z)sLZuELj4^;;30y9rg4Fv6v`*Nzpw^4&CIxRr0^0B4^KrgR(AyMhkW@8qU&Ne5^ke zA`t~(Ub}yO!ZAh}K81i|} z7|#GT>KsW!9%;YXGw$)?CH;#QaHSD{Fgn~^1)guhWr%41iC4O>+3?5!+eP@r;3;%+ za&Ut@qMb=&HfW(eII6zyRc!m3(9IMsIwps%7{**ruHJlmmER1W1Au%~#`Z-Vvegr7 zGLp1=tAGKNVBMMnu{afzE$sx8R{&FXfwO*^VriuchPf%_&1mx9<9x|y_j&8Uigjpn z%x)Vt=}mKAo?>skFb_p7#x1NsWC`Nn7Z>JcYy*5oOul23-&wgVdc#TpY=OFr3{Lv( zyB7s5p21YV(4zN$W&aMD?|%fai=+U%Xp#X;(iDA-zt+xTM#no9VRyt|tdv+6%lsg| zsc62$yWFG)mg`Gk+4?fc=zhqCjkBhGsDOt)DWU5!^{BCWf`^|hOlB?aGE4k*+&N3v ze|)2*@c)IwfnQ+J4jRj(H;E?18{UP^?eH2O5U^>wy#v@GRwl!RPGJF~ow1`j# z@&!5yHA)L*4jAm@LS=NCNHPY;n6AWM8Vbg0STc$6mmP>0*_tIAA|ADX`f#R&(ONez zb;=K@1MQuS&p{xCYR+aWffo^@ay+d+6VS?90vO(a%d6~bNpJ{f8tG_40U12+>ak>k zNY)M*HQN~}P^SOg9!`d9PnZEU@c#Xr!POe1I&kfAUV( z(nQ`4=lW|AK7Y&C&`_QDn330@+AyPQT3}#MbU*{S4RIk5VxqHePU39d)xdL|dB!(( zDe9iK0lp+Gkweg>->L95(qmflgAL8z!v4*rM#CY4@*BX(rVw@wn#d4u^uKm$Bu`}3X*}n# zXI~L2CI}i)?4+fEif0+qu*eT4mpj~so1lZC#qiO^dC*#QRR0Uq!x9kiKrqYIC#5K9 zfar7$@w(wBOh&vCtT0Zv)RN1rKBWA!=P%nl#eD9=E6QT^zqH_Rm@xCj3SjvA%s8pM z2zmBwRjl27tDTJm;=I6GF{~h!%en}(cHXZ;A$w##6(Oo+`1z`ZBBjS|&LRb?dN2F1 zciBDW6}1H=nHeKPhai8gC~601R@(9!{*M+Q-}(!cd=}KD5=z}kVoJF%fV3~yx6KEc z&zz8ynu{}vk*_YSRYv)izX09H1nkCi$se>$LT$(%U{&h5Vt3Cq3kq$}cL)j;J62F? zUe*s?`2)f@PmS;U_oT-PRZ6o!u~0JmRR7)fD^>-aib$PnfM&r#ivi{_XJgT-^hJHf z-oW;1{{q^1xK1AwV7zquS7v8mi-ut3L;E+z-!OXj{pVnodt9Ijsqq!-pns(-lBZ4O zSpftHriAs&f?TcV>1vkZ(b5nwb>G%!i7RejxShhl>>i{A(itXx_J|jXoi(L#py=|& ze4;$)9r5*$o7Zf6hc`tIX|J+_1i0k|%WJy!Tqj4BU3Xv1@`g`l>|(xPp=L*?PY;8U z6}IX+Xsau2jQ-2uu19@V0w=1|6_TKWoE?C*RI*-KBnS4&&w`>GVF_Pd?byxH)yQMe z6Z!xd5Z5=tc)qbOe?uLJAgrJK&I&H>1N`OLMZQgaTijE6La0Sx%?Vw`0MI#tpEeKM zX$CRxn_Aq&wd2{Ohqs$0tY;G+7r(EV%q%kcZK_Jxjo4dju2lc(-f#N-$r4`#DP&AYqAh=%_Qi`828Cd_gy<~<#OqGPRs4!A zhIs}a5%(4pI=ZWzzJmG5^Jhu+*-s#DLUzS7{8dnO)2AS}n6KQ>j79npQA*lk{y z`h~5Bcv5=TuAwykZqGUT+}j@>#GJA?7HLeQx`k_Wik8Ta-*g@tCH1sX3sT28Q@E%Q z)-2?X{x?Ln{D7%hftmJ2$0?Ds;t|32U`fvwaB>g#wH@q%$l5>OD_p*1F&*aC#_Z zLuKMwd$SW2(~Ad*w9vSURa)yT$H{Gst|C7SLiFd@*Tvoy6Q+`1$HTzY=Vu&e2Vv&=+%%6u@XF&(HD zVEOiW!ngmvc$TNigp%(y=j}W{RZ9+a`4j+EH0^dK!=2qgi*xRTI%yu?uolck5rq0N z=@Lk6d0I6eNk=nFOd=_mk1H$o`OOiq8re5`=9 z_b5}lL4^mq337UjADq3j_^QgD>&`;nC+!7Txy!$I7#@P*`dRn`{v(Mvlaq!IB3<+G z3Z`9Qz-|!n1H6)GD*SeY;D&;nKo{|q56p6@&QiKAQNl@v*IxsU#Y);ron3#h&HGD~ z&ET*>6vLuK8ZS&@sMsIhwrb>lTW+)qxP+tNMB>TpoL<)x{X;u=v!mhtBeYo7@ZL}} zM^0!~pDh*PR7!0O=RQ_5%IDXX8&?J2qnp4TomGfcM6sBtTem?McbKK{Zu6E8!8=PPcY3S2i-D;Ic z9cUU)+^t~CTH;;m0lhlq^$BRN8R-}7cYv{7YFRpQb~X03NEW&c?-12qyM_^A#eEzt z^{!9=I|%2x2=WkEr6uaiD$O-@MBX5D*osct70Ed1Ot*D{2+`)gYVS>JQ@P}|)v5MV zQ=XMcb0*9onJUX~=(CBp@Q|Ip>N!tx@60?eFDEJNOjJXi6@GNzWMqs!Q}l$u>EiWLhQLJ&XE;aN3%g{_@Q7sQ&8M7RY{_26a)Q z0U+M#a5D|@C*FY{r7|i0G`qfT+(-~of(pOoX^v6 zf`s+h|Izr_|+(Kl|47b=wh8vo;|D9ytgx%NUAze_g^M;p~4;kYYpUY21|mh zuPT!RTzBOoQbwpvI+L024Z!A8n`Nl&+~VpP6fq`yQ(B z(1`B(y1Rwuz#=}#9?&uI;=Q*kJFk1iIaXEysNt!~--jgsLm;e{8tO$UbSkoZN^H8H zSG;c)%FvZ>9b^DZIiS2N=A3B%?r)Y)0w8r$yVlfucW)-MP2~_^xV}L_qjcA+-~NCJ z`>jDqP5qC>uZjVylLbX91vU`k+pJK1R4#r!2S?eN{{;#?)i8U@+a-Sz&p_a}_B1c6 z5X&f$@2?U*@e+zH$lc{N)!Yd!nY0cTYojq(q^+Yrh)Z+sB$S32?azl8_vEwKfVcW3 zo=kRPeWzd_)IG)i*AUEO2#ray3QFV!;&1EOL%^H59i0O)Zr3X1GP~wsbe8YR!O=-~KN=Wb^#1O2I2Hn4;Gb#c(Asu@LAGyn&41)g4Hx^4yx&~k$a@(JUa_r{ ztm$*0k{NVu@u*QHaN{|{x~0gm#Jb=Bz}4{{{w-dS3>2=NIM1=5aPWPxgf8M#izh>iC4 z_h~e58B5G48ZwPo+>~ZPrjP45P)=@0u=c9^*1S911siXEEAZw3)1i}Jn#)?f??Zk| zN2hr}_C^hC<-P~Ogk60w>D+JQV^rN8#2Z(cNFfJAq2c|9$5!S=d`7>ub4b0o%EGBT za&BEFEv4wn#MiH2fpaY=$kim(w-yFt`oFI)$}L{N)^eSwZci5H@8xiMvG(-!xcu;H zmU)qBxmBSV#U)dOYYj@p+}Vze2~FD*g}5X|;eAzSW0pn{?tFm2I6z}ocSR=v?AKnR`D6Q`@`C+-6C~}y zDI#x=!MwAG^P-&xY_(w>H$cTw=q>Y`kAV0vnbcAsR@l;mczjphOZWYa?=b5phIT*h z?djP=$F=j&d$y?;nc?ii7GrFiV;vgnRK21T4)BJ@UAlEN;(%;=4|qb2HaTayXnHDT z6agyB3_*Jb^P$qBJY8=Nuy^VHVeNu|gpEJoU|aWedwpZhWoz!HZMZg$2j0LVwcsg1 zn(TGhb(sI!lkzoyLg;bQruw7YGq=Ft{)({Xn2{~5HKZf%HcuPhf!n)PsCq+N;cEEq zK(X6ysjCHkb3!itg~Z^DfxM8#5@da%Df`Lo(G}-w-tGz_esA_MMW$bPWRf(p23=>> zn5z3osKAjmUd)5%qcE#1^xm!@5~cqf?usJ01(k`$Q8t&y4Lr_kZc8tr;hoMdPiFOG zuyy4lyu!nC7dcax@+s_(J@&@V?xdN6K4uAjmG#XUcD{x53tv;EtCWvMH)mIXEA6|m za%LVk*~}NM&)u<-%BJokqzY|8ITS^-9Kya7R4UHX9LcEjW<=o^dh7Aj$%J>khh;CT zkG2#^26$fm{_0eYbh?e3c4tNB$yCYxb1Vz6z59Wr!5Sx+CxTUgKu53~_>wO9!cwQd zUeRbP^dYnIqb5{v!<93vHuaI01>1oV>{j6I$n8AIM$>`0!DdpU2i3tvBcKQwo%cYf?Kki z`GDp%=E8R_%I%raN`r?7bk-PZCnR~OYUh|HJZ6N$Ck{^tbJ$;rEXtvHUUHCSF+1Wc z&q6KJr#?;ZoNf^)^j0o(SBH3R4%Y&agQSwo_mV8H&anHGxJ-Lah}V92u+;&eh&`me z>&5!12W}HhQm0Fwf~SkDfriQVZzZ?(kN zC3Q>UyRunV9Vs4;1mw`V@C);Rp9)QkDKj&M zpTdGn>(&bnNqwk{p&UD~9Vh>QNRZuGYq2x?j-njRhf7;_90=@F?VeYEIh06H*1mKj zNMWZ`BUQJaIcr`;yOCjNFRqtuZZ47;*_8}Xsjw#x!VJZgljeG&6bowDId-b5;F_Ie zd-z8fa=(0?aBYjt{y=8NE^3##$!GZ|7C>ZiT~X`Hoy^-aB4F_xnJ;-qx(dIom~oW( zR8~?CF zp{7}a;f>*wSB~m*)p&ba91!Qb%hVtNs?iP0@wJZNuMtEf_ONo_{|&Z?(PMVsduvZM zvaX&YA;`4XSBpktjYGo{({{;Iw`EN!-KBX?In%df5pUHdx#j9Ev<`1Uo<Tdd-pQc}XOfW0ttbmEA=aHGTlekqd z6)i_Xp9=}CFf!CSb}WaPLt{6|mKBBI?fWlVQ;a5_aT?o5SAU1WAHmS}5Qe}pHlL;` z_{Mk|H0Ky-<6H?AmbNb|%gXHggfwVBIm>~U0(g43VhfT+ubDwYXeULsE zj(6qy3{l~M>uX!L)$QwZ3AO#ld9GVVjxJs58V(vi$*)18qr`U2tUUKnUI)Og+6VoS z;t|lcY=49g<%7e{3euotJ`Jk*#o*Q0Fy3+99&Y^M!x8Q)k}skqilc-4y}sT6_hBR; z3ZlND$N)Gitlp)^8l5Xp^SxitZUl6!az^Y1|<0_5Ss!x=u7_lL0&AO6(oNS zNJOr~@iEEpG#OmIXHVw?#ccpec)eL^iR!*M(a z%4!JZ+;N&mJ=GRUN>2k1>}Rtq^LHOU+~`mw40!Njr^!a~xxW0C*f`Z{uvqbryB5S3sEPyg%>uL)!Xi9O_(H35u{ zGB_#sQL&8e6Z6$h+LkAT5zNh#o{WIU>AKe$xbTC}$&2Y-fF{dO*9j;^`5!a}a%$AMOK zkM-L6SKHrGSfimwxnoYhSBkb{b1Xfb1=xd@nSeMR51h(Y?Ozv^c|q|*pqj<@9y;!*e#Qj4s-9GNZ57rN<%a#00GEyu%WUPP#}j6V3>;E z)C>q`i}<{!F9y$Wy8A>vHMAgxrs>;@J%)fC7JiX;3qB#0|w_McP;aEsfQspd$oH;Gbx3p;Hi>mc4gx$7Gi@U*#i_gj55*#w zYZ-w1Oqs+sPdY(x$Zsr$(4)hr+=C3ACMk;!^($hv9XY8UK(Dz=pw%3A9-0N`-(6Lv z>&BQAbHuN~{y8=F1zfLa>rW~36+ZIM)E_Jc8}dOQ(K~?TQP?z0`|Q}?^j+BBVKymO z5ywl9Asn6^Jm5B|&3O1?=|qpoAFa_0FY+9#U&{s5Gdn+{g??4A?nE9~nz)RyJm{2N zxqaCiT3~n1o+%&v>Ew&B1$%Q0(3wEOBpuJ6coLbk{MbGIPxqog+rKY6)f^hf=Q1`U zU59B{`Tm8xCvSYa^;Da%fT))jqY5r^V|3K~dcG(#yJ=@ck?FH~e%y~Zg_}pdxl^^O zgI;1BC~)YN$$@rXIlOTOHw`_$;zusp3Wl~_h&PMO^vL#g_>xR8`vLuY4-^aZDk zlQ0dSmU&)z`nN;9e*ihKm_W44(F_bS^-T3wzD`pJ8Ip$L=Q%Xes*NEaZdY&{d3_$0 z{8H-ULD50u!YBFcbnYNjkgu3e55mW7EJ45i(hJik(0@g)x}Ud>jrqV!{upoQMEmCFnkkr4h%>Q20KFQbH{K4fi~Q>+*~>< zI2>OAUDdyLy?->pbJP7U^8OnLnjC0WYJOVBHSO}q#CR}hsFFC=^Lhe04YW|e2H+5lxZW5AO-%ryxs*qZaMB^nWj-BAZ=&1U2wwM{m3jx(F zIM|l%{(bhuxH$c&;IF?H7uB+iVx5OQ(RAAC`&CxJ8>dIee&z-#|B5vw%X%tQ`xu=x*23*{1|BB z+Go^~Sr?g4lRkZ#uPpER$0xz*=+DQQG4p#-{Mf`Bf7O;FS$g>7dd z_ERO@f=2>M^QS5#25mX}DjoRP>W{oEeZ=YpC*>frrP|7TE*kmb0Qtq~(pJjyhclI} z)@_L+CmB9C{m0;`IIfie;c$#A4J|DTLc#(tLyHegWwZa0&%#6872HX7Y~*^S76+atxAc>Uy2$uo0TL&eBB`d|&_c-2qK4e$2aDnadw<3}=tP3AUkX&kOp|YR_Z9laUP~dpt}_wkHOW zl7w2Xk%I<=BaB=v{y41JFgnNZ#?*g(7#r92=Og)bNn$(DD++#S=Xe*}{V9M9f!F@4 zLk=Zsb?H$PSCv_cfQ7*o?FLyyIYf$|7&<>Zi?-||L-OZmu?kl%?JEVB{$P6ABhw2e{`vlCX^L(-eL zCQ$3bbDWIBXX<4@Oqr(`k@ zc8nEGqNt5}#%2Jt&ex^q{dk)nfq1{u5;*~HUWc}jetsvyp~vsDO`T+P%9B%v1k8V2 z`3(S;?Rj0r2U6%Itf--2=PmgE2^MwWXp5vzM)mZ zM}X|rpPT4!i&l&sEmW$STsV{;N7TUzqj~%p3R3Lqw~J6*(W5aaV|cQ}1K+fjiJq$Ut>dO^C5-eQ2#%BoceVa-V6C8vjvFwt z-M8^}@tjl|w10aN8-MLNi9h@o2;DyyF-LotPq`h#<|foZS;zW*7o;p;NSw;bN zM!p3|8>eA1T;*HJ(<6+w;d&tEbky*0?biy>qCye);3xq3FRPI?ZQ_%s`5lWJ39RNz?<43=P5BR-J#sSVj$Sd`x|n3UhmNZ0z}VEuqS06+vh ztXF#HXQn?Ns(%|c7Pv;gmddYheyo{4cg+A)Q4*fIC-%Wo;KpvDWMQ&>g1kFHOqeoI zJUHagogq`b2afBK71zkOGf6&s+gJo*aGFW9+{kqlbqygIKeoVXk6Iz>-^Tv-Bq3kq z$hf<)fByFMSH8#)1TQusKtB$CVAr*}BU_m*L5zOeE)Qgx3&lM>8GmL-WloprR>zx; z>mn5;oX=oEsZcjXvdYOm42V5}gTr}-~DzN>y=|0P7> z=aKu!yv)pG8JRYzKVs}7fo!}fRq+fOC-z$UjCbEJ6MKB1dqg-&;u)Q9;&9TBS8pjL zAd(TuZ<&c}5fze%(*dzL}dpcBJma;Pm`5y2G!IJ*aU_q%K)*?b;L0;YpCte8F zdV*hmTjlOAV4#{YK&{d8&-?>k_`f}cn$UqTOUT`e;}s%_ix>At77pz%1d@?F6}XWF|@?!2(TwP%I!DZ-1_wRYS2d(Gj4 zXf)>k`-N!Gp?RI~hK!?V(Vy7Fe-Ad?!4{VnVf8T|z-rWNdg%Ur8gGc_wteRCf{ z3eo}mwE>S&DQ>(PT>1`ayBl}_A;(SA#^5%Fn!LNGM;|m?Xu2AeI-r#(bYjFx9pBC` zh(f)fX`IkMUR5+RN#=i8E82%3`th%k<)W>z52MWF5?BoxV{e|`J?+HT`@NUXJp>v2 zk060_POuYsbM)R+qPWly!KIISg1#o5Y6IOzj7<{14&Znd1ypvtv$+T85!-cmWm%${ zp=7aseqnz(rGI8H|2EYQ#nU3VCydg`$ymz{B{6`LSOPBe(EfRkOKR03ETso!AkTrO zPaeY1i6cy4REY15y$Bv3Marz+-A5xBtdOWYuY|9#l_s~9mhw86cxNh{!XAe43!$39 z6TJZQupNW)M~39jsQU8?(enPs@u-Ni#nI-7pr3uL_yf6;(jQf z?U@G^-d6$^NOvXRY%!c;&T4#+D_(<#s5|bWmG`%WHn%s!;h#Ga{^e&%eB7dtFvNsDD)QuOPRaT z;Ed9T+FwWZs<6zRI{IkG=`2#Vv&@ptW}?&8m4cWE6?lq_2^TE7vkv_|=KhEC55mba zcWm+rksl~WQyC^J6~xG-HoBs%=5YD_?*_bZIjGE9F5fuKJd z3-L0gN`~uLs#dx#zK@W2%%8b(HViMy#>QXL{)R0t96clr4{W#j|MY4@@k+>5onz-U zhJBbZnZm8{K^vf4gjSs~S-DT*v; z`Q6r_#pW;K@id|C*$oB6Cg*ZAgMqK(t$HII8auF5Nb!QbCk{qf8Ey_}`!W6bY{t~_ z)4zhlpU>tmVGGZR_SsecyhFI0Ef_F*6R8b#d%~4aTJAVRmuU~e3B{Uedi}`VyLNRh ze4?l33OQRWFdU9OF_iRKU5e?uv5n!9-y|;=3g2ADanMTm+hH4hm?ZN*#82&=D11*4 z?qqUkNMPZ8Wa15VO}*XhUsk%Y37B>QXtLRS80@Hfpl@;6D_pDQD2E1=e=r~B5IdNY zr^$DUi$h}sWjOVe8Of$n*zQw*EY@G4@E>t-<0#Z7MY;1^k@&kbeEQgWY|Zy|Pw-4N zVB4({3`n;Zn*eJkY@BHzWsqAciA>#>WDJeX79jiADaKeJ2!T05H-V4Z{{(kk^`7VX zwUm%xmVB0>SV#5(IiJI0$+j9nDrD5lsH1a@Z>jFx3+Y-*J&Q(d-PwDu`qUOxo$^f{Ze zS0H!SqDH`iz+MQ36h~|~a%T+_Y&XOIw$SiNNO`kuXJ|4fW=#DJz_vTZT&BzV%E59` zlq&woJZh;xieL|^)%}j^(nFEbGq$2O9osF3%r5QtnCjY51o2vo%4A=f-5DP90q6=U z>^3wsw1)>>1n@wQ3^Cu7Nu?@iojrbm;vPcAAA+#P%d_&wIjg&w_uRlk@DhVGJSA9> z_09BIFc0rC_sGF%Ve>sb)f%d|EX$TJtGYbpYk3SjW@ zhgW>;J}rUOGXPMR1Cz1~)VQxZ$F5r8Hx=>4n;&+8mb2`XK?Jji8NRnbK?LmE%;@CC zII5biml8)L_L-n${RoDXkhFvD-)dj|8{dXMS5QA5u67IAG5|5r%>HObAF`P0kJJ-M zc92x<&+mtsTCPs&*n(~>(EbX_iLLipI&Mim0uzR+CV4?8RIxO%!;5Yj$vFin0bi2e z;6GE+|0}j1^+)_?`h z{f<;A(Vj#wut4X47RFJ;F%jE_XK;U=smpt*>1y064BP;C@e8hhU zssGyUpo9o#@PSf30ya0Q4hRp#`H4>96D_*>RV9mCVl`EW=6tnFH<6|xiZvZMfNNB8la&J zHAgVoAPySy*~jeVFHZ22z8$;cgaOYS`HV|s)|*LWPsZ4u@6Fe*i9HKQkfj1-btN}$ zi*ab|!u%+G{&AK6fEPBNE$vZQJ=>(s#-1CM-IStEJa{IpJ#jzhvjuQ%Fl>z%+)VVL zbOC(1;3bIqpNCGrK{y?SlN9JImZK>)7AVSm&sL<6_`@jgOOQB}QjWovu+1u#fa8?A zmZ7n+@l!#F$oTVcTuDf)pZLY-euI1VXYcmsidOvFbw2YV6VSLPp1z)&4HxV|U1#tS zN`_sJUjjMF5XQ--g%RjT zO!?TFHMO)x!|sM`-xG5})6_Km?8LOjQJifsI!*VmoOAo@>xHvv!So-G60Y^vRYs%J zw8ZcBUbs5zPqp7`pj5CS*@eoPy7YG-Vvk58Ltu@2>Pevi$V|5k0tGp4+qGMj-#rjxBDUM;e+#}pGt^y2GpMm8 zK?@ocP>Y1gzd=G>-{vQ>pBjKa+zt{8J~oOLAR?SWa?oYA&pG0jVQZ8_V_#}4;nqcR zwrC+m5sEz>72tQ#Df3)_I0y^>ERWwt%j3%5TOJwEgVz1uE)cT7C55tHOErxqcxq$n zn{IrBw2Rty90p5m3Jl7&1zL>`K;Il`qf+dxhQN;c?G%AJ+1Vb8+lumE2aJIYv1J7z zaiMEou>>eJi(6Y^2S%fmterYG<}Y9^-UJ)_&jIQ`-yt~bpx)I989TcYGO+_B0+%{q z3upkD))D3CD0fG_7iQPC{RmL~1{!E~oXU}^-^Oy(F=WwUxzA zuJ9MICzr@}Sz7h#MW$|Sw7-4TIe~xqf0g*{`5{0#DcO8?CJZl&1<5cASXe%6Q$WmT zp{m}(A?gk@mW)GZTLm}Y0p5l63e2JcsY#pOpZAf&jl=nO?(8ci8>9EPMzvnb^bI`( zzj$Ha{r3R+bLqGP1hR0SY3D5&JuN%n_Xb*!<4@O^heaV9H zppy}sYT6|GXP^M3n2J1vu`@%8m`I6k$x5&G9Qnx*@@>w*vU`+J*YPkgny`@SpwDN zX=n=W5Ob|w=q=GLFd(fzyWmjxXbTvgccKcaD@%=SE7~i`X^{O% ztnJsJNXC)4>HNnq^7EYAcoJ4BupEmIi^cVclsz~^-j;H(6RBI`CkD$M?SWgiJ#cJN zAA+AFz|h+)5v#$mJ4X|dKJX7@;?&-Ne#b#5F;;fxF7&9u8pvB&%DwQf1*owN!>9E> zT#H5otbu~&Te-5JctP$3{bC8A?cy&(e5jC$q#KCJPFW_(3%*KKKe`e#+g8olw+pLEaGNHQU4Xs15>T&I$UETo1D|)ilzER1@g%4dk z?FQ4KIL?pY0Ni$;Fvc&6AwJ5_Z;c-yIpwNo#ts|7m`q;!$IbfBac0o{B}o0;c)#(4 zp9dm?KZ4*l>Fb2zGpUz8WT!hkjos%z4oV2kkk-WE3G8XmE*$P(wNg!$d=3PXamrk~ z3*r}MAY_Wxnw(XYzSe{$3ZKy_z;sFn*6zj`*FnldAl3m|0ULJU2{ zk^8<{LL~N@UdNXBFq{p?dr-sgo|6%>i~D_X?^N-7{+<#3cz1tUPti0G&Rpv=8#g|F zfEv;g;5lc-+=GrX_aldGAxuha85}229;ecvllk}Vo*&seWqied_?!qd@YKvva1nlH zJ-xbQ)BRfyR=%If_?&GUCjCg|#sks|`-CWG9#P!bwL{(i4GS+do4dmEj7$wC7TzGX zpkVwpd~^cU34cg2Z+!QPZ#y7;A?j1bVybJc#{nBlWw{dRhl?LC_$Xs9?tzMXBpTP+ z0ks@4rXFrc@C017;W_he!QWfimJ&0W`LCzct@;CW4Pm+X7;#<=oga}p!t|Tigwdom z4BZXEHkwYhzgt93!`*FEyY1KO{vwM3TA1;ieIgS3APQK55TbgzV5+MGNVN`uC7>DP z%r&siJ*z1-Mmg2(m(ss~OMfS|BTeSM)Z(ZsQ>RI_;m^>Y`uW zuEWo=k~dcVds6HiwxrsupTYbd+p}+%-i322mW&+xzSJT&CkYQxAqHKdM|+i za{p5@CW#>jQ3cC^s-0rG^WggESky$PvV7&(8&uWi*K^0NgV(hKfRd`q?}sUG2G5Ki zy7UC``R6*y;KV+p0!U=N*2pvUm(94RxogHl%LS#BXRqwS!ghft0{UG&sz#})J z3WV_`fI4m2JUvV~dg1Ox)~oHnwQ&F%RNid$6QtW`_wZTXoEk)fG~e}2dr}O3VgVk~ zAPVmYkiqc^S7QM%)w+D_0~kmM$CBU7MhFK?e_t&Rl z*!5btm;cJ!!8AY{MAvph1*~8(9|WRZrzFHtA{`+b$Ivqs&QcQm06^wf#&DNVb)^rCnym$ za|eY!Aa$7?7DqZNEM@ywEd=MH=DAXD$*qo11}$FkTtzychG1gg2$LhKX{Q#Vudj?yJRHBDPY3@P#^Go7HKBIZ z%HSmc|M69;$7y!K^0W2DF!=utL9k&;$w^F3)k5l(^a{|aVhOl+%NGV*0gt!f-UEXv zM(Dc7coM4ExJPuC@oj$Y>>sr*xG1r?phm7dg`g$kfYSRr^k-LzV04~x_#Mf=nvku{ z5HJkQoYL-*+%B9BTP#qc4XH_l%}+G47AJq@lvh+Hi(6VKf&=jdlCt>1_I6Lr8Ts3R zWR+fD49R*2()z_E-f+1Cw2XWWDH1uV2r^XqY zP7(X-z!``7=+sWmS34;>!M?2b{+ZVz$44+^jjm)iy&o~TPA6!|D7J#{L3aeLYJL)D zsVcR>`_VJLD~4GIm0YYG!<&NhJ-wH|JSn9=YG74OwxXD5gPGw8CE$+CR~@-n7I`5B zRRFVBPN@w*^Kl4qkZxb>?L-E1?oMjd7e8N8qjk2Wr+} z__W}TN&nf`Z<)0VtVS5W8`mudnBC7(e`mQ4J(4Rn4?k1QuUt!C-K%;E1k})4*o^1~ zB-e7--_d9Qc@*D?dqeruIYHJm^zFsF%63qtX6Rz7w&TSZ<43Jx^V@?nve)~MS~mbExAxRAJDSz>rSs^bQlRBJBQRD75t1N zsJ5JM8)FY)I(1OG(Ik{_DA6yHK~MfrSF(GQ9rOPKRh({G>=R?{W|dG({QP4U$W)Y1kO*46>vpV z9BpKdACcB*oFOLHN6>^$P}z6Fw5{PN?ZF#c;0`}kxfZ+JI+-qe9)umaZZ30+^=QNq zdRU<)n-zKU0fMK3t!4_(rfp4iC7xm!KQwb^fn!=x-LGAQkTKy?e<=N0=H%WqO;9-e z9=1p(aR!Y8oUSG$ItE?fg`U9u!ywXlyf)Ppb-M1`rQlo( zPKrel0XjWH%~!8U7+ z#uqtK`4Al}0FNqe=)15fk2TcV+vuMRTRah~t+@wN6m1c_$GR|x-sFMmP0 zzXgo#>iHfi8&Fz4#}Ku-pwwikCW7%`hr}y)i_!JbE_q*QL+@8ib8xS#m+GX?Un2`b z*k3EnIoBw&E}98tf*z9zRGyB5r?b^!h)D8}XC!UeOpCPF%6kQHo+QW+TNr0Y0GUr1 zfK0#w1*?SIH;<2Uzv3b)#ji?s2rhC0j zDY*~6Ki=k1_9gb-QOr}oUY|8UDmpzvt}&0&#b>9nOAS1)G@-c9ZZB@`G9+7ti0Lh4MP;7gO`Fw+nv#YM*OzJkv#-}r#)#;u%fXP@ z-r*rx6PSV>f*nL-A2HJZEfQ5S64+;-SzwBT+5L?_F@CQXaN`)h#T=t$4K<`XzW+Y) z>yCrN&!{HcAMKoXYhk`{4mX4xOuzP9LH6}6xlAH{_}LDU4*vYs zmrgOyJ8N-dtZ}3f1}E(_W=U!jy#nPaz&%IUHkG3`+y@Zf) zNPNF`PkxWpQa=s&+C8F+*T;S^Bs$LXjZZ6mhe)g%%~?#Lyw@j6#PtoX8)$hrG{GE6 zUjVi`-A|V0B$#>zg?pC(m~Ah7)9NiF&>761KX^7W&AFbu+1oYwbk^|_vzPG^mW5u> zmZ(fMH42Gc0kE&@KqjWBF2zfU;ID*V15TBu@nqtV)TI^Qi};Pkp?^7#h|*A0hR&7@ zpN&j>FBWWcX9`htix5`0c4-+!ENO^XR#xTHS!&E12ahc`NzWfBxD>W9%nc6zEM@l( zuXA-L-|wvt>`&f%v(%d03&+i_$}DcTt37+CKj~|pG_ScQ5~Ei{vp!^E-t7SiD|SEf zc@d-qlzlUFec?L~*LuDS4e_27J)hM1uhkFl?H`}rLT+w;CeaWlY)i8w9u@1+} zp0`ZG{lpro2A6_hd38m((4y9|5clmXEN^-lqP2y?I@!E%@nen( zIz8{S{es0N&sfJ}+UaMTw@L`T1nS*+c(1xvH9juQeZogLQf1G5dAXT9>h|J^Ese$hV;q_M2 zb#sT{ZK87&o1yPuni$I%N%~4j-+xS>;l9M>FpscRUIyZ_0a<7qQ=Wu# zjOF5c_Pj6NN)B;t70sl|9a5;O3VJJ_U$}7ek$~>r>P-<+kBDm*K#b?=q0JFeO7bS>bpO#>~) z7sa7xaYLEpnw$9VlhxF}yP03tJYii@U>9Pc@t};%>_fj{V73h!t`fgkqjgf0c}klg zC+`zjLo_%{lwfIG>_BIobs{l1rl;)b#Yf(6pwtt4r5AWz=}qVo0KoSJJcP;SR|;J_ z`U4B0GF-XcXmg8{kt^od<*3j45Uf@ig8y&c7~ z|JByF1j0+o*p0-ERPz$5pm*rrc?;*yVbx8K92gCfripfT|7`MP9Hhc;Uw-&{O^DWR z?rnPd{&YB{k`H(_veWRWJ3MewBw2O1NWjJGHn?jNeS8wq#dc09v<1{*_|FqBmJxkU z?cuMnj;A|P=mlqS_H30O{naH4CGyC`PXIr?(o0!_Li+fswXYY9$Ch^-n%aAlZNlj7 zYiNqLJC&=fg)-qP1GiG$<>+!>z%4$&feu{ zIrypVxmFpsJ|T6bozbEB7>zwy;W*QUVVB_kZhDJ0@RAnwN~c>H)~jFG{m2QY8d^Fv;Ph0k`DY}0wi(mc2V)W>M4 zuiaWF_vkK*UOp0NleY9N%oE!gcci>Bz{p~l--|fG@LGFpD(1&X0F1-?*Ym}gm5apY zZZzDXOCc*lZtcbril4x}X|(`^<#B%*bFJmJD1Io3QNwf>@}~clz)XYpS0H)tf`X5W zEvUSm4D{@%XjB#}0|b~yw+@+4etDeno)sgl$lXzK+mwtO*=#ZDnooVu7T7YDZKuF) za@Z}N?~=ym*2EvRPiB#JjophPpA+7)!tw9uOx%gAf^FY{ar>(2L__r>WjuqAo)|nXh5+^a zE4mDFH=AJ7b6*pbRc^S{#ufj8s&e_OJ=0{2R| zGB2UVm(1Wpl&esYc7*#HAX6fdh7sSXhKdI2(=Vl_H#XQmZ02jVZsFsxZwEn;)-b_V z-2)%k7Oy#bUyrqn%dd;cW@uRrraP>!fb)&#qmX_Y*y3qkozcm2{anoR^g`j#8$~tD zSv?Hn!=^CNE!qTj+zUdEL3@_JPTP+dgwW1CI73{&*BGWK->u<$nEcj z&&`Ca%p#N|9Q{PwJI)zVbK;A|C{NL~k==`i0*z-`iSx$_`q<*zi&l>tKY$G{Z1FO= z^d^%xI^Un03Yc1Wr%hyDoV4*-UHH^GFY~S;Vo9bXXsqHs$NKiJdS^(y5pZ=F08e5c zwS6vu;R3kf*+;NtL>_c;UY|JZyIh%_;&fhx|c3MzZ z;GxYj3Z|fA*IY)g>jJ>DLB)JyeVbK%m9mNXWv&BKyH&W^LqBitJT!VO)s@b0|6+^X z?7*gmqltyv8C}8#wP}0vHgX=kJz}Vek01HLz4wn~^D~oRA~PSb6Cew;+C}Gop6l6% zwPtgQn*+|NFp&B}V*>*EwK(zEi##NatOVP`%kOVRIE(KB86VdnXu5oiR@ixmz)g2P zzSumNm&7IDOnSm6LZ5s;z|V%eeJ_q8HR#ln!a{P zDKWF~Gmwk7H=7jt5rpZ&w1;-rYc`%D`gHQE+KXKw*n$&zl3gN=Kt1ikb@l*#EaT=a z+eH*L2uD^1I(_0#cPYPh4g7Kws~nnbF;xaYvYgtNZ7otk3)RkrgrLTYMv1yYZB^{2 z<~)wVDCZ5{=Il{UhHSNZ$;MYuHt%_q%Ur)EB03R5KNj>sRt5@yK@jf#cq_Q+RBwXV zjmspB3OC-v`=b;%S3vY8FVL0NyRwOVZ)ksmYlBomQT;KNPiBJx{DnnLZ>{xvzFM5N zVkP0xHL$R+8C&)O9mN4ik8BXyQQ`2!4cEcmC$>0UB~M(*rwv`93VH3^u%jFj9Rqin zdoojXn##;Nvr_d5V|zvbIat(GaE~S=kJ&8cUA6jJsr!kp}aNAvl+v#yM|4`|K~)&=7k zhtT(;m)(vg-V^U7aN_Qw|GH%Ys`E@s$Jy7UWL2&0Do?_0Zk8#Tb71DCFT2B+uZ0ru zubdey7m(g7jQ)!sKq%Au^B9kS0jE!a4AAtjWq>wL@qr<+s$2rrAjog|mwm{ORcM!#;Fiuv(wn5c8u$L)^lXI8k24+YPtjImh3lugM6dlfVk4R)J+(f zm-7Jo!`bKozFMtuoN)iojjey$g z-SAC&H22@kIXd-q45z@EZz+^$?^8a+8osu~M66O;Ak7Q9@yr~ypitvmeVJh02n#pL zDbE_;P#l5)SOvS4oh1MaR=o~5fE#=K%z?P0S5IdpHOs5GzT^rv_g;lkFdZk){^so6 zsYAQnDo%+VUWZaRn}|^&k0z)HKm2&W!ZFi?Nq!7&IMIy0rLu7~cq?JP!Tm6CcQXfn zK8~~WZgx%KcDi$Y(Db;HsXbxD?lPIVURZs!0ZB|tgao>ta=aco+y7CXIrC|wYpApE znfXn9CvDXdUBQWyu8>0LL7il6tD`gdQ1c-tE}ZZ;sjYV_C;3KSsWG*z<>;pv72fp$ z3E^j|Z-J?8@ue)*ZEUYrQj|eKUHlzB*U&QQstYbu+yoV_)CmJ39J-W;zi4E60(yG2 z00#JzN{@2nA0}klj8b+okV&`pv>Xnwc_czP*5F=J@9^sF>fD0Gz=Q5XQ}f!Rt}ofX ztOHe}>tl!1Xy0Bcvh2${u&J)WZl^n3B!Xv+bnUcs0Jwx4!!e6?V$0{8oQ?dRhFtY| zW2H_RSt%Qd8}Ml|^s!5)0)!uVuX%Zd2I;dVK-Twc9ow%NVJpFO84zi)KM-kV43I(4 zF^#`K1q%zP#Yv~_pqnBlaE~K@L`ixlu?Qs1I9c4;b7 zCw&=7<=-d2eO~RUUFc!kC|PRdLWNo?3*y!7?DRJ&^ZQ+frSokg7{s3{yLvYVij2VC zQH}caU^Ftw!0QVwCqsRJ3GcEo&PcY(`m?319KGZUDxR{{sZm_A z0*4b?8}{EF(y*OKEh)JF>JX0iY?XnY-OGJCY2sXTgkW8Ll{kAb=GLZs~X$TfggPiek4f{3YBe>pCba_jrDb$=ygVnz}(mk=> zVZAloFX)(}D{@UcSqw8Hhdzt1AU_unR{Y_DGTb8{bv&phLLE10k0xinhA-KX~ zTvNr{Ps)VPnNDfqw$bZ50Rk(^I9{cz7e(7|H}uBCZ{ntiTyIDNq@%;OK?`qzIDD`p zgmuNb9CAB-O^%MjR|fTjy*uVlg67E;39hzOBVeoSqwM{(w)nbs+|%4-qA-nB);Gom zab|timT@1?w^ZWfJ~gDO9f~*~?1{CHxR?D{O{Yfv+eS4|p!BAN=V|X`!o`jH;F&dm zQmw4kHAA6R;r)-^PhDfhX=r0FhW<$JrrDS5bblsy|4Q)|akjHKK=s!?P+Y96e19{X z;WdukfK1SZxIlBYJAM5N&q@R9dNl4KTfP$E__zM1-ZUynj@--hv)8qG-#B*+z)hYZ z^Q6jUn;avRUXyQx*A1dDFXD~Q>sxU0(tUQAlfyd42?Rv!5#`2_o)j`~rw-ttl26=a z@HuGz&2$-(m`^9USRWA+ZN`&q%0Z4H`1pz=zC)GAK9ntA z5?Fa3^=g-O#t%7n?9qL}kaUZo^7(#!ed*jiZ7>BIjWg%;dS`Gq%OMdd@DsZWw}%GR zshU%{bnL+-vptc|t0Z33B=(jg_Fh%=ZuVVtvf;Vu7pbl{*_+(L>}~8K)FGa5d-#^q z_5f{*W3TR4jx2iBbn|>*S<$his*H3Oj2Z6MKm&j;S6~7x@4m!UQMibv^k%O;B^vBL-!Xvn1VVG_&zXD;3E1H)Q2sTLAkaBU z6nK+yhF}S7LaO(P7Lof-yIn~bLH(372WD}D-2T+8WI<>Jf8jO13HhHy1U>B=p6jTs zsoMtzdkSB)B3+Uz6gPF;c#!B28VxH*Js?PG$?S$mK2__3!yuGZazZ!iO=!Au%SBGT zq=27T0Ncc_dA}&yH_oY{I!oWiMGEc*;cmUHcS)e&EQ}=8Ae*lC>r7BGV>Ns@x=ca3 zEPIAaj*f&~ww30rZf@MblGjUed|^h_l%;n?JP3= z2d^$eom4Cc12v~*wriw`%c(YO6S1#>Vl@7}k+*E$p%nJ|O5Ep=*;iCY--R_Dlhb{G zSo7qDfL=J{)bRMJ?gBCn=65}H?$R?+;yFstres4Hsf zj9zhP#xdK^zY{Q)39JAJM5XJxD-xBro;*e=LG?zqtJe3sWl7{cYoHO7z)4XhV3B@5 zmNh*5$pt9$x!n%wy%rxCrW|`c5DVaD9tPA@*E%?BPu453FD|V>EFJFx%S<1 zK`K=yAsPG1xi5=XfXHUIp_Nkwl1niU_eBQ7POoN;y&K+MK=Fe6E!l(}jo#;yT0&7n zvB2xgr%t{vtO|Z0KzA|NzILIYmlH2fD1|UG7^i1)`paRbs6(yf zTjv2zbpziR>>xD!<#QGK(fAnS&ElKP3#WY9nXhY;Uumc~qIgC8&GC?@>k}-vZPy3f z{d>9|P%VV?(N0<2F=e;BrE0`NF$wj;_5E_QMIs%CAI6K**-zZ4i&^2FI!dsK7!ex4 z39-NsbZ~zktL3$0xW!8ZqmNT(f}@TV4mZc^5`^bwCLFxpekhxoJ{|?SNdYe$|hO1AWIvi8jSUs?Se*Cf3!%W^M z(>}S0eFz%s$@`pv3_k!c4$X+hIDXfWFHPa@pWH`S!vm<^nH!4;JZ+s4nQ8D64%*bw zGK;7m(m>y64YPWpEKTM_t~YApIW0~>iiQ4O6njP~=6eLQbT7oLg9^iwc}lAk2LZ{n z$uD}ao5HW7hg&kg+s7f3ex!TYwbS?xp(}DipNqe;2(fGmw-~59Xxpcx+LKA7x<0A+ zXr#wleo|&uF>6xr{&2CS&xB8o#dWvdqO-btL}_(H*(92Bb2@`FcG};PHR)hI=#+XL z#5;|PogMdo{k*C7s=_1I`bv$*^y7l`N0(SA&fqX{{9P|w(3puQ=+VBgMk3(#ff}bX zuVGRxu2p5NDfhbr1Co)>hCIQ}7IkaATb4FP_~8@r^wD0|L2>!@B4Fqf7kWDE?1ZCJI?#O&+GkqJ)e)~ zV>DaH9644T)4igXV+lvqyTmwm5uD<+g|HTG2T{Dn6q#}(f!i6zP(O@~9#~+xOjT z6&EE~5I$I@`dD5Y3zG`|MXOVP6s)T{k-TP@dG89Qv=@O$SD+y@jVgIPt)S2 zXO6~-z!rwh)DQzr-Y2-WP(f%cGMSqOJ z!DWh(KhZnEr%CMv{jruiapXy&G^~hkPN=`}>TyQ&n&FYb+dq;@)nfQOQs#f6FS4?b z_^T$~tF{=|tADu;9NXhXvB#?@fgohw_>zD2!a&V+-YFxZ#*Af(C*jR~&kHQ6-WQn; z`V0{>yA6@BczxJUiF8BWXgKaKL7#Hw!oY1^_fb8of^zE@VL~CL(=C(RM8B@~CB{-) zr6ZZFZb4?T5XZz6MuqksulG6Jn=AaPSoRIDmeMU&kGjYQH#e^iXef&a^+dG~a?Q$# z@709|b5t%uEd-Oq1OGp0?LoS;oQaJ%xG(0Y@QXC)Pg9 zghVNvk2fexChu|NNj7~RT@J}vX$QOIW4@G47LhMB9->^e#N2)6t4Z7+M(==E{SY!0 zJ_GapaB#ckRzpRri+_J4cupl>{JUz`UJ1i%M7juaE(GCu&Rii1*mvH{B}a78BxF|@ z8QD|LCWi?Vye)})`q0l&>%#r6!}Bfpa)SQR3mc*t^I%deUSb&@jfI(ZEBlS4YYxii zZAlchxTi!(j?4;_fr?Y3yv^Tn902=_YcuV^8wh=&ktL_QGhqq9&`(!s*K)j|b5t&H zcZfhTD+(a1g?Lc;hRDgWZSJ`>Vqbes%E*e)ri|RG($u@qWJw)gAu`Ho~v)Jo5ZRixD zOf(YCrG#hQh%mcCh-DD~R19a_6p;d<=|^+?ehsv__W{IxC@ti_EMlodaw%aKsB&oV zpVT}<^b|s%Y-FF1CJ=FTRmf=e6&gu^0Y>%RJ*d8Z06^QBZVOVA0J&Zzqu_S{ubABN z`sM5vCG^cPfs_C!e}`!WE!7izEAPXoO=U8Sz-8DA7(?2e3`oC6e8Duuzs_w$`ctqA z506fWRb18ppL96z_6M}{EjCy3pVEU1`q35fz{Sw2I;i)pL5AJ=ljzFv0ZRn8gV$R< z@x*{#hBv&Pb=u$VsQ}ivNptKiBSI0Vx$;9=`$uI3X@&pyq}wIsuigA2I;*H&Y;EOL zk(hf~JLz9C-W>-H0qzWr<5ynuGW({LJ!Z5C-x?F(Oe^n-(47QN|HbhIWA~0Za0mwK zW|$TeeJ-si;*Xs=t?^!81pPK=2p`01%(-n1d^Q2b7k~jYv=^2~0w}CLsVSZ_@!IUT z^TCmi*ET8UQee_Cdx?pqU-WNhLDJsxEF}DXrEMT}iNu0#-JvZIL=u;dz*JQyI!NqR zwyd9(AxN9}x4xDp{ibEYP9`zXVQg=Iwy<2FWtHAG?X9+igoQ@XB@!!c1}OK>>owUYQyvX%sHuBI&gOg!9Sp0%`MGhKIbOAHroQQM zv-`{H&+EUp8R%>XN#}t-wR?=$_leV~LrHAVe^n+C(X{h!iXO_twG+TJgjd zoClM+f9X?_RSp@VD8HK~*|&UpyBs+YWQjKV1Qc!!ox;gx7tAu=kjhfxT&K~HG~km_AJ5PtEc@< zG@6t%=!{P0cliH0E#dCMa-Ulx;3o(&YPdqf4QrdjChPI+1+E7>vN z4UpJqC%9*1>?G&PddZaNDIeNfG^8J*jN4oH+Iyh(t#uF6v~xjI&m4x4ltitu;2ijA zl`S9rR%C#oQ9yRiuqJ2`#&%Xo5BiQIg4VFE$Mw1X0x3fP?NN**T6lZ1Bw~Xo?;(;= zSPS+i6;K}}>;;acZsW~9R>>QP7_@JCOLZ}j2!~{u;XvMSaB`uw5^7Tq6aEMW2 zanh*yXD$T%YaIl8k>|iC z#PdMb;NM?Tg!ovIk081yf6qmERPipqtRpa)6oHu6-%$j{+isyUSLh2Y;kGt$E0p`|;JcE|n|?kG7H6b88y^ zI&D>=fba;1!R&>fk{a#E8YRs)H5;{e*ax9x71xFKtOQ0ar|v|pG43t~HjP-vMW*s2 z?1Y9hjqNN0z8)+rIB!Kmso5wxO9<1}*84z=&ye$4 z&AT%U(xfLXp(IVSKj<7g4S^a`kW1a-IT?0IyYh>~&mI{>J5D_@oy!%UM5q`rE;^sY zpC52TLibgm_c_X|rT1b-PTf?I!7%6pm5uC4x?`bgs$0&R6whdGenbFKY}oh%p|h(! z*K8k!p-x4QG|?~^bF0~x60NT;Zb=%> zq{;}(jkU!(Zftf067&4Q0`8+vBSbHM9r}o(_iDNxlDVs{3@HEBsJt`m;oJDzfLp1R zJ?D0)%^t#>G?7y3q+t+ZEQ~O8V>LVx%4mf5x>GsO*ymMQs6&J%LzB`r}*X3&*~m_wWc3 zm6`QPqUtXctP59=pnQzJ8)*yEjtWSOuC|cQW@$<<2KGYlMMr1oFgT2qT2u=r#ZfC4 zi!x;YGOSZDB#2zP?5m8Qe>1xM{uY$(07AP3OgZJpcLN)>N=BZ}4RU*^2LaSjiX@v9 zY1(p3mGEGvZ`(DyA&usSjGN_Q-3()Uu~43uLD4f}EW-0EbwUG=@`QzR=3J*b6FsdE#on|wXsMVBGQ zejgpb^jYomq6zVXOd2KCHjMQsO&>a0_En;OqVV+nU=N8%yZz!n4Nh&OlwyP%>{w+8 zEph{E4)mzbIqv7Bz&jaYSBm@VAszEEX)3S3V%J=Gi_ocyb zfoV3;8k*M|rX(_x926R(JIEQ0^{zzGWEOz}NC-wJf!C`H{qplgb`3ZcHr?w|zF#FTpb zlXT+o=^4fo?$S@~27HU`;&qj&1G2Zm@n&by{*3=joS7HtQeML%`ON41uctyF>a$wvh95q}X)9=a_w%%{0fH8-36)lp?i zUsgg$W3lF)pi+(bF*98ZFHeIDtD$TzBAYr_-lw+qaddY8_*rP8OA-Fgt+Pj4bBDi4 z*Exhs@QoTW6doQ3;Zrt5o8#fn_yY1qj#7H>C#rEET9e{sM#l79M#I`~tVuc$eo{{g zfy;Y8bDmvx_T4AEyN*Zr8C9dKZm@%hH`b`nn#XRuk*HTZ!!osIO(&PYF1^<%Db`LS}@a8Q( zh5%~C(^q*u25Gp=L$n*B=}6bcZX$psE!R^&Ur8f8_Wr@;$1=O(t(VI*pSS@T9HVQUKiqyW%II)JwRBjFj73}l|=HxGtW&CbZl-y z0v%&km!}um;PAV7D`SMc?V%C2Z(rK#g!0)?Yyg+1avAwdLs&_D3Q#O<_#;9u(;!o; zf~$!4@IE;B0%gwk2gB(g6vkOY2Uo$7;?i(K^n3bw0S5QQD>Cn>8KsnHGnvDs+^I6r zp1_Rc*F51`1q#*`$84^3AT^jRFU?*@DkZz-_IzIN%4~fibrcurFB(C zyG9;|A7Z8qr#!czc#QvSeT~ZUhdq=w!sQb9a?RVG=_P8mUV&43h%b!K_c3Nnqe$Z- zR;DSsZ%VAb}G~r^V$iE?h=+=dA6$9^y=B^i;*H64XdHior|Q> zuPpN`jfiPWbTKiG=O14plQ(b!m@Z2LF|9>hiPD!$2}lY3cQC!A$NPH+5RrFKa>GlE z^w%w--sOfR(HkkxTNsL#Fd2nY3|H=ORe_w~3j@?&vUHsz`spw9XNvj)St1;Z01q?{ zb0!{lz^uP}!Wy>V-YC$pL>IGtePv@e+@NCQ!prOU=(9Ex#q4*mAH0IzSc;sj}+qjdafvc zR)6ckP%PI2zubHV9Yul9aP+2#?K^pbX0`(Z)HC+lf_j_JhD@| zaj-N>5uKRUO3r&^E0THzDzO<=z79rDvd;Uoo`Pra&t3KA4JYjipqJt6P|QcRy92!V z_n-SLkx*|A?^T|;V>8J&l@M;Q56$-#Riwn*E3EU5#dUPiNvIK~Lsjn$VC{6f0>6Dbx( zZ}IXonjQOjxvqn1K}~);HhW}To?bc|QSj}o22)HTlc1UM>@RDf zry^grEPw}3d?Ayck#2lb(zTj!vGqpz(4>4pwyA<8cQ36j_rX5ZP%|WOC~~{pQS#HP zk`O)R*x{dcAY;^l^6JBnq&)Fs>4cGom*`l^!UnxwI=l&ASSW|x%)kpeU-jrpFjs8^ zZe*fg-lmknY*HS(75hor8(ZrOwve)?&D`GIecX`a$2V5q4a}&=UrnG_$ouRH@}*j$w9Z1N}etSQa^Axq__~ z`=evAf-RX`UME7=YbKT42!QhZTLe<0yQWz4WJC8c!IYXFA*uU{9o{mf~3 zE{kzIVM6!9dTRQl&F-`L{Q;FN(&5?0nS|}f5G8=g70;bh8@cF?Wwwxr4#*<-<^kfh zik#@-FPF4v{x=gH7U?PYfm!Itbv2Yx8XHw+ei~E9!Eo#g>4#16ue>I!e3XJwrKGd7 zD-s?N9kE-47I!jHjNH-VDx$3N(oyOPXE3sfeLh3HW$bP4QKg+%+CnUE+i2~5w80NChGdIFzHQTHK$0`+P9{l=);_~!a%D)Wegd}3QH2avT zi$|(~B%bbD148Ha+>)Pxi<`h4QIvZ=7H1T47RgDiYA_3TEU*hBZ(&wLf=y7GPWflS zg~*AW5x)c^+yarBT+(7?xQG?K4G1y(_JVj5wJy`~D(Gd2=_l0;isQK8>(nPHk8qzl z=NdPQkG>U$rx+G3Yh7}P+>pk%qd3K_!PQE9Z~^qnw^W?zZ?T{9(4;w4;|V>aM!V?} zokRDuTNu%@gasIXS~wJ}KZBqxk#maPE5seWeu-0`>_|ih=}PVo-A zH`oUxPo6SLW!IE2v_CnC-p&KORs)?TZHA(=a-Y4vy-3>c^Q9C?IX@B-ns!XQzj849 zR3k`%X0wyI?o8(yPB4`0nMEzKu>s6I_Ai)QS!(s5IoRLh*2$#oe4>Xeb>v8Kx|>ux zHBu*!XhQa0tf4Z`y~9h|=3SwaHA7c7u2ep4%vA^YzkSF^D?`-svILlvOyW$@4XTt3 zh>aW+mGS1c^sMPgZc3et*|eMkmMv0D-8x~Fk3dGu3GH;*7k!zITxnh(^-7JYADIR2 zjj5}&B({4ffq7IkXkAya-ANeF}UjK7Zm zc*Fuk&j)M>DG@d5euS#QFzzlAAlV#4#!t;ICp=0bzF4nrEpYa135iDwwb>9)X{U5q z{tNNv-}uOJLO7Q=O_kHkeSo*vU^+6yXX!Og*6{BfftZbyh}BJb?6AU#N{JHRHo=({BtZE-DBZRBn_rgsZ#=~@ zH+<<|emvRnb+e?t>Vvplo!z-W=hY@Rbj2HBp3tuE@y)?rEQBrLD;Tlcai8wEX_gYy z%h-zhR0A`4RA%^tGbo*2zoYopxnugcyfM$CUW~SxZ-Ae3fA}xI;*H$A!i$9w+8;BO z+?8)0qs6$?vC@eZK3a55p3J|n5hgr+PXAU&^`5{7-spp%g>MotBfHONRelDR6DMA@ zEj9iR&gKT|A!b5T8JgpvQVVSLu~&fk_z-u86}GECC!sVdn+#C(7&bmQ+-Mp;6hA^; zFTO~f8GZZ>=xWxGK|o-Mxp3nN{&ai%qPi{1X*Tz>KCCQqGcO)LD8~dLAz$}uc-Bo4 ze?6spueZ1R>s;A;#axM^_2$+bX()T%2*Twneyb9zeYXNQ@fi%= zG8Pe&0mvumdhB{~g(XJMI83l1UEmW>-d#*-vRR7jhx;g|?0jdXDDDPkZ4bbiB4>|Y zIDQY9Fr3e4a%bvan#U~x@+#ESWtec%c&n5SfY!VJVBd9AgaHL3OB% zg6W_0WBdk~+e)Ew*7;=nVTEoY%}!ibtUsnJk5@@1zmaC9_ZyWJ)FK^M)hUVoB4rdB z(N75?X4a}42(Yp1YLXTgI^VSJU#wIv zOCFRR@rEfbB*~7NGqI>ik#X(ZHHoGX#`O%;dtKoeVfR0%@7;kMB#e({*y)L;CUds{s-eh!kfgNn}Vy}a)yk-QP+AnsS zMZFD~1#QE%;{3^~c_?IV007|vXEHLJz=)yawv;KvA1+!EW1T6|FMYU?^U_*f1V-Pl zgCbRg#|Z#$?0AX`S2LM(;^}yKa|%c}ZFIha02eCWGYH;04@Y9R4zk?t9?cFq*wQ+X z>@Sln`2#na0mSVFN(V);cd;&HoteU?NPR*GL`4qYDPC$;7nbJRVu(83-Zn%$VIq%EZSe z*F7&*Xe&CahoeYFUz^sPS$Ae7lR9%cWR28_4kT{Vx+`)gyNXG0t(sVz`xSK`w$FTw z1DN=2OcU+&l3`OFqCGS0?u! zR=DY=K`uM0=x0nZ@|b|Qa3@)96h~X=Mxek#aUYUJ_z|CoXDm`-OLr1ltOwJ=bNSG3 zt^uk0^dQYK^wtxsbJ(>+fd%1MIB)YqV))x4FyBvlZOF)<^7B3(`k2nP>E=4PMQ=Ni z-|ZIhxK^JFd3^MR)i(y@6evlo)Ne-Ile0|0hH7}JCta4f(fTs zPH8mx(DUYVk*y~ zN0-CTU~j9?h4vt3rP@(AbD_ix!q21z#8=X3g_@nO+(CR5K7yeQ14BD;1jFSKK&o$v z!D`@db(H|RrfSxhAoG#C;09UTsGgpVipb^cIL(IEESPU<&ykzt-FqeDkG_jLZ?06pC zC3^dD#5eGqkxUQno6-v0H<7y+yD|nC!}X7CLc>y=;u0p@IDY7f2cq6+z4~Rpfa|(`PBRQW ztrl1mVdalQF?O$%plCBo@eV(8i;JOR5W8>fklfh7$f4ww%ss6?_bFmE2~d~1_@=A~ zOzI7mNJ&fAmU!JWgO7}N9@keo@T=Ugj$So#c%XLDe)lhCnaA7L5`@n#B2ZDH^=Ybw zGvNF;dA>U%NI=9(ILlQtS)J!sH;vOrn^)AcMhO@e@2SraUz&Nf>R8E>z;Yhte154n z!k2b<`4^LFfo{~VrSq%#G*P0`#P)f?m){?m*`^G-+zTBfOIaXoci0U`Y~c(QLkO^- z{x}miTRD$0Zg?bDFts#_ejHhK^5Y+ulv0E>HN2AdUQkvFnGYzS-;sC5wC6b?j|FtT zw$S;q;yTXiU-Yy14Z`f#kXEFsyay}alDQZ*BTNc~tnBHUpYq<`E^kF*G3AYx%)U4E zced{fdjc$>!&9>fJ}oEm(j@MP5IHQ3#+BVFI2}T@_{^XpA@(bVIuS@p9)o0tXJVj~ zA;Tkh2*|%#@QcrpbUK0Dx&00?1Rk_l5gDbns_|aw(a^J=Yo)1d4GOp<=EA$I=W*9K zGgqcaA2Zd8AK9yqBRVc?>{xZ z+?;DH&hZ%ic5NoFC?&rN`-^Gp?l~;^E5~2OF}Kb;EzueE$3J`!7s$5~5q-Tuc&phX z(N2)$(FwykOIgSK3)rf%)6(OrJ+TZy_(8+NKgii0=tK$P5Q;(BvAi0Q&bzrRz8ics zMVbkLn%ca}0j~ftpn2X=V~q09x~+BFW!?!Z8GGIoDa=c5G))P2TUDtbN+wE)hcs7QYT5J_&Q?G)LGQ^$qLNwiwyt0slxZi*?W}xm-I;SF|whn0>S1! zRI@>J6U!LsUmz{${i;U!bveK2984qHh_=e?;t$OkP;{E*OtWo5KiJzmf)Vtkkv$5< z@;w%YwK?Zk5$5UCHZd>HoPO0T!jELfLakhl@eN&x31#)H28X5-=t+=s-#(uQPqJMJ20EWnd5$TQyDs@Od0GD-XzD&pQo3~duvg=0qZWsB+KKJdYOk_OWR zBu!Uh`v-*rh2!Zbr$?6p%MJaV60Tc;7|b@#8E-bjaFa^kc&PMX$f0mXCgIz{I z7N|M_i#huuKyb1PG8qn@z4`_G$R;D4_ti2?_@rY*0UM!m;HMXEwcHjgb&eqFzzgi3 zQKuk^NwWrA^TJYZ7c`Hs@U{)B1`Bsq74o)$1=UpNAw@zuv`ovuAZe%R@z`LdJ{j-H z(#1>Gf-L8@7COd2e}Px@TnF0YIWJ%{M5Yq7Seo#E29G-ahA-l?b`)Z|CIMp3lKO2v8^meDabr_1yKMs{&Tp`!`XT2`l(-(^6u6V^9&j$55Z8~eH$txvLDXj zuF`bjl1<5Vgu1hEvxQOh}|W~Ld6v0KR%+&a|INo z?}I72EN9qG4t_&g+VORuu{%Aza5VhV1gUf~z<_H&pyTK-E^Hco#&#^>=MxV0bIaQv zeydRH(q=~FIx?k&0irl^2r0t+ztD80M@c=lof+s{_t#KPsP zHL8NW)ifgUB`BgeE;W12BcnjeG(O`AmlfB(O4>+oRKoKG<>5(^AJwyk@w2`{FoCUp zOkqb52fid7UlHfPiQJhGWBaE^$gnzbdcDO2OV`9wI zv4r{llF+dRdna79uPav4cL7p!%Tct~2|S?pFs5it?v%LgfSl$`=?zETysQ+{D8t?l znmRTnK}D`4)59TV9@wJd%L9}`g$O@E$nEF1Gm=xBjMLmynfI_F3(#F`Mj!I~UZ=nF zd|q;@<%RLV@mGNOiw-25T-`Tp)lN8cM_`%Fd8n<>cX%-yF#)ZOKlC~P-4$>GeBRTa z{m1TwA8%EUz>}#y)K)(TnuO+HCg2kDrr5j33K%t^#DGr$Nz;_vO4k-;IzI2UjaET_ z@nB>T_NjAa_^}MCX)JgIzF@6=sYwjn1MTGnT3sJa@nX-`K}57piL?o+k1xsqkJ6BL zfHUVMxW5UR_b_pr`9E=YVCgwe(6G7=elcD7Z}MBMHOIw1V-5|TpIrGRi>ihx^>%j2 zTmS9*329PS$;N7?cBaJTnYvc8ABewT`9g;<4Hc&7awzbf^J*1A<$nu`&^2c#Qa{{O7AS;gIHh@$)HWrkD+= zN8QyuUz4f6kz-=AgDLG0G{mu)h^v66wnc_OAu$aQ`C8_28AG!K0qokvXPdHA|skd0&enftSC) zlt6ryi@TJWc%PF4zLkA2KmUivb%CH*wqiirDkIwPvK9DJTj(PD%^EwOY3FGq%)a-^ z519RHe(ko-qTpu2S7u4GEG2-b8^T1``FopS`|U6Gi)ZI#!WSgnSbwu;gA{#+gsDb| znPM{F#q5e3Jz%JNu#Z6|_gm|SU9oPE7SR*!tycX+D#f6JHu3f?cn>x(Q_austoZ&l z=i@&&vqzMmj~w}Fb3%M1IZGMnH5Pa77Mz!R2I31rpM|<@>}yUUKL2iW2c5^gq^la-;E)Ri+;v?> zh@JEQ{o+09(5DMg6mcQIqYsvu4>0LSg9^v#TdWpx_{kqR^!bpR%lY@s{kss@|7OI$ z9x%R?P1iL*1T*EWoaZj8fupt?l@ElR4?|*7c4$9)eeG;!TtmPKY9m+NS(8R~3SKi27U*vU2oho( zi#gbmq}cG?&jyGtaEV1b9K@&3~3nS(b0l&4q5 zw;%oeMi0KJP4t!@CBO%2VL2i_E^r03X$_jH^!@E*JODt-Ol1` zkk?;yhXLi&9S}uihMm5^LO3f!(2m}Kn&U_Ii}05)*Ai&kXF37)VgWt_Ccl@&AKkYC zT(Bmg!Z5O5rCox2jnI`7)6ktn`fI7kfK#PZIpX!Mt=4{<7H{gmK&Q_<+gMU5%#%1I zzjw;7fKmNuX1r;_{G6XQxsU$Uv<TksbseIb1GFUvF#wzKdqr zAsjzqhVpEo(U*l)@N0-FD`gnut*A1p^2`rnlLpPUGxUJgLlxylqUKQ=kj0I{P)%VvlvMM1^@ks z;YfR~9cKmdRQ`#QAL_T1DcH~MQ^*C$!8<+SNzT76EJ%t0FXR7dgYP7P7pD6AMjb~s z_$y2r`v<2JmybBuV1{cB;eU8a;d?Su1RRfBK&ro5q08_2-%X=R%QZY?DBs zA%z2eX?M4e+x{VYPH_zUD#}#(5Rn%RrKwIu;|vISrF0N4`HF<|&YA=?Y-!8?^K1T` z&dDlLtpByo_lZGLkrY)TLQA0tb?*GinK(8Eu);)577W{(99%l?K&{8t#h z2hqT!@*4%g$d`8OqBu5UwSQgWpBHu$!6Sa7ijVBk1<;ZpT~x;Ed0?s{R&#$A&wuW$ z99cH#$L>DLJ$M+>RtamMzNI{FYL;NZ-q>J0yRM6buY*(+rk{oUS)Q<4IMLvRK}PSN zmp%9M>tNTDE8G$@{W5fmjVi&Zu4)K*N@S0uBY1;p@F{HghhG4I-H7)1xYa_ko z_1NI!L|kwaXiIn`{iBgm4t`D<$@odd2p?lmDBh? z#zqfglWvD8{P%szrs?Bzao{J*j6r2t0a~F}N^NuI*I)|jaIB?71ee6W9!K`~)&0In zX^w>EcRwR##(a7~1@a%$h*5}xd4T_LaULe_K(ierRf;k&{JL-5{tIFBdF@Ox_EsX- zNiQ$ec%bn6pEAiDA1vT%*R*vI14d-6yNXh@J_nJTuv88QmhLTE*m`1G<;GXMQ? zA4()@K2*uC`h7fs02kW)D(p9VOA%h_dUwFAO38QlRN($6fCQ^4AI+cn`%NW)lKkI? z$yah=KqU(xPD==6fdY+>`LX8k!H0exyJwU12MYj=h7cqU3V8TaX!7B7_lvpx74+{q z3NeELm(V?tKGgnAQbok7#}A5Ph>fU?@RsMn|BNI@yry_X^MCd!6{-E>`jovc1=Xh2QSq%wS;q?<+H3k2l2Pe4IpyT)qeLY~dc^``BkH8>Af_5s9p^S>x zR&P2H;vG7%0+#dpj=!?ShqAbSuakd2QcS7P{B7!v@M|D*H&UOYgh+}5Jehz$YQvNH zs6V$7*)RH#ZQDvd^Y?PD4fbx~`u+XEdbg1>fc>om;eKMlq#7u+&7C5#Yg>D}3wu8x z{YGIDA@M`-jrD%hh3rQB{*P3A5r4B*>%M zV})ep6eYV6>;CJJNuxsds2(gFH(np`$nNAD8zbZab6FuEMQmid|NCV~Skj*D9}3(^ z5M;Eej0du2eHhrGF!+J*JIn``)$sqFIDANoFMdp}?2AGE`k${p*)i~?RP?l&f$0Um zP$BeWeZfam!ORn?^UezJxf=q3rR_rPy1ugW`pZt5d-McfU@G3}S`LYM{Wld?LU*75 zF9*!{%pl%qtfQXrdZXY(5`SSLsE`K`qw^84Ewe>zM?JHkiFIPa)3c%%&Y{^?TOV9a z8K=+LnT1$|gQvua%m>MeXruZ%9=EkROC`TQ%J;d)R^K5iTWa_MdCcb+_cpG^rT=z+ z>m|(IKNNnK`yPnnZ7DD#FQMH;*B`~%0Kd%NX$PXcuzh0v>bHiWS<-ts4~9KW;L#qU zM2++O7U|f(4Ku)pEO#%Dc_01(Fpm&HAscPMc)cGXIkH!jKndNpvAY1X(Gp0-x}URm zXKyPO@ry&K1S3HHP5tTtx+6>T>sqvIi%{zf!FWGjB(@M#tMYj^!OIAt^MZuv3Y;!Y zF}e=def>oVTo6`R`$;^P4I-;4nn^drAIAU*R5@2U=G*4%%@i}s!gICmw!UjKJetxn zs)+h{82S+HSUXCFC3i$RiZmmB$^#UpT}E>b^R0qGA(NS{Il)M2>@hEHIv4pdC6j!gh;#|T1f2!gY><}OVSi6*0QHvy_w2aI{ zkVpiQM58^$IB2`k*;d|nZM1kt0!dUE(8hVjapQ8=;|GD#G6a5kwQheKB!FM|jZc8O}$ag1Jl9>B(vaI6&FRgLa$TK@>uCD=SA4T zW#73$eLsxY$U)Fh9x<&@zNODqbv>3b8M@GKhtY-wyt|vbq&FwQ0FUjx)QMNu?Xf9bG*ycbA+gI&5nd;3veWrwO(zwaaJz$j;Z%X4!T!rj4)E9bS@4SWVT{O9+uZaS2Cv5ny zLKVe4^tABHO3~|MfHALTuvO~whi6q_NtVkmob3TCIjTB@Do9<|nv1I)+R_Fc#cT-@=5Ijl{v@!>dKU zl@5N*I0Q9f_tpBq@bJe4+6zVmSAe^LY>6bu(H*Fi9l@aw1@81++@-YYQE~aIdgp*o_ZTNUoH|H zE4!sgAH+z?LkIq!8le;l{ayeM4MRe?ZSmRYtKXYRrFziE-=beelUq^sTCP~Vtv2Qq zKl?zr|08Wv2udGxybou4vmy*F>;U!T)S;KogUn#z3ukWTsR|WtK*d#xSOr^_1W*#-2NO3~zOBG!@c zxvtQ;#ZGmhmGnoQ6fB<=W(5){D?T}NTxav#i0~g~AsCeG)7-;Bt80UJj;Q$@xCtbJ z^f=O`mJvC-Yvnp(jCUizNn#tI1-*X9Z%B&s)NUL5$$6X!ZSI6Y3a1MMcg(6eK)i#p zP`BL}A{@_uIk>f>thN6Unn!uJUqV#XUE{g?b#dAp>MMxY?vc*G5df$%ba>%On#2l# zvh-Z|*C7eGVZ0R2(a9_Wv>&WR^+QBjC7ct;L<@<9x`}0cUNhzek{Qn+f$!v@@#QPUuv$772wM!nuu#%o*UJmJ~w*$AT zTy0@k2bu;rXvZo?5+*ylplsrw5{}I+sYpDl?w&qFGwB%M>x$3u;o(TXPjU` z`aN~0+xNr^>vV`ZU^3lAS~I{UoOyZR zBd|;cJ|vagFs6tz%WybSat%>RvTL~vyoMonq@9X~5;)M6oS*$T3Iw4OM5Pk?5#6PC ztozGT+}fk7V4oniT9{h4`vLRDODQsh4_k}qgmDlXAxU{;<&w;3oyY6GOUTiXLJ#QYsu|uz zn2Q+iO)~D8FA;StRyO=@UXW62g`n^7!A3C8qN;F0v;DaBxnB*(DWpFXckZVe@f+sn zFxR2TyM-rD$Y5^g$pozfp_WFHkai$24mt626oMX^41><4aXG(y4)*T0&^>^SdWsKS z0#l4E$;)C>QMX2bhirv8EK}wH5flD;*BVd^oQbkO-=D&N^J~tQA4eknUCn6jxmdj` zUFvqmNVbLnmCgg62g=cwrRt(AEPj@#gmY{;M+IA4(q<(%lQJeCJ4>3?OwChW^Za#Q3dwa3s3ucdbcLWFT-zRM6LCD2D5n&DO@! zWY~j4hMq0{{Y`uY(T$kfEi=4HH6MYypi|g^Y!o6v8`|l-7{U96_BUyqn+qul1-F`3 zLl!kbw`KM)Ddd;KZa5Q&-W7u7IzC$K{%+1(0! z@@4LT(VnIyla|U)1Upl{TJ;S`CKUL>*fgOFSx%4zK|20{Va4BhrAM2`c{#=B;UU)` zT$Mki_Pe1^;}M3*lursH5}j>>)>%DEhoB`-7B71H>WRMH=;MMp7X9fea-nkJlrF>C z-Wy`h-#-9tbPntQ=ASaK7k{~RHBPgMop8Rngfp%x84ifX%%|YmkMPaTbRHYrx}|bi zPW88_=kM?*qym+CL9o#fA$i*4a$aF|?ovh&0)*@0E1dGVccz|7|IN-6Z!hH?@N1e> zeD)iV|EFp|4wz|D^GDh%O$I?UA*7T@R9iRdGbt+%P%7DSn2P1nX-u=%k9a|Id7>j3 zdYaS|_Es1iLOCm=$ZR(BV@E`Ch>9v+Cddt#-wdxo+(>*yf7;-N--T3|9|V*SFY@7s zTzPaMb$5`D#Lz#TYYX0Kob3c3{{egcVL@%Y-pc~qxw+u8b&Z- zW)h4M9@vxZTTWYawz7+@33H|KQ!u`{k!aX^bio;Mn0D3FtGX?Gdv`Z>kWMpq+!+Qi zPOhGJ^^3DpZez2WX|E}0`K)f{tyT@TJU2+W(qMHd-wG1SUs9XKF)L3nbc@6y&`R<( zDPuApeQAIs^e?`r*;f}vAqcFveiNgnp~pV+4OvDX$RLp8q_5U}uRx%~NnIvT|4;g6 zS}oz%;J2ie6c=(aUjyn-*(>E#=lzNwRGV7)fOavk*ass{vc4sE6#jz+w4dXMn=;u& z>SdGCv%ZI9*)X>q3*GSi9I+(eQH#`1y%MBjS*_qIAmZylFAp6I2_N=_C0&f26}6}N z=aLVC8j7_TeGjK2jq)yl;+iEmY-_nIi_e_hywj8NQ8-kWkGg@8d8L6*C+<~J(M2e}4m z20l(MM1>CBErsq7DSuMm2Jn&k++#0kWQBE*QnD7%*mQ9nworYC%cjZA4VM!A+(igl zt%d4YvQ;`(M2aTXhVIG^tI=i^Kku%71FW1Z4VLu$Gd(8Z9zGxm;2Ly$Bl$(i3yRF| zMGJ;{FG!X%Dc}M&ImKPOr1hD`sqMLvM6?z@l+7U(r?501@d} zQ5-S$a03r`#k^_v#-}a`X$L*A)JFthv&kx)3Fm%+bjeYmVQ?nvjFC%6CPL?=52l>& z?q<^-94!Ucq&$A7OZ!x?@&Q=$691*;u_hu<{krWP6mK!*)a2?`&{2pzia(1Dz^YL) zewVRM&d;XWK_>51d0sFBy_acgNbu|m&qyMogL?NDa|Ohw_-o~nG*WOU1@XHxw>)MO zaZhEx1BH#0ctB7m4r<0t@&1h<%nfj*5#XMf2NK`;Fx-*4on^(w5oYO}MPZ{n#21cK z!~c7K0K$?CmD@%LjUI4-u;ocLJ^G8c)7#_?pT0_*6@Nuv;Knhu>gClOB?%ul?3$8jk>XUA4kBrGNx%jg%OKz8WYC zMxK@xF1i7gqfE_AWK~v@(}(L6=R%F~qRU5O8<8xhuvuTb6df>$pW~3+yzUl6d`(U_ z)WTnb05Lp|)pxT)4 zM}P)T`u(w~b}e^Vr`AxXW!Kw%M4kj3C@S~bjj}*SF&7rf;0RXsPtZ9{{t#@Y-UG%= z;@K6LC+mFDWS0rNN_vLn5Rw{rg4->KCwcoyv0r7}0>5wo+f~_#&tZ-02u@Q0N3{sW zEkvA;SVmoP|J5(bAp7juke{O^WLD*rCn$L~2|inlp7j@ISx{=>bbvOV+Bb`jnkWzx zW7DL~*iZz8;JN$((k2$C_A^J(`H(Rvk;BPdted!0?FY-{FWbCpj8_D7FTu&$xjCIw z3g%0nuf0J``LcL^+7kmgu{5~cn!piTC3`x|VEIoH#?0kCOKbKnL?xyJR5BZwq!QbR zZUTOktex{S8azcNTB>l9a+^uy1r7!Fm+ex28XG5%>Ca7uZ9r>n)xsr+JK8N4);D~^ zL?kP2wz%6`s($%?oF-T27VU8>BnIszEiuFn89oF|=EDpaN+CiosLK*FqluU%?(TXp z$R>2gN3?oE*?G>L^5II?rPr&Qfe#5{9IH}$E)6V=?o3~zM)Q7O7500>Tl-Tj)BFj( zo6ukW(T;_FOMIOh#p-mKB|c3eRP6l}B%^`1@K&hT!<-gKuQ{e{2q#T++3&{fxDjUW zi}8LUX&Da#UTg2Kr5MER;D^#1&tE4(DIi%9*+qK5n4q(wHhNgoC+Bw(*a0H8UzMCh zkNNMxu5S+TPsX?{G-)l}PX>GG^JV*uj#R`5ZMgm%dP&XuL$UwuX-;wmjyH~BZ^o|H zqjjRrv7uan#Wm-1i~;rf35Ibp>v^(OJ}*iU;G#sO&qyGY>|gOs`ecUK5~GlQ5zlaX zA3;ghSw}j4@Q7OUG507aAGo-j;h#V!_17u=+q$e_LcvnprzSO6d!&N|T^7fbdQnMe z9cGs_Y|r~$w-gif88Y6Hmi?uJ^!er1!ju)>!WSdL2ay+}kl)3HKK2r;t|QUe zdie-ZwxRaT7_LT9*!f=EvDU9&4__gaxrk8R-tnHAWFfP4l96Kl^?m;3r^8SkmX~P_ z^nqyMLe-^=U=w@{%arF#Y5h~d&Q_UJ@a1Vc$e3YrHC|CD_(AV znx)BI9F@~@;nfblOx!D)n|7QNnLO)f+!;dw^rvzkk3;b=xyDTeiq1s}LC(8Mo~wnvbz6r#vp8M#T6 zkgfN;RL}bV-s5=R%p%q3(H(xUmfpl^!nbUn~p?&jR~D&Fa?HWg)pII9$9}X^pfl` z7EG}}M|p1?Xy!)OXyOmzK(01!T1DD;q>w!5e^qt6onj5xvF zHhIf=YWPVTNBX3Eu28ZNG}V}3Z}7kXo_&BBD@h#6A=As*%nDC&^_cvbY9!b}JO5<# z$E0dynW*~P-oz&ytU`TPEbkr}^s&tG?;_dBIcm#S_+9K37#G&&yHNSEdUc)%>vL6g z`9$m~%pSYq+fJ16ywy)pwISlo+ysQh*jU_{^vo7ng-pk*C!rIH-V2@2ZCuN`nfqBV zrAwxiIA(4Thw!+CY42~Zy6mJD;J}JKzQVYspYkl19BEtAZXqgOex(WBR72Gn7Toy_ z%^QYg-9vPcD&{blO2maqJUET#dBW8vRX9uJCg~(scbsBu_sc@Mam2$-wft@icJuM* zn(A05zptm;@D?=BD5){e087|jf4t$%=62^;RfPUNpN@++wB3(=$6kS?oc7p#bqO}} z5@BA0IO#ivWdzJWsx4A)kl~zCA2aETE}mSU7C*Rd)Spnw`r8p|I1aFvMQO*+pfy)s zr<^-d^ewj-!n|$sB{it#_I0@N#x-n;AA6a_AF1xre2uJ3mDKn_WvJopLa z&*oE3>C;X6JZ(gOm>&JnrnSGIPITKw2|J)JOAlR0G(=A?@PFc}zX7#|7Rzx71zI8F znmhr?&JC<+1VbOLMeM6cz%mKj+chd{kj)&XI)_AQzS*SD8(=;Y5}NBMgvSQq=dEjU z00GPz11ysk33s$a>-ShSg@@QH!vjFw!UDzq0!@OxK~5+BAet#jA-V0?(nDUm))3X+ zy46^Ti%VK5soT4*qG5HMq79BpKJ&O+D@42*cj!K4E zvr&sM>%jRVwFCXGV?|GVIC9~_t-}K^baAr5+mUh7pWBQrqiEmRg`TWkDwU5;l`H99 zGYfiKAb9Sco6*U{PRaDMuWw%>U-A1y5d#XkjZcSv6YUZ6o;;`Siv{~ED|P}kN@XGD z0Mlr1Qwu8Z0&>`Oj5*%vO50gE-NG1~ z1Nadl(x4L_LOOImkExa*#DnI&NOQ<))E-Ao+SOrae{8d(Hp(bLBT;cqh0h649HZWY zgo-en(MdmoKly5V$=p-nfrSvAs!iv$bI$f-3=z0{c~PYV_nsZ+n1a|ES?3(eHrd#S z#Fa6V*VQd&P(pMGOWiME2+P3C8WT#|h$;8cWj!1<&K1DY{zZ*%fB#K%>D>!W%ue3zNW((VJ8U!P&oc&2XT~9#H_# zZv*y}e%mDSlCGVdQLZ0aDCTR!=mMp`i2yTen_S_uL8d$~vmd00`x8iE769b`TpWFO z3Q*8)w%o83&b%#syP*t)uW;`S(!FS#Jg-X{9&D6jjdbNld1ZYilAiJ@c3fQdHWVZd zQ+qB|HXkSXVSvjTnUG!&3p8`TTMy*znEpqRV)w2N$=_(=a?0Rf{Emj?_by}5WO$W9vy zUiXKs(_k{*!x2#7vW@ib0D-jaA8NJUL?l4_j$)#*)#&oDX7gSVpGT4*FhnD=DMzPj zn}%nQBkUWm^<|r$!?*?Dp4b-7C+0XbsJl_!l{JHo>()`FL&%F^aX>M2`#_`R6q>5# zG#4zqEtM^8@wXRN*TBSsD_w4uFz8zP9Rwokc$)7U=Gf2?LNgtE^=(?oY>q$ z68wf7F`3`EY^DWvq@TIhpZ#894fFsTJ0msiTG+u z5{*B2H}6Jn)vBP(WB5{K+cq!DXP1XU_skYL5QbvP&p8h-9h{FH3>^5>W`11sQ!g?b#tF4)ru%eMJ3O~sWS&$fERw*CwT z7f&s>uHfE!G{YDq*~PjDiEh3lHx=M2Nz2R}PaM z-QQe#3*CFAEA%W`D7YH0Y5S@MC!sGdaTt)17*Grtr=F3aYe=S%X|dHPK0)XS+ww(Q zDyF;-j8NHQh$L!TDcw0@<5sqOxNzAe51F#PS+KiL^dI(oL9Lp4Wfa_GwJSCpkA8ck z=t|Lv*5^v2Y(wZqtP2ZsU@C$b=J1hKIb0-DY~tplJOW zfkrji{khL;nd<9pY{?a(vSq6knM4G)9zN`A>1*F1-oJ|w$UYpFgbjQ&aXYpNr z+G2MPp^bPyon|@jBrB!x2XHDuTz*PY9e$D1YN&kx`30xbF0g@YrJu9(5>O*_;k@6; z`OY07SX+l+%a6Wyd*-c7_Fp3>sbdXMV@{oy9T_>ye@;&{Df9mqvIjY4^Yu^W_?JC(`~#% zRNC?63(B)A6f!0iWW&Z6d0ueNum1R%Bysctsw$zr1*w1F9#JVnW%`-DBnTS6SkBEb3 za_Oq?%2=V|FWa_=nf{bl0rPvThS_(i%Wx~^?89VtquOGFs}ZZa73#Q!?_Z1a85Kv(l6Q6 zfhaMbctw$;6T({{_=!jR^YS+sJ6wd69rfWj6>?c_tW`D-E#>PQ0bomGu{IFu)m1te z{f)Jw41G85Mc9!I%{n0}^PrdoJ~68}zUQxh7^R>p81cPL2<2j-v}TdcWx9iaj)v;& zv>gTn*uuTQ@DKnIlwW{;@iNk>L4zQo)o2HpvOD43Ux^lf(Vy<42+-+`>9odsPdp;| z^Gd;{?+O+9J;J4tXw*}j_^t}{Ci{UphG&`CnWVlO;S&Ju3}Picbfc(X^PD;d7E6HD!# zQ)iOchr<^m1&bM2o+=TydH0(>&hdV07pEZA`x*{EJuK;h)wn`rn?iutT*qU8n5qaY*e?#AMAMubxS` z@Q`TNW-NLl{Lc83j`GjLPMMyYNR2kAY_g=doBeaAZK^tEfnO~4`LowshAI0DEae*r z&iHb+;Q4qy50u7Mx`9fDDySU}w$@*4r>pGs^s2xiB^S?C{6&jeWx$u*XL&<|4yMoe zAHWsC0j;+>CWC0Dz!qTbeb~-mBU&ZNh%Z`FR_NNSeUpG~R#J6sZDk(Es0=Wb$U3m# z9$9*s?v!18Lq+d7^XEs(%(f?PZ&H0gIA&=NUT#c9waNy|P&7acX-xc}*)q%)9O38d zrkGLcw>0V&wl6_nX8C>gm<eC(K-J65Cq|^art2;3+J!7g|oVzGbB@~RUmD@PG{QjZ3 zBROD5W>o-`*!O6vO|5x>*{pWqvDr@^GdmpxA|hlMQ*oj4USn1hQkuIoW%|X&11~KxB}z-hr+8sk805z_&(^vjeWD zaAhQ7KcS@_huq6W|HO)p!jni|^%y3UvZfeG3tCKen8a6`hS|bz^@g zR8Z`eFajKgXjh7kGWp)*1)l!x7aa`5{*%>37B{azlmx<9{mVFEpL}#2|J4)7nn0(% zeLFgJ`*Rk&+FwD4RvqD>Lj1pQ&6q*4R3IlbAM&dE7^reCzZ zk++H`>fK4J5hj+`;An6$;^6f4Qrb6WRnVoFyKPE#nG3LHPk##WjF_`M!M&d0(&g;K zu|&2Vq`|Uq4;+^0L6v#^rS5LwiHNwfDp!o}+F$(~Rh@t&ie8PQwJJAnu6ZkL8b4nxvIcHgqfh_%_@3Vs z*@3mH2D6q{(vX*^*F$<&An?ZT zrEee}60=I))<#r%7)#<)Pjp?I)zMT@Jd|%g5s|pMAI37BHnN708MMyI@*wVplu&)x zJOaACq2B>(W5{?-k&l>eyo^`~fXZ$k9%q;sN-F1LPUf<>`!T3yrk!RGyjsalSXmVV z5C-HIq0)MSt3Z)yRno~e;nq>H2(~$?lS+#QX*}73kB@9-l}=~tvCDwX)(G6ptT*Qc z5_o0QElev?%M7<;@<88Jo+bbZena_cpBNHR!V3-ppJz43{kWt~M-MoeeD6Qj>=x6{ zoTA>T1WpTrl|S}5H{x8gtkM@PENb24727(9ruX*N>zHwsC6xQ&53>*L{g-&Lxo7+R zaNnh`NnGAbT73QJ)+lqjbDF;a&F#vzON;C=+hhUp#Yx4IgjcaLEX&8IFtMLx3oUKm zT!*&5-3D`>z*q@^?(B-69};7{?nxL`iol9tc#U5Xe*(%IW%_o&(SPF~{|yLb7z6|G zBy%9viJegxXz7+K6u~~ZdU?5wwfl}++4r>kN*ShS)*rlzzJ{-V1s=PrSM) z9~hV8v-9gU9me_A&PQ#wzu?iZ%ltHq*mVk3eL-4w=6)BfKy+ZOvDC7h)nbMr)A8=r z|8yj@EeNv&otpon<%(IUc3}3VKa7&Z zWGQ!KQbaDbUnr!!ttN>k{p8VY&_Zbz+OO(+n>7m6Sms9&F4=v6T&5mUxa|=j=Izg0 zV^t#;UC~8g*lr$&=M}*|14=WYA=wZ#9P?2iy6d(L(s_CseYdI6%*PLSUnCEmWvY@R z>Ptp_)9Es3l`}%nPKf_j(Q{GZcPjWHA{Nq^6*bFkOy(HXtXy2ECQPGa29AZON0i(< zaa>3f@zHMWPD{zp{`#5H9>G?O%&i?(2-az>d2!eHF-Pg#{T2Pjec9c(E#9;w^JIFx z2@9>g{8s*_3>)Q$bcfgrHr?8*>~}?^uf4J`sq;5LuRP~zWKAg>Ut9r^X&ai}qxusa z(B>9M7t)SS4;|=ehx(WIecnmc1W?ZVywQ=d;Cc@8DZyU)<|mI*ywLRayPdRdqQMai zRBjezQ@%^*<+&zNb`J({O*!RWLyphkgcGzI%f^Ouo8JXLloI{qOTy%Nn7xDa7Nt4I z45eg48qc<`L`PXax(D2NOF#&nlOWGI&AkRMHjD2M7BHXZT>BcY`zSW>RYtC5a}L_^ zlRxPcdUj+z+%;HMW#enF%ks2$##JAy;@sHUTKTw_U=5X~V$p;|!|@au66$;UjC-=B z1F22R-ef-(EkgMolBBJ}qdA7iSf~hCdSXBf7EY?u1dNxtT*8guGsX@#=4V_7{~8r= zz9S{bKMyC~MS@x(Hlzb#ZFmFa{sr`iHVp~NW|3$zp`=~bq@TF3+vJTpDV6z#5N}V; zD>NzeB%GTn(lEwh3Xa#iwERwmf|2ez_5<_m;_5eWtxQANWq5^dW!%6X{K$#sRBm<= zqkG?Ox}=I19GEUkc97oJKO*!a0<>}*id^AjiVPh?7$O`~5i7GT(^n})-nZ4(7A1#0 zxrDfSKFbiC9o7~6(u#LlCqy2T_^B&b)H+x6be^cLe&fT^E>Z0|EQ2qoOqheee@mq( z&triBKv={tlLF=HAPFzTFt~=%Zd9aTy+WF?R2kZS;x`rE}&J>l7Y$8Cd~CTdTBR;@CYW5 za~C}KTG*)bH%8$Ph(WWKYJ=i7lxQQl-<=EzHQ$2k&IozciqESh5Sq^Jm^L7 z6QcNjod(}*u~x`}>UU_0$z*zvtHKCyC=ySWG*vv%Y?d9uHMZASO?=upo9wMN`@ zT7>JZ%AUtY)8fwxTQF8xby0(E^yY$(V~*d8*ASYdq+J>PM8P%nNq*h)cP{MWS)0fo zU#hMP?~jJ`MDSl}kR2>XsLt4tn(-||M7X9vbj7S>^E)9#+8lp{jx4$o^1lrD_>%D& zsOj$<#)8wnZ4QxM!O*J2>y<9`N@zcu@W+DhJC-vGq zdX7cPEj7;glU`<%pT51Wq2~S#&|19p_|+MG8WhYxhT8-x`rk4$t1eN zpZ8U^P}ytFu!s-q$5xpYem2(lF>uiJx0tT`GjZ1D2$!F~#ya4T$qZ11q(G_{#LZ5s zM14cTI9M*f<_MG28*JazumR4nq|kHDklhoNt|(6h+$IJ~sM}VOF{csoZ78MMnlNueBLhYPp{gFjDtZ`jmEi+w$p-=Dv^z znc);5GS0QayYPmCOfMMEdc17AkKz#4P4ecIt)1_PTIIeGm>7JDl9*5`G-FR++g~^= zXO(aLrpN4SGhi=4KbdkgrMk0m91}wpbU%*%lO53lAS3ODZR_TMai>Ke;f$c9x)D00 zdAs8EEj_`2hPXiL0`sFK{qAr~wCXN}Z6fxX(~q;8DlTIJc%Tjg zARcoFaSo9W(FJr5YK$#f(f!yVT!U)qA`%%O4C1D0mB#CrWT_yuG8paKr0JDjx}pd!$G5yV%L?8?Sb=XG3IH_(f*4i%p23uG3l z{uqeU9vak8HnSRowbM8c(tv%J=O5GFPx&VGC0QCYry(lF7S(|`&yI2yvP6(It;lqy zdc~SQ1rMJPl&Sxwnau2%?w}vIxQK6j77KWYv(77fLlx3AhDpnuwJm-mxiIRK>sqAW za5RJRP?pcsZAK0mW91=+X3uIN{H$B05>YbVAZcqyE8|QFTt8&{eZRd3b$(bMny?B( zcF(Qsc7wcj2MJfrTP=~Ku!t4#g1qIqxGlfx2*R>&?-K%qYK!fQ_)VR!e1vyJJT+b( zDdZ-@*{ph8q!3RPCCObC=X zR(7>e2gh*)tJGcv=Bk8&eOr>64C2tuh{GX=7`!@mDJN`YyP`0Sw|sL*n>o9@UxwMf zClA&a+6rAuBIcrw6ux$OiT$F0QC?Edv{yQIz&7Y2V0lsj-oi)EyD1!(H+D@W8%5Po zw(l)ntJ4Z8FATp#vCw|cBjl$q!F;KOpT)y+kPH{xs1MZwRru|y3+xbL`-lI7V zG1{Y&v0@KU$u%2{ZtX3x3;Z+YBqwUDH`$__i@C*ST-EFi){B|TagwnU}9;BLsZaCdy zp|dUZgdM5thdtIe*EYaGO5Y%iqQ3#SdRaD;u~ooUThe|BcfH#4l>@aGCk&Y;*rxnd z{qO1ck(p-e7(BqcfiSTyFX&fYS;Xc@naJRxw=H};?CnT$oTStZd&_-T+H8eS&$_fH zcQj3q%8!Km`UHGBO419-6YM$@jnjxZ27}QrBPB2b0ZCyV&Et!RZV-r+g9<_oZVEGo zc^HCx7%SiYl|s%l=<*+er7|H8)kn1r5Zl=A?Bwf2t^k@j@C@i^&z$M7rK(|10;_7x z9n$RmN;!T4WYm3Egtv#2OJvfOYS19>u1dtMq@HgwoHWfW7_+CMwq?O&+obIJi>X zQjYNFytH@9j^8c2KB}i;L}vx%BiX5=r$q~6!&(q&jLIF_JgV4k&;EM`{XE$3XBoe` zOh#x>covIv$O{9Yr8wN;vARPdc)|Viaez|CfF{@-V_e;zD!$a0g&!asEc^XN+iWuE z-v(w!mnDPW-y)ZL((#f@pkMDUPAltc zqvq!$@3^AJp)+mDk0vul(x;$+<+f_WvRW^mxo_Z|06`UxPMpEDcS~te7=A1MmClwNno>rRPn;C^u^#8p!M6G;RVgdC<&NP%WRxh z^qZt*J&z`IId*^N?^<`C9HT`2@e@MFbpjt9@AT)0*a?hb3bq)>D)eITUrjU$+!vX( zaK=37J|APHX)DFnyIN^-_!C7_3wr2P{P|)NKOL$`{8e&6vFPiFNK=GxH4pj#}TsDVLUd$O59G~$|h!bAJ)7>!2r(ftmb1FfdE@n#Q z#&ML4W~FNxk#|ydgl?j|L?VQF1{&jkVExWo$`rqV_%iCk_P*_q1Uh zeApRcwd!$Otxu1fmhZYMs!AwE-vHaOSTl&~;P8pTCs5 z>EK!UTkEXMK}cywepE)Zh@>C}=EE;IsI_VCQAV_wqB6dRgjPz$guX%3nnA%k=1X8M z#4lybLA`vC6aVu%c}HBr}w4EkW{_<~;b zO8bt9IC=5m0OM){Dw|zXm zRd;20&FfJ$u@kr1UQGu$5r1a6jm=|+v{GjemjRx(htT8cl-<&&OD`wu@S2#ux4USE zKaW^3^zH3jX*rZb8odq!kXQpPb*wV_Z0$WqD%z+(-^xY>T7mv{MBmqC*s;}NmVQ=9 zrqP$q+(G^5HNc0Z-in=6c|ASc>2*uWe9|oHpx0`Y=k&ld!~r{g%LUfE0@o7pH$9hkW36RuSU#d<+q_{8)5e%{ zGn>K__aL0rtk1hG4AngFN(e{U9RYN`ZUv`r9~+z}N^?5WKW4Z-8jiI0eMKU^+<5|) zbl6$R(8&f#HoE=9A;*Mony6B zv%d}h?kgaM7pyCftoET84n+DMYB+j1=?UVW0FG_eZd~bPj6h5HZ=U!ZEdi6dF14~u zDIBfC;J1@~Do;mzJ_^j?iAr4GBduyjo!zj}@)Fs}c42J7HB% zBkSlNET9s-^(c05ne%27nRF*NmqdM|5f4`N0UBbG~}HJ>w*V=Ua# zkVi~0@}2d_^EDNeK!!OY(@wC%)WSag?;g5jZus7WV|`H9Lp|$_1&q%Nk?#7 zwS`BJ5-^TO@hcl;6;J#jCCKrFJO8-yC@{TRS1zQ#3sD}QB_1zeN0mI2oplE!<_#@w zGk)8Z=R{=bc=&=$c!$DGuUe+I+7?$o;hW;3B9mJU4skJ3!%x!lk{&w~8t!Mb(5l-+ zPURcu{5nmFv_AsTPjXLV&3`72RjBhf&0vn3zz@?$W$bX$+2B7mUtlQ7K^eujxoHs) zD?@i*(yl&2pYl$acM3IKm~TE2SMbcIn(nBLhp;^4v3gMw&Bhxs&*k3>o{lN?$o-6S z4Bhmd{3dgnaPJ%ft)^O>KqT?QJonseCw0TlqY50+x4B2nM?u+>$tciRj`m4>L#ax6 zzLm2Nje;1Hoi<7b!WPm8rVQ(tS#jFr54Idqx|d=%o}}4oPJA`~zIk!yjtcpkD@3RI zfBavLjijfu^-E zL8c3*&fT^)J?%?JW@-)`q4U`-lsGO!O`2fk+KU5?R2=jR7J8XSIC_W|AnUQruHy^T z%rTzlT79Ep+bo{ez4p4bW!v`r`ggPGSBxaHr5Y0vM|4_WOHz{HDEnImBz<3W?87>8 zvxpvf!cvDh*fguf?-qKr#a3)xDVuH!EoBM4M2)<4DdXdw@(Z0=%TP06ErsrG{g`V4 z=Q)>e%g!5xN5DPcf-O~wk8GRQJMdJ`aKI!oFmv`m%0|Y+h&g2V^@y%tZb=Qs`896i zvyq&IHJ2?#!!C#>DwT?LtZdIX(Z{V1bUswlo8KJ470lp@mNOoIuzo7k2EW~yZ+uSr<=f#zMxY>&>P|-ZITRTRtdfKM$fhs1(lErE^=-VN{LRA4R1FlV^Z~Dd|Es*N{wlE7?DeS`TqqrMkXuQjSiZe|}hH%EE;0D09;JR-)_P!9AY&^?>p%o82(r%KkDUOAu@9b?w}=;rwQHiTiM zPQykeMAxPg?|PYi%clI`dYoS12QUn75^zgBGKpcpDV(Xz+nipmu_RGf^?&e=p310N zhx*mq>;6KR#-}fY%eVJhEus{q{Z3*h5(mt(Y+|>sJYC^my75%T^-8U5=n9kIgF>?0 zc5fFs+n-<(A|x&^Ma3@Q52RH$WSCHXIA;;e5}s9oF7_JL(8^I?u;w$SEp6Nb>TVah z7neqhJ=uMH6gP)rRs}lL(?`Nt<{B%po9cS7 z$3K=^xI*gqn``9o?9UDDzd?1~&$i z{nAG+=2s6^VcO^OtLI1leqWvFi6_=}A25z}K-*N32$pwM�AowQPW9 zC>HU1NrO=Kg`(&?WRt2uzss`;eGTb$7{sT4MgV#;JE0HxEj_%Sv}Bv(prX;470t

ct~ z!ivEvAxe`zljTk1CkGL;22^^JSCZ&ymRL{!kWZ8cTY||{RUZIu5>mmK%$30_WO{YT z-W?P(lb6)OlP2HQI9?-~6}Va$MvA5is4NoNO#8 zEa*EWy&JO^!WP08B3y;(*tvM>VCJj>&|9$Nrc>|RUbL(W3yR{yD!&rBUN zB@?69)KslRZ@`I79dwkDvfXnWk+6p4I`|~Sssu^^3DJ&)H`eaBUDW;DLUvryNadvq z2M&3^J6_BbZ|wKV@Wvho-8eArqAN41E``jOc(sg*XKrJ&01djwW02Bz1fQM24i_MV zvslE0Bt+2kw&p17TDkfL%c=%-RX<6oRHr&vb}r-?qDq_IBJaJfm5K{Pt46-NyO8CY z;Yi(&l8WDu>?@xfnt_R^q!jCB#bw2uUC`kQCw>Acvh-FUL%(dwhnCs98>TUmOc-J2 zK(QltBQAN6ORJS$HVn%n*B`>gv9u1Lr#` z@IhLPaQ?u)zXIj)_db4%`k}|o9M+N2uMewtT;+cGnRa?@zo4(`YN--`D9eA;4#-ilmRGs8BL4YWXoAefv31~{81|0lDhi$9bvsw8aES#N$%mqzAGJ+}1LM)7mQI7pW5e8OKE!i`l{n3-@eU%viEAlgUu<+7Q9z4x(l zjeWR;;Y(omJX%4AxDR~^JdDPJq>JX+P z>u_5+b~%se2m$&PX}KX+PyYH&Q;jVj9r?&&>?PKLoZ+G~6%*$N%!B~`KGwL%*{TR- z*Z$1-DRI!nos5Jx?;5BIE3H8KV!Uv@9PF`&K~00Hlvk2nZ&KKVoQlHRPL-}#(DM-Z zYd_hF3Q1h9IWk*vEcyXgNZPATOgKw_%T$$;@uRpv$#IJYxwm0YIfpS^c-<#3mTsK3 z)4(@O)saWPIQGS|8t0Mym`RD1YyB&Y zd#z=dzCVXoc7*Il!>jJ!b4g<_>EC?kO~)St;M4tH6njDo2LG`7^WN4c%WydFxy*vu*Ib@02P(YBP# zc_85xiWgjtP%#q=Ms^E?_N!bUAItY^0Pf}*{IaVEvX8{U5=TAg0}dq(1PIX<^|~Z zt|AmSOtw{f$*0<7Z}yBwWNab^GH+xXTk{YI?I~-=<0L6_Zbp&~Wo0&x;wKJG%9T1^ zneGs6nD(Xc6trYF0k~U`=`SX_VX_2e+S8fxc!%Z)sx&wGI-?coCeSK5ySXigM$w+# zmizRp>0gycRDS{F;5qRmEs!`unTrsBU*J1E^-Xc)a?jtlpTHZ>SreJQ2}&~jF?emZ;4J4*|E{!yXoT}K>s#4jeU{0yNvr=hAQSX5!)_x!?9jxmU2cR`XkieC#?p(3Bh zugI62Ce%S$@178n;c8r2zN{FGbrBv4Tl;WhuOaFypK05RCd_;3FV{LHVP!D54tF|N zdSAg+CO@0SG9G*n*iO;iI7wRi*`@@C+G<|;@p(-Df#M>F4j)0PfXP{k=Ez5$qzfMr zyE`3-Xz=EG@Ffucz!#|MD2U@tIz*!2A_CUe>OKM@0HK6b>x z!5!wu9#6VlNO11OeC_!KUk@Y?+PQ8a*bjz(0@vX9km%L5q^vssR}e%0TBW0YrexM5 z49y*5GzGU!c0E8X^YX97u&4!Q13xlPuKh8H8_o>e+V{QvYq9+P2HaMOX(CuT{$K&j z9H+xQr&~?=q>yr&_$eDC`@W>%(H3ov&lQ-kxkdH`1R33{xlSE6z-n;K3)liYd%zp( zV3HrF$g+_1#}PlwhD0m;(dP69>H?M6BKQRSfEtyFK()Pj^YzHc7~;;Ssu~?QvJ!m| z9TD7bebb*=>_P+waSafzitgT_Xka7|oE^ zu3BuI^XU4K+1liQs{@s-k}Z`-ViPNqT}zXJ?b=cOMwY3nVON~)eR9D=nm7*13BW*+7U^H7QpIun zwO>p{sM-H~nPuY{k8d2L6Y}E_Rb}`%2I-paK%HpSJ+=w6m^@Zv)^v)C z_;l?6_=Kyx?k!hXEbNz+hBklgiXNJwh5B;(I~%;HP?XJPnnz*pve!`OJjGI7tHpM; z+MQk-FBW}>8HQBF)J({90(=Wal7_8{W|D0GNMy26wQ~QS|6Zl|J+tku>U!CR>Ibex z#@E{?vL5~0(_UdCWNzZ$%Y*-9q*C&r}8sY-K zD!X^dh(BhB^TO=8f?w3B{aG}!!T$RCKYr5@%FMqE{f+lZFAX0WGp0Wo64+Hop7wfN zku;``I|v@&aKO*)iN|e2J7oaLL#lvW9A5t=m`s0|F~MiB1eX`LclS?80m+8ycke!@ zj5rB@eB`3>>y6zcy!&s@$-iG@iPOKFin@48o2j)15nDm>?|>6kf|Hh53>X@}<-WgC zl6J-D8ERE12psVz5K%U7a@jnQ@tN-5qNa#;Z@wVd&U!Zv9tsOrn?z#U?{P(RR4U@H z?OQ&7MhwvuKK#d<pI{Plp~o1iy@Gyg~Oun42eD(J5t9aP$y#b{PMe@>ey1R_L^DEp zfyM`sz~4Q8?yTJBqUhsbu?j%}nP(Bd%W^nmhW8Le{XlchH)y}?l{Vk#COlXC^(M%r z!00;jNdj-F@|iY_!f!z8CCpvR5ag#2%)ktVdcS;kYn}u1UJWH*L%jE z)qGvN@#5=Zae&PHh>^9C|JqC4zM?yypN;b<2jbxq5TYpAe}6M$tsDY>WVjN9sMOs{ z8xDKxLqpfq>4U}SyWd% zn3MD6F8}!+;Fai;UV>d;=ltVyIs(M>vODa0TJ>TC)s%Nc??pB7q5ko^(|PYZ{^O6x zHQi4lL?SRMKv{o{0%)%nHIca1b-$lHZff^E2)gQC$(n*^7pfMjh?WaO2#rQ&6loRx zrpZE0# z)g93h#kO`0B1$Jo{ArH=EXeO7?5F>;DA<1zaB?Hp8w-nQgeu(h&hJYM`b?1g@7sk> z@UMsX>uKJ(iBHu}cSqEGq|M-8KiY``{~_{&|9a@~&3}LYs=0EbTiv{yhE3_gFLD3+ zPvPO!1)~1GdHa|0_XDG3AjT&uS9x$Td;fCpCmw7*_wV0@`u+0#^M38$?)z^ExjU?pJRF>52qQCD2X>8!j|NCg>-l1SyeJJ5I+j#}Xc6qw~pU*oZ=8W*>Zdby= z^ayL$mWLFq3P6o>9Jrs|SeEB>9UWpI?TL3E!%} zT*4z`C_5^^M>H2|brB>t$eZlu(r7j0h+oZ@OJ;DiWa+Y&ZPn+y&~^z1KDiq58FlGO zDtwe}m3prg&v+^}`|5XpLyYt*5Y0)JIus`88u(cSSEa$zsdJGy^vm)Q;-SU((i(6> zepCXH@$<->d978?JrEJyZNWK`1#U!^+8XlEsr4d+8HesH%c`?qkW4=vgu=)Kfh=bB zNk%>JzYE?jx7RF^?){9jwh)>28-YQ357;;MA|$Kgn$P*GaOgko`H9e)ZBMVm&^iJ9 zfSy%=H0Lp7pzt8@L2f}>F{P;1Ul0ENk%O=fr}R(oz~*FHKlu0a{m1ePqN9HfWhAp$ zqejAYXj6KjtjL7He1rt}>`OqP%4#Et$m-Ld8e2C2of032Ax?j&9@k}IT!1ycJOj3v zk#FKFtDY5Z5>$58Y5a)3@Z$OzDx6K_g++~{F)LyPb^Cqzu`VQ-B*4R_r0(HmN%Iw9ks==tkgQ8ObjFX?dJ*;t;3(R+zw zFYCg&Y()hm#OJ9<9ca}0-x&rOEBu_gCXvt7CMi>lJ8&xEb2pTAURZ%eaFBm?e1qY>lnkErGok<(d~&k)j5i)Xi)alyU?cV7#H zL+EgwiGFRN2%E(!c<(tJcQu@bX7L`9K&^OEZ-{t#jN|@8#hLbe0o7~lw}15 zC*#JIev}6f?d~k7xW$k9gWn8Y0aM!*HmP~5K4RVGc=bG}wK~9dZw|TSXwh!%Eh$lP@Sbs6mH@XG*T1k!H!x$+| z*vdYCFFaUD{ce8;LHb4aJa@{2E}1uhT;Ybit)H3RA~IA&dtx%?0B&MNDQdRY+^oGr z4+*D=*=uGC44r9te~Us<1~DtV_%2IniN{s}d_a0^nzxs&bo!_x?8F$_9+u#&4U=QM zxiD4z&$r8k5*$D_oGRhkU%2OXkr|ffU822! zA$to_aFdYbd8@4CNrGun@R!kQuU@zewD-|_7i*mL-lXjP!2)50}kS^tJmM-CJ zpxy7c2*lEP_)81HjF)$!E({K~fniu?vYE@%{1IfEn}?03ux6Ct_eWI@CqkttcMwC- zGo)f?^N$r>ksU}y^JhI%vWtEo=u056vw-sQ$_addgl{e{a|EWKO)=39$WLNFLWGHD zXY@CDg^Zb2!O_)NiXQi{XAVe4QN3$B5g|h^3vtZS#Y>TueOo=_H-pUJIo+}Z++pGK z4zd;LS4z1)d}55`kQA!%Q&$ya-h)-Mv9??paJVK}?eqq`OFdNTN8_uri(55B5!bgD z4mWCbGvy=^&4$9T7IUop_t&zyh3 zmWk!5Fr6LG0n2N-GResAxM9L4A4u~C6i!XfFH|pQmW;; z=W+F(FTlysx2V+PdjxY}Nfv1TTU@umZw>9%z2ylfb}o$6PPoQP{bLoGsY0a`bu^-i zF)Zl+wFGoJAEfaeiRs9X4L}TsYYMM4oF);z%gMM5_8?l)qnA|7z+GIE{+h1(v5_=! z$E)2b=j0*RVjjv`5%rJz!TdsxXmqTSK|P7+VDw86!RZTx1OW_%=a|+)vGL z2AoNTW3IbpuRiwbd~V88y6}x`g&S8RBU9{SerA{=`%lKLpBY7)2n(hHajt=p7%v3M zIvWkd_#+TyS_k4!wL11SK-$Yxf}B}OXcx{7Ev4OgU0368(caI%@XVI;h8xXFQpv>b z(l!2sF~O0y6vfJdnK$*vHo#z32gzYK3PIlDF<2-33Bv`&5;srDf1$*=?40Y&UR>r4 zptuOTGV3A}s-hyW;m?LDrw#WpoaNFaaue$b@Rk0@saslk5Y(5kwwzYn&((4;TxU)? zc4g4^iI#7fLDpd}{JxaRCk`XP!AQt)xloyu!{pvy#-MJ9>olu^W+)F%e=%46zA7^! zCs4L%o57ep|Dx+D-Jk}=pP*5lq-}eN({On<3bT776Euv}&U05d6j9!;>JzXm28o6< zu)JRn7rK}~(9=NJhmj!-g-KKE>;=~ycP@hZV8|#DwkM=RL}UmpnnfojMi#uXw=IUj zZC>0YN_EZ5C_r5L^T$>&7|-xLgP6LX&k&EviFjo;xfA7c5sWmifct&Rg;`fP$@sh8 zKVitIKCNcA!^#HgnIlDP-Ed6Cuyv<${@T$F>D0%(AOQ z=8IZoKIug;y5pzjD}UB`F~+5`Pax(@<-6;G{SIGq#m&N}cB1l&p|mL`kx5{j7Mwb- znKsgwpL%pejoP(8?BSUhO)Vj;YJX0;JItaBZ@ge=gU4V{i4Y{D5p2=_Tyjh-=jJYn z^~P!KA3mW&z=RurXsJ?FU*X)_^XP11kM-X7l&J#;0k6_em-evw(e7Q*>gf@>BEo8h zsI|`+VDRQJp3R!-Bfpc4wb*R zzF&7UUFiOeU-#^OBB2!!o%h>*q}x9E1qu)ewIlUQVFBmlp&aKIz&g0ULMqrN&FPhe z#v{NlN#blM>z7OF;4~FT$P*ZOF$<%j-r_fkbp!cm<|Hq!G;DXKeIbMA61?&)%`K-N zyt}*ZT3pRz*L`c`!#Ui9vH*{Iqpjo+fXzqZJSso+4TA%1^(wsehUOVV0Z=yOMR2)d zxN{H>V`p%CG>vkta)%|uUlrHhu77X~T-`43H|0oGT>}#bu7rZ2{S`o0DkY~lW#!k1Z))@MkY_nY+@w)HNfr36KmilUs{S3 z4j{o7vjm=5%S!3^Vb1(7JdfWt{$7M|Z$&Ezs2#%lC&q~==VSM z89Ln|>*GxYl0SO=XMqt`iuxIG=;@c1S4X#0eD~D6hpu*7=33}8yoixYZSi(*0IR$+B;uP*yXT`SA37FGPgJzuIUK$pf>4((xs^i@QE3_I$q-9&z=aU1UwK)qWN< zfSY<^T;qNKs3C02+5}m1o)|xU-qwDEO#gu_wWl?dX|xpT7C?rW2k#tyMN(=CR*lpm zJaK40g5-%KZX+f2urcg~Bdl@)w z{jED~?k8AGZs9DtpCOz%M>`SWctg6rO9jU)ihy06_ND}!2Cu+dte+;DZ~LQcp{xbU zHrp1^{j8sP`F&6~gAMMbI~Zhomv?2ziUXA7nl^$!mCj)0+-^Z{Azflx$&((&vmv=8T=8qLxdxM}gFmYbK(%*$|LZsaBz3%HBv{N0aD6Uv>iAu7-G`Ou>M*FS~( z)kR0C@Mp`br$oUGf$gIGhddGl<@S{S-~#o-Lx*r$_@=wl#I+LLI}x& zY!Q)_GRk&UHmS&nR7Cd9rZP%IWUr!OyUL!w^LcEyZuj@!!|VAz-_JOo^Eu~z-shYr zcl0fv`inAW;e3rja4C5u#%e2X(&Q1f49<^E8YqTjs+YDveZ;~`j|YKt6_^&s zEcH+=`TCEq(MV(U%IZv?orV&>=_+hl64CF(9_3e9Vn6zv{L;0RLKKm8M&Bqnr9G}U zO((jftQNs_UQFDkll_|xt8aDi5f<*JQ2i!hk8%~aVB;Df3M0F1yGif+-E?^PbL1(z zmuJ7^h%MRck&cAuo;-%CDBsA7y?xxe??VQJk@#3|Bbmn4Mt78;c%d#G9dMgQS{sFC z1t9EQ3)Km3Gr!Tl?RtsO2L20#_;?% zVvl?4y-+M= z?K_A{o0Q6=Dvo@Issl10__BS2MW=#%*+T;R3jjxWrt;YA%QQiFa^R-pHHAM?96261 z``T!NS))WZacQnW2J3q%6$PPZwLB0Py>K#*wEnIFG>;es;8nF%E>$>ds^NKIAQbe< z>2hfFhZ6EnE?Iw#ozx7`ZOzo;$d`I)j~zZlE>h^Mb>N-?cn@FMI6V22=q-iW$SWE- z$weakZ_J*mWgIvcre%=B5uw7rpmz|Q6N`L=*K4A(ygFw9j)2n)i+AdCn;#*pK{*5I35&_DE=5Coi^Q2opF1aJ|?W69ECsbVHw zGW1?sS0g_}IPT9mR4gNpk#>85%g$Botq1GcsN*b54-I4tJg-`E_Jfgg8Ue!MYTzyx zl2ee=wipM#gLaV*o&I(M#@=ka=3YIxVca>w!gv`2FK@f~(q+c~b80L*&8;fC!PIgF z0)~si^d+gUyQip1H>;=_1fKSa9S{hfPzH56TA7^X3|VTmQ1$)J@v;tfk&EUZ_W33X zRK{kt46t|Zv_~rLHr<==N1i4$0{W8{nz?NGq6NjneqxrbM$m;s^^Vy=>oq@+4( zRGtZ_{wl(6!XDo#MmZwGB)h*>h23X9&THNl0RcbdBK!mzE$kEDusPI|zP(kYUr7+~ zU^1h?ejQCwj-u~Z2bxlifn`DPhck4WINPgQKBjWQuvqW|9!`109@1r7{2H_ zaOAdC@2vn`K7g=lpWZr6qH;%<^{u3J8;H2T)izG(o8{%qVR+b7tQ!IqEjP4Vi{9o( zI9p!mqRj`AYDn?v-{}J~DyFDB^Xd!Vp!PYkz6s_Gmi9YeKXSRfY`W!8K**p~oP!IWP~Zd; zyKqUPI1fw1WJLlL6!kX#{`rmd{wn0g8-sHp3$^)7{bka|{Klk2rxm9wR15EP{h?aW z+E7$@h?vxf%2g$I-oWw8#V2vtHn7bN+*ujKJlNX|d<~ahhjfKfai7~B(gpJ{Kqqn` zC|dDRBzABa3$U>TVNsP!;m}BZ7cx2Se~mi-T~(htYB6{U*W-e5{%`jT$e>ki9|uTE z;YdUr$Fa*Nur&0-c2)%Tl~StLg%)J|0SD2q1)xW}<%2LddMzJs4z3buhhnTZM zpJx&+9OEae_|;|(IBv?ma-Ee!Qlh)U=7%p8H7LL%(<;Yt*k+o0jlQW?@&U>;u#If0 zmLZQThnV<5?TtdXrM2$lHrVJENnKD{#*q6UM?Z|LYj7f)zByKg^2DEeWYdyi9MU>~ zAcp5fb7rWhl~P-VS6HLvk7E(z^PfnZgS*_^D|S55lftrl#E}NRt=z>_6M~;;H5Z>? zMXRjacuwCJk1=@ia_09}9kEPGiGL|J|5>$qECFvPChBrh5W3+AZCwI=nc34NXCQp@ zwuSb{E($G-~V$WtOR{SXP~_GmD_NgS*ewArKSl;Fpk3u+L977Ck-Hl33r3pbTqE?j$^A z+lCk0nAL2+Mw53_{vsHw@nzQA-d%B!w+uU_jn53B0>7bwxv-GsE)^#?>0T>-NF-k4>$u%w^ zvaPbMGBL@3o#zg>m-0qC-jkP#eg_6_TE?@^x&TeoNsN5BnPThBr};Wiq-2gkM~BZe z^M?fhlX4?w+Lk1bl9SJgX1(<~erK*L`{E(*EM$Op(2RRoV+E^Wy#mf zN3+~colD4)*CdHMRM$c6dO*bT<(B=Ua5K(~Dn598=D;ySDT)G64v5PagYwSxthO0; zpP0Br5lWTt>Dw9Nru|D>1l#h0>^7I+x!Q4Y_#A;xU>T-j|Gf7<*>k&+SKZKhPNHF7=~&VCz~m^qT|(WRo+Qw##PDH26OFO}H&ugCg2S0~ zt9nF{m%ukL*4VG`yld(?AUZMp<70I96WopRvUC6dss*$z&+u&r%L!Bwgw2E_JO@;! z_ct5WF7vjlzV;*mbcG+z$_6I2EGi?wH1?PBd0X?1pMR`E(G0dN*!GV!_6`+QLPWnZ z?rlQ9u$N>>!ElA5(^u|?(w2_B>YV*^a9PVEum8)_9bx{C@*zj}A_ULCkvF}-Jk3^v$A8m7o?NPvw90M0PGe0w{xH|hz8AXPd|0-?zDVbKO0 z4Z)tYAtRqrZLXRE71n5pE9$o5r6=1oy=X6^;!MqVCb>TQJJ0I3zT|-3c@ZHUGv~}!4SQp{7!{!f(9cSI znhoL^THz&bxd^RlG;Ovgr$w#O-nQf#rVY_kZN1sW=UO_9VKr2ZpQUj`n7o|gu}ASm z9Ubvw6ad1!qif*-)LrTFI$~6GASXeF>)pfGWKUV!R5JT=C z>Ye7g0I6JTCd2)wv7vLo&}b1yX51@vTt3k29g z3#GJHJ;Me6%^ck#+V#GIMknGUoB<^+cWfx63*z^W3%{zUg~+be1N(+Pi7d?i2zhIl zXPb|VmS;*aLGAvB1`h;D7<{PBQm-4yQ#G4HMj!L;{FW;a5Ab-rOI-1bpk$lOHysBN z#X&ls{yqp4>AluogS=ZsLeS+;p&qdzO}v2Tw=iufUS2eraoVE>QHsy>Vebv%lb`?x zqG1@A&4qX--|Dc1?W}$vZ3rP~&f4+E8MV!h4?HhGW;sON2Ep+V84JSZg5Mqul@(^#$P&^7au8h% zU4sb{!Yz-1mcf~7^$EZD zy|z-rmPsXZEx}0+iI82xb|-&CivpdZHTD@}dh<)k@A5kry0yT*LAlB;N}6 zV&g4K{UZ^742SwpKzLZV!!F;vV64Fk(wBlV%jH^=9lmf7%yY4_J2-sWrgNZQ(A+^q zTlgy;ML#xb?C+u;p5w@mE{f%4TvuhSSB;Ry;M|`{6JH6fnPO!<$48C=Q zBXgViy)apo?DN6ULLl$eLTie=q~_3JOVON`=Z{JYzMUPP%;iS3D+NtM=9FaY5>znvp z_)bFiaB{`C`j3&EHz*(qWPpNEhyX`HM?4`%r29s8OOkU>wKNt6fs3RXzwPacEuTh| zK}L;*Tg9!y>>}LQX&9`)5Cc|JZWrP_+=fO!26avfFM z*L&Q_EpC-%Pb&qUXVOoBxH7>mkA5vUhI@`exZ(pG#lXhNrcTtj#6mlVjCA{|{W4A! zycFqEW3m+ehI+4|$hVq(y5VDWgSME8K2&~VI5W=Bl#0Y$s!Qw9?Kv*H61Digi=#Ui zGiqN>nlV0$PD9zwf({1PSS4;h{%jhq#2r3wwv{Ii~wh!jjYN3;Db)mnYh`kw5h5? z-(zxKdDvU1DHj$2KD1pXaM&ZM{#_BZ68X5tL_#CDxj_s7t|Ul=m|4D)_l* zZPeuUSFeWD1lEB089|^&8w41pXnc)`NqZABbnAC6yjPxw1!70t^#1-*l0T92#js%hf|do zz3O}?cLwrxx!p?frtR~UDKRT)8a?5H8OFa}FfZ}BDgj^Py03pSO~SbAIiFH*oPOB; z%q1LI44Cp24&1ZR^L^RhtPy@6d-(V{u1qpDlf9>v{W#+)Q6Ma^s&p#$06!S|p~{9R zh=l9|^2X%ZRIt_?&B!KtqhxTMxxuHV7={@4T0@oi5b(N!Ga4<0Nflh7}Kq?(I)eltdf2GnBs1vT^A?VN8b*?nCGPR{S?||y&WekP zM$bINIEcT8)XWDm!#j42MyNWnoJ+BBuveO$F@2#qRSl{vjRBuir@uSrTFRUUi{E7S zBR%#zGjV%a%i;ohCc&UByWp>iE%NaS6Q=xNMBI9ux^rhngX z_**9=LugKn#3~;-K7?0(J+$6fsEM}TI6bIT_@>{`sx(R@) zJ*C!r(w|KEDh6<~JC-^2PNj!98&-t|0=ej+-iT)<#aF(vxqi6rbmy_(=APwGP~vx& z`zzetuOROhc#w9+wDbpO(gMO-w{!lmE~QY7f}l;BVRSctwKIaaARv@H@acB#pDa1E z8lBTYuwRN`X+i7@xJ+C^0IML<-$h2}_q&+5i19~C9F3!Wp+-+Ml(pnSHN)mQ>>H}S z7djPaW`-96Z>kp>xwEN|97xQWhJbkcGIrmYOZZxz*#W3D~Fnfx<}k zx_>OWpNThqt7!v|6WoFEQ+P^^!FJc52QOZ$i?O&JJ3ZVtKf(Wk2*vF>EJN3=ZB@!k z2Ab2AGFcnu9a!oh79Y%STPKYOR*4*L{gbzo_{WLOwsTnGU6+YkQym+W!YQe7huGNh10Y(KWH z^fE7Y8oxgwj?=?oc?%#x0?r{lTGa5e$J65>$g0g@|@`+Fg z8|dV{*5vFrye_Q6*;sGf_8FzeDq-K90~TH#>Lr&MJ0om9ZVEx%_8(fi)O1oupD8%9 zr<0jA@}htpovV<}Le~L9WmjL40pxe&Z_znGK0U`kp@Y&pY?edbb58zT2@RMx&!9JLrT&JjoIy6^m3ddQN6{Q}fQZe>nZAEZSMJ?8W zbRG=JfmEUXPS0qL(xQHuZ!<^fw`lmvxD33VZ#f^H|IpbopAit@O7Wf22>~vlIhUQf zAwQ94;o|ti>>}FMi=0*Fh*uE553dlmqZbu2x9qrRQ4k5F4RVfahl^&vZ=;Eu^|{f6 zBtn8xE$Z3=3mH9PFvLL7g>O8&DBRfRMHXczHZ0fdwtWnF&|Rxu0J6FE56E}g=kb_6+#+8aR`ezDe!U0iMqZH0v{zvhQn;M_p7vJe~W0> zAM$NNhqO5EXm7hYO_qVcRFp9lgP52zlLhrzQF7vw33e8LDT^m16F{tMD^CiOi<5B z?+?Gnd_D0@?C?DH(HZ+Wq>8MS=lWCYrgn@J8)ilofCm^Kyotv-Gj|@b!ePTIw1uw|-#3mE)LZ)9HkbyL1+1CD^- z8;0ab`q&^NS`I0qs%y#LC@5q|peT4;m?juD%JG8t&B>(;QNG&9^qH0pk6x%3$Fd`X zUxKCVNRwkp<~~2UwukKPww2|4#S~jJljCoS&AoM=e8m_v6laM%ExxBmQ43NaF*S^61Zx28YmVbbHx?zu{;-+z&h8?py%=$Q-@dSU zFOrfj@s6j%um4=JI^jc&cX5JRdMyKD*-E>~zMPl@{ z9f&jwboR9PSoYk-Y~Ds3zI<1Fe25>AGU3KJ`|;sb@daMnp*HMw|2PvYxFnsO4XJ;> z+!h0EB%&@cYYSD*0~YkeM74ARXjM;v*__C)HN|pABYv-dN>VG2Xv}@W4A`DLlX}1F z!#92mLr0iX0SCja&ww>J7e{f|M7SxhjK(DDl611#44av^R~BOa7%MefVKpLvU8Sbc za2jq9m6$@v4*WyY_bL?kmj9FiGORL3UqvGx(J~I6N(NB0vreB%bebpn0C-Ud4wTMj zD0c`{O|FtXl!?s+eo`&;Z42r8aZj5s1%LU>!i*2?2NvU(KRxkwQk&wvV{chd!@*`NzNmmjCvIjV_S*!y=3j*7;VLX*tAg7M3NGja^29S6+fd< zjFJeBNq&R~uROt&twKR-2Lx`7J@*E^rgLEJQ_fT1t+D8Dg5HZtv-Sr~$^&X9LBw)< zYBFa*42D7nMxaq?(=lM4F$`wXga*2(m^>UzIXL{S6SXKD;{y5{rSkn!VbAR6VVPnM z9Ov4eyirY1v$Wx^jf<3@7;%~R;4mXiGi$P2ZQB^}(=`$bQjzzOm6 zO1Gv&YlVZXD_i&ht=hg9O54b!%ClMpnondVJ02=+o~jaP$;j(NdJDg`V- z*LPBr;R({8b(M#3l=8GWmZB-a#KD2-Sk&gmcPpqd(jzkXd-c`e+}43QIXdhu45-wz z@2(|xl)dVw z2n(ja;A;55*^={kKb=<=;tDCVJODG|YYthf7RUix+& zMi|Np(l4EoyB8DrgOHhxhn=pZG1^)J^;?L^R{Oxy=`pdJ+b{~M560xhXE*0S+JSYo zDyW;UhPg4E>XiNEo!-1RdD(he`FCpFf5L z16=&Lb;D-7c+%I=7*>VSssbGUtZ><`*x}qI9AP-r@n+UDTa8))Q~hvYOaUA0yZ<{_ z-R(oxP{wDPTmf4IVU~8YeMoXtUFGxVOI4E#pdX~cN#8hpjVYd6@d;@%UhWJPHlTFT z3^Uwa6xS1s*5wpMCZf!o`cFsC;S;JWGLgx#e6j)_bNegr@u5iSvH{=|7NxMVR`d6Z$rCZ+xW)RY8M z;p2-H_t@CTosEJ!$U&@K9UF0Are`V7DXp?V!KPJ<1o@?rQ(F3Izo}5}$s_OsP5zjsu6pm0@lB!9W0D^U3S&S&k=1h$P6mV15t^ zOhIHW=4`VayW@Rx)#LPy?<-7Z!33>?PLk}ZW&`;htG6dE8oDN7YSHxpF*uc@5Nz!O zv#UAnYFzg;TKeuj>tQ{>fO`R;I<(KuhL87h7gWfRhgK2}YW~R6Yj)5vq|~x{Z&i7u zJnH-_k$IDk0Pf(rwtBH<7mn`q%#H4s$Sj5HC@I4jQ-=x(cwK|+!al2#ol;S#8if`l z77_H-mBF&fM=B*lAf&Jnh#BOK3$A@Q`WGLIXEeaU?$b@Gr*I{u@ppb?EFA*YUjUTq4)3y>^(bjP#p>H@ zrvuDCGenww%R2)gVG#5A_=MDoO4O|koz$$+1`UftVZ+0xS$&{BgMmSq1yJyfK}#Pr z;TCr(t|7MiKE@eeYs*@R8Zi-wP@_sTsGV!>jHk%}1c%#&EszqxoxMmFLPCh?u0QCD z`Jqf)ClRrcxWgRM_AJ)Xeo8USYU8MhI`Y7x+}g*Mu>i|LHBp4?q$Q~WM}*un-oO_j z=&jHNBg1qM8r|?}K{r4HvwB0lB1Cy=?uzB#{U*u4*ZSSbo2}l5a}NjuiQhn@?3^m( zgr@Ow69WCOSc#x;e$1jW@yeWcMPp!K;qxXv?|CBS)OvJ#Hl!g71>)d|3013TB5p!I zPxh;E+9?xkR-|uO0zaOL!BPosg3Lo3(#$eS?~cT>|S;11wIy~6LAQP$JK(ibny z!lhqF2F4Dd=T9g-Y{#T-KJ@eL4Ul4B>%R!47Ec3;h1)^Qwk?oGxK{I$GA-w#EN#?n z4#1Xj1Rnggr-mO-*kD^eXuMuj{h}^LVOaYU@a_~q9yFEi8t7k4zgT^EUsRb@qY1Dr zj3Kf!9GW;I%$_v_tpN;LB@7xN&*ND_VoN37X1d!bYL!+R^Wch1C`6CdG;}VqbEw*w zQ8`LRmnL0@j36Lm_IKj{sE~PXNe^6((Z6mIOilq?ItDd_OmN4=V8zVUp6p&4KgNy7 zYGcCaY6>J!-M6G~qnm|fD@-yzsuLZ$#5T!oq+f&Q+iIlmW8RXP_PrnI4m=;*4fYnG zAV@DT?RzqZL4gX*^%u>XG~1y9_bm`8N0vfGi+va>iB=1QP<53YzAVohpHY}&Ujgx` zR59-k(#vxiF2TyZf^k+-rGrE!qYD=`1>p`vc`pls8GF}mfq*O~W6fQKv=}aHQ@0q7 z$mY|r1Yl4?IoS+juuY}gKfxPwjlmBvMmpTwix4MDYU#tHRvA6^v zuWa+)Jvn;k47ZRT*omg`-bbc$o1J_wis0sHqb_L1P;5cVyI|KTwi7ElcIm^$d{V9_hBj_pzQ>}fIdnE7$(ZG zM2YKqXU)J&_db|*Dpgz`Yxp zcnkSHA|3B%pT#n1U)PH093WXEZikq4sedMIAajJbzHqXlM7+omd}KAYK%o$tPD@66 zpQu`N1WgB*cro`f$7~J5tsA6Ky}RbGipt*s`sOf+=T$mDUJDT3m=*9}Vi3)?RN@2z>XC7s^dhX@P?0zyR7B;OK+&O41yBhP<4Ui+rNoA?k#98y-2Zey)6DR~{BY@|G-Z{+_d?K0 zl)M%78t8?9*lD;!jQp*Sfj@H$KgoGpTbNp}J&FUuZfm4GnG)T0Q>+Epn%@+rAhZeL zDXJQRH3LPfzFyb%gh7-Al^}pGi?gRd0)8}dgo5*FJQGIH^(V7~t{!OK*aqi;?u()` zYV8z%qPuSt7`(?&f^9EoM+FGi*`{vQ?>)nE!UhgzFH|>`Mo4j}psl%OSW}jjFmP!| zfwtHQSA59)>^IT-TKiE+4!)?`2`G53(qN%E%wjI}a7Df`&s~5~u+FerUU=81Q1HM^ zAe9~=mfS?h(nBuzQ;5_bMXkCF-st}LS|zI>GIb#r?3+5!RxP)0q`$*b^0>|td;Gh7 zvuwa+T)9DJs4>+;O}lRSGVZ#h{);V*mfVaToEkZj2j_QD)8N@JCuHM(7k=s=$_a3* zrD6a$me={LAAUI=8?4~vA^fax0q(ZxgE9gdn}d|sJ_l}PnbThoG8H`%>r>+iq1zMe%mtZmj^|3au5&~p&){cjWj`t@aHiz$M^j(b;0uDnuw zuWr%GAB!J;E=9U2ED#!M>Kfl*XP(vjjTC3x2Gvd}Kz&P$NeBP&|523$-~m+I#=rZ( z*2SfbRKuVCkBV&I8fXQ2=dGL8SY?sB2upq|!)LT$Q>SeGxhGk9GBLR9aMS*|z~ZVe!Q|S}`E1?E zt-T~f6ofvm|Nb&0GiYN{+~850nirJpYgJJNQRRvbURvCLl*YLMB7f%Zie#79|L49C zfR-1;V8Rw-<}XN707GB*6S$4Jt$WgL84K8O`W83omOSR=KuvQi_sYOs<#&;CuKcz5 zVOcAzu7+z6x@Br!J?8$|Yk&Hx#nHLuL!p|g)}0i{z^2&~`O{(l;`tt^Ak->%eg!OH zvcT{9Z)(EV$?2PV!++w!LlI4IYJ44t-W?J3q+>Bf`*nCtmha!7;aNiN{hdi;)$g1 zUu7S}SOkpJLGC~boG!z}Z=qi60U^=)rw}Z|vTl3ePUN~b=(a{a{!?8jYCRaP+vQCI zD_i>WL%n>?7RzwKY$6>|Rh;2e?klh(+p}C&>AAl;Xe;B7WPwL*KA)#Lwj|{Ly((0n zH%O7AcEbjxl(_=( zF23~_FIz6+bpZ;RRbk!(Ed)mR%YsE~N56dE7$tx%EVJwLU7ee28FA0e)jx4hZP52H z=i*3I`|4O<1%1f>IapGo&9Fp+m+$!?c7NhQ-6bP*<(2<(XkO>Qa33)0ep=D-qjJUS zzgbx{gU>pV>fo!zzcJb{+QI$00D&$E@ZyIJ@5hLOFpLva?E|5Yc5z&}SAQ$?aK2xF z%`2GQF}_?=>>Sg_)nt{${rJTRKi`Uq)P;!~M6Mm3kuV<1TJ?n1Y@=*|Y4XyP!S6A3 zC>xXxT>JF0QT!`Gj(mkq>EsqB2lUvl^Z3{O=HmEkbYM^C0@LXiCxw$*H%?vubzl9d zJ`807b9qZFL2qr=@4vj>(oWn9k7oM0zei_}6CZeizna;~|CeqWj5+M-*RN-`uK4)? zCD|<>r)6o_xU%Rq3;1l(!GkxR9F$zQv^}PHK$=_s{tb2q4=irO=hWMqTy1u8$*+6* zHycxP5Ei%UPW`fl5b1=cu{_3Q(cSPew3KLPvQVA@rO<&}i@IU)+pgo3Tz0=10LC89 zw^?$xK}I68E^s{7y>G(_!JXU{=t69N zO|$0f8CfpxSC0GAF#b7PYUIb@jqGSBL%Cn;-nTlkmH)4s02dZ)26vebC%A=cJn{85 z+%*3Fz=N74dLnvt4p8#2r`Tpf4hpJ22zFB4fhvY^XWFsl>V%f z;9B*G`AKg4#+#xh4jE))uc=i9w^FYfyo+!B#mknek=_;uu|F;pE4HZd2zI6L{I|iv z^U?5DS)N65>(aXz@dDOu3kbtM#i-{Ah>?g`X4j>%wI>Gs#D;A^zqL+`Y8=oh<;&WP z7IY=4dU+F9OrdqcxikQEbx_%|j0|ooMurh19?O4lrX#h8rX#polXlYZZCIKbTRfA0 z_4-`@M9zfkX06wR0$P~abwaRVW=pcUvH+0`Fw-$3wfjrwsYU=_^0y%3;&1Ywf{od{ zrNw+%1aa?WlEth?Q2)7Fx;>yi|C~F*^;iBjkN>a4r;!N^*UWKpdjxL0+ap|r|Ldvg zK`A5QcArbv)FR;~I=TAS;%=_2%*y6Qx`P}sunucHcQz(mx!qMUT!SR9?zy^-ZseBqM8-!uH_8kFMaoKrm8I=oe`;T6 z!b~+8wV{sJZ)I-jBreqy+~jHstJ{27eHqCaWYhgexze9h;YF*xg9>JP`7Hgq;TB_v zOji@Of4();r{SG$&&+fPMJTy`k0q}?;u)SWQ{LleZY?^5>Pp42E9<=Y;h&)ArfJ{0 zO`8Z(q)(o}F4^2L{FkQl{;6v#==R7JBd2Pue%jy@gE8rcJn=p5I>GC|xORvuKd??B z=Ma7+%BO)O3aAlH92<1S`VCzal_kye2LNsZk#}2{RPypIwMLwN`g-7pUIn$!CZ@j; zDhOqXRQ=bP-rfZpbo}`3m*8+7$G7_rN^o_h$PB{?mKNuqTe0l&tQ|WJNV>cU=_Hqn zO6$f2f->_vQ~Q_{Y~@wWF_}nb{H))78TMv%q=f2#0hzv~CnH#VY><;_xm@GYDO>yH z6~Vw+q}PF&7#8z{jdIO+Y1kq;*ZhedSo5+a>HHI^hdrAG1Wzaazamrs*5IJrYn+f8 zIpVSWH&YpBBkcmk&AU^zarKpbJ5vt-2N4u!;R*&=ao3}Qb*CKG$Bj+*--9cWgUEqz z-@~noPk8J9i#I^!w|UV`n>H;hwCTS}fDeD5vrDk4F!#U+`6r1z@Sjc667naL#B~4q EAKl1G*8l(j literal 0 HcmV?d00001 diff --git a/documentation/Rebuilt.drawio b/documentation/Rebuilt.drawio index 0bcb485..57746bc 100644 --- a/documentation/Rebuilt.drawio +++ b/documentation/Rebuilt.drawio @@ -1,6 +1,6 @@ - - - + + + @@ -388,4 +388,143 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 57268d869cebee2a80d9d9214b1809a5febcba47 Mon Sep 17 00:00:00 2001 From: SAKETH11111 Date: Tue, 17 Feb 2026 17:15:47 -0600 Subject: [PATCH 03/14] turret: implement director-based aiming and triangulation --- src/main/java/frc/robot/Constants.java | 17 +- .../frc/robot/subsystems/shooter/Turret.java | 442 +++++++++++++++++- 2 files changed, 442 insertions(+), 17 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 086d3aa..e941717 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -129,6 +129,13 @@ public static class ShooterConstants public static final double TURRET_MAX_ANGLE = 180.0; // degrees public static final double TURRET_HOME_ANGLE = 0.0; // Forward-facing when no target public static final double TURRET_TOLERANCE = 2.0; // degrees + public static final int BLUE_CENTER_TAG_ID = 26; + public static final int BLUE_LEFT_TAG_ID = 25; + public static final int RED_CENTER_TAG_ID = 10; + public static final int RED_LEFT_TAG_ID = 9; + public static final double TURRET_CL_METERS = 0.3556; // 14.00 in from GE-26300 + // (https://firstfrc.blob.core.windows.net/frc2026/FieldAssets/2026-field-dimension-dwgs.pdf) + public static final double TURRET_CH_METERS = 0.5969; // 23.50 in from GE-26300 public static final String LIMELIGHT_NAME = "limelight-shooter"; public static final Angle TURRET_PASS_TARGET = Degrees.of(180.0); // TODO: Validate in driver practice private static final InterpolatingDoubleTreeMap FLYWHEEL_SPEED_TABLE = InterpolatingDoubleTreeMap @@ -154,16 +161,6 @@ public static double getHoodAngleForDistance(double meters) { return HOOD_ANGLE_TABLE.get(meters); } - - public static double getHoodAngleForDistanceX(double meters) - { - if (meters <= 0) return 20.0; - if (meters < 2.0) return 15.0; - if (meters < 3.5) return 22.0; - if (meters < 5.0) return 30.0; - if (meters < 6.5) return 38.0; - return 45.0; - } } public static class VisionConstants diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 8566c7d..ffc0fe4 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -1,25 +1,138 @@ package frc.robot.subsystems.shooter; import static edu.wpi.first.units.Units.Degrees; +import static edu.wpi.first.units.Units.Rotations; +import static edu.wpi.first.units.Units.Volts; +import java.util.List; import java.util.function.Supplier; +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.MotorOutputConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.PositionVoltage; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.sim.TalonFXSimState; +import com.ctre.phoenix6.signals.InvertedValue; +import com.ctre.phoenix6.signals.NeutralModeValue; import com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState; import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.Voltage; +import edu.wpi.first.wpilibj.AnalogInput; +import edu.wpi.first.wpilibj.AnalogPotentiometer; +import edu.wpi.first.wpilibj.RobotBase; +import edu.wpi.first.wpilibj.simulation.AnalogInputSim; +import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import edu.wpi.first.wpilibj.simulation.RoboRioSim; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.AIOConstants; +import frc.robot.Constants.CANConstants; +import frc.robot.Constants.GeneralConstants; +import frc.robot.Constants.ShooterConstants; +import frc.robot.util.Utilities; +import limelight.Limelight; +import limelight.results.RawFiducial; @Logged public class Turret extends SubsystemBase { public enum TurretState { - Idle, Shoot, Pass + Idle, Track, Pass } + private final TalonFX _turretMotor; + private final TalonFXSimState _turretMotorSim; + private final DCMotorSim _motorSimModel; + private final AnalogPotentiometer _turretSensor; + private final AnalogInputSim _turretSensorSim; + private final Limelight _limelight; + private final Supplier _swerveStateSupplier; + private final PositionVoltage _positionRequest = new PositionVoltage(0).withSlot(0); + private final TurretDirector _turretDirector = new TurretDirector(); + private List _cachedTagFilter; + private final Angle _defaultSetpoint = Degrees.of(ShooterConstants.TURRET_HOME_ANGLE); + private SwerveDriveState _swerveDriveState; + @Logged + private Angle _fieldTurretAngle; + @Logged + private Angle _robotTurretAngle; + @Logged + private Angle _turretSetpoint; + @Logged + private boolean _hasSetpoint; + @Logged + private Voltage _turretMotorVoltage; + @Logged + private TurretState _turretState; + @Logged + private boolean _hasTarget; + @Logged + private Angle _targetHorizontalOffset; + @Logged + private double _distanceToHubMeters; + private TagObservation _centerTagObservation; + private TagObservation _leftTagObservation; + public Turret(Supplier swerveStateSupplier) { + _turretMotor = new TalonFX(CANConstants.TURRET_MOTOR); + _swerveStateSupplier = swerveStateSupplier; + _swerveDriveState = new SwerveDriveState(); + + _fieldTurretAngle = Degrees.zero(); + _robotTurretAngle = Degrees.zero(); + _turretSetpoint = _defaultSetpoint; + _hasSetpoint = false; + _turretMotorVoltage = Volts.zero(); + _turretState = TurretState.Idle; + _hasTarget = false; + _targetHorizontalOffset = Degrees.zero(); + _distanceToHubMeters = 0.0; + _cachedTagFilter = List.of(); + _centerTagObservation = null; + _leftTagObservation = null; + + var currentConfig = new CurrentLimitsConfigs(); + currentConfig.StatorCurrentLimit = ShooterConstants.TURRET_CURRENT_LIMIT; + currentConfig.StatorCurrentLimitEnable = true; + + var outputConfig = new MotorOutputConfigs(); + outputConfig.NeutralMode = NeutralModeValue.Brake; + outputConfig.Inverted = InvertedValue.CounterClockwise_Positive; + + var slot0Configs = new Slot0Configs(); + slot0Configs.kP = ShooterConstants.TURRET_KP; + slot0Configs.kI = ShooterConstants.TURRET_KI; + slot0Configs.kD = ShooterConstants.TURRET_KD; + + _turretMotor.getConfigurator().apply(new TalonFXConfiguration().withCurrentLimits(currentConfig).withMotorOutput(outputConfig).withSlot0(slot0Configs)); + + AnalogInput turretSensorInput = new AnalogInput(AIOConstants.TURRET_POTENTIOMETER); + _turretSensor = new AnalogPotentiometer(turretSensorInput, ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MIN_ANGLE); + syncMotorEncoderToPotentiometer(); + + if (RobotBase.isReal()) + { + _limelight = new Limelight(ShooterConstants.LIMELIGHT_NAME); + _turretMotorSim = null; + _motorSimModel = null; + _turretSensorSim = null; + } + else + { + _limelight = null; + _turretMotorSim = _turretMotor.getSimState(); + _turretSensorSim = new AnalogInputSim(turretSensorInput); + var gearbox = DCMotor.getKrakenX44(1); + _motorSimModel = new DCMotorSim(LinearSystemId.createDCMotorSystem(gearbox, 0.001, ShooterConstants.TURRET_GEAR_RATIO), gearbox); + } } /** @@ -27,7 +140,7 @@ public Turret(Supplier swerveStateSupplier) * For the turret specifically, we need to ensure the turret * is behaving according to the rules defined by the state the * turret is in. - * + * * If in Idle, the turret shouldn't rotate at all, * even if the robot rotates. * @@ -38,6 +151,34 @@ public Turret(Supplier swerveStateSupplier) @Override public void periodic() { + SwerveDriveState state = _swerveStateSupplier == null ? null : _swerveStateSupplier.get(); + if (state != null) + { + _swerveDriveState = state; + } + + Angle robotHeading = _swerveDriveState.Pose.getRotation().getMeasure(); + _robotTurretAngle = Degrees.of(_turretSensor.get()); + _fieldTurretAngle = _robotTurretAngle.plus(robotHeading); + _turretMotorVoltage = _turretMotor.getMotorVoltage().getValue(); + + updateVisionData(); + + TurretAimSolution aimSolution = _turretDirector.getAimSolution(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _leftTagObservation); + + if (!aimSolution.hasSetpoint()) + { + stopTurret(); + return; + } + + _distanceToHubMeters = aimSolution.distanceToHubMeters(); + Angle requestedRobotSetpoint = clampToTurretLimits(aimSolution.fieldSetpoint().minus(robotHeading)); + _turretSetpoint = requestedRobotSetpoint; + _hasSetpoint = true; + + double targetMotorRotations = _turretSetpoint.in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; + _turretMotor.setControl(_positionRequest.withPosition(targetMotorRotations)); } /** @@ -49,25 +190,39 @@ public void periodic() @Override public void simulationPeriodic() { + _turretMotorSim.setSupplyVoltage(RoboRioSim.getVInVoltage()); + + Voltage motorVoltage = _turretMotorSim.getMotorVoltageMeasure(); + _motorSimModel.setInputVoltage(motorVoltage.in(Volts)); + _motorSimModel.update(GeneralConstants.LOOP_PERIOD_SECS); + + _turretMotorSim.setRawRotorPosition(_motorSimModel.getAngularPosition().times(ShooterConstants.TURRET_GEAR_RATIO)); + _turretMotorSim.setRotorVelocity(_motorSimModel.getAngularVelocity().times(ShooterConstants.TURRET_GEAR_RATIO)); + + double mechanismAngleDeg = _motorSimModel.getAngularPosition().in(Degrees); + double clampedAngleDeg = MathUtil.clamp(mechanismAngleDeg, ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); + double normalized = (clampedAngleDeg - ShooterConstants.TURRET_MIN_ANGLE) / (ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE); + _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized); } /** * Sets the desired state of the turret. - * + * * @param state The desired state of the turret */ public void setTurretState(TurretState state) { + _turretState = state == null ? TurretState.Idle : state; } /** * Gets the current state of the turret. - * + * * @return The current state of the turret */ public TurretState getTurretState() { - return TurretState.Idle; + return _turretState; } /** @@ -78,7 +233,7 @@ public TurretState getTurretState() */ public Angle getAngle() { - return Degrees.zero(); + return _fieldTurretAngle; } /** @@ -92,7 +247,100 @@ public Angle getAngle() */ public boolean isLinedUp() { - return false; + if (!_hasSetpoint) + { + return false; + } + + if (_turretState == TurretState.Track && !_hasTarget) + { + return false; + } + + return _robotTurretAngle.isNear(_turretSetpoint, Degrees.of(ShooterConstants.TURRET_TOLERANCE)); + } + + public boolean hasTarget() + { + return _hasTarget; + } + + public double getDistanceToTarget() + { + if (_distanceToHubMeters > 0.0) + { + return _distanceToHubMeters; + } + + if (_limelight == null || !_hasTarget) + { + return 0.0; + } + + var targetPose = _limelight.getData().targetData.getCameraToTarget(); + return targetPose.getTranslation().toTranslation2d().getNorm(); + } + + private void updateVisionData() + { + if (_limelight == null) + { + _hasTarget = false; + _targetHorizontalOffset = Degrees.zero(); + _centerTagObservation = null; + _leftTagObservation = null; + return; + } + + List desiredTags = Utilities.getOurHubTagIds(); + if (!_cachedTagFilter.equals(desiredTags)) + { + _limelight.getSettings().withAprilTagIdFilter(desiredTags).save(); + _cachedTagFilter = List.copyOf(desiredTags); + } + + var limelightData = _limelight.getData(); + var targetData = limelightData.targetData; + _targetHorizontalOffset = Degrees.of(targetData.getHorizontalOffset()); + + int centerTagId = Utilities.isRedAlliance() ? ShooterConstants.RED_CENTER_TAG_ID : ShooterConstants.BLUE_CENTER_TAG_ID; + int leftTagId = Utilities.isRedAlliance() ? ShooterConstants.RED_LEFT_TAG_ID : ShooterConstants.BLUE_LEFT_TAG_ID; + + _centerTagObservation = null; + _leftTagObservation = null; + for (RawFiducial fiducial : limelightData.getRawFiducials()) + { + if (fiducial.id == centerTagId) + { + _centerTagObservation = new TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); + } + else if (fiducial.id == leftTagId) + { + _leftTagObservation = new TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); + } + } + + _hasTarget = targetData.getTargetStatus() || _centerTagObservation != null; + } + + private void stopTurret() + { + _hasSetpoint = false; + _turretSetpoint = _defaultSetpoint; + _distanceToHubMeters = 0.0; + _turretMotor.setVoltage(0.0); + } + + private static Angle clampToTurretLimits(Angle angle) + { + return Degrees.of(MathUtil.clamp(angle.in(Degrees), ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE)); + } + + private void syncMotorEncoderToPotentiometer() + { + Angle sensorAngle = clampToTurretLimits(Degrees.of(_turretSensor.get())); + double motorRotations = sensorAngle.in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; + _turretMotor.setPosition(motorRotations); } /** @@ -102,5 +350,185 @@ public boolean isLinedUp() */ private static class TurretDirector { + public TurretAimSolution getAimSolution(TurretState turretState, Angle currentFieldAngle, Angle robotHeading, Angle horizontalOffset, boolean hasTarget, TagObservation centerTagObservation, TagObservation leftTagObservation) + { + return switch (turretState) + { + case Idle -> TurretAimSolution.none(); + case Track -> getTrackSolution(currentFieldAngle, robotHeading, horizontalOffset, hasTarget, centerTagObservation, leftTagObservation); + case Pass -> TurretAimSolution.of(ShooterConstants.TURRET_PASS_TARGET, 0.0); + }; + } + + private TurretAimSolution getTrackSolution(Angle currentFieldAngle, Angle robotHeading, Angle horizontalOffset, boolean hasTarget, TagObservation centerTagObservation, TagObservation leftTagObservation) + { + if (centerTagObservation != null && leftTagObservation != null) + { + TriangulationResult triangulation = triangulate(centerTagObservation, leftTagObservation); + if (triangulation.valid()) + { + return TurretAimSolution.of(currentFieldAngle.plus(Degrees.of(triangulation.relativeAngleDeg())), triangulation.distanceMeters()); + } + } + + if (hasTarget) + { + double fallbackDistance = centerTagObservation == null ? 0.0 : centerTagObservation.distanceMeters(); + return TurretAimSolution.of(currentFieldAngle.plus(horizontalOffset), fallbackDistance); + } + + return TurretAimSolution.of(robotHeading.plus(Degrees.of(ShooterConstants.TURRET_HOME_ANGLE)), 0.0); + } + + /** + * Solves for robot-to-hub angle and distance using two known triangles. + *

+ * Triangle R-C-L: Robot (R), center tag (C), left tag (L). We know RC and RL from + * vision and CL from field drawings (TURRET_CL_METERS). Law of sines gives angle at C. + *

+ * Triangle R-C-H: Hub center (H) is TURRET_CH_METERS from C (field drawing). Law of + * cosines gives RH (distance to hub). Law of sines gives angle at R from R→C to R→H. + * We add the camera-to-center-tag angle (tx) to get full robot-frame angle to hub. + */ + private TriangulationResult triangulate(TagObservation centerTagObservation, TagObservation leftTagObservation) + { + double rcDistanceMeters = centerTagObservation.distanceMeters(); + double rlDistanceMeters = leftTagObservation.distanceMeters(); + if (rcDistanceMeters <= 0.0 || rlDistanceMeters <= 0.0) + { + return TriangulationResult.invalid(); + } + + double angleLrcRad = Math.toRadians(leftTagObservation.horizontalOffset().in(Degrees) - centerTagObservation.horizontalOffset().in(Degrees)); + double sinLcr = (rlDistanceMeters * Math.sin(angleLrcRad)) / ShooterConstants.TURRET_CL_METERS; + double angleLcrRad = Math.asin(MathUtil.clamp(sinLcr, -1.0, 1.0)); + + double angleLcrPlusNinetyRad = angleLcrRad + Math.PI / 2.0; + double rhSquared = (rcDistanceMeters * rcDistanceMeters) + (ShooterConstants.TURRET_CH_METERS * ShooterConstants.TURRET_CH_METERS) + - (2.0 * rcDistanceMeters * ShooterConstants.TURRET_CH_METERS * Math.cos(angleLcrPlusNinetyRad)); + if (rhSquared <= 0.0 || !Double.isFinite(rhSquared)) + { + return TriangulationResult.invalid(); + } + + double rhDistanceMeters = Math.sqrt(rhSquared); + double sinHrc = (ShooterConstants.TURRET_CH_METERS * Math.sin(angleLcrPlusNinetyRad)) / rhDistanceMeters; + double angleHrcDeg = Math.toDegrees(Math.asin(MathUtil.clamp(sinHrc, -1.0, 1.0))); + + double angleRhDeg = angleHrcDeg + centerTagObservation.horizontalOffset().in(Degrees); + if (!Double.isFinite(angleRhDeg)) + { + return TriangulationResult.invalid(); + } + + return TriangulationResult.valid(angleRhDeg, rhDistanceMeters); + } + } + + private static class TurretAimSolution + { + private final boolean _hasSetpoint; + private final Angle _fieldSetpoint; + private final double _distanceToHubMeters; + + private TurretAimSolution(boolean hasSetpoint, Angle fieldSetpoint, double distanceToHubMeters) + { + _hasSetpoint = hasSetpoint; + _fieldSetpoint = fieldSetpoint; + _distanceToHubMeters = distanceToHubMeters; + } + + public static TurretAimSolution none() + { + return new TurretAimSolution(false, Degrees.zero(), 0.0); + } + + public static TurretAimSolution of(Angle fieldSetpoint, double distanceToHubMeters) + { + return new TurretAimSolution(true, fieldSetpoint, distanceToHubMeters); + } + + public boolean hasSetpoint() + { + return _hasSetpoint; + } + + public Angle fieldSetpoint() + { + return _fieldSetpoint; + } + + public double distanceToHubMeters() + { + return _distanceToHubMeters; + } + } + + private static class TriangulationResult + { + private final boolean _valid; + private final double _relativeAngleDeg; + private final double _distanceMeters; + + private TriangulationResult(boolean valid, double relativeAngleDeg, double distanceMeters) + { + _valid = valid; + _relativeAngleDeg = relativeAngleDeg; + _distanceMeters = distanceMeters; + } + + public static TriangulationResult invalid() + { + return new TriangulationResult(false, 0.0, 0.0); + } + + public static TriangulationResult valid(double relativeAngleDeg, double distanceMeters) + { + return new TriangulationResult(true, relativeAngleDeg, distanceMeters); + } + + public boolean valid() + { + return _valid; + } + + public double relativeAngleDeg() + { + return _relativeAngleDeg; + } + + public double distanceMeters() + { + return _distanceMeters; + } + } + + private static class TagObservation + { + private final int _id; + private final Angle _horizontalOffset; + private final double _distanceMeters; + + private TagObservation(int id, Angle horizontalOffset, double distanceMeters) + { + _id = id; + _horizontalOffset = horizontalOffset; + _distanceMeters = distanceMeters; + } + + public int id() + { + return _id; + } + + public Angle horizontalOffset() + { + return _horizontalOffset; + } + + public double distanceMeters() + { + return _distanceMeters; + } } } From 6c0976b47612085842690b056074b63c08f61e06 Mon Sep 17 00:00:00 2001 From: SAKETH11111 Date: Tue, 17 Feb 2026 17:38:09 -0600 Subject: [PATCH 04/14] clean up unused imports and improve turret documentation --- src/main/java/frc/robot/RobotContainer.java | 30 +++------- .../frc/robot/subsystems/shooter/Turret.java | 59 +++++++++---------- 2 files changed, 34 insertions(+), 55 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 603125d..03ef31f 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -15,12 +15,11 @@ import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.Constants.DriveConstants; -import frc.robot.Constants.ShooterConstants; import frc.robot.generated.TunerConstants; import frc.robot.subsystems.Drive; import frc.robot.subsystems.intake.Intake; -import frc.robot.subsystems.shooter.Feeder; -import frc.robot.subsystems.shooter.Shooter; +import frc.robot.subsystems.shooter.Turret; +import frc.robot.subsystems.shooter.Turret.TurretState; @Logged public class RobotContainer @@ -34,9 +33,7 @@ public class RobotContainer private final CommandXboxController _joystick = new CommandXboxController(0); private final Drive _drivetrain = TunerConstants.createDrivetrain(); private final Intake _intake = new Intake(); - // private final Shooter _shooter = new Shooter(); - private final Feeder _feeder = new Feeder(); - private final Shooter _shooter = new Shooter(); + private final Turret _turret = new Turret(_drivetrain::getState); public RobotContainer() { @@ -75,26 +72,13 @@ private void configureBindings() // Reset the field-centric heading on left bumper press. _joystick.leftBumper().onTrue(_drivetrain.runOnce(_drivetrain::seedFieldCentric)); - _joystick.povUp().whileTrue(_feeder.getForwardCmd()); - _joystick.rightStick().onTrue(_feeder.getstopCmd()); _joystick.rightBumper().whileTrue(_intake.startRollers()); _joystick.rightTrigger().whileTrue(_intake.reverseRollers()); - // _joystick.leftTrigger().whileTrue(_shooter.getAimCmd()); // TODO - - // Temporary shooter bindings (adjust later). - // _joystick.x().onTrue(_shooter.getFireCmd()); - // _joystick.y().whileTrue(_shooter.getPreparePassCmd(ShooterConstants.PASS_FLYWHEEL_RPM, - // ShooterConstants.PASS_HOOD_ANGLE_DEG)); - // _joystick.leftStick().onTrue(_shooter.getStopCmd()); - - _joystick.povUp().whileTrue(_feeder.getForwardCmd()); - _joystick.rightStick().onTrue(_feeder.getstopCmd()); - - // Temporary shooter bindings (adjust later). - _joystick.x().onTrue(_shooter.getFireCmd()); - _joystick.y().whileTrue(_shooter.getPreparePassCmd(ShooterConstants.PASS_FLYWHEEL_RPM, ShooterConstants.PASS_HOOD_ANGLE_DEG)); - _joystick.leftStick().onTrue(_shooter.getStopCmd()); + // Turret test bindings. + _joystick.leftTrigger().onTrue(Commands.runOnce(() -> _turret.setTurretState(TurretState.Track), _turret)); + _joystick.y().onTrue(Commands.runOnce(() -> _turret.setTurretState(TurretState.Pass), _turret)); + _joystick.leftStick().onTrue(Commands.runOnce(() -> _turret.setTurretState(TurretState.Idle), _turret)); _drivetrain.registerTelemetry(_logger::telemeterize); } diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index ffc0fe4..93af02d 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -136,16 +136,12 @@ public Turret(Supplier swerveStateSupplier) } /** - * This function executes automatically every 20 milliseconds. - * For the turret specifically, we need to ensure the turret - * is behaving according to the rules defined by the state the - * turret is in. - * - * If in Idle, the turret shouldn't rotate at all, - * even if the robot rotates. - * - * If in Shoot or Pass, the turret - * should rotate to whatever angle is provided by the + * This function executes automatically every 20 milliseconds. For the turret + * specifically, we need to ensure the turret is behaving according to the rules + * defined by the state the turret is in. If in Idle, the turret + * shouldn't rotate at all, even if the robot rotates. If in Shoot + * or Pass, the turret should rotate to whatever angle is provided + * by the * TurretDirector class. */ @Override @@ -182,10 +178,10 @@ public void periodic() } /** - * Any logic needed to specifically manage any hardware interactions - * when the robot code is executing in the simulation (for example, - * update the 10-turn potentiometer's angle based on how the motor - * driving the turret is moving) should go here. + * Any logic needed to specifically manage any hardware interactions when the + * robot code is executing in the simulation (for example, update the 10-turn + * potentiometer's angle based on how the motor driving the turret is moving) + * should go here. */ @Override public void simulationPeriodic() @@ -226,9 +222,8 @@ public TurretState getTurretState() } /** - * Gets the current angle of the turret. Angle is given - * in field-relative space. - * + * Gets the current angle of the turret. Angle is given in field-relative space. + * * @return The current angle of the turret */ public Angle getAngle() @@ -237,13 +232,11 @@ public Angle getAngle() } /** - * Gets whether the turret is currently pointing at its - * desired target. The target to point at is determined - * by the state of the turret. - * - * @return true if the turret is facing the desired - * target location (or if there is no desired - * location), otherwise false. + * Gets whether the turret is currently pointing at its desired target. The + * target to point at is determined by the state of the turret. + * + * @return true if the turret is facing the desired target location + * (or if there is no desired location), otherwise false. */ public boolean isLinedUp() { @@ -344,9 +337,9 @@ private void syncMotorEncoderToPotentiometer() } /** - * The TurretDirector is responsible for choosing a target for - * the robot to aim at and communicating the desired turret angle - * in field-relative space back to the main Turret subsystem. + * The TurretDirector is responsible for choosing a target for the robot to aim + * at and communicating the desired turret angle in field-relative space back to + * the main Turret subsystem. */ private static class TurretDirector { @@ -383,12 +376,14 @@ private TurretAimSolution getTrackSolution(Angle currentFieldAngle, Angle robotH /** * Solves for robot-to-hub angle and distance using two known triangles. *

- * Triangle R-C-L: Robot (R), center tag (C), left tag (L). We know RC and RL from - * vision and CL from field drawings (TURRET_CL_METERS). Law of sines gives angle at C. + * Triangle R-C-L: Robot (R), center tag (C), left tag (L). We know RC and RL + * from vision and CL from field drawings (TURRET_CL_METERS). Law of sines gives + * angle at C. *

- * Triangle R-C-H: Hub center (H) is TURRET_CH_METERS from C (field drawing). Law of - * cosines gives RH (distance to hub). Law of sines gives angle at R from R→C to R→H. - * We add the camera-to-center-tag angle (tx) to get full robot-frame angle to hub. + * Triangle R-C-H: Hub center (H) is TURRET_CH_METERS from C (field drawing). + * Law of cosines gives RH (distance to hub). Law of sines gives angle at R from + * R→C to R→H. We add the camera-to-center-tag angle (tx) to get full + * robot-frame angle to hub. */ private TriangulationResult triangulate(TagObservation centerTagObservation, TagObservation leftTagObservation) { From e96966c8083a2df3e22d439b8454034728c5f5df Mon Sep 17 00:00:00 2001 From: SAKETH11111 Date: Tue, 17 Feb 2026 18:53:28 -0600 Subject: [PATCH 05/14] turret: extract director and simplify aiming path logic --- src/main/java/frc/robot/Constants.java | 55 ++-- .../frc/robot/subsystems/shooter/Turret.java | 304 +++++++----------- .../subsystems/shooter/TurretDirector.java | 125 +++++++ 3 files changed, 278 insertions(+), 206 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/shooter/TurretDirector.java diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index e941717..cf43491 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -120,30 +120,41 @@ public static class ShooterConstants public static final double HOOD_SIM_MAX_SPEED = 45.0; // TODO: compute from motor free speed and hood gear ratio // Turret - public static final double TURRET_CURRENT_LIMIT = 40.0; - public static final double TURRET_KP = 2.4; // TODO: Tune - public static final double TURRET_KI = 0.0; - public static final double TURRET_KD = 0.1; - public static final double TURRET_GEAR_RATIO = 13.0; - public static final double TURRET_MIN_ANGLE = -180.0; // degrees (full 360° rotation) - public static final double TURRET_MAX_ANGLE = 180.0; // degrees - public static final double TURRET_HOME_ANGLE = 0.0; // Forward-facing when no target - public static final double TURRET_TOLERANCE = 2.0; // degrees - public static final int BLUE_CENTER_TAG_ID = 26; - public static final int BLUE_LEFT_TAG_ID = 25; - public static final int RED_CENTER_TAG_ID = 10; - public static final int RED_LEFT_TAG_ID = 9; - public static final double TURRET_CL_METERS = 0.3556; // 14.00 in from GE-26300 - // (https://firstfrc.blob.core.windows.net/frc2026/FieldAssets/2026-field-dimension-dwgs.pdf) - public static final double TURRET_CH_METERS = 0.5969; // 23.50 in from GE-26300 - public static final String LIMELIGHT_NAME = "limelight-shooter"; - public static final Angle TURRET_PASS_TARGET = Degrees.of(180.0); // TODO: Validate in driver practice - private static final InterpolatingDoubleTreeMap FLYWHEEL_SPEED_TABLE = InterpolatingDoubleTreeMap + public static final double TURRET_CURRENT_LIMIT = 40.0; + public static final double TURRET_KP = 2.4; // TODO: Tune + public static final double TURRET_KI = 0.0; + public static final double TURRET_KD = 0.1; + public static final double TURRET_GEAR_RATIO = 13.0; + public static final double TURRET_MIN_ANGLE = -180.0; // degrees (full 360° rotation) + public static final double TURRET_MAX_ANGLE = 180.0; // degrees + public static final double TURRET_HOME_ANGLE = 0.0; // Forward-facing when no target + public static final double TURRET_TOLERANCE = 2.0; // degrees + // Pot calibration model: + // - MIN/MAX volts are measured at conceptual turret min/max angle. + // - ZERO_OFFSET shifts the conceptual 0-deg heading without changing hard + // limits. + public static final double TURRET_POTENTIOMETER_MIN_VOLTS = 0.35; // TODO: Calibrate pot voltage at min turret angle + public static final double TURRET_POTENTIOMETER_MAX_VOLTS = 4.65; // TODO: Calibrate pot voltage at max turret angle + public static final double TURRET_POTENTIOMETER_ZERO_OFFSET_DEG = 0.0; // TODO: Calibrate conceptual turret zero offset (degrees) + // Dead-zone model (robot-relative): + // - Center/width define forbidden cable-wrap sector. + // - Width <= 0 disables dead-zone routing logic. + public static final double TURRET_DEAD_ZONE_CENTER = 180.0; // degrees (robot-relative) + public static final double TURRET_DEAD_ZONE_WIDTH = 0.0; // degrees; set > 0 once cable-wrap dead-zone is measured + public static final int BLUE_CENTER_TAG_ID = 26; + public static final int BLUE_LEFT_TAG_ID = 25; + public static final int RED_CENTER_TAG_ID = 10; + public static final int RED_LEFT_TAG_ID = 9; + public static final double TURRET_CL_METERS = 0.3556; // 14.00 in + public static final double TURRET_CH_METERS = 0.5969; // 23.50 ins + public static final String LIMELIGHT_NAME = "limelight-shooter"; + public static final Angle TURRET_PASS_TARGET = Degrees.of(180.0); // TODO: Validate in driver practice + private static final InterpolatingDoubleTreeMap FLYWHEEL_SPEED_TABLE = InterpolatingDoubleTreeMap .ofEntries(Map.entry(0.0, 3000.0), Map.entry(2.0, 3000.0), Map.entry(3.5, 3500.0), Map.entry(5.0, 4000.0), Map.entry(6.5, 4500.0), Map.entry(7.0, 5000.0)); - private static final InterpolatingDoubleTreeMap HOOD_ANGLE_TABLE = InterpolatingDoubleTreeMap + private static final InterpolatingDoubleTreeMap HOOD_ANGLE_TABLE = InterpolatingDoubleTreeMap .ofEntries(Map.entry(0.0, 20.0), Map.entry(2.0, 15.0), Map.entry(3.5, 22.0), Map.entry(5.0, 30.0), Map.entry(6.5, 38.0), Map.entry(7.0, 45.0)); - public static final List BLUE_HUB_TAG_IDS = List.of(2, 3, 4, 5, 8, 9, 10, 11); - public static final List RED_HUB_TAG_IDS = List.of(18, 19, 20, 21, 24, 25, 26, 27); + public static final List BLUE_HUB_TAG_IDS = List.of(2, 3, 4, 5, 8, 9, 10, 11); + public static final List RED_HUB_TAG_IDS = List.of(18, 19, 20, 21, 24, 25, 26, 27); // Feeder public static final int FEEDER_CURRENT_LIMIT = 60; diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 93af02d..f28a0a5 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -50,12 +50,12 @@ public enum TurretState private final TalonFX _turretMotor; private final TalonFXSimState _turretMotorSim; private final DCMotorSim _motorSimModel; + private final AnalogInput _turretSensorInput; private final AnalogPotentiometer _turretSensor; private final AnalogInputSim _turretSensorSim; private final Limelight _limelight; private final Supplier _swerveStateSupplier; private final PositionVoltage _positionRequest = new PositionVoltage(0).withSlot(0); - private final TurretDirector _turretDirector = new TurretDirector(); private List _cachedTagFilter; private final Angle _defaultSetpoint = Degrees.of(ShooterConstants.TURRET_HOME_ANGLE); private SwerveDriveState _swerveDriveState; @@ -64,6 +64,10 @@ public enum TurretState @Logged private Angle _robotTurretAngle; @Logged + private double _continuousRobotAngleDeg; + @Logged + private double _continuousTurretSetpointDeg; + @Logged private Angle _turretSetpoint; @Logged private boolean _hasSetpoint; @@ -77,8 +81,9 @@ public enum TurretState private Angle _targetHorizontalOffset; @Logged private double _distanceToHubMeters; - private TagObservation _centerTagObservation; - private TagObservation _leftTagObservation; + private TurretDirector.TagObservation _centerTagObservation; + private TurretDirector.TagObservation _leftTagObservation; + private double _lastWrappedRobotAngleDeg; public Turret(Supplier swerveStateSupplier) { @@ -86,18 +91,21 @@ public Turret(Supplier swerveStateSupplier) _swerveStateSupplier = swerveStateSupplier; _swerveDriveState = new SwerveDriveState(); - _fieldTurretAngle = Degrees.zero(); - _robotTurretAngle = Degrees.zero(); - _turretSetpoint = _defaultSetpoint; - _hasSetpoint = false; - _turretMotorVoltage = Volts.zero(); - _turretState = TurretState.Idle; - _hasTarget = false; - _targetHorizontalOffset = Degrees.zero(); - _distanceToHubMeters = 0.0; - _cachedTagFilter = List.of(); - _centerTagObservation = null; - _leftTagObservation = null; + _fieldTurretAngle = Degrees.zero(); + _robotTurretAngle = Degrees.zero(); + _turretSetpoint = _defaultSetpoint; + _hasSetpoint = false; + _turretMotorVoltage = Volts.zero(); + _turretState = TurretState.Idle; + _hasTarget = false; + _targetHorizontalOffset = Degrees.zero(); + _distanceToHubMeters = 0.0; + _cachedTagFilter = List.of(); + _centerTagObservation = null; + _leftTagObservation = null; + _continuousRobotAngleDeg = 0.0; + _continuousTurretSetpointDeg = 0.0; + _lastWrappedRobotAngleDeg = 0.0; var currentConfig = new CurrentLimitsConfigs(); currentConfig.StatorCurrentLimit = ShooterConstants.TURRET_CURRENT_LIMIT; @@ -114,8 +122,8 @@ public Turret(Supplier swerveStateSupplier) _turretMotor.getConfigurator().apply(new TalonFXConfiguration().withCurrentLimits(currentConfig).withMotorOutput(outputConfig).withSlot0(slot0Configs)); - AnalogInput turretSensorInput = new AnalogInput(AIOConstants.TURRET_POTENTIOMETER); - _turretSensor = new AnalogPotentiometer(turretSensorInput, ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MIN_ANGLE); + _turretSensorInput = new AnalogInput(AIOConstants.TURRET_POTENTIOMETER); + _turretSensor = new AnalogPotentiometer(_turretSensorInput, getTurretPotFullRange(), getTurretPotOffset()); syncMotorEncoderToPotentiometer(); if (RobotBase.isReal()) @@ -129,7 +137,7 @@ public Turret(Supplier swerveStateSupplier) { _limelight = null; _turretMotorSim = _turretMotor.getSimState(); - _turretSensorSim = new AnalogInputSim(turretSensorInput); + _turretSensorSim = new AnalogInputSim(_turretSensorInput); var gearbox = DCMotor.getKrakenX44(1); _motorSimModel = new DCMotorSim(LinearSystemId.createDCMotorSystem(gearbox, 0.001, ShooterConstants.TURRET_GEAR_RATIO), gearbox); } @@ -154,13 +162,15 @@ public void periodic() } Angle robotHeading = _swerveDriveState.Pose.getRotation().getMeasure(); - _robotTurretAngle = Degrees.of(_turretSensor.get()); + _robotTurretAngle = getCalibratedRobotAngle(); + updateContinuousRobotAngle(_robotTurretAngle.in(Degrees)); _fieldTurretAngle = _robotTurretAngle.plus(robotHeading); _turretMotorVoltage = _turretMotor.getMotorVoltage().getValue(); updateVisionData(); - TurretAimSolution aimSolution = _turretDirector.getAimSolution(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _leftTagObservation); + var directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _leftTagObservation); + TurretDirector.TurretAimSolution aimSolution = TurretDirector.getAimSolution(directorContext); if (!aimSolution.hasSetpoint()) { @@ -170,10 +180,11 @@ public void periodic() _distanceToHubMeters = aimSolution.distanceToHubMeters(); Angle requestedRobotSetpoint = clampToTurretLimits(aimSolution.fieldSetpoint().minus(robotHeading)); - _turretSetpoint = requestedRobotSetpoint; - _hasSetpoint = true; + _continuousTurretSetpointDeg = chooseContinuousSetpoint(requestedRobotSetpoint.in(Degrees)); + _turretSetpoint = Degrees.of(wrapDegrees(_continuousTurretSetpointDeg)); + _hasSetpoint = true; - double targetMotorRotations = _turretSetpoint.in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; + double targetMotorRotations = Degrees.of(_continuousTurretSetpointDeg).in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; _turretMotor.setControl(_positionRequest.withPosition(targetMotorRotations)); } @@ -198,7 +209,8 @@ public void simulationPeriodic() double mechanismAngleDeg = _motorSimModel.getAngularPosition().in(Degrees); double clampedAngleDeg = MathUtil.clamp(mechanismAngleDeg, ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); double normalized = (clampedAngleDeg - ShooterConstants.TURRET_MIN_ANGLE) / (ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE); - _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized); + double sensorVoltage = ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS + (normalized * (ShooterConstants.TURRET_POTENTIOMETER_MAX_VOLTS - ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS)); + _turretSensorSim.setVoltage(sensorVoltage); } /** @@ -250,7 +262,7 @@ public boolean isLinedUp() return false; } - return _robotTurretAngle.isNear(_turretSetpoint, Degrees.of(ShooterConstants.TURRET_TOLERANCE)); + return Math.abs(_continuousRobotAngleDeg - _continuousTurretSetpointDeg) <= ShooterConstants.TURRET_TOLERANCE; } public boolean hasTarget() @@ -305,11 +317,11 @@ private void updateVisionData() { if (fiducial.id == centerTagId) { - _centerTagObservation = new TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); + _centerTagObservation = new TurretDirector.TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); } else if (fiducial.id == leftTagId) { - _leftTagObservation = new TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); + _leftTagObservation = new TurretDirector.TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); } } @@ -318,9 +330,10 @@ else if (fiducial.id == leftTagId) private void stopTurret() { - _hasSetpoint = false; - _turretSetpoint = _defaultSetpoint; - _distanceToHubMeters = 0.0; + _hasSetpoint = false; + _turretSetpoint = _defaultSetpoint; + _continuousTurretSetpointDeg = _continuousRobotAngleDeg; + _distanceToHubMeters = 0.0; _turretMotor.setVoltage(0.0); } @@ -331,199 +344,122 @@ private static Angle clampToTurretLimits(Angle angle) private void syncMotorEncoderToPotentiometer() { - Angle sensorAngle = clampToTurretLimits(Degrees.of(_turretSensor.get())); - double motorRotations = sensorAngle.in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; + Angle sensorAngle = getCalibratedRobotAngle(); + _robotTurretAngle = sensorAngle; + _lastWrappedRobotAngleDeg = sensorAngle.in(Degrees); + _continuousRobotAngleDeg = _lastWrappedRobotAngleDeg; + _continuousTurretSetpointDeg = _continuousRobotAngleDeg; + + double motorRotations = Degrees.of(_continuousRobotAngleDeg).in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; _turretMotor.setPosition(motorRotations); } - /** - * The TurretDirector is responsible for choosing a target for the robot to aim - * at and communicating the desired turret angle in field-relative space back to - * the main Turret subsystem. - */ - private static class TurretDirector + private Angle getCalibratedRobotAngle() { - public TurretAimSolution getAimSolution(TurretState turretState, Angle currentFieldAngle, Angle robotHeading, Angle horizontalOffset, boolean hasTarget, TagObservation centerTagObservation, TagObservation leftTagObservation) - { - return switch (turretState) - { - case Idle -> TurretAimSolution.none(); - case Track -> getTrackSolution(currentFieldAngle, robotHeading, horizontalOffset, hasTarget, centerTagObservation, leftTagObservation); - case Pass -> TurretAimSolution.of(ShooterConstants.TURRET_PASS_TARGET, 0.0); - }; - } - - private TurretAimSolution getTrackSolution(Angle currentFieldAngle, Angle robotHeading, Angle horizontalOffset, boolean hasTarget, TagObservation centerTagObservation, TagObservation leftTagObservation) - { - if (centerTagObservation != null && leftTagObservation != null) - { - TriangulationResult triangulation = triangulate(centerTagObservation, leftTagObservation); - if (triangulation.valid()) - { - return TurretAimSolution.of(currentFieldAngle.plus(Degrees.of(triangulation.relativeAngleDeg())), triangulation.distanceMeters()); - } - } - - if (hasTarget) - { - double fallbackDistance = centerTagObservation == null ? 0.0 : centerTagObservation.distanceMeters(); - return TurretAimSolution.of(currentFieldAngle.plus(horizontalOffset), fallbackDistance); - } - - return TurretAimSolution.of(robotHeading.plus(Degrees.of(ShooterConstants.TURRET_HOME_ANGLE)), 0.0); - } - - /** - * Solves for robot-to-hub angle and distance using two known triangles. - *

- * Triangle R-C-L: Robot (R), center tag (C), left tag (L). We know RC and RL - * from vision and CL from field drawings (TURRET_CL_METERS). Law of sines gives - * angle at C. - *

- * Triangle R-C-H: Hub center (H) is TURRET_CH_METERS from C (field drawing). - * Law of cosines gives RH (distance to hub). Law of sines gives angle at R from - * R→C to R→H. We add the camera-to-center-tag angle (tx) to get full - * robot-frame angle to hub. - */ - private TriangulationResult triangulate(TagObservation centerTagObservation, TagObservation leftTagObservation) - { - double rcDistanceMeters = centerTagObservation.distanceMeters(); - double rlDistanceMeters = leftTagObservation.distanceMeters(); - if (rcDistanceMeters <= 0.0 || rlDistanceMeters <= 0.0) - { - return TriangulationResult.invalid(); - } - - double angleLrcRad = Math.toRadians(leftTagObservation.horizontalOffset().in(Degrees) - centerTagObservation.horizontalOffset().in(Degrees)); - double sinLcr = (rlDistanceMeters * Math.sin(angleLrcRad)) / ShooterConstants.TURRET_CL_METERS; - double angleLcrRad = Math.asin(MathUtil.clamp(sinLcr, -1.0, 1.0)); - - double angleLcrPlusNinetyRad = angleLcrRad + Math.PI / 2.0; - double rhSquared = (rcDistanceMeters * rcDistanceMeters) + (ShooterConstants.TURRET_CH_METERS * ShooterConstants.TURRET_CH_METERS) - - (2.0 * rcDistanceMeters * ShooterConstants.TURRET_CH_METERS * Math.cos(angleLcrPlusNinetyRad)); - if (rhSquared <= 0.0 || !Double.isFinite(rhSquared)) - { - return TriangulationResult.invalid(); - } - - double rhDistanceMeters = Math.sqrt(rhSquared); - double sinHrc = (ShooterConstants.TURRET_CH_METERS * Math.sin(angleLcrPlusNinetyRad)) / rhDistanceMeters; - double angleHrcDeg = Math.toDegrees(Math.asin(MathUtil.clamp(sinHrc, -1.0, 1.0))); - - double angleRhDeg = angleHrcDeg + centerTagObservation.horizontalOffset().in(Degrees); - if (!Double.isFinite(angleRhDeg)) - { - return TriangulationResult.invalid(); - } + return clampToTurretLimits(Degrees.of(_turretSensor.get())); + } - return TriangulationResult.valid(angleRhDeg, rhDistanceMeters); - } + private void updateContinuousRobotAngle(double wrappedAngleDeg) + { + double delta = MathUtil.inputModulus(wrappedAngleDeg - _lastWrappedRobotAngleDeg, -180.0, 180.0); + _continuousRobotAngleDeg += delta; + _lastWrappedRobotAngleDeg = wrappedAngleDeg; } - private static class TurretAimSolution + private double chooseContinuousSetpoint(double requestedWrappedSetpointDeg) { - private final boolean _hasSetpoint; - private final Angle _fieldSetpoint; - private final double _distanceToHubMeters; + requestedWrappedSetpointDeg = moveSetpointOutOfDeadZone(requestedWrappedSetpointDeg); + double currentWrappedDeg = wrapDegrees(_continuousRobotAngleDeg); + double shortestDelta = MathUtil.inputModulus(requestedWrappedSetpointDeg - currentWrappedDeg, -180.0, 180.0); + double alternateDelta = shortestDelta > 0.0 ? shortestDelta - 360.0 : shortestDelta + 360.0; - private TurretAimSolution(boolean hasSetpoint, Angle fieldSetpoint, double distanceToHubMeters) + if (!pathCrossesDeadZone(currentWrappedDeg, shortestDelta)) { - _hasSetpoint = hasSetpoint; - _fieldSetpoint = fieldSetpoint; - _distanceToHubMeters = distanceToHubMeters; + return _continuousRobotAngleDeg + shortestDelta; } - public static TurretAimSolution none() + if (!pathCrossesDeadZone(currentWrappedDeg, alternateDelta)) { - return new TurretAimSolution(false, Degrees.zero(), 0.0); + return _continuousRobotAngleDeg + alternateDelta; } - public static TurretAimSolution of(Angle fieldSetpoint, double distanceToHubMeters) - { - return new TurretAimSolution(true, fieldSetpoint, distanceToHubMeters); - } + return _continuousRobotAngleDeg; + } - public boolean hasSetpoint() + private double moveSetpointOutOfDeadZone(double requestedWrappedSetpointDeg) + { + if (ShooterConstants.TURRET_DEAD_ZONE_WIDTH <= 0.0 || !isInDeadZone(requestedWrappedSetpointDeg)) { - return _hasSetpoint; + return requestedWrappedSetpointDeg; } - public Angle fieldSetpoint() - { - return _fieldSetpoint; - } + double deadZoneCenter = wrapDegrees(ShooterConstants.TURRET_DEAD_ZONE_CENTER); + double halfWidth = ShooterConstants.TURRET_DEAD_ZONE_WIDTH / 2.0; + double leftEdge = wrapDegrees(deadZoneCenter - halfWidth); + double rightEdge = wrapDegrees(deadZoneCenter + halfWidth); + double leftDelta = Math.abs(MathUtil.inputModulus(requestedWrappedSetpointDeg - leftEdge, -180.0, 180.0)); + double rightDelta = Math.abs(MathUtil.inputModulus(requestedWrappedSetpointDeg - rightEdge, -180.0, 180.0)); - public double distanceToHubMeters() - { - return _distanceToHubMeters; - } + return leftDelta <= rightDelta ? leftEdge : rightEdge; } - private static class TriangulationResult + private boolean pathCrossesDeadZone(double startWrappedDeg, double deltaDeg) { - private final boolean _valid; - private final double _relativeAngleDeg; - private final double _distanceMeters; - - private TriangulationResult(boolean valid, double relativeAngleDeg, double distanceMeters) + if (ShooterConstants.TURRET_DEAD_ZONE_WIDTH <= 0.0) { - _valid = valid; - _relativeAngleDeg = relativeAngleDeg; - _distanceMeters = distanceMeters; + return false; } - public static TriangulationResult invalid() + if (Math.abs(deltaDeg) <= 1e-9) { - return new TriangulationResult(false, 0.0, 0.0); + return isInDeadZone(startWrappedDeg); } - public static TriangulationResult valid(double relativeAngleDeg, double distanceMeters) - { - return new TriangulationResult(true, relativeAngleDeg, distanceMeters); - } + double zoneCenter = wrapDegrees(ShooterConstants.TURRET_DEAD_ZONE_CENTER); + double halfWidth = ShooterConstants.TURRET_DEAD_ZONE_WIDTH / 2.0; + double endUnwrapped = startWrappedDeg + deltaDeg; - public boolean valid() - { - return _valid; - } + double startExclusive = deltaDeg > 0.0 ? Math.nextUp(startWrappedDeg) : Math.nextDown(startWrappedDeg); + double low = Math.min(startExclusive, endUnwrapped); + double high = Math.max(startExclusive, endUnwrapped); - public double relativeAngleDeg() + // Exact interval intersection against periodic dead-zone copies (center+360k), + // which is robust across +/-180 wrap boundaries. + int kMin = (int)Math.floor((low - zoneCenter) / 360.0) - 1; + int kMax = (int)Math.ceil((high - zoneCenter) / 360.0) + 1; + for (int k = kMin; k <= kMax; k++) { - return _relativeAngleDeg; + double centerK = zoneCenter + (360.0 * k); + double intervalLow = centerK - halfWidth; + double intervalHigh = centerK + halfWidth; + if (intervalHigh >= low && intervalLow <= high) + { + return true; + } } - public double distanceMeters() - { - return _distanceMeters; - } + return false; } - private static class TagObservation + private boolean isInDeadZone(double wrappedAngleDeg) { - private final int _id; - private final Angle _horizontalOffset; - private final double _distanceMeters; - - private TagObservation(int id, Angle horizontalOffset, double distanceMeters) - { - _id = id; - _horizontalOffset = horizontalOffset; - _distanceMeters = distanceMeters; - } + double centerDelta = Math.abs(MathUtil.inputModulus(wrappedAngleDeg - ShooterConstants.TURRET_DEAD_ZONE_CENTER, -180.0, 180.0)); + return centerDelta <= ShooterConstants.TURRET_DEAD_ZONE_WIDTH / 2.0; + } - public int id() - { - return _id; - } + private static double wrapDegrees(double angleDeg) + { + return MathUtil.inputModulus(angleDeg, -180.0, 180.0); + } - public Angle horizontalOffset() - { - return _horizontalOffset; - } + private static double getTurretPotFullRange() + { + return ((ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE) * GeneralConstants.SENSOR_VOLTAGE) / (ShooterConstants.TURRET_POTENTIOMETER_MAX_VOLTS - ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS); + } - public double distanceMeters() - { - return _distanceMeters; - } + private static double getTurretPotOffset() + { + double fullRange = getTurretPotFullRange(); + return ShooterConstants.TURRET_MIN_ANGLE - ((ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS / GeneralConstants.SENSOR_VOLTAGE) * fullRange) + ShooterConstants.TURRET_POTENTIOMETER_ZERO_OFFSET_DEG; } } diff --git a/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java b/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java new file mode 100644 index 0000000..9761db7 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java @@ -0,0 +1,125 @@ +package frc.robot.subsystems.shooter; + +import static edu.wpi.first.units.Units.Degrees; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.units.measure.Angle; +import frc.robot.Constants.ShooterConstants; +import frc.robot.subsystems.shooter.Turret.TurretState; + +public final class TurretDirector +{ + private TurretDirector() + { + } + + public static TurretAimSolution getAimSolution(DirectorContext context) + { + return switch (context.turretState()) + { + case Idle -> TurretAimSolution.none(); + case Track -> getTrackSolution(context); + case Pass -> TurretAimSolution.of(ShooterConstants.TURRET_PASS_TARGET, 0.0); + }; + } + + private static TurretAimSolution getTrackSolution(DirectorContext context) + { + if (context.centerTagObservation() != null && context.leftTagObservation() != null) + { + TriangulationResult triangulation = triangulate(context.centerTagObservation(), context.leftTagObservation()); + if (triangulation.valid()) + { + return TurretAimSolution.of(context.currentFieldAngle().plus(Degrees.of(triangulation.relativeAngleDeg())), triangulation.distanceMeters()); + } + } + + if (context.hasTarget()) + { + double fallbackDistance = context.centerTagObservation() == null ? 0.0 : context.centerTagObservation().distanceMeters(); + return TurretAimSolution.of(context.currentFieldAngle().plus(context.horizontalOffset()), fallbackDistance); + } + + return TurretAimSolution.of(context.robotHeading().plus(Degrees.of(ShooterConstants.TURRET_HOME_ANGLE)), 0.0); + } + + /** + * Solves for robot-to-hub angle and distance using two known triangles. + *

+ * Triangle R-C-L: Robot (R), center tag (C), left tag (L). We know RC and RL + * from vision and CL from field drawings (TURRET_CL_METERS). Law of sines gives + * angle at C. + *

+ * Triangle R-C-H: Hub center (H) is TURRET_CH_METERS from C (field drawing). + * Law of cosines gives RH (distance to hub). Law of sines gives angle at R from + * R→C to R→H. We add the camera-to-center-tag angle (tx) to get full + * robot-frame angle to hub. + */ + private static TriangulationResult triangulate(TagObservation centerTagObservation, TagObservation leftTagObservation) + { + double rcDistanceMeters = centerTagObservation.distanceMeters(); + double rlDistanceMeters = leftTagObservation.distanceMeters(); + if (rcDistanceMeters <= 0.0 || rlDistanceMeters <= 0.0) + { + return TriangulationResult.invalid(); + } + + double angleLrcRad = Math.toRadians(leftTagObservation.horizontalOffset().in(Degrees) - centerTagObservation.horizontalOffset().in(Degrees)); + double sinLcr = (rlDistanceMeters * Math.sin(angleLrcRad)) / ShooterConstants.TURRET_CL_METERS; + double angleLcrRad = Math.asin(MathUtil.clamp(sinLcr, -1.0, 1.0)); + + double angleLcrPlusNinetyRad = angleLcrRad + Math.PI / 2.0; + double rhSquared = (rcDistanceMeters * rcDistanceMeters) + (ShooterConstants.TURRET_CH_METERS * ShooterConstants.TURRET_CH_METERS) + - (2.0 * rcDistanceMeters * ShooterConstants.TURRET_CH_METERS * Math.cos(angleLcrPlusNinetyRad)); + if (rhSquared <= 0.0 || !Double.isFinite(rhSquared)) + { + return TriangulationResult.invalid(); + } + + double rhDistanceMeters = Math.sqrt(rhSquared); + double sinHrc = (ShooterConstants.TURRET_CH_METERS * Math.sin(angleLcrPlusNinetyRad)) / rhDistanceMeters; + double angleHrcDeg = Math.toDegrees(Math.asin(MathUtil.clamp(sinHrc, -1.0, 1.0))); + + double angleRhDeg = angleHrcDeg + centerTagObservation.horizontalOffset().in(Degrees); + if (!Double.isFinite(angleRhDeg)) + { + return TriangulationResult.invalid(); + } + + return TriangulationResult.valid(angleRhDeg, rhDistanceMeters); + } + + public record DirectorContext(TurretState turretState, Angle currentFieldAngle, Angle robotHeading, Angle horizontalOffset, boolean hasTarget, TagObservation centerTagObservation, TagObservation leftTagObservation) + { + } + + public record TurretAimSolution(boolean hasSetpoint, Angle fieldSetpoint, double distanceToHubMeters) + { + public static TurretAimSolution none() + { + return new TurretAimSolution(false, Degrees.zero(), 0.0); + } + + public static TurretAimSolution of(Angle fieldSetpoint, double distanceToHubMeters) + { + return new TurretAimSolution(true, fieldSetpoint, distanceToHubMeters); + } + } + + public record TagObservation(int id, Angle horizontalOffset, double distanceMeters) + { + } + + private record TriangulationResult(boolean valid, double relativeAngleDeg, double distanceMeters) + { + private static TriangulationResult invalid() + { + return new TriangulationResult(false, 0.0, 0.0); + } + + private static TriangulationResult valid(double relativeAngleDeg, double distanceMeters) + { + return new TriangulationResult(true, relativeAngleDeg, distanceMeters); + } + } +} From be9d51f0321b781cc0e24dcccbf28f3d4ac107df Mon Sep 17 00:00:00 2001 From: SAKETH11111 Date: Tue, 17 Feb 2026 19:59:07 -0600 Subject: [PATCH 06/14] turret: use center-offset tag pairs and select best visible pair --- src/main/java/frc/robot/Constants.java | 26 ++++----- .../frc/robot/subsystems/shooter/Turret.java | 55 +++++++++++++++---- .../subsystems/shooter/TurretDirector.java | 29 +++++++--- 3 files changed, 75 insertions(+), 35 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index cf43491..30720ab 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -139,22 +139,20 @@ public static class ShooterConstants // Dead-zone model (robot-relative): // - Center/width define forbidden cable-wrap sector. // - Width <= 0 disables dead-zone routing logic. - public static final double TURRET_DEAD_ZONE_CENTER = 180.0; // degrees (robot-relative) - public static final double TURRET_DEAD_ZONE_WIDTH = 0.0; // degrees; set > 0 once cable-wrap dead-zone is measured - public static final int BLUE_CENTER_TAG_ID = 26; - public static final int BLUE_LEFT_TAG_ID = 25; - public static final int RED_CENTER_TAG_ID = 10; - public static final int RED_LEFT_TAG_ID = 9; - public static final double TURRET_CL_METERS = 0.3556; // 14.00 in - public static final double TURRET_CH_METERS = 0.5969; // 23.50 ins - public static final String LIMELIGHT_NAME = "limelight-shooter"; - public static final Angle TURRET_PASS_TARGET = Degrees.of(180.0); // TODO: Validate in driver practice - private static final InterpolatingDoubleTreeMap FLYWHEEL_SPEED_TABLE = InterpolatingDoubleTreeMap + public static final double TURRET_DEAD_ZONE_CENTER = 180.0; // degrees (robot-relative) + public static final double TURRET_DEAD_ZONE_WIDTH = 0.0; // degrees; set > 0 once cable-wrap dead-zone is measured + public static final List> BLUE_HUB_CENTER_OFFSET_TAG_PAIRS = List.of(List.of(18, 27), List.of(20, 19), List.of(21, 24), List.of(26, 25)); + public static final List> RED_HUB_CENTER_OFFSET_TAG_PAIRS = List.of(List.of(2, 11), List.of(4, 3), List.of(5, 8), List.of(10, 9)); + public static final double TURRET_CL_METERS = 0.3556; // 14.00 in + public static final double TURRET_CH_METERS = 0.5969; // 23.50 ins + public static final String LIMELIGHT_NAME = "limelight-shooter"; + public static final Angle TURRET_PASS_TARGET = Degrees.of(180.0); // TODO: Validate in driver practice + private static final InterpolatingDoubleTreeMap FLYWHEEL_SPEED_TABLE = InterpolatingDoubleTreeMap .ofEntries(Map.entry(0.0, 3000.0), Map.entry(2.0, 3000.0), Map.entry(3.5, 3500.0), Map.entry(5.0, 4000.0), Map.entry(6.5, 4500.0), Map.entry(7.0, 5000.0)); - private static final InterpolatingDoubleTreeMap HOOD_ANGLE_TABLE = InterpolatingDoubleTreeMap + private static final InterpolatingDoubleTreeMap HOOD_ANGLE_TABLE = InterpolatingDoubleTreeMap .ofEntries(Map.entry(0.0, 20.0), Map.entry(2.0, 15.0), Map.entry(3.5, 22.0), Map.entry(5.0, 30.0), Map.entry(6.5, 38.0), Map.entry(7.0, 45.0)); - public static final List BLUE_HUB_TAG_IDS = List.of(2, 3, 4, 5, 8, 9, 10, 11); - public static final List RED_HUB_TAG_IDS = List.of(18, 19, 20, 21, 24, 25, 26, 27); + public static final List BLUE_HUB_TAG_IDS = List.of(18, 19, 20, 21, 24, 25, 26, 27); + public static final List RED_HUB_TAG_IDS = List.of(2, 3, 4, 5, 8, 9, 10, 11); // Feeder public static final int FEEDER_CURRENT_LIMIT = 60; diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index f28a0a5..75955cf 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -4,7 +4,9 @@ import static edu.wpi.first.units.Units.Rotations; import static edu.wpi.first.units.Units.Volts; +import java.util.HashMap; import java.util.List; +import java.util.Map; import java.util.function.Supplier; import com.ctre.phoenix6.configs.CurrentLimitsConfigs; @@ -82,7 +84,7 @@ public enum TurretState @Logged private double _distanceToHubMeters; private TurretDirector.TagObservation _centerTagObservation; - private TurretDirector.TagObservation _leftTagObservation; + private TurretDirector.TagObservation _offsetTagObservation; private double _lastWrappedRobotAngleDeg; public Turret(Supplier swerveStateSupplier) @@ -102,7 +104,7 @@ public Turret(Supplier swerveStateSupplier) _distanceToHubMeters = 0.0; _cachedTagFilter = List.of(); _centerTagObservation = null; - _leftTagObservation = null; + _offsetTagObservation = null; _continuousRobotAngleDeg = 0.0; _continuousTurretSetpointDeg = 0.0; _lastWrappedRobotAngleDeg = 0.0; @@ -169,7 +171,7 @@ public void periodic() updateVisionData(); - var directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _leftTagObservation); + var directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _offsetTagObservation); TurretDirector.TurretAimSolution aimSolution = TurretDirector.getAimSolution(directorContext); if (!aimSolution.hasSetpoint()) @@ -293,7 +295,7 @@ private void updateVisionData() _hasTarget = false; _targetHorizontalOffset = Degrees.zero(); _centerTagObservation = null; - _leftTagObservation = null; + _offsetTagObservation = null; return; } @@ -308,20 +310,49 @@ private void updateVisionData() var targetData = limelightData.targetData; _targetHorizontalOffset = Degrees.of(targetData.getHorizontalOffset()); - int centerTagId = Utilities.isRedAlliance() ? ShooterConstants.RED_CENTER_TAG_ID : ShooterConstants.BLUE_CENTER_TAG_ID; - int leftTagId = Utilities.isRedAlliance() ? ShooterConstants.RED_LEFT_TAG_ID : ShooterConstants.BLUE_LEFT_TAG_ID; + boolean allianceIsRed = Utilities.isRedAlliance(); + List> hubPairs = TurretDirector.getHubCenterOffsetPairs(allianceIsRed); + Map observationsById = new HashMap<>(); + for (RawFiducial fiducial : limelightData.getRawFiducials()) + { + observationsById.put(fiducial.id, new TurretDirector.TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot)); + } _centerTagObservation = null; - _leftTagObservation = null; - for (RawFiducial fiducial : limelightData.getRawFiducials()) + _offsetTagObservation = null; + + double bestPairScore = Double.POSITIVE_INFINITY; + for (List hubPair : hubPairs) { - if (fiducial.id == centerTagId) + TurretDirector.TagObservation centerCandidate = observationsById.get(hubPair.get(0)); + TurretDirector.TagObservation offsetCandidate = observationsById.get(hubPair.get(1)); + if (centerCandidate == null || offsetCandidate == null) { - _centerTagObservation = new TurretDirector.TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); + continue; } - else if (fiducial.id == leftTagId) + + double pairScore = (centerCandidate.distanceMeters() + offsetCandidate.distanceMeters()) / 2.0; + if (pairScore < bestPairScore) + { + bestPairScore = pairScore; + _centerTagObservation = centerCandidate; + _offsetTagObservation = offsetCandidate; + } + } + + if (_centerTagObservation == null) + { + double closestCenterDistance = Double.POSITIVE_INFINITY; + for (List hubPair : hubPairs) { - _leftTagObservation = new TurretDirector.TagObservation(fiducial.id, Degrees.of(fiducial.txnc), fiducial.distToRobot); + TurretDirector.TagObservation centerCandidate = observationsById.get(hubPair.get(0)); + if (centerCandidate == null || centerCandidate.distanceMeters() >= closestCenterDistance) + { + continue; + } + + closestCenterDistance = centerCandidate.distanceMeters(); + _centerTagObservation = centerCandidate; } } diff --git a/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java b/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java index 9761db7..7913df5 100644 --- a/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java +++ b/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java @@ -2,6 +2,8 @@ import static edu.wpi.first.units.Units.Degrees; +import java.util.List; + import edu.wpi.first.math.MathUtil; import edu.wpi.first.units.measure.Angle; import frc.robot.Constants.ShooterConstants; @@ -13,6 +15,15 @@ private TurretDirector() { } + public static List> getHubCenterOffsetPairs(boolean isRedAlliance) + { + if (isRedAlliance) + { + return ShooterConstants.RED_HUB_CENTER_OFFSET_TAG_PAIRS; + } + return ShooterConstants.BLUE_HUB_CENTER_OFFSET_TAG_PAIRS; + } + public static TurretAimSolution getAimSolution(DirectorContext context) { return switch (context.turretState()) @@ -25,9 +36,9 @@ public static TurretAimSolution getAimSolution(DirectorContext context) private static TurretAimSolution getTrackSolution(DirectorContext context) { - if (context.centerTagObservation() != null && context.leftTagObservation() != null) + if (context.centerTagObservation() != null && context.offsetTagObservation() != null) { - TriangulationResult triangulation = triangulate(context.centerTagObservation(), context.leftTagObservation()); + TriangulationResult triangulation = triangulate(context.centerTagObservation(), context.offsetTagObservation()); if (triangulation.valid()) { return TurretAimSolution.of(context.currentFieldAngle().plus(Degrees.of(triangulation.relativeAngleDeg())), triangulation.distanceMeters()); @@ -46,7 +57,7 @@ private static TurretAimSolution getTrackSolution(DirectorContext context) /** * Solves for robot-to-hub angle and distance using two known triangles. *

- * Triangle R-C-L: Robot (R), center tag (C), left tag (L). We know RC and RL + * Triangle R-C-O: Robot (R), center tag (C), offset tag (O). We know RC and RO * from vision and CL from field drawings (TURRET_CL_METERS). Law of sines gives * angle at C. *

@@ -55,17 +66,17 @@ private static TurretAimSolution getTrackSolution(DirectorContext context) * R→C to R→H. We add the camera-to-center-tag angle (tx) to get full * robot-frame angle to hub. */ - private static TriangulationResult triangulate(TagObservation centerTagObservation, TagObservation leftTagObservation) + private static TriangulationResult triangulate(TagObservation centerTagObservation, TagObservation offsetTagObservation) { double rcDistanceMeters = centerTagObservation.distanceMeters(); - double rlDistanceMeters = leftTagObservation.distanceMeters(); - if (rcDistanceMeters <= 0.0 || rlDistanceMeters <= 0.0) + double roDistanceMeters = offsetTagObservation.distanceMeters(); + if (rcDistanceMeters <= 0.0 || roDistanceMeters <= 0.0) { return TriangulationResult.invalid(); } - double angleLrcRad = Math.toRadians(leftTagObservation.horizontalOffset().in(Degrees) - centerTagObservation.horizontalOffset().in(Degrees)); - double sinLcr = (rlDistanceMeters * Math.sin(angleLrcRad)) / ShooterConstants.TURRET_CL_METERS; + double angleLrcRad = Math.toRadians(offsetTagObservation.horizontalOffset().in(Degrees) - centerTagObservation.horizontalOffset().in(Degrees)); + double sinLcr = (roDistanceMeters * Math.sin(angleLrcRad)) / ShooterConstants.TURRET_CL_METERS; double angleLcrRad = Math.asin(MathUtil.clamp(sinLcr, -1.0, 1.0)); double angleLcrPlusNinetyRad = angleLcrRad + Math.PI / 2.0; @@ -89,7 +100,7 @@ private static TriangulationResult triangulate(TagObservation centerTagObservati return TriangulationResult.valid(angleRhDeg, rhDistanceMeters); } - public record DirectorContext(TurretState turretState, Angle currentFieldAngle, Angle robotHeading, Angle horizontalOffset, boolean hasTarget, TagObservation centerTagObservation, TagObservation leftTagObservation) + public record DirectorContext(TurretState turretState, Angle currentFieldAngle, Angle robotHeading, Angle horizontalOffset, boolean hasTarget, TagObservation centerTagObservation, TagObservation offsetTagObservation) { } From 1790369440b41b65c740a30dcfe8c75c20e30563 Mon Sep 17 00:00:00 2001 From: SAKETH11111 Date: Thu, 19 Feb 2026 18:04:43 -0600 Subject: [PATCH 07/14] update turret command bindings in RobotContainer and add command methods in Turret class --- src/main/java/frc/robot/RobotContainer.java | 14 ++++---------- .../frc/robot/subsystems/shooter/Turret.java | 18 +++++++++++++++++- 2 files changed, 21 insertions(+), 11 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 03ef31f..d94e895 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -17,9 +17,7 @@ import frc.robot.Constants.DriveConstants; import frc.robot.generated.TunerConstants; import frc.robot.subsystems.Drive; -import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.shooter.Turret; -import frc.robot.subsystems.shooter.Turret.TurretState; @Logged public class RobotContainer @@ -32,7 +30,6 @@ public class RobotContainer private final Telemetry _logger = new Telemetry(DriveConstants.MAX_SPEED); private final CommandXboxController _joystick = new CommandXboxController(0); private final Drive _drivetrain = TunerConstants.createDrivetrain(); - private final Intake _intake = new Intake(); private final Turret _turret = new Turret(_drivetrain::getState); public RobotContainer() @@ -72,13 +69,10 @@ private void configureBindings() // Reset the field-centric heading on left bumper press. _joystick.leftBumper().onTrue(_drivetrain.runOnce(_drivetrain::seedFieldCentric)); - _joystick.rightBumper().whileTrue(_intake.startRollers()); - _joystick.rightTrigger().whileTrue(_intake.reverseRollers()); - - // Turret test bindings. - _joystick.leftTrigger().onTrue(Commands.runOnce(() -> _turret.setTurretState(TurretState.Track), _turret)); - _joystick.y().onTrue(Commands.runOnce(() -> _turret.setTurretState(TurretState.Pass), _turret)); - _joystick.leftStick().onTrue(Commands.runOnce(() -> _turret.setTurretState(TurretState.Idle), _turret)); + // Turret simulation bindings. + _joystick.leftTrigger().whileTrue(_turret.getTrackCmd()); + _joystick.y().whileTrue(_turret.getPassCmd()); + _joystick.leftStick().onTrue(_turret.getIdleCmd()); _drivetrain.registerTelemetry(_logger::telemeterize); } diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 75955cf..8c9c584 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -32,6 +32,7 @@ import edu.wpi.first.wpilibj.simulation.AnalogInputSim; import edu.wpi.first.wpilibj.simulation.DCMotorSim; import edu.wpi.first.wpilibj.simulation.RoboRioSim; +import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.AIOConstants; import frc.robot.Constants.CANConstants; @@ -49,6 +50,21 @@ public enum TurretState Idle, Track, Pass } + public Command getTrackCmd() + { + return startEnd(() -> setTurretState(TurretState.Track), () -> setTurretState(TurretState.Idle)); + } + + public Command getPassCmd() + { + return startEnd(() -> setTurretState(TurretState.Pass), () -> setTurretState(TurretState.Idle)); + } + + public Command getIdleCmd() + { + return runOnce(() -> setTurretState(TurretState.Idle)); + } + private final TalonFX _turretMotor; private final TalonFXSimState _turretMotorSim; private final DCMotorSim _motorSimModel; @@ -149,7 +165,7 @@ public Turret(Supplier swerveStateSupplier) * This function executes automatically every 20 milliseconds. For the turret * specifically, we need to ensure the turret is behaving according to the rules * defined by the state the turret is in. If in Idle, the turret - * shouldn't rotate at all, even if the robot rotates. If in Shoot + * shouldn't rotate at all, even if the robot rotates. If in Track * or Pass, the turret should rotate to whatever angle is provided * by the * TurretDirector class. From edc3e2d49c5d7231ff3ba26cb944a855ed3592b4 Mon Sep 17 00:00:00 2001 From: GreenStar <77800979+GreatGreenStar@users.noreply.github.com> Date: Thu, 26 Feb 2026 19:27:47 -0600 Subject: [PATCH 08/14] Work towards making build work --- src/main/java/frc/robot/Constants.java | 10 ++++----- .../frc/robot/subsystems/shooter/Turret.java | 21 +++++++++++-------- 2 files changed, 17 insertions(+), 14 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index fa539f1..60c7562 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -177,11 +177,11 @@ public static class ShooterConstants // @formatter:off private static final InterpolatingDoubleTreeMap HOOD_ANGLE_TABLE = InterpolatingDoubleTreeMap.ofEntries ( - Map.entry(0.0, 20.0), - Map.entry(2.0, 15.0), - Map.entry(3.5, 22.0), - Map.entry(5.0, 30.0), - Map.entry(6.5, 38.0), + Map.entry(0.0, 20.0), + Map.entry(2.0, 15.0), + Map.entry(3.5, 22.0), + Map.entry(5.0, 30.0), + Map.entry(6.5, 38.0), Map.entry(7.0, 45.0) ); // @formatter:on diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 8e55195..0bcc07f 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -19,16 +19,16 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.sim.TalonFXSimState; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; +import com.ctre.phoenix6.sim.TalonFXSimState; import com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState; import edu.wpi.first.epilogue.Logged; +import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.units.measure.Angle; -import edu.wpi.first.units.measure.Distance; import edu.wpi.first.units.measure.Voltage; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.AnalogPotentiometer; @@ -38,12 +38,13 @@ import edu.wpi.first.wpilibj.simulation.RoboRioSim; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.MotorHook; -import frc.robot.TestHook; +import edu.wpi.first.units.measure.Distance; import frc.robot.Constants.AIOConstants; import frc.robot.Constants.CANConstants; import frc.robot.Constants.GeneralConstants; import frc.robot.Constants.ShooterConstants; +import frc.robot.MotorHook; +import frc.robot.TestHook; import frc.robot.util.MeasureUtil; import frc.robot.util.Utilities; import limelight.Limelight; @@ -198,9 +199,9 @@ public void periodic() updateVisionData(); - var directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _offsetTagObservation); + TurretDirector.DirectorContext directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _offsetTagObservation); TurretDirector.TurretAimSolution aimSolution = TurretDirector.getAimSolution(directorContext); - + if (!aimSolution.hasSetpoint()) { case Idle -> null; @@ -238,9 +239,9 @@ public void simulationPeriodic() _turretMotorSim.setRawRotorPosition(_motorSimModel.getAngularPosition().times(ShooterConstants.TURRET_GEAR_RATIO)); _turretMotorSim.setRotorVelocity(_motorSimModel.getAngularVelocity().times(ShooterConstants.TURRET_GEAR_RATIO)); - double mechanismAngle = _motorSimModel.getAngularPosition().div(ShooterConstants.TURRET_GEAR_RATIO); - Angle clamped = MeasureUtil.clamp(mechanismAngle, ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); - double normalized = clamped.minus(ShooterConstants.TURRET_MIN_ANGLE).div(ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)); + double mechanismAngle = _motorSimModel.getAngularPosition().div(ShooterConstants.TURRET_GEAR_RATIO); + Angle clamped = MeasureUtil.clamp(mechanismAngle, ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); + double normalized = clamped.minus(ShooterConstants.TURRET_MIN_ANGLE).div(ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)); _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized.in(Value)); } @@ -308,6 +309,7 @@ public boolean isLinedUp() return _robotTurretAngle.isNear(_turretSetpoint, ShooterConstants.TURRET_TOLERANCE); } + public double getDistanceToTarget() { if (_distanceToHubMeters > 0.0) @@ -342,6 +344,7 @@ public void setRate(double rate) public TestHook getHook() { return new TurretHook(); + private void updateVisionData() { if (_limelight == null) From 70d9f7b5132d29966acc5c32d37f3ccd0443ec3c Mon Sep 17 00:00:00 2001 From: GreenStar <77800979+GreatGreenStar@users.noreply.github.com> Date: Thu, 26 Feb 2026 19:29:19 -0600 Subject: [PATCH 09/14] Removed unused import --- src/main/java/frc/robot/subsystems/shooter/Turret.java | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 0bcc07f..adaa9d4 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -38,7 +38,6 @@ import edu.wpi.first.wpilibj.simulation.RoboRioSim; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.units.measure.Distance; import frc.robot.Constants.AIOConstants; import frc.robot.Constants.CANConstants; import frc.robot.Constants.GeneralConstants; @@ -201,7 +200,7 @@ public void periodic() TurretDirector.DirectorContext directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _offsetTagObservation); TurretDirector.TurretAimSolution aimSolution = TurretDirector.getAimSolution(directorContext); - + if (!aimSolution.hasSetpoint()) { case Idle -> null; From c7b1ea8183a5e2526fc3ce2cef81a85a4719c13d Mon Sep 17 00:00:00 2001 From: GreenStar <77800979+GreatGreenStar@users.noreply.github.com> Date: Thu, 26 Feb 2026 19:44:07 -0600 Subject: [PATCH 10/14] Reduced error count a tad --- .../frc/robot/subsystems/shooter/Turret.java | 58 ++++++++++--------- 1 file changed, 31 insertions(+), 27 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index adaa9d4..b2714bf 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -82,7 +82,7 @@ public Command getIdleCmd() private final Supplier _swerveStateSupplier; private final PositionVoltage _positionRequest = new PositionVoltage(0).withSlot(0); private List _cachedTagFilter; - private final Angle _defaultSetpoint = Degrees.of(ShooterConstants.TURRET_HOME_ANGLE); + private final Angle _defaultSetpoint = ShooterConstants.TURRET_HOME_ANGLE; private SwerveDriveState _swerveDriveState; @Logged private Angle _fieldTurretAngle; @@ -198,24 +198,31 @@ public void periodic() updateVisionData(); - TurretDirector.DirectorContext directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _offsetTagObservation); + TurretDirector.DirectorContext directorContext = new TurretDirector.DirectorContext(_turretState, _fieldTurretAngle, robotHeading, _targetHorizontalOffset, _hasTarget, _centerTagObservation, _offsetTagObservation); TurretDirector.TurretAimSolution aimSolution = TurretDirector.getAimSolution(directorContext); if (!aimSolution.hasSetpoint()) { - case Idle -> null; - case Track -> _hasTarget ? _robotTurretAngle.plus(_targetHorizontalOffset) : ShooterConstants.TURRET_HOME_ANGLE; - case Pass -> ShooterConstants.TURRET_PASS_TARGET.minus(_swerveDriveState.Pose.getRotation().getMeasure()); - }; - - if (requestedSetpoint == null) - { - _turretSetpoint = null; - _turretMotor.setVoltage(0.0); + // This occured while debugging merges. //TODO: Remove this if it safely can be. + // case Idle -> null; + // case Track -> _hasTarget ? _robotTurretAngle.plus(_targetHorizontalOffset) : + // ShooterConstants.TURRET_HOME_ANGLE; + // case Pass -> + // ShooterConstants.TURRET_PASS_TARGET.minus(_swerveDriveState.Pose.getRotation().getMeasure()); + stopTurret(); return; - } - - _turretSetpoint = MeasureUtil.clamp(requestedSetpoint, ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); + } ; + + // if (requestedSetpoint == null) + // { + // _turretSetpoint = null; + // _turretMotor.setVoltage(0.0); + // return; + // } + + // _turretSetpoint = MeasureUtil.clamp(requestedSetpoint, + // ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); + // //TODO: Check this var target = _turretSetpoint.times(ShooterConstants.TURRET_GEAR_RATIO); _turretMotor.setControl(_positionRequest.withPosition(target.in(Rotations))); } @@ -283,9 +290,9 @@ public Angle getAngle() */ public boolean isLinedUp() { - if (!_hasSetpoint) + if (!_hasSetpoint || _turretSetpoint == null) { - return false; + return _turretState == TurretState.Idle; // This originally returned false, new version should work better } if (_turretState == TurretState.Track && !_hasTarget) @@ -293,7 +300,11 @@ public boolean isLinedUp() return false; } - return Math.abs(_continuousRobotAngleDeg - _continuousTurretSetpointDeg) <= ShooterConstants.TURRET_TOLERANCE; + return Math.abs(_continuousRobotAngleDeg - _continuousTurretSetpointDeg) <= ShooterConstants.TURRET_TOLERANCE.in(Degrees); + // This could also be the below line if that works better + // TODO: check which one is better. + // return _robotTurretAngle.isNear(_turretSetpoint, + // ShooterConstants.TURRET_TOLERANCE); } public boolean hasTarget() @@ -301,14 +312,6 @@ public boolean hasTarget() return _hasTarget; } - public boolean isLinedUp() - { - if (_turretSetpoint == null) return _turretState == TurretState.Idle; - if (_turretState == TurretState.Track && !_hasTarget) return false; - - return _robotTurretAngle.isNear(_turretSetpoint, ShooterConstants.TURRET_TOLERANCE); - } - public double getDistanceToTarget() { if (_distanceToHubMeters > 0.0) @@ -343,6 +346,7 @@ public void setRate(double rate) public TestHook getHook() { return new TurretHook(); + } private void updateVisionData() { @@ -426,7 +430,7 @@ private void stopTurret() private static Angle clampToTurretLimits(Angle angle) { - return Degrees.of(MathUtil.clamp(angle.in(Degrees), ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE)); + return Degrees.of(MathUtil.clamp(angle.in(Degrees), ShooterConstants.TURRET_MIN_ANGLE.in(Degrees), ShooterConstants.TURRET_MAX_ANGLE.in(Degrees))); } private void syncMotorEncoderToPotentiometer() @@ -437,7 +441,7 @@ private void syncMotorEncoderToPotentiometer() _continuousRobotAngleDeg = _lastWrappedRobotAngleDeg; _continuousTurretSetpointDeg = _continuousRobotAngleDeg; - double motorRotations = Degrees.of(_continuousRobotAngleDeg).in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; + double motorRotations = Degrees.of(_continuousRobotAngleDeg).in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; // TODO: Find how to get dimensionless as a double _turretMotor.setPosition(motorRotations); } From 495aa2c09ef9ff33e20e04c5347261806181e1eb Mon Sep 17 00:00:00 2001 From: GreenStar <77800979+GreatGreenStar@users.noreply.github.com> Date: Thu, 26 Feb 2026 20:03:41 -0600 Subject: [PATCH 11/14] Reduced error count --- .../frc/robot/subsystems/shooter/Turret.java | 63 +++++++------------ 1 file changed, 22 insertions(+), 41 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index b2714bf..2455f6d 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -32,7 +32,6 @@ import edu.wpi.first.units.measure.Voltage; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.AnalogPotentiometer; -import edu.wpi.first.wpilibj.RobotBase; import edu.wpi.first.wpilibj.simulation.AnalogInputSim; import edu.wpi.first.wpilibj.simulation.DCMotorSim; import edu.wpi.first.wpilibj.simulation.RoboRioSim; @@ -72,17 +71,22 @@ public Command getIdleCmd() return runOnce(() -> setTurretState(TurretState.Idle)); } - private final TalonFX _turretMotor; - private final TalonFXSimState _turretMotorSim; - private final DCMotorSim _motorSimModel; - private final AnalogInput _turretSensorInput; - private final AnalogPotentiometer _turretSensor; - private final AnalogInputSim _turretSensorSim; - private final Limelight _limelight; + private final DCMotor gearbox = DCMotor.getKrakenX44(1); // FIXME: This is wrong. Find right value to make it right. + private final TalonFX _turretMotor = new TalonFX(CANConstants.TURRET_MOTOR); + private final TalonFXSimState _turretMotorSim = _turretMotor.getSimState(); + private final DCMotorSim _motorSimModel = new DCMotorSim(LinearSystemId.createDCMotorSystem(gearbox, 0.001, ShooterConstants.TURRET_GEAR_RATIO.in(Value)), gearbox);; + private final AnalogInput _turretSensorInput = new AnalogInput(AIOConstants.TURRET_POTENTIOMETER);; + private final AnalogPotentiometer _turretSensor = new AnalogPotentiometer( + _turretSensorInput, ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE).in(Degrees), ShooterConstants.TURRET_MIN_ANGLE.in(Degrees) + ); // TODO: check against _turretSensor = new + // AnalogPotentiometer(_turretSensorInput, getTurretPotFullRange(), + // getTurretPotOffset()); + private final AnalogInputSim _turretSensorSim = new AnalogInputSim(_turretSensorInput); + private final Limelight _limelight = new Limelight(ShooterConstants.LIMELIGHT_NAME); private final Supplier _swerveStateSupplier; - private final PositionVoltage _positionRequest = new PositionVoltage(0).withSlot(0); + private final PositionVoltage _positionRequest = new PositionVoltage(0).withSlot(0); private List _cachedTagFilter; - private final Angle _defaultSetpoint = ShooterConstants.TURRET_HOME_ANGLE; + private final Angle _defaultSetpoint = ShooterConstants.TURRET_HOME_ANGLE; private SwerveDriveState _swerveDriveState; @Logged private Angle _fieldTurretAngle; @@ -112,10 +116,8 @@ public Command getIdleCmd() public Turret(Supplier swerveStateSupplier) { - _turretMotor = new TalonFX(CANConstants.TURRET_MOTOR); - _swerveStateSupplier = swerveStateSupplier; - _swerveDriveState = new SwerveDriveState(); - + _swerveStateSupplier = swerveStateSupplier; + _swerveDriveState = new SwerveDriveState(); _fieldTurretAngle = Degrees.zero(); _robotTurretAngle = Degrees.zero(); _turretSetpoint = _defaultSetpoint; @@ -147,29 +149,8 @@ public Turret(Supplier swerveStateSupplier) _turretMotor.getConfigurator().apply(new TalonFXConfiguration().withCurrentLimits(currentConfig).withMotorOutput(outputConfig).withSlot0(slot0Configs)); AnalogInput turretSensorInput = new AnalogInput(AIOConstants.TURRET_POTENTIOMETER); - _turretSensor = new AnalogPotentiometer(turretSensorInput, ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE).in(Degrees), ShooterConstants.TURRET_MIN_ANGLE.in(Degrees)); - _positionRequest = new PositionVoltage(0).withSlot(0); - _limelight = new Limelight(ShooterConstants.LIMELIGHT_NAME); - - _turretSensorInput = new AnalogInput(AIOConstants.TURRET_POTENTIOMETER); - _turretSensor = new AnalogPotentiometer(_turretSensorInput, getTurretPotFullRange(), getTurretPotOffset()); syncMotorEncoderToPotentiometer(); - if (RobotBase.isReal()) - { - _limelight = new Limelight(ShooterConstants.LIMELIGHT_NAME); - _turretMotorSim = null; - _motorSimModel = null; - _turretSensorSim = null; - } - else - { - _limelight = null; - _turretMotorSim = _turretMotor.getSimState(); - _turretSensorSim = new AnalogInputSim(_turretSensorInput); - var gearbox = DCMotor.getKrakenX44(1); - _motorSimModel = new DCMotorSim(LinearSystemId.createDCMotorSystem(gearbox, 0.001, ShooterConstants.TURRET_GEAR_RATIO.in(Value)), gearbox); - } } /** @@ -245,10 +226,10 @@ public void simulationPeriodic() _turretMotorSim.setRawRotorPosition(_motorSimModel.getAngularPosition().times(ShooterConstants.TURRET_GEAR_RATIO)); _turretMotorSim.setRotorVelocity(_motorSimModel.getAngularVelocity().times(ShooterConstants.TURRET_GEAR_RATIO)); - double mechanismAngle = _motorSimModel.getAngularPosition().div(ShooterConstants.TURRET_GEAR_RATIO); - Angle clamped = MeasureUtil.clamp(mechanismAngle, ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); - double normalized = clamped.minus(ShooterConstants.TURRET_MIN_ANGLE).div(ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)); - _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized.in(Value)); + double mechanismAngle = _motorSimModel.getAngularPosition().div(ShooterConstants.TURRET_GEAR_RATIO).in(Degrees); // TODO: Quickly glance over this line to ensure it's correct. + Angle clamped = MeasureUtil.clamp(Degrees.of(mechanismAngle), ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); + double normalized = clamped.minus(ShooterConstants.TURRET_MIN_ANGLE).div(ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)); // FIXME: Figure out what's happening here after doing the easy stuff. + _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized); } /** @@ -321,11 +302,11 @@ public double getDistanceToTarget() if (_limelight == null || !_hasTarget) { - return Meters.zero(); + return Meters.zero().in(Meters); // FIXME: Reread this, make it right. } var targetPose = _limelight.getData().targetData.getCameraToTarget(); - return Meters.of(targetPose.getTranslation().toTranslation2d().getNorm()); + return Meters.of(targetPose.getTranslation().toTranslation2d().getNorm()).in(Meters); // FIXME: Ditto } private class TurretHook extends MotorHook From c133e21dba04313d9c4971ff84dfe9c8d5da6f74 Mon Sep 17 00:00:00 2001 From: GreenStar <77800979+GreatGreenStar@users.noreply.github.com> Date: Thu, 26 Feb 2026 20:06:01 -0600 Subject: [PATCH 12/14] Updated comment name --- src/main/java/frc/robot/subsystems/shooter/Turret.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 2455f6d..7edc9ec 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -228,7 +228,7 @@ public void simulationPeriodic() double mechanismAngle = _motorSimModel.getAngularPosition().div(ShooterConstants.TURRET_GEAR_RATIO).in(Degrees); // TODO: Quickly glance over this line to ensure it's correct. Angle clamped = MeasureUtil.clamp(Degrees.of(mechanismAngle), ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); - double normalized = clamped.minus(ShooterConstants.TURRET_MIN_ANGLE).div(ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)); // FIXME: Figure out what's happening here after doing the easy stuff. + double normalized = clamped.minus(ShooterConstants.TURRET_MIN_ANGLE).div(ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)); // FIXME: Figure out the issue with .div _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized); } From d3701395a26e18eedd074a8fd9fa18a15f556d16 Mon Sep 17 00:00:00 2001 From: GreenStar <77800979+GreatGreenStar@users.noreply.github.com> Date: Thu, 26 Feb 2026 20:14:14 -0600 Subject: [PATCH 13/14] Got rid of all the blatant errors --- .../frc/robot/subsystems/shooter/Turret.java | 18 ++++++++++++++---- 1 file changed, 14 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Turret.java b/src/main/java/frc/robot/subsystems/shooter/Turret.java index 7edc9ec..140f222 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Turret.java +++ b/src/main/java/frc/robot/subsystems/shooter/Turret.java @@ -228,7 +228,8 @@ public void simulationPeriodic() double mechanismAngle = _motorSimModel.getAngularPosition().div(ShooterConstants.TURRET_GEAR_RATIO).in(Degrees); // TODO: Quickly glance over this line to ensure it's correct. Angle clamped = MeasureUtil.clamp(Degrees.of(mechanismAngle), ShooterConstants.TURRET_MIN_ANGLE, ShooterConstants.TURRET_MAX_ANGLE); - double normalized = clamped.minus(ShooterConstants.TURRET_MIN_ANGLE).div(ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)); // FIXME: Figure out the issue with .div + double normalized = clamped.in(Degrees) - (ShooterConstants.TURRET_MIN_ANGLE.in(Degrees)) / (ShooterConstants.TURRET_MAX_ANGLE.in(Degrees) - (ShooterConstants.TURRET_MIN_ANGLE.in(Degrees))); // TODO: Do this in the actually + // better way. _turretSensorSim.setVoltage(RoboRioSim.getUserVoltage5V() * normalized); } @@ -422,7 +423,7 @@ private void syncMotorEncoderToPotentiometer() _continuousRobotAngleDeg = _lastWrappedRobotAngleDeg; _continuousTurretSetpointDeg = _continuousRobotAngleDeg; - double motorRotations = Degrees.of(_continuousRobotAngleDeg).in(Rotations) * ShooterConstants.TURRET_GEAR_RATIO; // TODO: Find how to get dimensionless as a double + double motorRotations = _continuousRobotAngleDeg * ShooterConstants.TURRET_GEAR_RATIO.baseUnitMagnitude(); // TODO: Check if there's a better way to do this line. _turretMotor.setPosition(motorRotations); } @@ -526,12 +527,21 @@ private static double wrapDegrees(double angleDeg) private static double getTurretPotFullRange() { - return ((ShooterConstants.TURRET_MAX_ANGLE - ShooterConstants.TURRET_MIN_ANGLE) * GeneralConstants.SENSOR_VOLTAGE) / (ShooterConstants.TURRET_POTENTIOMETER_MAX_VOLTS - ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS); + return ((ShooterConstants.TURRET_MAX_ANGLE.minus(ShooterConstants.TURRET_MIN_ANGLE)).in(Degrees) * GeneralConstants.SENSOR_VOLTAGE.in(Volts)) + / (ShooterConstants.TURRET_POTENTIOMETER_MAX_VOLTS - ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS); // TODO: Check if all this conversion is needed or this can be done better. } private static double getTurretPotOffset() { double fullRange = getTurretPotFullRange(); - return ShooterConstants.TURRET_MIN_ANGLE - ((ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS / GeneralConstants.SENSOR_VOLTAGE) * fullRange) + ShooterConstants.TURRET_POTENTIOMETER_ZERO_OFFSET_DEG; + return ShooterConstants.TURRET_MIN_ANGLE.in(Degrees) - ((ShooterConstants.TURRET_POTENTIOMETER_MIN_VOLTS / GeneralConstants.SENSOR_VOLTAGE.in(Volts)) * fullRange) + ShooterConstants.TURRET_POTENTIOMETER_ZERO_OFFSET_DEG; // TODO: + // Check if + // all this + // conversion + // is needed + // or this + // can be + // done + // better. } } From df8a42bdd7b24eed1f8f338a7370a9a48d336123 Mon Sep 17 00:00:00 2001 From: GreenStar <77800979+GreatGreenStar@users.noreply.github.com> Date: Thu, 26 Feb 2026 20:19:23 -0600 Subject: [PATCH 14/14] Got this to build --- src/main/java/frc/robot/Constants.java | 21 ++----------------- src/main/java/frc/robot/RobotContainer.java | 6 +++--- .../subsystems/shooter/TurretDirector.java | 2 +- 3 files changed, 6 insertions(+), 23 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 60c7562..cb304af 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -1,33 +1,19 @@ package frc.robot; -import static edu.wpi.first.units.Units.Amps; -import static edu.wpi.first.units.Units.Degrees; -import static edu.wpi.first.units.Units.DegreesPerSecond; -import static edu.wpi.first.units.Units.Inches; -import static edu.wpi.first.units.Units.RPM; -import static edu.wpi.first.units.Units.RadiansPerSecond; -import static edu.wpi.first.units.Units.Meters; -import static edu.wpi.first.units.Units.Milliseconds; -import static edu.wpi.first.units.Units.Percent; -import static edu.wpi.first.units.Units.Rotations; -import static edu.wpi.first.units.Units.RotationsPerSecond; -import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond; -import static edu.wpi.first.units.Units.Value; -import static edu.wpi.first.units.Units.Volts; +import static edu.wpi.first.units.Units.*; import java.util.List; import java.util.Map; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.VecBuilder; - import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap; - import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.units.AngleUnit; import edu.wpi.first.units.AngularAccelerationUnit; import edu.wpi.first.units.AngularVelocityUnit; @@ -42,7 +28,6 @@ import edu.wpi.first.units.measure.Per; import edu.wpi.first.units.measure.Time; import edu.wpi.first.units.measure.Voltage; -import edu.wpi.first.math.system.plant.DCMotor; import frc.robot.generated.TunerConstants; public final class Constants @@ -173,7 +158,6 @@ public static class ShooterConstants public static final List> RED_HUB_CENTER_OFFSET_TAG_PAIRS = List.of(List.of(2, 11), List.of(4, 3), List.of(5, 8), List.of(10, 9)); public static final double TURRET_CL_METERS = 0.3556; // 14.00 in public static final double TURRET_CH_METERS = 0.5969; // 23.50 ins - public static final String LIMELIGHT_NAME = "limelight-shooter"; // @formatter:off private static final InterpolatingDoubleTreeMap HOOD_ANGLE_TABLE = InterpolatingDoubleTreeMap.ofEntries ( @@ -194,7 +178,6 @@ public static class ShooterConstants public static AngularVelocity getFlywheelSpeedForDistance(Distance distance) { return RPM.of(FLYWHEEL_SPEED_TABLE.get(distance.in(Meters))); - return RPM.of(FLYWHEEL_SPEED_TABLE.get(meters)); } // TODO: Tune these values with testing! diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 3cf0557..fa2879c 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -8,7 +8,6 @@ import static edu.wpi.first.units.Units.Value; import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType; - import com.ctre.phoenix6.swerve.SwerveRequest; import edu.wpi.first.epilogue.Logged; @@ -24,10 +23,10 @@ import frc.robot.subsystems.Drive; import frc.robot.subsystems.TestOperation; import frc.robot.subsystems.intake.Intake; -import frc.robot.subsystems.shooter.Shooter; import frc.robot.subsystems.shooter.Hood.HoodPosition; -import frc.robot.util.MeasureUtil; +import frc.robot.subsystems.shooter.Shooter; import frc.robot.subsystems.shooter.Turret; +import frc.robot.util.MeasureUtil; @Logged public class RobotContainer @@ -44,6 +43,7 @@ public class RobotContainer private final Intake _intake = new Intake(); private final Shooter _shooter = new Shooter(_drivetrain::getState); private final TestOperation _testop = new TestOperation(); + private final CommandXboxController _joystick = new CommandXboxController(0); // TODO: Check if this can be removed // private final Turret _turret = new Turret(_drivetrain::getState); private final Autos _autos = new Autos(_drivetrain); private final Turret _turret = new Turret(_drivetrain::getState); diff --git a/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java b/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java index 7913df5..95ef60c 100644 --- a/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java +++ b/src/main/java/frc/robot/subsystems/shooter/TurretDirector.java @@ -51,7 +51,7 @@ private static TurretAimSolution getTrackSolution(DirectorContext context) return TurretAimSolution.of(context.currentFieldAngle().plus(context.horizontalOffset()), fallbackDistance); } - return TurretAimSolution.of(context.robotHeading().plus(Degrees.of(ShooterConstants.TURRET_HOME_ANGLE)), 0.0); + return TurretAimSolution.of(context.robotHeading().plus((ShooterConstants.TURRET_HOME_ANGLE)), 0.0); } /**