From f594d2e95970800c65b9c6ad6846b6c3958e0bd6 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Sat, 7 Feb 2026 13:50:54 -0700 Subject: [PATCH 01/22] Was double-adding pose esitmates The SIM mode was not separately gated behind an `else`, so REAL mode was double-adding pose estimates. --- .../java/frc/robot/subsystems/drive/Drive.java | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index aeb71e6..a604515 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -388,17 +388,17 @@ public void rbsiPeriodic() { Logger.recordOutput("Drive/Pose", m_PoseEstimator.getEstimatedPosition()); gyroDisconnectedAlert.set(!imuInputs.connected); return; - } - - // SIMULATION: Keep sim pose buffer time-aligned, too - double now = Timer.getFPGATimestamp(); - poseBuffer.addSample(now, simPhysics.getPose()); - yawBuffer.addSample(now, simPhysics.getYaw().getRadians()); - yawRateBuffer.addSample(now, simPhysics.getOmegaRadPerSec()); + } else { - Logger.recordOutput("Drive/Pose", simPhysics.getPose()); - gyroDisconnectedAlert.set(false); + // SIMULATION: Keep sim pose buffer time-aligned, too + double now = Timer.getFPGATimestamp(); + poseBuffer.addSample(now, simPhysics.getPose()); + yawBuffer.addSample(now, simPhysics.getYaw().getRadians()); + yawRateBuffer.addSample(now, simPhysics.getOmegaRadPerSec()); + Logger.recordOutput("Drive/Pose", simPhysics.getPose()); + gyroDisconnectedAlert.set(false); + } } finally { odometryLock.unlock(); } From e2d8fad903cde1d96a7ab96f433877a1fd1ecc72 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Sat, 7 Feb 2026 16:07:03 -0700 Subject: [PATCH 02/22] Fix double-count of pose estimation; add kS for swerve turn --- src/main/java/frc/robot/Constants.java | 39 ++++++++++--------- .../frc/robot/subsystems/drive/Drive.java | 1 + .../subsystems/drive/ModuleIOBlended.java | 3 +- .../robot/subsystems/drive/ModuleIOSpark.java | 3 +- .../drive/ModuleIOSparkCANcoder.java | 3 +- .../subsystems/drive/ModuleIOTalonFX.java | 2 +- .../subsystems/drive/ModuleIOTalonFXS.java | 2 +- 7 files changed, 29 insertions(+), 24 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 7d30eae..1887d60 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -74,7 +74,7 @@ public final class Constants { private static SwerveType swerveType = SwerveType.PHOENIX6; // PHOENIX6, YAGSL private static CTREPro phoenixPro = CTREPro.UNLICENSED; // LICENSED, UNLICENSED private static AutoType autoType = AutoType.MANUAL; // MANUAL, PATHPLANNER, CHOREO - private static VisionType visionType = VisionType.NONE; // PHOTON, LIMELIGHT, NONE + private static VisionType visionType = VisionType.PHOTON; // PHOTON, LIMELIGHT, NONE /** Enumerate the robot types (name your robots here) */ public static enum RobotType { @@ -324,6 +324,7 @@ public static final class DrivebaseConstants { SwerveConstants.kDriveGearRatio / DCMotor.getKrakenX60Foc(1).KtNMPerAmp; public static final double kSteerP = 400.0; public static final double kSteerD = 20.0; + public static final double kSteerS = 2.0; // Odometry-related constants public static final double kHistorySize = 1.5; // seconds @@ -466,7 +467,7 @@ public record CameraConfig( // Example Cameras are mounted in the back corners, 18" up from the floor, facing sideways public static final CameraConfig[] ALL = { new CameraConfig( - "camera_0", + "Photon_BW7", new Transform3d( Inches.of(-13.0), Inches.of(13.0), @@ -483,23 +484,23 @@ public record CameraConfig( } }), // - new CameraConfig( - "camera_1", - new Transform3d( - Inches.of(-13.0), - Inches.of(-13.0), - Inches.of(12.0), - new Rotation3d(0.0, 0.0, -Math.PI / 2)), - 1.0, - new SimCameraProperties() { - { - setCalibration(1280, 800, Rotation2d.fromDegrees(120)); - setCalibError(0.25, 0.08); - setFPS(30); - setAvgLatencyMs(20); - setLatencyStdDevMs(5); - } - }), + // new CameraConfig( + // "camera_1", + // new Transform3d( + // Inches.of(-13.0), + // Inches.of(-13.0), + // Inches.of(12.0), + // new Rotation3d(0.0, 0.0, -Math.PI / 2)), + // 1.0, + // new SimCameraProperties() { + // { + // setCalibration(1280, 800, Rotation2d.fromDegrees(120)); + // setCalibError(0.25, 0.08); + // setFPS(30); + // setAvgLatencyMs(20); + // setLatencyStdDevMs(5); + // } + // }), // ... And more, if needed }; diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index a604515..2dcc959 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -388,6 +388,7 @@ public void rbsiPeriodic() { Logger.recordOutput("Drive/Pose", m_PoseEstimator.getEstimatedPosition()); gyroDisconnectedAlert.set(!imuInputs.connected); return; + } else { // SIMULATION: Keep sim pose buffer time-aligned, too diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java index 5c68481..01d0ffc 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java @@ -243,7 +243,8 @@ public ModuleIOBlended(int module) { SwerveConstants.turnPIDMinInput, SwerveConstants.turnPIDMaxInput) .pid(DrivebaseConstants.kSteerP, 0.0, DrivebaseConstants.kSteerD) .feedForward - .kV(0.0); + .kV(0.0) + .kS(DrivebaseConstants.kSteerS); turnConfig .signals .absoluteEncoderPositionAlwaysOn(true) diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java index 7573861..1c92c68 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java @@ -183,7 +183,8 @@ public ModuleIOSpark(int module) { SwerveConstants.turnPIDMinInput, SwerveConstants.turnPIDMaxInput) .pid(DrivebaseConstants.kSteerP, 0.0, DrivebaseConstants.kSteerD) .feedForward - .kV(0.0); + .kV(0.0) + .kS(DrivebaseConstants.kSteerS); turnConfig .signals .absoluteEncoderPositionAlwaysOn(true) diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java index fc76b59..587f8ec 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java @@ -202,7 +202,8 @@ public ModuleIOSparkCANcoder(int module) { SwerveConstants.turnPIDMinInput, SwerveConstants.turnPIDMaxInput) .pid(DrivebaseConstants.kSteerP, 0.0, DrivebaseConstants.kSteerD) .feedForward - .kV(0.0); + .kV(0.0) + .kS(DrivebaseConstants.kSteerS); turnConfig .signals .absoluteEncoderPositionAlwaysOn(true) diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java index 65da2c7..df569b4 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java @@ -192,7 +192,7 @@ public ModuleIOTalonFX(int module) { .withKP(DrivebaseConstants.kSteerP) .withKI(0.0) .withKD(DrivebaseConstants.kSteerD) - .withKS(0.0) + .withKS(DrivebaseConstants.kSteerS) .withKV(0.0) .withKA(0.0) .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java index 23f2885..f3cc029 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java @@ -180,7 +180,7 @@ public ModuleIOTalonFXS( .withKP(DrivebaseConstants.kSteerP) .withKI(0.0) .withKD(DrivebaseConstants.kSteerD) - .withKS(0.0) + .withKS(DrivebaseConstants.kSteerS) .withKV(0.0) .withKA(0.0) .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); From ecff3ea3f965eca3e2fd808705694bc66f3b2726 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Sat, 7 Feb 2026 16:50:25 -0700 Subject: [PATCH 03/22] Clean up the consumer syntax --- .../frc/robot/subsystems/drive/Drive.java | 7 +- .../frc/robot/subsystems/vision/Vision.java | 145 +++++++++++------- src/main/java/frc/robot/util/RBSIPose.java | 21 +++ 3 files changed, 111 insertions(+), 62 deletions(-) create mode 100644 src/main/java/frc/robot/util/RBSIPose.java diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 2dcc959..041a0e6 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -22,7 +22,6 @@ import edu.wpi.first.hal.FRCNetComm.tInstances; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; -import edu.wpi.first.math.Matrix; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.ProfiledPIDController; import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator; @@ -52,6 +51,7 @@ import frc.robot.util.LocalADStarAK; import frc.robot.util.RBSIEnum.Mode; import frc.robot.util.RBSIParsing; +import frc.robot.util.RBSIPose; import frc.robot.util.RBSISubsystem; import java.util.Optional; import java.util.OptionalDouble; @@ -743,10 +743,11 @@ public void zeroHeading() { } /** Adds a vision measurement safely into the PoseEstimator. */ - public void addVisionMeasurement(Pose2d pose, double timestampSeconds, Matrix stdDevs) { + public void addVisionMeasurement(RBSIPose rbsiPose) { odometryLock.lock(); try { - m_PoseEstimator.addVisionMeasurement(pose, timestampSeconds, stdDevs); + m_PoseEstimator.addVisionMeasurement( + rbsiPose.pose(), rbsiPose.timestampSeconds(), rbsiPose.stdDevs()); } finally { odometryLock.unlock(); } diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 74d318a..e37b6a7 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -25,12 +25,14 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; import frc.robot.Constants; import frc.robot.FieldConstants; import frc.robot.subsystems.drive.Drive; import frc.robot.subsystems.vision.VisionIO.PoseObservationType; +import frc.robot.util.RBSIPose; import frc.robot.util.VirtualSubsystem; import java.util.ArrayDeque; import java.util.ArrayList; @@ -45,13 +47,11 @@ public class Vision extends VirtualSubsystem { /** Vision Consumer definition */ @FunctionalInterface - public interface VisionConsumer { - void accept(Pose2d visionRobotPoseMeters, double timestampSeconds, Matrix stdDevs); + public interface PoseMeasurementConsumer { + void accept(RBSIPose measurement); } - private record TimedEstimate(Pose2d pose, double ts, Matrix stdDevs) {} - - private final VisionConsumer consumer; + private final PoseMeasurementConsumer consumer; private final Drive drive; private long lastSeenPoseResetEpoch = -1; @@ -65,7 +65,7 @@ private record TimedEstimate(Pose2d pose, double ts, Matrix stdDevs) {} private volatile double lastPoseResetTimestamp = Double.NEGATIVE_INFINITY; // Smoothing buffer (recent fused estimates) - private final ArrayDeque fusedBuffer = new ArrayDeque<>(); + private final ArrayDeque fusedBuffer = new ArrayDeque<>(); private final double smoothWindowSec = 0.25; private final int smoothMaxSize = 12; @@ -82,8 +82,10 @@ private record TimedEstimate(Pose2d pose, double ts, Matrix stdDevs) {} private volatile double yawGateLookbackSec = 0.30; private volatile double yawGateLimitRadPerSec = 5.0; + private static final double kMinVariance = 1e-12; // prevents divide-by-zero explosions + /** Constructor */ - public Vision(Drive drive, VisionConsumer consumer, VisionIO... io) { + public Vision(Drive drive, PoseMeasurementConsumer consumer, VisionIO... io) { this.drive = drive; this.consumer = consumer; this.io = io; @@ -123,14 +125,14 @@ public void rbsiPeriodic() { } // Pick one best accepted estimate per camera for this loop - final ArrayList perCamAccepted = new ArrayList<>(io.length); + final ArrayList perCamAccepted = new ArrayList<>(io.length); for (int cam = 0; cam < io.length; cam++) { int seen = 0; int accepted = 0; int rejected = 0; - TimedEstimate best = null; + RBSIPose best = null; double bestTrustScale = Double.NaN; int bestTrustedCount = 0; int bestTagCount = 0; @@ -150,7 +152,7 @@ public void rbsiPeriodic() { continue; } - TimedEstimate est = built.estimate; + RBSIPose est = built.estimate; if (best == null || isBetter(est, best)) { best = est; bestTrustScale = built.trustScale; @@ -161,12 +163,12 @@ public void rbsiPeriodic() { if (best != null) { accepted++; - lastAcceptedTsPerCam[cam] = best.ts; + lastAcceptedTsPerCam[cam] = best.timestampSeconds(); perCamAccepted.add(best); - Logger.recordOutput("Vision/Camera" + cam + "/InjectedPose2d", best.pose); - Logger.recordOutput("Vision/Camera" + cam + "/InjectedTimestamp", best.ts); - Logger.recordOutput("Vision/Camera" + cam + "/InjectedStdDevs", best.stdDevs); + Logger.recordOutput("Vision/Camera" + cam + "/InjectedPose2d", best.pose()); + Logger.recordOutput("Vision/Camera" + cam + "/InjectedTimestamp", best.timestampSeconds()); + Logger.recordOutput("Vision/Camera" + cam + "/InjectedStdDevs", best.stdDevs()); Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTrustScale", bestTrustScale); Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTrustedCount", bestTrustedCount); Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTagCount", bestTagCount); @@ -180,23 +182,24 @@ public void rbsiPeriodic() { if (perCamAccepted.isEmpty()) return; // Fusion time is the newest timestamp among accepted per-camera samples - double tF = perCamAccepted.stream().mapToDouble(e -> e.ts).max().orElse(Double.NaN); + double tF = + perCamAccepted.stream().mapToDouble(e -> e.timestampSeconds()).max().orElse(Double.NaN); if (!Double.isFinite(tF)) return; // Time-align camera estimates to tF using odometry buffer, then inverse-variance fuse - TimedEstimate fused = fuseAtTime(perCamAccepted, tF); + RBSIPose fused = fuseAtTime(perCamAccepted, tF); if (fused == null) return; // Smooth by fusing recent fused estimates (also aligned to tF) pushFused(fused); - TimedEstimate smoothed = smoothAtTime(tF); + RBSIPose smoothed = smoothAtTime(tF); if (smoothed == null) return; - // Inject the pose - consumer.accept(smoothed.pose, smoothed.ts, smoothed.stdDevs); + // Inject the pose -- commented out for now... + consumer.accept(smoothed); - Logger.recordOutput("Vision/FusedPose", fused.pose); - Logger.recordOutput("Vision/SmoothedPose", smoothed.pose); + Logger.recordOutput("Vision/FusedPose", fused.pose()); + Logger.recordOutput("Vision/SmoothedPose", smoothed.pose()); Logger.recordOutput("Vision/FusedTimestamp", tF); } @@ -301,11 +304,11 @@ private GateResult passesHardGatesAndYawGate(int cam, VisionIO.PoseObservation o } private static final class BuiltEstimate { - final TimedEstimate estimate; + final RBSIPose estimate; final double trustScale; final int trustedCount; - BuiltEstimate(TimedEstimate estimate, double trustScale, int trustedCount) { + BuiltEstimate(RBSIPose estimate, double trustScale, int trustedCount) { this.estimate = estimate; this.trustScale = trustScale; this.trustedCount = trustedCount; @@ -353,7 +356,7 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { Logger.recordOutput("Vision/Camera" + cam + "/InjectedFracTrusted", fracTrusted); return new BuiltEstimate( - new TimedEstimate( + new RBSIPose( obs.pose().toPose2d(), obs.timestamp(), VecBuilder.fill(linearStdDev, linearStdDev, angularStdDev)), @@ -361,20 +364,20 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { trustedCount); } - private boolean isBetter(TimedEstimate a, TimedEstimate b) { + private boolean isBetter(RBSIPose a, RBSIPose b) { // Lower trace of stddev vector (x+y+theta) is better - double ta = a.stdDevs.get(0, 0) + a.stdDevs.get(1, 0) + a.stdDevs.get(2, 0); - double tb = b.stdDevs.get(0, 0) + b.stdDevs.get(1, 0) + b.stdDevs.get(2, 0); + double ta = a.stdDevs().get(0, 0) + a.stdDevs().get(1, 0) + a.stdDevs().get(2, 0); + double tb = b.stdDevs().get(0, 0) + b.stdDevs().get(1, 0) + b.stdDevs().get(2, 0); return ta < tb; } /** Time alignment & fusion ********************************************** */ - private TimedEstimate fuseAtTime(ArrayList estimates, double tF) { - final ArrayList aligned = new ArrayList<>(estimates.size()); + private RBSIPose fuseAtTime(ArrayList estimates, double tF) { + final ArrayList aligned = new ArrayList<>(estimates.size()); for (var e : estimates) { - Pose2d alignedPose = timeAlignPose(e.pose, e.ts, tF); + Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tF); if (alignedPose == null) return null; - aligned.add(new TimedEstimate(alignedPose, tF, e.stdDevs)); + aligned.add(new RBSIPose(alignedPose, tF, e.stdDevs())); } return inverseVarianceFuse(aligned, tF); } @@ -394,48 +397,70 @@ private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tF) { return visionPoseAtTs.transformBy(ts_T_tf); } - private TimedEstimate inverseVarianceFuse(ArrayList alignedAtTF, double tF) { - if (alignedAtTF.isEmpty()) return null; + private RBSIPose inverseVarianceFuse(ArrayList alignedAtTF, double tF) { + if (alignedAtTF == null || alignedAtTF.isEmpty()) return null; if (alignedAtTF.size() == 1) return alignedAtTF.get(0); - double sumWx = 0, sumWy = 0, sumWth = 0; - double sumX = 0, sumY = 0; - double sumCos = 0, sumSin = 0; + double sumWx = 0.0, sumWy = 0.0, sumWth = 0.0; + double sumX = 0.0, sumY = 0.0; + double sumCos = 0.0, sumSin = 0.0; + + for (int i = 0; i < alignedAtTF.size(); i++) { + final RBSIPose e = alignedAtTF.get(i); + final Pose2d p = e.pose(); + final Matrix s = e.stdDevs(); + + final double sx = s.get(0, 0); + final double sy = s.get(1, 0); + final double sth = s.get(2, 0); - for (var e : alignedAtTF) { - double sx = e.stdDevs.get(0, 0); - double sy = e.stdDevs.get(1, 0); - double sth = e.stdDevs.get(2, 0); + // variance = std^2, clamp away from 0 + final double vx = Math.max(sx * sx, kMinVariance); + final double vy = Math.max(sy * sy, kMinVariance); + final double vth = Math.max(sth * sth, kMinVariance); - double vx = sx * sx; - double vy = sy * sy; - double vth = sth * sth; + final double wx = 1.0 / vx; + final double wy = 1.0 / vy; + final double wth = 1.0 / vth; - double wx = 1.0 / vx; - double wy = 1.0 / vy; - double wth = 1.0 / vth; + // If any weight goes NaN/Inf, skip this measurement rather than poisoning the fuse. + if (!Double.isFinite(wx) || !Double.isFinite(wy) || !Double.isFinite(wth)) { + continue; + } sumWx += wx; sumWy += wy; sumWth += wth; - sumX += e.pose.getX() * wx; - sumY += e.pose.getY() * wy; + sumX += p.getX() * wx; + sumY += p.getY() * wy; - sumCos += e.pose.getRotation().getCos() * wth; - sumSin += e.pose.getRotation().getSin() * wth; + final Rotation2d rot = p.getRotation(); + sumCos += rot.getCos() * wth; + sumSin += rot.getSin() * wth; } - Pose2d fused = new Pose2d(sumX / sumWx, sumY / sumWy, new Rotation2d(sumCos, sumSin)); + // If everything got skipped, fail closed. + if (sumWx <= 0.0 || sumWy <= 0.0 || sumWth <= 0.0) return null; + + final Translation2d fusedTranslation = new Translation2d(sumX / sumWx, sumY / sumWy); + + // Rotation2d(cos, sin) will normalize internally; if both are ~0, fall back to zero. + final Rotation2d fusedRotation = + (Math.abs(sumCos) < 1e-12 && Math.abs(sumSin) < 1e-12) + ? Rotation2d.kZero + : new Rotation2d(sumCos, sumSin); + + final Pose2d fusedPose = new Pose2d(fusedTranslation, fusedRotation); - Matrix fusedStd = + final Matrix fusedStdDevs = VecBuilder.fill(Math.sqrt(1.0 / sumWx), Math.sqrt(1.0 / sumWy), Math.sqrt(1.0 / sumWth)); - return new TimedEstimate(fused, tF, fusedStd); + return new RBSIPose(fusedPose, tF, fusedStdDevs); } /** Smoothing buffer ***************************************************** */ - private void pushFused(TimedEstimate fused) { + private void pushFused(RBSIPose fused) { fusedBuffer.addLast(fused); while (fusedBuffer.size() > smoothMaxSize) { @@ -443,20 +468,22 @@ private void pushFused(TimedEstimate fused) { } // Trim by time window relative to newest - while (!fusedBuffer.isEmpty() && fused.ts - fusedBuffer.peekFirst().ts > smoothWindowSec) { + while (!fusedBuffer.isEmpty() + && fused.timestampSeconds() - fusedBuffer.peekFirst().timestampSeconds() + > smoothWindowSec) { fusedBuffer.removeFirst(); } } - private TimedEstimate smoothAtTime(double tF) { + private RBSIPose smoothAtTime(double tF) { if (fusedBuffer.isEmpty()) return null; if (fusedBuffer.size() == 1) return fusedBuffer.peekLast(); - final ArrayList aligned = new ArrayList<>(fusedBuffer.size()); + final ArrayList aligned = new ArrayList<>(fusedBuffer.size()); for (var e : fusedBuffer) { - Pose2d alignedPose = timeAlignPose(e.pose, e.ts, tF); + Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tF); if (alignedPose == null) continue; - aligned.add(new TimedEstimate(alignedPose, tF, e.stdDevs)); + aligned.add(new RBSIPose(alignedPose, tF, e.stdDevs())); } if (aligned.isEmpty()) return fusedBuffer.peekLast(); diff --git a/src/main/java/frc/robot/util/RBSIPose.java b/src/main/java/frc/robot/util/RBSIPose.java new file mode 100644 index 0000000..4a4df2f --- /dev/null +++ b/src/main/java/frc/robot/util/RBSIPose.java @@ -0,0 +1,21 @@ +// Copyright (c) 2024-2026 Az-FIRST +// http://github.com/AZ-First +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// version 3 as published by the Free Software Foundation or +// available in the root directory of this project. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. + +package frc.robot.util; + +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N3; + +public record RBSIPose(Pose2d pose, double timestampSeconds, Matrix stdDevs) {} From e4b0e3e1f8f4dfaa17cb7bdbf165651eaeeb392b Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Mon, 9 Feb 2026 10:08:40 -0700 Subject: [PATCH 04/22] Add extra logging for when the vision pose doesn't work --- .../frc/robot/subsystems/vision/Vision.java | 45 ++++++++++++------- 1 file changed, 29 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index e37b6a7..c7849e3 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -82,7 +82,8 @@ public interface PoseMeasurementConsumer { private volatile double yawGateLookbackSec = 0.30; private volatile double yawGateLimitRadPerSec = 5.0; - private static final double kMinVariance = 1e-12; // prevents divide-by-zero explosions + // Variance minimum for fusing poses to prevent divide-by-zero explosions + private static final double kMinVariance = 1e-12; /** Constructor */ public Vision(Drive drive, PoseMeasurementConsumer consumer, VisionIO... io) { @@ -109,43 +110,52 @@ public Vision(Drive drive, PoseMeasurementConsumer consumer, VisionIO... io) { @Override public void rbsiPeriodic() { + // Pose reset logic and logging long epoch = drive.getPoseResetEpoch(); if (epoch != lastSeenPoseResetEpoch) { lastSeenPoseResetEpoch = epoch; - resetPoseGate(drive.getLastPoseResetTimestamp()); // your existing method + resetPoseGate(drive.getLastPoseResetTimestamp()); Logger.recordOutput("Vision/PoseGateResetFromDrive", true); } else { Logger.recordOutput("Vision/PoseGateResetFromDrive", false); } - // Update/log camera inputs + // Update & log camera inputs for (int i = 0; i < io.length; i++) { io[i].updateInputs(inputs[i]); Logger.processInputs("Vision/Camera" + i, inputs[i]); } - // Pick one best accepted estimate per camera for this loop + // Pick the one best accepted estimate per camera for this loop final ArrayList perCamAccepted = new ArrayList<>(io.length); + // Loop over cameras for (int cam = 0; cam < io.length; cam++) { + + // Instantiate variables for this camera int seen = 0; int accepted = 0; int rejected = 0; - RBSIPose best = null; double bestTrustScale = Double.NaN; int bestTrustedCount = 0; int bestTagCount = 0; + // Loop over observations for this camera this loop for (var obs : inputs[cam].poseObservations) { + + // Increment seen++; + // Check the gating criteria; move on if bad GateResult gate = passesHardGatesAndYawGate(cam, obs); + Logger.recordOutput("Vision/Camera" + cam + "/GateFail", gate.reason); if (!gate.accepted) { rejected++; continue; } + // Build a pose estimate; move on if bad BuiltEstimate built = buildEstimate(cam, obs); if (built == null) { rejected++; @@ -261,9 +271,11 @@ public void setSingleTagYawGate(boolean enabled, double lookbackSec, double limi /** Gating + Scoring ***************************************************** */ private static final class GateResult { final boolean accepted; + final String reason; - GateResult(boolean accepted) { + GateResult(boolean accepted, String reason) { this.accepted = accepted; + this.reason = reason; } } @@ -271,36 +283,37 @@ private GateResult passesHardGatesAndYawGate(int cam, VisionIO.PoseObservation o final double ts = obs.timestamp(); // Monotonic per-camera time - if (ts <= lastAcceptedTsPerCam[cam]) return new GateResult(false); + if (ts <= lastAcceptedTsPerCam[cam]) return new GateResult(false, "monotonic time"); // Reject anything older than last pose reset - if (ts < lastPoseResetTimestamp) return new GateResult(false); + if (ts < lastPoseResetTimestamp) return new GateResult(false, "older than pose reset"); // Must have tags - if (obs.tagCount() <= 0) return new GateResult(false); + if (obs.tagCount() <= 0) return new GateResult(false, "no tags"); // Single-tag ambiguity gate - if (obs.tagCount() == 1 && obs.ambiguity() > maxAmbiguity) return new GateResult(false); + if (obs.tagCount() == 1 && obs.ambiguity() > maxAmbiguity) + return new GateResult(false, "highly ambiguous"); // Z sanity - if (Math.abs(obs.pose().getZ()) > maxZError) return new GateResult(false); + if (Math.abs(obs.pose().getZ()) > maxZError) return new GateResult(false, "z not sane"); // Field bounds Pose3d p = obs.pose(); if (p.getX() < 0.0 || p.getX() > FieldConstants.aprilTagLayout.getFieldLength()) - return new GateResult(false); + return new GateResult(false, "out of bounds field X"); if (p.getY() < 0.0 || p.getY() > FieldConstants.aprilTagLayout.getFieldWidth()) - return new GateResult(false); + return new GateResult(false, "out of bounds field Y"); - // Optional 254-style yaw gate: only meaningful for single-tag + // Optional yaw gate: only meaningful for single-tag if (enableSingleTagYawGate && obs.tagCount() == 1) { OptionalDouble maxYaw = drive.getMaxAbsYawRateRadPerSec(ts - yawGateLookbackSec, ts); if (maxYaw.isPresent() && maxYaw.getAsDouble() > yawGateLimitRadPerSec) { - return new GateResult(false); + return new GateResult(false, "YAW gate failed"); } } - return new GateResult(true); + return new GateResult(true, ""); } private static final class BuiltEstimate { From 87268127d04de9a87a96c9cfbb1ac1a4038e3e90 Mon Sep 17 00:00:00 2001 From: Timothy Ellsworth Bowers Date: Mon, 9 Feb 2026 10:46:00 -0700 Subject: [PATCH 05/22] Documentation Updates (#126) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Add GSG instructions related to building the Pi Box * Limit stall current * Begin the vision documentation * Minor Nits to vision docs * Update vision docs --------- Co-authored-by: Lewis Ruskin --- doc/INSTALL.md | 9 ++++- doc/PV_Cameras.png | Bin 0 -> 1250232 bytes doc/PV_Network.png | Bin 0 -> 309054 bytes doc/RBSI-GSG.md | 21 +++++++++- doc/RBSI-Vision.md | 80 +++++++++++++++++++++++++++++++++++++ doc/restricted_section.jpg | Bin 0 -> 39557 bytes 6 files changed, 107 insertions(+), 3 deletions(-) create mode 100644 doc/PV_Cameras.png create mode 100644 doc/PV_Network.png create mode 100644 doc/RBSI-Vision.md create mode 100644 doc/restricted_section.jpg diff --git a/doc/INSTALL.md b/doc/INSTALL.md index c3c2372..ac19b1c 100644 --- a/doc/INSTALL.md +++ b/doc/INSTALL.md @@ -13,7 +13,7 @@ following components on your laptop and devices. This includes all motors, CANivore, Pigeon 2.0, and all CANcoders! * Rev Hardware Client `2.0`, with the PDH and all SparkMax's, and other devices running firmware `26.1` or newer. -* Vivid Hosting Radio firmware `2.0` or newer is required for competition this +* Vivid Hosting Radio firmware `2.0.1` or newer is required for competition this year. * Photon Vision ([Orange Pi or other device](https://docs.photonvision.org/en/latest/docs/quick-start/quick-install.html)) **running `26.1` or newer** (make sure you are **not** acidentially running @@ -22,6 +22,8 @@ following components on your laptop and devices. It is highly recommmended to update all you devices, and label what can id's or ip adresses and firmware versions they are running. This helps your team, and the FRC field staff quickly identify issues. +If you are running a RoboRIO 1.0 (no sd card) you also neeed to disable the web server ([Instructions Here](https://docs.wpilib.org/en/stable/docs/software/wpilib-tools/roborio-team-number-setter/index.html)) + -------- ### Getting Az-RBSI @@ -118,7 +120,10 @@ steps you need to complete: https://github.com/CrossTheRoadElec/Phoenix6-Examples/blob/1db713d75b08a4315c9273cebf5b5e6a130ed3f7/java/SwerveWithPathPlanner/src/main/java/frc/robot/generated/TunerConstants.java#L171-L175). Before removing them, both lines will be marked as errors in VSCode. -5. In `TunerConstants.java`, change `kSteerInertia` to `0.004` and +5. In `TunerConstants.java`, change `kSlipCurrent` to `60` amps. This will + keep your robot from tearing holes in the carpet at competition! + +6. In `TunerConstants.java`, change `kSteerInertia` to `0.004` and `kDriveInertia` to `0.025` to allow the AdvantageKit simulation code to operate as expected. diff --git a/doc/PV_Cameras.png b/doc/PV_Cameras.png new file mode 100644 index 0000000000000000000000000000000000000000..b5293864853be9b7cbc7cc73cfa899f1462b36ce GIT binary patch literal 1250232 zcmbrm1z1%5z9 z@7d>`@7&Gam*<(8#hUf6U*~*$r6i4oL4<*TfPf_{BdLObfGLiEfHIAS0^A|f`cQ*_ zfKg~AA@NF9LW2C2lY_aHtr-G>%*TWzR5jI&M}9Y+;}YWXXr$r}0U#t9^z8R6q>?n$ zh~nrJxRSOZOyx#WlE}8}#eM-LDyCHwp?0s;wwuYrLaJHtC8bvM7ja!rGEU~*<2WqZ z1yX#kQ*P#N(wh*XSNJGj6EWe4Howp%*<2Efiu{exotqoY*Nb~KjR>L?Xmq>PjT>m0;)hQ(sfSPy>Tve9nEUY+9qGQR zv8j-M#mVQj3YO02HBKEh;-?jifB)i%mEX6YA#n)gqYp)dKBNULQ#4W8(l4V2p@reP zDk={zQh1RVn^2?d#pLgEJi3mh+i>8+%jM%sr=}l1WM_V-ESC5@qUQ2OF!F|Z!zy-0 z=)pr8nlNvPhb1BDGl4%I_|jwI1q4`Ve@=_cTs8gZ@Qum2Mysl3VCmht{8aw^`vXon zpVOEJ;|8%a&3qCyr^?p87uzKY4~Q~C3Lqzu41ONXkc&kqY97t?%}iqhEQy^g))yGGU(~elxP#U@A0(q+bpG6Z!;3x?bg(G? zjzbS|>a+Au^HU@*QuzCe#i`w=7+I#TIODPVNWP0!z4}t9rA8?it`ouVGU1c;E386p zHG)m-VjQl3^YE@5dQ1LU5?J`Llyp|py27FL;Y$$BIa)Iz^kaJ*tI6}@szQ3{3qAI;NNkAN^_@(@_{Wo|Q_nTo8&&qq# zY$VtPp&Xq}ivf-#dfeq`4VZ3^-LTz=c|tCNlD^n1mF>-+YPI4T`muIT{T%+~u=HUU z57|8c@ykbCg~f-7c=fp0k7m($&;x_ebC5O90Vhq9hCjX7@+X*{6doz0^ zJEj>j`x*Na_HMKCp2L1GTKZT8Stb<{S@Br~eg%GI4;c?-+BmFU__CH0w>w8uqF2mi z_@!(jr42=Y;!1CMOj)d5VjJ_t%Sdty^6q$D$|O2X7B>}m{#=Nl*!(Ln&2Wq%vmuSI z&UO1`GLqC6ISMTbedAB!8DG`kCx!A#Nl39uf!}2RLi`>UdhhXLsi?0xZ|S$5qtYim z4^(5C2LY#?gHmc-{IIx6e95m1D}qgtS&>XJW|d_yER{-!li988aT$AAjZWw6V>?Yd zf7g^_KA0wmhCdGcvLefEOxlGLr3hj1rS15=q~0=|&T^0NhI7}Gctj*f7>O6`6PL#1_%hlQQ>U|o52yNyKsUcI)- zxb?y035b9`!@X#P##ZI&noZ0tIEK3iB^faPH&WihhL|A8h?d29=_FE znuedw^v=^mHiE`8hgOG*hFpeN37#@9vhp?>eU_Sfzf`@DH=F<`+G!rH8&>R&SkhQJ zp3@)BSo7)e4zc>GVEoLieXsHm*OSvdye3_%L~BjxHCPz@9Sk)HHF#){U@+Y3(iYdc z)h6w|?WJ*=e)9eF{KEdAZFthud8TgrwFqj5x=+S6_05YLxtle_e8gXV^`g8ZtZzLR zu>DiiYXHQp28HBkq5rx-;F^0A@ zOj|m_f0fApNX%vCt5LJ3x7g@?r{JaLrGKfZ^r9e`Bk{9Rq0-Zp>PCU43U_!b`}~WA z_lA9Bav)hIMX!|Q*jgbg-Wld5L3hc|kJK>c^H1})6$zEGl!VgxQ}7celOvU*ltq}; z9_M2SaMZFpad=3Y=TN>j%vW8F9C%&Tarz2BzK*wqD=qZFOCIX3STgD>zH&ZwzRW}^ z7J-zKXvTrIsyWbE@QQ@{yt_!5XvJdrx>iw*6RhuAeL(#}Q=$Yx2wSGCdn#RA<; zkIt{zA9Wr0TKMt!URnfoAJkErCozo^H{@OjZ4Eu&7ttw!XU)kGwK2y z+?MJof9x|uH+^E%F?_vB)S0?}Z~7h|ssTy3;PesRQo*c*^#?g@ZviI3IXCJ<8H+Lr zJG+dR&_s_$0~HZ3PWXD63AkH_c!2nrXN*WbGH@w&slq4n=4>AQ29K1Ekd9c1FumA5 zhw}-K#9)7#v~H~KxsHjBr_x0R+|t?J=KTAwq)r$=Ox+@W$d*rDQ1_kdzTSLO)j`ey z6+tY^0}vDJofq5rFX+(w3~16NtA5kA_t_hQnytAfNsKVfjB;>$SL37;^xES9tA$vx zWAAowkWG0G?ztcEK>vf3mKK8aa7rJl|#PPg-=O?gxep0&7fsNlz z-tnAl>{+q5)m63kwCCw$iBtuOVVHq(_~WbWUFjp@C7yz7(9J=Y<>C6G?jEGqjd-D? zUF7o1u|&64&vZ@H1{qyfm`ITi|9;9|)0X^?r0kDohK`1e?I~V17x0^_UeojC+z_f& zg(#%wl0UymBFvMb_>tU0Sixr(VM~G!Fjk`zs~IQzyDN50OpP>ZWX%;75g34LGz4TsB82lr2B^Y$+qc-@Zq^LZ~e7y%Xd?-B5Nmxc6?r!mE|?)~E$Wg7SnK}=ObRu=eFHE}XC zvv;<108Oe!*8(@t-^yq^BOu_@+`bTHRj7A?`KPVav_M*l3j8Jxb}YuG4sXm@-r2pq zod-ei9Y1hsX9hARe`jZF@67*Bi1POn{J{0?ZB|P1-;aQ7gebKXUy(~VIGK@iv%Fw= zK`D$uPEIc9WNOZ@BKh*K;lO`Fl$IdSTYgqnH#avHHx3pDCks|KK0ZFy7woL;?99Lu z%+BuiAmew;_Rds)Ci%xal4i~(PF8P0Ru1;$xAPjmac}_%QBvM6^!MMNeVVH!xK2_AdV`t9NF$+LBgw0L*|jgxPqw*ad$N_#a>W*OLD< zRO`Qnvh(u(x1s;^)&DtE-Pz1Z!odz$6eRp#2>WZ@fBy2Xfr6~JXa6Ty`~mduy8xtx zF$7uv#+ooj2xUqrfJhQ6No6(Q6CktOzk9a8+w(u4z%^=DJxUpJ1OkF6f~=&N+B?K; zD5}wqm8G?)1s`99Cb+ZR^eo^C28Ykabtr<*{{MHm+Ly-Fc->6bnI8P z*lOPp89aMvOQ}uuR&UOP-8z<>n!;O_S=@Rrtej7Xhj&f{JEnG=kk96L9LM^&?dKW? zLPJBVTpS%eyCx>E%J4QElu|6(s|Pg`&*VbF!um@~O61x5IgxQi5fJ~)w{>JBS_wTf z_HU5EyvgK>HwWsb?HEgv8Y$a*lyO4fxYX41iFkU|TIG?!bh=a5!%^viv`SeP*t@I+d-n*k*pVFO~Yb7;2)au{@c{` zn;y|#k_!px@9*zZb5JdP4-XILC{RdI+3@xHBxYHLEaZ8--7EF|dqKH=%j6C3hGdhyj!yq3bNty#7MuTk zn}_UFxxPc1u=n|3yEhU_Hjc>UZlEH~I*tO(y5EJj@@Mw{0O@GtxJv%Olt0WY%t+7S zEjvS?E-PG+@S@*66`QS1AA=^R7108`;eVf;fDxje7!P`e4O4Ilc)TV{wV&`up@^+Z z;0PTCPuNV(z1Gl}1Rt2%{znk`%oq&@vv^+|Hu-dg6S{45d5En$E_LOVX*KO9MG*6> zdPEr^{=1UsH?TvH{GSPV*b*gYiWv39)2|!_jG&Ud{Y=Q{d$uw&J3IS4nO0Sl{2Wx+TJF!@08z-B0pA z_{q`o69qk9AjuED+bZO^ugLlMW+obxGxdN~cskAo#Q+eRnSY+QmCTAmw_I6!=I)-c zUEHL1yMX@?lPGyJ$AWh`>D{mvBIJLGcn|v+CA&ME(0L_)Fl{HSt>35%t+ot7Jqt1! zSMysceTzgeUY~B#9C&=UY1g-rnxHL)D_G)D(`HH1eRA@2AlJv`9nP4z0r0t#%o6Ea z34}}WV6fz_qKF(Hd5nYo*%3-MD%P`0S4G9a*HteZS3^X3kovwNsM7A(FELsFk7C>Qa`kp~(7P`>{;Qc(7mXXTwS=7O|v zhLW9>x`7qiOwUe%{FO-*jep>C`m@_Dk(=M=#>WrsUkRN#<8Ztq)B0mGR}S!?wTTjW5M=EK)Sj(!mLbC{7a%_A(d!Updj7t&;XrSK7M|PCGNn%F%a3M%}$5>l}40n z{cW$4!EY*xq>Q%1E#0Hv3(cf2Ivd$8-ZAiKW$xGeN9b%4%C2m8WdUrh4qP>et1!x^5-0Ee&WC|*h9es2{0?o{7 z3A3)EQ~u+Viv%?~H?{&7)byoazf7mHuS{<;4$O?AY>UcD;_|i{`lLmelJXcQr^x2d z>`R@=(iRyKx4CMHu=Nc;a{Z0s$}j@;dN&5_EIxSuV(YT65i)|gFgv#|4W=zHYmJze9~Hq@Z# zm+v?AdHr!{M&;6=XNPB|^7&1`d-dNoL~X+YP2#gKWL zWr3B^Ch5!!7EhrsZ7Q3XVqx9^l7%N)uDx!`ldG>_NQzxCt6o`qL~l^troTFs7aD9gJp|H~mTSv7^HdGh%;Q&@|(o{G=V7P}7)9h+*8J4P^#_->^Rn>2;*N~Hw({aSdz9pFeJaRPBbb_|K zT4!Hb7pXZ+nkf&TL916ngoT#f+75E%RdS}8irquPIFc-4i(J4ZKMG=tt=)aSvlVpP zUa#6mC?r6IKA85r?$~6IjvS0(u|hXDaMb~~*sNM0RquiAzOU4=UzL>Y4-x2^4gDJ1 z?LZnpQp3yb!v`909e4WNxt=Goo z7Z$5uCVS3BKl4(-5Jc(A=jz*Z*dtVyHLI?n-b;t6(Z7!cp%$WfeM~y5jB>QS$u;@n zaI~SrsMyw?qwQXUq-ND}>8Z@GO=~1KG{-Ib78tF-PHT-mICLcNIj_pN zySs~iYWKeAYde{@If1%N>F;;qh)l06Tpu?$eYsDN+)&T&zUYs-TvE}F@lKE!z=eN3 ze#k2M;a)cx>yi@h7lZwHO~ZsD)q?t?6=&hQYKiBME44Kb&s800ZpCiyN4`%r2LsBcN1P)YVhQX3Ul?rU!k#1?#3%bDf?j#GzLOBc934w zmA+F6Co`jAHRm@ct-oNg5re4+wH$^VY;;w2=gfwN^fxI@vIduLRUt|}JGNKYFp4Xj zEefkPMHf>GFV<97*L$0^6A6tvHhT5t;u>uYuQi6J*WJ3NwO|VshG_~Q&nW%8R>-Si z8--=Rw&0$nwX1os?h5Vjx!5zGCFdCf>#ya_UpU)VF5vBPbI#`!V?rE*_GxYJBGO%U z80SOBdS&ZW)Jb;?+&Uzwy${5DpI?q1JCuANF!ZYGRkiwVj5RBKwj76bezhiY6B87K ze70RPyc{F_%&Jm^gxGb)j6haNDN(&dW9Ee;ZjAR-GeQ!$c{}_fWCp z0mr9rvP{?Pd+3uG!uZ#K-qXLYQDy)wU*h5B6R_HuuS+ zPpbRy#e~rk4CIL|}=I$IQxHl9``l0@($~9Y? z*@&YzHH#x^v}f&&rHOktgM_A|F~@juA!&L#54cy(_?&m z{Aawn~DUTgKL*=Qny+g1nqmf&=$9(!8D$JDFXfF3;|3u@)3SStRrh1 zEA=I#iw1L7Sa!lX4?d;2*lNadQ;f0_jR(-4!lTh8E-B z;ksFMId)t&Ymw_*$v5hgKYI09%j^#NMy{|oC?vX0;u?|h#_CxNXa<*4`8-xlz7BIg zhOKf$!SfF$tS4P)OWSsv)T?Q`7$h2`a6LSC*i^t7JJCIPbeAu$_gmOpuiAMm`r{nD ze?l8f#2hDdbknyvD+@sVa!G@_Q?fd9{4+(KDG&O~qF)OQYO=b$U!0(Ebh_;LAg?VI zn`^JnpwI2KCfthkEQ9=TAcbQ~-Fv9FH>S#@yN{kOlajs&{uzF_F>bcM+&ljoUEGr% ziG{>%&XL`Ij<-cwqF-6$sGwF-VvGHlVFs)6lza<^`zoN*D7bZgX7#Nz~m~ihLvyNokuqKVZZYG?*fiiDhC_IX%8TVxE?g%b~1GG0VX*O!F>ZpN?@#vu|*?JeDsElK<%K zP^AK)kCK0G+Sv@npcf~o%-=#lb{M&|gbo*0W&lg6DQ`Imi?67N&dk)KfZ*G^mA}}` z)Floo4^xgEl!#LTlUn14@!uteDx8QZ4*tV3aJ6Z+AkLY#mnrk^vPp~t_&yTk9 zii?X!v(dzP%wbMB-mTfs z+xg<|`fTW^<-MSKR@tW^sgAisxY?02nQ_Gz;c5E**_8Lyizx}rgu)ExwcKd1zD>IC z-d!FQD~oL(`ai9a7*B33w{{owt}QS}&qMo63+7Y^t;L6l-aWHN8uqSHNN^JB6O7jk zW14-+ipgEj^Hs5^`kiWX>Flf&Hv!EI_7q9A8tovQ5h4eDk^*HVi7DkWl#`Q%wBn~? zif^fLr3+a9cs^R(RRH!Vwyz!pJWT5e2EOz4Pf~&1v&AJPc9q(U&ytdoAa?CIM304U zE)UF3cYo$g6x2C+Dk?@`&HL>4((SLNIh?yDt${s?g?rsZ!IRv+*IrFakpkOJVq%Nr zhdnV=E6rQwHQwb-tEni6PHjGID0F&dr1EldrlUDh``_@CWnRC&!tqi_ej#=Ybu%PR z1k`yN>}rx>BC@XJE6uRrMYz}HUbm})_sH2X3^E0gZs0qSxKK>xl;s%(Tz5(TMC5ec zF}iO*(*(oGL2-iHl6P_NZvC`Mzd_T@((#E zyk+5K@Mk)SGo;Mi-k=7kRsFPNZTVF1@g`Bq?vYnYL)o+~S{sb}xjwBvn@n>q&2-9o z4;)d5gS|xOe)CZNr@;X2Dfe#>LTf`Tr>z=p4#OJd64s>n$v*cRJqExNao)k$WAiLf zn1O9l#3mbygTY%3OKEJR5&{+(0ff_p3rb&==4=~gEFoWpbk?-hHK-OAYGgtakqzCs zzsXxo7?)v*Cmj+oKjFJS&o{TX*12-({j#T?J!#u*Wr=-n_r24=E=Eg7-`rT9?jzGL z`PABK$qZrK1-;c@AIzwwTic7J=N1(7d?L6KbA_id;wWCofqj)3Z&F)~LXPmy8fwe> zshvCBuG1uR9At6NTMvff?%@cIfDI*Tlw8c{(AwM&%s1xSJU{Pofl7Y9!J-sUyjOp+ z;M-A#1hYNx^;wGGSq3O+-`GB}+CcdKmyw83VVMpY84@XvR?BqkRqTv=1 z=QUtww+Z-OKoC_^KjYplo5)mERn5>p0w1+z`d&9d^ZTty3kShMy3f3JzlgR>1D?DX z8s`&`y|p2(M9_}}a*&KINzfg294;*)ULB}G3tc>utFc3mUF}{lZKF*<6K$~#>t|Jq z8E>{!lF8bdwchdXZNu(ApynM|SE+AJ)A^=4F*SR}7WCvWM&m)x7+WOMRy=3FFg=LNX#U~x&pn2|H(IPq6X2x`j8<_db zeP(}Xj>c)i#G%*9vm!PDqGC3)3exW2f(9w5)4v^``gwBW_K}*7wr6Q)H~}@^i=^?B zg^kLYd9U^iD3exsv8IMbY#lJ#`=Ti%Y~Q(Fp6<@nRQI#Q zwYCaEP7*W?Vs5TaI_8&Z+2a!v$v9Yo3cDhV274xBV zt0XS!QpC+}GT*s!--AJ(`sS)~%Q};?m!;iSqEkh3S2Grwz2Sr$+t(7#ft1^2Yq09$v@`sgQ^E0-IC+!hKQnw?uJ zst`QGZ9WDDY3N6%ODDH3P|VFEVLNW(`3y%W=8S&>CFe$XQyGHL79XC;Y%gBx1+`q z>7dn82}ABhtkrb^npIm9`C+AT=W?R1ebw6aN|Ir#u_km8Ih!k}^hv09$upZ*8i4~u z24E52_Oh>~-IiJIW4W@;&w;#~Q!h=@wAos=+s?exg7?YH5~tplnzie(KteXxa%r~V zf-B&khT{DIbJ-+XKAmYG1&xR~!JF1*6?MdP7-ek^u*56$TQtgB_vKok?!3p-CM&sd zO4TLp>M2x*gq%cmo*N5nlMHFFI$DpRlAcvu z%k*vM8G#W8T`vaWEN>KK9t$aW1#SU^?$qY(fm2J=sBwQvZX5`lS$ZPgyr|tli@_G# znua|I()f@+%ObGDB#_2xCvtTdcWK$4Y8~?+iiZp5&Z)~SpwZFJbSK?NTXRkw#sUY6i!ZqiWQ%6zPPzh%dPyn)a+oBG)@M1r{>H<8Ts| zd!DI&rP3N}zpw<-IGVdbBFz`c*ydk)`(|yb(>M!l%?reI#;N87Sqyh#sT{O$$6C_^ zeOv&Od=hf1O%2_AW|&061I=+Bi-Db*2S!#LOt|w8IzMq$PwJo4=pmRIaC4PDaxMuR z>5Sy!))^O2a&lrfJ#M2lvau~szVuhP7T19|1Bv4X&9jwxB~RQx5=gq`!ocG+gF^IFQ*1)UCnT9-2LoEOLEn;y?!IHOHlw zO^0LhZIF!nSXgU7C@GOy*Ys-;x@(QY`sw*rMbZ;S4PI#5@T}X-)d`N4Vp9=$E#CS> z=x{-XYwC$tJEqdxDV`vhKmmYSgL$6|y9EhbGYdMkD`0GYKWm4cgKyT8ZrWFs{I70A zA%BF+Q}2OfHY^4=fwf5tD3D2v)}PoKt!(7(R!s7~H`ZLPSRyNcxXxJKm}9UA-J?c> z)&F|v{}vq?L!v<%O{b!wEntMT?etCB{&nw8AgP^)lhR!y(70@fipI0}fan;;fheos z;VD>7eFJd~*di6w`&IKG!t`Q>YhXsddiGYGpc!pq>Sfa{7jLMyKKIi4@iyeozp)K%c`Tc`~?+w*88d&oV9arJ<8R<@a z^jMLjSRbBw6s7}lDA!C4HiLGrrUpY*vGv3tr;OsBc4Mmr@ zz_8G2Zdz3fVqs*A6S! z0kQQf8s^bSI#>24rTnQh)?`A#fJH z=R)L)Ab@ugD?B*?d%9q^TE%|hB{Akvn^Emv&LsxZ_Jvc6t!G5WHcP6WL24CLv%Q8y zSS$P86t2{SQ!cVwUCuGI)gRM2u=K=RVLF+q8|OniI(2?Rom#NS$XN~DTcN(Qfj0?! z2b%BB`IQCEHxo}cF*e$BeV)&35N_At?H-9J1@`6T<#7jH0!R%D&bUg$3%UjZjFR`N zu3sdg~9ew@yTqvySrQllmff<}Ka$fIuU>ce=`CWxt=b!5dv1bE{!)#{sS{ zZKH}uVCoOgSJUjBSOgXih6Hx>94>%Zb6EqtgWY9Q?MAWmu4OOZviu^xY_^)vpk19i z9LHXUb2=DX*w~kU{TSNJ+CvJOOfL$4XE&!tW}7p`G`%_M5e_veIo>RPLbI~pedBGX zOt{%uD-bL%wqxpSj)iAKYEgC{2F~mJS=G&I^kjzL4iExc z>7~njut}1QoXy&Hr~(*;-UIT5dw#qAsL!6SWw?Pe!cbDVrnhT>C{&ctaq{x=au1L< zXnhi%v6OCswGVH<;iBC3XV`XP(!v=kPEr?fl7I%d3n zj3MsH+8A@cj%dyC4AA_hzw8>g#^MI=8s#LF6+I~Vt-P;=UiSF6?Q@#juG-~0JZf^` z{$eu;nxF-_Bq;}Ij<=c@v}t)J3p_8|nq5G@^rHRzmDOV`iktO0l(J%ao^s9H{c&7 z;LN(s;!yW3<<+5^4c>CZeQkCVW3Vj*Oo?OQ zRZ7C`l;u?gBpkeV9-p8?c@~sM+Su&2RC?!j+ZNhKG^j{}gijX(SJIt_s^Z!|r87Q5Hh(k)av$S3+X*ym`yF}Y#dxXp>1sRi?UBk+0d;q%?EEBgau>h{sNWW#*bAM_l(98R=6H0VaG z^Po%JX=YeNEvmJyZ{|hIJeA`naECnv;Ef4U_K51cR7B=%J&hs$-cqaT82HqLeq4phc>&! zp^|yM0%B2ljg4AEA~%;F7a8QBER!g{)u((wX36dbh;HeEeXq|vx+6&iG*~(=omyaN z4(%~Ol4zLa0~H!685!$sggZAkcbd(7AejP)W~sHE@iO|}Tr8L^e)e}gx-EXZkBL9M z5)iN$Fyec;M79EisA{{drPkdRyr) zSBg=&;*&J_(H}Lz%11Y@qfE(mN;0$FRqz+pEfq6m-Ko0{vg&0Dryk$|h=#3@xc9W( zt7e5}uV_%O%!?T#tT!#)6%!VoDhHPJHkOcbh%k7!DkIDw0M2$$Ep(`z+t~VY=%$pKbM>-Nsq#UVZk#5zQ&cvrW0& zz!CmoPk58``N@t$!6lHq?P08FrDW77jRsP>x=JEfpx&XO`U?Y(4H|bK@U&fh@B&cm zvg`{Nb#-;zmY0AYkWp7pfR>3Zd?53gCKd*A&z?JNbSo<>PM;A`r=x3w{f@NCnp;6d zEgtTGr01ttC?09P22{pJlz1RwX*;4@!ecW6X`25lOO>l{$M_tL1uY{X!HiMf=2U0F z^9MW-M>yIJQa>X%ibtz}%QcoiQ8S^ZYZEZyHt$}rE?CzFD0tU_u`v}JTb_Nuw->`i z#(RsM?=XUAwTu81Tzsy)W0@3?$wcNHw7!)XF4a7dB$VApqCR@%DBUZ>;hmAGJXEa(%Y7lhGca-W7p1f&iGR#~drLu#t z_v+nbxV6<`!X5@qS`QOxO>T}v)M?k4_jX(#RiL!cDWyM`2!2r1a0M8GNkHO%+Rppp zI03M(AwY(2s@Fn_Q3(h;L0V|^#4Je{fy#k|1t97)Uj-5ioYrBRZLreP?wkRF1M`Ew zrTo!n#Cs?q8p+2Z9VfZwKR-nY$I8ahy7Sc0qQP|E&+`2Q^4rGuW`_8IGE&@hKZnLM zKp@-}32?gy7+vtVSL1I}qd}3Vo9|HO^!pJ>1<|F7`tK^Z9#Q2pPI2fGI0Fi9%JZ_1 z(k#;6AM3?2m+F;#)Za0i9jJ{@0}}?0#oUp)UHK8NO@=OOE@j? zUC7VEOF+>g5^Oc|qSnm=Zav}1Jq<&q*)l!jPr8K7sIyx*T5Zv;^6^_}<%jcHWaXYH zxqPS^JmtS%rUIMK;y4Q5VMf%qIscXh1%FJVuH}FM23+-S?~`g5V_UUAjo^AT@hNJH zzQh2D2Ve+8hXc6P`G7vwQoNkubg5Xp>1ajS^g73IuGCyNiDkoSQ|y!3*PkZT^sl4B z;?{&y=-dQ(I$IUCOf56toL%h>I;~o^O}SL(Q;R7j3rf}}(WOnl0-cY2f1BXY;J!W_S6&&FCbN6n18Z1d2}H$7%*mky`av-_VN-qI zk_!8*NnKi|8?X(-<2*>>z(F27>3PH)0JT1_UiRH=w- z*=rs0Y!>XfxVZL@rVJrQjYFdiSR}k7!Kp538l%_85C<51^pkWy;5M2hc{2(?uvU$e z^j%~2mb#}}e4qshRX|{Za=bvq`X-UC;+BnN$PK&fLLi9&p9hM?e{UZc~6yU zt5$@~cLQl%kDU*}14rNyAQJ*Y#Nx5BVL^t4e5H@ zVwT@|**c>1*t{xpzoqR~(tWncB%xQ#NyRT9wqu$opZ&m3hi>PpKJlaPN`yI1(?`4I zlLRqShS#fdJx>)f*~!WhEWEV1)V*!n^gS1nVL_NM93vBU!^bbMc;~0?oG^~@!i66Z=YnuJ3INZDi zA3v@EUEp3PGQeI zBEA#(fterIFRqK*sgz{3z}{ zCV`xb%Ob|?^;GebD6Ypqu$P`^63{xVK)XUUXk)CaS<<#e!{!;cZSvvzs06p&EVc96 zP?;toKMCF_8y5(uIL4r7woAiN;p83$8XbTjV9c*yZ-@mQO35G(Mak>$qltGPUzr@= z4K?=Oi>Ffe4RMF*@T-f<(sWIlgo zS1cvcZu(xZ4U}MSb>KSxT4?2~iHD4wO2CiQ=&H!lm^Y+`9ktIY&2#K(;+!fViso%& zLE$$$5m@XS8M{H@sL#fAF(P+NI!E~PSF;8W=M2r=yNkOAh71Lo*NQ0C%~YrQ`go>N zBB~~48PN0zlE@(#*zudDZqGHJ4DmXZ>bY&Vr_!Hr?gZ3)nQcEBeABd-;+8k2E^np4*b9o zkB>Tp=gXJvv6(Te*g)=-x#i#!oVw_s(9z&36OfX&tZ@XI!-zl$&x|bXO>H699)@ocVce_=6rXkZp}!@T z_{C6+*Ner@GOu+yj|0y&!1 zc~$y+QqZjd$^x04484-cPDo-Yq+#Rgk#j92ruj6}g{881EgUuH+sNUAf^u>;X6IA7 zD=^mjzVz=g=b=f8qR};~vw@Gn()oa(Y%)wg( z@)IHKXk`Qj8L`Y#_k5V^(20UwbeSv+xusiRsI=O)*j_YA zh9*kVX2Av+Nrvr6gC_Z`&DL|;FJu(u5-s{xA@cp6HUWZ0&YDrjk7HazWj#HuPx)+) z2-E_OL;ti|jLZYY$B+x`7s7Y!dhx3e{eU5UVeqscjgtm9lDw9b6)406DwbFDQPYf^ zy{J?zY033988>v3V(@N`)_wY@J|K>2!Wk4E9&!<1UYw;-&0Z>WYh~>#&DLNf6 z@{FSlTYu6!xe;&$_4NW~HjA!FdVb8P>rz?Kl+f56h|3nvJu9Sx{Am}n)C6z|>lRcJvwO&>%hms&wUDv%%7Ky^>N4*oGN&C?~^U;ZgO-b4lt2xT@FzuTgs1^B=LiyVB{+D>KeXA4xk(EME?IPwqxl-swK zKCV0VgjE4m>-?@eq#QV}$!Tb$JeF79zvKMyS5>X6ca{mt-^CJg^ye0XaCm7kdJ>Pi}&?$T;TlJrJ^QT(<@6LoT=#QTe z$XA`^+!0cM>5K&+`qNLA7au|}fHOYl3H&`2M2?u$PowkX->9YML<7bLw|pj{WEkl% z>wyudslt&^tS5UgeQCh_z4)U^${5Fqkkx#oL_I~xef1Lr$4I-z{zuy!&UNr zAqwehdz9Y?T3D)-;^eYhvb=v+nCEB%b8#+^u1=aGsRi0|$SM6PwD5Z}f?FG$ zZFM)|1o)yh2|;ZAIM!k=1RV(Y$V9cahD3CW{zVJ;KnIFjqQIcb9a~UF=>dl0-@&Z0 zmhiv6IU zkPz(;Eij5cO(j6O6xHmmbmgyf z+x9a)e;(=flgI}ilQgx*63!_8N2qrp163H={|2yrJ_dlLq(4OZ5V2TPIw(c#4?&{I z{o9~=3rJz?B&M~9kpBbhk_8C<>+7wo0~mjR_piXdjs}o|z*qfk(<#yW>q@SjfAtGu zQ)KyD+Nphn<2J;F{pphZmjWV39AF!@ITYH5GNSi}mBv@p4pv$QXS#ua@A4!NTj@IMl~Ya;5ORfwqk{d6RcC*T~9FPB|= zSpg$JSxu~6yXF6#m0x)F2K?i<0RERJfi}ZKp2!AjTxbqCC*u0sIm)3sHj4i9_7IRF z&^ZZ0?77jPRIJKC?<6a4(8M$S2r^=Vg$jpjd@qmV93J-bb8J?7KP z382$_V(T-;e{>#PyIXaME-npGG!{matPur@dDYa_KMHSY+S!$PPx4JoOh_I4NFl!4 z?6^lrj*jr=M4*%Q5s>#dFEs?h5XXF*tbXW}xH$+-xwt=hOSKW_HPdK9H?UcfY@~5L zD%y^VHiSt|C99p8+BV2`30YGF63pe zFE5)qe)VP+0{fsz#sQ03HWO#Kv9wlnUANJpkzSlcGm4TkA?X}7<>Y(~&O#UY@IE>2 zjw+b~)AF5i=SWde5%*Kl{g1r3{%Dxd@}VzyJL|OkPA2eGrPRBD&iSj8g$|Zt^KMfh zLiP*kJn*Hqc1jrn>E0JY-2b-c|38ZVbC28-u?#l@3|1oNx8%bP$pwxfW6hyqbN`*8 zU73+-RFrct6&g%tH(YcLuduwl9&x>|uW!h0Pmk?xm>NMut`)CE$-%?J6Zkyw7M)be zPfta z6eC30SKP3=F0h$1s=>R@d+D^8X#me@h9pPoluDbmZpe z2RkAwMTmOedH}%R5l?lnDC(p2vAi(AoC9SshF-~2{DXv^`|s~N>7w%&2Co0{YX6oJ z|Er?IjYHBQ1bQl%Y1f8wP2>TP+d^5*iJK92O0psEmt=sL!>g5aG|3`SE32Y)9FjX* zEkGCss3L)n;-V!1lmfJG&s#oO^ycz_KM-4AZz32#2HLP|Cvb@O_V!}qH=$=A)tc?n6UM8|+e^P6GTe3(#5s*y=N^ zShCVKVR5`g95e`UrOwKx0EqYq3|314VqyOY;?5y>(bX5Q2NB4ON)>|AJBTzXp-AsF zv=AWFgoL};``mlSy<_kHIbRrj2_*Tgr_E>1x#j~Z8<)MKpV0Y+lRtrYJPHQVl!>MQ zzei(v7uWXpJv6kmsMmdHl)2MLaFc*LmHXI3>Z7#e|2}*a!x_4Idv9GHTG+P7n|`=f ze(&yGyUbP=reMB*ofLrwtg3n&`g%9OK<_NcJT*a9;kyl(;>vZ7e-6WccPOE`TM$Ne z=ZE$GIe-84h(_22r=_tkREKo#3pgHiSKmqeyZzY)5VVv)x)IK*+W7(mY7kXPvX{D9 z1qF|QP9`L!j`*QC^K>bECTo0cx}OBsR%xg(X7hjd>Hps@xwv@S7&ofW6$s@Wt!WIh)c%Wb6&i{` z>vC0OA$_;oM@K|V$c%+r@b;V3q4K0kYZmQmaf)9qgVL&@tE(GjllyG>i_pI;k;qsG6QLm)yaV3ND-1+wt;<)GmBf-6Ot!>^844GxK_SdO8Id_lN)Q6Tm>2Vp>vQvG`fkYM#>CLR)yxjQ1Qz-|%-y zNopkr+qi3NB%zn6izElFdlE)WXi<-aL5AwJs-E%stedMgp$9#hcAvfBQD3EqZ%BWp z$Q=SQx*FZo6;(Q!pR>{L6rYiY5dOyh8?(sDrLu+mpUU}f-q-=GyK&2Yna%Hyu8h65 zQt>+&Y7M2Ro~W$aS9y{s=wvq*ap-{H_9(0UTBXJUg*T+Zaq9=#cu>EmJb5ALtu#5< z&*Mwq($R7}bQ;07f#%e&T-UP0Bb(+n#_*VCAuj(Nr7UON>KJa1zcW|wgek6(;EDxJ z1&yM#KO`jFVPRnr*qHjH4fFyHr>9ut-mng|@~dnBT}0A(hX0b7sO~6t>EF}k|CkHb z(twQtZrm!alKJeM&CBM}Krc!Mp7{`<`xT@iE@6Szpv)`TMC{VVse2F(O~JwvmxN2{ z7_fuR(k@1@v67(g()D4AgH1^q$JCbmEV61rcQOh492s8$<34`l+=E0`=bP8MSxbe# zPj;8hgbZ_$r0LvSTTa(;T6fPH8v=ZX&BhKO6qu}MFS!hk2cV%{8$_)d1D73-&C!xt zXC-tXAd@;la8*;zmp7zjc<3lE5@riZN@9LL{WoeDq^Lr^FNDNl&8@Ai8(k@A*!djB zN}b9Y&3Fy}hxRT@i#*MKz;_6cWV*oFn#n`aqPiCs7abE+GII;bsa92e;c-x6jie3Z z`VZ2WF-{P0ZW_U>)00lYMM{$1{pVZFw8+7}18XSB0$s%D(MU(>h@{Z^{-EQxCJHq_ zEU~*1C@Um0GonL^cL{9*hC{0#UkwB7hqI#O*$-tIzw47n2QPI~e0BomPvBOa%5=u} zls0)0#zR0Id0Sk(^7adpzv{(GnQwkkR$=~^n!;(&)k7H!R7^}vKLH=0j3)8Jhk1g> zcQ~}_E7bu|n^-p!4jBkfBKutc%WH4e5A)vehjY(py|;_>P7A5^?+E%sA)E5oeLn-$ z!erhNH)v2o&A7z$oSdAeIwSK^CHl=k1UE%nY8!t7C}wr-@!RR2*Bhk(9ZfahU=sK% zF`sM{BbEX2jdYraXU+@}BMPoK7GK{Xo9aewEgnZ-bXwcGmn^XIh}_@IlVuK+8Z znGmmrV^*fty#y%YRIk9Yai}>kaM1O@<|E)S{S~BeFO^rr+~D!zydm$q|KXgK^6B=I zWh@d(yUMr+v;>owCjqoIJHIZIa&AiD*lzRkMqSc85YNS@*aMk-Z8W>|kk`qk`58Yr zG!8|w_(|P!GqJ-78?N=KY6Ot~Mm9-MUA~NVxc6nu&+kPfJPRFpue5BAtKaWK6H*>1 z9=skixTNzDDE6x_t^=!vVfb0am?;bMe@&gi{Ws@Ls3&V*pIfBJ7^V=Xl8J23#VRd+ zLKjlJE66WS0iKqo;9d5k*6OZrM3X~zq&#n~TFh18Dy%hDd14qd3TFk#>p%v{;BnJr zQs=o=3@by#TiuXl0rcH7==f=9F;Oy0wDer#gER6N60R_WkB&v@QP+J#kk5_je<#lt zS1Gj2ST(LGQo_d;8)OIK)_Lc&oa(+`lx?J;Hn$fpEzDDTL?BfyzPL#%HE7863|f;`P*FR|=(lEP#|Lq1O1U*2gE)$$57e52pqr?4xX^SONR!+KclEtk`#IW9<=~HDgQue&{UpIrXT`HR$2mZz74A> z4vtwvlr^#(2L}ZR8v?CZ-`ik!H@9UV%VI!D>PevnY~PQ_NaqihcP2^dwc5jXk=Y)3=pYQLq(fXlI(bcc(QGTuUAO9x|z}7w30ns>0 zGzr7Jw<_VUxHjTWoS8b3nRK6!Od3m3{P{X!-!!{oG@9*?PanrH$Xf}kpHfo&3h)7; z12`9=_RhqaKWmuRufaMUtX0MM)qzECR*SKlj>hkgL1vFCxxAC=B-Vt$X${tIWFkj6 znqZGzI{8c^lDR9OZr?9dcgkb7EN#!mB4V#`-I=Rlx(dePB& z=lj@Jm^RyGQ%R`^YI>#tS`NE1`GIidQ{Ehe5Mf@mY^0NbWavKt@v9pvwFr?7Yl>SB zFAyVZv{)c9xoGY!wc!7Pc&-;Lw?U4o{!iU~m4$4c|H!xnwPwlxw*w z0(-|Vz%r%#_j?8t_ag0pEe+oETc|YmSaCi094ESML+(l=V6* zkD8Jo%Ca>y*KXLV=j@{TS>Ms@uL}@fMZm2jMo!JGhyl6skQZPEHK}$!$n2Wi$QFK}l6hkkjQYkxF{B!S<{qTiU z!>$0p-Bc;wGxOhVpAD!p4}3H_Z(F7n+U+ZtZ}-f+_^w0cBH?ffNxa>9B!mbgVlx{T zq)|zVNMLM`b>uhg9SEqFxI`i-PHlcN)Mv;P@t#X~uNhAx{JN(3(m6-igOi9Z$c_Cu z5|NI^F<&MS2ZOQ<-;EvJBh0!_iX!EBgc^22$|n~=I=s$o=969W7!&x^N@?wB>@KwW ztZvd2wi54!ovd^KltpUdi;a>^+B_oH_kpoABKbfeNy!|KJ%USc@M!W}+&30wm^qpk zIJ!phct4bth|WuO-hD$uRba({4y1B8Z!TfQFu*5; z9_IuGbI80ZNb@{=KATk;>k1@`5%7(gA9;bX^t+k7fZ-W5bh|??>3|SD4g-w(R*M6(IY5} zxtZ(5W`IFj2Ov*@VrI&V!LCho9ZA>k!Z<+Nw}!MJ3V_~#MtYeJpDOz6#6;$_)B3*~ z8V2|C&$ETWfvEtx8834t$nIc}eK2Q~a_=i+H(ryjF1rfT+`KXSh9Wz(`?h$R(`NNr z^AWk;%7kQ1;o0o>GcWe{dCkGkiqGt`o2=sGC9Xd7>Jq6C{z9xWcM1*}NSPS0AH=0D zRCc|(Ut#NK9z$Mkfx3PG>VFXbjkSci#s2H>oYAz`BT+viBm_}A8V(= zFDM1R@t)ODrdHlG&&b!w+@@aKK$Py59B=okcaH2<+DREcL=v?gMrj{-Q#aW2O*8|& zG3;M1F3+3iJZ4+PJlW-aD~{+0zl)m?GO^$r%VuBV$a+scXWyA^=r{5d3&cohz71DU zR41BMj%lXyb+~E){k@SZi;|IMgu4)v|Ge@OaKmvy)UL9+&@~nm6qwo0uwZJIVm|{G z>}2VNU#@S$moHNF=s-spsQxOX8Ixj~CD|JtDSCs?o1q88Il)awyt6X8INCKAgvmWC zSuN=J(&+?(%O^?FC8NB!wcKUCuC|Gq=JmsI^8JHN|0HGe%ea(eQ5)@0*8_s)+~;(R z4Z8Tqa4tNzgaE7q_M1A*UE7%ih{C27FDS78ww3!&!&(*(rR|M7`RmQQ4iFq@Lp&wg z|2E?{T~s_DT%Nsb+etomKkl0H-;jvx3dMFN6W@%{=&2!*kagyDZjUGK8m*=eg#!XY z`%>->I4bE0jL&=Mp{QPSfl;P{6;u5DDxuoA@1`bjpnxAQg!`taYerx5bBBL+Zluwz zx$1-|)_wGMLFPQbgb~CPGg&cI&15+UBRWi ze;w?)4`c$w^b2pyj!IB}u(#Dqos9WyEOx9fF^DE z769MkzguKwm49~5-NBHkv#h1!_j8%ScL&ar#bJ zCw2oFfBLW({uBr)eW53ERvlN^KuW(JfVRKvfl!vtn|Pl@;~UdYyU)76AIN3bExlc{ zL^GIGUe!_bXQPRd;Z7HD#3_tA^fNjeTASKOKBA^^7%mznw))MK&YiK2dzp>l3N=ec z(Np`C^I>V`{tK$Gv(Tde?HqQJlF^=v*I!)OpDbj@`xGYdMpU6Jpw z1Dn;uX9RH_92*79?&4%jn*3p(j|`BAW-Y~3;?`-gB=80Ma39|HI;Qw$dP_aqh z&|s4Gr}Pp3`51w^>)N74>x8 zg={qMEOx8@MfG}ftCZH+3vSj_qU=L8HMPH*eUhESDO=Z-)&^YcKs;y14IF=5>Wo7q z+6)AJ5403K%N0*u#A7A}q&v>ov%fQh(WnX>TfG#4aDeD-Eml9H*JTSkq^+!4rTw|q zOudl4a8~ZkyYuPG%FGewc@WDrrE3?ThrE};ag$x7r(^sWlyhD9W@*Iby+==T5v=06 zjMRd0IclWNzi+2p7*x3((m_Yh^k$qv^VM@~cF{BbUH!or z(hnxShLXp?^e%PJ<^JQ54(-fITumRsY-Xx8zShWKDhley8V5+qe>D#M$U3b5|EB^!;IagVfKj(fV z7H-^p1W`VlFXH-IeL7-t^@f?Yg&%pg^g>J)@03G6gUP5RnGWR;e4do+S>PQRj~gG< z#}fy300cG!%r>4*@U~V%B7YL&WHt)^5ZAgSz;K4YhH=m5$o@y+ayhkfIVQH=lhRtP zromoqPf;Y;t~XbgBi;gv2ATlvOx)l6#S&w#WQrQzu5lflO7)O{LBXxgN_LG zVqMzWFMr}F`6HtVn~u4)l|#P~jigo5F7jS79LX6H#q7$P9dNh}B-{-9>KP>Q3mNC`WlG)2X%Eag!i=K5bM zX60S`KDX0{w`@|_A<}+LO_=%OEtp}|qY$)v)hEBmm&_*DX7u)IFNNej``@BEPD!=_ z+Bxd2+@cV)2+iTet)4|c?mBD)g~UpWEar#i4;{;?+##9xLn~a5vvI<#*WT1xrLCx^ z&q1+SI%hqqj(;08)A%n>J)-MRlZ@_kN+B3I2^|PYl>%w-XQUoyKR2u>5(swi|0J;z3B?&CBLxLdfWRCn>d&`OwP)_Z|U?v zoz$h$*%&fTmwBrL*Ml%jtCBAM@Pb=hbC?sq`=t0w{QFakPZckc|HmKK)i0Kw5!W+` zc7CHg1Jm0B3mTkZuao$SMzW8*P^Xh3WAWHAbjG{=uubEWgP%9Fs+L||QAX&9Zbc55 zI;3=quOFcNaW7sQ&qyO~YQ0Gj-p`uy2puqWS(dr`HYZQ-QPgITBdKY9Mt@Vt=G3wn z-|_ECd#YC}6H(3z)9gw#5e})Q4tLn0pCyK^`}4(TxW$HF)z&t3KbUjt5#Yc=PCPdJ zXDbNy={=)gT*V(ioFH|?KC7X&ffI>g7YOT$2BoszIzo?p$=~5+C#L}oc6&Hrws=F7 ziDM2oT750|c9xoOX=wsQcADx9Nz4v2Xl!D zU7bBn#8mF8#7%A{OGF@HEKmzfiP{Y_V>~zP;E(h5+LlKU@B`lwh0NV(8;>hyoi*nm z*5OQ{N7Tw~K z5I$P}{7%R~nC^2S*t{$keSCJZLgr`f5>o+L+|sRcEM`;68Mjp4iHoFa6LI8RMu~C- zpZY*)m6096NZqjLlh7N1K3gN>LaL8aQ*Hia%4=_*oVFkNj2sKwG;54YyZ9+oF@?bo ziX*kRrfMmRr+l>GQ{Ct+KQn51E*qj8t#UJ{C>r`}d9IH7rBqrMQZOmnG1eB%EedZt zv~150-(;iSOj=NY^!(iRLNMG|ES*Pg2kiI>cxF=(adxIQy`4r(VcQ1J>oV7u2_96+?k|KR74{s)!#)80{`g(;A2o+hUWdO7O=rb3 zKcI&Vs+4Yi3_aNiho&{*XE25|e<~ZBiJQ%W@N`K`uw^Z$W=FAJQ;;Uz*aVCEET75& zNa6D79zz=MZ+_`Lvkd1L-L{tK(d6VUMgKD(uy=F$$vD(NywvY=Xg6Cs>X>}%cxA>X zZtL=xLOm0C6nxXyaS~oxx?(@%!^#}iPggZFco8G38kH zq;q3Xv~1G`L|Ih6{n?5xsv5I-csAKc}rHSvCtTFPp1yFK*$21Wo^m zDZ@OfMNDByKdukD6wRY8#X>C939zTXa_5c7>>T}{{6Dh1T%MI?N^3>y`>gMfo4_Y- zj&mQl3O)glwmn{4r(my#l7a&JT~?v`M@Ei1$<#Duchk3`-IKGaX2MhzL!iDTM>+JX zYoa7RwPqsNPM10z>0Z(BSU@u0gX-@vG~2gGc^Fb5T58)1<-Ji+v=T$~xpl17Zo>-Y zxRx28(?)t$7HC5}alX~Sj_sx9V5c1{h~$j1Q?oLO+Tm?;KN5(kx68%3??3rA15RMB zPq&t+E>kAW%7G8q05BRH)!N-@vH@2Xx@Ta@ClbrA{6L`aZzBo4D6lDfn%1KF)<)ZY zDeqkp0_egVLb~*^?HnlKh$Gl7My({j-JJII`F!?in!!CzgJ>+<1>u*e(OCjhmjZ9i z%hDMgTDp>6>FMxAi5PQ+#X9?+xwVmK%jM_nIdbelua>1RL&ceg)BAaNH`#}O`?iIZ zi5kS6(9HV@6!DbxH7=nswiL<9+Tf+@dox{HDw0C=(r8@LizxoyAG5C99$Gwa*qa$! zL>`efKu@}LItn78|NQngt>zY+x-Y5O?lJ!ES>W-`i}te>{^b>J5BNh8{3sHja_zV& zr|OwVr!7lbzh@%mTZ#1sJ}$@xo&Q*?|5e0o3lt5m%OF}brHN-1~g10Z)h7z3A%ZOotp35*?giYcPqW4ew`rRG#m$Wy!NC z={tpn+ylxsn7yqsSSZGJdtx?cJK5beYq4L(44Sk0w5XR;7IBMTE^_*`R=%N1j4yup z`7XE6Na4=4F_l`PR$h?9CQPYi;=bsZY4iR!Atv`ugjObS1!~8-_%E@cw;sWyA(DD& z0+UOeM>RK%=*LuY{fLj8H>tT zarVj>hkf0+KE~If%k(U{+yCiBNf-U-hTRS}thUvO9CYo*SCt^RU?rSZ3ewYGrOKVO ztI|@-4@vhfF6Z}3%?l;($F*LlLyX&+id6jhSdo%|Azgl{M)bdrr0kg>+J zT))v#gN^zy1mvsc4O-9SXucLGvsnJVEr?-hVeoimLNefrYiEjsB!upvoT#a^rNzG!Oa>4ju;YJJjkofS17 z0sePCU#P8^;EL}-`f85ZvB}Y8q7*%3_a+jSvc4c$JIPiUGEXlgg}N&T(Z95w2EBst z0!GFd@zi}p%$NFMOFTpBGcSeD(-TS6a%)eH)+8~!8HuFPgX!u;uif3M`y{3+WXt;o z_W~Hb1FtR%8I9z*ZJ&<^`$%uykrx&1sU?Bq>g|+lQ*2X~Vu!W5@yDN@2x?5fd;3lskGbY^i#davGx-xG_9{!FL+ zK4hPg$7AjxOpQ)bxdYR_8W?Q8W}!4=h+QfFsFQlqA3Cswt+nHGNm>bHzk8+|1Iw9o z58IT!8^^|YUB~QOGWuW8$YA*^k*R zS!2)wqdFd`+dMst-j~ar8n-nciNSVx2Yyf8+tt_~6M)1#AzSYmnPAC4CnEjA>edZsJxoL(G;N;ORP`RjH}t*sKk?b{=@&1pr3+iF zbA$IqZ@MjglKg{8_2gtpmKhBkk;3)eHlUtzsjj^m))DI9cuFEY5^E>qL%cl18TY~{ zD5`->l^?5Yz=+KCVTw5d#yvwSd`S+8VR2l9HT7zQ*5}QLP24L%K3hhnSxSM=^;wWH zhK!vs6+_Wd*-tlmFITyuKP!7OM&*b=uRIY>_H6gaEnvlzYo><`?82LS(ol+f++vx} zsbpLQKE08+_AxML-o&4VleiPkJjS23!C|N6V3&6r37MU}Yjk zLDQaZz4c{|BYexrDrCSQBE7|CNS=gTl%{f(R&E{Mj*BmBSl zWSq6ND(VN^Do76Zf6Wl~nic$6b=MX;rCR?rI)E0d_?LLYj(#&hYbumv?M-b(%91 z*R^wu=u#9#Hp4smF2bZr?Ty(Le>#1ky;h7%*RGcP(D!BwnrvA6qd9Bu0mZvsQfSXF zCD#g>&;kF_Lfcd>#!ipLkHT-vPQ>cmvrI~ddi-E-^=N*1&p91c*zV?B{|2 zPBMtedeEb(YEDu*cyqZ&?rMg>lzQNmsk?9bsx)gdJG`$dVTyJK%umx;C7X8|hh2L5 zARVjT{NbWYzDsO#&-9=7clKyFkquHlK=D=#nw!B=={%;hd-1Rj2>}p%g&U747am?D zC(1Rr7ddcxl|)jwufo&KqCWP6oTQx2Y^fLg#@7vf#nXXYI_ zr59C@h0)ddiz;40T9IwR%qofJ54LHXYlrYluFOe|$tRCF2AV?mF4pRc9HdX`rC&=( zYWH5`oCpmU(|;XylWqmq{TeV>f?@pTQj7RC;)YzRPCm(?|UkpDI0(VpBdg)VT_8B5fx+3 zl^1a<#$j3aYuwX)_e}hBj_jCY_v-Rk2_-{jz~}_}zN&&bV^!ql+448OLvEx5Rb&Qg*%7DwlHTKzhmR`iC()LV6KF%t%n@ zVM1JYXf?32nyjs&zof*PY$^GM3&j3#$mq82pCeBEPJ7?jpqLDbAj+NJI+9QCif&W! zs~xsL^{1li*(t>VLQz5Ry3cIBJX`{q;ndiq9C=Xd9`(2YG%qjkEw^zCPf{a4vwtXK zzpo?q>-|c?*%$JQkDGdvFJ<$xnoqNj?@xjD7|X!M{$<4}ujf;oRUVSUGidf6gs^1; zt>^f?bW37;bhCmz6r$`dtX?KS;!9>#IQn8_kM!ZTf?&ADCKz8Hk{E<6<%K3OSB(Nx;f(sZSui9Yp3dd1#dxew+P#r6I!SZR&Nou)IGv#NB`{<>@MzI9^0YwMcol zC775A)R?-aetxX|2a@QGPung>DyZHz?a;c7YQPD1-t?CoDwu^%K|2_E{ty?+m0A*7 zqbC>&dBsXVrqGgrd;o$wBQKIvR>M*dVicjmjP1c8dzgeX9 z%*gXnHrCbCq$)2wn^y!f;}j6x;|G{2&Nr(c{`k%p(cXZ{wkQ?nbng|}6c_?d=(>y| zi`0A9Gl~28QSf8&N${=I`^=WCagI$FZfh#(mwq0uDXrNot-pp$er=F_J|z|NDQM`N z@5iT3E>rP~=!n60(@m9YKZ5IqUy((Elbv7R3u;Cteq_|wmg!F}HzR(gNNu6GjYjsn zPm}{@ceBrcFgjAAfgjQC`D@1|O#|!gAj@toDWd9Qe!@|*?!B>Z+)>~$RorZbahFv2 zQlD?`1qXLUEwC2(6S4bOV1lRadD4(RKtg$I)S+1D5p>TJqZF1F2#c;oL9dMiDYKG z$$~BZRqy7Zam4CKzjUlc>he4CU(4yn)h*(4T>nDM`KFEm<88oB>_xr%m?-w~d@?%G zvs>ep^w-(DkUmO@%uKf)0MAi0H7>q`z;DmD3&CAQY&pYb0g#b5EyC7%vM1(~j^u4! zkoxg@u8re&1rmN(zBz+7ZTLtKWuS2O`r|Us9nt3{Io!c@2|^sMnFt}M=O?%zPpHX2 z<(iTzAn8LI4Q|jVmj^~e6_+~w?Fja3%-k6S`ftU8P_Y=;%ad5Jb5uRkwzmn({Jbf`xa zRSc$g-U-hR=Lp-DO#FiHYexZiUZ{TSr{x`8LPF|&mF>}-GnNeoB_Hs{L28%n+k-UiMhH;wy(cOOQ#Bz`6~rv zT(#VIVSJ;<_Vd+{*RVZwUM#Ko%+h77lKi1xi<0#KL`mDmtnO_Viw>vPom16$X_r$m zdBQ-^EE11CXfUBmv8=TUuaCD4n}f)!c0E8qwBEkrzdbBt5OzngJ>8%}$skNn&1_f4 zEG7lXuhiJ^Q#4fNx-3^3DdVp=_TQ(NGonk*0}1oJFmXE{mA6R$8f_%loD^QG1%w&q zP=?XS54T6|7w$g+ohQ=cc_e-RB3D9Y*(yMCA_q>C9I8V#SJAFjSQs_2Z1E}d z&qRe&)kGeor^6;V>)wb@v2yShPeE6Y*F&C$J|(-_5&Ez@y==`sic+Vyg;vjd-p;Qg{`_`)a%y>lRcRJ7rB;0^0)2)VaZxbMN99r}d#7Z&c^@{rUhVCEGJW@t z?;SZdr4hFe5?sjgjDzoo8iRl0@8wTxwxZ;m2e{MVzbJW^L$zT|Q_l63p+o+c#(C9w z-aOe!==foNl5ZC&$$1>ExOqMREE=59s+_o;Qw8;$V=eun-njW+yRKo@nh?M@Cpx$& zPjY;!bkD_K=y#tr!l(V-Rf$1JcL!H^jqITf6#u+oWQ+%^1Ys(N8^Z`cUi@^XpbzUG zvw~u;5#~J)MvRz+@YKp`Uw(!6|Te4H2lP{69(IzvN-NoTbuW$boLjP~ze&*FO?Znopnfyik7- zDv765Mj0exHJ%oTl+LUu*+!1jPkuWvNsEEkja=n@N( z&-Xo@Ct@*RIhF5lTmT|JW1XQzmvV(_;(~FtCgkl&SH}Q&QsWJ4!a;#4Rp#ibh#x|) z&aUJCI1?mS8av3dgDHCzNxleOo9ZRMBTW|b7~b+v=b`emJH{NX03XTX!~i1VpUA|O z^<4%CtflxAo<9bguhRQA0+BI#8@-pc?^vvS1eOgUOT3&nm(zswIK%ow>&Qs4+_&4_ zC@QXn?+(VEW5PG8g_E6CZTUZN`n1%MesMX)OY*n%YQ{a~U<$LN4_lR9KtgtO`zlSp zCBlKX-&-Kyb09RO%*buAue)DBhp?lUFUUV4xU&i%TD(C*8t_;l#fr#x*6P| zQ~~fwxiS-l3-`flPh8o%!i?hUie(Q%T5;JzLHYN0Jh&63^o4Hi^qH$xj7`tic~=12zYX=G#Se#+w4I~5LpppOb7k$nQq4NHmZ zr7PaIm1p%k;9U&8|16 z?BMmD$hN*|>C>j8MuZjS#2=Nteupf(P^`};$&kpNz#Ng9Uh_WIkSQ#dSSSqd%4Gj% z`a-)z_YV~@=bD9bg#vS{i1p)w{}MiYSuJJcd)yvSrfe*?So7mQ;>bJ+_%|^s5^+mT zuy;x${kTy$-Y<%DCk=pNM$xEzmum(nrEyj1-66|9Qdz(EgyZwg; z+yKf8mM+az-z_x5%1m*Kjb(WQ7Rt*9rm3;!XhEIC%>`4v`zQ-AAcAa%0`f$E6ibHN zrEk+N9Ej8^^AfA%6p7eFgN;$7Gs0=8H@-P21=l`wt6UrVVEu+|LcKrt(0b6f&$_dX z4d})NYL~7#=Vf;i-Snn6dn~gapS6Z_+N1WgJHt8co7LE`jS#*WoV7fh0pQDeB*Cd?X?a|=-H+wslcgvaR9eMOQ<2h^DJ`LDZ00mFrV;{FVr8NK;Y6jkk zy9cknITL`a~>Q=dLG zXI=DvdjY_IhFLm> z;#G1pSk+hf<@>_P&=X^(e&|Z{(H`$f!}7vYTsP?m*-kCX*P@rwgw=&nw@PagESS`U z8kr0RgzDCE7NyTlPcqM7_}5uAR!Q3@lzV`aG)vs>syBD<6JHOxESPnav!djtEw;oP zxfrnh+uF3ExU_+vfL0$RIO;acZHkzyjXodIB7s$6EH7oBa1wv>D(K! zN7WyN%IO-VNb@@pR)wI^_kY&pU2qfmiONjJcO=AJe7uGO7NwWvt;xAx(?Z_h^Wa3k!hd|R zg)})@O-H{~v0=BX@D;TZLPLP3SnyHqQ&pUO-u?npnQnfcB9XiwMS?`7Sk3c$n zslW+n^ZDm(*!A1khffneNTAU!fqo)7?NOsp{aY*Z@9bOj&0=DMh-bX(>Ld)Tj$A!41#iR^auGt3jVzHXee-bB-jx zWx4Z&VV$`4c zkw)~yU}$J?OIR}+E>yO8>_`p$x9LAi^RnFhNcCo}lP>j1Nh<&KC+7BZUGy02qo5NZ z;-XNbwgEPsqUwZHbp(}OKgLtjt0geKOdo^f%Vbdy5=r+F3VhYv05~a3>3>?^$oz!T z=sDBPFBjRH(a7%)con3-k&?_=&fY1qjy~zSXG$vy>D$Nd$j*IBCq50j-P7hx#oIUd zOw#{oKmkw^^1$7eWdMTJ3nztg#Tyl(@QM73Gps!fl9yJ31Ds!4vVC*Ciqv{qJ?+-x zo4bhr0yXVGy@k^Krqtis_I*Ag?=8X#*(YsB%>-8W$u9WWO= z?9uUGWQa;kKfFAMi2ILy-@h8d=-d_{)L1`sL@{N^l7H<4bDnrek@xu{cY$CYf|F3nJtjx;u$h?|zGx~0b{>zfMoN11u1I_EE}nbGKavmrfZ z*+39FBm$BHbJPU4>{ZqDKiGD0$H-+@CqdlV`L3MLQ6u-6v1xU0_-*{dR#9WK+7k^O z-+x@SzH9@fn~U$ZduIKtM2n~Tp;Lt}S$1s(rzQI39nNFkQBrK5LT%9xYId)2%XX9L zuWl>xMurE5Ce?XpBL|bROECq5O15c#77W`42rlyOcgZ;T%jJ)|!)?;E@hwKR^g)wg3dr}!OA!ceF^duAHQ=w;N_2hmLGh7LkxZu#xQb`T zD@dd+o~xOFcH!lpTa6J43@Mvo-4xl5&VlkHuhwjdA-EIWp-@!8!Y?4eakiK2OIu= zYvRo!rKhe>mDcj*(RQk;2ETrhnf2V5jDzpzqM-^NMO7(A79EKUna|9$gN}RO-IX-h zp-6Gd`lz@(1;CXGbk)?gs6L;9x?U@>!}74)T>2CP@j4SD5{X2Q2Q%d@EE9LYfM^?u^z4!1BsQJm&t^ECw zZ>*lwF2eWQcrZ?YHK@w#%+BX>)_ZyBWonLqN!9l^_s!&XbZQp`H<#3*INjatWSflV z_i5)y!}L!I3mXOnns=?omDbK_a_c~zbpQ2x&vuD_Xvnb>v7U-h`YSfvhvr}lxi4u# z(ecs6&*vxCpL=hIX=4Z!a|>}kzj-3Z_ItcNo19OgRleD1r%?7FOlyCxWd=T*3){_A zR<3pP&;tvSxLuZLB((D*6l8%&^cQFfJvY*&>*WOKAc@ac@Z{BdO`&W7K>SF1Nq}ha zPgC}HpSHmNzSzEQ6)XqQ3Z^S%W~hmJYSCnC+H?BHsOiCqu`6drKi=t=JJs*s;Z&%&c6IPyBgQa%H^8o_{p)W zV?B1S$j396WBB`#uzvSQZKD^S1~>01`c3qh8ImQzv~_Eln|9u!doRp%k){F2-fnQw zb8H@a1yEK_$nkt1epl)oS~F%W8t(uwbFlw{uwW_TAISa5esB?qDQ3l!vn=)qwp{m0 z|7E{Bx2elFAJ!Q2;yX`1NdomLF~<77&Fj5}E6MB$_gvy&y;hN%b*4hrP2D!jED;TJ zbs3UQ&BkMH;&yT|w926d#E|6mMB~r%6!JpuB4jakC#Co64rGGX#n@$4t14Y>x1zCS z&#Gaom-&mby*6EBZmc;k-E9Wl#kNF>hJo#Bx@@B@c*6ec^!zd0tQ1xH3cYN>dL%hO za{X}Xt&lVhU_m{Rk#(@M-Lw|Qi$XL%U!H=iY#r#IMZxRj{}K5#|BOtdhj8`&O~$dp ztHP~M;l2vWT_SS90{ok9bh;x2pU#nczs7|m&UhzT)Y7>3oNM#(c^nNG3X z_q~JAfQHr1&F*Lh#0c%!hEHOxzb^~cWUZMUAT<-e*_+PP(GT&5Q`R3qXO2Jt7S$fT z=gmJfJ_@PBLR7C*_ zJVO4{&}TT!M)MlXFjNDjyMt2x}K>&lTwVBHQ<2(!W zIUf#nGzQb>?~a&KR-9ie^nS;IJqvXC!>0`zv%Y;Uvo3O=1*>Dfzj`Y!_2!=1h(l~# z&Wz7ejA}$$QT_B+r7p2wJ^O9&1)!3Tn~hR;rg=}b;$d;7M3?wfOlekKVezBgSm)NH zLUs<9cG=>#u9>>uaO&*eQck2-j65&nbo!t4>@BNY&tmRg-}lfWI$>*LaM_~g59%`b z&8>cg2=rar!k;B{ba|eaA22w7d#te3)m95@H_z+&X;=v-9a|~8i=P;;nxH6q(OG3) zs@R7TDXJ|mDL0e4fjW*wO5md!K!+J~ap4F;ZgqZdDKoaq?}xugoa1GEcx*>gX(so+ zBS#Wvb69JPuBDcw_FnDadvj?E76`PQu-vJ>k|p2fYT8Q8PJi|FOd0YeSC7!`9eKJb zp*t?H9+Rt*6)Fy(=RAS^(aZSfG@EC&S(6Vg)puu^AnHnpxAz}1zV8LwG za83Jqikh`n6$k6ZTQpaEdLMcPJF7>_#RI% zYe-E+vf*37xbo65vV(#hjiA`j8aUgHd#n@>be$^aEKi13dXnp7q(08yqD*wNZr5JQ ztrM`6#_=|c-`iqcdcRO$3j?B(L-D!$yi7S0qf!@Awtse1$jW!fX?Z`Fi9t+rq{@js zhX+<6q%Bu$ptfO~dl%j)IFr0GKmNr$dilXBVJB^#f1$(8O7_M8E5#3Rfv8YOD=hFt zLus~g3hVZ$)}$GH3OXEuxPcf_qTu+;$s~E_&3vZhsH`*DYd`U#Qg>42lXvf~$IeSF zoSMaiKBIZvQ<8ZiKr0%-?ZKJw$~RrPafRC*28jHC{x`dXaw&rI-d!6U~_xHW7`QyG|X5V|Sz1C-a*4lfo zJ=;IEjl*!#C)c2E#W3|~W{+c9k{smumlx1Gx?o$t+wiEWr956m z`qso3(=>lv=B2ux3*2&MPx&N!%lgzK_@G~AKj7*Wo9=iqBJ8N{P)#I1eqsJB@$Oo< zONH8*$$;V2l-0#bXHwC7eYZiDP=&Tx6vx*KM;*1Lq(u~$vwB#kt()ISG@Hz|8 zExQJ$Aaa%L123wOJPF5#i{PSD_6YOd*cM<%u6r4+_lj+i`gNNUP^gz_{GDxEDjsk(o`OJxY^=;-%j@Fs?Fty zaA;kl@!$guHN0M_I{F>`CN`dnPv5lpJ*Xe?!7PCFe{ioUe^}OpX|9_X5+$u4$+8UT z+_|@9Dy<}m`FcQ@t&)UJ$^(_LV!WaV5bD}@CljnjZ3zz#1{(qiYmEs(%2-5QL>-Yb zk>+&ua7o`;I(fb&$3=yg!8-jhw;_I_6lpFBloDJcg)L|OPV74x%aU&+W>(CYP-*9| z!9|_Q1+^5@#Ty)rnpsJlOwpVa2`RnNdo&2D9pMy$+NAZ*C~89QlEP6k1{$%FLX2Q}#w+N<8L zZUk!jdpaQqr0xHLQ< z;dze%>O7bC+JQi74OmI=c%C5Bue)4=!8_<)U$j5?VWz=UOn}XxxuBk3!92^x5--V= zY@(0JPsh=SA@+&4ZjjY^{yoz({U7(WrObr`8XAh?Y%`s8EXlK}!&ZE#LOXn*9V~K< z-w@xZ-XoSmkRzLz?e66)yFBDceVW&9J*#nWo$F}nFjOJNJh-db{1z7iq_GDKw>xWm z%B&T}HlGLE9Y4a_w0Z~F)#vQXM+2(|SM?!TUCd}$_Az4Y-})dGz{c3t#W3=S7yT7^ zb6?hf&M23kkwdm$Ty5(|pXt0Cid+kC6o!vt+R0nUK9EC((%+=uXFD>d)3u4v|CLwNStD z18+--KH(L5#Bof93#cQ`+4C@HnncuBmwSPh+tst)y0%4`UNf;(S5q*J!Zet}-)A#a zDsP3F9CR+sv>har6SUn*_ljK&$+BI+7*5B?_~M-N{DIEoV7WcE+k6iKI3Ukh*Qm;f zuo1M+%csm6aqr08RS`OQvXO6C(7=pDxtzN0%ylU!>dKa}>1IR@Qp>EnGAY&9T`Q2Dv=jAcb;4~_Q|;0vB5~(iJ2>(KT-j&BN5K9XAAlo98eyhoVPKlWS#`m(r1(%8UtVITd!$68J8nm6Agpmm?=2J<+ zVkmU_EG$7w$M>l6!T*@qcG_(+$2I!`t=!uBYa21RI zk>Jx(V#gFUE}8gZ2>#umwPu&-jLit%h$~&_U6*;7k>C7xKyn_#>z(m=dR>Ew7OcTT zXNcGPMgut7=h$Y0#?%d)pSvvOBiUo9G~OC>5t%#YTkqXDVB*wA5)AS`hzA+5?f^N_ z^j6>=CmhS+LMhB|rMk6_cz|H^Hg%5^NxaKjVJ84*7K)y)ul^4C^(5^{f-q~W>>@(H~HFS|W zS1yv6uvbpwoUhzlbwMCBimvmHbz}F%Sdm=Ov;e;YOrLMTod<1Bv2zC_Dytn>+l~a0 zt$B?zK?l{p%n&5$0F~+W2vMKJH~O(BB4U)_-+M#xNmZ?42QcrTA?H=#fDpA&)CF*_ zp(1df@RelV@UKLI{HNWUwG#%e5PB>ORO9hI24DQW<@J#wNcR!+t=D0=GbAa9 zZD@WqtfExU2SEJV0y6j~&4QEf2v?f}Wj&pM6Lad3E?}s>ZkD4KiL;K>+B*2{`F+Da6xA?b!^^ zF8<$bHwk)8oFq{0QCh2;{9Uj77J?0;Z|wr6PH5J`UYNjTYdD@bIk4MJE<=soHbhpf zQ9cN`H2%SL{S4ddO+hF4m&_MHwV9-{25^cyaE~x{iN@pTNY1yK4W^XrO+cwV9}zxe z6n4(Jrt;2GBv?B_dixi&(|A_=DrRHc>ple`V2Z9u;V4~i;xVYTf4m=Wbvq+1=kJ$W zB!j}xqb$Zo%yGfyYq9=Y7EI-2Vo~c}DJY?iwNqB9OWW5?6-;>Lr7CY!-|^Hp8$q5e z$M(V^51}fn)7Ca)LE*% z+LWiETRRYGf-H79ynexW0MnoR{~_NZDxf0p2IZbI_cq(?!RgX zH<16lc{V5u-5xl3@fvVhD*9&h4IkFkK3@?6hesjBIgjm7vJ{qgbO=cz+JVb}XR2LS zdTdoAn=bk1+_iU4Qs1YD#TvY5!n!{A{3S>AAG{3#xe?R8;uDH3aHrVreEcr+klgh< z*>eurkULGQJ0_p>0tiPL zh@h$G?g&0bCZnwYbT>Def4YFijR#`&`QFj2;VSz+1wp0(yRMt{G*I|D2Mh!1X%4va zV&}J)AlIk93AVX%a=qm<-|TI>JzY~}VxsW3X_i0#(Z`06tzu$F`BQjx;?r4zb1I?- zdLMtH&V-*J6|y`XFnFDVHc*+=+JfP!O3-WICWZc>E_?E+Zcb2D{nV4IJ)xNGq3H{puTONJY;9EyOkgb4FN}({s~_r?mrPSu&1FK>CUDqU|`nw z%-C&FY_Pe<5qI=ctIqF83s@TqGGN@1YX{|!U{v92{%K$T*$Donxnwkwga9t`BcreZ z4Gwk0v@u;bSV=$LA1<|KRf@AJAC!d#R1*PK?;&$C$?yMZ!vrMJ?Lgh56e2bQULal? z6Jl~+@Q38C^d=5=KlRF54Qsbbb$HJ|ZIjdRvBIMA9ZFW0rJPVI#&@=gXJbWQ)U`^0 zH2sdIi1+D)nndquSa#$(_RicDK=OfRLpA7R?$U83~tLu7DEI$qe6S@cM_Zk<7hC({ha+XyW)U!8NKuF2GoL z%j_I0!86be%aXy9x+;6;GrVAoeBigHWIjNG>H`tpzL zi&FuKcDC8<(@WmKtIIF0n1~Zi%*MQ{{D1k*-ww0}lO&`p{W~5rymrIC;ctEo0M{L9 z9D~VymjA<#CASe#vg{Z5qBP#3~crE=S>B9l0%r$^p?n$W*03O7Wvi!eRYe{@S3IZ;reP)0{4c_XP`tPl* zQxCwk$+E^m9!FfCqVV$nz6E+ipoNeU)Bk4_|Ia8G|1^rckLc3n#!VTc=f>lkU$Nng zqdkq#22{U_c*xuY_E#Bq8>C~f^Kaz+{X3i*K|MU34W3j&8s-W&KyK(k(24inwOgR7 zQM9v4IUHHLcXXS$WUf80L2KI>4olW(hs3i$-y^3olsz9`wC2LWrHZN9(%}7k^`)Ef z7XG~<@dW@{=IyFnq}C!Z#}E0Z1#|nU-hv$(byMp0!M5|+s@ewino5{NF#@e_@C@vZ zmf3O9JH5HY@v?f6(iTXa?e<)olItHe&0%^=;(=68nQ$DG+7g$y3? z{uvcVp#e7t4KppI=?Nt)=~xJ}15i5EZ`fxs%yynXFbV8XZ5syWm?c2NKuYIP^Pk5z9-1-Rf;!ov@`V!JKY z#!f%-jk9|7ZSc%3iYmBnajFJ=6pT#+b5AwF{XMgN77u`anoXYvz;VltW%~wsnTnkg)VBDrc|1_G8g@rx$3w7O zERiCnN*g|XV8u98fB21*Jv{hE%-lyAbV4{p$06acJ^Og8+i)ZcC9B0*%$xj;@`vA* z4WDHwDRMGHS#66S{POoU+AYy}!J@8}kBrG~^bY}`Jyf_`6$&ENK#iG2pUv>xYl%%p zZXDgvn>?n9oz>`aCoI0~o+02JZqYY{&uI`82U3Xf+)r=3F)1Y1FUd(5bI=RF8{%kM z@7UkniKB)IJ1v~E>W18S57~o?jc`--_4x$?H=Ro^Gm{H-#Nc%0K|0jU%}F?}9E5-# zwI%8**}H55_jd$jdhJaAF}LnsbwiQlNI`-3&wzrJHKmaga&}?^3)>aEfmNkolrrVQ z--U;v@}fOurA^7M>`cCx@u*P(xsO~67tjp!$>&B$zl$v?9x+EaHZ6XVz52#LqX614 zm{j)oHnu1lC1JBc?4hThib2KUPCufv(THWCdPVqKPFFqaS})l^2Nj?~+V=|9tg+u=@sujjEHpc(w}o zhjFEbY2a)(BXAN=YPV9~U~hsiCe&^1V(oU26=U-&{Q9BV1v2qq-uga^ni~X)}=ZgxF?``tLwTpkek6 zktH#JtKZN+(5~oq5yp1I&o>hV@$m9OVd306{Pt;})#Ap=K$022+wm)1QK>>4jlZZ} zo3h_z20ktL$?si#f#{}hHg>F^=f0_qs!s@TH@a!wNVOBsvH&wNq@oC3HS zybq@XsS2JRWGIh!tUZL&rJzo30JZf8|W2 z)gy}=#BjLLRO!mS4R_xXiMztUh=SHPgfV*e(Q#Ge=(OqlP!Wb02Vo#ZK{4~uZ7INY z=hp~tJ%*cIo96cRf&1ibKL;}5jZHHCnxlJft60pV0B1=9d!Aph`{pC#7;{GpRqEf+ zCwk11)|KgMa9FRQ)Y{os`@65oa=h6ehi5Ot+er!oXTjk&Fk7J;9I#?Aa;hP27pEzk z1WZr6q`0hl6iIGNt(`J0SM!$|SMjq=9y8fq5zVNk7u+QJoqA^d>2f43{M9gOb*R6<@%#;!NCDdjr%f+Vyt{GBocoXyuCIgw*hrDh5zL6S5{ zpy@&lQXl?)x9+Jmp%OU35BUW(4&F~~`!aANYX+<#PU{OMHeXhIbWh|BemvA?0#cc8 zzsA7z`~{*h(njkG2i!)?S||7^!M~>g>?ucjQ;&Az7x%BD;w3_jiJ!npYr6I4zmHWi zsNuc_1lc}#$jy4jMe%ocYUYUX-JeQGfYA8a4KWA<1~^eD)Zs!JLPgUW507A-I+;6| zlfZg|yNq+~@9jwji6d`_$8Nb*p5(#LbEc#M0L7HHoxpu^L(4U-X@+nw%tS}@Fl`6! z5)P@^5QU%SVElp$QCDZTjU>1?As~Yz04It5codjkOSwi8IEl35BL5Ph&nuQeMR*zB z$GvV3De}jI8|~4n{EEpn{!>hD_Ue!RiG4{}{QxgqJhW>OzLax*3)h1ei1_pXJ(kuh zxb9>edl;OGaLNWXa+m>&&PzRR@U*%e4GEAS#V1-pMK}pb2BG6$n-t6U>%_rBVi|ai z%$A%ZuE3JUaaj>!g8Q8r5~2sd+|2OOKEU-Lvpodx!x?V~pIvwI!wtKj|a9QAJ)|1rB1#`uQ@${2a8!6&Xrf+Xiw7k*QAfR3L3*ro@7ur9!c*#-cPIX zF_YzwFhzIs{f~+h30nM*W|c42{kP7!(8N58`$*yKQ=a_~Y2P=^9e_7OAVmPo9;$Fv z%#GS~W@>0ry12rKL(njgNU4klk{5A)WRZ^ zZ$Lb-i66*o1nwLwcO}UqXb(8tv<8P2+Yo zg@-hNa@-E;M9B&#e2HDV^} zEOC7%Y1SUmEK`K>qfy!oE8LXrAF$YH>U{xEp*yvI$yUd??1tP@9t_prJ5rGzQZ8=+ z)Z25)r|g1tifOybvg^3fYtwn_0@lD+mfCbY@(luTHrEI+3FLzl*XwKGmtH!8MX`83si^Qp});BLuk@ZlkdUjC1Fpzdwig?)kG?B8gq*v`et-|Tb3q&a3OaUBrm)JOgXPQyv*KT5&Wibuj zdNFwA%z!fuCS#eKWk~73VPqL?tdtW#X%zQGso4Vq`ZvqFO>05;uUh@4@~)*^-Gp`U zT53&dL)a01oZSCn4BU12iSRB8?OMnd&Ehv403)Y%P#g+SI5*D19EJ2{j4ke$JT~Z5 z^Ew|(i^o2&!ZyiwvRkZ=KwC)v;Ga<(+L4^ z_lpZYsdAzDU02PpF|UbCIFqqEoM0q_Qjp}yLax>sOlMrUs5~xFMOyVI$nl&r9DX!B z3kV~9X?2d0RXpBd*4VO@-Pr*40|e3kB~i)ZE-&N<#dH6D%`1G<2*LOm{vN z-xf$*@HIVOYe=m9Pv0KA-}SU1UHwL^e z06VBFh3zUyw5{mdp6%|CpNR_J{!5{&i2vXy8y+1(?Gp1v0d8KxYtbP4wv*S0 z7&@4&^EScNhy1B^R|~Y;lRmS4%h4ljZ3ZT3A`9+aPNSu5tt_R+hGHege@zq$z~#Mv znt?|?-cZLrx}Z4ZEL2S_VZ?3^)QqWnXkv%3m0o_f+E`JfU&ij6>b*V{_~>Y2hw}pi zO4fuFYzm<%uTFgTN9*@p)0!eeak}Tz=P+WgyyEgUHs~r2tZ5aQH+aZ@e_C7d2QYeO z${H9xnO@ST`>v~x2F@Kt#w-ikK*Doz()XfHE-s74wCCNe zo`^zu9oJg+{JR(i1Z=GXmJg2N%1uTFGvy={w%hE4&yd?-hW%J|FnUVwp4BF7SY|YF z?lP#>%V+pgtZF2`(d5Sk5PQ>o|Fzx)WnvS5|E>VPzbJa9$u)#*ri*ml2#Yw0k>&4( z%v*QIth<#%;4lwvZq1WQEc*XHp2D=%hKf6aZm_|Tw1%Qzg4C~4grw8}nLD-(G*SDO&w zc}5#tANoo+i==~EuJ~N~q02#H<9P8&45S5bNW`)HN0;KF1Bk>?PxYq`nL{i?X|)O3Gc1XGwI@9pLEy1SFzi- zu}gTLAjB#Lo~1F=22ZR&icQ>hE{UmO2IpVXz4Tig1pWk%AhPQKwZvtdBH;!bpdchs z{EO}>9Vk%3J~7Rqi{TV?@Zc8}9f&?f0dD+pQ@^@I-goT*0stn8)-_tmW9uRlhf15z?Ec4)apJa%oTCX4)avQrp@Hwg zGWHY;G%(Op@+sjePzejmkodF2^N!I`?UU1-o_)y1bG^+&*B;`ls@-Q#S~^#M%N~6O zf?~uIqdU@F(*_OCJbX4+ukQPwy@f@nZFjj&9@j3+repgoGtBH>SngoFtBam`xTmZ? z=sWoMb*f(P_O24Bs84de5Nl_nF}WgA%{B^(YwT z)#JUdEOE*~83?s$8y5}O;K)d*e=OiMv2c=lv`}{?tl58#V<14mG3ByZeMTR7U~<=d z&0+yIXgjvSr`>q*7i0L}Y+zcS@I8?#SSs0nRweIYI^ zFW9iq&XY3>gj%&7gCc|$3`nXhsMV1%Sm#~$jv5m*v87>`?}4L$ZLrZEz8bmBms2N( zj_;{HejZs4e9em-3EdS7=sDQlU!_hym?q{Se!h8_ zk!Iq&N0o5DemzEHRG|FQyYVd1i%`P)a>iHhL%8E{<`?8WV*_IM$gc52RbrU9r2o2l zV(zl|-q+*KE+4-^Wo%{C?W^$37Gg>tfQAZ!yp< zh4`Jyj4m5qe2wORM3Tcn1h*#dT~JY(P5{VqUnwvCzccwmr0I@Oyc+_*~!4Vt$q$|MF+Y^o!U zmE7(cG@K6Dj$cOy6k=hnu5vkgip%OM0}v68lKRX=+&Yb+Jz08W7bL??^ZZDlJZU7F zm_yuh@Ca;?@qOpYQ~*jVwwZ2f)3$T+v)9Sj+~>R6jLLc_xkrO}o&J44RWy<5meLj9 zOVhNtdY8=ETHn3Ab<_Ftj_MVw$Qh@((@2p~rczU(^Z8gOd#~m0CB1}AeR1gidT#g* z-%6O-plUwn*`NAC^6HxK-A-0iD1syUjGXyMWRxMT;Nyv-7VbR!=R3Sw(u3C&KEX*_ zGtW?WttTjKa`@hn@Rlp?d8$5Cv}NPS&9@Aly|3kJ3N;T_btp3pov&KDa<|;fH%Xk^ zpYasPP*K7?|CGwEmRMcHy;8a!1oJaVy}T4c-FdGjbn@odYX2qmrI+v_c_Q(rrQ>;4 zk4N=p0X|n!fwM&!ZB9Nzoskh5u0SczLHxiUgy9VAL<&ut^MvaYy@C26g*k@6y$=W* zu`L_wITK598lAo3r@7hF7a+Te+7I|vDW|# zC~UuK01|T(AM+g5{;5Ll1Z*lu`(-MUN-O}G+AlL!DmDdCvlh-TgGVtlF1s934pg_d z1^h-5CB0{Uq&b2n(uOB0A`JuzS|Lx>Rl~QBUwOhp_NgH$qxtrM&5DF8PM7`4)6o47 zprU~^CzI3GLIF*ltu|9{W1nMESm$V2^d2A0mJQ5hEHFP_4fd=#?cm{o#MIB5+!uOuhr9oZPl8f@0kHQ8MfyzuCLrLT%}P;)R99bE zg>(%8yGcPm9`~1|O!F)wZj$iC^N7#_`TP`U$MVr@O7Xk2HYuB zG7p0s}a90amXRzDiV&0)5RQ46pdf-2}F#g`Oz6EJtXk7Xe}XJ)A7a*}}WT zLig9SN`|Xm0hzsZPu?{azFc(kKiZ@>XkK|$xMPEgfP3rTpKo*srOeTIhx# zZ6iieP=FSq%c6|gC6V)tCWTe&8AlI&ZtXl4kSnm>3t zVE>i0><(LrkC1^N`!c892o&}EQH{{MbI$&XVx3i1Y2Q|$<}MX-?)ieR+9*D)Yh$kk z-_c8t3)|^~ZTa1m&P3ty{JQgMy)sZlv#NUFQKXgt>sGqZ%TruV^2jo~=%i$aFSa`( z6*B%lO-`Mnqxw6UXRxhhWzOIG&w@KN9b4UTm+Qg*5WA%KeKR+jYNo7@IcQmw#sv-= z7s<63UfPMS-!t?D%H3E(!2K=3Rq~r$%UBOR9?X}742hfUd~dWuex}8igy`r01tkO3 zI5s9HQWLV)5#97<_`Qk)=Z5MtjYYA}u!LTXN5_>ql}WL@wfW)XbFWq3(lW^zMdo>+ z4raDw4uQu z*i=yul&uR%x_tlYl@l7rL#++IXC9-{ zzFLT%?!%LAYG@qVA-(^qt*VkVZ}JMO88X7?HK#`a?iRU#X)v0b1AeieJ_6_1S!rG&*=#QvqHxT3??ja z6|EPL(&j|djk=6VHjJ-}H`EwiZl6UGnqQXA1Nr=)(o+40jHi z$ER_x3A{!0BJBNEJWn)(RvLOv&y*~_9V>TGtE(s`6qT{Ff6sJfdS+aVm~hOYM2EE5 zwBOxf-Ny29-t+S9UKRd|p~FF8DDHXJ1SmHz>r;=&h7mEKSPmnve7MuV{QS{+#p$^kbE!@LFcCfaD4n0#hk(-b@FL$(dnb;P*;k=~krERsr z`SRnH$QP?M+>gV_31_dd_V?8V@&~Y(wP^& z+=L&RKL5%3*i_U{&$C0U{Q#4lS&g!Y1?&#nofI*pxko`?uLAuAU%Z6+=l1%YHn!|3 zo=NiG`AdH!+l7&;PwtmiDMexYC8mGL>kSA^63t<+R`s^dwF{355M9coY4NiZ8+68s2R5+m=hJnj1~fnZ zX6qdN+CbI6E4n`}9k)>%+H*7p1eM1o+JU~eAX$Y zg-G7k&=ygZxx9%1%{IXvK80IVwJz=(4Hg+%dFEMO#RA|}M#OsVhuD~4v@8(*aHTk| zW|id(T?kpQjx<)oT-x9<2s^tHK`x<8#=7io_NDSouS9q4l>!K*)wkG?a-{Du* zj97OB#`O=inbRD7dmK1~xVW&FrR3IU1nVRVNO>=9b3#28`_seVS>Tqi9O$xENL!EM zSTIa_O+O@XB*&KT$zn}It>vcXIY{u49VXAE<0Iw}Fxnh`hHWA17$;eS>!M3mte_2a z_yx8SkHX9j?>cI38T;kozOqi1C0C*CXx!nF$OS_v%Ejmg#8jh^ivj%9hH_Is+ezMC zKV?e6@#@^DB^ccEwF`OR@(3iDHW1!1b=vL)D^z|!bGgi(EG|wu8JFRpscmbGcOfEC zst=E`HtLdg5?U98Ph@}hZ@->{F6GDujV7J9kQ}^`al@pJ9WS~mOe&@koH`cUH2vP>p*tocd)cv^E(3b zD<8f3N!SS+B=RZr$n&Z7W_Cv7zA!zFCUtrcc;%X?lK33|cx%iiqCOzpNY;|s#FUT* z4Cd{6W+8Q&BosK(DYH7(uQUbdk&v%%eSB;p`v$MV=Df?&+jp%=kDU#c<#m-d(Otbc ziGEgcPE1=dvRcJKD$4Z@eGPJ!Q}2gRO_icYZ(hj2xvVt|4o(h}u`jt}NA*2g zcaGPdGcW7Q9?%tI46`X*>XIvj2kal_(&MC)VPpyMXg};;>cREX@Z3!~Vp7B8ydwqeHzTflM)8Db@1XTZ)mu`>*xBu)s#`SE#Z3wDrY zrA@>b&^F0T`>=TXH6(x*{DD8FqS@S4zOw`pIR8+&jxxS+4=ReC%KGL#bCCoHdrNk( zx*)51&wLMk0haS!mC%R3SY8{&Lz7!_-+ULuPnB&dK%JKgS$e&I6$pE#kM?20x90mr z3!U_(-iXtN*1oUeIB9`Of3)ZCYIuldv#pRKz~U2hliQ-bcwvj!!>&F?Gx}BUrAMjD z7H}dE07af&}F3m`k1S&OGOhVr=D^!`Si3TV)sLx=THPmct{vnD=m*}H?URVimfpH~^w z0fWLM?P`?Fd_9-)m<@(r?0i@^gc~`1%F+6OnTA!Y>^+Lir;ar9ylW%Sx3>m zp|?(^;12#aP)T~Yc#avkFSaPqGY;dYFjN~^C z^uhxj&?5t{8WPIiyxku%x+j5)Yltr#jBC(^fS2V#aj*fd$-+(f+U=D3%C-09tQM^j zmxA`rM4lQw-v0X>Vw+QeK+!9X2g{$6aL+d-I&4oCe7S{5nMm`Lz~6?Uavx}AcnH3y z#ACeg`tj;vmBMi*n6HOP#`Vkkd#65zc~;))S+uOcz)hi+0%Z#1#@(L_-JIFgi)j=> zzF(W5-%M*rdo=S+&s`hL^%c>sb{ROxk;Virh92TY4Ew>~wdy>PX;o8^t-2*i=DLrKt9LR08&6f;(+h z3$P|o>!Xiiks{9Mze%HA6V0Y2C|%!QQD%S3-NnXZYI&`0!|Q9DmomXVJ<-}h(D&BT zXWE+7P!$mn$AUcO1f|A;6+Wz!D1b~tM=f+{tC;3R-_=7k%F8mtLy6jhiBpmtRJEm6t1#-I&uljDN~Z z%*RTCFTHB{+yb>hHJV3_;wNRE@V6#~)0Nv;mj`F%;-zRqgGMbfViK2+Nz07WBY1t? zadO3$38Z=jSK1H>Fa0mnXjen3o^SUg zqH$LXEz9p?(M_Cgz{c?35`aa1kzQnAPr1y)=V$o@6HMNlN3T-VzwMugX3mRBh@VyqSIoU zwomESIqN^JO>b~*>axnUy=GOf+(+2TTL$A&=UE*Rpq4^_aZuKS8y9!)nouFz4(i|k zW-Oa$Wx*v9IsMdPSU7UxY1M;9{=h`*JO13G<{siC{&JQ-B2<;)XuVKR&v7yHo-V(d zY;zKmj}Kg+mFs#xvyc88&&?DAk|__j^}lzg9``pPqEUfww8V-=J5S?fspC{rLyws3FflXXx0w)}UfkMqAKTpX?z ztA`H1Vn}6FRbZbd7)}Y)-f*SKm$p$;zfMqili)qx%zl;DVo;c>ed_Uq`k6*y^~iBk zAY?d^#goy4ox~AE;q_5%>B6a6d2C^X`G=3%adqqKu>o9T#_=Z;AX}+&ciRt9$Egn$ z`qtC8%>mvl^pz`L_>v=+}5*8af0C9jtw1 zX})OB>!L_1o^gp)Q5$H%A`uN@U;s#AO3PvIqR+5D2_6wWE{cXS{2z~J!{((8f=U~p5;vExd9)-Uc5BT7r_geEm zs1H6uIDvF5T4Z*dc^!8Ps$FEZDtZ=BH?8joSMS*iTmw{oKvwe#P56lq8Q2wux7r{> znluyxJ>2M74CpjR+esyknq}J;J`V^_dM1bLgv`ZVj%=sGJRM}0eQVwn69gP^V`Y5Q z0@T1pw@TCn!*J@ZwpQV%B&U_4gJf-*YM-ijR30xG?c_%U^rEA0!`y8Pcpb!DgXH_p zWeVLsIrE%?Taca|=6Or6J)?d3omuz$hO#E4ptnh4Bf8up7xYRR+RBXKp@y_%P}+SR zZaae?4ph4E+QeX_;~O%5K{JG?XhB_C8sPXR?wjq=CPUj`M!rl}~&1eD-uq$V$CCJgSXqN|od7ak=z6 z*#1%p4w%e}?+JB`zYzb4!&KMPNL7`%%E!66o8dx%QWPcr`V8KF z_4MOX*%cF`!=?ujp}wo)jyZ=8GTbgK3DnG;$%bJo;$cO+937Vo>@uv#Pj>l`qsICWA@wyOtF!MalAj_%V*^Ye=)?Eij($Mj=;(u;6Q3Vn;?>Lt6f9DiI*BG(QDs3aqSg&i@#%1L<$*YAX{urtMiH%#| z^i_1}C2zoZ8d_Epe~C0tm{?&ZH~2O)aTTL|hHwZ#JN0}>4iyelfve%%OH5z4k`5a$ zc4+3F{iqSXo#49fl4TgL@r0||et2K;`_i%Zm+-H!)C2AWc1_vFYO4iOAO9xqrM z6GWv(m?S9;qY|3Z_mT0IWCu;#e;jv{&A8{SZd4qeWowvx&L zDB8gIcwsPrfe1gfGFv=@K-^!jfj}dG?1OlG;C-U=stS`@0pd&Lz#VZq{bTVlM8C82 z0I_Uxk0Q{1Q|HKb*BVrg{CI~)FZtI(N+Mo#>h7X%e~kx_*l|T59sYo-YDyz#CjbdJ zy8Z7(5@5B26LgKuXFNF!zeNTA4k<|(GPgW+D7lTl_u|Mn$@$r4?zUq?-YT?vz&P?i#uqq#N!Y_52S<@8|pJe!=}? zoc->--u13{*0UBn{$(YXU}ueS_ZjC1fs-Y{D$@}o@6XMv$su|J8xt?PDhCWRs+oba z*dXvkC{ij~-Up9~>_t8{dMbT!eZJYCFH@PC<(zU$!hpKP2o6%#%0P~Jj41cTq5&Qs zxsgJYZRs<3&K@(fKa9ACvj#PA5f+(%d2GjNvu~7&4VoUDcIrgbM|^M7vMLT0BwTAX(=eP|>c6hCNk5o}i}6?AlEj<{$dRUQXi!$%I{{$A=R zz{k@~Z;7#Y7~FgKyj6`8E6U@1)KU@+wCZ1{CE+&+ez&^3u+m@W_2y~S^h$hhMe4Ui zd~pjJR3b@qXr;89w`(oSz45gA%kV2+SKS=}eeA}aAFRpr8JN-b4G-})tj1cz7;bTT|{qjK7njpn=^ zlbI#6h19`St8mtxToX~v?Jdz;4!OOxL8HS-#3Pqxbe%m^_0j_Je)ebF8+~-KHjmNZ58dqkcDuiY!l<6p%!!~cS#uyYga+V+o{{&C*8;C0ml>Y zVwv6bhiuXahsI5(Na3;r$ezxNVx@e@x`W8-C8wj*=aY>a*`CnpW(5p zPuR`f`E|WVcRL;#@|aU%2tY{K#C$kf>CwTxD5#-6Y}hnBxyF5HAi-3zHIv2Zd9bZ+ z;MDn|J*nM3-jeY*vpTHcT8%O50Z>4&lp?Hz&Xq0Y?xBf>)S98BbfOaJ!MkD!9%b{W z4u^wznPTQMe19PY!`R$FStvEJWxi3XnSxiRZH7#5&atL@{lokC?h-kPk1WQCv9>jVOSHm!t~ElWAh zJ#kE|5P1M~V@?R+Uq?oe^v^~u{j*U97@)w$;)@9h)fRM5M|bW|d`Q(aQ$8N0aTNr0 zSwp3Cc4ioodXLs}?4%^z#JgL1p>OVnSpXa6D@QEbjO;?=dLqw$O%xibf_#*zveS@a z_o_kQQh}#i;Kh7AS44|IL zV0Y>5+nC8$S=Yb@ig5iqR{UbGpEOH@Kg>T~ZJY`2-AkgU{T?9 z+mQ>Ja_w^lg5yUj)Ed(DktibCX;(@NfiDXtKi#=uOy29jp^wL;WxJ!szcbva6I}*l z<5AI$k5?Bnq-O`m43bmIuR30$7guVCHchup6c6c$TrM@HjXy=U7LUO(TU#S zlHIu~6VC4RzM%Fh(1B1eBp%d$de1fQ(D`tG&C<1Gz%ZxC9!7_yKGeFpq)U7)Nmcmf z(q%%eF)5w#aqg2kkCGEzdW;!V+pZrj&9RYOji0%3NJbhIE~35*6qo~fTyW}ZjK%-P z*K8DU135SF9P7qA{W3E`0+cCjl({IemWF(zli@s#nDF6LJsC+dO57zslXVj zcq-oAO1@|_R1^D3QE14oN=r{)Cjkf{-IO}t<=&@AyG_N20mHn$EJ>5%7Tv|QBy@yN z$Z0qiKM3ZD*qhY+ku84JnxR@3!k!zbjUXHukzk7Teb)5$U50G%$}UO}QMG!!fFnDBwh= z{ZHsZ1%xgfUVSZk*$fx>S|=tKb^uf@oQ%@dMz3!FjUaR0TI64}(nGcQB*eNXGU19#-Hx6eIWx=sUk4a|Hrpo{op#O4g{a&3&~ zgG#T4O#`FOX_+Sg9U)G%@3KPnl z1#<~af)KyGy7{ytq`+pHB&xhtzKMhXF2{&`WdyB)F`bnbfIs49(_^A+-1w~w1B@TM zk!263cCPrwkGTNO%6vI))NA_|0c(TlY=_i^H5XG5Fbz}(-z#_HOV|Xq$hBYkl zu1?NMhuGNEtEeu9u<__Pq%c1#MREiaxXqA&aK-X;cP%|=*B5|4nJncYf_yb4Rtkn` z%PQn?$bP&q?S1YH(c!N{90G#x&+m>}rry~*W}72Jgfb-9%}>nbshoN8L^IHxFr5J0 zuWb9Ph6Gyo4l4&U7$be3H5!##atR!<6#BXOkfX$jBzP5CjuzK?>7a~is#i&di@ngM zv4N71_7Qy)>Or6pNUpRmh(mIM)A8=uHM~k;HsYcD|2Qzf#aqNXnpQ7gAX;3M!@f5Z zdndQZjTYIMoGo<=bbKrcVZDeSE;}3pLxV~Qs{-h`e>zm{mkp7qE;$VI&Sh;Wr5}Q| zzd$UbIxZ&qsqXS9YRpk(2cgEu>Q%j%N{`sDM&nt#x*PXpR&UAa6E@df1qth{suC{5 zseFknU5Yn`R|#B;uJbk{4r7gs8xLIF>g_ZT zQ+Sa{%c@#@Jx;&opK&4y*j*0iywxN_!M2Ssd$F){0hD?Dz(c0^oK}x7ORw{)9~#_L zgvW3o+w=?DBZR**5V?nAV8m{G4SF9A1E6O2+@3~ki~PG?ydZgFiR=mussJzF`y;Wl zzWTOL5xINpjdD2J@q@iT1oAh4Vu>GsfX5{_$)%s`T*(U7`PJ+>`lPW~H%+S-ld3ak zd7*XTkmJbV!^)N>OukiL`gA)V0>%8nuDLVx=xs_0sj$QaFRscsKk+UFs9r*a@{T|O z8~UAfgu+9z>Gvx5$VJ@EyW?h#ew+<-(Tu|1+`+6C0T}_^rYhN;keHn;gPP|7j5ih_3mEYZ9YEy771Ec2iJ7KF8Y~6K)L7k0#u5jg zR_0@VUW?;?Ot5zLQSXY}{rDzT=R++RDD#^mLV_ARv`#rkjs{QG)QhV3>Tt6Fl(Nou z>5;ISWvje`m0S)ch6oVgNz}-Rtsl<0tOU8mX%10mj`m<5*{fr@G4RNqgw_vylNV4n zGu8^$4J|>6-4ooaMuYuuV#tpVSCHh-s1y^1?GO7&H_*KmF$t!(2)0hQ3O>oN0P0`q zy;0^WoCaEq%L|k!I>%{>pxHbQ92H`;2LVj}asuMoErp1?9!d$>0hb!(Zr3~RXRn(b z>@hoT8V5W~fORzV&glutzp=^hV2p$qqbLw9jyw6vGC^We6YR~w@nIx&RUb3Bf0mNe z0r$lV#C(^D9x|`x%(*N{;`*@VQo+I9LR@%dhNp5dnSdrOjmMu)y7W{XyRB?xL$C|$`P zmjck$ID=~A!`Ub#$f<5H{nhS!l%ZTFAQE0L9yY)sa-||G?p7~Xn)<|Y!&?avk^N(& z>lrTb&CX2r2HA5`d1o1W>f_3y>$Q^r^eFN4`PS;T%vxkY5T!zS`|U@Je9}^x++=tA zwdaVR2BOeA_7(!=c*2=e>$}DBlZskg1-RZSy=a-X%4-0MtoT||v?437g#cd8#nwm} z;sDA8^La{9c*vVn4MXj(iQ`7Q!qNn_O2DpyZ^cIyw^vdBJ!DZo314q44-jsomH*fv z{d*A%xj8Q~ChVf$bJhVQ5kqqs#fdyY$NszqhxpopX72>Q)Dl!RE$37yZ9jE1-(03=bR&ZgF|wypbBxuDWlGzM_ZPGU&LdG+LF`lL|icO_?93@9y zQBuTHX>+{cN^#?lJJ805Iz^*BN5udc+6FZr)6HxY+8Gg7w42%bHMet@bClEdwOPt! zR|uz@H13WG>Qr2E0Y^q)URv_z(Z9U`KQCoh0nB%A=-RKy=zS?>5r8XkcHzjZCQ{Da z)}tp6M#+cn)&_wW$zFt&Q>L!Eg?UFH_K`PQN^~x8;JldVB=M@ib(-kzq_#ngv2Wv;Hc{+vCw0NgH1NO{Z+=o8sKArWE8bFhL@Uck#`88^+yo$$(d&G%R*P#* zDDFhSf@;1FADF2ORo5qVrYP$fz-wOK?3dzfjwxP#q#rKuk%v76NUWFM707wafCR4{ z+vd-ak>=h-4!8rnKh#KiUG+0NhFK8(n-Hw)lYLksS1F*iwYONUW_Q#h2PnO=AXyO( zTr%b*de|HD>?J3&x}cI+atQtnA-pHY1U8Yk5D7wfO1R`;F>)}-=dA}zu`$V^zGxqC z2UA?{?BzdcKjvj}m9X_HB0`wT3j1L%6-iBYTHW0AP2q^svYA5is$U=s+LmB#)7d_G zj@pAK! zw6jjY|8RdZo$+D#Z(1$ao!d1?kjLKb8SjlreTb&&Xo9x;yN0luY&ZE`*p=>?24gXZ zxp6p^u6x!s0eNq(?wtUVm-lZYLb~63G2UE7R_>Q$O1z>A-ysIj6xVC)Tetr8_HD;- zHr77B{H=fN%#F|3;ZNaoIQ}qViK;96NnG#~xd6_%HzhVfCxGo*JpE-=sjs zdT&Ub);LbR&|uGEnEf%)v-GmD$_rFTTjk15R}pwzuSA1)T7zyr7|ARmy!_{b21B2w z9eF8pC#^}?#gTKAKqf5VEOfbGJUq?C8uQ;x1E35pBse%A=ERtH_ixvzwnMOxK3gaTrRUz!dd&OJI0vkE3$W8Mr)5 zcCrLY3;7uzZo1&#W|8~%&J(P!-u+XKP5_exI2M#2BL6SP0_nCd28b0)%O7G(>*)}I zYxD&L5%SnS1?A7Xkc0w{4@V+)Uy+7RZhgz9mr)>Y|_;&71?mS##A2#8Lz9A>^Uk?I^ zL&)JCfg&OUljg>1AH93h;V5G!rZ6iLB4o+x@qY?jzqFwXP96mE%;nEwf`9HyTl~+X z{0t!v?@z52`WlAFRfZNPT>M1yY_nhbtgD^a2uG-skHjlVV)mxv{e{?k)&8C9Fgn#c z=yv`y3*bL+_s>_Wl>n#=ELMtNb8Z^HU(ZV5|Gp6!VxS&{l&W#jwVa2ZV!*gZ<<-aX z@IS!OFH&2K)GrBkQ--+zrHY(z#b1^|QfL2L@yXHKSV6`wj7y%wirjX_b14E-9v5=k z5`v74+-u%({3)a&lwW#L(c|(x>(7N|so@eNT&gNU`SW|XKGaH)^ddp_8ErQ50Kj+S zZS&t>@A|FRu?-A=uS_xk3%RHC*L`oJwJ`v8+g7Sic-t2ZCaile>h_=7?Bw^$nXEvf zL!dW7H@NJCP~hsd{PN+K8(`x9Y{vmWsLl5!-%%y;>Z#d5q5D%gZ@ZxXvNtYu5?#oD zE?n^wD2P|l$NBrYjh@{iEeo&JL4+hOg6En4x8m=MuRgzp;lqTgbhCsFf9Cgu@Mnh2 zp+Bemdq>03-=o1Kbg8}iWcSE+pZvK=FJJuD&Bkco?7vn;f$!kf55yRZzt2EBAd4*u zCM=LKl~dTeM}NLj5$SK$nCom*{%h3-cQnt#9NyiNzRBkJ1zpd+xkuvV@EI2gE)Q|O z`+vUDSm>|qoA|NxiuSKn@4}rLFW;SvKdlM?Ik4P81M#*ad&A{HLG+i`GZ+7LXe>_l zo@4*D>IZl^ije5G(w`aw__(Kl$|Wv(gW&SO2>DClI4FLZ84g#c7^FW1xhVvvFQJ6I zr}_KLCw#gE-!>2_Tps?d|8p4sT;Tr>>+$RPr2j$}97y1>l&{#=h(D!&>yE7GE%>%U z;PMD;(*I>N{{8tLz$|{EtB>`FGVc6go^SL1%&Qv7UrPQd{ad%G$bYJ_{QpOrSSt;DhZbHN&OCa(w^%k9)3n zFxx8aYRh^av?HvI&rWACm)GTfvG5dGT@F_W-y4%`Fwo zWH_frkcCIUpAp>L*YW}#%bFi%x$_8fC0Iy4F@AAA=bUhMyZLp5YcH$gUDyvx&JZ@| zcQeC2tgrujRNJKCo^Jn<@$Emg3(%=fc-z8LCf_X}nrg|VA*mm3Ofm-PyKs=>7QA@{ z(DY0OLN-h~`;j#czEg@(^sO#^R8AexF);}lK<=wB>89as+2t(CwF^!`VqjF7*RkUH zl7&JEcHt${&AZ8;BuPetXH-nc5RD&v2J%Mh>J5q&R@aI{{CI3`2vc8jc@tu{91Fw zR~D?7)oX7vu8iMm-&mQ(l6zRD3LTQ2fx^-^yr7 zCuVe&z1e5hGJn&mC;UvLoKz4A6-&6f@rDym2Ky9=_$YckV_B>1u3w@j*7&sb`P33r z>E<3=)9PGjlr)totHJoHA{)gtP!Q{096m6-u>1yEoiN&yRi!}SLb_>PWQF0zj3#B4 z^yZ?!t~Vux!q7p87Nf_Z8|?s+LVEF9Ty1@XLV2$0v<*S?V1|^(`V^;`5*iwxi;RGE z2m#7f^6@b2EU8A?vbUEXq(R0+3xgjBq1M|?lnUpSIMn)@r7sJe@=v8lp2Vlo`j%Ct zbJ|IMdSH<_@_kvM*p$ycK$7zdWByW0zYtGFUdD9w0WAWN!p3N0d#*^ykn0->nQH4V z>AJYe|9RN2QE*q=6A0i^n4=y%ev%Ib!x(_NE{>G|h|VDi-rz}ndUbct&N1zCGm;c& zE%=a5@w_@R>v}~B;C_v|vW0e>thJoJ19;>BZ&OA$vu?S(z0ritKb|WF<}kovV=py| zzuS}}A26vUTG)*fiL>Ak=D15?k`wNsoR)ho6`L@UtBzFetnX`A6i+T}h5a;4aZgB; zA{^BV`KGj;;^4u3lFx_cKVx#hC*1>l65%}iqB}YoD4gQ$^xi3&jT6D1lgi0M=X2k~ z@$ZL6)Z!Aa^|dVc<5kk&xS>p?K4$ik*XeqvD&2&cZZ3Z)_I<|LI9ZDsnDDkh_UBdZ zE9Y0ViqB-@*1pP-(Td$KQb4>ENy}k#TgB|qdL#JxvOO;^CBBV=g6HirX}LuVUktqGDdTtN zf|6c^=D6;@=GKS2=WnYF)v`20N(b7Q!|IjUxKwFNt#AZ#{jm+ZoZCjMHYu3qhym=R zg;AB!=OTA1BP;wimJ9fpu+#az_J5JUjh~LJhnAW4PjCNT$erw`BeOt+_{WV>iy`Z7 zKx_MdRsSXx*Q2mDDa9*BYom&a9cRAcRc1{ii$M*FR!?CcNOC6hs2IPvb%dbM=a>yr zYSMaDtj#}v`ky7_K+@xY8sDacX+kR0ywE8~ z>222tPT}^mN!c&^G*P*b|%AZywEz2MAcKVMRlkmbr ztnqH&jhn*%eGTMuh>%k92(f|}h%!S3vfw!WYTvz<>Psthuy%;*f8S5^BZ{Iwts~Tc z;0($!C9oi8F*7ZSP)97@A6eVDaNC{8d>Ps)HjPNqwx!*IC7%ue`QlnmrwKYFrbi6XAQP4pZ#)3nInZ)$>~~ z*bGEKhAOtlRc5PKxh!f>sQBe5HJ@xpV5|tYJJzkXgnf>9*Q#Zek^)mu{(6Xxz*#NX zOxq+r`kL{4Ad>%^WW!jlH_fgCDYVD?GkaPaG=;I6;8+f0flhT6U1FhnRr7Tr4*Ky% zZ|;GcHnpyBUe&5wwu9hwVk&t6zC+l$_r>R|cg;16n4u!x7ntpJeQwpsvl7SpeAMd^ zf>YdDAdJuWbx(tC?wu?=LxrD!?ccP%z2I}{tDs=r+H8P{ae}j#K2lCAKK1O#1Wbvv zapiG>%`4lN#L6S+&1A{#{9&wttxSH-r94L?3FH|d<^E>(yKY3xXWG-S(e0-GiiPM; z1yq^)BecZg*pllP_ld5BL=3N0>sok7g_UJbCd@Z6i3B`exM|R+QEPlkGF8=C$5-$2 z1qdPiTVov#weg;5?fW#z?Q zp@W!)*3d)2x^kQJ4KiUKhma;$&R_&uw;=4vS|UXuFB|I-w22gi$|t^u zNJm^bAvdt_=iizN*~daJbMq=B5NSU)cSIY1>y~xXXN>(MLc1m1DgD1>H<-5#I5XBm z*SI^+*QMF^ev}F!$}B3T+{(XvM-quj|E#V(;sL4&K)^BCs%JH97_ZWIR*Z*f1R8S^ zd`e-qy&Av|U(w$0zcv4OGVc@ThlW#IT!twJ=|U~p<*msSmTrP+89d)s3+`9-(=k4g zL^8SkD@=}IaT+mGb6eg%I_Y+OY1Qmu9C@rd%IwbvclSqgH2v<|n+w&h^&SDu3MSpU z`&Ao{BfwC}6+|QxTZwgR6BiAhx{3g0MuHfjZoLVHNTt_&CL1dZT>-PpiqC^UH3?}Y zGKB$5p>{R9g7Y4PX}#E)jSa&Y4``~pSA&TypQ#Omh7z3`K%`ymT|!61$t75}$i8UkGmPhj*{W z<~{}W=hdULcOVP|IG!5}gR4gtJ|?eivR^W1KH8@D_bsi7MXi_Bs!t@dYNge&<=Jro z8hWoQ?9;8stn{xL=+57~6mzZs%Vc)~tT$sIc0R0Ttz`1CgUTM#g}?2T(X2)+y=IBUMFBHdYoQi4_bYt$zz{TCeI_CH%b~E>G@sHl>Fk^QSv~uFswVdJmtasES**z zZm{CZAT7nyrVdlAs=_kmo^4cO@%+;+nmxv_2!qj~d%)x#IfH74=i=*X>2`eHLDS(& z{I1q3YBDqe9b#*(phY0~p|L-58oskg25tJH&(bo*UxVH(az=ak7@0JmNg707T4vQ)l>^0H<@pteP3AogVt_^F~}4UFYJ;7cBdbd2ka; zFk1_H7Wa4diD_0fldrg)5%t>gf_IVYPM?;u1&a(H$Oa;e}sw0<&-cuPkPvnf?@ zX|I${u-lrIvtLu?@YD_Yew^K2bT^ixfEz_@_;0h=@aDiM$v7`U>M~DIeHx( zcS|5q#+T1(#c$BVqy<6TRs(vIsq;=KEj&I4eN>#^G@mXfCmdS@Uov#v+RA3Eu|O6sc;# z{)go{Ri^E=9 zu$^6%rL0p>N2cGKDQ6Iulm90vbKHuE%+d{7n&>L|f^lr5Eq7J9u`8iB29otFU`w)( zpB?+L>KdC8BuqvVLpC7ozQO`1PtrJcQ+-6^ zxw{6iktl_kGUrsZPO|CBj2B2@&YPa?#^2oQz1yVx+yIh_2&T(MD!y1NRljZWWx=CJ z3J%+}1r{%;D+HK6!&ap4HgDYj0Ic~62R%1GL!6(l*wM^X8H}qF&^l}Uk{~vgfok8B z!Atj4*CR)lLrAk1XpJsWl#IRf$a|gbI4e* zHl*&C5_n%QIOCb_Xb?H&+N4iFtVk=6Nhs$`Kc=0zK-!8O75A@Rq7)fGXu5BMjjmAr zhC%0E@x<$CB@ZLSTZ-XGNZ*RDj-S`~_0{%7Ei`6_Hf-}cyfWkFIkz%6+>5js3_Fi7 z@|#qOlg%s0&|Uy_>t<$2lk3Ep1)sQTnp@6rVTptcL|(5^Srwn^R1G>I<+v%qvR2H_ z>kH)^nQ#X2k+E-X%nBT*bI`>G**YXwo>yex!q(2wfh=64B7X2QlN0S;ML*MRF%d=@ zkxui#X9rOzVK%3^!*c_5+J-ewOdp8+c855!l2Wr~*KTXZQuF()l~aOy`7GEcDfW!-6Od0;sqJt<5C-jTgMenttH>6g^UBk|@k-O`UdTuY@a4Gc>p`i!rEq zD+z4p?y#VS5=w;};GL+Yr?4jh4LAwMSfOd@{4r4yh}eCMFdUr9)4Ne32lX#EPnrxM zdbV+%HrZP!$;M7#=NBllCZZ)`w-%u;r=xRWKwRAX4&CTSEV;LQ8cO(@p#Q^%M?d^AMBrq2D-0zsp?t52~TC_0`1lu%*o0Vp3kUr2EqU` zcAp+GN@(h<-5{kXOMt1dN_O3GSA(Sxmc~Kb??@v9puqJe+fW zaBz_I;kRxg5@6in17fm3%4$A@j~i_G?zop2k(br8ux+IZ?IW z%gMRbfjGNMd5JW)rItG&zV4$o5}mjCMzV@)KBG`G`V4`+8b*V%p_hvxK!?uZSvp&@ zlIFUF=YEk-c8Ft_x#UAmRz)gY%&@O<263j*&1TfV3dVXO2|OulAwDG1>y$! zAX}wl$j$a>603hG0!x)`4+N?B1{Kj+JGU;XR_xNTy5G%==dK&p?fJBSq#2u0GiB|% zmp+3{zdy}mGSCsu_ZHg3N7aab1 z@9T0c5n)*=dv=(fklgk!aO4@yY6$n;U{64cPfCRoMX=~~oMG?;1(?+_ zS~K<8sT^>ZWLKvrlsWQ>xCk)_F!~_}tcBIi{OK`L=#q?_Jwzs4Yq0S=mh-dOv4Aji zeI_)Du$a_~jKlkhn^#ofRx0R&|3Epu*xl7Ot26utQ7e{yV}R`(FNRl+j=yOMn(S_w zH^tG&&0iiQgW2lql&#dP1oltw;Ab%@1?f`Jddd zl9Ok!m?sFIiXu5R?XB4x@GVU|~UPz7t-_BaLQ z$_B>yJ#zGX?u&^Q&?5^TXS)plM|fp8p#2|_FufE>LPl{`%ITwwt-;0v!@~m^$cWW; z1R2l1cilezs=?j)wlM&tV4P~y@aEDi;~6NQei=fy^u0-VVY~Wc3nxlo<2R`i0RnUL zM`bsQX^RYS%*1J9tyuG>?)e*>U@ivlke@&bbw+)Eh|kmPeUu~z}cqd)3+&Q?R?%Gz+1$6#ZboqZ|T^G$tm zQS^hyYXhOx962Cp0B)Gb*klq(Qy;+G?9(Kz)}<_YY7u`F@cEn3j{|Hhcgg5(@AHyz zDS$U#cxp_d@@U{xIl3oenMixpPVJ!PqprFfB9MI zBAfftEo{^(Du&&YfOR{2k8J7A{M{iFB+Jym`|dj>Ok1%N)JnusczJ*zKIU6A-yXd) zpF%fLzvJEDBG5RKKQvd1CZ!iqU@fwdNLCsOlT@yj3ep`hC<5Ve=IH|;aF=j5q&mqX0I1jqx!&>~ft=@7cW_{?V2=S zrw%)9$Dko?a7>_H$VXcy9}aG8Xo;qa5<#Vcx^MxM0!*+*n`y{EYDd~YVahF_9U$3a zHnFRsBPZypo41Gq)B1f?!Q5M_c<|cI%Yl8?8^w zLSHQEv1^)!{0bSPvO_2zkD!6}FYM2VGE=HKq0mV_93fxa4foto*A4%P_B8PvyRDzO zt(>5Xs)qHG%Cm*l9(vPYkIj#goG~X#DPPHvvfQ<*j}=hY<2)rw((&>xE()F63_yg1#~&*0DUX$g}TA-EXN6esWBTi_SWd0 z+nNVu;&;38FMXn-l4Jupi6KvO9TY#04OMs}jC=tf>T<=UWm_g5WPTLf5G&ftb@jzV z5uguhou510Det5pt9Zj=_7LLq_;=hBbVN62u)3%R85q#4t%!HMW3SNFTY%}g#IOW) zIF-9SYPWu{`>bv!-nDzO7dgIjaQrZ`Yb*Fa{1c}LcU(O1p9d%Pru`;j9jq^`e* zvdv20!_s)>)#r3x4iv-2&vSJ--UA(BdQ~Pvl^z(G98ujEqzAoL2M|#eJB0`b|AQu` zUUi8Cl(9abn@4zue%LSpfdXQ_E^A?>StIRGg)Aa7Q@J(P7SNDOg(Ippf%k|< z`buSc(HyUsZ~CB)cm*=KL!L@h`Odylapnm8#M-VXAr5FlzYTHBx)Mq>K7SQJXK|H> zZ4H|Ps+>}tG9K#hEBq>k(mi9NW}Lsv?$JUpkM#u6MAl56qA#-8a}2!Q_(WVBN^rB< zIXeljn>iSgvUy;_;W^Cnvd{Hcn@8+U7QtwYnbdk1w!p+0+^d7L(gC+kL6o?9&!dE3 z<(4pH`WVCOgGOB5(9VVM@?dJOsL@U-b4B(To{>Un3p2G8MaqNHQ~I+VG?^>6z{x4o zWbns@thKf}ZX!XOO23l}U-u>>ft1b%_T!cWj1po|ZwLx{+C@e%K>M2CMYo`226m}i zwi|Q)&AnYTYYXnpakNBkM&Qaq7g{T44Sz1cKf;Y!S~)wdEEJD_|E-e z5yU#jWpUd1d`wt9&#{%J<7@&;@T*s=m_a5NgWb^ONhHX`5DElgfS(6bOhj zAtD^hSz4%{Sp(f4Q!&lVv+UNH?`0HDwsw;T!LF@JS(YJsW=ccWZjj2!(F8f5on1qu z&*nSI9%F$Ej;xM0-(u3|ZQ7&xb8ao3!`D+{FQCsEuVS_biPz37M zNsdW{zTxn@>Y1!@%~d^14>UAA~z-Q`%{w2dv>()%t&OQ6(Gyq0Z3>pS3c+vz1XUN z3gU+JM*~&D265cA@yflDZ@N6!$xB;-dN(6%`z3laowkTKhrxmuqH_$|i_)ivD5S5R0c6$Lv*%4$gpbL zU?Ncl6f@I)1)G|&y?>5FP-xWG_?p`G++gwH-|n!wN1@=m5qkyK z>yiuCVV49*Nw;0tgk|Dh+Q-24j_6PB6)ui+Rk+S1I=mINJUYDc9maxH#jb&LSZ9kG z*>P`k(VPOQdl?I=#U}v-BIC=(8T!cLIc<4^P$Z9bXwInj%d@P9-^wP5|1-+-H2kM4 zVDxg&)^~Hxl`~uG{2rEo|LHX9^UlWAwTtD&dE@P-ar?0h`YB04OD^ij$Jd|Mrz2Vp zjGwU+{|cI!H&ciBk*oVZXaIC)-NYFaX+(?dT0Y}s)$&zx^jC3P7eO@#i|2w82KpX3 zQM+lx;KlXV0=feRQr>;8;Z~$_NXY`y8rNPs*N}$egpv5*)({Elk^PAS9(8%^eOK|V z>1k2MZJq{yH@2hU64s+qSbbe0lEBd@fSZV_9Y?EL?lWKlS@4$9x>)p3%7$+#t~wp( z6D-a8ia>agHa~Mz86w5ofp^fBb#{+JG0?gu!Y4l&AD5+*@I(VvTleB5DO*u#GU&Ua z18Kn|4n0cD4=n(qQSe3OkP=u)JGfJ(FUl%e8@~TYa?kn4O|IOm_D_I25GCpUpNul0 zuS5WYuHu0`UDrcWw*K&-9L3w{b4~yz6_F0}<7nDiSYm{d6e!42AuVsbT38vFI(Y-l zg~(T5Y9X&`mNDk%4Xjze8a`)&*C?}F6rkMIWy~AX6cGaWLmKEZ_?RFq7A7lCU>Z^x z2DbS$td328xJO#46w&$H7hUBVki=3PGcax@N0%|xMW+fo?LY~ai)Xh4n1Qye&s;ut z|6L6awh1hh@nH59Pf*O^1414T9k-h1r8|rvS=~)riwYu@)-HP?^3^3ZpEMS}xCo-* zk4Evd*$uz)iHH9?{ zW#G_K%^ap$=&|+M>;oloJK;j#p`-jyGOkXRvI?~>vgB33klY=!t98b`gE}Uinj&be zU$72MXSoC+GNNHf#PwjPi8kBKSe^^_pOSVYW6)~T5;e^B+2?@)djYTFO6@AUhi8Y~ z0%YW&jGqgN#d}J{j!BM!##DWi(<|N8jm)XxZIW)hIlgv5m!rYqIEr@KKsLfRT3gHy zOyBr)H=+dy|9UzxIr6mQ+|heUCuX10(Ew89Ilk{3<+R^5XGQ+C!|tD1>f3 zb}cD;3`|O^m@DZn019cmOV&IXTfF@ zBsBgIBw}3iW7J#`;9~$&1mo^IWXaKx;W1my+vH4TxjclAV&^CwY%dfiMZ)%6vJ86R z-`rPnS#)(vMkj+wclj|aQ4fWDrxm~a0a-!68t9Gdp)3K=Vy=ytueA2#6n_9s-^HgN zXi!RL5xaN3o$OX7Y5qO6sX`q#k*}5P4z*mjbtU|zVY~5T-N>$$-(KsaHiD~G%yv#Oy<0I zUA9rFDTbcY0U;Zh>s&U_-vtsnoKU`QCRf}k^JOeEu%Vj| zGPKR_v2CTv>XFHI8G7i!b09@nrOO->qXIaP~uuqkthFS^!OoZQrokHBm57tyU~ZS0Kf8M^VIX6Sx7*k?AW*|Ks!r zps}s(!}pWkW0N(;EZBv1(UN{H74Fm8e&1OYg>qX(p5CxhU#ou3EyM*zdd{f|5Ol_R z7R&^NyS8gF`!6c=MXI+=r04v|Ussk-#Veh)1;XNi4Dyx3dbBif`bvKYIlpa1La%pW z)k2fO+BH=nxoe}!92G?|wV2TIBS8X&*e&Hni?}LhD#EI_N&(Mx^3C5bN(oGqJOeNV z++vG9BIJQD*lvkKFh_bJd{5 z7aR8vARu3P1x=-i2-bh8;!8w-0O~FWUHK2$xQZ?=0X!G^i|+3oTbslj_~pJx&PH#9 ztDWdWQ-dFfhlLYU;8HNnV6{gdJPwAk92P32qM`3xRA;mJXv-VzIz_0ymo3bfcI-Lz z-{~NqcRBr9;401z%p;R44(71hMq|=W3Zvew;IzP1NLsRHEy$95ebvH5jB&N7lN|ad^(_-U{(juvNEPWS6*waRm=!n3lf=u)5>pbao8e7DBplr+wfS!Q z3o*NZ|2>BARPn~QiDViqp6{tsQ#@1e+`os7EsXxiF9}@)Ec_`(wl@LuJ{lJ5vwI?7 z<_~@knFH@(evTl)pwO?)EsP>^F{Ii)=-E7~zuy1aWv8b0F1NDgx}fmN^VU6*TelH~ zZrwp^BmCe;k4b8`oq{VSfe5)q2N``=`#5QY>dtIAR9Np@&W=ksC}8RELhrO~@^}EN zQf~e=7-2BQf#v+Nx1r0c*C@Wgh261z{vo8Ce99(L6|@z-HPHEZYu1KkP_Yw3Vg{C3 zDitM;m`@o!SS(k6-kxBY=94XxlsHrzS+(Bu@zcHW6;zjI>66zLmAT@{`7R!>$c-2r zTNz94e$@+-B_O2Jy{&M^poVO3f&(e$zB#{A)0$4ThZ#bPpi{h}dkZFLBZb4QzDOYh zc^xmloeFirSWEDNT$?%ot=jamJmd0IiCm*5%doPX^ZLA#GnH^0{}QSY@15ZkJs!4{ zn0DN9%{~_wj0jmsdqwv@u^!~zsw0QW)aO^$#0%ahK!=mSPDHNN+%8F{K1CR(Sjhd6Oce)Xi;B*92wCkNk z+a1@Xrv6Mv%d|!$u-B1SpQRDr_2WuR-v>eE^V-Q%wyJ7_P#IRLTRRsst=)>eu~k{B zb^Ww-%2(;LZ|PJ$jtd-2z^q5nm7}rAv6>TwcJVl45(T9#*e5@9eX`YU z(<*7!R^pmf7LXv7StprmZ+9PLxJC-j6J57p`-+g!HLIZndKjN}wDD#&c*cKYJYOXj0n z4->GrH15{NTj884S+`$+j4k?7_BDKW3}m_AIpQHz$S^WH9h=Ro<*_3M@-Ppb+eZyS4c8`Ei5d!RN2Vife9j7}m2^pHn*AjqA8okgnPeMBo-Q!uzIHS?sCgX}w0sM{sv|Jva`(rGVe{mo z8(!gi6kHi*m316?rpqaOneK#k1oYfXlZ~-96`7;tl~gJz0>WNZrX15{kD~m*uNTM3 z{VSdW(Ul5CnnbL0C3(eyAtYXX9ae>`n=fmFM(E@DtzB5p^S7ps?XD)iGq%=Vez29% z$G`2eZ=;Hx^wnKYYg%+S=T%0?^l+1zk!R!BqhCi9E@1h9hxhp3>)?6!omWow5R6pB zj(dzgdx+4rKHqS4mF%>?zcWQEw6}|)(YduAt0lK#?qDomBahL5rpbF;oO_}Tv-Kzq z47x>V7WahOItlPYnWs-CARg zweM{p2b&u8Y-<)FDVmEIgY7IUrSw;%h)P;f9(oV&p(n?jR5_h(F(IGM?wwKo9iMT*XRsS zMv*`=ygl~04^*;n8hUsP=Zp@!YiWWkD3)oxkxR64I5jOC_#J$*H4DF59a13ytsu!H z7b`6`h9!x>zgGPgyU|b2b;6Pyc{W{24L-6L*N`<}GdmxCXXs9Fth5a)Cg(l5^RGP7 zH17zXhd~g)jsFs0FYgNaw^91LgT^P7%8t{J5#ICG~f)?$-cm0%o&=G zH0zqjMz~H55xnrAi&aT(Tbw7*>6Aq@MCV&IY)Fv0>Ci048fSKyDLj<~Vj2&{EsfWgZIpDQ zcrw(N_7=|dQ#c$0dzKT!jsmddk=D3|12x`P%GXG8c*C~U&yFl>RAg3KJB%*f`&mlA z5|QuPKZ}y6>QFP_thma(5I_AOWj?+~sp2awLx;mYo#SKn(Y4)Uyvw7aKQS`XRU)4V zi|2gwTKdo@SH=LJu(~!V)%@z1snpsYVMVGyOSKs(8(A(Q*q}&*d#SjCdVRlv<2qTR zvbJQrsP^+A)q!$@o`FT*|y!*JDWEKASswBgQ zl*=|nWY2&X|1R|NwnF}-@6oE8?7$A#z=TUe!C;?%UG&fMj|0DL5Lz{T61eQ?{~i+l zU1}+~HSWaVg(3Z`-@m+j^NU-gcDrx8oeF@Kz2Jm9q`#g1|6%Vvqng~dwqdb?jV7C| zNUwr`Ql%FG=}7NIq<5rANg@!XNpI4n_uiyNklu^b070a;P!k{|d2jYU`#fiR#&~{x z-x%LJzWwJOO31odYt1#wHLp3>zor=Hb6JYmj1kIpoPYJsU-JL2KP)QlV)|q4(?q`x zN+KT!)Q9uY#eV?qJy3eit^VQa%CF$Ob4$)^~+~cPQH9xHAp@&uD)vVbt?K|I(pXYwGv@ZKVJBC4W&8V90^z%o};Sbpi+I zh|soZ=zn-^7c-B#aiPMzZ7$17|0+y9fEB*05X1mHUX0!TWebFuNRBQENUuNiq>=r_ ze)n9tkWW!Qe}-QqMUu|qDv5MZ&T~@W!DxH^mo0cm251Q?diT2`ky*d4iT{Nh(IiVo z|1vW=5}rSfQRe@0jKWETgVJ97dWsGt>1-r;h*dtz|1vWY!utf!5&Dgn7Z3Slf?u{E z=xPAXS2@D8Z$sH^zkJi1j--Y*DTw7I)8A)CKnVSKA(rlJ|A^&(uFOAT`HxusWlR1) zt1bOrgsuM73*bM6_aDvqkLLWh5&p-Z|6|bq$4~gj&-};F{I@jx<7fU~8~((-r9ToR zHvU9$po6`Ug20`Ouc*HYdt)^_;#S?~oX?9K+B{hj{+-_4HJaJvk1YKSPWWHX(aSvO$gABASYE{K8t>aCH$r0vegP@s zJdl_NAZvgoD!`$9>+{S&$rZeF{|8TfC<`;TR&yMVA>zW@6Vfxyy2>9aCX zCWnLikTR8zlg@yr@ZoMr1b0~=sWc^}{=qL_ATjw99lVQdknaCwYl8v!iAn2MIP22o z88S&gvq}MK`!b`@-=ag{^>KRt0!Ay1RXTqe@T&9$`V^%YP4r*ivc1e~LYU@wb**mg z4nGWknz&`bAe|2><9(YZ&Y|%OO2<}u0Y`NuJ}$MseEbXA8%1-0!yPFyQ~df4NxG;0 zWZY0yqvHWI9aJ^re&EzbH3ReCf6aeP@d7pU>mBo9dFlL%dD|cb;8NvsEsbBWKLAoB zBL~*xlggZ!NSe3T+|KF3$<+5~e;xm}ElJmy`@g({OySRWkj)Hg{feKO{bALLf4~3h zJ0z2sFRWVG{{>d<<MD{V#z$1zI)Uq`mQ9rk;r5Pv3#; zdxO@sUyi}k3!M7#2lkj>b_)=0_<^l)4_SxXn9Q}K`mQ6#55j;^S?AOFmH|K{Pqvh989=SyZpx3@q?wbOFYnQ^9%&RkaN#%N})ZPV-L<8O-})(Q_>+sHQ_xG12Kf4 zs9Rjb@wMlSC&#!s+$V2ivUZ@amTDktrFbxWxYe;0YnvqDt%Fb#xAAi8gb}-Yi}G(M zxgGZOs-HT(_CDIKD4y|7Y0Q(_v6GACnshv$e{57Ydz^GKU{Jxg`AJ5CscK{7jYz%k z_6^=~aV`N^-Qa`dq0*F2C)G2|PWkF5Vyhu9TMcTM=Qrm%yl&Dp)WefELrXbpQA2CH zm|X`0zJG8XgViFBmJ})wiI&P70iaIAAHJ2&38KJmggM{*7121X+Q1P zDR&$0t=<;lQaQje-@(5eo(2imKNWG*>^}AI2}1p>3a~y?N2)}gTn=Hg+R8`SAllEA z4VnAI?V501R@??OwS$<-u;WJ&wYaLcJ%Xi{AfsXQSX262@j9;(yr%eRn=c=Kca8n4 zx>DV54#sXuhg*%|sAO1Qvj`|1BVzg*oBo+I9ID4u;9XW~rrJ3hL; zc*L5-u~4TWKxnpVy4ag>ZG6)&nzr2c^GWOZsGwClB_ainEq}Rx-%;KJ5uTWYZ}Bbq z$=l-WHT(KTHmowOM56rAt$Gk=nP9kZMupkiy0$tvY)vUlSuUKJEtL71LwABI!#m}v z|J$@K0YZyEk|u#!3jdWPBnegm(qu-DLj)P1ssk(t-(!2J<{?R%B>B=4kdLn?eQ+ z!!sXZ+fM=qd<`r2DY|KG+?|yzAn@pyvRzHRH=~ZlCIfoDWmuy@o&r-DKEb1sexl=8 zJ@g8lvhYr~8Cu9KHs8OX`*^q8LYY!O}iwjzKSu#r|n zJ~w!A@W6)E{$qVNMJGTuA$D6~+4pShMqt}-thVV&c=qxNnOw#;r9%*RLx;Jv;$+SP zFY$4aY^KX}=N7!J6X@Xs=_P8EYG zj6Y+!Z=b3Fp1&%C8(1i-3nzh>BklWt7>hsu>EC{p;UIF=`ZjyXyGN+L0d z4ik`yu&x4ScD)~iHJNKx@w7ml=pMyZ8;-KbXCrN>f1Vqx=U^J4#y05_?fvF5K>sl> z0;U4oWP@;MN!C{JM!btW)8;NZ)_BN41>`dm!@*o3rEz;CEi{`o1Cjcf4c;~}{ zoO-rpu>)Tb@;5Fw(!#nTlZov*5U4sg{5tb^PQ*_qnxrRWZixbe18LR|t(Yo~#~>|> zl)O`+Iuug&n6p}j0K<63eV68fp{X>#3ghd3f{8)br>za!j(nzSIF&{lH?_(gP!6+SA6BAOqs3n` zA*Eg;B85#Pm|VVKO3JKsMW%P^KSM`CY07%63Y9^EoAVo7Nv1uNzUQ!#&8EqOc;&&O z_^hgC$D=0orCVvVk;L1iq)Yfl&+H_=og39X3lL_f?;vj~xaWR69V2Q+Z|Q)P63yqB z!vALFsL}po^s_5~qp!&I2ZyeSL>P6JRIqkFg^;nGHu1Zvaf%P^XwVL4-vuKlmUe92 zlwtJT-V&#euUzbjzbco%ibKou=Z8m@-ANa$E|yt^po5irrFuyA`ZDdo(z9&sHx|i$ z-jg8iPhQpoZZIsqm$>D)X2@xr)|0GT(-~r$Q4D!=%4e?!2grtZ?JcR2(x-+SAV!%5 zFsYM5ZX-}t3SD7uH5rPfdMh2=?|1H4gPf>!baT^1e4BsegU%;PI!HWj9&z8ARgd*z z1@8w^Y)6C{LUqV}%oi&st&7QK$_w!0Yh14FuTP(*n;Chu%!X!mH%l>(5NR*FY2dFYo;bwYA~=BwqTUf28<$%|1*plB_!S+8 zPu!5L)I!g{^*%#1MGS03HLuF`>Z>_6Z`>^0)lS^DH zve0x1yCdc_%$T%5&UOcAs(&y1!h;&MYx^~CPIt*40%&SnkgNg1ypzV3IxbKKqC$P& z=25Qe-Yj0)BfuE9JNJtFMjvz_H0T{GG~u%|^413mcA0=80TBTnN?LeZjhzN!2lBHT zIe1Fktii@f)vf?2uxFUsoO;Ezc@Q?jrTz7Uc0a~PJ)evyld|0C=hbT7RqVqFQ6i9Y zMRXMLyxWUjpiI5t?HH0?$>_UoNi45PTxCqKDFfz|eGv|EtPyVjqU#3}Lif+y8afCF_~ zJ0eS~R}0Zk>-&vMop!Ki=k~e;kxNE%PJaI&t$$wz_D;ShPo&z(zqTZ--n zd9qa*I&*yJ0(K)t2?(LK$JUkd+^~-u#PkI06C&{3Qgg37V`i8q6HA&Do_T%ajU5C^{~Ik1IZLb9njgTe(j=d`0}2 zYdhQb%tc7#ow+4JopO8uW=EVm&ZDQ4O%ub&em(%>{XfsL9^2tv1QOJ5-FTR>*~+;O+uh(v zyF&I9f4(&<-Dzjuko9S}4u=Cg;9EQBtIM;l2RqpV`3O8Yf8$GY0RT!RA_9O~mdC-= z|7~0Nh^BR&ugS^SM9LhfK}UK|m))F&xwQ`UCHf-N=;BFcMT+DmLapZb^QQ|;wCD3c z+f-~nQ{p{IoJTpCBtvplW$2wZE z_dx9Wd_UPK`csGm(XOQ4%!&(#sq}Ku$ym=83MJa9SGx5ImmPe=&%9JZL zp+p0o-?kRoOpUhW{gPTr!X5h)Gs|4ZT}9e&L1sH=_I~O?9NxUAft0ize1(>;-!W%9 zYuZL+aaXo~7rYb8wP~n+@Z)zv$z?(4Qtang2) zPs+^&@3i|xirdfZ1MJL|i5NuGt~Rk5YEZcY&q$b2_@XAak}(wdLBQ@f`3{WLcxDip zQgFvE3{hhqsiPXBaPGI{INW)xDNs#$mg3{Z^P-+(?`HsEPE;T4yP{CC49B=kibw`z z_)P1{9P%v#+Nge|0OV+~FMch$lNOBC)RoX}xQ*{ewfM4hvo<;tOW6X)f*F!S z_zCn9wvqkJixPyAbO3=2+XKB;`3nQ^A|Jp4gsQdy2Ql60Xg}h z?;0zkQ*r^VHk!+}oUSFg5n-bff!(0_YP93tse(_VM%XtBp%zMjLx61T=sED3IW@je?QssZJ_vC(>~soDB+M$^7x^? z@aVon(50(4FH%J9|7(f}Kre=m-WS2_MBtVjXuH;Mcn;<6E$|~f1J^?!oO=Lgdo1E$ z4EMu*%aX5&7WUMizsp%y-Oa~$>;PSwohbT**pb{+>(^<3aQi*!U$^uUJxm0eU54qF zJbkdZK2jB8+w%HK)A_ln)!7`g)mWm$CtH+e-U>CvQ;YhYt&{}#B(MGUEx#4~G<0}g z6K0RJkSlwA9C3&zY~z;PcMrqaRa5TN~8n1W=kC!%y?c4vw2M zxlcG8DjW2z62BRpZ3)*e=b0Ro*G3zM+9eTYwh)%GZ^6`*pS)hk_z`-{tCEjD_n0_H z4?<4N)huLYh6$9S3LO#L239866GPtlo43cGrrijtb+nq@p6*%I?35kX5?9hGt5nkB zav_ytVh^+SAwcAM@Q#n&JuisllZ4q}<*GZ1&|hvXiTsL;H~@4*qg)2vyK?JJd})Oq84lkxcUR-TLQuo zZz4dbw?nEl`j(JxUWmS$^7&jyX=9D;>UpnmeX;XzhKT2_%l)(uo7<33AMm% z`h4oV9AacgBUBz6whYNCPk5s@&=U8>I9RH(PM|ZW(umWJYHH8|hoR*KeQD%0#3(9^uy73)lEIq7`0I)7$Kc0OjO9?!qp?O78>oy+g!02Sf z07b#}b{!d|)#mS!&JOdX;SOgrb9p9)ANZ+SJXmko9-T5?u8^_iEBI_PVV>T@q$oZc zdWo3d&=Cfyy(3+g{*rG*6@Jg3O$qy8hl5HfiAQEbqcg^xaBauVYRTH zhh0A)vd|07J5j9V&XCkHMEihQQK%l%x|-^Q`662W;AvYr`Wm@d48@y?kQ+&{!gX&H zhNw|hhQEpHpG|`dr1hsR>pLu$PuGNiS^J*{6szl|F5W%9Zp2(S)8J~{lnOG=Cit0j zn3z0l#jPw<$f|x?3FrS>Y+to~Zg?F+7N+;kirGxX$+(jPSJ8dLupHD7hvhHQ;Y&Q8L-d#`T2Mjo+cRc!P(7`bJnYFx(4CNr7H{N@KG~>q_HFZO`HyoR>*$oafeKRbC+rc4y zxcv6!vSZEy4pw#{%wRq}m5QdboWN}%-H8mx?_MeuB6$COS4K0+PS$}s=jvlfOBa7l zyY*=snPfMw3R5d+z*mlV&c`aj*ggYMTXpNYe~jcJ^on7U{WhX}`=>MH4bsnii{IgE zbl&UYo$#`HF(Q9%+4eaOOdEtsT!+r4ydNo41+ z%Wm_R z1b-2L|E*B;$%6~EU*-W(k(V>lYKR2X5KJ(>uMz$zQS>%`?2W;w|y(c z7sZ|;g23MKHDUVcbP>K_ncLbqv3)D`PgWe`%tNY~wa(yo=R9k!q?6h9GRgcAtei!| zD>fuxHhK(YA)cq-yd@}Q8g)8~0==B=j--tQdhXV6yvai_Mfv>98=upNnJr^}0;}$K zXXnv&q}nNxDz)RfJP8=bPZv=}J=P9a@f#%=5t8uqpH@~rVuWX05l)*0V#x%(&> zS|mkFG=)eK@2*t~lv8oM>OyqW&QV`MVX%pJHR-UV=VhQ;rKdsu^a1BDe4Hhk)FN$Hx5yVB5n_*2Bd`0z9A2US77B1;d>eB}UDwci;}goDzGo) zMl1_yO_rrvMt#SfOHLK3%m5r0lSQ|Il*}T%FKrX#j|b>(hV(T<$3cR3raKKIP-mKV zpLXxSitT5T(5+?*)l+F&o>qxvig7_@Kg$u*a0mUufE1=t06cil zvdbhq2~TH_e2$(Qotr8*+tVjaxL3Is^IAk^m%~K-Osm6;6H+p9v#L^|K7IG~+&K?nR@Ja+wQ_UBl z30HV)4kDw+ogvgz-ZwT}`Pqnxp$BKY!l&$bzeW?|MQ(3t8(C?cWh<40I5VA5D7pgt znf2kMYyO=x>!p0J>nHsOKsj2@0ZP}cr2HUAs6$*rsfK0TPS(IyF4jQ&+{*vdZivhm z!Hs0F=o5_YOqt6K`O0kqdLzTfEFnYgOnF|_CnjhkUE!xN|D4}j*BmjOyHPH7YIcac z;^}7DW14<;9O*Pc>1bmHx+k`UoT8dInua`1JLCARtR0NL%HBqNn~|4NM~wUwp1(I zelUI#aZoP4ILtbO)&duqzD<5iOBCk}+NDMdCO$T91|{D8q522Cr&dQ_*$|I-igT%zwc2`yqmyF>o%e z+;4yrv=u*Er~jOadgB>db17HJk*|B&GK~2oW=~b=Q9lmTaTNe)Aq-JxH*~b?vOt~5 z*I{1ufgj0iC?_wTe`l zV>W|D?0fZE4YXmt+;`08^Pn@Bbcl57V{qe()A3W77u=WCt^0mZgG#b{cCX;Zr|Sx| zHR`u12oyY{!_86)2_L12`gpN_a>?RxA3lbPlZinrJ56i1uLh;n75Ktf@LUKAeY8WW~%98W=rbrZ{sn%Y!(upKG~m@e@^OvdmE zrTkHe?<-M}_60a{&fQrTs-h;jlY5-VTzOQh23zSESOCx8qL5Mt2Posd-A6Z*tTauQ znsh3E$&EDRmnVONhAq=0UC=XsA)g55XHCdlVn$q0;>#sb6}#^(#^|DSL9y3NJ*a`O zr2-;Zd>seJMk}p7*;b$XFjwd)7EhEhEMP#*ILU56V4hevnEK3kCt+TAliG{>aO^C} z&aes>ODu*eicKBSv+cC5SjjFxfJHiPK6KtKm7k+XE%!<|&czl#dnAnp2n7!}@>yBH zyU)tQ4)10wV3VDg!>3B4hIz#dTRopU3%csI#<9fOYLp+rsP%TMzC_R z^2|plhvT#G)oH2>4>XOlp>PI{s5Nx945ke`1*KA@Ct1|YzGRO@Vuz@$8!c|?jr5nX zCl*q4!nE%9LPt6$erx&m{ifEwvN`64!(Lc7t6#!s&g69SIeK0h(Zs=x-=CSQKjvCW zWkfy2?t~inNbDvJsiaASUMh3rqaGL07USKRbMi)sO$yeTJ^`>f$BP)ymQq>zS8B~W z$;+3c>tzWu$w}CmQ%I#>z+S3MIKD6-O@@3P!7~_SeUC-{zQS;r*T*^vmTeYoaigj? zylhSsB6fj1FEeJEkc>GqA-{GAF zOpZEajz@(=kLDN|)i=mOG;5iPS(U}t4_nY55X8)hAp;1qkETf_wAVzKlg zkt=OjSZDDFmj*J{FrH%WQ?vvmq$oejD%=NM9CszFlOC$7;}vonB@EHaWWr%GStLtq zIiycY~;6Uw< zgcKK4b&_$v3#dIrWt!NO@llQGR6Pi1QatFy&t>|>swlUvm6SOhRQu_KEVQ^) z7l^-7$4ufM8*AZp<TZs96SQ2fo@yceH*6#yOX`_$KdbvWKV7Q;i=KSmC^Kib8$ z;Vkn^J`$;Ssqi2{?Xzk0t|C%GJOxvyTgQ-#z94JN$=ycZ%A$BFLz;zzoPLV~H?vH> z<*+@`r8(+bB)?1|uX@2@^|syqg-8oTbU7Dg2mIL@(Usbs_95;39uN2~WeJVvE8;aR0bo^|7)zl?X zoi~%Pmdv5;Gi`Dkem$W}OVmh#S$xg+iiF&F1!b{?`kX!Mz~QG4PA15X3_`_|j6Ig5 zJPSK?xD+s9K`E9gS*94-x=@!~!l>+pG?V3EXU~eJv-LP zMfme86$T7?qt!7pl{<#XRK66q&5E%X=?vy6ji$)i;GwE4LL!Q^EglYBtnF#%^m>I; zcOKr(;Kyu`P83}jg_+Nl(b;^qSCP&8g+M2cwSqR#&Y__Ih^nK(qfLEhV8*jTT41S^ zdti`}wFw!5JG@0fD$SbJfm&i&gn4%0s9D$z(V;hn#QKQBODy7JI#L>pwEOUx&IYkT7XQ3p7wEud1_ab33Gg_SNhZOB%qk^Q=RzzwHMw&W9-K#jLt71nB@Pfxx+6pQ@%xn+ za|p-Sx)?Wjarf25f9x;ts9GLl1LW`gLK}_wtV!0atPwqV%;7IgaL$R;Q%Jp{^AD1} z^nVbYD5b4^u*bJ-U$eG#ZCT1zO&l9sPQQ+7x@sz6XnFwfE)6or9%uXZsbhAR?uJwF zVESXePLtQ3_1~Y)Zc%qv(cj)TX_WH3#xTES0j90!tUDe!^jx8ziC1g3O@~18FzM?O z^IjhKv?hyO!?Z3XFZ+z4XaO7Z=qyG1B`1ev3vQ6QI5wb2t6S-W|NJw>I5u4v{cp zouU2$M{!ksVTod{9zrbuH*~-F!i2Mq%Q}O~?!Z5vn@ThhJnv2lF+GneIql+>mL*KP zMpeaYTYzqh6eN!C;|Ga3@6?a-`HN=6gevMEFPMH2b#Xb!h* zXewv?ttMc)c9J%3-87bZr~z-u@gY67iaF_|@DXn{5tA@@RMm6JL)NoP?Dc#HIhwH- zV&K2C+iGm=ZhIOQ>aas>@Pm3b8+0pML7eBB?aPV}T6wWSF%OJ&SF_KQxO@+`f-~ z#Z(9@k&(7(fll=6B{BHfy=0n<*s3UQz7S=Z8SO*pKJO~x%-RKuujgN#W2=Ap7G*9mUWH2T6$O?0N7`9fy zj4Qh0dXQLjokVymzk;A*Wq(bpbWeGh7>TlAk zN9DxYoTP0D80kp>P`sh5kwee)d$7QruMTDDDFty-c9UCz4^v%=giSIkX(kkxD; zs_zZCE3LKL^^eoq?D31_(!%98P6zn?mEVtqx{IElXAjV*++x_UGw*{q92Lm~x+MQj z?;pI~exsYJ^!KQ~bM++t4OvSjo)A}@Z@UD!sk@5UO2nw#m7xuTJa0C#3Wm%5dW$Kq$BV_q&wU>@|G53PUDQZoR6)i4&g?nP6 z>eMy!5Q*;^aIz+hV<`oEBfaq}4%2mWm&f=_H*iB2PNZc5+oYL9w^GiDb(=<@K>%3q z$kcV&^-Sa`nw$Gh20-G&U2p()#HKb6ArQP}U%dn~K3rM-3jUaPe5>449)8-_y}dkb zN}k|3hiejkm6yKtGbx??o>)UNMSm~TO-*-|;d4u7GHFu_UGRF7?aB?=uUbq4dWRB` znD--%$a%02WunpLaZ{bra5273G)^EUA3C4>xCSE>$cS-=z1?fhp1b6>J`DEJIFpW?1&49UL(XeQ;7=TO;USxk{qZxX)3t$bsL+z@q|Pz^_!G=FM(dhs zRA(zWI{zmCn34Q(zRxwL|C=%_e{sH#^yAm#2s5)y3#`thCnfgMl;tl7xV*c`nnpDg zX(XX!rw8Ai2dXBvl+*0Am1EENRRl3Srh$R!ouL+3ONt;8pEbwLM&{6#1K!i`Ujq{w zj|@|&sb+f~lnz`Fs||$5okR6};wd7AO={*~LfOa*MrShsmnV!?nwU$BTVV5#LZL;$ z1yzRWzO1&(F1hVVowFT}Jo;rtI~p$^=`)bq^r(nBECQnxeXcr41`)}(j{b z(}eN6;lVx>E9-Ia7gQ?A@>8KP-N*S4&6!SOjQPz2!h+KZnj0sIKcRQGw>X+}-l^4(mQ_71E!pb@VdpLAjFn<#0g|@#y7GI!jj9;=^Mr9+$WfB=$ItR(YNnp4 z{RXjaM_%uMiW}z0Kid%fyp>sNH}X4&4u`YsNOCX_Dlo~a=(vUHlD$o~&F=Sthz+av zJ!A)O6M&2L%Ace7E<%y=laJztsUB+It0Q)^$ujLaZ;1_KRI=9TJ$rpht)e$_9&*#d zKC^4$5&h3IfOJ3Xcb=~ycP6YIhp9G)S$4f3M;0np6FGEAiIM4@sHXL{FWoHgf;IAx z`@FTUeoFA5TYnd;AT1z9(#au3t#BBd0*Z#q&9y8s9VWYnKdGR z=2Fk%bd5e9vlLW40AQ7*g#j$&b{d&w(WN(TKfOs4)$`%*y3<`d?LF{D&sO?JDsBDl z-#XP)w5+yKEy;pBKrpf)kZ+Ktiu}D?xH9{&nonWHoyvu7CR9H3Ep}BUzoA(I;I^cV zP+?Uc*KwWgz%pznBuZ(35PSlr%mN+KHS99-&a$<=;@flgbU0hqV22xyajNUiheL1$ zaD!`wTN7$bqDN1gc;Xk1dm7KtuGx#UzXS9i@juG9lvw_&(npd`oPfiUtpeaSSM6(6 zj41--NhjzCW_rCTl2~*yjU}|zeZ(?yS}FvVtx6Tr$@Q$!*g|N@=vF2_+eriU=lKEl z_=S4u3c=S5uVu9bR=Y(^2R+nt%>|k=3^p~|=bxjd+uUs`)2RHuM@(!9&L;LTGW4H! zi3rTp0b?}nPRz{#5NVlWZ-=2t8XUepN9-IrR9avYYWDbWjrT9-c4q_UHTrZ%1@UdR zF?d8U!ViA_iZLPgb-zxjU~FDzXP_JJo}x*EjsHaq=pb#N-d~J(k}N6 zQ=I(R`a5>(B~Fmh)zX#XDY)eht@~8$v>%1*L3(wg9E*v~lA^Q72D3U8JN@&xsla>v zLB4(3Hj8h#-55v+Ex7%<&k2ph8rvt-mL{>outUsdR2{h*>Mmu|ym49I7R=Fu3z*Z1>;rzb=r4W7=}=5zlDp zNqq}0b#BHqtkf{8FC@FG5)0WoyTRNG3nz?FPp6b|s3u&A9_{cgN^P|xn zgD-igO5~M$(~O$^sMeI7{f)``fICb3qhi=O-z}};8_h1qy>e2t76z7*9HQoci*R=6we zVH|&VP$?+>GeO>yYV2ef64AlspWOB1Q7qe7>h+YCwu;DYp6@NY4`L6#XkEm4E2cc! z(Qmi`TIQI~X=0Hw(*uQM0ug$WOaATvTYiX(v?d`qu?48k5h$A4vV9@^&@r2Dr}2^E zcy45~Q_|+iAj7ju{Wi}$^2Lo3(i_Sefy$+OJJ$4&ti}|rkkYmyzSS5MSOTgPE zX;s&GedPe$&jkk$VXu)ZEKzvAg|Aw@LTYp|d$l>s>b^>hA{kwzFN!^mMVW0RRks8u3&+9m}G|e=W z7%RbG?~HU_xcUg+QSvA1{7BfxCG%rwg%r7>vjp~uF9MgCa=S4o+&y`KR!K|dWdOUx z_>iu+)hc&50#X#jlIUSOKA^1-ZAj6^A8lJ3M&vn`oSu7+0Ki~qo=`a~YbGIJqcVmn zUj{px-Il#Xl60i)R%ml_4~WR)<4c?a4GKf!%x79(7%!I3Yb+?H}jG>f52#GYS zOlO2B>D~>)U}G`Mx!U~SOPQi22m%Qm36q6>peBe)5*4zt?rV`Q>@XdOqlt8G5A_~vl*ReW^XMN^6j}Z76%uvJrAkuo+*fqd*BBvGO4fJ^( zV08A|+zG`zQct^HY}rgO|rG3e`s^5_rX5boz!Q{e*;8=7*WF79NV%g_>p zDc{RCWJb>52`x`7^BNBJiSFOYsjUXCi?d6#ink3}B+z;GkXs`b^5_+3wBIM=_6dmN z*nT{R!z&t5BpX#jeKfd{h^leOg6s!duxNAe`%oVVv-SRH<{!qn0@!@}r0ZuC6b7E> zgTr}ZbghrVdV(m8m8P~qTyMXY8j#E+{Yc~mu3Ml)uP;U@QsfFh2JVM!n9e2BGIr4t zar2xCD98)-0lx|$;?%`qB(v9O^s{gkd)I&!8jhn(gYRQa)DCP9xM6vYi?gyH3?O#yiMueHB`Gj+(|PB9mz$`YSt% z7+yB1_zYWidZ0sc9ez7Tn-5=u zZybUn;BR0y21H~bygz9GrErgzpma&#JC1rQHKDUrv+*zf8AxzeTRXj~xVWRb%ftRt zVwup4R@Lx6OdsJgOn`n-Di>FpFXos0}OaB_@qg2e)e`f*rm3Q!npB}_HAeL{tSB8R~^R@ z3Q1BVOxvp4Zg_qL?T|^->N7mDI)~x)QTyTgr;#aoQREvnc7iBgHz{4qeVgYMtBKrQ zTSywxuWEk?o*>_ksk{RK5`UEDE2wY((kb%-)|3T2ErU;rUPTKY}a7U z32DlwxQcXS6tN%abnd3DND+d|k@*hY)M5och2K%Ne<`a|*&NO@i_c)o_JZyCd+$v| zVuSLrVzdCZ;Rjg`c>R&VxVH=ZWL#F{kO3;6>UY6U40G(be`i^~#CN=>{fZhHp{T=Q zw3(ExNwRQ1+nd=)0pUDwe~sFeRnT2W#}6M<>{wJVth0&NYx%w~W57S&9ImHi%n&3a z=e|PWHu&+y>AGXPFQUKAw&nMl4jy|pSc-Q~6IOB06jX*j#C*%5;3|qBTYtvcvLm|; zBxhQwY{pvuNPH-HjKri09`7!1KGJz^nq+5E@0j73h?sP~W02 zw+82!IR?4lPAgd=w6)G{@4k$6P+gi_tmxoh(AaMDL>#u?tM0q|jI|o540nr;jAscJ zjf*U+Z&ckt>K%{J;c~dwWD;VgJdPSQ?}o^d9zdl2>}ZqPn(UHBU&D=&EzfW z{19p1?TT7}m5LnHqT+;f&K^hG*Nw?XfkKT5q{*MUb81Vl8|aIwHzr!^0k)ki&u#6Z z*16unz3&tSMpcKW*P0Ldco{o6WT&Gm)YBv35Z&^P)#g{_p9Cc$xw+nMBx}wIeeMV? z!1fn;ME|^KE*h4Lp#XHCF;qWt&(z6Ha90!NFyl*wWPE3{1-&LQa7$T0j`9T)qv@PkY}Z@ znP2)Wx6=$kCOc9lb)uLv_%&}yzs%(U%necI${`*N4IEIQ28bO+_9hYtq z%IVgvJi2JY03vp)Gnr8R}kA=V6bn?t(JNsEV z(H@pz%J2bunzc*O(5B(p_5Z`(dq*|3Jz>L&APAx;0@4u_5CoJey(mShfP!?TNGH-E zG^r{Gh#);6UAojr3D{}UOQ?zT5&}{J(vo*a@9$o@?^@rtzO}wT?>}b&hn(y^d-lvT z&&=$DG4@>Hk#<#%cg4Z)!J&8EKchO$avydx3|-s?Z2bAc&^}^%Vea!WsOE`6(v*TgS6Q|XN z5w`MON3u8F%f4^g-l6f;-(*!6@kM_5oYIaYFFBuJ0^pk6JW%p8-BQ?!P`~3nO~V`F z=FnQ;cEX9hO!R`m0{=ID{zfs3j3XP`f3DazC}plBr*RSVodEMzym6pGje#eISyVtn zM*=aaaZkCR51RYMJ!_%z=w2=?Tu0KA`lHk6HR*lOt3 zn3J=zXxE^q{d}rt>7KHC(S7o-HpVJ-1<@!*=I8;e=5(_^Mb=#b0qWhS(Q|nVk{Orz zI_sl@l1m+(7oFWYL@l-!Fe)7hUqz@Z`Ph}))-*NPglbG{E2oYq&#qm`;MM6BmaTv# zX>er>_+i7&ZhF%&+9iJR;-#zVn z`Rp^Xv8K+g@pV4_YxA96M=Xv7XB1-3YB(rprO{p5GjF&EzurcpBz3ugQmLxhn}b+b>%V628yY%9)KffsDM13oA}L%Omxo8!C?Q zV`rnhc>=K(+l&`B8QDt15U@&7>7i8V6RCB&)0(PF@gP-9WE!Es*5%9 zI>Z8wFE@yXsf6{ch4(=7gQli3;_?9>(lD}~M(v0N3ptjudh-B&74m-H-ep3fTD^TIJe`U?B($kOtf%iQtN*^*Fhw2GXz z?iC8fSM8lQDX@d?3h)3rX(n4&;P9}S` z)3W#nb8i=___uCK~{AJpj`(WwhaXejp`I~V;k zr6XoLF#jM$?d`8Njmix2o1-w^8(QnK-oqVnZI_<)<&9><1Tm(mN-5c~#ygvM9Bl8o z)W?)pub#csh(rvnIu^@lkr}__N3jQ%suhFxyeB#TKcCe8{uKMU^B@m>b8#O;0n!($&F!{pdoOlNH9A{A z?v!>Ez3!i6ma%q2`p7l>uDOeQ$zydPBUxSBY@4ZV$BNRZdnG5Ql=lX_lw&rKEiA7Vj9P{eyw zt&gchsAyJ$qIB2c5q^nQdNfZB?%jLCa_qHYdV_NicNEFetb6Az@;W;?OE$-|QSt{{ zq72VIv!7_yfLGC#T7Z{KaAn!Z&|=u>h2Zla$#r|R#1<~bg>W`j*TzAnQg-L$_%CMI zarr^%Z=xT%yZGXIY(d{qDpf2>h;JQM>v&%!l-^KgD?d7SGc84U!O2;L0?YfuLXP4h zty0UWQw1i?K44vn+m7xwthn1TGwjHUH+S0#RdyT+VxhZ$%H%d!z@U?s8!RYTZ?fSl z&qd!3!qhkK@W}H-2vR)DWt0;fz18xcz8N+a~aWezu=mkxVt3@cf0-iRGKVHhztqb+F#N=msH&N-fSb zaoY-$NaJFb1va|w{qD=pZZ59HSTO@0(C=?NV9?E1l+Vr2>iESu4N_}#$5unl@5?l# zetybPLb>r<5{)rkzbwvQ+EuOlVudG;uk2~7v9DT)So2~ax?g2^Q2kbgl4M?d^6ClZ zGn*IoWa1a(rn-et+Z?2K+u^)GCiB@&Y_*1_7DgZE*Vu!sKpUV-0>|x^FR7f&+p;C4 zv|?XZXqlCF{AZ$dew`c8Fm|v~J%8%q>u8Fl*o!MVym7PDby1x`YytgRH#fFG#plUv zNYoMm>WM7)+%xYnhD;xK-B!!hhct6DG(JSfj{o>J_ArRqbsMmA^=4oXD-rjw7OCuL zlg3!FZ_c~b)H_Xh@fPhAdo~tAg^4b&F3i};q`P#>^LBB*>zC%#N7tS9Rp(|4(f68p zr0N4{0*ee@=v(iGF5_gpKE5%Wm((yw-osMbMfUMuD+3+t_4t6cCZ4lOnDfuRiMb+$ z#JAUX+sbmcl3_H(e(~pR9T$HlRoLY6hYh)oR4aS-^Er^O3|-{Ae#0qXK;F1QJ(w(# zFT@~Y1m#^NYwp=|Pzeh1CzcE=R_UrO^5-v?zAG5aZ@f!SxwXI1oZ-lg>T4nUc>B?d zV}b##WVt_i$k3o=+k@ENm#@!lf2fD%*O8%ZptoLIrQjU)1_f-dOV6X^p}1ZWCnY~q z$2L_GGvZPAT%Mb2jZ$b>u`m@9NMOE4A5^r^1(p@$ZiW2)? zx}dHcO=4z>z2eYhEUX)<5&8X6Fyv?w-7WH*saJGqv7GpGZ+FEWke&^ai)5P^-iqzI zEMQXShCPndu`I=_KV)ikvD>r97!R7}ik+ZhD7}a6>acFH8H0~xn3zw9o-fGL6 zN=lC5W$lkJhbkCxzitLa!AP&r)X1d*UT>;ph3!}`$*DdE<1(+72+wiZTeLSk*i$44 z^9kEonxlRV(QhUKGDGru0A1GD`x3bLV*_IlvktX={s*aLlN}{jHHz7z8Jw6K?VY_N%Mg&WWc5yj9lj6aO-wX#JA{D0goaVqa&6*Ap8l z)?7BRu%Ax6_e5}6Q`Z3%$o(nZyQGj&yYOtg5xeTP5?;9nG`}2JjjGb#L~SvowhWQC(-Fzm431q& zY4)&r-JNJ|CE!5EYF4n>bqlA4YvPM{6TVgKi1gY@Eocs!u<+1PpJ%n@ zw&8WI$J^xZ?DpG^(N8?7e))J`9LB%I4zrEI$}T3|b&Qf(Y_({4xoJk5iaT{@8)dwO zMvEth7~Hv6X;~VOl(sw3$jv`Kxcvy3%TVx5I7xm><(31RXRt!y1tKfuz@)AG@9O2( zpTQA%W|j@yRgs|m>p4T=|Neo3=ctyGFTRX zkqVp}BFqDZl;TT$o#gLR!TxtTDvcHh<3(fj_NXp+6k?_LPW^RQufls$VlJrKzj_%Q zV37t2O;5cet<<=w5V!JmICvK3lp7?_Jps;~=qw@ApuJ>EYzH7Ab}fN7s({zY-u?9^ z5%4UIt0X^@g0nzRkJ+fG$aebR;Goq{L2`hT7M)<%4T z%gm;-ff#s$3!U64P#ONqNO0UF1?RC?ezou}>U~+)fh>_QD-ZlAki?SBoj9C-a-lYs zu_wU7u=#g-?0Vkkp;wUr_LKdlZ97x`_a+gAWQy+=5jhgX@{&e3GohSraNEl(IW6a``x3t~5(i3Ex5Bz5?rge6$cw35BZJ6zE zGF!J;rLCHS4QUiOxJXUC@6(2LJ$10*qER?ZbY+iH<@BEq12?)zDU_shG*=@jlnRiUeP{l8 zn8J}@r*n@cg0*O*nB~cwL=F$*-D8ZG_0*-Ri--OU9@tApp`_~FR$oV&RaMqLeE-k! zDR5wa53m5CK62#Ho!1Ivrf@DQ4=W?d!%tMmqT!%mec`|jE|Jy}f6NvP@Eqm4mG|5f zu#fFIyoVmgK}}LN7H2<97J2h;>HL}+Me-5Fg~xYziIX!9jBssLIj8+r*2S z*ReyIqL%d-bIK{C=W>Zmq|zY?^>KW!XHAJPd#!e8Hb;UVpP&glr51h`T$C%B4-bKo z?3aFPKbX}$cWC)u96yT0wu&y3D03bXCn%$0&P6r<0R!*ZL$gufxKBcwbxbddc!^sE>4!gL_d@9?l69CgOaGqlx$r;t z1VyeQ*c8Il4GM98{y!M!QCgzPQC|8_<$i7d|5WZjl_Od?DnFXt)o90Kdhv(180oFo zJ|h9bP;X!aY)xoVYpqp+WJa$4VLvGI6dpLL(zmNWEclnnOQ)m>^J-6NdUYlY*zqPE z_DfuU7z%|e!5@c+9%zUsc<0b2Rj?!pFJ( z1U|RQ`KF!Rv47oYI{~Z}x1p5ApHm`QpcndJh}!Wb={IPk_=}^XRSsKVzTf80xH$gf zA!!AZFaS4n_INy zvP*6CfiDYQAo|!|jR%5ZRs{Q`VJ|^kWkD1f85E3j8uB`&RetAEX)NDKSdE z9hF=El>TMCTmFI28YwYi;D}LxZ)m^J^J7RV9joow2>m)dt(5*H&tNdJZ_u9yBihMg zdptJn3}me&u(Rq}Ev>ZIO2Vw8_~?fAGeBUP+xM_E{IvLFJG!0+@HHo46G`ZK}_i-empCU&G^QsxSZ(2SI*<>Ns?uy z@!|ObJN^4M*)8>U`n9Z7+)a;Q2|{Ll$19B|c2tH1=|&ud?2T8CjB%SI0^NrlWfX}h z;iOj3Cg1r5iDvNbyfWs)0erE;u(|9!ZD4q;Aj@3YB3OL7< zIeOP&10Z9yl|h86LbGMG3meyCg-LoMmKaZ6mOZ=_kEuY^D0oifJ}YUK^8V4h@gnPk zxzhE~dD__tNZ?E7G4C*eK(DG@FY7C?ky7Nmut#6XTcil~RwIW8wFq<;8EYY^9Ca=( zRt10Mbkm+zzO&p|C;&ayC65_S^-=rJR-IU%`d;A*zkB0O!0NJf5~FZn#5k^5Xj(9{ zQ)t(D3j5^vm)#&jRHLYM`pt+pmDuyM1lSqIFma=6JJ~HZTOV_FI*@7&D~P(EyeRTe zBv{oPBE4d3MKg-dZ!dMDFS*Cxed@fxr@(aPT03zzs>bQM7)?gTu$A7LXw#m`ECfwS zCj#;X@%Hk`5FViR3KtlDz?nT1LijV7Ii??8d0y=HX{4o13!64(v$86yDaUr8F+N*` zQ*PFB*`vvIhp&b7j0_2Om7;uDkCIZx5~KOaI4hk)U=7?*=XjyGU=H_4m|j9YcN7nt ztNi6W{))g&VW=N#uSyShSxMj5n!9 z@~hm?7)pKwa%UKmvh^8l&o0Ti*%rOj$}dq1Pus_Ql%E-ATeTUTtCA(oqxS@N_F5q^yVVKpzmo^}GiTX6PE)UBF;_IA{l$cTrSH$C$*`(<^^pN4uG zoupNEq_JF~J#_5}2^F&CVhn6p8+m>Kmmsqt=h3S2EZE#pB6bZX(i-5~5DpXEJN?_N zO-c6h27HFf9` z%@eOR98DIMpX|1N6&SN@s=InTi>kkF%tvv-$&sODpJs!EgyNhOkv~u(Z$0%d41Jw} z;*t`^Y_R{iZrp*sB&`>0a|(9?tJa@p5l1~o4_8d4Ad2{jRtmoaV%I*VNWewO$W~PH z&WcQP-hwl^=h7M;zK(h-3ok6WTazv0-*%b1bu(6GA0<&~H(SqwY0G5<%lsvhKCVSj zR%^+i{9-pX3s+77A>&qBS1plWU=;Ws9@-e4-r!M#cztnQn*@acqAq=aeh6<`IunLp z5>wSWC8@A-wPj3&9BVrtB<344zCLQ3Wkb~I)1o(zXL%NsIgQnrcy55Bi}{!e*@E{az`p0L4Vn zWU!lK%e2j0_NzX`>LY34YIx?p@?RzcBH^R4NYO3T=U!5HSj@X8Mc9F=X8zJ)TI<+< z>98pksUXD!D6C+7MEG(-61KgtCw#Cy%q7iT{qm&IQw|SHMZ5C)n4+p?|3};5*@~qg z$pwO_Mr0)x0t`YemTD}DxcOg#&A$!-i-YIrKKT;qjDn^R?y3OW~Ohf^#t^ zZLp1Va0Iubgv$v;hSur*;0QaQ38M_PbinNWpaMkSDF>QSk%ryp`EGl4Ji`U6DepZ_ z)24R~wf&L+taR_Q7g0+V>A`N^A9L%B3bmf8M(4zJA4UsC#qf@)O=eovM)CRWPRZ65GYXy(E-FjA*|8h?w!8%0 zDApo)Hmpn0(w1~~TtIPQ0oP$lO4I5>+)&Fy_c8xkX<t#C!F z*}*K@v&Q2644f1&f0|vG%Y26`&T+Iz7K?)0Ot#Botyu3iwp|cgo_#vtTgK~>mE7V6+j>HC7qt|V$2Y0oyZBE0kYXl}&-J2@ScB|`iL!F?WX${>< za@b1{8#5T#Jy@IPW|X$dsz~NxhC4-FNt`E|++Yfy$=9A~we2{e({WASW*o}j7`8&_ z9P>VXT5TVCx;lF^w8!_Li;%R_C1~GN1z#P$uo|75YL(fMBzT$CgvDiE$K>re%ag>p zd-*AnD}(Z{BVqC%S!n4~SLYiw1Ji&tVe+O!W)5n)$k`$xA_&%MHXRT3t@C-S_JcnZ zB&S{<%v^QpCYK;5g_#wW*-=>f&LKUhhA?5i<{b$mrKWswbXI!htHotgP8JQT(s?FFD6Z-egLiPOXiGJME2C zUqZGg#m~16TLi%|&$e~UW4lpOm{jpMwU;o<7Dh!W(z?sTb^UDUq%tGOSpT%`mCB9A z*&U*FI+p;P(N(8*)0BrRDn5QK)6TBD0Z=5N>6@-cw&Fsg|GXiuzMhmQdQjW65(+y> za5axvKV4c;E-GJ=2$NrKsoT1DuI@$I4P;(?t+yqt;JJS$!8f;4t2}TiNU~-6b$UZI zLzs50nd!j3L2Gy2Sn6FqwXv^HhBvyQr|LhWzBs7`n6sH4U`Js0C;9n}IJVScgfYXx=3}0xoz;ej$ zMkG1&-s0bjtc{*6+b|h{1`UkQ{WNoLu!5{-zFpnuj1_(#R+rI`50mv>7MLa!D;6*l zq;IMmRKAy&Uas&OmK&{!UJzin(qg)U+0_gh>t(CcY~-juUM%0VYPm;`^?$Z}|A$l) z&U(8>h`Msm%>%X+r#w8bKQAQGaq<-A$hMG=TaHv8Vxx`w+ub4JGmoc0e4XtEdf{U% zW`@wz-f_=_^n39!x$Z-u0hWkw{s5)FFMPbsTBvA8y@v`=e zC1BFJz40ALc#?i>nN^3({A3gN5f--n!5I4k*4+4*`jQ+WRc(MdMj}c#KPDP@H^udQ zk&46g%*ToMCa%rNdM(-$Go+QGRx8T+c*dkdz9aD1Hybzz7uo|Y#YMQ_2{iB-qnq%pz`MFy)bEL zTPHRRL{_Rl8BWNWKTwHm*mkm{7DNi8IO7X+9-slJ@Vg-IFn>* zY;P|3w2%ZfV80qh41*(rJ!J2;zv7#`t2}H$ebYN&&dR9K!ED%{5Wiphp>f)`nq$*Z z!t=$DDw}nbBjGmsEmh2Z%gqC=&B4>|nkMU-g$^XGz4>@Ff%EhxBR%#~+v=K;VG-8b zxuqp-le3a-HHaB<#{35Gg6R}Lo4IhN2^ay15M<(s8vy2F`XH+@X+ewTINx<%qxzTes`E6*r^Xi7dO znfA+`o+3IZ7P6~{6ILL0yhv8bO))X>Jb8QIRY6CBuSOpFjeRy3ZdWyNFuq=@9$We_ zEczbnvp8|)+Wkx2r&+92D|$>O{NiJNz-3va06J7=E#a^%#kK}6W% z$;w!!1&-}m?dPb8c_U-n=D;W$5L_af!;V=nl=_&%KrwW6Q;WMt)NK?ZDW?SW`*z{9 zX9cE*AxJcHHFHjYmRj*{>FuHCP$R9)s`B`l^InCE6c!Ivo^9#iPvKSqA~c#;3&PE{ zH?8Zv!WMF2oKmSZ#}^(77}={H>A!DgFS1mlUGE~m z^aE4|d24ku%X|N6`X*T{ zXh>*5{+e}@V{_0}^wn6m?1yy(L}e#v1|d5+3cPZE=fZ0!4=2o{+8XgwS?FtTlpZs? zo~(!Vjj=$pj1_jVlQ2+pl89yP-k=Q|it=(?HbISxWN4!j|hT zyNe$wR$lGP?-!ynXx)iLK-m5E-#~f)cNPF4eWIj^NX~58mxw39of?~aoh${|LCh)` z(u116R6g%=z`*Nh;_;4g$L~X=nfKE^tGwDLH3wz-I{g-Xn2l!@MG?eI%VRn~4}=k+ z_dmcG?7@A?<(TMXn#H@a+ZTg38Vp)ik+&lwlySKg685%f5yCiw1y9F2L^ehM%G}(j z3FXJNe0vk)u9aLfz4oMojQdEbA}yrvePqnz>Ht-r^I!aAY4K;nw69Q@^?6)RM{V9- zd?-~`e23Snc;#6j*DUOTzS3Z_9nGj;XbfK->v#P9CIBB9v1?zeVymL;&l{_LNEh}l z+!o*428ZKU9kn=c^7NZ_-)SEgzwYMX>f`J?8?mL=H(qo*)C5?k6I5p!D3lyi>JMTA zuPdQ8q92!T;0WO#<_PjN{bz29ecqb?TDtoZwpp8OvH4DO)1Xz#VZ>ADbk{ZYLi0DT zbAZ;FYwTsTngs7kdo=CsNJulym({H97&eo~NcjZy>LQbYyn^olNXQ{XQEIcqYc7?V z6j&}Ge8HGC#dpIZXsokMfC7eI-CyUvB3(OQBVMvsbwbkefv@`Xa25qQ; z-^9w5)k4#O`ZyUol@;WoJbQEk>eDvMo)XoipB$;tgwmxPhF2301#fSt$n`gnm=e}s z^jJPSo`sNDaE7ukOOGFah49^l-~DtJ>`OdOENIT!Bq_3Bz)uQg5dABFKnDJ>KgR|!~3{6pgQT#|gN$g!r=uO?d4 z9rqT{3=tWaoeu`yTQ6T>#KY$nCw^>x)PhN+TJ@cDx2@LP)^mEFeuuIwPWf` z2z8OYb0Oaw@Y~7@BsSgVv9Dr1B=2gY&APX@*|^!$q%Q~)0bK>LO2g{aCnCThM&*BB z&eF9;a%|c-$HW1~=e%cT^@gtW1vAaHAv(rHPu+|TPmtO>tpvFSYsb@WIh0PmRnOlT zWsXyyUu;7Y{3hey(zpvNF8IKI4&udK*WhrviaKylv1yq0Ilf$#)sUA?*ANPC# z@rKfn#G5;Pbe!;h0z3&$WCz-w@xD3=;JI|1!IxtyI^DXpT|K=SVkIT|Gp*O)$pMWn z+j2|JS<_^%G9_4fph{*03rEj+X0LNBX7hC|5;O?v0`2m&GpZRPT(MV)(*(iyM@2kG zwM%@2U%BMQy#`jDA}{Q&FNcANL~wS@5DS!u0B$U_$5GrVE}DB7lgXDVJ#VMbDzD5ea4m&n6E=7L!2UBu z8)_G)EeRc$D+|<;#<;pqdSyZaH_ho8oUfXtc*_vonb1qb`i{;`)w&q*XrFbyUg;x? zUp|0yI`kHP&M*Dk|4iqsylR=-PuCq_sX81}%leH7+Vn1gi2rA3kJP#wxJ2?`5hHWy0`Vin7h zbLqNKUFfS{dOfdF#N+Q5AlVz1p5Jb9CJP)I)B_#c-CzrlZ`nJr!C)ypH?^rP9Di=V zVKzS%tx(8y5gqWMEbjj3_+BEb(E!1mU}e^Qop!2kF(*#GBecn67tBBv^K&a{mA#O^ z@)N!$tt$=yWv64FOeIkgHO~G|8y{hfyv`8R@}MCBKZDBNZq$UDsxGWZI2aF@D72W! z|4McUk~KcMZB1h=9Y;PMRKZ$jSXE+}dLMg__AQ9zyl^md+c@acDk~VB7`R$${vxOU zfB|+fDcwJTn&5xkEw#~S!e}n>he_U!bNSe`jy?4;`5>6xTRt~Y`-YHa2WNST?52C0!GPN7;i9Al(` z;06F3kBB5%*A|C|OJ;;`$53+A-LFq0#yAUr$TOd(2yQn4)HU`g11_0g*61-Y;)Ti` z(a7!SKTs-funS#mC&nFH-$C4Q726o53jqf z&SThOOHi(X1`lgw#v}=Gch)wCIw|fG(*U{m-V<0CPb*;_4hVZ^F|NO^!=%4Gh(;zzfCLjTeK_)RRr%nAU zJpkVU3;M|FC)m_g!65=f(?bQqZF=bKBmdatUq7u2yjW9QU^5$QB@O@fS_jSzPI@VLFXz;07C6my4^dpy?DcH_65@` ztVRKTuk`l2?Ou(s)*T+v>Kwg5(IwjriTTzSc-&$oQxmf!R-$h1i(*!i-kGqbN@v=- zjs3*hZy>f;KOVg&b_Y*Pt<)6Vsb(ET<3)u;0ek)aJ5E!YE>_D~KNx`3;0Am(XJ}9T(I?0vKH$UEJUp%-Y!ERC9``!= z`nJ2wE)2Dv$ubL=$B4%9mtO1cT!-2V&=-E9)LXDWZNA)smxO zg=J{E{Jt>`M{=(~?rs%TyA>-z^EDmmZ);9FqtRPF#aWjj0}ce?-Rr$T=~$akQ1+`2 z9$~AIw?5f03HKKsxISsqH_UKhKTUAWIAOg?d4Gga7jJLl!fck~<~vgF+)(#;F|X$= zFvxbzN2kKkQ=a}$D6gK5x&AhFvw780nqTZ&M>%?+bp)v z0IPQh1^C0R#n@1B0SQ^*;7PSA*2YWgy_1r|u(IRbckJCB_Csq=9;jmGlgK(cVF`2X zxBC+Z(3doc*rN!b`iNHG07Gkys%&tyWh_gmqu9iaiqgEg z;X0=FaOE2#cQt8@SIrB6qjd=wM8(ZFQJF-seezhcUg^tW7@G53A3K*1(oUnHWuspz zx+YfOIz~Gyg@mfR`8k1@wQHz5tB?8IG$)q4;;7jCEH-6-jYO0fNZZ+5J^d%z09qYv zO{(=hGg4$9*;XOdq`_M=k ztKP`QeV3xZuKvXSXl=-!_RpJ0AfS58wIz$Rv(xB|UDn4h_3gCD<^+Gi+!k7hU#!=S zH*b{F;i_$x@(5|XYUgCvycrx5=BtZQacl4O%*|cw+0v2kGT{Rhg`m_~iC?J?%A-Oo z=L9H9XVE@eu5MO)b6)x&GvXq6Hib=u0=pz_L4|Q|A#-y=9CIqzbcHwai4_}Mg_mO; z;5j%m$ne`(26N~hrfuDtpexQXP@#OR;W?`P9>hL9^Rh(R%^~d4`Po;qt3LzwKdt6= zOUREV3CiNm?`$_~Z_;ZlK|&ofPKQtI!?qSFlp6L=UJ8Hz5fE-Z#QM<@wy?m>&@<~R zaQWFnl-cntoJ{NKhoq{A;!nGsL2VWA#pZYM-IEhhO?#+Vc#a~fE2r*BQ4a*!@ErCPOBF0TIJ;e+)sOko1-=Nh8>uU>U z-uPZ;PaLc~=XPw+ij*`H?z2%;9*Ep;WI3_28mm4Vq6)xqrmyE|v;y`maWybQ2%Y@8 z+MKtDVK&{rJIzbsNh8zT!}tYg6?WWN3OLpeTkltrE~+!vj?c=Hw_bPO=I17Q@l;~= zr&>7q36Ws@#WMcBC+VHIrA4? z6}1R}=#knz_@4?Hox~H<_FhEK%S~Z6e%vK3B~J7pzIkE`lt#2Z;R*tT*|ci_ttnHr z^t)V!&?Pk(YNm*Kj@^M8Gd7NIeOhmrVY=v98KEs*u)h6T zWZwLsZDb(3A4AWQaJQ*vMEYP!(C8NF|h5$tNsG|5NGMBHbPYn z>lOjeP-ud9$zoPe-+0}pq;Y+O)a)i-l8``7X5Cl8ja7JaEte9;ANWC;a(zzmx>D(0 ztAsLDRsMe64oj^ixw#R?Jj)TY=2Z_-5!OM?f+D((_BRFI6O{J?1~`P`0k&gRv`fm& zYFw6IRXh^>{ja76KN={=u=UL@;$7wMnCVD@*5S7`X58!E;l<*~-ZHU6Y?~{BS+B$Js_jRBn^JVw?K+sdp5r{Ck+H-h z|7`?!-~)}nF}ve9`izYkMOd+|tGPiH;5aPorNV~4HNXwO`;Sf)&l<*>3Dy)FRC|_q zb`sV39kJEIqe83XU;HmXuhvd9^@~|zGcXsBO(EgY*WxNT;0E5qMQ2#WFVpKC?&@SG zZR~a4(GJ)7#b=8h8Q4r$m@R46Cuyr`Ptnh%_ctuFdHOwNE$~-O>Je+fGu^4Mv-veQp;vKbhyOpqq<#eH>O z-dcL|P^#XjGX6MHJb6qOL$K)0k7pi?Gjwr+STM=BL@YSpNFlmgVCO$70$f{9Emhwf zGla?HJf;DJhY)Vm{eT~Tceg$1@&i@x$di`?e7eKk?!XRgIwJ(UMC}3~pvc7rRVjvY zSl^e>P4gkU2xv&>rU6sYYQA>XqoP-T47{>cYp}wMOo@KaRpcRTwjG0ETPK!0pZRL3 z4rzL=dyf`yQDApP5|;5*GN3^WY*1o@%Xnzdu6>`bn5RdlT|CNlK4{M6IJAHTwt4>g z2k*&}DDmVnq;v-OXz6Ujbveuz3+VRKd;PL7?Szg|7AuRU@@=H>{mspLQNo~hfaVb= zh(>3;0`*o+bGU@}3jW$4H)8pxq2`XCy3M6^3AK&WxE@JK);#FG`(%fmbjctLGUIpW zz}jh_J1&;!p6Ww;yuBSRCBf~TFso&RfXky9HpBv|b$(($3K~0k@Gql60o1{`cy1U< z-s)}$ugYQKHonUg(gXnX34s;%6y7)qyZKRPM8sFtxT|rvbDxDtv-*Mj>Icr~o1YgQ z+BdrbO_~6{Q*HW&gPH_w*e735Hfz2 z-(6ah;0EPKj}G#wM}2baczG8yBkgXYL`YZxh_53^P+m)_*6zN92E2R~F5mu>G3q19 zl+?#>lQl){Yfq3bfxk>7;~$FfnzrC!yNt~6E%CQ@X^`A+sRKnPQahMcGcFB`0Ea!ax&C%pt1oY*Ma?PUs5#E%BCD zT+usu+~Wgt3-z_U2c`L3PF)skY+GejL6;csf9$yw#ZdL(2kKKn>-&o4xp#JDk#$tT zsNmO1DKEFgd+^xpUpiJgHnlD?gO>PTWf`$%zk;JWa7m6)WTMtN5FNm9jJ57vxV_NC zUir{gh>@Afr#`0CnDq6r`+R%vdrr5xbg&W_j6+H6BH>hE-0TySI~dghJTu zVhBu$LyLe&e91m9P!qdD4)l(f_h?YV1vp1F3Tq4e9=7f##1DiwQs^(lhc#w7Gg z{Wh!|k%UD{d^2M*No^2=_LI*^Z%uAD;WFlSAj0Bnl()DkN-?*#>&86DvuapNun%Nc zR)*{J^hgfj5ea zPI|VO7%DcZ{DM|(?n!DD*~&LQz=@TLMYyzFP?qUstzDjht8yRQIA+s7w2&i<_I}{F z=)bP}V70dg7So!YwG?Ti5w4=LYOnMj!Kw5^wKmu!no{m~c9@Ic(&F`W>y<@AFyPLV{`zsH$hcUTaJ*Gc?l4p%w zeu8@cOA(L!rHBH%-w*iO-mk!JpbbHezTPyjdBc-cYEU>hvz)!zA4$7We%z0+(c9YN z9`L9qaIcj?R(GxdYNcSr$48XY26jLo=CZ`sp2W#TS;JP?V>? zL|WQ01Eo<@;2Y|dAl@i9w!_MXSt#_74juX2w#zdaEsm!EcL)(rc)(kpY#xsXz#!KI9 z+OaoZsFQmtqvP${eN@=x>&Le?>+2Vd((c(@{0nTIQYy9rhl9_&Vjdma7|JMS6ERHP zdYch60ryY2ZDKUf?m7{LviyHl!Zo0TNg$2ZI>AtVmfHVo8Z=PY7z&^^ic``&%1e5$ zHN1Lbtqq^Eybu~!Zqx1_(o=X^$&q4d1>Th4I3`vF9~Cexx;fmUs49w|dNR^CeQ@U5 zjUE*9DG{EWRpHFFxhI3`55o@zW-RQ)Iis&G*y zZ=0n;<_FM;ZO!OiWBRgvkxk<~x4fDCMAcT`7Ks<5cljgc{7!oinlqaeGOp#seKW6Y zPwTWGnmq*~%I5?#p+O9mpxg`!?kU;@2*{&%b^{?y0|#fvQVP4pj>xzUS+3^wSWqiD zau^rH#5VGa(3e)nZtUq)iubl_h*Ds~t2WQ)a9J53Q%-wsIur}-cdOt>|ci5TqH^~S{D+HGk+niEZ&2t_IL?2^d2+EBoC1}g!lMC?#p zQCtAo-3~+jIkoLBo-sf!+acu_l`EiZN5ty3ZAx0myA#A&1WHHKWy!9$9s7w@R!qX;Dwz&1aeht2=PsBO>gv^a!7f z6GWS5ca-35O_W9kz!^e35=B-L0zlKo=Jx&P{V>BVC*NJ&9dTTKO(pf_lPkQ5Z`W)w zb5jYXt79Pm6?kTz4E2X2VWw&?8JG!PzOl5_O1ABFW1197#V|aoXQLIFJ|gP$p0fKc z!A10#@$<|&H5Y%Ir$OSxy1-x-V)3>l<^98bQvm7TqO?{9V<*e`JW}LviH%HwE}gS z_8JZi?q5cuvz>2~^pF`jmM|YB?Ylq|28QJ}J?^|x$@B;*{bNuRaP+AgJ!9V}dZ1?# zQO|V9r-m!~O`U(0%g%5TF_4C9<8uIz{|v1Z%1Dgp!ZNm&IqyKW{NjQ?Qz|jI&~3315uDI(b>5VUqzj8_ z5_SKpHjqPzB)y?CiU~v=M@e52o6j@@seH%}kKqW(Bxt?`6_!DqUh+8`QhZUYYre#4 zfT%bwCDkDEKORP!wUPbRkBEt9hz-O2iO;muQo~;bpMgI9U!wc_qNd5g|GPrCLCEgXsOx#i(oUP*BJNABPt=SLme>S= zozHk-)fA+Hh6EI5+AG<{kt!_7Zc6l z;lVKXyKDNp-eZu!7c*i2W2Z48maTf-Y6O*^hjqb{m~tsIt|)1I&uZ=U^wgaX6 zZh%;yjg^;}t1l6JjlnNZ3hFg^EbHbY=nk$!3PC|~PZ$!55V{+5La9I{HGZ+sHUHdi zDNrbFFcRmi_gCM?CX|bUbt1g(_t(BV_kFxnLu-iGQ~jCPOz_<7Z26zcNgUscWCa!S ztk_cT$1>iY(uJl?9+rMqiA;Yn-6sSHyPd2vpSez{+ZmbJ;dVRSOvWCQ_JBKH+ zg8GD#YIy_5fh9)TsE;rJbHSNb>k`$(@wY;D6SZ4}6+%2B;N@AOb{9ROKirE6o)xL^ z^>_CMYSAnBoWR-9&%9~u0f`Y=>0oY^PAri^67sBt|O3Q5=gwaipk}oqXNWCO25;HktChC5Gee zZ!G9%b`HqaR6=^lvf8B%)&2(G|IJRZE_YM;9i{+*=5t0K8Y7_H0?7cIQ!2fMntqSLH<)q*+nXE4zjZenUl zeOA4VNP*0%ziM^1pxne!o8Vv8ZX*OhYWZ@H+j_lQNRRKU>3~C@R+t3UIUvNU{}Grt zd}t!PzkGD~jcCN-0n+fQ1wRJ>xXWT_?tEQA|1(`yujTQ}pi$@9u5qQvbSdVqYMYm4 zHtmT#6fj{2N}}=mM+Hg#G6MJIn3gI2)LIUjyF`oRaN*m(zEXkXL~sd(5(B^S%?OzR zrd_J{c&6Z$o^J46#+pQUwLRw1K)-6KU9QV3{JE$%Mkiv)1y(sF7f{fLI3%$iyq zs9(}6yK@5KHQxMJc_9~j%)SwjVpS#Ld3y!UL7j*8sa(E`XB{TUqCIycYPyVnLI~70 zc~jq(J0!3d0lzncE!y_6z+rpyk~mV$e5b^J^&|j}USSBhN@xFSUmeq411V8?nNbbN zIclcu;_;0kL&-VY>63pqAp9Yg7v{gCpMI0fgqVMX1%5hLP4uve5Frea<@;x$X(*Z$ zzK8T6YaF@Z9(HlJI}umyN*bj+l$1Kadr?TUL=X|fa)1860>{Q*$J;bYJ&gL}L151% z5w%|s9_>l24f$ia&S@X&v8eI&EAO7&xK;JPc7sJwigoxSDa4{#0J-M|ubKR6A^Q7) z@4(3@F&=f!zqs4K_c;;cQ2yDxGC1cO+a%NnbJg~xS&~nq4scYtX1Z>utdsZ zMmP^m@qHc;R&Iy0mDwMYAc{F$pIDCVmZ#pD%TTWKMm%kN-(uvQjmiK2!m45No9NR` z9hBy9iPlc8xmOnW;QqKx<)SiJ_B$p{{C|p<;|1eiDyD*{q&qZZ1x4bi1oQ)5mH*ld z!5_J3S~)x>3!7y9)M=oxWU+^rlJqRGniB9j*Sr%Cn}*6?2Ec^%|FHL#VNrJP`mi7% z%@C5(DInd=fP|FNAs~WuC^@vifFLc>B_W`6OQ&=rAu%A`4I}-($H!+MTipA7KkaY7 zdn zZ2)FZT*JNy(D45`$44p(@6R_AKcn(ua6Pitb^$Z63J%`4gb^Z@W_5Bi9}DO9cwoKZzct}4$%ornaD3X5cH>^ z1-d+e@k(KZNlOA@K!LRpd-xwOLPN8FsGE|5uJHbs_WpC@s1$@Ta{O4%_urR<_?s~B zimQCxJ;J~|sj{g_%Ri2RrtqI5&#e@>fA5doVtI+kek0F4!@P0g==Hw_Kym+P0Mvg5 zK>cR`)PH7<{k9tanK=g7+W(BX`)_0J2KwICBYKU2gzR>Q_|Z=FL1#JzA#5nOSVX4h zJv+yyfL*L_)1^!6uBr4tPO0n(O>t+#Mr?2IB}rvfotV`)fxGAAlI_f8*!0RJTWri7 z4vB922|TB`E(7BqNv~qt(P-xtenpO!f_Gyk7N2j@crV=qDcbe_ z!7M;m@V1;TBX{i-`8mvEk zHbBON0$2q+{zIiUpMjMBNa@!fzs6}eq?eUBobr@eUoz=^aZF`DTU0xJb;WZE z47UJAZCGr@F73z07fBjS-7}nMtOGi_dUtcguCu4Jmj?`MrzEE((tftO0DOZYMVdWO zA1-W!*BS;nr-ojdQUer99cpc=oB#W%x-Yh~RfcKQd`uIIvW1`Te%!n-Kb@LZ^{fV) zN|3$|NxlAfKf?3j$&^ykxM(vKr%v(Qy{Z?-xRW|)l9OKtMi);h9enUlMAQzL9#?z3 zINkbDbkd)$mc&>MKNE9cTL8d$)II_c1Q0+u^s|F2Y;_F=Z1vS}3#uaRl;YU5z;Q+2 zX|Po4?1AoOpn2Fg<`pk7u>$4l@t4W37sNHYt>doAwQw?y%f@tVn(6p~*p73yJhb-LdtNZD_3H)ks=GYCYrLuYO(9?PVU-EiA%ltEYOxh_uAuNY4&RmA4KJ<^_%WK|QSqf{JP{27 zmp*U^YbOmHg#2rYdk@2|(ZB4Fo zfGBsNXW#obLL&}7Y6uc?kXwW0uI?LkR{Pf2dZ$cZS#0{0&H^0bJ)~VvUHDq;AX696 z`_VC5lk;Xgs?p80tQVV1QfB9DF8)>g>erV@g9gAiD&3JDM;6&F`N!edkv0H>GrD;Q z!G}3BB8?5pKa*1cky@(PCHJ!hC_q0-D2?+SC)#bw)ij!OZI&3DG1as>StD{W)sDfZ z?>Ec3*`oj{HvvE=u&-gF&(( zy&tTCwIp&0izewv+O%2@rHcQKmBbe|UF7L7EV7>iS+#3;@iQ3#>z4Wfa{4<(lY zV{ETBck>Jqrmy6^33(BT6CzB=T$_Hj5yN5ewHHehyDq*Hmik@j_^$3{(U?_7X6(Tw zC)U=Y?RDp21Tpk#$#1|B;JsW)ih-K7umlmwiaOviGFUIxZaZXukrcFx^~vI~X;<|h zB0I}4DF?CKLWC*b?*aAp^!#R~c!4iMv3qFmU=6 zhU~z+N7+}Q=FlR1$-(%h>Rt5yi93vMNq~>9=65}y)K>^?v+f3Jych#IF3GEuebU-R zGmP@BAG-g1r_mSk({~BT^+!LJ>)w9hoo0`WA?a$0vN0;K#9#aja_G)F+)GskwM zDErc7s+G*i+4Fb6Oawl@LC?pH&KSd{2b8Oo@27I?;(KVE>ldF_p=HDfb97Am7W@1} zu&3Ed&2tj_Rnqd1@#r*Dl}|v*I&V}zPIVT><(8XF>f=_cJ00JB2G-*JV7j^h#_wHJf(LdaG*+i8@F3Xn<)Q-IY0N*3KoA4G{k}1M<~Xs7Jk&ZjoqA2Py#$IQJFd zeMA_mpwN6yb;5b^yV(jph$#*X^v&!Vy*((Z4-$c4I&J=pfWw>{-@4fe4C)oSF^FGX|Y2ChM4%VTGuI+0qp-WcU zMv1yUvK0_JMdE&A7|1)Hc{p%{5!J01Db?ZCFn=E)-y)4w?gPB4EP~FA z=Fvm@4GsUx5JQ0U)Z)6?unkIvo7T9}L@F>`>61;mvOx*B$ZLmCugQJz0iK58$5Y{q zw26pa&0SM7ca#kJhY)~x`_4M=jpr~`+mDv)%-~7+wdqiUx?AlqZh7*7|B$f4yQClP zgizJDh0Vl3ndq~M0#d&)1l^Jv4%GYbMtW^rXFHybRQVi5VBs~2KD|<0^e#W}c*=mD z`szBgR2rS;aTm%(%hQJZC>Z|-AZ3!dol;J~2+S|=Rk(lwskfcAgVZqeZS@!z z+Nc@?FPB)CYfJWLye(CQ4k&C~QqK!f3~=an1=aDpL*_YLxfGMqyFeI()j>hE|V`u$5y1(l0xpU%>A%=LAM|Sq>vXsXcU^XyU zU*bKmq`GG=cV_Qq>n(ir+WVva*RnG2PFy_`ktm;}rl&zk(Gx)Z)UL7E)++$2Ri&zm z90u&>^i*w&E(tkdZ8E)~qQMDY{&z@5-&eMe@V)yP+c*Z@JIv&mqPtKu_0EKK*Sr>B zCfd7?Hsig5lKnCJyu`~dL#n7&XkSaYq641djMDeAS0;PckR;fLgj2UvTLc)=WP9o9 zIT-;|01ouRr;yIIOFI34Dzu)jg%sb*_@ger;+1ckik}>x`{+*!EFXu!On&s`9Lrv7 z^LI9;GGSDCZKLVcdIWfJTU9Bi)iHE_KJ>WQ(_V6y2g+9V)!@dtw2Kzd*>zg|PPgys zo=S-66pPCl{3o$*S0K65*KH|`JTLo-%ckz(WvO_CIUq*7d;~f!X=BVeaUWF8NxXO% zc{{(qRA*NxL*o;{*N^U(`i>VrD*Im5_=}rccbRl=xRkZu<89)lZ*=d}ad=2xwdpnT zB$FOIH@Yq>>Iqal9-OTbHas-@Ko-b19{4nTb3AG#r#=8aEsr}@{O-ao!p4I=>6wob zcB+tuvtf;jzAMn&*b88t5VVWl_mc)I4~*%Z;tJxrI~3pmO>FVv{uekL=wdS#yRo=PV3U(UnyNMrjaE`aXxgRX!IV}|j&+)-> z4Sb9585HMuivSHrdS4FI&UN7`k^WAZzbCwdzO1APvWam zk0r&?1_e7QuHVNmKChocy>i)f6#(Xhq?r2Dtg%6=^Mdxa9ZXb8&bkl_c zhUdNS5#vrc04$UxPjb4AqvF|!m|P=RE-Be(L`NNY_4UdK)1YOC8R7bPlc-n=$*EYz z`gTJwflU7#58H&@JFBL`C{E_VxED48vYu=}yB7@>;LT%9G*)^l=5)HYDI=>rGwl+A zHq{pq4UhQHQzv%$#jo>Le;j$P{Y0y@I}PaU2iYC2WzW6H^3i)ny}C+0+i0HS{cZf7 z&aqI&>XYO84^>|)C@({VaUq=qzQXQSI_|r0Pe6eFYkbV6#J$sUpch+k%6&R(W6L4Z z`&e02eGtQek3^31Vo}Xg!sVhbklUAXn<9+>=7*;x{xBC0-7Ie<-7 zHgnInk-rlnUQD(Le@(5zNiMqk6U{NqDt^cKQ;K+6KliF<<%82$;i8RGLjNHjZYp}v zQ-t%He^hF5gN^+Je4V)2Rpq#7BeA12qP}q6!3dxeLoJz?W#UtwW848+OB_s7bkuge z$+sv+56O3}zBNs~I-6kw}*IiNDS#%Ah! zXX(}Htn;mzIZs_(Dcj~tl4;dg-Cg&+S%)Qh<2N$)=f#`DxMy!_Q|MClsqk$ot8Ops zM>fVZ&RvkYkoi)kyp-pxsquCio;H$C=6mXW$d;Z|0zbINtLy+>=PM`3HLV`-uAhj%+*foQ-uVDjYOADF>efn(N^ULJQ%TmxLSR7oU-9fW zX?<$EXdmF{)QezPc3Sc$;a zGEn3=HTbNP7^ijRJRK2J7I|Am0o6)fhzT=6rA9Rw-YmE9PZoBVMF^~Y2|w@p&V6+q zSdB67-fobHtYSf^$1OylSk8?;d$_^7jVh&|>eh7p(Nc)LNuxF*)I@r%v28oB^^5`- z74M%RmGzfHn=vxB`!B5EhdLk zIL8hH_orIv`vZ#v6Ayz#y1+~C`?z_FSCbDtRHZl_y(?^zzqn+XIM^+2eg&5@;fyrd zPQCNoy}|+2q%^{Tif$9m8Hw2xf&K!&EkyRNPZhQ5Mz(_{2Ed&b z>UK+}27t!Sxcey804Z-s>++__eYh5wB>C_2Gl7PH`Z#$WLnI`qkY{6 zBb`tpFPOhg!{AkxuP2iov5-Aei$usffng+X(Mp`(%Trc9l2`j=CATv)T;q&_@8AK0 zW*CPO1f7h3%#w@bZYfq$6Yua0B{Ou-rF1{=lW5x#+b;1v`^;;WNrs~?Uq3FD6ld&` z&f^HoHp&=|buk$5DN(c3?0=(ze%Wk&-epqx`O)bJ<5q1>pP{w<=Womoc*%5gmtu1R z6TXhqzLaFj)iTxc%#>tKOBJZDOE%&^is%zl&A@)ODXN^lN#*npSI;-4?xQUQ zSt{$dhqbfNW1g8OUAXyx8=6H7vE zavN~ZRrg$og!2NsXEjDc=xaeco-DuhuYw*ev8q!h#cr}gC5H>Kn|69%LrG%E&CS>; zPfP2`_Mb50L>Qmh`g-oGDjo`ZT(01{`jpRZj&CPg%fU}_JYiR?>`^%`ym{x08K#X_ zxI@u7BuS#=Ylaj@)vqHWKBaRT#s}3pC(|)sVqZ@pMj7wa0R$bSe)@~0LpW=aMx zUvo^D!UmZN^5@{;{aqizRXnSdyA4TB*C-uB{*0hqFg+#4*+JTE zFbRtlNI#&Tun$$(Bl=TgkzJbz)9a6&B*oh&#-pyIb$8Yg00JoYZ_;vRZ>nf;@xtNYw;Au#!P0H6F|Fiu}ISXb$XzMF0C;Vvpaw@@k(@8hUWUdNeJ|AzS@1vE3#EHXxcVXraBum)td7+nE z>n9sEj~mM0Q|0Dsv#`nEt5{9Q+wN0JKNafSMe;UQBJ>}x$|mt2hpX{y&lrQl7AcyKK%}S9WB4))M`&bW-ywv73RTzaTJEJxsly6={oD_iNFLPd!v9M7^Wv)`g8fTahf7u zkx#=d2Md)JfpSY5CUWsUyVu`E@wk}Z3WoWPcbfH6?#d&&>y>_I zccjBbG*+Gs@;JyMzrlK;?d(9};lfY-pV+0q7uR)zxP<;e`h<_yAQ@lV@&X zlIB3(ppJT)A}y7hg$YJRr>hmqAo1WQ&W8|H$SAa0BVW3NKT}5h!A$F`O=xZOz!aJg znh8Z~lz!mAUW7oo16Frdt5NIxENTo@koQmyzy?>e-CixB*6GRqm>j0D!p!uOHb|ATV?6oB;LueV zQqOc2r9k7RlfMKiS}74!Y>!~wI$@|lgLT(58bmkcOIlA)2bI$s&OO$7kzRc=*V#%; z&*0Ko`@%Vv#>=`;?3sPJEK-STCdF|Fa`sn>lP=Xt7EHo6Pzyy6hWC3C|K~aZAY1EV zb9Jc)ApeHTWx7-MMJnFJ4fPkR(CT9es9xo{w@sSU?3#L0!HIJCqVa?8G+C>KuQuvl z-6NbyNa$GN-8gBzBe~Y?nZj%PbRx*(3E@d(dR>9|YbuR&?SQW5kT)VZQrN33&?)DP5U5rx*xzK0KQU#B{L#zg5_ z)XEMyI4xgWTw6?|J_s=4vu1Ga$1=_9?iI*KZGMAl`e>rmh|%D1wH)L_pPf3fVW-~?9B5S9rI-FNTP03SHh|sj&vjE)#2pf=?PF< zti}Mo-`XU3xnC-9Hs}868Cn|1S8MGm@M*mVVZ3F=;oFSuV*y>-g|;z@>f^>^6d1V3Ke99mHl+^*DCanN}j znu^blzAL})`2qI&zUrb1ddWU6GT0}f4qm+0nXVBUFz-GE3a5V%IP^h^-fxKE8C-~m z?|!K^gB0?OpC^j1!E1Thlp*j;kp2=De@H0Ej|+Wt-tInY-yT&^$gsMD*UnMq9BXTM zFv#PKdb-|&Jm@73vH&TQZvM&Hl;WCAYV%hHWw+ynX;z<;H-u2bdayUH&g+1TBN>_Jy;lpogtjUgbh zwx{AYzB5H}&7&j*vt8fI^xemDqHke9C6E@sTipd`jXSV$+vUD_uD|IIasXS3rrTU8 zdz?)@0&Rl%P}&yKg8~|z2*9UFk=4#7$JA)M!I&9sZ!t}9u)-DR1)CsC52vS8^LmH$ z*p`!xsf;fc3e(1&v@k6M8zfEfafnArSMukvOj0HywhEY2e=OI`cBPA99+iBsh}a;c z{nnYu!XCkcZPfk>H)sx%(}&OS>BAv8{oopNmQr#^GYeFpYcB=`9P@gXaI%F3dgW=W zvpq)g#ImPeSmF`6NZHxLd=OTsB?Wd;CW%8$K2aLnm~F88PawB*j8^ zX{oV|n8c~j?8N3l92=tCfkzPR;-sL{DNecuLE4JSzF^y7y@!f>W}KR=3^MPZVO71_ z<+kFt&CyT?WW6JjRGu84Hih6*YR0xT+rEyE_s@?RyeQGp&vaSNH|4jF1cwyJh#S3DDZG^1E+W@NN>73LSl6K+}wB$<5?*obf{$b zP`md_;AYr@#L21pSSF8@aMNq)C7jY~6Wy1g=&~gkk`7V$Rg=yU4ciqUvC+sYz_vYoh z6zcorCfy+{e)2IIJ^ACRch4LKHhh=+8{ z4ddo(bMdindT~4>lDfk&o+?8nN13qV z9VDlBJ-x%+sck1|p=hHM8?j@jxT&9HEqm)jhk_dP4ah%p^>gV&3c#kMjQ94anXZ4- z5DIJ#QhH>b|G00ZUi#sHcm<@`#&%44x98MinUV;ML5>k6wMM{|mRbb1ggBginp2tz z6&u&8{|x=K_hCx~-EP&Xe?n2sSAXRJFaZBzujagwU{KX1gniz|2!CA?8*x6S2esW% zyA8w>=rUolx;FpM^? z-io=+s^30>H%0e}rdGOhaAnQz;!tZ(i_1p;(z}iSI{6}09-nxiEo|=g9W|q&G-gWq zhXrGsqy+J1KM zV@68gNBH`!kraXp9O5q@P!C?T*>u~)_t0mFjE!22=Y!ydlBq9ps#lh4KXfXaeSiI> zPV4wNtG}E_cZ$fT4H;_7$Zu~{jiXREUDxMSJHBj;reD1;j<@A2KB+WrM}0Vgu^wrTe&UHQ_qqJ{?a{*+E1wh#c7-y{3T-+6uyM>liSmHyt~dZoAm# zr9Wu=KH-LJXT!?5#3@uCHL)hzz1Yg~jn+N$XPMlC=D_~PxWZ_vmnsfzSVwcF#yX*P zrfZG)Gt-Nxy9#1tXXEZ0qV}@0S)eJx`&7(+^UMfC|1+cn?S_>He)VJeV5B0>?9ai3zXNBfg#O z-rP#BBJV`b33?UTbG(4+y2hU5`TGSS4sOfFd|$$i=AllyG-eRF6XxRf{l$&FE=xBx z*ZmC@#W^#r~Y^M=k!;lf}t!Hiv-$lceyAu)&@lEPkdjLlQQ<=`WjK zPDMBu$=%X}zubDl9|pE`gF?bkz;AwghqUZ^I(l}oE!4aFXrU%_)_xlZWkAyKiB0si zhwIhLF6q3;-8UQji2vpZgCJcw$gTO7Nla(%l3J>)~+A0`0*d;#{hJkGiW9me14 zGhJqEbnVrsLtBwLSlI;vQ!EFNn6Wdp=1LL|zlx1@lZ6fy;j+(+Wkl$U@g4kF$f)TN zmP>btOX|M(2iO2&zgzu@RwbPy8?}#D+kO=5eIIh&cPah)+t;S&(ta`cy4s8|L1Orh zh@%`iPTI!Gqg5H*XMus*T$mZD-(N-o<9%MwE_OYB-c}oR3**KQN)X^1{C?P<8{UT! zFNg5P5PWF(@STp27EC19K3}sSzr4>I;emub%+_9N6Wck+CTOoHcXvS`9g}2EDkNt9 zxQ9z;KS2<`XclZ~aC7a*{=E`Z+Ikb%RI@^W8UR;PT8dAKEDZ*=TrPUNkyPXCd`bU0`-jr8* z9iu77UG~J3N}9`Go9snk0(Pe{q3bJ@gS|k}nJwlA<;J51o(NQ)y+&XRkiqiadg!~y z?twwM)f*3;SRxbF`;=PQpjAOh0=$Q>vYzEWITOTw=X)wgFRfseP&sh+I@y;9T<6y+ z!vM-e*-C51l>;82)_Lf)2k)i-Hs!ZPa*6*u;~nX$E%~Tcqz$KW6XOfmJ&W<#iTe5P zL{zH7*Dav?rY%#3jwc8FlqTq~DvG?oq96;i>=1U^qm@!a#zyii(;1_)aCw&&@!9X4 z+t!KrX;0~u+|TWv_xC1)$k*p7DbmVHCrMhJ@=c^?=K*;1w(w5Dn;I3sF1I7>vK!b^ z%&lo1rrGl;ke~z>6Sua;lO_h9{>KbIkzhZ_o4izNGT_KuWM$j!A_kMFhx+(7$OmZ7B%Jd!36pX<*DTl3_t; z*4`vdjJB2V$Rc%9>GVR+xfakIdRgT+x~NS>E^rrQH$=q7>LzCxFU^Xw;CvTz zc#Nw?yim=_30aT_Is`J65xeDSP`NnB3M~=bge_UE>*iLdF0dk3JMOQ{em#3WH%4Ev z*}&~*oNs3DUIpQxbo~wrYV#yz!lb#E3jk>pNdQQ%E24)Fm6TsifIZ*H+2O+|sWwcC zs4}*_iU8~W32R|d(&p4_pLi>&kn-|Pizpq~Qth&`vK~ZLK(?Q>{;38G=Ulpor4Uin zjaieE*n3yGd{`tR#uedC5UHc_d~M$_eKbB$2mR8yrQqP$K*gDA?$bk6&#~v6#&&TB z$kxt^0S5VvmG80~ywxx+a_(oO3znDd1?E@RLm~iF>OolIi7ZMQIP}x|db+b1(`UlC z&fS0<@5%@_y@qrr2+OR=^6qnY@=-lDb8lE32TRq;a(^9PyVu-_<>zv7m;KM0yW;!Y zoSi>skF*ytM>48RXNdK{YmB>1bl*pqCSLf_;I)c52rSN$e6)->5((J^(>gS%6u1X5 zLIpzvEmz3}Y_65xg_gu&Obd(%@_u=P+A5O4oy2@6*ST@CZ4H|T>&V|l$FwJdSk z_SxVZp)gh%q7Dd|Cur#|B@HB_Pi(ZDURtrehc7>ni#r=laQ>>QOE}4GD#qxGvupdd zcH`(;dp>o9i=NYMfrlPPVj|o_MDS_v^>2TnK_@j#0Nt1 zeS57Re!Ny1J9aS%c}J`LdUXd`Z)EN0s=}}G*%f+5;l$m(B<&7Yt7jg9o~JR1WhR5% zHU#!Dz!u;CEuz-T0}1NpaGOtUopc_z(mJ_*IUN4YY-Xk|?k7}F%7ZNAWRcie_dB=N z0NA^8#+rX;6$k)h#5)I)zLu+c&DA>T7+qM_PADLs^5n+V+}2;;9DG{K6zie-GC96Z z(V3pM9wPnameXA!3adS6xA-9oW;| zwtwp2?XWp@r&fliN=as!h&ES(|FLjXg2^kIA2#V$mkmG8a7R7V9Cnkvy_uhFyBR<6 z?$aNe_-O;#t+j?QBXCS35k6_S+v?6itLMmij~|-s4&d8opDb__pyMC}T_yn22B6h$ zkQN{X0KDFL*BB1Z0Zkzh#^e&hEZJi*UyR5mTI^bb4EX6U=abnz>`pC3oh?7}o zQam2*@#0`Z!{8)6ibOJP=Y3ySZ|ax6q#=+{n~Xw;eR|z75poOHM%c?XKq~pf%-Rfi z`leBWtIyg-PkPiuFv09?HW=++Dd4pvBnHg0+{4CobAmZ=rS~lc6!QQgfDY|_LoH@b zD^M$ET|qgyX1b=6EIjMfP^V%BG@TB)qkME0`l*t9PXUiMbnIy$!ub!avU?R*Hd3CU zLO8?n7!^Tk+CEd#Sbkg>bB>eP(!LAb&%cJz!nH)&ZZ{$f_q3t$vdW%W>Q6cMhLA>3 zgpcE3j(L-~$-V~}_bO+3(s=!hN+tzH;ewftUwJfI`h(BJv3?IIu{>u!8t|5t6A$>A zo>n)3ye4K4JlnB=WBepSSk7S6en|Opt#%OxFD-n9}P&IDKS$^Nsnpr!?d`of+ zMBo?lUx8l%*fMN;B`=W2Dt1+7(l?hwVX)XYj`BM7U~-()S3;-p_0i*|+dG%#`rHr=5j6BLFMn zac=lHLrOdGsEYm_a>vVKG*#lG^rE1uw#hNwBVHiZ9`Sv9xWI!j@u%(tU>N|-UYh&I zzjBKc@_EX?vrEU)8*-?Vt-o75%ecr50A3n;;J-is1g0N+;g8Ox?Q|D`D#|&Aa0Zce zZG^+^>H{t}`a3*Go*PAGy_?>oSKjrjez$zHWD^FBz={cvK(BT#!Y+gO7BZh&jz3H;4dto)Snlr z53m$nV6J&NhOgC~L~_O-X2_eXYE1=*y=)5(0lM%n9l-^$$^NY)%P8NRL)#9js52Pw zE1oe*(H>>RDFLwy@U6m{C58A_v0z2p;1O3!;e0V7<6+L%<@qmb^hTLtE_!$wnC?E) z-faVrIRk*uGa?~OvfLPfo&e48g_jp$V=mq8b=H#O`|5=o@lT0WbV z*D`oI4)b_Ps65s8g!44Kq~n1^8f`LMG`@u$TM%HD{NKLb-@;Zx$1xei^VZaLIaU?` zUMhUiReWNB^-2GnX`S`%D5yf>`U-xq`(yM>4_&&PnY-|bfLeMu8_~Bx$hSK%P?LU{ zv?LsRA0#IIQ7Kv%h*z`3WydMFzNg4mW?geZy(U%<~xaNlvb(>-7fdWqRYi)|uwmbaqyR$&5dxld^ZBV*qaHMH~@ zb^lKprt7n6Scd~yfGF;gayr;Y-5Uo*YqfZ0Xnm#NN~gKU`in!2S7PPbcm5HSk&JLj z$j6`$5B6uts$Ul3w&9rYpX^^+X*J~4=bY)Z1&|a0ev8PG0aW`7?gN~l{ukYWql4q* zNN5X0z<$b2*+)C=UFi^7>y+k(Ub0F!#6&Gqm|M|07Q*S|x}wM?#?KlE(gS=ObRdZ-k=?zi@alp894)0pGX0u` z32DBc7QhE|^M1W&#P@0@6*M*BGYo_R@Xd+LTH=Bq5~OW-S3Wfb>c|dZ@~^0xP_N+6 z`DZQYaOhO#1(E0;>h@1N5ZZ{Sf!DUy-}Odbdn&Gca>M^=_vQMh`=Q&NvjvXh-bWKb z%P!ja*W%eI*5!rY9g_jPseoWXf&376T7qO=(#e{gEAFT%t>m9Vln-B_z$ERN%#OAxgC9g-ZX zes~gyeDG>oKj|1|x@tDUnQXS6Bd+>{bBOr|r7$d#TGUg~XU=ucWK&3jOZB3v^U$16 z;wYKa!F0y%C2Oo`%*JLqF?(4VdEk&X`3#fa5FLUVs#q%#xam#-YKZ28(W)@OPW+Bu zX6*O0XPO@JBe=;!3{FqTlk2o3noI9#q*P3BNq5iTtNV;8{?g5!drPQ(6Om$M8XFkM z$^?tcoJO^6bTa5TuSR;duN9}07>}`jdct=%6;Xpz_ZFtP(6gqn(-|S3wyhgg=UX+p zX8Z~(+#W6YVSs|W7Te!43iD$hJ8ozN=y(tCHHLkbq1PB^F7kBx## zK`3bZ+n=y>P(wAf^CYmr1$+9HnZjmfxgPp2ZI+OvIm8U5`2sN<+a5LS*W8Cz{ZepQ z^ajgId&L|vY8|gNEgX}bVRt@&h1}otC`MGctpls%j zc@I;6R3FB|-sh=zZ_UpYwaFHX_sJu6B=aU2nHP;vy#A(0xPI2GG-+|Dy=h4%q(;lf zGNeG`jDetH`@ohJJRJ{o(X9;UiL^KA-?rAxaf~fK%*Oc@S%n){sLJE^WD>iy?$tMC zoXMf@76hTD%lPQ-F!*=4+ZX}hMPa(()x&k&YHWc@>1S?N2RPl)5;aDa0Rek-R_L9x z7#ZH%Bn=oDlx{l1A>W=e$e4whf{G|5-SptS5V{rRK^E&N|b5`HuA3wN}o>eYwJmeC)Cs?Sd;K@{#*2Z8x=ioa`rGi%JA(#FZ zo0g9$lmaJ>H8yr0le31K+kwA6<;@rClB6#|mQw(S>lbR{#1;*&>)|D>Z~sCLZQS!1 zX;6H)jPsQi+x0GZG07ry^*wE&O@hBQeY(Y5>QX$2e4>So0?b7`nAk#;Om-@rf;(uG zP$8K!)t36578=x9LK15+c=qBz7^5WoT>2i~@M5lHkvid8TAMHV`Y$^D9!i)+E+>#k z&HFczDhxy(DPe0)IPOwH0ePsEk5)R0tehq;C}?Tx3eGtPYBk zU!>K>|3D(^r2jWR4q1&fzu?%miH*Z`c_gf&pA`l=r_)C|Q+A{EYfF-qr_#$Hh z-8I*4LpfFR-5xSZ^SvxdjUb;_MGv>38QCa+nrcT2`y>MdXEgEf9hg^<|Cyb}Ug;d8 z5MG-?hoV)t6wZ1;J6;)| zJv4?6bzxn;=oEQ@LX~fbL&Z)~IL9bsQS>b|)o{>s4&e;9QsR*GTWwZ=n(KL zia&z>{Xm5Q&jwA2YC^pHC-0;ct1~L*HE^}?a*GK*R~KLp*kh?qVtHL{iXJxa@}2*l zx32r7i^Qh`=aBe|y{@pKK2J?Onx3j@F1@hFjopNdk4-*sT1N9Tg?d-Y?k_5|6j(84 zJx6m$L1*+n>SJUcPAPV$rJTZz;osB7i0qwj(g@k#%M|~NO~;Qu%*&#dzW$9`EW8zK z(}+S5IDwJDu|J5?6| z(c-uO$2e1VXyP5B&hQOvzP0WA(EX)Ev6wPgDtyQzp zrd@V-)Xp^TxE&ujV|zcM;x`H;+1RYM-z?=l6F~3u=J!4ST5|Apm$8C2lljA7JE?tV zhDPKAC@x!iaEcm01nks}<|<@1$&=DAiY{?vYRK-i*(kn7NyA3Q_bxIKd-6D3vMj$# zPWP7k&k9rQg+bB|3aj^cmr^|p`^P_tcGdTBiJv%&B~mW3ssX!n@5v5VNAIT%zb*)= zsfl#Sta<0Tx$hhXjs6qjG3HEfklikj!t*d8f-yexd(Rol`J>8LDvbO*(b}x@RqLv{dixHsve=O`>t+-S6qh}V8M zcH?kq{8)f$859AavS1QYfA{8kQC=gA&Mi&9YKA|B0=Nx2Hy{^p6av%{uib5Z(<(_3 z5dfriGI))}Rt)y`=6aE(5QPr6J~tZx4D*dkp`-vPkja+554?7e8UJ6$gNcB2Dzwf- z0#ptUZ>|@K1_AtUY0W+tPkO(G4WHsH5_4?fc z0b)${nsx6l`3G{ba=*m*@qfhl|5A*>kI-iU!ekvN-!oR>v;QG-`g~ZVsVF2O1W@FN z!d9NYEW{DhKe9bs*PthIQ)z-(5K4pp0IwL}AOBK|D15M+jjoZA!()!84@6vB^vOhh zRlXF3bC5hir!>^}U;gWgdD?#-)-rm+e*Z6-26EtwU3>5SCT<8j;@8))QVQr9b%I4K zl$&v-OZ*4275wN4Y;`)iI-{}&I> ztOSX8zimHgBFR@wtWRW6^#3yMD1Umgyjg8_xs!F!a&*^m;Ubo$$yZk}8zjOG7W>Po zFw8&t#~vDDIHliQ;r};OlB&21&Q*z1Si$qq12Q@!=p0nL?(0)3Rzho{!aypmlh02` zn%0>n?=bBz3o-NCLVRh$V;8@9AW(!8HPeMJy8k6kfVB)oJQvTivWkyAUb5ie&eFw2 zrRc|rc1EO{>fB@?i5h|(38aEX@Uvut zUTrVxFq-x-_?a#4!#W2H<1EgUk025tX22t$xWHm=Zk&JeKi=yO9Pan=rdIfs{PMS( zKL5jMNFkfx2UmgD3Kwe?XC_NqS$(Aj5UHrQu4IH!o}RV$ffaP^{k4Lq*UbMo`0WtB zzZNfL`OD&xYwBYCwV!@c1Q0st5FV8fNb<$F!1FG^0+31?0qLEa-cKA+iUl}}BTJn) z|C{Tj`-Q2ySeXz1hCL8R^n{W5`fYi!_gM0gJ@W1JM-AtAW?#o|^SJd(Is#mfuj^~gZ)fjC4-$RiI7fiS5{oDkWrD8g@<Ol;D?*j6_jBb|~?LQUQsa#1cqD4Q!O zC^&e7oLX$GTA@o(7l|4+*rJgs(R0<5QPkSDcOg*%*aIIr8?I6`*^=6XmX2e9Cqf|q z1K3kQ7h9*w2*^&6P_J))#n{t(Fv{mne^45e<627AIpN;vPgb{V_w#KrA=9eUUkEh-!EbvL=17siB$Zz(WgPOK$d<0_1Tlk{<&$ow31q9UU)?gQ&eYCe755`E#!7utGTuR zF_FP&OSkOBQ$eS>QMCWXFiUa$-u`FS-f@3z{{>H<%lcmfAx6Ye6H5JGE&~v-6bzIGP%Xe_A!OXV zP+yCa=~7>l7v5l3FKHL3Y}oi!`M`ER1yLsOf3?GaoLL5cpbZjW@6b@|hBqWD?x&E2 z$=FK@?n-hzcr)<+9FHnt6`=wm>{mAiH|E_vq&N0CM*d zgziC$aEIA)bBc}^GcU?j078SEUS#~3B`65J_8j^Z0C0B?lYo>)R~g>4Vjn3J!C}fK zAZH}QW%xTx1qD2RMp==p## zkIDYoOMWY$r77EU@vVfh5^cp`UP9F04 zK;$x~v-3f|-|&I)Wj(B$x1#zaka-OlZ{1}O&T5G_0vpjEe1dNGu?1-LxdBl8o-zIo zV$M{a)!fwEWAT6(C!=P%DUk;r)L0`Ez>eHU6f;g#uO7y*)N z2y8Tc2*U+{ZaD7X-`AsH{Wf}WaTdZiA57!*E1D@Ls{e~f0Q8XxA6=N1@3ZUf)oni- zkDVmnrTK0w$E^YxqEv1zg6=eq8a`Iz$5obRUnf3$sfG+gbs z{~KvU5<;RxkCteo1kq(g7oyh~A)*t#6QU$U?>!PBdhZM&dZI?}Wpsv7#xTS04D!AA zP3~I1f9_ptmNjNL=XrMd?DFirkAd7<32j^}XL}V~D}Log>A&#~_dJ#MPGdpjFZ!;Y z?yV+rNAYiwN|&P@yO!>KbfDf5&n;WF;0085xn}l!H&w52x5ygTp;pu%4~k0olcnNi zr-`Mu$i9*U?fZX9T2Tm~Ff!xUT0i{FhEy$_J`G%v^}(_JBE4hNQO?tHcH+1vxg|jC zouByDpYBhw{di8s$9?N;41ZGD4~S~!+h3FVk^ae3Kx`W&us2KL)4rD=wrnh$$f;ju zo+m$SE!X^bx+6PS^Rs&OeZNqRpWmAP(86%>XFz;{MTC#0P9%T%cuh~S9!eE{6aJsX z20WA*I&5?%h3W@D^TfS4F}fp3Hj?2TMXyw?2PQUe+EYz59tu`WZXoI{sj3z5@7?^m zMfT^m!ruVuh|P{}gz){PP~vC!jeeqa@lVpz`iK+18v>iMCRY_3X*+-RI2uZ+RrXTy zww9qQ6Dy1V!z%}t3*mf;SkFNzu{V6$HG$G4c`A!Ds4BKiR710w$*|fRX3?(mJ>j_sm#pGbtz@G0> zk`yW(K~^1uHWzl5imZ^Yq_9Ld^IC2?(K!GGM;T8Fu16|`Fz%Qr(sLOKGcIvJ;!5KR zI}%d@VQ~$}4(R-nZ}xj_jZ*;t^1R_pqf{$uM_-}yQ}cK)4?D}0U69O68W0DIj48~k zsH>}k)|1E6o#_LlR=FMp*N4BDwG61-U*i>tRrt~xOIpwxNxU@QnQDahazF85$)5PV z@y)hV^`#}lx=YukuKaDg!^L;+8L)@}g;|d!O?S;H8ssGCcIov9)%Q$QWDRrhENu2i zCkDB_`UGucv8B*h<-lVqda>Xpn>>>`QFlios9t#=kLi|xy0@I;fc%sVtM&jxlm)+y z{FhYXg~NQITTtz}17yZ@@YRgR38iv%iz2l)uRxko2ob=eLcmB5F@sN&KX+8D=F9cX7E&Sh|J+@puiRBD@sCxig;iWD}FQ7|wn~9GDP` zhusYA?Nic7O63v%rN838h&W?D0cQp5F12u=-QexAw3UV2{I$zZ>nQdqqo@KEJ1@iV z1htzEA~_`QJxFFxd8wG9cG^!xn#Vg}_}M6>-|b|sJc-*L=9FbWafXU6CAh-x!OK^S zyJZ4yS2{{~SKdn@Vru(PCIw0Yl`3rZsV#+xI=?~SQYo`0Z{&Pft&-->tTTQEOfdg(^pSr`m@9D`QJw|bFvCtr*g+f)X;eh~sIrRQBH3aX4k+Qz*3W+V}Z5_6RZD#*@ zz8A)P48W6Wv1JxO$J-@aqpn?NNHkC-v%*(xk4!~FH$GAdJ3cPRX%RGwWKyH1BbHwg zCTEoObwMDQOJ6oq2Lcbweq(>5Q_#;E8%>KjqqBBq#m=ObIjk{?#V@pT8(bLxgY8{` z?Z)M{X$Bkj9Zudl{=}=&=Xa&vL42;I-e%FixW_wdu45(GcF-Lr6v_DWschE08{|$9 zMvSFC3Cd1ZYW`V<$Gs+HiSl03eR!YWsmpUv+;|Hi`TF2uRw^?$e(Ct+> zb^wR?|8uIMfQRef`)#rW=q$V4k*fG=-zuE~0mNMW+ob|ytnX@L+2eWhzlYwDaNT(H zA~nFIGlh6+=;$OH4?c#0^7h!CogK||&~GtZOV8RzOLHpY<^IaeNUpxk+<({0rL9J# zu&jA)aR+`vdqOFAC*A!qTDWprW21$FJf)UWSE{FnEtoGeGM7L3@}#!PbR=I7WnAo_ zVj>dlD1U85P}CCiaq;r($U8ac?ETa>`Bb-6pLKLovCDezii=9Fw{4i2D-hn$9{gq< z&?yz^oT$+s;(V|x$?hQPxV>r=LeBc?dUm*2@Vbz#erTHgZk)_*@?dxBS^MquW9BbE`A1K*tUd$Cta9kp)2UCP$rHH?$m{O460d z9F2X+SlS8gSX=S7jC!on5u{IppX{@h==mt}T>S=VHv&uBBs|TE3qeAOvul7%EKXP^-iEMRTC@Q0U<^ zcD=-O5>CnQi5kM}@XD#e(nnsR1rP74sBu7?_i;8JoP?H#$|IQqcUO`s4ciCmb<^JDd>jAUH}oSsJ%{81TIyU2JiN%q z3M#DoQlz_OqUcm%-`*Bckj;kZYOpd9f{|t#l91QOoi|W++ip8^0=XyZzBx&Y$H71u zE07KcI)~Ou3??~tT>AaC88i>0i9ptDs5P3vubsl#d~%DO_hI-iBPdrQ<@X&PEQDU0 zbUB>k)vi2x$EMRD4|8r#oG_zErwLw^0Rescag-~nGC2%*47TX1)x%u7-F4$pw=KUP z&+AqFE$iS8DaA(7>hpF{cbuNfCnmu1l z9m$$3l9HjA_$)NJnjtslzQIuEhTZhViRkyl?K?`O(f39NWZ?1@~=R0FNY zPfQ^o_eSShx->r{Oc=C%YjeUpUJh|=_4)S5`cMX z3dw%?v!Uac$j^I86vhbsNSp-9jd}-rIRV?LzNuHfffU>GQ*nz*LQsh|wM1hU_Ulnc z`8lb-8Y0{pw$enMX3Z`4C?0&CYHb*`=s#c+lzdUuQH+wy-K&*2||!3i>%ZYLHUn6Fii5NTmVU_z$#wEpVxY_j9bp>R$CH zK&5xdi!gdM;hPz%Mp=5~DxK9`!)=EH!W4zTQa2ZX1k5< zeph~=(W5oTRwr~-@fQy$n~HLXBu|b7SL_qD0HY<24ldqUwCB;|%6Uya8+M-7X{MrE%SUA;50-Jo-jG;?lL>pg^NlW zqOgZ%0jm#t1EJ^+wn`5Vk@$zR&r$ZvQtye6d{(86WMET_u>Nu_sD8m=|J4$Q_E#O@ zOflu?r3g(u_mVG;`&aF4hwqO5f*b_J06KdwtueD{({Gk=onq9}v zlBNPTgy$~H6uMzD_osT2HC#MDvukR5NS)QMZlOeqM&mf{S#p z^W9W7_ZkY7FEf&!hc@aJR#%BvHdLxX@^ribE%mIot1`lVLXvcjMUtP{&^$BJ_HNra z1Yy@J7imfiT?jgTQkOIArVFKAFKI88uH=e3O#$Q*N z;%{@by05Lm%%hl;7GDNO4H^QipC25owDf5kop^B*AylXVBk<1M7Wn0T*}iUBKa<*YXT{io7c@88`(_oVfmf7lR`({<7Ee9i991|#fRH~EXw8BU*p9q;&=4R5(tG!Q0`hBt=laygv<=;+{QFwWTU!KC zWm`kn$L(k%>K>I9C6ol1FLCA6znCXAj_g@9;p?fkHXsttWg!65ldh|D3vYlRYsg%^ zFqQuO1mYZsXy)aPSDCRP4bg-(T~!|Dh^gwH%`7M+{}=N5erG$*Dt~}Go#bjpC9LN~ zl0yxzP?X%b^5tD8-zww+ye||UD>}0XN%3hZd)EB(0X0w(gG+So%+wfu%j4e8XR2u_ zn%dd9Y_YK8Z$U!=ui`TsyeF^_Y~52$&4(G z`0B?8+upMLzOK$ayL7{i;)FKTtHJTcgV=#m+?ArcS1XPkVw3A;v~IuDN53{Q=vwWc zOMf=Lmt0H$8o_qAu_sm=Que0}afj(vDRN$+9xI5YZV+Hp6MEYKDImS(y(M>pF}i!h zO$Q#9P&mS&wdTN~pR9!#ObUs4Ef_UmJDkGbpta0UaitdMkXV(h>Df&<&>DSSxCB&( z{)6}A@&y~P=~^{BHfuOoOWJWFpTzsorK|$jk@9=JBhR>jy&~c4`O9@#>tl^v-K(g* zo|4|V&}UKZvmfo zqee$mU-8!p@g)Rx+sK|=TFmSQ6@I!@c8zyBS>xeDjFNt~Z4~H@z4Hl6SalCj zQs*;6k1dHhz%4rU;QoC;-WT#FI~H(xYj{JvVd+30ZLVyKFOH4=7SrY0*LwjTSxoUJ z=;G(DO|R?f9Ftvl#ZnRLXc$Gv?ghVx0pI8m8nBhlBGG9!$3!*WCoP0~$9r%(vmHx3 z`s|5%XUNRsF~Z%ZfuV^D`3zZzx$8n6i=Xx@9JO3E1EftT14+4DGFv?%6g)jv_g~?r ziB-N$^T*<5^~_DE=kZ0fTaD^`oUfnUk>zfjyyFShUu;Wpx?{$!-UcTx|p5-&^P z)Ti9IaKq4!OjyhWh>eHIiRawaMM}SVZuv7?YJ~xQcHfmi&g(~8oh7?(D{u<+INyDl zH9lPMXN^>GrR)m7_ddEOO_D>umd^1=X~=Ag0Ezb0a%WG~&qJ&M58TD(bi^HK4HRgn z)KZ;;>y?MHWrp4_z3q%r-Y?@XM=k(yfT^vmA?!|-VzzxG7mVF=@|d{u;=;_QPKyTA zfIQF%=pyOc1|jqNsvASf=;F|@-)?X)Rk!adx~B`SzU6ItE5#)&OZfd$m-Y&UsV+fH7rF7A?{fir$9$EC z^)pigWf1{sKp@a}S}6ide3HWVoT!L>m@}h=>+AVpj|o#EE4ewk(KpWhy~Bn-=f14k z%a6c8`8>CXqL52J-6P-OMgCUMueR+T78WTe8FP&Lqbn`0F5<_pTj7WSmbN*{58FUx z&M4(uE8ryC{iRfN+Cy35>~;~er`w#Z309(*KC_7+;TMG9VNjA%7*AMgb>2O&UepMS zostx9K(4A_nEpbr!ZSS-8MEO;@bZ&) zE`G&ybvlKb5n)9T1xdb~bYYoh>)fw0z@)g`d-{(K?@&_wS|xvciJok=!fEN&sCR$y z4BOjIR_E4em3t;qE9oTbhCfV4YJcX&8*O6`e!X}VvBSH<#XsU{wRC%1DsiN=F7gDw z6bZxyldDdtO@*kZ+28XCB8huaFA@A%SOO9?#@PK{m{M>*IbN5fK*@N~CxqFy?jPwJ z4W1MF($A_~_A=GHOnf(0lN%4J2TI@Dy;NSSg66boRvSkIRm>OO>F`p2wQu{xTihYD zl1Z2dDdixnp-@k-d_3`DPiQ`Mp=-ef@_JFl(w=Vh%UW^9IH_w&kY!z4W7U3WkX{Vm zsFg_T^Gx9nG#b;@3fb1HG8)zWxyS{A1|!JVcVeFxMTlP0Hv==pW)o@@vr8i%?6D6R z@l6Gb*WGBoH)$JO4|>y&hXUeU+A*NslakzuwbS>{qW~Z%xZx96So_OQ@935_j``K6 zBB=+yD!7-FP-@^e5Rx_3_Dj zF9W`gJPMQ5$1Rwp!v8cYwCWY`P2!HQ`Zp-hg(%gdJMTc<#`O(@TDwtR33`_fdDc`^ z-}Wmbutnu-cr&3WqBc>1SB5p2OF6^8i=GNmEvTi{QN9eT3otmVp=6OUi z=b);e7H4J47W9o5=t11SHMD;R_I{X!yJfqIMFC#LQLFaIUAjv9U3waY%J=J|7J)!} zpwBl}?mGHrmOYkiKb8G!dQr?lAa9TU$DqW=xJOJ9&|zdydjsjjUge2tT0U7#MvBG>mS~tnGEllETcm1By#D%0VQ< ziYG=%z#+Kgd*=yIL5uHLhe+b8P4kZ!ma%Wno1dw)BwJcFmw^0q&h#z!mszW%bgu%W z&6}Ys$94J&K`j-87eJE>TUDmXZ6?523ghIv@`mZG1%>CF}8CKa~la`I=5(eN$GF2ro$g_mA){FXn zd3VL_W23+&&7E3ORaDiBHP!4bR?2arYNb57_ z3}&;9B?tV(>Peu8iYB{3fHpl7DyopTrn};VNVYWWT2kCNFEwityhOokyjaG3D9!B4 z$uG)95k3A7NV3*#l!a>7KQU7^1|&-?q&2igLh#r}tDYAvN5Zs?`%A6^F4H|0KR#|Z z3CW&Sm6NYi8{6eXNx9C<*zrZZr!~+IzZU%u2gE)MKw&)X%D9USFjnXVll*O^v7!6f zP2Wfdrb0tXT)vgs)kcU3 zJhjw?r!gC`BzzW@Zf@>Cnn!xRWBDu=fVckCsK%U*r_Q3OD|7HV-7YYo!ExlJb5vLB zrCng+djb{)Ak*%KZ3WxI1A@&(X8>CChkd3jBhA}d97{(B7w zQeQ0Jx#;-LTQo7^DO2vV&LRUM@MoLN$-EK{Kz1FG&&Of)2X^w({<@JWXc&ZVg{` z;$iQ$42Hi8`S+5{OfdKmp4C!aOApCx!RZ6WvB zm(xo%I{8_YoC8`u5rUfm0AmNHZrH~u(70!tE0cdDX>FSExjSd>ohLWD{wg{{R-XR> z*DtvpyIjJ^TGmg! zZJT#{8&PUh~H?zJ=4!`?%?Z3zkl~n#;bQTk8A7-RapAdjcVQj?YBf? zKn6}2Tl2WGBKkkn=!oM$iGVz+rb?eM6>tVhaUUoY7F2-C4+hDR+$kC6bkViOtgvO_ zO>E(&bCDk_q`kM>407)=xLleUlXh62VRO{b(GX7;8e&)F#R1Hb*uNI?tkdz(d(BNp zZlRO*e8ORjnk>=kQEJU=b^jjWPZE6dZVI%Y^;-04<{j$k{8|?rCy%32y2*uj4lBYx zjSgg!F03AMbPrRQVN0t5UpukW3p-#Am4#BSQ&-KVT%PL9qptlR3=DGwDE&>mQIpOg z|F~tLcjdr3_Y%Bw3+MWgZHxq`6+_vz^rbvScDSOG-v|EgTCbt|UW%;_Q=bWJCX${2 zp5Zf_t5Jl9OLT=Yz${hAG9NjX=wd2xmLOwKM|d?Rin-yxWR&W&DT2(m3Cg zfHLZJ15z*rd(gH~aE{~xDhoeHQhNJCvv2z&U>?dX7Z4wtFfbT%$!vd?fSRlZxH$WXg;csYw#QFY34F^Rzx-#U@x9>J@?NAxs!K;z? zp+<8CYd*yNdj6BV0I8P;%n?-xAqcs)@cw9#o)`JPxs@k+_~((j%u#OGmtyL#dBV2F zYA=E(@e;&NCl9`UH(iio-y$)tS`mVmG=<`edW?tmGYd(2K!YG}JEDZ~BOobi~>eHXS%z%X0VZYT9u z^|jA6N7dIYfeLmsN7j#LU^AQ8d)rjnm=&p%g$4gAm2xG#dMY;Xa=$A#i&FSchXilE za*4yI`iuEBqG_y&^Ep43Hw@PAx{VDhJRDcLt-IHCaDEE4(=U#nUXQmC0v=-X(wE9D zYAtfLP?d$-Q2Ji0Wtw{6$0xJ%d%|q`JwHAjiU?=HVRm}pQBr+<&aXY1dMI83c?2mU zyfDJMzN@K_6U)Wfnr*M7yZyT>V4eFSMlilTl#I(pBFT{qg^-2<3K+My^3bgy0h>YR zmUK1jP8;3%ln6|Ex%P?W8{fJB3&@+ht8R*v?%`&wCz|3g@ptj&Fa-s0_{`HX1dJ(V zTf`tjqk-zo+?88x~tqgW68qmHc%6>%Zv?8DZq*AT)Kp>aN z6H|O{x_221qK3cG`c+)p^d64{>(iuZ4!0D%cLq+aP<&kMc$a9f&gzYC9HKN64a~Nw zUIGUns~&I(OLzkl&P7WhuFnei4N4MNfN67S4O7p;wtplYR27>|bD0V3Mr8dspDgHg zAz0h{z%!Rp)Ki&=rLb2!`cbu8AEn9@$;;eqgkaMN3Ye>G2z?rB8bn$aJB9n*r#22P z`e}4Y2PM63k3BGV0}u&fpJjkWi`zKKy6FAwTtS?vFBbge5<$8wkttLfY)f|%rYr)x z%}?GRsMtK?YAD5&tSM%zjL>Ppw;ipu%VzsNQ3IG1@xad-vQxF|F~vo4e12;BN}R52 z8gf}*97l-~+ZUolDXtO!yFv^A%d=Ob6ONq9d=b#r;NlE=$*^Ej2Ka+z@Soh((yAN9 z_?iw>{E(S!a$pqlau)upn8IoEPdg`@l|M^{2`+5qiB%@Oh|JnI&%E5)j+_4OR^-Sa z=X>m|KG}pvKB9N-)0HW6xJ(5+IvNG4Q&hfL5`jXSReAj;fNEXksp3L%S!`20kUWSK z2aXh{k3<6%bQ6YH13eN7yC%GJ9q+C&+u9JB?PV`5Uy#tD3MXX|0H0KlX~^)w zmDU}4vPDjmF+Ytx^Hd5WSG6(s(Iu*2G3Oa$I~X$+V<>{GdZ(S-OxPtSO~6ITI>kW0 zsC)Jn3L4g6$&*>fIN$~ke<(|p%9P~s?1?0&jOi3-FL=4;VsM8~)b>wA)wroD#!ts( zFHLl>8NTvzt8CqEyb~4^aXH%LXT~N++^?KX@0;TpJ^7;vYGa`+Gtr@7Q)bEuI-hVL z!*$UV-t|pUThj**4bSHGxi|Es~`vOz(YTTo;zF=!L6b_Do&ZebJku<2g3Fvto zOqa??&&7NS;i~zbyt$Z=Y|iRk)${yBB8f2gVX`PCK+kdotTUs-XqVkmUd>=~czf}I zrqaYB-dQI5;XT4Z@bWVn5cVh(x;!LPxwQZ}i3J7(ys)s)z1#qOVqP*;7l|0bz}9Nj z{GeCufU1q`yw=`IxZt5)MyZ7`2{qj=inaI)xTi=2?0r0Dy>~pcJwEdjwA0?-pt{PU zQ+<0`PhViZXb9csRNrr6>~d6p*!Z$a{7{=>%kcgaf`wlBBLB68~v-~dindk$4Yf3d9KlH1(KGQ9()5w%w~-^a8XWv+?2 zKLsk{n6p6ogQ+sYj0#a~5ky{&y;*JSdd$Gk{{84*Yqkni%umUbtS4&d@3?zB7#_?L z(mi~v`?&pu)<^%|A;cHC#Ah>jWqQybhg5gh)#i6^%?&#H6k71)g1ji!b<64VA zZdXu8^ybN`d?qGBW9o=5(6)MjdF%yB+S}ssUcI}L>^BZra<@?%%R^-A@ZHtJ9sdO5 zAHE7Sb>?5EW>@2KwV@-vI`}hbjkb`fz*oRtlq}VcT4EPCZlwv!FhS(4gA|hB(Rq zgPkY5=n=2v7~)q=Gtd+gVb%w4%NBT;WD zk-#KD-JPOP-RA?^T^}x2YsIgb6YAN}oCJv0t)@xzd;PK;W^hXm+Geo~=rsA5{U-a7;z(V=70R&uSZv?DmkM*=+C&oSK1Z67i`A^ zW;W{X8b&DuC7iHLeQ`-Q>^|+9b1me0@D5kZ8~42|ia{Zhz`%_}OmObkTidTY&DO6y z=Jgxg%rlOO>OcAN_E1d=ysW=U)#|aw@m2~5o9>>LAz!&O^mkhTZ8)~gn!%F-{uC%O z>14oLn1HS6XJ=~o>M2}eR$7R!bJ}}X{_3TP=O)x{Tm5(gq(A^ENH}EiYjrF=s*DCE zMYgx(@_!j*=4sw*ngWLI;cJ}^-MgakNLMGJf9LXhn&E9jL4Y`0`>wD<_OSFIE;FAF z{E<3dp)be`Mj#_FPxcePxwzQ$HN{5XEqphYdY;DxQ?GHunj>P`d@|g;j|=KQ z?%&V%q8GR)5>JjT-l8=<)hS?(6r?rs4#Fftb~0^vSL^3-B1Qnd@0N)KrR>vswK=9|HHjtf^T*~m9r*ud*e zv_?fg-d1xXMMp+({5a!VUX_A~gxasX;G+wFCB@ml?%uNtRUdY1K!%}rUZxbR79Nhn5dw^2m6DyE_pDTz5R{OhGoMv4U^J`%u`OPD3de{9#Ih0hZl<%_DC^}-hJi~_1Pyo)2JFm zziwfehnIOonjQl!Lb5&i1tZwhs}rfo5HOXVrXp&)Z#aT37prE~h*EU_{;o`$D^ zSGuuw@M)iaRR@XZJh?O5`juRPqs;e0U*+)}!_IS2gd~Pp9Z>PZA zy%wDd)X?NGOjlu5rN?NNXy2I2>JKecIg_44h$fwM5iRjrL>91~Y&J}*F=a`0hT3{QUWv6gJo>6} zNoY{xxg2i29`rfgL#b^z@RYw$cy&Q?HK$5Iz+%@kg4a#o3mMSqKJ-x zrLHOsLFoPrwWsVd3bvQFS5jhPf+@L?v#}74>1ojQ+N*c2KsHXiwWC4aNJGB2O4%a>pD0Zd zOxd0g!x}JsSG%YPD5DH=p^J03ady)VV?j4#qf~id^Ls5b+WNbt{JSc;^ChDunFvRU+ zNG;8%x)(+%G?qYK0ll!YZ6|{i=@D^LZW!58bB8>s4%`bCfNa}{>7?!GdnrBqdQ|+r z7=<`KLH6vjK6B$5J^{I{$?u99IZu#oj`P;e$mgI0u0U^54|;B$d_Ed>#i$H zSZ~nB4lM;-jGbrdb}0W4L~Cx?U;oHPUqvyMg54v*#n7?F;0s?V-#FYp>cgRF$9=RgF@oDKoqF47y8B~5eiwh_He zY|{0CT4i2r?jIb2@`l~~hK~e&x$)Pw_h~Tg!vP=Nv(t1!gN}`G0G?VX(9+Nr_!AyZ zy4~+EmkUHbl?L_bk+G9z1vp~#s_YOdxrdvBa(xYZg;RwP>92dPj}HB)hc<^UPKx|w z>8EjZ(5yb{OM%%Z#uShcgCU@ZEgP>BNZUnO%4$vly-@iDx6l1zJCM4E)QAEHvKq*u zYf8b1_h)r>O`ffRRvQ$;y({!ROJt3XZXN>NTG=38n7haPhLrWBnCPFAxyor}xt(ru zb)~?chrI^0Otngc*(+&%U)f<`k#t-Or?NCnsy<#VU!?7Sw7_nnHR|qhuS@D6n0j58(f9Z#^0|G&5#&faESBH1@1m99P6Ai`<9qIhZ#g&Hc8R;E4-x}E z{ZIif_Z%P0!=xMbH;20MMCwu_A5qg69u~w^tW0rTARh6!bOrN|JI}RrxZ4rMe5$#? zXXLRvHPD+!-{3J?xa*Oop>}*NKTlys{~c)2u5c%i2Ef8$AupkRO%}h*ex%1}Zl_q} zNSr(LI&N+?a=g+43>ljw$FW3AWrC8S^{6JZSWlR=NLC#t3CijBJ;PRPe@oS*vy@>A zy7>%K?sGLPB?z>LSOc#C4!wKQJ1FoAp)*BjfoqMh96by?gro3SXtca+F`al`*gT4Q}FK9^7>u0jWOhusIAT zDPQ)SB~2QrA?@yA?_QO!X+XF2ut0W@G&k&n@zPOtd=NG-s75){7OO@WFS0+c4wFli zBozM!&r%WREi`N*`SyA_9`NhGUX4=sdPQY-f_f>;v@|w@{d*7JPsB~>K$l^aaZ3F` z%6Z~-S~EVYAWRQIth4!-B_kbnx8kiEZsDDst)J=NxtoiZ9Vz(rYRz8QZ}S*%G9MN$|Es(!*-K4=WiR4qpP#dc>!9 z&-d>Q+}~t_AUeZ1An1c_=xMi;^rq&YJ-<5TQN*>QOHo7x$Lny2?s0Ri&5w*O zLk+>>V{Zqz@70*w;OMSZC7V8p*21Ipz`eUjnP1NpaGzdb6~oMEPOIKr*FOkH@jy*r zfL{Z9qke+ozTWVC>+;F!(x;8V<7T4vpTgldDmC(1QH5v}q*GmZ$XYAfJT z3+UA0R9MK>!4n-LM4wK2-siXYVh7dpm6)-gFeC{o+wfYE+e0?!Q^VzY9rip5YB7NV z^-nhJ-kIv(;plC#ki0K`y)V7ym&}gQZv)3;%4FU32nN{w0{q_MS?c4w^?FlJ?%xYJ zA`ngY7;6(Q^!Tw;piBE`Gj#RyArU((_X&b#IvsLZ>)@_zb-fVtoTi)T+Pu3VL%%o1 zdwTDKU++lOMkYN>2)e5}rynwMT7n+f*FMk(%1*DHk4o-GuSwD zAxeia$SLIm-i&GYHL(!)A;7wNmv{**%R{!6VFP0OvHSQ@fu{~oIV_ov`y{8u&k$+XI*l2FY?8{dVZeu1;3xe7LHsR zWEAAop)u7ioGH2Dh1P2o)>ylj^tMrR?ZsRY#2NA^nD8);p_8%5u;0Egg$-19>_Oh| zY4 z9>Wr~T^E(s^|<14w>L<^Vz2W=(kd_;neJ$7O&!`oP3m6IM&%IIguv-8A>6hdjSDY@nI9suN*({nCg9Z6Eg zO({d+5FpLbhCOsv_HMK8=ml*||4#u-Vy{`gu*V*0lWt*yR4%nX{kPt5eH+C<8Rut6 zi@Xt!Qm+fki}Y8^h<0yc%Fr!ZZ48G*3d|(q0ws`ew?WEET``vitS((as>Y51HbOw zx9+bx@fn^#R}woA(HcI`qlo7)<;fm)=4VKfa@YA;`Qn`2=LG9ROQWntoPykilAPTu zUJfP6#0^&+mAdN}zO3wT|FYAwB?riK;|bQsqxfp!)bh6&M-iEdnUxT_MTHv7SNQiP zxue(XPi;=)K7CO%q1#c!>#!p{Hb%>3(2@~0J|(;4^H{8L>IZoF@mAT5^N3Z;3cF*g zrljFxz|HtMPVWv#Vv#c5^+Qp+&-(*j34hozfJW3ffbygk*L=z%0Yh$u@jN~AJ`I|0 z0ZwQ0jgA1@_NIUvJhz>`U#hr_y=4WVo2~+dbN}fc45;u9yk1bv+H7UA`%TSUe2G*r zz`sSd>$yMzo-g>9%{;wz9`ObI^kF>o$E0#Xx85gKJ?E6rhEVtUr{?Yi1&F+ z2<(CIHvgL&`04zOv?G^)lj#Dm3eA5klJ1ljy-2!IRcnE>rf_yQ{iO?zJ6PLjfTNrG z22NUmCKTJase_9t>#P2R7vFg8l$QQKYpc#Z0!ulZVH$E)erhV+Sh%;>lD~0`J>Bo6 z_)r5ka%bb)O9fc!cCcP|#!@~81G-&4%3Wip(WU@nUpp>ftv-ZgyB96-)30)~@fl)o z54_}wwlGbRrWKw6{=MT~*T~-B<&k5dupnXHy8WDTLlKR`4f`^vfMM$Au~$LIkwS6m z-TwcHA>1yp`E3@D{Bj4lyo&cpU-9=WfZ5XXZH|XGrlyp_8aES`Q62W5Vd#Z+zKj_T zkkm|K{ebb(cfFS)PKI?qy31`wNm(}^Vz=fZg>_NK!OJEODGMym7puuQbL5|UZ>-{S zLBpa7`OwCEo;5R#5LdC4K-E03nOr5T_~*ilb?F%({Dxj ziKm5Izt}$c@tn8xrx$(=EWTa5hT^}Leaca$qJZ@D<2=9+p8~**t36Nu z#F9oqK!QCN1RcITO+15{MqmUAq1(@h+Q+B2^Rbcw_QK9RgC)O@1OH#Ny#eUf1pxdk z9=TX|{>2ub#*c9N;dFfKGvsN!G?WbR)gpA_#@X#Gc~1Fyp_0%o_bd zfR+T-NwlKdy?Zk?iTgLje@nU}E$8x4yW_HN(z(3)@M2{@k>2_3+3m(Z0DIAW*$BYh zy^AZ>|DpK#o5s6DXXr5edTS#3FScAf1qBJxiH!5F@&vFjOIb~EcDs>Rz+Qk0TmN5) ze33bLS(gC90;*lnt47VJ2^87CN_z3Ut~QG!H1?`eXk3GbsS>JPl{lExEisz}EcWzu z!K*(RG#-Dhcp=PDwWl7`e{rdZ{Z#LC#qF8T6+r~62$gllrqb4P{bTFh*I)MRoLfAPf%0E<%_!>8It#rtorjbxsR#8a-C@&Cr7 zam&WZ=V!O%W#)WMw>#|FUyN9nh#RV-Pb&U)RZ$`OWVa#g=66Q`%6uR_gF&{NWo!;t@kAatCN}c}_ z#gWZ(h}jVRJmGz=>Axj0UlEHix+!r-Cg=1AY~D(>C{B6@QVJ6fI*e}0sCV^!0t~C zg=x=UU<9B&R^!Ues(%CgGXO|863$=}FcpJtf;OHP3QE>bwxMDB03@qem{rOK(hkU_Ry@mp2i0h-6!1Zz6K zNRc7VMPjgbTP_W-(eARF!nRI7SRYqDB-t$D-Ywl%tbC7^X`17=Yh&|SrABnS1L=!` z|5^Zc4fW?xHtsH34IE(nOVoAKut-)Z%7r|Gmc~nR#e`#}|7L*=W+ITp#cg`~{pB`M zEt#3>VLhGjtwra_vKf~zR{_wDj_*2iivBxRoZ)Bc-|$v`>b6)6*ul>Q@*|K_9OF5S z4}nj9yI-my{RtLJhv2A$u)z!7WHYdowb&#e%! zmn;F`CW1cBzjyfGc*=fe6>B8dsQ#^OKr%1#^xBMc)xUYtD-9SyQCiX8hTsC$MmCDa zS#*P!VUczMe_nypXYk&+O&^jOE%-~Iub&DuS$zrVZ_?LbN&g&r7K8#H0>Uyti6wty zt@htnk39q3$xnNse_dPl^xBc(6Th{08E|eKXb5S38~8T>okR>icJZ13NmAMB*H{SB`Ryg& zeK7uqX#>1u;FJl7ML%oqH=S?$90G=iek&)Ss)-i?W)QpZ|Fw6f-gAFMw+x%I{*M=g zedEI}dun2cB8ATU+oD-qJ@1!!6D|&xljuWVC81}~8TG4igU4d7U7lSml{)^%=x+R6 z<1we-oEgNrq2{KAmLuS0)*aiwgg(A;mH5nxYI^^e@cmOR@|aKkArr{N8OS&8(-lSD zNvI@mWC16A8^U(fn2!B?=@A$TJcVAZ9mpXZ;Rxv!@`%g(7tlJ9&D4!?0)!9X4$ zg6Bf4--6LMMDITsi%|iOd+Qh^w^hV>(EsI|V=Y%VemEdC6YIfg`L7~*=C+}7e)=19& zWyLvt9Dm#30r8r@jHnjb{j)W`%>j+9;D@bCRF zE7Hc?X@i;c;TEc_p*N@7T}6~T{u@NGIGTHoafRIzjDKMd5Adbu!mC#=rhkKGHC8e? z9>npS;jvE^02ZdUYuD1h9c-;^BPg7y?yHuvr)Ehbua&d;L2)Qe{*2&(^b+2Afd4e$ zXUJd5P;;8ttNDM7y=OFB?H~PpCy@{#gAlz3(W4tRI?;mYEeN8A(G8-v(R-cf-RRLJ zI-~a*-RNy*gwY=N?|JU$&Hv5+{hYPtth3I!zSrLSvoE(E{QvK-QpWuJ{d zqdK6NSzb{|(;ax6V4rh+go1e|9y<*MmyFB@D3mp%QiVMy8l~Bn)GpKDkz|%kp5Z5Z zJ!R(5G5q>9KB9npQlDQ^vS8EfmU2Qc-*u5pcPDK_=7F^JQ0zB* zk;x_?Dq5v?AL>?scV2A0rL~m5o2&x=J3#yLKGJ@McL89}u5?ibh)ltONd4|yXS79D z>p|cd&1r8!arurfBV@QEj$@^epg_Cl#E5P zhvOqw7NJQR(d`CM=xQ!mN~B>2D%*?4I1~Y$^y3bGeiuBElQ{exui<|D#W`Eq>--pl zX{t1+#pp0wy4U0vevO9mD^W>}Ys&F-zCEqiZ)R20yBC@^N+y9;9$)-8E=PGxDXK)M zzex9k7P};vJi?rYP1_J{C7Gkt`efAEtc(_QmM-#Fw&DJuGRa~uaemoVTUd>(%tM8} zbGVlz>0O!RzK>acQbsy-wa~L34-h-axj;ysoynLFk}H-Wr%dGRmGLfJ07_`=6z>d$ zOp(H;Lu{_<^M^~1$VWWn-4qeCr`4m`HZiVMUmf9`ue%BtXmAb6pD-2De3iizm z!3fvnNij*E8+)L~Ik?&NIFHK`F~mrFwdC@CWho3nDh%rzf~;j{KskyLW2xyA3%t&L z)5t)puR{!^=PvZ|(asaV|&W{Jb>> zhLf#S@}1sY!OM(dJAMn90LE#*SJ_0pfL#c(G)`p~4mm>R1AB zd{lb{vvE?K!}_qPg-$vs8;yV4jaA4YHHVMMYt}H0t-U4mVxUEP^H%^3Ph+i!%f!J| zx>XrvokRV&z2<&`Ob1CL1`Yf$(=Q5p7vA!nrIo@>Yu8@XLcR{y%SpN1NRiZhZHysI z`{-1mqt90n!ErQr44!BZKQs%fB%KKo5o*$zj@v$cZY2`)j9BYS&YX#K3galx7=Hr? zj*(WAPS3%IO@XGS+=(UPe%>~#7 zfC^*OwQ3tld=th7e@0{$Y0KY+14|C1ffRy)0QFv{A`nan0KZL}Yy zvxHC~HB93#eM1B84#cGouj-s+VWs+=#D8Z zZW&eF_1S68Q%|BV6`MWJvh-9+|ERpum6)Neh_XnHss;XhF5`UMYjUZPsIbN0(3OQx z**0qBFA&<&IOl3^KQjj#3fn9)?j5#hCt&L+aBbJMF+3vA8n>W9u(Zsx&5ZleK-3X64Qpg zwE1_0M@9g`I({s)ag{pL|yS?(&&CFKybwBz<=5fj-Cf=@}Vpsa(dB zZdc~b-`1rm6Z-`7eTasN#rNmtT>jARs_06%v9Pe@gWDy?Su5fVVzgJ7DY0H1uRkIpqSm56#$EXjuqa(!zY*^; zO;Q0-IITheanVf}hjd)&Z~PKQjWY$%ks(j;8!(2YHUT6|V61ocao^{T2%)Hq(wk z5GSDIYb49<5ZSf;0)mQfF&|HG(qwj!7s!&Pdl?T(_e!MnEnKxX>7t;()-X)JB6Kqx=?h5b@D+~E7u02LQGGyiiB_Z-N&CoLM@G_*&RD>@2*u1 zFQq#bH*duJZajhRhk9OzHT^?_i7XF1;@0ACbm03;g;*NSFaRx=&&6Sc!@Y#D#YKNH zff+aMzWUpD$FY5bd^mZ$PdWdjR(D~U=&B*BjTm?yEoPPQxpChZq zp%!|WmaqTtnD^MB>>!m}dq#xIVpkX{`WD5$G~DDf8lSRVl6g&TQA~+hD(lDS?RQ;y zj(qn&w=`NCAtOAMy#D3fNVwcdO;Yyy4n1O9w_62WIz@$AET`1wUSE5S45O&7#YmCD z2)naj*?m89{>ElVXL}RBn@`w755u9?4EOpP zHt9W30Jzx?3u?zMM`2~6Wn?8T|G)s=S8EAjzf)ZyAFEhtHz?FBe8x6v*SSX*XUd68eO9iU!8Bea^)L>=Bgk3tDUalBq202G6(13jzii zWygqI0TFxStlC|=!2&qB>#+zly^dbb0^Z2oM~LnN@>_nexsP2RH$sPT7?{B&QGJ&| zX|^mpcZScyLg||?Kjjp?I)0->?I9Bf!6J+xn|M{5j#n@zwnJf=VMOy~*VFYA^1XT8 zf-u z1f$)*@;7jD^RYliAvNy;9}}8Qhxd$Icz+b(%B}1B0+y9f9ZOD+GJh+D%IdKgUe!lC zrG&jd%?5J5I5%MUeFco!h7SY}4O!I(INYYb_jFYOtnCJI(LvPjgZ^ow&H0{+H7|0K zchHUD4eIfLC_@CKzh>VvW+7*M)@M`Mr4a&buH^!EfDzR4@DOC|{-dt13qN0I z{G@3!Zu=1y<v6IdSRXYD2?P#D%)2XqIeS&_XC29MX!IU9$JdrqDuoZ($WZenD(#LWb4UQDoV zme<7AL)^&B#m;Pd%4WFGY1~GnO*#YK5Llo1=%7eB@cN)3h_}Ir)%ugs)o?@6Z5oS4 zN}cpQzwXm^tMX45U({GMkJ*9ez_FU1hP)hAXSPJmrQEE=3_yTAOf?}N5DjSHS&%;T zTtLgB1My7>N^b`a)Y>*|MiuB{xof`}fA&*=da09;{?prV>rJCkTpD&YuX>*(r;oL+ zQ4HKEY5!xbzd;3q%*2|FO5R3=mDG>f(dBw^_OLJo|KPb9uQ5TcD}~pNfIlA(_g}Kf zEJV*W7zr5s)pl(3GLFVd-ZEXR5Xf8%Z(9O}a1Uo2l#g=a9ry;D{I&Z5Xxq`@0cAV2 z12wY)B|!;xe5M&hfW`0WHwerMNp0Cj{1tb`5SoWCma8~IT*H(sLV`o3V(tmLt;TSZ zT1xt5eTZH2A0F^dRPcCkBkk~`#}0FTpYvFP)ez~e8Xx@?%a@G6kL0fD93wR=ynv;} zxiJ>F{mVOU5rSy%-wo0sUZk4+9{?T-Xm%b{sHxmKT&7Bg%s6BKiP6-&6b$= z#A(f;lHTg1rd)9ZEsdGW2YUU&2Mvz71QdpC$2yYfW($tsy|;bO>G@B1(B3PqZ64WH z@`4r%mkPJ=zMw0~*l!_ss!=2t^PavtMvR><6ilX1qMI?gg~B?`jn9Wt+r7nA%w7WV z5xYSzNw81M+F$aR=5wEG^Q7$JnxfX)N$%9prmt#9k3JbDzwke6E#hfa3eX-=_p@bQ z%*SpsK{S;mVKk1)VlJ!$RjC<$?VfkHI3h#1|LF3=PDB8vrx>TGwvh|#2dy62t~E^f zklI*sZ5m#cdN_H0xs_|iYM*L?q>NA;067Xg)^`DSvgC( zml#}#e`v<|6u6~DvrghBJo>#F_r8l|Mv2lZYdf4(!AlU!#@I}~tyqhEQI;xI!Z}O& zM|}WwBZ22$`{%_sY5@dZ`i?ci4%(8yNdeV4wRHSen^&TT4@c7Wj(b6HD5PFF5G0Vh z*BMW)KNcl(mm7y@TnL2(0M*F51KTQM9WW85gLJo9r~Y z8wuunvut`|SnKm0Zi<~2xa}@2)i!n1tSGGcJ($!2-`Ho=x1(j5p zj#-VToY%7sjO2)Ay4V_e>YN&-PlKt5DRq0R%pPFhbiUuu+hujh7BnyCk(EApuyLxB zY6+EyTCSz(Z-zGRc{nb(&mJu1(QLm>bjDRdwrzWNgPE-0ehOX@8_l|mUqttm+y0gm zYqpT^TwMmz?rF_756gqNc*lU)my?eJErK6T9QXGHdT)INx{l=5dcY(AUuCy!g8C*M z=K^-;rd`vgeGD;jSE%RyyQIEb$}iQ$&SYDis}NM{ivhdo6641LVO6ZyfIa1is(H8_qql*6wUky3uY+fcxxFYN?qQo91KR3Q=bqVzRF1F3(Z=ShFi*UQ{ zLZ#>fepA;9q?koh^>zc+D%lh1pALuCqRnH@m<;DdCN;`E7M0RWdW4uo{C2A^v-nsd z2V8h7^{XPht)V2?gc>?!VY7Y_4LMCj~*DGyeF=;+Af0FEv+~L*gdXw^e>b9i@TySdxAvI{L zB`@dFE{zA=?P$wybV=-Z_Gl6A`{({!jAb*G-9}dH{E(N3ph@R$5?b;8;{Gh&e)Ru# zsHl7RTTzv#Z47MLU5Ew-6igY<_eMIBSR{Sy^V~!F<{zhYZ5fmfQuf*ljVc!*t<=F?M)_R9VZ`L&N~rW4bBUw^d|4{6XJl41poVEB zu1P)?T|e>Kt)#q-KxbW#b4)3m8c)8$*nSp3Xz8KWWr6 z_G!MdsBGPPw?9sMQBn*hW_B&&q)a!1kw9b#htA`Q2?I*JFGJ$^?O6?YOPqd_II}QFsH+E0bo*t;FMf&IzY>`uS+I9j#$7u6vrT62e~IA73M1G&h+EO zgsHXVh=|ZY;n?CEmB<;wOp&cmm}D!-s}VVN}cxV3&S^X(Zalc_a6#`b%XQi}U2WJY%zT-3n_{`iH`6 zpRDM8`}Ec~^ku_y&(dC%G3N3jxDe)oVxQiO>z0%kmghjWyGI5FBpJh5^cRd^_!MJ= z4Lp#voEic{oldF*GVf0ewPbdaZ-TAlzCP@wvTNCM8zZ|N-S6tfGLpaRZ!*xxi1csf zCWAA(XVYlzVpWqUt5$Vi(gHs@wp@kQ-mm#p((!A%*LWuk#L$%`z5p3W#U}qQ=E~x- zhJq`o{I}?RPu`n{Ag3%zwn{@}2|{6r+|v2J+1y%{E# zryFb=Qnet^5{PAFP6eqn#EU@y7F*K&&?PIr^%toao2b1wdP?r6b^lb(ukM@2#gqu8py}tpx zg;!4N+;!%y-_Q6ocgrHz`!_m7d}#XaE6aKLWot~tmw(=HQ@9LoRgYR=4b+ZCnTPY6 zeHgf#6*ehu1+i7FB;}i2D9vquRNe~*d_w1mooFq5O}~Nzqwb0R;m=d0 zo~Ek{V2#axDPDpsRE^0#l;I}P*xwFtdBL}Vp?In^)@IKbJ7_NFLfwDOg^9Bmx-0>V zTo>hfQh(A69@;tgb(U&d`clkf5cMX*CWB`7nzYK9H8AGP<|fNYA4ycJWigx@;Oa1I z2QbYl-&k1mKBCM|s+>lNI1b^@*Q+V@;^YFYr~Pgdqg>sm-SF_KPSyJ;j(BbCLdG zJPtlgy&;VJ%*5Dc_{E2-4o5`5z>b+ ziKuD$rocn$bwr3BBSsTUAcBznduwr=m};Kxc`|Z+V#OHyx2M^g#k`7Gy0`?thT&(G0Ll5UVHQL5 zpWq#@iaBLX<}Kj2!*Ia}vxGfkX9{+bejl0bSCg+9I*89F?s8?q%w@y|Q#N|-g?zi@ zV<@jtj8`>zZ023W#0-uWRJ+y}9=J7y$DCXyPMN7v591&l**Mx)UwOkf5=*BVq-Qvw4@cmVVa;rYnd{1G=dI7?k=yhmK zhkp%!9yNnNLrmqAxO(+;_ zyEMmgLp(erw)`-IZ3A8j&WnR&KJ|%rmYHX2(pfEnC5c!1EJx$3XmoGT*-K2{$RR%5)1@BOqgPFwuQ0v0>}yZ*`-WKyCCI09D68Br@D{*UFzKnA-_-{h;8V;t5Pe7eoHYK8icGP| z{(2e1J&Q)=EI%t>^FvD!=UMn2s^8d0UvNq|)W;+f=@!JFw#jYTa#U#Ab17reXY+Fv zdlY?qm2|aop6*_l*5>GUY*Cz<+E3`Qc${*QVg{`)h_z25yg#5`*=g$>{9n8+ z(QWnkKVy1|;lY!e>e~76pKoRV_=v^%!8jc`oILz?b$=}Okw(1R)+gxsLl7WzGr3~< zdddkm-V90Z3MLq`4b$G$d`f@>|03JKkw}vPcRhKFMHVT27}^vJ=ti%bm=(6Lf!~LJ zP_hquzVKd`^I{mQdeDxbK>R=~TT* zASDa?7Dv)r2e|R?`t*hwLgn#rPe2#~?XZz#9A@n#Mg1#M!-jOn9l7$zq^fZmeO^Lo z>Z3l-_@rm`w5^}x&el||7(c_BlYYF9OhEk>>uSfFppOW+d`Gq(^O#X8EkbNRv5RV4 zB9FqWCo9q-S!$9m^rMh&@Jq9APZ~(}|0%7CgEWXd+e_TY`Z-fJ#D%v$)K!o+1O8q) z$U?{kQh%CvzaQmp@p7NrWp%f6$FU+N+*4TR5rST}3WrmwzG*r~2tYbBXXg7O8V8f5 zvtb^C{O0#XM>_XwWEfSJ!o0RW`4cz3oeEsMy%+yf)GLbL6mzf#YM-SCcTj{9>Uh)4 z;0_sRd+Bum2Jf=4+QdHQno1F75>ce;i`OU8XUp3{!xX~DW}G5?g8*oO=kjj~zF0Cy zWYNyCeMv=)=U@lln(39ZGD>7k9Xvq@FP6nS8*JUkqbkB845&Q{z9uuVDNr!5iZ4^H z)@Dit9#U{J+ML>DzVS> zvz&%KoU{_h?b9|Baol*u%z=m6VbXi=4l(o=PWVP={>0i3pQ1k)wb)IAdQ zhRFrI|P;HyDM@M)qAS(?9kxdw= zUm17_fXU0j3KB^@ASD*D%!j)9eUq4pyJ~R!yDSSH`!Y;Kt_53h8lFZbZrHYtSl%@- z*@1p%H4@yh+-LOOoXl9pXhFY6qkdvcV;2yZVjvCDXj|BWl384eWv&(D?bR$<_NQUQ z_Bhy^2-m}ioRJyWFBMx0w13=T`BG`G{K6biz>$tKU$eJ7u6;N$$lB@b9<7X zR2aKuX*v~pZt*Y?{50kLffoRbI6-^oHf%67%sr1*Zo6<7VX8tVu_zfD7CtOwJV8gf>#O&kMT=B&Qk#cOg`b1Hn06?S zv|xKqsPx*)Y2osA_!GAz+RfGa%!;z^349mZUw%R*D}sDWW{`cOu8BXM8oF~4o+qIM zMkflJ-q7}Z?CK$8kpNYAdbe|B;qNRh9)foF12%YlK4+h{9BWll4s9Fv`ct-}x#bJ0 z!QZ`rjAKWSrG>~H|#b13kh z94>}!dKr2$bGP&2A#0sIXSU(>pb)GE?;t}ev8ajjQICveIIh{S=4hltks~;13*Czg@}`Qndl zw%nd-UEXw8S2YA#vBb1aSS!I4m*sQqPTT<}! z2Xj0uFxMI-$gnmPEU_)mcyYADP5+$fjs4j01xC&%X%IhU?+KW&zKg06t1qD@g!9@< zO_rG(dSf?FP|Q6TDN8vZ(qPZ z7d8I^4>T)hAuVcv34$#haedCAjwZ*O+_{D?FYHm-;NU)-9R25*P)f%*0!+&#-uIbh z@^UeMyUv=~%<=`bi;%Gom*z?ri5Mg7YAGL7A_%h{M$6@~;->qr8L@#R*{{)v1qQ0) zr{y!d{_;_yp5irrycr!%&|ER(Y@jA!3|@5MIn7X$ySt6QG!&(LzIZb2bW zM3ZH^U+bleK@qpMW9g0K6-S-kvZ|pyt!RO@35~+AuRLgoJ4HPmPkAxULHg&NdH=1= z%6T)?!8Nutl^zKkZB7T}cdFcje{k6hi#Aq39WhUj+!@-2rP$G=Y zrlpOw9I(~mu-3MKS;h6%){}Y~ zh-7EA(Ro5_u{Eb*%5fEs6&TOyN{g;_9QpfeYsKA z0y~UUozM=-shpg-(r>CA63EhHYOszXakXIjYVa}WEP(Y$lX=rX#w5-g9d~X7wqmRo zN%to6ml>c8*=1L$QGdMIUE~LkxXNWyj1l`$qLnX3_luD_>>;laAx6y;Xn$CzNhi%J zD_<`~tMJCaJjCL#E-;_QIe298zyKD*ccc@gjWg0sgr$$;JK4X;yxl@C>3LifJ?MH7 zqZDCU^N+KZ)kE z9%YN>NgZJouaEyuKCwH@At^UhCT%No_YRr|`81ku9zsBFc=?Xq`8-azn}uw>ooyIj zJxPD`g-Aa3+LS@%^GIRSG0uhARBV*1QXr_uSQ`>D;H@JuN5ZyegO4+{o=kiGR}wPl zf>T2XtzqD2myS{WsyYbtn@tYW606P{N52Q`hw=A!Yiq~pk((h;2VSmkJWA1dH^oz4 zNMDgN5xKT$@j-XOS*LYYX23=~9NMQ|Lz(i`H7s}zOl}VDZ_;tdne6Ug+1@n0nEb}> z7o!6p*jpNU&_BRZ^HCX)SpEf!TRD|b0&DQq;=L3oA zDM+G9=)_pJNn9HELuSEZS8s#DCq3I1?rFPErsnLyR%(;Z=I)m4R-gKYjh`K{(LZxH zOYhwQ8AY86?Qn1E(=Kmc5kL0sdq!v&Y9%z5)7!^zbYX7+jqar2Sg>rkBbK%+ z@upw=1v~Z$TYLv9G1+ugN!-U`&k%A9!M|`TLQmS(#rGZ01dnI+XR){?3)4{P%zaI* zjD&nG6zw3k#g)(McZGn$52%o0{d(vtZb!6%0`NTJ<}~MgK0vO4)Y9#En&4S*wm!>s zWQ|VyTIAetK68kOXSTnEN4%uoT81Xv>XAPF`rH0mcmroup+?IY%!PKA^ifG>8yPjt zVt-ToAH6C8n{w82l>4*@sC2ZU$ap`2H2HI1FrAeXulENX`?HK(2m!84p#gLqBfX0g z-hB5~N}>ybgh*WYr#~^RnZkFI_}og$@6lz#UASYn{93xOx9DTT$iYHI6<_u)8NX?L_}!-e_D2K(Ow#Sur{3jgyY%C$PwJ+w8jq;!c)~z_&X8^9X?jhK9Zk2AIT|~o?hg7QR*~|gHS5jWI{m;HLI6cH-*w}o?%H~hv8n(6FJy^%q zLt;wzcFc~$7*Bp<1Zd3i&#e*X8xW?O>a-oGF`f z%-=4doA3J$9sfqBkK8m>{>4L)xvQH}xVbgi2z&qKY@sChW|ba?oCPab%^CDpSkAsD z32`fS&Dz9p9O+R5b(nCB>@7(}*Qxw8`osOLvul=w+iJBs-n}I1$IBYlt7bFn8eg!I z=;5pC0PX_oYklV1B0MivK@rc>&lN+FUkQ1bC?9{gQCz3ro)SFTI>5QEmT3z8eAW~3 zswRZMpdU!n6OLC01JVqpyWS{63E!^+Bget3U28LTyhGD-unSp3mc)j%=zNsK*A5KpoSUPhywO+vLw+Hsz|O zztv`sMxU2~R8|MWY+@euuhdqDVN*WV)j3t=;kR6$CrL$kg+w2xIK-y}+@iRrc$s4x zr=D4Kd&w@NpLb&5R@so6bj!D^`1Q~SIe^Bx9ilYW9Eb3`Umo?-Oc89QkDY?`ZrGP+ z&O!SSbfWGLgEc6L#|&+)6C|$(-WrHk+!V{}JRRyN1b9IlE`X#U4j`0O!FW`r3cDJS zb|&}F%~}v3MfA9dF?hT{Bh~x#7t7*~GRgFaV8mGnDCNe`vAJ;B`=Bzu?*{H%NJV)O zLn}!$jKnCZn3$-aX2&5(@0!)KHhTsBk>raNnIAkaK%^jmURaosHpZft?$rv=h4V!j z{qxNi&%8S`E~H$9%#6zz`*#d58bd2f}~pfna#Z ze}T?ktc+Oe2Q&z?e@HNWcNg|I89-ew8R3DZP)>b_UD^l+4K*7|?`ExGAfIRpb`bFe zv-s_Dx4W4t4&pO%oUgj#Z7q$UjEvtiCc*~5--VVcs;1J)0M!{7jVB;N&&zIX2>9bt zJ%OqcWWsx%xSeBisG1Rn^OJf^BeTp8sr5yG%LdCY;2}w*_bszbL0G$*e1&Wz{$#_t zb(-UgGkR}7J;>YAk=~6d2M72aT>oB)Z~&~DYtymBJBF~ zTS?0{A{;74>VYXDx?$=w5RVC(hhYXdlnR8weVanfi+Ssk&!s$NQl zO3|E{8H_URwhvygi?r`>w+W43^*SSu#HZur_axG~P>OXE#$U1nLSlj6-Sq$jT%|{F18nMRtvIWkp38T_VxZ=vb_so2B^aB=dINZ1c$eqw zKZ?xJdPy^B`>~aID5u?E&*6lo@C3hu50pqGdRQf*OP`^A4Y*y&-p&zSWg+}QV`VZP zIcGqBm?t}4XB#$Cte(?K*5YoJ-lkznaktoNP*VQ*Nj!*UjMml+Tf%;r_&kO1HDw&U zY=Y*&EI+`Rd$veF9jadUHE_<2SBV^k2{M$I^3cfp3YZ-d5;(EQ?EPXuRS-2PpwXJRmzA~GXRhGW0 z$G&rY|8n>N7sIzk?;TqOfm*6N%O_hLG^e$sWn*qtmTG-KpevQ?+n0{E#o4V1CNFEG z!D9?QEwy{xl!9gI;`IDBE2?2;bO@}?8G*MaJwBzs!0+Fyl}M{IagePNS94p^+dg#5 ztz^*B%NLi|PS~YLObf07KqeLgC(*K_)L_f}dve}ri;L%~2EDHYk+(8C=aE|dp$ioU zToNI)Mq^$pRgJc+N1Ofyta784e%XwwKJhTkD4g8*Goj;pXC%=QNECc>Gl+|i6rmBI zb$%brkstJ@Y^A;DkC#al@~6;FQn@9XZJKz1A5(EfbTT8ns*lgxjBJ6CCJwZ= zm6=w4dB|$4RFN|51OKYUo%UO;mrZha!m+Vbb)pCLUl)L}ONQOsVc<*p)=0d)Wt<65 z!;Tnp@YOr4*)~UWJ2SGFzh4*R9bg?rGy1<%CpX|G-QMb5==c6hzpe&SvkiFoo2`>o zn@tuj&1F#`=M9ylZR?el=_B=g534kA)%>uX0cDke8--~xkp4;mM+$BFVYh%H?C2P{ zdNk?%rfvtAe4i6N(!NiTZX_T0eM=6Gtc@Y2iv_HiZgKlF!EZK>v8 zV+I)u#%ySv>GDJ{@RYz@u~A{5>$SQ;mX^2pP>Vja4He5T0sE}2BZ!q`kMnxr^btLg z8`0hJpm$mG;`aV3dhl(*~M1))`r-S#QOw>7C-j$kmMo3~k*fd!t!`&8n6WPEXo3F7w6^89V>fb;zBDQc zuyD^ggm9ZMwfmy9I44qgjB>xmGBe3?^YQ~dveiuq&SMUq6a@V+0(l`{G|)d1!qRP~Zf%0Cr1C3t+t0jq){abv0=Ut9J$KrR+lL2mqoIlL&0em+x@%{5-7q!0o zU&J?1^ao!gAoI1A@21bPQ5->?w}uyt*9m@~B^M`$7TRdXF2Y;smyQ|}uhZu^S69Zs z=3VCfUfGrv=SD%!F^m$-nT7VnCktvR@Xb46B;WDhD3oLN@EGcDQ{|-Z@YST6M`z~i z5RvVcMpF2};@}Nr%CXNuHjd{OY8`eI=lpjU}}#J5x4WF8;-x_;=% zdm5~=wwqMzp=~oue{qrGoKM}AA!>=L)cPf3yS+ys+v4|!wHviG zeGM-QSJ>=uS))~c32?|sdU3oT@cJbas8}*$Q@A=G!Eej3tcCl87}#(MxncaNqd8pA z<@d&hz?=>hP%HdbcKl=6V_N&)YzKg3BaPSB{CWp_Iu=9>`4)_lR?G(x$MVq=>TFo^@~SwJ>7M6-imMNQPr~JlkGMQ)-#j}1n-KtDR#;5 zG*x14w|g}zLtmEZUzYiL_v0#EisgH68fae~E`Yq>dT{M=ehc1uMw8)^9pCvGg5z+2^q zUIfuPAG;V-l-un44eiWXxXu_&{68tB0o*s6{}5jGsNHhZc;<}D+)@)I$ByhGY|$U% zfYGPfX9~jpYZSN3Xp>uxDxD&~i73-I>uAr1B+esaXnk2d&G6Ae0}L`6lbqe+u4>1$ z%R+PW4d`=zcD}_UK0X_1gW&#vMJI(i)51j9;Y$z8HV1r#c(u(7@aWgq?5GVh-o!?O z7#1c)=lh-$=(v4D69hJuljP$sK7Ka$w2?|-awb#$^IQ)6L%U|ltpoUFfbC+w&PA** zRxZ`w#Q{6}CATYHShMDJj+iT1fFO>5@2BK$Z$76wSECHu-U9a=eoIPA&OWUgl8CXC)lk&q*2r#lDEPW**w|t{acI<6xBUwRy*33 z@tTvVtXjs~F`mFb)I7w1Y_^%q0ZVIg_m%wo8?d9?c(^E`G~be436DQ$IRnC!x6hO= z4sBxgh_%z+vC{z5q{po(^6l(vfbfNp78lK-r;q%Hb-fSX;`fViqI?trf@ z{^P-b!SVFgfZ=KJh;^|`0N`FrPXn&|mSl}e7I)qiEIf!L(!!3vW^a2 zMLXGt`)K|O(~G$!ey)+?Jzv1_SW4E7m3T1l8Y4Ci7OltC7Clw>@SBq7X z%DXmy({L(6k=nA?C6}8;pSLTeH5k(72*mU)kDU*{YUEItygqO}=$AO*6S1Exc5JSf z%JO^FO&`*e#fbA%3oH8c@^qaM!|?m~f@)`R8vUHIp0C_bO<6GuVV*@RqEPFPvr;pb z`i9J7k!jpx^hMuw05(lHx8%31IXH2}GK-NhKL7Y}+RO4Bo+jQ| zE&KmjGxX@d!uIu>zsF=b5EMrrOV~^sbGRNPsMB6j#lJV<9rAjx5&8qQMbe=s{HqF=PSW8S|aa(k6N=fDX6V$!F}Hf36DD0pDqrnjIH zm6q!ew{!Wbj;GTFnigj<1BD)0UV*dMGvdn!krE+u=-BI`d$PtGYta9Q?wx|qu>UsU zmj6XH(dm<){=i%%IRlcjr7Rb# z!lD$(wZJd|%9C~Uy0N{a;@?9yJWx~eYZ5B`H{{dY-IPz9l_|g zf~*01NZl&9iN?~RbP81vc~-`#Q9YX)AhM$&<6p)}qj#zjFcVMyv9A&>6vagt`;~(Q z_1;TtTk8grKdFD zZ~vQ5Ig>Ie^p%%|EWGQS?4@I0XV$$Uz7zV5eRwxaML|8+Hf}_gu;LZL5f=8v-#*Vs z(F8C%qSKl}TWEvatz^zUd zox!AccZ7jT^Wd3ZJZS0d>E6+qD zTs(7tI!)G?;khM?1u=?6c}3{r3;?La-lTZru;iYPX1BgMT+}aOZtyO&kLeBKR_eE^ z=WWCa11*L&@S@pG(YRN%wj;TSp5=qrku1`8T zv*N$41?#x^XqJPsh22Di`52qcXY{aDf-RqpDobZixk=t9^!I^_!r(agsqCpeua9{2 z$t4@BXu}VLf0BXZ;5g1+F)kGS7Y50Awc_TBwlOkP;j}Asl8bh4_iPw9hZyZ3`&qvz z5bk1YcD!A(uQegnounmFAD3?1FmTSazYVYbHz!Bc(z*~R<>zL6*E0^OxXQs^I=_n4 zVtqNAzd=wW5u-*woU>oCCCtrdu_WWZu7&mNz1kC)Mz%%jr#}IkJ#%K8+(>)nN}NVy zGm8oTu^_C#Od1W|Q0d}as&0MI%p&d1b7bb#)O-vw zo^c^IvHGD3o;xYuK`{A+#Y_tkLv*LxC-0L-*KLIZL;)8~Ci|vY1rThxR*nIgdys@-}fcGUeQ5u`q!~j44$M5(403Ifyw* ziq1R{@jPScF?Xg<`a7w*w&@032x?Qh4FQRrsKw2O4qT1|4zV|Z>4t~YwhaSMt`>m4 zma4GdiQcjAY0Y2gES|)8Fb30*w|rt(SZJaA`$*MRp4+o~$;Csf_g_E!!G>>8InnPk zJ=4yN49hlFTzf$5Ex8b~2FH@4s5{{h{+?#_72@8)YWAm}SaaaQQ-lWeTNcU_+Q*Ea zmCp?31l<+}^6|`R7mqM8>Z}RMxt!9S#4j{bIG;L(KVePn`oYof{L^0_M#+-Nk?Opd zXKas%9BY1z`uzkO?)N;_{iKRr%7Vq0p--)GOyah1mG!$N(`TJPE0V8R{WxZc)Y~BC z)_IlVK|Fa@`%o#2;{8-Am*EhjpOp;GNFS-0B4ROWh3co#BZ^!WiJf+OKg-Pd0M!_L zujw%omvrtuzP-yN`?tyi!Y?y6ITQ?zt+Q-y(Y)=Hbx^aKbKRkQ@NBMwbSGeCvwkKz zkuPwG(y5I{2P0P^|DAjDetV+jeL zvdW>=CpC-;8CLh1hPO1E+l=;R2@U@|e1cv$O+0u43U6C>alH7;cwh-}IYayFBS6y)OFiv4hKdnHF|#c zUD0h|Dw)Ur7VfE+!&+OevHiE~-%f((XV35F9b1nY&o@Xrg~9n^fh(78uuuW>1AzZ! z_rx=YSJh9fZ~9Z){%q-ed=|Q(zG#u}AbZ@rF9ymuQ1Ot^fStn-N{e|a9;0jQl%PkF z37l>VEX-?Kjp|p2l6$CJQPY+?Ym*{NuZ?=u<(1fHnUd+LeoRq^3VrEnz{hv%EJsLp zK}ks!e+uM-LNpOw*IrNRUaR>EZuckj@4|O|)%=&YJ%Fm_D{nmO3#9|ZJUZaE_vWZY zid@=1%W~3$#(LqwA)iu(yO2M)LA98h7ZOIO*=DJdGH?;#LscOd<`rH%`Qsi*y!4|R+WH9Pc=TmLJX zWdFCaB{IJGzuuRM@b|Z$q_rP94Mc?Y{th|auiTx-7ZY5H)jj-KKz)E}+aj!Wqxv zLM@}jk75SC)^j{n3t?LLbcH-TJ!%f^_F2#g>Cou%+L}8qS8Z2i8P4RFoJ~C z5F!W?Qi7BcN)0neN+T%UAf3`NAl(ezT|@Us^Kw7Wd;gE;+di&O`^!Gowa#_!--u*0<%`ar#o{K=0pL_10oLEx{N9R^K)X;gU{Q$)@K>TCHpw|Lw!2Zc1MvJjaI3 zb*G)~oQjL`m+vKGDP20Zjyyh8<#!Iha!&5Upx`&fKdi4M2J35gFuqN#f#7!d*xp=Y)6VFV`ISrqpoXiJ z)j-IY#F&&}O3nUvr^A-^qsf(spO<^}0@L|&f3evE)B_Zi41uoRT!HN?>-0nAyT3A^ z=Sknkyv4r`T|fWusDJZu&!Y()wGQ{rk8SQoKHM3eZK$4Kf_q1l4{08EO3?H7XuSKH z7kK+v*s)^CurP8qt6eNPFr_D4^Rj18(-_`LvU8$8iU@br=!OS%%F?Omyz`z;JN{(- zLbm+%ijJYC)ZDga*4GWhcr?*>jvp?REqeEVQeJ;E7q?)p3%5iMn`P@iKb=(K$IS>0 zO9+a-`c_pj^87y2fT-Ctcq8FCnd@*xL1gB@d3*i|vDo>2icYaueZ#nqSEQ_>B_Zbq z)5n}9moe_`ktvn_&mC)&tDqk!AkVThJ+FoysdbsNhuJ!e5287Jjcs|tb(f5T>@KDz z_tvZh?1idJ2ggZXYb|nQ?m6xKAre`xGcnQPabIKk{_UPMx}#QmBc=F8WgAD%K%CB# zV`Vl!0 zEL9c@yl#`84#HbzNcQ*;B<6f1dg3aT6;HJOjR2DSo8OWso8E`R%9c z0*D|D6#~mwGVlDLF>osVq1kqj;IGr(z~#U^;w>$~4^|dP5rLK8U&A5>k&XVC$oD(K zxL}Nrna(YpA7veBnv^V?(TG3qL`&N7^FhS!C-r?a*M|4cA``!kYeK_d0F_}GYpGmA zBHNTSr_~z#jmFx9eNC!z;-s?YWS0y2WaiS6uF*q$nYj%bbQ?s4cZUi`FZ15yuy7N6 zY^z<^Wj@W7PnwZ~o(4&db~*&VrBeA#oIra>Wf)97l2ehmI}G{8`J5Fh{du_!#QJzy z$<1}j(x~CRto{0A)?hcMUT`wzdYNMGWeaif+)-&JBU|1{GCKR3ap6G0&OoCG?=xuVK+k&q#MG59OgTBLd>M0?pXNW#)gA(HO$d#go*>ogRRGU|K%;{)}5m$4es?vA7mKAsx<>xMr)S zT4{WdC?xSe7Z-UoS<~UL^I_%!MV&_rv@0jcbAZt!Lieu0*Qjji8&r|J|}EcucyK#&?#`KGMlWo^TD8+?9#8{(ON@qorK;|2)q!# z-<8i~rgmJ5P)gu@;}&XnKDhoL^yxaIxTpR9fcHw#|1shwHxB=cWHjBTwuTzqW#b>^ zW%w#r>!B`b(r#N$QL|%P{J$JoPt0BuCVu%h=#@jZh4&KLYY#PrP_V-71G@(UW;48J z6LawHMkE|h6j_~cJM%n$7qcMYTfTPPtehQ{3H)G{%5uK7uREjg>aF+l-P9Wy23L6j ztwi`iUM$=)Ia}D)&uu)t#HTsqIzc`Fh4}*?bM`uUuW$O6#0pCI4Mm36jEUD52gIoX zkK?io!)(i1<-eVM$I!L0oZ@XQQ8t-H*15`~v~9KP9b{NTe|Wr+&`jH<*N+!z4~k+O z`^n5E|1%w&FZ-xP4p;7veeapXNkeTauFe+}!11(=-pL$a3mKqF@NIG)2HMb2KjtZA zK#Fy;<-Lk{?Untq&(=%RstEQ)zz-GNdY5A#uon^*Nn{?i8q`X>5gV1K9r)>1THB05{FNpP?MzAj2wc6MGU_sYxlJff_u1DY3)Y`vtI(0Gzyj z+A#s}zMS=RJmyI!@pmd%|3K)bybHuj<(-U&v5Dy7Mn1=$?xj5Y&%@V+rbU4Y!jex| zU83S>{))(iq-#qSXgc+6jYz|meBHYPD#g+zzGkHMd-rnUC&AR-oH(+McD;9#x5!TY zus#bJlTR1&CVWF@_S!~2@SWF zX(0WI+`GB>DurIC-kF&hKyRQst`+?jMyvkq=vUiK8T9^|f_~k1oOy58&0!=vJSdiV z40Ie1qNr!Im31?N<1hx$n5#gL5mgzUsfO?9ZmRTwml_NCCcoqS(t8>%OHx5}ZBbyj z5-62-9{tt1#%pc)(`mc_Ih;iKx{}724pM(4)fx?#<~_I=I5^B<4!TwEE|c&&34sSB zdemI!c`sk=nxMtJo;J63rW*fws{gb04<7?%;oE~4e5o>}gT>V6Q)87eha@KwR zdLG)mWsQ%J?;DyA90dTn|=p&t1G>ddH13zRK4iP+0$Lt-v03qCfUS` zA(J`E=*5hCDf=BJRRjt9R{2RwzMzVtVe?kl8Wk})Wi)Z)w{u(XhA*p~RjS>QGA=1C zO&x*7);SW`?b1{wA>GPRgD1$yLhg_5m7n8-w*{$W<4>}R^uK%Sy8VO`j&DBrxC&tr zt86!UEh0%LtOfT2Q@Il#u)%}DwvalBV%ze3J=GHe@ZEZs zL+QZOEyXFrrqF1%yp6ERt}7unk5S!fm*DXHfrkcOWemf*0@Dc;JwN+KsW^@DXOU*T z^zqx?&oP-bhCI6uy!MqB>8UT-y$!j_#RaAxhy!M@_{4Dl^^B}%pK1&+vgPpmuQj9^ zr|FZOjx~i@;U}<=d0Dm(SsNEZVR{X8^61@DJ@Xqzf3^HzqU$1+g_Njf6en$oT*>``X*97)he5_~p_48FJJTTT0t_#_u zH`rz?f1S#1Y*)UcI|yyjCcx(Q76f`Mck{M#P2dv`$?l8T&z~E=*LrEinE)S%D*@=Z z8QeS7K^w-F@WZTUIMeQ#44#PhII&gqJ2}V>&=ZHT9vN|+L;L?z;F;=V-HIouhdw64 z&kZI?Y6 zAF)z5gJCdyFSYaMeuL|;lss`t72H&#CRZCFaab5AXlFM#6etLa1C5e*mG9|22om6$ z1r0w2jdEl|Y8U_3ph`fPELqohDVLz)ld#l-`@2A7TVZ^LK++G zF?>K;k|iVKdhCRaq%!<5U`edrp`75MZPEPfjLme0#>8ug|Hnsw3W)B3*1*ZHWx9Eg}e!H>t%8>=%BrqLYLsz3-y6f1^_)Ds*Cr z$$gycYBZivyD~RI8liLoyJuXszOHH(5Wo`?#QN4j-`IzSl(%3SuVc$$4kv%GIVEPh z6%1vBo@q9nWi{>NedAoKuo>@|K;tTxvSW=udis0Is4Ud#k4*hDW4^fE`5=3YZoVPh zPa@NxbDwgI6hN5WE?hP)FrZJ19NklFRAq$C@VvJA#TP_b5>D^l2N57#E(jS~$T)rY z6xuS`HhG`^!ZLJ{I?<2QdHu!7&_t)6@{+Ip;b)6);mXKqbH}YT%N?u+6sjOqku_?G z=B8F2>G(RB^aajzeV<+2hWP^5_2}B!e)BXqG|DkW5ps6FMfTjAj2g?1(AG#m=Ny{Z z+4+a9I0IjH?!^bXN()oiEX>EsN8`{*b(h%{r$W~viWk3kVq~E`UYYMUCq{DMCb3u2 zjV8Ah90<*Yia>O#?D|*8Q~|JA2fk1!e-Ws+&V#0b6zYz1FUU_aPjb2a4Y=mAjjipV zxtT(q%mr0sZD2s8loyN|(`-j(KJB0of=8rR<9wxnbmX>9DRHU3X<74s&XN6m7>B_m zN0yTXkMoNIN4z%-izym))F;I-fPdk^=w<3RRyO{dj!VtY0Ck7)xSeXu3?-^Stf z{*7lCDzR_ZhY@v;U;%xsE}d`@=vv`CLic1YW-n1U=h0Z#U&ToMp|CUy6y;h#`?#rq z%qo?&%ZI>JRO1ej3(+O&je|Sc^H~AAis(}hO>(XVwRFPSVfiR|9}SsL^)HNb6tp=m zes2s^0dfFk1j=Gh82F+*@pni2Pt}tdnMOW+>{sv+cidW?{2u<<*_;`3k44xaKwFjC z3pAVFB_Bq}cISo6wC3z|bNC$Ugt>l%Oec_>Ql_#GX(>I$i*7M_O<3ed-yuWZa=`Lu z%ZBwV!2X^tdnrZp^CwD6Sx5~cKV+B|dP!q0Fip!tnYfe|MK10wqr__-)bJC5_cm08 zE7`$v?o`mIj+um|A^luIs&qJuAn2hC82%d9zx6vhn3K^_&bQ*L=El!xyS$gxznQrn zE3qWx!gVIh1Zl%rm|s9(FDFe^gXA@Sxo>T91#YExGEnF9kiKC_P_OtsOBe2 z{n)eLT>=0(7AzFgGLj%%E~_*IADP~hZTLimlpfw3jmS$pn;n8%d_>GL%ukGV=TMxM zZYrZdzZ~CcKE61CaMw2OEr$$)w22Bq zL4sFy{FS+co!X|Bnw*T!)1g`t*wu}*$a>Ab22T5{P5(JOm9?zB<++Yh(<#|$!H*!p ze*Tvg0fO3%Pm3Q%U6V6?KgjiZZ?>Io)$Kpv;SPHMxK!h93Ra7D=z1v?!)L&Jr2L*j zr5jYJp?R&gUr~5craq;bxW}2_@MU4#GJ(#!9TjfZ8=XM=3Vw#PUwbVI+yeB|@|GH3k7$7KD-Xp9QU z0sjp@j#>pk3jez zT`dz{^HJY)G<6USUpTOyRcwSM^fAQr6TTKNSc`oe=Vv2p&c-F>)*z;6Wx{XYhrvA` zCe@m3zmirwruNPFnM3+_o7>-PZ(F*tJvMNgPau=5_%AxGJs`o;1=P( z23`RjRx1?Pa=JjzLA2^JqM@-cSu>F2dtQz3wF(oB+v~9sZ%Y72nl+%Kj6*ox6BZoh z%ulnDu5*%%m*yG2_zDR+1@LBqB{c)!>+D>z>;mqnx|bTb^?hY);4jcOjayW425$pa z9(fWnXkl!g*k^wwcpM|@Ql@$p=u|@E(%8?Vv~li*QH&e;x8@E#vgq@Mw(zcGIckH) zJ6avlS8D>756rHD&P{g@NEMO@!yEyjg;`uua6Rkodui zaHthpF10NEd%v=Xc!iSQR?yO}8UvS?oV?_Ol=;A=4tO`~Lt~sg9l{LnsH^*`895g> z>W}Q$*Xal*SIdn!c~uL)M33rdWHFbsP#^cD^tp0OJlbNj9n2a0XYP+o9XLj~59A0$ z%N8+0es7`+G~r#9E$3B&t-bgdm(%W?-3o8#x|qwu@k3=Jtmn;YJQ3UOVVQTzib)pu z-e#(6TV-NX?<7M_3Lt1bfs6^-_0E~^ebMb4@(K=V^R~GK87>yyhF^gS>Vm5NEB+w_ z1AYIwCG@G)3K~59e|G{~K0)a9S;yC#&vSou#YjK30f>13a#o{CYxtlN8IQxDXk4j~}X zx=-(w#64wwM9B6S?p;0j@uLxi8Dh`txVP8`D#%S-z+Xsma7|2<6jK0=`u@fNw;CI>nFiM^-jdV@Y`cPdi=& z=j&NX0Q(E*Ed>n((n)k@3K%kL`SC2KtRO=6k_t4F2N-P?@fFm3y$s0x~?%kpip zqwA3NWO*bhbel!VtuNuivVg0o(3&{n%q&Db#KxwMJT<);D(xRCxInJ;SoTN53_XHA zYvr(+%v008J$9=p6PcZxWZHB3R>$dNcp>AxnE`8}xkiywvgg1I6K zi~yVUo%^r8cDt2|G0u*+mP&o&-6oV+JV_=+tsYRzwEcx7G?@c4!-w=>wd693lFu>n z73Pp6n;XiX(X5ss0G+(TN`kaU#zJkDm1!b3?~W+|jTdIBR*L<@V>fAst_@Y=HGr;a zhcg#@PRhhjz9tbzZy_yDC-D9nHI}0I5Yt)fq0+7PDtf4HY5i{^;D59uV8)l7@+`~0 z?bT2_t=F88 z+`R(XQ|5+$hX*(H7kM)g-W<)fkY{t$+>2EjZ|YtD6tcN{xm5xSCUX_Gb2DTr0j9?N ziQ13+fyD%BA1>upF;|l<*4AyDSg zR)Xcdp-C8J&pD4f$FrWxL&Ox1%)hpzkAK)vv7c!0tNe3bm>PlKKrW}$t}ptRiHIg4 z6^BfFujHdx5TOX}ac|eKvraa7Qy0wG#eU!(@tj*i==N*F?);9Mhbq-P3;B(|4k^7r z{hKg5=h4j~75}KErzOi*383=?L12?j;bB7C?+!iNxTDx7U3!mIcU4c`Lp|PN_HTfw zms7spJBYE)1@gXvEjN~0`m|O>KW|23J2p+d(+0sxl@O~PyfPshHw&iG1fIOnzOS53 zg{5;YijXjlW??o*8>H+&f^NJwww+YxG#N!hdq$I1l@BNXF}RI={jKc1hn8ufL1Mh2 zBVSaOF@apB2sC$2!MkEb<~5f&kW7CNrm6zYx1?N;*#B@51@NEz)!@?l{11RKA@ZDy z;}^4O?^ebBzWPD$>`&dqc3sEb?F+x16LZ;KRJmOB7n{_Fc?Q&?^S_H@r^SP5#{IaU zY^oKuwNk}Exj)cPFHUN+0{1TKQs!$_P5iZ<9m?}@9dO>~RNc-mbn<$*Je(}%g0-bb zs5~<$NM;g+VT%Ze?dwf(4H2LFp?D+l7CFk0p2M|9sF=SU}H4)rNg3 zwv_qAw~!8;#y3@fT5bW}5xD$Bqo%A4i3aX1lFwtPBYB(upipNJW_Na}vyKUPUA=^HD6HGU0oDHWg-ke){r6oaylq?5Q7SG0w}VL?eZWP()9yi|*i?Xg`o z_#OU4U%vOZ#EMEP!2y^qS{9cR|KeC6Iwlj`tOnD`I>;cWlW3$9UO{r4oi6| z4*e&~;pzUx)yT7#O;G<77}K-;%hpWCUPeo%lEjjfuNPKi!_Wlx%UtgYcxB_$?hzFT z!{S1riI>=>sz9S?!^KtsArD^oK*|f*b)NJMB^d#i*_zLDw!S03zN6CK@)j~J9}mjz zkNj>r409w)noJUF@fw~lv9)`(ka~NyF%OQUsV|dlj{UMuo-zo%ECdrQqLtQ{$Qwhi ziI4|GHqt8vrR$t^ya^L)gLH42Z57^>6`^1ET|xFf(V-0n4rXl+4^BraY4 z@Q1Ci39_)=Z9>S1#f<{$0QF=)f}%f*)GMURD4MEEt$|Gk+e7qRbdaF+9g?RW8v|me zy>3xfMv^kv+&B0kpH%um#6edv3@f_3yxhSKyk~y1&&Y z(~r_Z6Nm9NG?sp^g)xXr)p6pHu+Sbp^+xIE`oe)KqQP;6Ksok?o9(Ln7c#S=r{r$B zia7f0Fph8%CCT?=U&M1A%5UFAfDWgWH$8+a3uAR1El)^fy9GhZg_?RqA+I7+IpVMA^@t<7C zV`vZZ&Q3(M`(ZeB&J}li_++G)mhi3tCia)Cp=lpIxbNW{;arl;SeNBp`xkWti__FF zT2DKp8qpoct%?sm3Wu4k_2PlNp7qm-CHntBaLGoi?-6C#u zZ|k*{IH2I;K`$k}U=_eFOg(wn@T^4L=P$6}MFm&nKOl?uMQ&0cVT*b18_6Q0XU#bR z+v(C!v_P{z{M)#^M2D%785d;ubNN~E&OjZzCY*V^(+5s2d+=m#gz=qbgC~s)LEl4e zdz0KX#L$9FgC%lxBN^CdG&xmSNF%UAZZfi|J-D6o1!#=)+8tTK^)uWNL#Ae>#Gwy~ z9R<@Ce*uOHZ_M}EdjNvfnO!yHg@&FgK205!&|;-2OZ>3+O13CS63MzX@ajl0&N_{31pjl1awe#&;ri!Y~W3WV*ho;{8;CY`Xq&`50X^kXGLPTcz~ ztB;J2V99o`LdesR=|nqPS^s;+OLH4G+6d&eh`|Q5DVFkf8;`}M@o8H^mOu)9e2fgA^kYhoR=nhntOAo2BCc#xnX*UvM#E#0vFM$q zEA^IcOv8g;@gMvShB!2!M!X}Z2@}IiGyhm+43dMzRCb%qzO{21uV>yHsvOG$$pmS( zM8vs|f!dh1#QnHBL<1*3uY@V^1#+_{u ziqg#rzsRQZ&Ldbf+PW4GK?mXuvx2(V2$KkyPJs3P6gPe-9}t_|8?#k5M?fk%)>-b3 z@!fW{YpQsmoEnq))omDT419rSwVJc>UBZ>>K!~LV-;K?7xNGoxD9UhQgr~%@>9`8+ zOL!7IkAbCrezg>Zo{V?WwgaexQG{m}jU0}S3}@Qm{Ft3h$A>rQEHKJyi#XIL3B>`l z-Vn9kI;z%oyBp%86dr?-pks=~Cql_*v_r$gJ>8wKxfAdRUh+cbmXY!-p#2RDLiH`0MM~I%>SyPLB^L6O;a1OJ$Jt6^z z8Jyu(Vm{e9J`=a~ckQ*=du8Ib{-J zQT_r?bfB&qO617KV$JsNJknRf%4n&zjNL2VStBTi&z9Q~iy@&r5gC*=pNr)Bg8PnH zxT!j4m$Ju1bAi5H4MljbMiRXwQrM7!o;&;-cZix5%3U7~zs)o^S87Gc_VJx4=hd4)rR7xPKN(1zz6$Y}&eTphzN4kMU$(}y8Yb8@ z$NYXU|NZ(32aUz$=@~KWbPSfGv7N4dU0tNE+Rd}cYd8P z8vMs(O9yi5zcl`@0Jno8?CzBMx{K3L^68`hr^`y^&29{<(!lhu1ehy5<6AekrSBv^ zM2O^MgC7FaZ?Buq=T&0=Iog45M@*n%v-7DA2St=#11)!=oJ8mqv?qHNf~*J9a+*0T zejZ7@#XoBP^Q1y$;>U&}q7t)jjjz2--G(;tVFM^JI)a#AGr+9z-hnDW`sv<#oRkYg z_CuCxmT(fN*5~XZ2M3y(AVOLdC|=3W5!%_b5}nKtq=TEh-ZR)dAl;o9R(lrX@Iwuy z3NlsOE5qw+$RWDNQU3Fj)H7jX#k%O6_DuSNhjW(y)QcuG=Az{5eZYdfTzm0&(h5&& zr@AzNB3BQl_2{;p9E60tdOkZyyO~%`fFm+_U!Cv%mkLf0%FQ_{RBwgyUD?_XjAm;%!UWNO75PFkE>iT2Sl z(nYC`h>h!rRZ+dHe2DS(QhTG}L?EA!9&>$G>g3qw^5vGZTbHlOl_HBNlMM-F0x{*; z;+e0cmNKV=WK93+f>Kgk;Yh6b*JlAUpf}7tO0LCW6AyDLj;J~E@ zw+~BY40H>r)p~DFY1K|Ab1QlO@)9$or4aZXcaIzZ9#m(KNV(=yEPmA(297rHO;NZQ zh=3{GCST6o82z<873}wFM~_>{SX=Qq$(*>QV3Gb^AjMT+yT^_q;~9p|=$um~KfHQO}1G&AD{w-UxSD#wqmkaJ@Vh zloJtb$PCQ->TnO6Mx>F%(m%^`>9a~e{2QbgBgS1iP^wEh|5bluZKPaL?Chmhs0Q=+ zC%GakAvOQukM{GkVvZy>+}9iHOPo;9IlL^k^xD|vir{V1FXjlWrIIuR(}>4@%>Fo zowSaKlj|OT5NH#!x>aX+4{2@JO9XFsVJdkzlA`HCDHxk|^z92mJKaCJymrZtT&^i$ zx;Tney|m3laVb9?$4pg_d_|%)eCxv_J-PAQhuuL>SJj@)=G`fxwJKu%m58;Z_1dMR zqKvDqV`BJ3+9W+augtK69jIK}Xa;@&3oHC`^->FEx$je`Xwvz*XfeAWg8f5UY--m= zIP=y^>#VMKiE}*6U9Ku44Uz%L6D2W28Y?~g-@wfj=hacBa7Yri;U zMiMb5zY?8e%o}M?e#kD741FA8oN}}$AAKGb?}aj^=tNyaey4=)Oyo29uq1j2<>r(< z!?Evw-6M_lsBD*iV!~67^?UJf$IzZRbI7))|K*j^=mpW4pTsOBS>>o_@)7R7=*2K3xZ zBmbnqEYA$hY6EoB#_k_<{fdzUm1{DiKEV*L@FbsX{a|Lw;NqdG1BCG#HHf}*-{~Pv z!FRzA661O?=-$GRGITr62m5dr13}N4VVz&+-9NB6sjx4;a$y(bcWQ|MfL+4pyQ4G2 zg<#y;fPNXxU|b*gw1OIFL3p*(l>Jf(X1t!;y)R|Sj8?YDheCuV9cY;sCc!aB@z%B`u-u9y=~SrjffU<~m(6El%j=QWMD?5fsjs_!~! zZe;dD1NkC(?1#P@KTE#purldt7>e-d2!oucLY*RUqK!{6gKHEB$NfnruxiF1nOHfrY<^5-9&dBb2|y-1QxI_88JJJ4ADB?6Jww>F9l& zNGQjScLc~-_YW%c^x87^ydzZL@H>?8Ysh3TpvQf>-M3Pi3sdMH$EOn}%xFFqQQK(B zT6WU%o0A;b%7%jvP5s`XDKFOpMQsJP8E+q_)}lIus}T~%!Csi5RB7RZ=4rsYU7jLR-3g^ zE_LP}gwYWKafD#FzI3{K=)i8v#fpmFNeA>+@Y*vW<-^hT@HuVYi>nN{PHLTd(;4$= zp@13gxIww~T9IwS3|H%mFbX^c(F=Sm6)(FvzxnHRJ8@ev-XR$uTPJ`f7`WK)5oJT^21$|1cO_!<9ubQhpsKNXypkraSoL!^{in{Y+8tz*2PVV9++J{U(t zxzv?_BUECRfjR9fUb5B~pj>Jc>wfFH67n!&)PUc(I;ggrxHQw@4b7|%Lp)c!n)vB3 zKi2m}A%Q**deb`GtR+lJ#^sR2x8nO3e3B!Gd#`J z4zx7SIrv8R-9md~`56j5jKKH3@C^B~!RFnBbwh7+){Zd2MCJKh;ij=37*O*M9Xr*D zzhI798wr}XjQvE5EC8yLf|1t@+^-fXTZTH&JVsb3r(x?WuoFJ?GvIZ*FJAUK?~Jf^ z%ird~D>kVwj)#7ba$WGWUGg!2t-&t#A&Y3$U-?B<)78*$CX%e50wzxkTuS+>gdK+$ zyjkiapjm-G2*;b3!lASRWo{bm8WM^eC-+~6LHUd=9$UV%OO-tRxX9rwsG0ZqBS}p0 zn}knUBx0pqH@vF08edK@AC$P_KkFnhOkaASYL06(u4=qqF_9N4kK<=^G%D=;)kLeghT4WtWZjdaJ}k`i zo%isuzQ=5B=16xtLMcZR&zkVr7dOr3t&P-;ik0i7OxvdWvO>SKQCYnDs+NagNBss| zLZD+vH9MV#~bh*hBdpxAUI0r8-pCB(-2`Kf}bFx8v>Jr?HBFO`#Bd4G#t%LkMeo!m#7NEUji?@>q^4m91U>Wsy1J{*!D*DY#f=IBhl9p7GyP16jYa zU3cPlYPN$~?<@aQ{J7QL^$061XRbJ1a@9to{C@pH%tnV1**f$mJd2H4re5ByBz4|- zWE4_zt#I+zUv+b2L4v~G{3#x8d>Huew?+5suoT# zO%v8;FPZOJa(850)$Iu*Gul44-hCBL{yJvwh@+??kMwxmmi`#LpQ1NdKUm-iUw^^o zsrb0v_g<+^{)334SZXqZ&QSKZ%WBIYffoF|><0!%erPZH+l)eZhbjBFYAm9Ej3U$Z zqr0xmu0kc0vKu$@;oNO7LP&K0jkAE%TQnxyH6qC`S7#@%=@OOnUawCCR4cqzkLCrv zt6|1$>4UxeAUW!AiJ=AC049>Aza|g(WKp`~sdDBz=T+hbi((v^n@K9U5Zd*L`VmP% zfmE@icg(|@p1n1(_}2VVLJQViKcmI+COoB|W;)*&{k=*bs$ggCin={a$1TxjlhirP zdZo5`9sW~UV_%lapF&}txg<7SK-+HE-OdicC?JR82A1sy6!yD$45A&r^{fTO2TOp%}C zXo|mQDL)lnm-9OFy34nz$CCah-~QvUV|YPvw{Lwre=gF)c4+PM2VZUiEmDrV5&8N1 zotJg~+f>q~tn_>Y-=!g9pQ72$WTErlsnPRhE4=*^8CuQ9s6qf19ft zb|3>;D6XHrURz=Y2&HvKlpv%VZVUdAtALX5BY%9c^EHkFLV+*;vP-uA#wz&{8j<T3>0kk_<7zQyc`2un`M?9hNq4v{r{s@-iIZ~V)W>;QON;MFLFfwZ2F@g! zu1epOnIu6n=-$JqSPacJSrE6!WRhNdKnokYiSV-?MdG5W4mh)sUeB-X9M8p0jY%&O zlVXz&^~QI{3iOyHbmO}WSUNZlUUlimL@}F~tFQV80Mdc-IyBdd{&oUQS4RiKssiK- zXC2~XejR$4Kv!TFop&fz>f#N7z^{>;5R*mRESH% z`H4#h))n?;_40fW=>U6dE8+5B*TZHiOX zExgiZf4Wp_H<;ei5zXI~LWqE)SS$8Mp^LF!v@bL}&-xxdqo7T=jz@GhJ({o^Ki)cy z3aoQINAru`*>DxZg_Nr#rJgLmlwyIBg8gks%>IlF2GOB%DV=;A1lNT3Npq?*d95Sj zrLg)Y*RFv&X{m1C^aVJ|-lUm>m!t@{Q?54?(8yU#BYgd)UKYDA(U)!9W8y-Zbh;2_ z;)0+#|39+*R{u`RQ~e*(K>m-wyO541Kdnq9VmUFVp$Kfc?5JGo4v}^1`wki7|!{oMJD8%tQp3;+qe-}4dX zCLl0pnc1S9{jl~y0jO}cp3?j-Q1Vqii~>}c*N2xX$tMi%K2ZIuLr*!K(?!q74Lz(T zga}10(>A}E!ym)~IQnB5FdkPK@@S*Q+?; z9lBAX^g%AyA&x##eU?{~+}B*sm!ZL)e>bWL%1f%n~L2&x$n|H?jm}L`O)u zuXeDFzP3Txfqx`zRL$o{ci*n-BrCmZI6@7MBX=z zTg&&5F_fTs)?N*IkbStM1t`e>c>IQC;S4rpkBub(2(ANt;NdZ{e@sj@VO>%llK}!O z3uuTHlPdAVcDeu>TpE8v7;93q8u(HA>Tin4#qh|5`_@;{0El%67@Q{|<9RzkUW9xT z*>S&#{Y*FuWy^rgB$`fIuSLXD_qZ%4LY^?rjzPY8-~Rz6RQQ7%J+xLry*MiOI6f8xkkHr6yIFdf72Gdq zLClWK9hl$U;)cGXGB$Ju&MxbUo1D}>RRw1=5c28iOh-MR1&wR(Hb zJ#9lIAWkLm=4eAp>Tqc7;yI6qvo_AQQH?gf^V~9p%rBsReahLtNQ6eEU&)16z=DOz z2e(>a<)xJ!eDm(Z<<{74i4&W~eMQ^Gdt)66Pp0j&yvx6If(FpMqYJ@A-Ow8V48vYT zMZXt5OLx)-8NaH3+mo5q@YNtVhR}#PL&~)aWZy*Sv1qdcFtToyay{5|*WPP=H()$} zmys*NcR&c)M-4jRUaxe(>Tc1);l|ikC<@O`xVf_zx9$1)Mk;fPr$!D;_OcK-gaN#s zm@1_(!`OqkBkT!}Y9ut3ofpNjbQqKh_ znq$w?ksYcM<{$bhlpbA0#!~l%)+U*cm6mz>e{oqZ8+rb(hr2#AjTyC{c z8(}q@;A=DY8=b?kFyjlwD#8fY`B95R8Ao^Lm?52lkmilX`do%o&YX8(^D zmo4x9Me%?1JL=Ahr<`ZtrKi@pJipprxUhEHY1s-pRT{2h--Aa|P+s)^!v)-)D#5Yq z@08ALd-!2klj!$SRkD|R_H|gZ(Z0N^10-bx0v^MxQ6CBUNi?-tC>aaPd^kaq34ZIGY(nDcyo2z*adJpiO%>d){c=dm+=0HQ zq(3d?L4bzu{LE16gp5NL=~=;&1L?c^GCml;?S^K~A@OWr-ORL$02cr8dT&k{$(h#+ z7Hm<9 zd_asFONXj30h=G5&+BoUi*WD!t;5G!m&kP{m@V_@gpR%^0bi95^ZG%v_A#4rS9xtw zXee0_-CO+;h_R~#N5auM&a&6}@gmeEh%nC6(NXUbYQjc~WtYOb%F0%{Z>W%+>LMO+LgL|tvTLVwmZCE1Ogd{t;aJK$;j6y@^sYMlU;iBsC|gecjI zdel_?R+CaGwt8-6yW2XP3@K(gWi)Jg^VWR)Q<(UUEwP7w%t{xR(_m|jfSi`|exux? zq;HSRBH#bV)LTYH8F1a-6QqCxQj$Z52q-B%5>gV9l7obFNH>F&NRA+#QX<_U3@AuR z3|-PSbk|TX_w#@6^*kT1HJ`3^tyz1WefIvHwGZ-*oS$Ew;epQ%IEP=rhA-sWA;ryd4;g6v$lN;J4g3!XJfk_Q(Ms44mn`4fDrP&Kaiwh+8 zi1l`vzVnMJlq8zpQM+V(d0CsonCCzG_D>NMJiSw_(yO0xqBejPT40`P7%pafAF+Uy z-nKjBb(bLw^>o~RbXobb##VK+t?5IRZTs!ygigt?B<=P=!YbUggVGjLWqbLPGAS^F z{mG2Q96nW28#4RLRAF9RhRWEr*@RP&L79bfpjo_1i}CYv!0v2|WhX!F+xK z^o0#Gt>t6?Ky4>3ETvWOT``+)H)>aD8%fF2oz528*QWstXgOeRM^%>zBy^&2B1Bh@ zhoq@D`8wr;MPs9zvLD@~R$$D>$u^2gL74NIKs%b&LvDfRZF;Gfw*w0`nYovy`bz6{ zCN2SQhW&D*FjL+7kp%X{48?1Od##4n zL&nI3Mp4n0S;mv=GCtT>Nm;R;Add?wPbPEl&ZD3x)8Xfmm1IIage3K}Ym?lYS6B%O zBQ!sm;TCDyJ~7hqM}ra%6v;3X-P?$)IFCVdklZD{qn|y!oDy@3knDL)JFT+U8ziSn zn|9FeosVSZ7P8$xzK^TLVIm+^(g&IS+7m7S^u@lmhP3WEStmF%o);S~<8eV9I6zoZ zx^llk=myC30rF~s3ijD=T>q{8O%B&L^|4}Sp%yy$20dQ567Xf>zYe_UfMRuQCRp81 z@}yuG3?&`v7Q5YX58YW3>qeo?iB_$h0IzOWIc2J@4=m?MN3z6vUmRwZDvpF+yr?D@ zJV#ejDG73Jg72mx#M?Li>G!=Dd*|lP`K5>#DR8rtaHvcp;h)QVa;#*uH8(Yr8$8K2 zxkalA#bD!oFV0p5&sR#DPGVluG-!;jR}9o_dtwEhpjFQBaK7pSjS;lMdx!Ad1K?Ti zPVU${$SSjZTmF)aMsDV0K}Nlg*lAIL8`fv~<~}GV&Frpxh4t{Lm3b{C6nPS<){{-; zi&|aTHl@418QBEBMVV>AuA zZ5`iUu|48Hg})|x3d8WPw>;J2{qJgY?z zW0fD(4THrS@z8nZL_YC}>4X0)SMxVO%`bICXH>(VXe)BTyp&fT1TgK|!Gaj6ncG}I>^A?BbQwnMFsM6V$8;A^L8I-trCwi1DJ)hz4fHTtzaU+RUKq)-d6vDi zDAvySCupbe8@F(y?swBdaZvn@fW^2!Bau5UMWiqQF~YQJa?^4>F`NU=J&jj(-DcZh z4Ni9^nu<=5NI%N|Ob53x;e<$A_1&aRQd>3nX!lY6!aFKMo6)WRJKS|h|Kr%)OhOL5HRgEe_ z_VO*b92)QzGsN|Y)>QQwkKf|s-J7F8D`)D;)QCqH637T3&K*V75u!6T?(84+EW?8w zmzA!fFY+ZG>EwAnk3AR3^UrZ<7e3-cxE3QiU3EWD3;TV+=mt@=7aSQKNqhs2S666+ z)yEZ2aunICTKm_6g=XoO^|k?ft5=`!a5kr=H@&rQaZ|UEahf;NV0!j@V1JSeZ?>%G zxucY59hIu;*_+;22HWibnqita-#C++4mrx`W*+z|a6n2*2b=>hi@En+9{-etDW>qi zuiui_lG-pdsC?x_yeQM`)$%kv3p_JqIVB;8K_p472);^~bEncg!NGdCTVxr|XX8g6!9t^Jy#&NC!6cs&p5+rR$d)+kj^L~s2> zCS+}DFRg|sO?$F(N-6F|e{~({8Cw-n?P4CCeB;SZgMW=WqpRx?y^u!Ycjx+~jBUSe znFQw|LBi7&51=0>h1!lu-DU@^2C6RF z<-i^-kvW(2Md!{{+Rs;C@qrf7A!kqMCAY>j}hdqumx_I$`^4=~QdXOIU>tznJEq zhO}^E`tXgm%d12l$9WVa+@wP+SlJZxQ4zKLJpKO;`n+x}3vFLi)H zK>hcn{n}kBQtb+sH=7zkTRpa=&;WO}BDSENgfB=2LrZgqktr@oK}WZn9BWDSP&N<( z6p9Z46?>2})S>}tpcjNnWQgY{(Qz45;zgq1lyA{H@`w-pFF*du6IY{6CtV^8vV70D z2_YrQVL!$X^2RZX;N!M-%7d>1EtCDxP+sktxc6Ps5NVu5+O2l&Hu@5fPRGUU6p8YBm4T?#(24BtJOyS$qPg-3oxts7_1JJM>s5Wxym;R0^!1?z7^t@S81t ze3tDbSazJut^D>{vrh+9=KbsI$R_K3vy4);>yOVDiPR?CR&Q<=?rxUiZZUCB!7bH_ zXmz;v%_6?cf$~JOMgZXYg3kVd$&G76{Ugg?;nXKQX4Gd}?w%(d>S*gZ1wM>H(N0{n z8qI7M3Mt5aiiWB7U%w+V$KV;cnp_|`-lIm|b6`I? z1o)JzcB#P~to)RN&OTxUH*lo_@)VDTnJvz^B?*vAwL(H1dor~rmCBavG4xZau&&wrvpwW2&R_Me3i;dv(nPQ;_=GFoo}b6`#OsCA3xrRPk2)p<16j_P z`W@YA_oI=mkwPsyHJPPLYT4hG#7!+~)L#J8lEtUM*n}m6pQVKAKdj4Y^ba3V*%LzZ z_^%i?gARkv`B92n>{9&yZ+MQHkIMM35LdokJpPaQ9mKfJ8}NT7>JVN{uX6cw1zg#- zi`CYp{gyyAre=JeV=f9QQtTUSCgtwEqr{_{HMo(?N@@s^ZR~xb)o!2&(#IhvGb;L# z$@q;XbXnY~5{@3QXQUs~$lY7`$!CZGB9`MnsKB1MIDatKwWQT7noAT?0~@%XQ!3~O zUw!wLeh+sxnAl$s3XpM?#hhI7+?jA4P_-{87I zdT8Pg!_|@NohuZn7$i%7Hy zq!5xGms^4JA((^+RXV?OO9lm?K0g6TtKVhSQtZs03rm#)Sjkr#QP}O3b<7ok?{x~> zF84kp-6_}Lel@hq>pnlWsqKqlhaEG_y^x8&&d7SL_%0_j>Pu^)fLgi{VA&_-Pq7k6 zmIs$Wjn$s|uahk^1B0xhvLj%QQ&)EqG$37P6!WFEJ>y8G0?rX8<_zut_CYZ&b#uG0ac-`yE|% z*m#Ze3b{Ne1FetrSc9ecmzYDx8hiL;tq!RjLW0-csHEabi`iygK4&kb{7v=%+*HMW z!*Ds)JAZA@kAv=ptade#;%g{uPj-fYft440x5Yu{Li`bd#laJ{tK1rKT|>lXub=MP zNd2Z_G$QnwNczHE$x)fRZi`DW5GBMlcik47=YuT2EYr#2{qFsb_jOq1VyKmBR6 zdmvN&ZFVfJ)W-&aT z1#}GsK3QtRb_WZIKOFsfZjTUF=E-%Zl9$z8o}74HcW3~j1FS)L z=V`(3wtCNVy`3U8ercpar=#nDLDON{zJFisn77jZv8Jp|M>f_g&Ih(gL!2EJCWjsM zf-zPYnx$Trk;$wgVt;^E<@tMlk3M5iBYH|CYL)cPaKA)yyLR^;3G2+ULddRJ(n3E^ znb?(V66WB4zhff}gl1h(9?zU=7f*O^88eG}_y7JE==45_;%@4f#XG-i(l+X;xykAX zuxz)epg@|4V>%Uk(clv*!s~RnDvmw3m`FI$XS+#Zj7=loL)^ym+G2cq;?T1?a%{}f z`2KaV-T&`j7h@k*XWTcjCCzosvk7=3AU3_nGrP*D^-9i~z~)m18H5qMt?x$EXlv~g zBQOBBmYkG|`}yLtb_s-CG58-CMs#4pVzm{y)GM6&*a*jlqRh{yhZ8T+vc1eSZ3$PU zT^13O6?E$Z4$OXZLB04!T_Q$WxkCaWfM}NoD9fwc5a*D!#-~d6^t{bqQZPEopL(+3 zfeFa~3IiKiHKK_RWQ)eYDXSDVFipUzED;=l>>;1#vhdsayqo)yu{}n92S%JiG2a7V za0?kcc<`9kG~g9VvbAdjj#CM)a0+HY};O!D_3D?97nb zR&{4~Q&sB7OmVdndJvUSeJ@hveo{#4X{@+q_k4a2^eR41y-H&>^7`;J@v4avnjH(3 zFT6MA`EC{yB)NCFM<-@ovf`c&$55D%%k4jJ`G72mM@4`AASkjasj0Ygs@#@;K^6#p zk?HeGKl^e-utQLv^3)uBtPl+!<`?Lqz7k)@&t7N4z;BO|@u)!}t3o!{=}jsK2s1zN ze~Q<5vO#M+aGFm&cxn^$w)qxoefSk-H1_w_x28e2CBZZ??j|;ygoQ zCc=;=4Sm|eqM!ZVAET8m9bg0(E!w?0y+pt34z2ymBV;yS=%jv}b%`LX}Tn*A+}H)VLd+I{6RZMR|;pTXp4PfFRXPbR$We7GXC0dZ1yOUA-E9o zaJ$GD_z{>jPsKmMDhaWw=>V6J1mEv~`M)7v2)3QpoPGadCVcWCgWP`?0^~{>=nJgQ z^;eIR;G7d9QE;U*+mU*OwYhy!jP<@M-*{*yQ6xnND2u>Hkn=F5uZp)UXPZmKqX0Qx zUbvTnFk^uCHEj_Z3|7B>Zx&Pj-R`EOj(wrinqK!OcRV5({o~7RH?6bw3ih4$M#dDB z?+?jc?3+qT*xO$203wRmuMWjY%lti~T6W-!hMUzl7X-KKT!Ad29@;YWxn{)bO1v~V zvUtEhc<1o-r9ZYVV)Y z9+q(EBDrTkvL*j!#&Vc0#hKiLbBB5P1?nY`c6;T7i&KbMpu2ku+3CcjY+jTY64$VNI4%U^vvW{LMzpr9q5*+_d--mTdPGatgD-lqwG22QjQNV|Y$<;4n09==|c? z#fOY8KjUO~i^QHcExJog7qN!%ug`3^e|w%W>cVU~$M@{9%clPd>vUTd^LUgg84r9M zWKzk5f0m9_i%Q9(DRpXk2EQkp0k|+&&uuCMW$(c4(v5ZjuZhe_MfAeXNDSFcHS|O- zn*#E)3R;2J#w161yQTBx14|%X`MP%7bq;lo>-gc!h$I6P-%{{V6nL;fybmWdwv(j> zA!RZo=Wg1DF3O^qSJGJ^FBDmus%UBZ^z@f!>GPVn@wD&(p|jyvcTr4gUWbc*kC-qZ zSvLh@(llYs``ddrA0J5T`~5CixQt`@)ub|n1)jkp+SrH2accN~g^8_w z=sroF2ULFqRsna)uR05Y1V*SNeu>sU_|Av;*`pFL6VEM)BsXktLdf=7XMlkRd-JUp zFplceb}JY%S~;3NLo!v{2`KCKgq>{OjmaJG7E$Sh*?-*?%y}4#@Vs6I_z#y|7`gq8 z=$}gY6xcb1Ka1uR0pifWI5wqjMur2AbNhW9(geh)LGncpFa&dS%Eq55509!e-KWCK{;&I^hFMQ}@GXhd^CYuS8U9>{n!8`g1 zWd!;^`hKH@DoaU*>?oB${*) zXtJYhcq|AEE>`^>IMs$dYkr4+rezZ!5|3KakaCx|WPX)|Zp`akF%orzd`3s$`&jlh zCK7VXb*J>a%+G3#N(m5K%YwLXlGD8k+!B;_j}$%<^4!u;^%EOym~5@EcBE`=QDD4~@}R z&3wz`#u7FXj;K*cfLm*%#s|mV-ZNvbqY<2AN`Mf*`oRd^@h9gnsH+yo&GEikeKbnd zH}I*;M37<@bbwm<|4h)<4ej^MtetuzU%vku;pV{+RqfuB`%!qIfh$e39Wv)zMa?gd zp4mx?4}d~ZZ39?3>y6Wm=%9l+nc*07r|_*VY0k;5Lhd`j%SAolDj{bvopYvC<4c0a z3cY#6m)?!0p!moQoD$!`8b_WigIr?(}|K;sEt63|7;3<4y*c1ZN+umTe zgrM1&xUj=AuFpj3D@cpe^4u9vFBl|r^73Z!@LBFUxV0(R z#Ns(rxTfc==ZpwJFN;d~5zq1DvjU_Faq(#APuh(oQ#V4ZKOpy!RP}F~eKC$sf!ZtD zHo^}p8T)W&mTO`-B(%PLP*gl)9SsJwQu7%P%MC=C|CHJ>8L^cS$Xx9I&F6-#S(nHE zX*xXMy4qBRkB+Ej<;?hi70fuDdQ}8hjYw}etvslD2j{|ogM-GkMKPyn1Hguc%#9|5 zyzU6cUmA1~gLvqp*+Gl6#srJ3hwO*@18GF_q2i9r&6YU>Z%$H{7oP!m1{A<+uCB)? znmN7>n>ZAVDHdTdYB%(yj86ie!hQ|Tvv2+`R?-ju>H9s<`zri&{@=uuIHggXMZ{cG zhB^rs?ZHX?D#e{2f+59+5vPY5vR|xL+@;x7)BYOpU?@WwMp^wHS>lg7n*@I&8g`_N z%lWE$25#q8FLO#9kzD(KCx6B9?akvCY zxg@ss1@`0CBGnA=Q>^-{;eDFs+;N+z#F>i$dIi-xk#Zl(p^+H>ij}E1r{_e1t(|wP z{+}9P%ZxLnDs5^Ls-s`+*w8-vg=YJwrcdB*@tITnn?S4Gf$=ednMUMKEwG^)tj$L$ z({kPn&iV`@49%0O>uG&B-YihvtdS>d`fii_&~}&gdNjoUIOqz%P$jccqrnr)q^}@TFadL`5s= zv|43Yez&*W$$8`PB*2p3E{2(N=WjBve79F^@&%a5vx$ULK(cajQWC0#-2D&~>3_lp zKcQ$h3G`ELCt$3VE{v#Z33b&*aKZ?q2V|~sXdZg(nnO2y73YvPFBDAK)ZG{=1aEbD z=j$|nc&SzXwcH%qQ-Vt?eL|^g6)bWDxDFt6?kF4QS@Cf$RMtQ0^-a4?iJCiG5jsL6 zIw(Hdw>iJno4!EUf0k9oXVB^v{gFM3t5>lPc(O_4I9>88SDtO`78ZNR+VOP%-59kD zlZcU9%nZQAF<#7!q3Rjae5#=gtA-#M@b-su5;jrpLFXsmG$#KKr{wA?(CLxO zy6qQj0Z9@oiPmDk2s>5&SaUE;y9e49^38 z6B!{j`Yr-Ky{_W+_P)82V>V6VPK9M_Y434t-rcJdR;QuN%_!*0jOhB;Ay z3d~EB)m`nQ)$#7CgzS7CUoogAgY*NDWXF2(N}LGHg|qmL7^uRDu0N2$^i zhKhH_$izNi!>CPNWc*2FHQfd&`SRP=j#zsfl!h9-p5iE9zGc31xvNI z1GQ8k*G0NcMgoQ)d3D*<5AW`&0WV_e_uKf|%K0q9IO~<99a9s?PX{J)f5QE`)WwTP zATw8&?Sb1McPYod{6h%#RC;PO-}yRHIPD%DXa9Vg*0j_3r;l<-3N{YTVqtx>LS7e@RG z-tIAs)!qM*^jueP%t;Fz}Ip?JgXVO8Z)ph_ z6iiSMfZ}(~T@wp8(hT@=&P@#1o{#hz3+qW?aA1xuD1_3roSM3uI0ZwIA!uiAy7e2? z%ioxs37%Lk_yspM-uV=%IxE3MEOdP zO~vJ82ydj2G*jtiJ3qmZSV%jK;%!bsuBZquVBu$}b|d2?w;J>zov*hj{dO3kdS6n% z5ukC+2Gg-Qst7_cKp%N%Ntn58cLsiI#m$n$Amf-wq0PXV{EoLHPo+TU7RtYSb`5o zHuKTaw0mTk=x+)~iiwvvj|yJhmzPdID9*kT`)e%Rzfs%83ip}&k!UA~cA^!9*_1=A z?AJq4I9&r%%Ix;xnmjcIl$#5}KMH`syS~^% zAO@kAdS0$4_vhz#UbtL+kFxjxxzIV0F`T|7>qo_|?WK_PReVfG-Ls6(<)+?B(3#4k z9pAlsE^{UsYEvjME~oslobZU4MwOkmB=4MnX37LQLFH&T^vPcuFP%5-WWqLY*-(CQ z+SB?S%#(a35jG9(&96#vW$hU(hX6%SP$K9&U^t811?z0|F$NZYf4XDEr z&VQO>c=REr5Uy8mbGd&L%-A!9?@eadib^j7E0pB<7Blp%Mt|NIGg zZf4}%yz?Z^Y8$!|Z7(GkwW_pmNB{Iyenk}v-O9vmKkE0);JH7l`x(( z7%al#`g!}FqPd)40zM(CC*+*TKYrMxH9^kGfM4wb^?YDvHy!mooZY`yL z`iBYU18ifJf-K{%uN`Ckr4Q?YkzliYsAN1io{dQzmLf(do?~ojDd~NF^o|ITBo-!s zz#wko6Ho_)XlfYMHPBbU6oE!cSj2w|vW&TZR8Z`K1E{2=YTn&1!M!41 zF_j^7T}k%b!d%1LVKx~_o&Ad{1CQhxC4!deL*Ic}>BW1%62NxBXM-Wc80@QVq~#FC zhlFM#dBnrKR$q&W#5nb&OWMxlM!+vPG*atB#TZ0FlT!S5=(5$)d`F~1Wo%aoE6@sh zHnQ3EC#+Vc2h=BQn(w7kLa0$kzYo?b#+3UJ7c20+ihZM71)fVq%bcvobCojop>_Su zfg8JC_c^Hh_UCE8t^@L((Gm+?gaBnXDD-EBg}2%K50FztrfBBLGNT6E(A%n){TI^i z7XYE?m(kZZhM}>C1~pUozSn!*GPhO1Uk=*eXK+QCJWiL!$oIcR7N1`+wC1CFE8Od( zJ_<>9z37**U4Le~K2&V1VY>RXd61Q)75Xb~F&Td?tBUm~S9Jo{%7)bli+nUHtue}o z#mJ|{i*&Bf6HETa_d%0OSS|FKlEj&|^#lhZ{W8l>A{mjn8*(P_z2n^d(H;l`vnvz$ zII~r7viM8!t*IImJ8+yPrK^4#;D^ypPV|-SJFYb>x<9+tU7YmJ-eHR|Tv3Bs`Z$og zNXphyDV2imo)>Sjs-_}!`^z_KSGj|gbF4@vu=A9if9Br*t_y=(f4V!63aJ~2df2(c z9sRWx3CA^Sv&h8<-)z{|hgpB9d&zy+?`W%{pvW{V$=E@ejzO zL0JlA1G7oISRbG5XgfI7*y0$>vpFTLy$_n*zFO|0{w4a$-EB)UYZ;ex=3E;$WAT;Q zrVfmN9=b@p2`o~`E0yCVbUL{dX{6oaFwc8V0DjC4am@u1^D_DWmj$2+tPCa36?++n z&yY;~_)x9gvm;=6p_zMHh~E$pLZKk|bBo~LB9&b4a*&D?RH@|dUt&KuKXQ^}FCAiO zOfve|)?QSl3{uOkYH7H8Bc|fUR14$7`|WLP$sOP!(L|R&ZH3#Y?}5!V8%Az0>(%6b z227%D{D@$+j5wtL!4l`wH=^kX@l$kUp06ibwio<@+m%v@PzEMV07Q`j4?`=kVo^g< zuNOH4TT+&;z_|@BZ^Mp&;lHP=Tw4#FG?(L=wuLTr<%$~pDuHq zUK7#j1$!`yiFiB_4BW&gn}I&IQ}jr7|9CuLbbe2z*zDL^#938iXzP#c>HgxVfpF@| z<8O8*`cz;1f)?KL(Bo+NEZE_@w%z^?*z=LuTQ?xg(b~&?s?E#j_^%wRI>GWg2qeL$ zk&XBCS8vS08R6e2;Kk)Id@}CO>OLfSJw>ZpT2Jm-=|ZNtT%RAIG7>|x9aM(?cJRtr zI!Nby5Pe~8Xne+JIs#7rS^X>a7dpG;E|(EDtYzk6+*j27;2BBI6j@G#I$yV8H|Pfg zl(3Q$c2bCgn-V+uwe-uXMo<&@PhwGdtu64upk8Xvmg3lOTmlKs___P5af zYwo5T&#d~GcGs5xrAXlv$=$wLzO9wpBZcXhfch6O_`HdI9+Xauu((8L{=0Zr4u9Zi zT#d>s|n(m(YeiR?dL+78G#tA2@1?(b0w)o{<~Vz5-{)45-%w%m5s$Bk5&pA1pAK3p*XvlU|$@tqNG;K*2 zsJmm0^DNv5B(eGNEvLtpuVdDM?%?Dzy9xgVv#~Ec)jA(QvV!lg5vNS^M^J|sE-}od zJG_h94Xbx`)c9)YTHKcy15d=>}9 zBcBI!Z1ccxKff&CX2mDFHNNvXq`K;e(sqahd?N`(6_dw$RP!C<++orvB;w<)^D&btTWd~8s|bxw(_V?mqxe$N_I{j(yil=3KbQC=B-J< z1n&bEY37z9N~7u0+p`5ur&6zo#mH!Ln9VR51Pq8EXUI`c*Nf<(#OwP1xw!r3G+qs&iKqiPBPt(*+Ug_mqJ~kGh|FA&2BA87A8!L8zsY%$J$`mN4?lJznAZ)=>t zak_F2`kdW7jvzJ4OiIHrOFxb}baU)s{Mt&MD)7FGWOgh&>C7D|=mA--E5A8DN;%F* z-ta}MD+L_g&i*)Fs6t)7IJx-cKVMuFD*}=p!=I5$2#BGkY((K)_ooe|4V+5w!w-ol zI{QuhUsOM%YJ2)?=Bh^Y3YmQEQ`2s6$KW%60$(-xUm#ibpZ`R(Yu-9;*8Cr#od@lf zFHn;c#L)7~1bAH}w_SdaItlb{WmIYcIn|W^Wf+CvwA&{( z`n=r?Mo_|-pSY~>i*|0~3A>M7CYgbSDM_Qm+qrRlXJ#IKCr4na)U`EvMO`3G$bq)o zKyx}fw>3+-i%c(Z^%?xB=cj~o zI&LhJ01eJ9{U?jy_C$Ox;0Xny&b^@ZB=c3G17BkFA3hPSgzm8ScK9}6?@Oi4iS_cG zxYO<2y|K38S&^^Z>P8@GkUOu7Pj81U0_hBrowTJ%^->oq)wW+!u%XR=`?V+#^sq24 zps(ojktSYtC=epsCyJm1?-Xx#A5RdsqdAxa6}-DqV}4x$kMg{y0!xWj0pD{{A3gI? zg~VCKFS)=WFgCff&?AZAVuo~z7mpV&gJFGs;tE=v_=HnLp9m@`iXxqeT3TxUYCxYr z;Fivk$nep8Zf9GU^<^c9=t;^eUU6Y<*i(j|PifdvZk>sM9&GUkNr>*g$mBuR2{{gL z@Y|W;A;GIxSGnzDAmg0wT*h_!$cha;(U~`56L0iZH0^99e16i*oFe#%blFuOm<3%P zeZBveiLw(FiP+B3Wc&k|NXo}U9XEsjCACN3H^k*j6d7#)I{#%-^`)QDxLtlz_`=;_ z+AgT#WHQjz+gm?EZeiRwac-7RQ-HRe5AW>GP>`K1t(`6%U12wC_GHll&B+uhlx#vU zzwJ2WZdvw2-@dzEu|>!=l>d2zJZJ@2-Vub!yY1KIE>3*TYF$t;BYhLuE0KS^)K~=l;!*h1<*py;IV=WRSa^Q3^rGJEwmO~IZ!C1`Ds(xvvBXzt z)6vWt+SaLbER)TNScSt|MHVL7F8&>c(ZhdpKQk^9Ly-ruxyM3%`DeSFp1c3UCvg0g zCs3{T=4oQ=X_j-kGI5mD3`?3flXlXSkx#<&VM*y@@e^%(SAJe`xP#rVwcll>WC=S| z^R33|FLNXV8C)3SvxnsP$N2RxjNiPgEr>2EJO4N^*la#)eLE6F^P5f=H3_NwlQ#BT zAN4O7E&7DMoa^ec?L4`nw&30Tf}6)vzr9`OuQhj!ehbh#>rKYpi5C+|=Lv{TK%FIw z_evgMq=Fc(Jze0SBPE5b)b*CHUGUrt1KSDETeTiPvPBI^p46t{4IFKQ-_q<|8UzS`SJ5K zW!sUiK&6#GMfPD>w6xi4j~jnVy2&Z@x}gliirdP=`b6oOHQ_(|>g{W)&0$?{&3vjr z2TwNGF#X!z1Cj$RBQh|X51@a2ivAo~{YZg!_vRYrdTXipAw2OejS|Nyji&YS!A^@4 zqraH)F}}=^pVH-=0h4P74tRf6PhuH%1Wi9LoGL6F409IDWdPDqI`H`0b{?<_bxEW? z!t#(uwW~YpD`#LN^R4<^Yux06?|Z5wVjjY9_h-(j$?s8z-BHGug4vg^H%{ek+-#m^ ztxsc_oKKzobLQq{&+ePnr+D&FH>KoOh;#Q}63>@~Y>xi0&Y#?tEnv%H#p80#wh5B#(b;aInR)x0$uj9@Y4_)4v+O$@oj+0*^!sLsPBnZuMrQ#0%yO)Mfz+f+5E+4dx6`ZcjsHj#6o_}G>qOAcd;!rdi#cZj8jsT zerD(Gd%-dp_?}EB(7~W9%pCY9z9(eo{u$Ke-ye{Mi& zD1F;|MCn2Tr>L$oremA``Uo!dd}MbS__Y6?Z%oRI==K2Zkd2u2{KLWN$0h{IBImV1M{4x zanCX8UuA+0LF24QC%EKO=?l=e1cUmq(*zLrnOyM|?yHi^_gUoWhbW_)y3hwFL;&6G zB5!c^JKw9bzkh0B{kZv>bdCO3%OOxKQv3!B*>c~S z&9m@26M!3!1t@~hWn!|IAOtz``P(X|HV z&d#dZe#OF5`@iVCo{MtIj)sM!KDn=oYQ-8dHv7(>WNBCKrj&znPnTq>Bt0CD6`*bs ze%R9Ny?u}7KY`s0Sc_&xf=vA2lG2{nsc)l66tjwiB?UUxiV(Sw4>@o?=l)j>CUHA6 z3d!3$U#~ki$cglW$Mf>epD4Q@6b!K)7ksnZ2{3464`^qzeQ=)kONvQN(>@X+p;X1fs- zd&N~7(JXkiUXK}L0yS;4A1n+Oj0X7GZEmQlthr`~p^vL=?Va^~O4>r>KZuXzO^yV{ z8_fyH8roOB4g_$uH|9-o(AKFz~Pa`sb(k!^l^(6INW` zh-QYR=C^C&PB%hD-kG;db}bP_ci1+P!S-7e0kU_Q>t3U#^Y<*1n(UPAw9K>>27-W5 zmSvrV4Pfq@!Fg}-E^K<;W%RA!kxcAg`%}~_WP*2j%2^f*e&W}JZ_rlV_Ob>%wg-~U z9~*a$bM+zLHH={IS3^01YD!_4j02*@2lTu9O#6;qz|U)|EBbB6cG);2=qF%>joP;W z#Vh`UH(J*@iHEQ8G{0b!M4Lwkyi)^VF+ka~H2#3!QL*=)GIqIFhG&uHLLfC3(cnC> z*`U4{tL}i;`Jm^Ej3u}0*F(;LODo(Xywyk{*uP!gE>H>difZWU>~4mX&;w0tRXWUNtQF)NtivX5u5${?+Zs*S=-gmwpsT0 zlKYm4xU>-eHT4a7$)ViI9|@5ft{d!=f#Ee#4)@+p-yHkmE%*OE*x;L#0n${-uO%`D2%93*5wk*K@7Trh32vr`0?%aeLX+4nK%s*z_EG!jPIX83N1X8MWorKW%bXPq z6W*9i`K-EPUi&5OZ0y*dp__k0r&-M9s5d#i`~jP)B<-=$okE%8yHI~C-rg>5IsU!L z*BZUbHR_@q>AZ)Tfh`47W7M;C&9^6I?9!_|Yx$ibhTLbbtfkGs;=ZK@3u&iKSz51& zTMzw%BWjP7q*l_*d?HP!vzIN{Q9EB*C8YCYBuxHdYn(dVc*nE97LyzLPi)uPk5bg#0t8U0W2)WF{~ujn8V=>(zdcN-BuXX3R6ld3nuo9oMTlzUTLIp6BO0ql9N$x0@BP zB7x=ZE5v9VdfX>Nrl(d+;6R`jNqp~<;U&Pc&~#nbd)X)@z+xK9OHxg!)YgigKzd(? zpxtu%f-sa8^sYQ+|0hvtPoB~)baE~8+?3W|BCGpoP3Hx*o*H+O9@JFyZ@4XjO%P}Q z1GY23?GB(k%khlAYr)Ka{WuGpcK>m>9f^Ii#v`KKM8;jdLfJz#UdkkaYR+$;gNK$L zj|4r}|Bbiuw`E%-nVHs?7f8^1zo?70Dxw~u`j_F|In#|aWk`H*4 zqB_g9Nmp+IT^q(wI!=)VyVdlib(&o4322U-otuF@KBF)mB-6~?`hwX2!0CI$zG2nx*OJ_!D~$OJgn3e9f=fN5l^xjuacapQpd z^gnK5djt|1B)=qgWrn#pzveR&uAI^oM!U4%dbwL#zXzV~jq6}Ay$!Mk+Pbz)P<|wr zRxU1!il~o>A;QbyL^J-5ngmnPMw_eOjX0D&)7MjJR+n66`c{4a5JG1SRy+Pyz7Kr6 zvHWS?j$`q1q_*#I?MMx0OQ$DV=8Km=$(-@gn<&aq|KCVd&OohPng<-tgifsgcdFqXT=IB=w$NcPmm4R@^?mIf(*H%1yy7ux-Sd)5vHb@xTd zF~%wkHQf(dH@q76#;I+Ci)(p^@V9!Xh&=-%(YuCOKk=D&w6geldrrLapQ@{-+qZm+ zj2FhE{PrDU&2QU8d8l|XKEkfZvdBo2aOJYOn8qc?=B~A?BqUMEhe}p zpuB@BVC3dkb!^Xl7I%rG^cT2gTm8p71;aN&SC4vD{@k1kFR{1&O?o<>Zro3IkQiXJzqtPp0Y`lzoC z2{{jN?$7?HTqg3n|I_1qSpR%e4frPhYSG(k^05m|#t8KXN~+^tC8Z%V)w`J@Em@Cv zQ^CYTQ>pfH^8m?}_XG)Bgs(Mp_v!TBvKkm&A~|_-ydhcdq5KFlzvAHLQA+hI)BK^H z;5*ZcCG?uU*7qDdZb#W%lg#)3Mnh_^Yvqj2CQjDNCT6~1jmU=07TJd6nbF#@fGF z!#gIeM0|PHUr)Z7we>3W*=f_Wcr6CZZY{lCOxnTZAZ7El=j$WubNQKLE7*@g6<=uD zpf?Gof~c*8R9B`uIN}CW-On-?7aM?)S&Mo>!$SAqEixWBOZ(^Y zr(SEA6~<4tSv9OcN+l=#_xF+DBo!@^pbF0d4WG}RINP^7=+2oMAWMe zp}fGVfcz+t4yC;h1KI~)*X{yGx>3tfN_IF{7XKwCEH4+0>)OqVDuY-&Ikem#XkB)< z6p*tp&AtCNqsA(PF%@_ORWhE1M8aqchMxrPsh`%=acYWq^FlfnZi-5rOgpNxam@XVjSCb92JO~x2!?&=S?lqItIJi})N9Zd%gqJtub7|KtdA)teXGcJ- zZ3Jebr=CVNP2SgU_bDl~>$#T3fu*n2^Z@bsDb~=caeVp}@p{TyucXzIk5Z!^yOO{H z11|*%dxyVDok+Ny<+HkLh|9;P(}`ZZm~NOw6Wgyj?(U!2J1B{%3PT1*hEk8xt~^=p zJz)k7q`nsvX9?2#aO8M+hFKXFIcH9c-(ScwDJW=>}(Nnn!u(^-B-pR*kezmVGGiM+j7Yc+|dkz z^=PsBxuyR6*W2h)dC1oQHMZcy1HI-lhttGia)O*}Fwz;_&~=raN|xG3CZ4OtljZ$f zX%80cH_wx43E12|ZdP{ZLI1pZ;q6ye_{H!7B``V~ycWifFY48T_M^#izR;jxH@{4B z5g!k3g%>^b^#@+Np5#z29ulDZPB)p{^F3)h5LJgHVxQHy3P`Lh9dMuE2z~8xu(Al8 z93L_1v3s_DfL?W-W1soDe*Sc-xTh&Cux8s~89)k+Wa+cf5;joro&v=Sm^MfZ_(?#Vy}BD_cbtcz zb}zIuzYN-AKC1`Wj8;c1cI58mpBuprgs9H!rtgE~fg!KCE6hCUhuWDd1k{0DaVx^21N=7ftKaUogLr5$!d|W@8j+AbmNnfKEn` zX&rR2FmKiO+k;7sA0hqt}~Cmi3EhMp)3C_-H6Ymd+7%+0vkvW`vc z@a3tt(>#TYM`UhVc&HegS>2z0ukzr|gvxh8DR7}Ks>4vE=`gZv*(Fu^I6iJ%?Wc*5 zb*Kk`try>p48;nMmrds6Rl!?UHRF6U_<0rreK_ryyoSrM5U zX}j^QZ(p8H6^~-_m$6H7sTVvWAD1;{L!Zl~J|bZS0%;_Qc)aX5RS?WVewp)gPhYSR zeRd8BZ`OO+Jd*-cRFdiZz0GTCcgI`h+H>-E*OtiagT0I@PJ!x=OEisrUsur*5CIG6 zh%7)RlSFzT%+_1WFxwReHyRy&giPQm^4 zb-COXR-bgCZdlA)P&F=7 zeEfT5QV1W2#G@u3Z?a~CsO+A}sTQ(rBJ`flP1)54ym)kY^4xx$+`rK8NH#HYOYi0i ziC@qW*N6!TvH@<-BfkCVAKJccl9o9pU)dC|SU+)!m8itE3l_XBYRWeOn>la0-76U^ z4Nte^Q<{8|<01cw>fH>K5e4^M(p)kZxg?$>Tw*=TH^`mm|Pn2}%2L0F#|5h@zY{xrrAV;NKOL2JG!Wklb*a#yC!koC2Eu=t=8B1s!R%X42x z_GE1XDPDe(wh?7a>`Ixly}c*xJ8v00CYWkGv!rwbX0h4NOMi;QExFc9mh5)aG@sERMPq->oAdf1Fp z^7}b2%VYR8*c4s%+{|=4P8>#N-;R>zzZ9msvNgG}u{>P+vkvCE_`ryI>fKeW9#96| zOlE3kIB}r!A+27+;K-!iy2pT8orfo}-s7g6R@;9_N*C>)c)tZlacMU~-0vQgCZz7p z{<9NP!1=cy{W*-JGqlQvXieD2IW=UFnEaHK%_&cRG2{DV=adC^5I1Fm#x=2o4JoA- ziL@M>olvkxg57u2x%ZlWYPcnAh<7EF)*I;!rhqYp&ygZAPm;@c3VUMw$ZfG})Qy!h z<6exj$o9DuZ5EW@bczCIdz#Bw4jr1QtR{*2l)I1jR*u$@exe1O$K?Ig4`a7K@4~BS zXK6_^6SU+@@ZBMvtSV>BlnKVeP~`!X_H^$sTI%kP^vg^a(nr1kujWQQ0VL4y&{X{^ zX@kj@&YtP6NM6wGvyYZEugZh;ktn?)5uAOg)H*Qw2ash1b^N=Vu@-mi%N+^cK>5>O zylLiUo0j0Z#&~g4PAQ7gbCl)*2qyz<%Vb;Zl-@eRn`mxFu+7HDHxb6J!drqw{*;K^ z&G_eLj&u;b@vAKZsC{5n&BQ%2t}CC}iY9tecqGMhsAHQZZg}NGAeBFjJ0-5`fm*)& zOAZ^Etdc9AE?0asfn>|0mL_gyo+ICi?zsw_3Tv5GlE*5_0UL@sljp7lSw)0EUi0yd z2Cq#yrekBksPkMOrE&puw&xVKs6fFJyhh|j9w_<;WP2JwOg@@G^+U|?avjN=ZMrIX z;{t$#MNo-1pvzVo-qIJaC}_tR#5yuw+xXX&V%s~#1BwaoxnFIV4Gh2K=^tL;waUt= zf^EUlsOGd{Lb0`v``rOM9c4-fT7x0(t1t>KgfcG#KGGhvgIpJKV+%WQ5D%^iIUYfv z$s-}h`iIG*)$oV2(GE2Ew&pn|z}BeE9*zpU*gYL?ogAtn12PTg!CPd8;P+ZrIGt83v1? za1Y^bBKz$^aE7~>btG=Gwe!7yFJyjY!^-`=)dCmiLctEy_?)`fEG8V?t~ocvdoJ#0 z`^V{zu%SD&8uet$I!Q#iDx8-qWz)ZnS!j?OQx>0u3!pR+YK5x|*AoVi1-{UH{a9=5 zAXZTyTo7Jyt1)}UHGr$+@hrG7?1}YROE1Nm_QGcG9i^~OAcg*jL(!8s5y?f9hs_KY zL1xLT?U(>@4J|%yGihoovfn&PHz=T5VaNJhq^>T-*Z$W~to;37#5D7Aeemd3=zpkb z|AKR3dhX{X6(iMfz!>t#dQlc=YI>hz29HJi#c`~lx>bFYz zXM&`^5H92aD@sy1m#-CSDk@yOm_uF+|HULflsrbGh%*Ddjzga_%8wbV=p7-=JrO&@TLIpnDSx&1J zIX8>bK ziUD$G}HscK*amlfwDsp%_7B4U@ffr}duPy2X_8bzU1;i|AGLCx7*x z3%zV*U8}@b&8}yTvzu}oozf|Bg75#l-~=t^p4YE#nuL@Xj^>Pzy+|KCN|W0@yEaQv z#kcQ{15eDDTN#*wC#8L?*#=*@&95*+|Ax_3kgZ2*$Mf!7Gx@4my`YRLO|UE|lR&bz z=S8OU^FN#xN#iPKKGEq|h*%&iNFla#W%hOR+$I=~G`Wg>oC1|beXPU+2gGMnZ^M=y z?NcXxrGD4%K$UZrpXSa^2C0I$q=Ij~#IH(IIwzd24nixx$=3!tHtTDY zRVKz_S5mo_`^_0&hRnm@*fAcGkTpP46KvP&sJ#{cb466yhf<1@T|&erI1ejmGlThd zd1I8W1p@7&t|_IO7I`P&PD@}v7hL8;oJ!Bz18W5kyVp}cIET#LU9_OS*|O|a5Bao$ zRm#~wIUnEO{OmFIWY@okM+#)I*6lf7`n0mvJoRX!MWw#h*IJ7QKQYM&rRi+#O_21T z80@m;4=4^$M)a}y~h!I{mQGvg|& zW*~OdH>bKZB&vYz|O3Ff~m$X$@ z&uCw^pLoT-6}|(Vy8J;uhQy6qd$^gGY`qG8v9lzgW+dis;Qv7lCg70Yw!W-{dN;yDnI9{bBKi9BKM(b<3OKN+^JznxH zr}TD#dU=uNo^$u~XiCgIgx{<1kTGc8dhmc_?iBd+zD6)35yB{X z6C;o#elphG9)^PF%HA|*XZPQsfqSVml>^gTg_=#w4jj}}mJXu17JGJ?xa@ImSCnxF zqPK3RWX`ctGftFMRukvdI@mB>zxns?;O8Ux0>A1$#sid)X6euHMr=*z$*>oG&}mEZ zx70!wOwjuT9lc3NMokB~r1B~tmS*#ex%-`a;u@66-#WV$oS>hUL z5Np4Mz4;N%kmrSUt67OWh8dX~f48x3ay-y*t^P1mTA8zM#A$a_T*&Eyl{7!H*%s9d z5d#e|A=-X^Pcl*7|M^VnY@E9h{t^{S%c#rcCjH5nB zb7g*2LcPcZi2Ljsi*iQ+`7Jv7>ERd>R{QkJxlsyi-@WQUiu3|(D4#e|-A_ceB%K=YmFU-=AupluUcAj*sW1 zK}=ker(a>gUx&$E0mh049V3TwiaDC(kB*S6l0g4Siz>%Ri`|pIXJJS8yZpfM10A>1 zb{D@4Y6$pvTQ!mj%A-A;88JIAl+A`hnQ?bezttM^ceJN{aq*m~iP?%GNW!3HuKrP} z;!^nAeXwDi5N?Z=suwY#d`}i@uSXnSQQ+Uwo0@U0AZ9%2uNB*!Lye=~CzPsBdfru*w?@gEPp8B>$zPO+1q?t3oVTto#mIscnsb|!5f|CgW(YWo+%%&9Sv5UT zgmb-QIjmyRZ* zKN;LF;mNBerqMXQD}r&i`MS`OZRT0W4foUhLDGMm<})d(BBk`lo2Fp3^Twp*711%M zk;_aV#A+u#(RBtO;LC$<5da8z)afakGZ$WNvG7JH1UUWucF{I1*K(c4!)mQ{EN11a z`+!`g7&>w#kH!NawK$THLFQEK?&C)8JgeNaQygeTM90B;s;U91Wx|p!Ha;B<#A1eb zzUGM|3Lsz@;=vPXrsup1p7`LrsrCSx()HJ?KbJJA)(sZSa8KMI>#ScDE-Y#r^-B3t z2olm{RIr*T;>q@IDiX{L-cR_r6xZp?@v8lFDMMPP;CiC3>cFpCAM2`&qQO)D+z08n zxJw0_fp`(+T74LVsQ`=q`HevtA&gblZ-g!XB7JzDXB zA1Z$+(XLSV*?rW=t*L2KZa<$SuuJ!+ z{gz1$3LGaAh!<>wo=UmVM&-?x z)lB`)O~uu)lRt7AsKuIr`RSni!?mP2tmB=>l-XA&>k0hFtJO7Fs z4(rd7J4AQX$L9eVUi^?ZO-HocL{tmYl{lC`Y$#leyd%`KpBSN0M(B}bV$KfGtphIAQ;WS0@9?5o0GhZ_Mt@gnljzeKUflS?-ULU{D($lq zJSbKRqa$$PjEjsc{Mo=%h)XFVpTU;S>B5CAV*Q$0K^N_F+OuATOhE3jXL{ws1*>-B z8vBsdFwlC!ec&U@r+V2>*#NJhGztPheHyPl;PDQB6mnh-2fPS-3Ba0gT;LFGP+FJ} zWazqNb2N1bF2THF07NFI-+rMb-7-wjd!}ypVuOP#{ou;;wO+ecLuC-)(LxS1ThE(R zFE}%=cCaA^F2mCcO1+2P%}GAe?I4`b=47r6|97+^SsZvk&vKiGlDXl=@U59dy)gPh zNq*Z%<@Tt69C->^`iO|L-WK8E=&d1{!u4 zW4x0R&T8_mWDvS?91rq?oRX&cx5_<&$dV=|H*Kl#Im-P$rc} zdJFHL+(r6iJb~}y&q&JUtQl12uoOGCmfUpN0T^ljoHJ$%*&3uY*0syM`|1YAx;@~5 zyST<;a&&Aj#SGe_ujn(AIMO7G5nJR7qcIGi(i-+0g*ht?`>o(hEtCffSf@_;lN8sz z>x_{}t1NPM^HJj%`-e+AT|{4A42M2L9wf_0e-bmFlp8DZv;C>J)4b3L;*MyIU!8V` zW=P%!#2HjGnU;Iz$L`*N4OJH7gK343KVB8447zt`vLDwftoY9OE@no%F68st8GL+< z>*-TJPFw>MaJ6NWb=S+30QS_Hp9ASG39LLTyjFHTPBGhlA^eSnxSa~Tzw*&eL`bfF z?cs;3;5)yix9dqDgnX%8(3jc={Q3Q6G~A86g+_GjZJ@5Z6u?XrTHq?V3=)a^mf!(4=Z-Qj=1@(eJF;p%&&$90y}GgvVh zeAc*a4L#PxyZQWkbe(T10iP~Wo3*7~LKT5kB|0ehXC~7^guin7#m#XL;Nx`H>P)&X zPepN($5Z%gmkkZv=cZ$h{c-6RGvCY8V7>-hPsUnB*!*8-rX{vl10IOXVuE%X0J(9X zFqbj4AGE(-U|elva{vNYpama0>Yo)otdnCYzm#WbhEiB4B0+%a;%z>XygMmqVLWl-Nr$?_bChV#P5jK`yf3bf?h1zt0AqIVcpD zR)RJH{L+JCB}M22J>a(Odu8SXHKAqgw@Y=yv%{{o%e%XVDyK5f1V-SQ0$y~(BXvW! zs@;2w>a^y*5)3Me50dpd{h+lnfjtLLqhj6X2h4?juyzpPxwaRdyQRvT_u}n5!&cJ= z+_~2!up_UJ59G3NzaeIx4XKm@Hj!KX8ujhZ!g_*#Wp{ckOkY|ZFBO4|j1hhmC#YJO zMEIg=)IECd38SM1)Pn%3`zexdnxCEYS!k{l<||jiCaT5rp9cnWB2cL8a1Oz2o!F~A zJ-fPub&g=-%OkE_8dc64Xd}X}PFJ_g+2XXvWf)TT{p(o&a!m-OP-Jg?ay$@h1db9# zvWiR+e!KFxHqD|xqxEl$NbV~KFM+2eAc#K6A~ZEtD_wok7z-vG)XqNarKW@>R^~UOCaYsJ z2d}wC$*CSWg&qE(f$upkP1VQ##bRTkVTjGj_7BQIN>A7WK6@S1$ML$uWOnxtW&~}XY1$G5Z>^i~Tu!{v65dE34KrW{=gmQ)Q)2cT zN{?3yT3w<1N>$6G_~}fyP?z&PXtPQO0Kd5P8Zb6q>4;UB9EpV4G13W)7RUh z((-w~3_^N0l{wUfN_@`V4iDS&c4D;1xh`?7uM)4sMJAgcsUM8mE==>&VYfoaW zk|#~1VGshTt!I38o9!lnl4&ME%v4-pwHW$z)xRsLZm=MJv|0Y@!4W2=q)9}JJUkB7 zxH0JPY7*5nhR}ej{K&2-TGfV#gdqXIXR7_Qu<@S&ABDZ%h+^2nb;U!%rM0J4^i5nbdD>V4beO{`xfBWae zm!sF(t1-GMu)DG<`RTcLPy;$}{u=*Y8eZC$-3J#MmJ;AscE1=mcF@-xh9)ax|GH)= z%APSbaFCCf(aLw`0uE;alQVXby2*S*w;(fzKf_FwiJ2fLVH21_iX%?d#>T=rISdIs& zN6Pr~@D%`_dW@t7PKQd%&NG%(#z%-Kc^laBY>p!y4GkWz02PL`$#X%OwF&WUFm{lv zUy*B^Tb}Esm~^sCfw)u=!Po2$vsjI;M$&Qg(CjHCG(N7l@Ty&Ga}cCr^lY zOp3U9QP{XTq)dT~w98%=g^eQGW*r?Q&a+ElUcp<{WIgt2>`16^cjcuxNr%&^eAw)k z9Qxv>uLNO&aJ*|e;w$0VxiAwA4sf`moR^_wD=UkulswkZcW@eh>;8%PM3+M} zGp&m821C7;Q(PqryYC1XZ$_)9)FX=CJ377Q6M)n(aiEL1`Muz2zKmOOgJTGF zHoe2EK;=2}*7+Dcys)(yM0b0B`ZH>8AtNa6WYk@{P4T(6xJ5eJtRRKvndC$>B!Ez+ zyvjMDms)edJn6fIH@|S59%cVt#{%|QBHr&fFwaQsp z^m}4`McU((FNYyhPB*VN)GwESK>hRAZhEcZAb#Jk$oS_-W>hJSHQjN|8N!1xSKm+s zf!!Lo#lIQVf3K4~eJ6BKd^GjwHYhuCW&t_ocpHoI?!MzUhWCP(d$$pPgD^u1{r6-B zY?-Eq8R!0zm-M_?NrhTT!K*r?D&`#n~&Dz$pt;UZl zKq;Zn{b~O4gd?~8nPm*UF^Cj1HpqzxvurZ&HFG@fCUHOIhps@!;#bx!rQH**N=bkD zzR7c99O7(afmuF`thIt(J;8RdvrFdt7DUO+9IuN_5wUwHk(w87fYMv|)Y25>B%*lt z0T(5DWR?Dtn1EkO+%R$K21f?3T^i%?J2$Q$BE0gh_2sy{{V{Rp(g zQ)Xals95o6yi9JbZ2YO>Z=@809SVDBJwZIlPI@|ilzeR`JJK?e%A9QXE8DZ$>0(-g z`Fu$ucd+U;%KW4-pS+ZGfIs)RMBpwi6{PdPG{1Cxv)7%=Xra{K4tFf|cSrpaZcv-< zM&S|4aGQ>D_8N8oP~_0?!*q_FEIGB_N?53=OA=8muEl)ua#P+C9#P(f*3{G@*>1_G zZ}}@KJZ5ZAK;Vm!%Uw;WgI9P@|0>s*Nw4?kxe1o%>2C}HhxNuMemt{4QmnTWy&tX< zUZ@SDpw=nxd>+aKZPV2}`5*dz2K(9kU`a z<~rsQ{q5Tu6nW>}1DThx?mk)xU--M3{*wg&^Fj7F&_sCPTF+jkAw}Ij7auw5wZ4lg zU03=p$`dHP`X+6Ap`Tqxzu7T!=TIGf^kO-gzqGw7tL1P*<sdzS~!C~Pi&~p3L!IKe~D%hgy zR8AMgJZ63o@F+`+_vO%KiC$lAz&+VLayr#2hvxp}hTC6W&EQ?*7+ao8HSK)5)6_F0 zfb&1Z8$^|NXvcHjH3VeRu+aN2d1@Tz*;l_n0z#6?DeeMvP)Ezf5#hixF&ZwKvK{8z zdX2~T054%SJ|R~h!nDZRbNYv?U!?pvHTfwtSsJj_gCSmkD70oRE~MKac_(@{Mf$F~ zT=k61=}zR#)JOzF#=%g#0-z*#o|P{A@yimwg*6t%=t%Us0aeVbT@&uo;s!5;Tu-J$G;j1F{~lW+=|LN_Ro~_M&Nc4 zFz67+$&yIO(Y!18#JrPxa-8w5!~FLv3V>|tZ!nor{XNnRN}Mk_@1|%+Ql^l^?s2Gx zJHTi@QXg90*Az!xi||~Xa97+(dBzQMy3QJ@W_QjH1{nqa0$csOGwUXP8~|4jm505_V?(A>>Cu_kagBcLGu+Scb(^@8fZ|vYU@j7(LJ-j!MkaJBxdMN zuDpDLRcCCMxen2BX@X_OvJ)v3=W%#=QdgEWXz8fe9s$k#y|OtqRJI>;26ZbR?A^H< zN0jq*=qMxBy1SbsXO1CAiE4_-loN8*VY)lj1eYoK=2VtBn7~niF~yK1Pd*Hvg>?j0 zA!RNpVN~8Qi?Pi=^15kJwUxue?KB_clSVu$0ee%O^rgpu+vk1C(qqg&XaBP*^gnAv z{|mS~XS*$Pu|(Yqs+}ni0XsUcdYB9bH9F4d_V8{~gkEUb#GN;QG5b&dA1;!kBTr{In4y zf+3vSBJ^3OhQe5cnvr14MiR9KbP|gzM6N3+9I;U6n54v-<8qK)52@1Vt6EH)?_8gf z|5TKn_i_8O-7$H!R`@d@^@!_l+(--}9grSX2N3r8e6SqG4F)npg!HBE91+-qqW;`D zmC%c-4*nd=V@Uw7l{9+k zFZI*X5%$tM^lQ-v^S$bi>$GzMP2XeSLx%+Z?}%Agj_Oo*kIK@1#c%yNT2*P8QqTM# z>_H&D4feX_L7fE$>PF#E&&!8OhD&VHKg(Es;i9{=FV<*uo;30;b)eE#$V$Rl4<^zU zCXe=JXM%`-LH-qb!jCPs|M1pxe;q3tD>I3o6+C$t5>?JHGxcVysSHTK z!~+JE2nJMKrCx&U%_-mmpDz+pOsKk?7+~?`nSE{V*~c_8%rkJ_-h6XLccBE1QKLX3 zH$1ofTk+;9Znh_^gPJEJW6Xx@|L}Gkp4K4y2K$DvKPKkKS0TrMs8>S|LCr-f;^` zvqDz?IAv!7cizsv_VV}D-CsF?Zi^QtY>Z+c8V=Ig7gie~sq2c9QLbJ0m{^8*^%Ba| zzxJsPuQk0O5SPeTL?Tb0O~!^tH})#$#rXX}7k&Tag1GLElYb zQdJL~gyW&po0-J)Dp!c?lu=ufcZR`;foCcKtQRcT6b%|$F%O^TPZp8-^6+#1T0=%{ z2mvrUP^vqLe&{!}u1Awypd{8Y9Pj<5q$C*esvN0bpNTfwe!2wCnyZ=-;fJ_zvl~)~ z>P1?%FEhcMt91^8+l8*6t6>2k^Y89KDy5@#pZOoV4CpLndT%Bn4%lj5;y6n6f~%>; zJ2T|%3aMN8L$(m@8B7snGuhwRJnP(dBT+mf+fMYDxl;tP4tkVK+3r zO!wqcgM=3pFR`SmyE)ygKiYj6#5x-Oex1?yk0vClGlq!))`7gBHWo&3*qDAcN(`fI zvK;rfxwy6?6*Lj$+$%jk{nU0uZ!lh2Utx~)c2WBeFR8}ZL$Tj*Os8X{N*?@mEur}* zr9m3HEJ9&xm}&SQ98FFkoNoaw%+FcQQ5TZWh~_{b_R1H!i!T*b(k3|vHMx=aa_aM= z))JH+G3+7l2Gv57e7pojZTIGIcaD1>JlH%xtriIa5Lg6_0Z!N;rhI;+KFrQvg;VqeN zt1^^w`4~)Na7Cb5x3j6PPbhLGf3W?KMeHB49_LTET<9-29kA{h zXW9bW0VH7_@6&jY1cXbyFW+70orp>fTyB?7qfP<;p|`#8`edRLR@%c{tF-8NWzrji z#96j0xx4WvL(v!Vmqa9vSCL#;rk%}0*!E%5GX@FHS%Gea!IYBK8>p^Nk5_#D0iPms z4a;-h+vm6O_&N*=@)HxC27KRfasIZez32BmD##bvrT|^!0XhE_-w{`7N=WXHM6do( zSSe%LF+J;$Mh~e#{;H=Jv!%soi4!CMuj1u-1(CwLkx+ z0Xo4?;p@1Ut5rz3p|$jK1~wy3n$Jf+xin>8EU?iuc8%#yLgKi2i=(C6m zc{n<_=gbbNeOVu8-)&!Dl`=8JoiRk22{|YgDULX?Mk5seWpFxz)%oJw|5ua!*P`uz zp{K{kbAC9=LyYD4ZNu^F-t#~EdK{=@OqQi747H^%#2gAHp8MbEJ*;`&`Ah*Tn@a!G z5WNFrDp@vt3}*gtvh>2+I98_?JvL~f0=_r=V`Q#cYZL&ObxI@2zh{K6=LhU=8nzg(Hbsgohj4s+|yF09Arv3}Lq2XkE|r+qB}uyY-H9I9{o&` zi-_`h(Paf?$-OYXR5jQ#~?7&eZzc#3%hn|x3YG7s7RCi7{= zHK5cH6?xL_5ESuML-J##Xwxl6< z>@HXHBZsL-ts68x4cDLkvsGdZLnf^8msL3~z5>-@4D1&HfpXUZPvz{6?4h^MMz$oI zV})n@`sKg^25dZ?H$dt*%aPIMueJT#PamfaF&UwN(lbs*XhG0HP=WtN3!Y;(z;9)1 zB&FK<*6$y|Cv7L_=IVePZ3M!+{1=0t!)D%Lmbm;u{clbA&+j@8)0xAXnct*HRLb9P z>v=hq(E(hoq1dRbxQlEFRlj{G(meoq-L>|ryk1WTr6tg9 ztHB`@UAi#;kcgE1p6k)+?>#PHapbJT9L=_>^m-wqE_=2x2&A;(%BenL9$^R80F26P za^7Ch3)cJPgMM^dzkYFirEsq*Q=dHc_x`qNiLbB!;G_JSu32$d77KW%U}93qb=-gV zV_X0=C1k~OyuDxNU+&)KdeYSNd8mZQ-2sU+JT)w&NLiWT;ev?+91xmc!`1Q##q##u zcEUGZ3SltnRu{;w$peqp%Sf1*k@{0Z*I*ZBW72u3!D?Me++3sqcGINL+2oIMvv|Ux zG(1g8o{XD4JS~+wCc|u=ka9JU{Ayo^kw`Odi{L&NzzS}>+dXqUjm?B^&t7XT8T3D< zcPdHj=F>mD@b{B4+5i&y2XFvCcp%4cfx}`xhs?9N5gDWC9~7B!ym}3gwMFJrakLR- z-!UE6t8YzxXmbyrtEkZR2`Ux;L7EE)AArtxI_`S;d#<1F@PV;3Ho|w!05}t+9c_xi zKZhhUS9^6S^qJDwO~r!*-MGF4C8^aQOMsrz8L1xQyZiHe&y@*6H$nFiIBVsu=9!-U z{dsr!gjAqHh)9dj+2Eb!V@p1BGi@t&&_iVJs!1wQE|6dncUF1NVfn8e=wzZ@|Flit z@{}A$^#^9teCxj_7pUndHV<+?CL1i{0sS;rLXGiI@^ZV52nGUp3RGLr;orZ-BDo`~ z9LZLBkFV<&8%rt|e)a(HHJBvaGZd;6Z_JXUQ3$(YlnC}aqQps2@* zt_s(mKTlF(3)y80>W?Zz-eNi4M^K>%T3x;)_&1@3VgE}`IO}*>truj~4#wK;icXFt z9<*pI+Fr;CS^1BnEpV{!(ELaIc;)e~S@3nP!Orv8y@y;@tt*ys@!pncjmAHcc1fN} zp4_;X$G9hpU%C-APfHlcZfEvqmOi9ARk>ptFok*^NEs)kyqjDK8PW|p%{;@pBqv-C zf?Q-VKkbamw&+bNAfc_564HBRu;Iq7-;Aw`gc8&WUW80}XNYZP>jo{$Y-abSBkBv3 zl`3F-(-8$*!LkJnNN+LYZsra%X$?iuBUnOY)UKU|+a zn$a{ARFTZ;m)MFC)baLt*QjtYQ$w1W(yNC1(>c=c z*)3Jr5>w)*&RpF?db1*=rE2xJQ@X6$A*rv=tmM1l;+&M52`AsS#%0x+w^^ZtrjPO& z4U?n53*UOR^mgR+%jn?Rp}(gOjg&vf=y5;53Mq09zP}RAUF0$Q7Cqi5vpVW#k>jFW z6pwFj;WM$!Yhpsj;sK1(|8TQd_t;CSth%^RD=JlVnZ$}CjJZIq3)Zy(Hlufc+($oR zIiRqCo8J8pe|ZpA%z3yv^q%uw+bq2@nU?f(lePfUD`K<9vpm2_z5p`=^*f-)7JFY>4OlqR=wDLR$ome zCFd`=zV?Pfxn6oLh;L&?AxhFjxb|E19tfo7PxsKru@%s_#)JsbMlDOs!BYF^xeF8(f;0R21Dawz9u)^Dz-Qjx!Jfe1 zZ!ST&L_1^$_X!sD(`qaICgqHRPu!Uvl-CaN{#@JCO9<&OR={yf z*sT6|IDCB8Dz9DrxQFc=H$CA=<1^-SulBSM0qJtrrjEqUE*z+f*Uc&4>pY|r`-6T7 zAj|JB`r03y{Azycw&2BpjdiPI0@zO#mz*@GN<#*99Mnf8=uAg4yqzyR)Z2tw|qoXS*!NE$V$NN&T$jpy@}t z1o%Q^c>HCVAh(pzdQEJ;3DK{4m8a9PDsQ83-Jw725FKMNsA-j+>z3?ph#1rzr~wxb??>TsSH1q?`{DTM ziFwz}uPwpmlj&6$_>c1`saYEEZB89}v_C@K!aEH}Z!V!=@QgubN`US8-f7Ldh9BG1 z15fHcL&XcYu+S&LySHs_H7bKhXSV&L>!nT5OgW`T4cd_@*iyUE!4tK^<~_NT!5rme zFBodwK5CUR$MJFd+2h#^SMk1}=))9vTRAX`Zj|Bqjh1URue@7qd!lj4B>04?{w*#8 z4Sw9*o9GJbq&=yq}wph)zMzftW&@#sn(bPRs?g;h#GH}on- zHt(iPv`9Cz@QhUgg7u&CO;hDHM=lNOgcgI=iFtnTn5NbJu<`?-FwMWsuV8ah%# z?<63-_uhNxgc?E!H{Un+&fJ;jnP2h`Dkd(x&d6eyBMX0A4~AWMX=A09lW$G-tI5|4DR#6? z@)Fta`+i3I?iLunV*VdB{vPp zm*;|C+WJmN`{cBmuGXt02+dmiDmF5UBU85Dj@r2WWRDBOvCS4dug{o!2B)m^R}dGJ z2T;rAWd9>?4u0Cg|o9D?7p7i z3()Dv*))iDV=F$lFXXL+8rxw%vg4jJ!eAqk540i3aI~R1J3<3kY4ubvJ_;{5tu9{U z!3f=~$sP8PuOfzageXdQjwO66%$#n{xUixgqPs?wFQfq0&ZT=aDHUz{ibmO1Hci8| zshCLpZvr4tBUMnL>e)^8PPCWs?CQC=s%sKq{Jh7`6o*K5bWp$@t1zfF_KCz#N6c*X z(v58|#>*jZD&XSA;1Axs3SGj{jEgwjxr&us5WQMi(KK%1{Vof-nz#L9=ALX+0`%IL zrCy=_pLcN8=~0&?XrjV1zUIzO(3Ek)5fznYd0~gp0R=a-Q5hr-=Hk3bPi%=b&A)df zSisRRSNP0(C4jSrKrK-g)E5A6cyP>7fBFe^pUOsT9!Intk~*q(EQi*;Pg#@Ly!SQI zk@DdTm4`{0;VNej`$O#4-DXj>b ztDW%b_egC8Qu`H4+%Oouh<77z(~gggI1m$T;1x2TFIs7besn6Y-(qkXS5Nc z`%a@Om0B_zpK{oTR2K#)dD0IZF;%p(e&LyvrEOrR$EfdQW=JVd`(e_V9FmQ?xpPb{Fa`w%&McCF- z(XU=@#}gK{rSiH+gDctKKI8E31v2h-_rJ<+;Dxn zQmUceIm*>_x79Qsjk~Oc!cZsC6OjB1R-f_Rt7;7Z)A%Ph zGiQ>dgz!7(WX92<>;o153F}U6Idm}-yM-j=CMk3^lRqh6#GSGG1kb9wp|)Z_fWL9~&cBd_&&xOWxYzq6q5D$Yi!G_Jj!Z7&U8a zyY>}hyYN|M?qUN%wl7%!MPSfp61>&G`NojaxXn_fVyZLSHd+xHHp^*O;E+l7o8yOh zSx!%4_p1t%h4_>M+BkWV4$hkPY8;=Q?|TMgp`(c&Tt!Hx5$ZP@m;UmwCDdSsqZwv5 zq4>Cy);-e|ic6$VINN7F1Cjme6B84kjv5m?j#co1f+YafN>lbQd3de)f_tvn0019= z@Fr6I>#)^REhMsv#MPEtLKS}TW9@Cv)GLES&XHD!H#QqS{Dk2lo63>h%w7>U=BzPg z16u#EYw5^eULJ*z2WQeVUgvQ}hXlHOx*{Ixj>3*VBfaHXzT42VvM$DR94!E}e3||{ z8ts#*^-XuIRp1b>;uUAK&jkJncA#`7Em!NVC5R0vWAeSPXl>MIY^pF#1{puT1qqm7s>7hHe4STG7iV96_0VUa03_ZCtZm?>-{U3{u>%u!5pXSkBQtz&@&$~n@{7#F<`eYLb# zsyfawOFWJD5zPaqgS~$roxR#bc&YIu1D~ZgLGZt@H5m}n$L{`I-c7aG(+;`v9istR zhr)*zJ(td+wMi8*1H2wtue`zevE$*JQMP?mWsx_e$5VRO{4#e2j#rrB155?Y@*RZJ zy=2JUg?o6#lcNz_COiq#_X*nOWM3GJb+n%hj!Iql^)sDuQtOeSkMDTP7>D&+6Q0dMB-XH z5kl1cH{C*7D*qUZ`M(a#i>F>@JBiT`DT$Xb4=GPdUUY5_N*=+EDiJ^0%xG*Gr6srJ zj)f>+WB_H|j`oC4qOuXJK{b#AL6uFJKT=oKGlBLr2BxLW8>0>*LZ64+H>x8fw?|09 zqFm8Ky%p;jIc|IkHct#vZVWa`ZV1@dQvo7ehOOOxXuclhHkO*>1)L(+QEWb_3y@FX!zhR)@h8-^( zz4S?Vq;9k~L#q5D+e)15GLdlaCjDMw@k=zOx>wefZ4 zA5U8}tIye2;3w|)YSxhL=66@CBz~(})hT>hSU&z>d^rByRQIWnYTiq!W+u~ChxG^K zL9cRScg$pM8Q{@jyyQl{xW})^g8Cz9t8D2cH)=wfz3fRs(N0vAXR33lXVl*;Lhh&? zdWu7|Y&+X9&;9<6^vhDGdCymiAD+rpn3x_gTs8|GdZ!COg;wTv8$Y&aTg49f_hF>E z&mtb25o8V%jtv!cI^;gejwQp(ES~xjMdjI96UJN$=Fr6h@7F)%$$mEXV5;bO)%tpK zWbF5hM-*ooG$6H2UX4BEfkk9(K}0dL18%^|Z=mp}01Gq`MK^EkFh!Q!rG!h_P7AUj zM~|?W`NJLMZgzb&@)oF+$#@3*J<;btF{>uScyq>U!E(Wtoh+vZcp-kh{>1S>zbv*q zHpb~Ad*E27R+8MR@h{&v$g9UElc^mZ1!b$7bIzQDym1mK-`m$)?VxmKA$I2nZz`HY zgTujnP1A$uHSW4RtcAtuGgFocWf4@M{sMf`r}+EJ^W=99WCP|IHWA#{ldC_KT5t;e z4uu<=f+oF%w;J1uygNfRFPQybt87F3kNIW^+$U0OL(VxP_8V*d*x}Y*D3rjv#T~qQm01 znL~)|4#VK_btSe_h#IVbbj!l3)X_RVPOY=<^=8@YdT)*2eF0(~BI&+^s9SdIG4&Yw zVd!}6;i*D%>YLHEiP<&{^kr4ly`riqq3@n=e?@kdX(j)8)S2A1@Qt<4T-d7XPV~+w z^B13rbqGrtbTJ{#A))QK(0stcnqxn+b|GW?xW!ujL?W*awocKNvfgsBv27H$eb1F2 zA|V%%h=nHJd6s$R`Dy?a@Z&OIheG77Dn?B$EicVs)qrjF?u!p)4^ICcQ=({@(E?*L z_{7*?h7JnUb2!?eL*k~LQLG8P-w=6F63k?i$bkz+6KYMtt_J6}cONkPe&+;)c>tvJm%Z9lCad3%n$Eq7!1 zC=ZQ+7X|o;^Wq;)s7tj~+CqAMH@z&%NiWya=mJ0qD|Jf5^H9NZ1_3cwK6f z-}%-=T=vLCak>0u;)BYGNSAWy8no47*j2w@GZSNnc0t(a)<`x^RnT#&XF>2?3*k^X zvcTug1NCf_?-0V6({i4T<#oS|=Ga@G*6(6=p8TyP$>lHIn&r<U9)zB_4eftOERsG>k6z4<8jzIHjpuj+8Nk=c>_X8NbCWSd!|!X9 zKfmtoxpphFU3F+k5^>^>{WX!;Vp;J7HOaCGov7CFAvtZ{X#}AOk#<52#~15t_!yn8#?;T%2B~X4U2U0LZ(#m z)wlzUa?8dEcN;wOK5lHfJ4*tLgHdkp9Yg;0h0Jw6rTY0B>GxtwDAQBo?!x`o=@UP= zk+uq4YHVp^01vu5jIwRX5qG%CKyY_u87^UQ_AQ5qK0iqS?8+YF@TCn^$XmBnyU&6g zt>Nu>l{JvXtJ29j;U>b*kcT(Ksvyl|E4dVuUht)HfY zrZQ9<(&JM}=h|T(Lz#_wsJ}&|16yQ%NZk{y2O+~bYDTH!s2C+9@TS0&-P^2_%8yE! z_$u?ZX9J|_Lw4Moyfq2Aflpg@N0$N_!Z8>78p)50Ns)Tz%j;L%S>620X5l_~rE=M- zlN1i5@o+%yuE$(Dl_K_V5VWCsD!)SzgK+%r&%C2;U!3Vy%OehG?j0&W&`rs#$Z+Ey zG4f1aXKL3l)@=f$h2AX~Hc&gvb&j6!wl#$(x{$__?4G7!6G6&>Fnhmeafsqrv1U_` zO>Vp8q}B)wOuz8B&Mnw~?QOK+yhd}u2~r#MoJTbeJMxIr?XFyy9`R1UYQ{qRZ>`f; zi-GR1?B|H?o4a28Q?<`IlLit3elid53c&U}3ekZPRf!eS#fLIIeB{(5a-0tQo8J)L zXHU9rr^>-`Q~{q~{rFjH@Q$xP^f4+wY~mnU&cwgq&_LvNHJ$noEf)DxLJQ+r%xKreoiaREk_G5{sW@-PZX)WXcdHolSe0-SM}wVN%Cin;yzD4h7z=>lOBj?%9&7q9sS*ohB2#b9Ra+J7-w9f!bY3oJ01irxYKEGFB(ahTEBWO>DT ze)((iou|7av%Zy@mVU<2XEk*nlfwMOe5!KZJ?fW~vX`3Bx#lY5>azLo=Q1O)<6v** z4mrm+MZT8ZU$ANH&T*^iShV_1N6q?9g$pt8ZyI80M&`T4)D$YV0KAV>uQ=%%Y__iL z^(#-22j2`EWH^y#hxXLD{WZu?Gm$Gi6;e?kRc@AcL=s&_-y$~pWP0m3mv&pI1c06L ze#RVs@5xF0DJZ_(w7_)WJdywCv0qtln0MEI#@_~UHS<5B(OkKjVw5+PNwg#Fp1YQR z{8UeCN&WO82#_SqHE;-eKyAsrbPt;F$+m}>Te8UG#wQ)~bYI=hr(kTRy57=w(s=5C zEV!Py2LAWNkosc5)sGSGAF! zoPS}g1t=E_L|0#D0@{7c)=t2P6(Y-nX=P}TrU$tQf?be+I-f8x&9tlyvv!nv#YRv; z5ur6#i$DY86f(?Fp}^Q;pcaXGFvu|ijpFQIUS)DY8Uq!9N+x!(=Gnw* z*~#C@D%mDHUCbq>Xo&LKu(^Uwwm(%fFk7mJ+2rNpgs^M?TVK|A76)7TL)0eYL|oT+ z{;R2tp#G)wuZ!j2l1zcr(k{HmNrLBCMYnY_ zY`L3RZuK#-pPK)?1=&Q?tnBti)#EU1hiGXL?e$CTaI(F7RvqLp@PxQ(h)R@w?2&PE z?r>G>AZom=?U@Ue%(cEKH=QtcbxEmZDUT#5s?yqc5+4fDE{T=P12guuE<{Mafx5RS z4{F6`4EJ>%kdIh*GlIL04CV5)yotC!Q5DwFsTKi}VxBf4sKRxg1T5jTtZUMd1!iRX z-f=k?qYW+0fh_G6*LN_BZC$AImK!D5-IqWT%Fky;DGILkX#6aQ{GVOvxz$Wz&;N>9 z{%>v>5AgJJ@ZBBamI6+Ga-DKam-j&+j$$v;zdsINjxneH;_6gY>$1-xY(%N#=&T445S_tQEYSbpbpSl?ba`czB!tr(?t5 zSW{%p4eX>Z;HuTIyVZm@;6dcultk)%nnx@2qH&kpntXA9kE{=dYWf3r6M3t8r^ch$ zIzbHZtFtfhukoRzo!sN`8^24uw|IM~Q}8nYm>Rg|mG~nMzD*)4ms=3L4Pv3w4!XW_ z*$FRM?ROKu*aC9@{YG~AbNX2ik>w=-H(KKuKF1e+cx8&gjchCE<_s$)&h8C$sGJ>s zlcr=KEroPt;CaaJw8Awy$1V|f;L9Ia8(d8q9>E(xqT8Zu@|%**;>fNQxrsZ_DOSkjaQ59%hRLtacwYWa7~W4dTKF zr7IrJBht6yUw&((6I7{hX&-OS9&I30_&qxA=bVTzc&=eMHa+O0YjW-}T5haeb!b;V zj=O0lXJ&HxBXY8BB*x2B6$))BWq0=VtPBmFkT=(A-AkxDeJA0^V3V$e6ALU<_dl%Y zklU+x{#uYM{Sf20Xjjv#3C2ARY;kc; zhTcxp+ z27JS?S#NdCgxj2bNTW(kPW|L!Nn_J1Uw2-Yzku(kqDSl3z87^CxY~$MyyhI84YZM} z_}*olUR`;#*Y(_V*Wk6jg*dr#s)EILIe1NIy(c^CFnG9Ho$XtHp|d0657Xl2LBl=M z>yGi2t`Z5hK6}8^gl$=kMz&y*co7?Wy4Kc<1Yu;}-W$_4CNmA6AKxC3j6va` zy+=V$@ZXv1DIU+?G#r^0Td!DT)9frWf_KKECxfAFbY?s;>q%F`FL|*FvdCJAzwqie zq5$Qa!LRLm;GH#%bJoC=moJ0A@@zhJSyV1z)Zp{pBWgQA56I#nsUjXn7J%G_zY3*u zgjR_fw@*TX5Wz$tMk5^8Qf17V`(fUzF+w|uiG4Az{52Hd$znl@PYd)r{7uY_t;sj( zbhiG=%_80T)&{jxm7bAj=*I;c_JX{n})qD10an3s|5%x>7 zbqO_mV2A>@$a*vBboQ&vH7m7d$#16)2_$5XrwotoSDbcE_Ft>&3JngqnkmFLq=gk* zY5_4;do8daUCbf-OB#p8M#l3u>a}@R+p>|xuEL@mZa-wiTb&M#HJ{1r=w^YWtD=m5MG>WeIX-h z@|4^@7f~Y<5%AVH&(i`cDsDyn2n;Awka_5xQR2N+oJ8Yu7v{Tt419qB=CIj(?Lq3S z4%cg^0LQ4Ka^eaSnpB|ko4N%~?fdLpZa#>2aDYVuiCW(-Bw%D`ctGzwrB57V+0ECz z3Lr}ZWD2UIV5GF&Itu+4LLh0z{OUbrq9Y#x?nP4#%yCHb}6K>$Lr zPCGLNY)hFaorKHh@3J*V`HWSZ${5Gh2rFNWWzlte^NZ#1{?m+BIX=0t&A&Z?v|k+K zg{kilZDrrUjd|5hI_}ZNdvKF$=g!aJ3U9fd`*gK6^hbV_tMFc(5e45iSBqZFI4@;@ zX*$m0rR*I#KXd%(Hf*_KiMcyjSSeF#6qJ#BsMNjnY&~<&* zb1mT6$ooqzTkM*#6C8ffx{9N#W2u+j!Jpsun18+9rv>sxX?)j`CD|uU*qC&a8^#JO z@^lXNubs=()H9v8UST@0|D8$DHV_T4$m2K(5KT`8rOCXSJy+mH%uSL2VBWV!gs- z7t2Jej#_UeGuc`DIhYbSr?lq6aQ9%yik>6gRp4w2SEb~xoQ2EzMd``Mt{AH^*sN_y z0TsQ1P4IWXi%70hy4wyWgifc_B0l1!n-%$2Odcs=-n3uFBCjt$$#D*UihMwy)<0o$ z>D_zrZ2U!t5Vm~P)Ed=I6aGGex9sEUbSaywTdBcj{?TrAM-v;C?uFoS$7VclMJAvB zX7`5|r%_C;_a%7O#eax;M_Vp9n?TDNXZ_wfAX>jTkAJ88Y8YnvGe|zwQ9hA(9Ur`9 z%-tS)F&=*T!Nfu0=9H4e@t>nuaE+7m_LV0SG|Rm3g7{Xm>dF_cXVh%U7($-=E>r5l z(cP5uE0L_y?vC->xmKmNTsCUq3wB@j+KXjipcP59S+ z@4X>GRIQ9V=8qLr6fG;R+-K@nt6s02drx%G5*oQ?nbYMQSHN9jBOwg_qcsiz z4-%C$$huahm%3@LzGg}4XYYRm&{n7cxRzU#yB>9Qv(0IXC;6gfH!iWe57GP3e;a_uKki&u-8zQzLo&C^L@oPJ{kEeaR+D<7UOs7$l{= zvByk4bbC*F!2zY(r+s%Vgb(I$dn+ew+8Zc$(Mvf6G7bctHkt<6lg#>=gSqjLi+zX| zc@aW3XHnDqlH@;gsOEGS2=?O+)5Nv=w5koKKe1X)OYjcD(9wj*xKUfathXqM{=jJk zWCS&1 zcI)LPDRJ62B93{*ZXftGM3VP;oLJcATVjF9a&~~S1JEh%zWf@pWH|t}hw=z#EKZOs zgURx0)z^6WhR4F=%&E&ZQm%Gwm>VR#E|4haNOpamyh$~e!26zg`wKISO2&ql(I#Q& z@!g!*UJo7E+~~ELpvh&Cv#ap4Zt<=wMt6U)*C zWUNs8dVpsP@uzuLEt#wlx=T)b#nha}{H3G`$x!U_4Z_VWMLYWlfNwqMK7yqPja zZPZ*qN(cg(JOxONy_9?vT}K0bS`-Zjk2ZvS6L({Hl-6hHjRENGb5&Foh%Y;@>^GdG zAx91=_yn*44Ci$R2fPk1gfP@P0u57vTsMwvh|zO~2>P#dZp!F7ddl;%?XthgV4|c4 z_FoF5>Y}HyoiS=_=RZ?RG9ReOrSa#A9fJ7Z!-utg&^t{#(po71BKbbwB*p4oiI@^* zOJS4@3MG64Z70?YDQMw<-R~4uKCLg3CKPZVo&$|+OrW>RdxsloOn%UGKDj7dvbt7R z#Lm(E?aioGwWqHgm6#6>rSJ3mcK@#mF~XjA!H277Dh!xg?Y^#$mJaGf3lzhiQpg8D zdfFR4`+JHFS8UO-@9-n%GNSUJAJ-K#eJ6XMMeWK&(ln}wjpHfo$ zQux{1nNm|g-NDO$t*!yS@~qM%Z9-p(KJBC%LwjZY@ z3R3AG{KuCp)UmABrR+`b{40IcEFqh>_YQO}>eJ3FVZ#Qf&q}ZjoQpkfT($WnceIguXA!QwZ~@KfXc=>8*_@;bp&d>0DJ)Gsa5|xAE$IO68oR| zwDIn*YZlj}F_YU(yE;bKOLidb?)Jao^=xOpBFIZugA7XenFM;W6ErSLgsgmY4!6@u zZ#*~plf(mjo(7t?o1x}4o{kr3zfO8`MczI3F+-OaYua0|t-4oKEj1NvGQvF?;^>y+ zuvqFnRJ^|Ks_Q*&nB~Y8RoZ?{@xYW%?;0UngMt_hi|;E=-Ie_NB0qA(*0tWEaw!w6 zOV$s(I32tFTUmF^gaO-#-f<28j!o}`jXvdNat*1ki`Uw3E&2TDp)~Z?Y5RK#RNnjH zK$A^VmtyJ=$%jdp0*y7De9R#)9alJBKftH9U?Y&=m>OPXT%=ZQnZf7x41#b$j}`-W z_!&&9`nH);&oEWHO90n06!1A317X-mulqT@w^pM|T&8B&^G?x;))|yyEvQZ`+%SCo zWJ%MBr2L@ax@^1n8msq45UUh&-?-`L$-cx9RvmuwZ`03zyWHQ6Vl%BjEgB&pWDwcM zd=28yfuDE$09qDtG`%@*V3)R&RCF@pZq}E_|7qhsPDAi_j_}hfUpH==*`mbl>H!kK zFIg2jJP@p;%I%dnN)Jypy2g3NV(XHKyid2xhuP1A!dw=O*ga)EfWdP=-yeVN2Mw}n z_#&gs)Mtf~+#fh`9)49dW05jaL#)XWdm~O|5599+5wEDye15?Rv@PTvqaj_QbpEXe zyt0{Zo0~gw8dptn$@3kS$R?M~NVzqkk$h{BK@@oHS01Wopl%K6GD3Tb0}egY-mkU1 zMlb6hRV)G4f=!8sb;)RLm6o^own)Cb3~}Sbu9AO2v>eVF(KdsA@(Mm}U!s^Ie*#i| z0zg2pNT>tkgvx=*r|i}Yp3ilJDFw(ZY>j_t<~RA1Qg-wg72YNTs3Lh&u&)}+&#m2B zT8ZwF_ROW&{%=Ch$OA7Hfn>~5lEV;zz@Rq~T-S9O;@r+HacN|86tdb1ee?q-eyf6A5vCLx4 z{+D}P_uKlC%J#lEKl{GVF3fMGS5hrkpz{sJ+&(Z&w1N*|l)PDa${*$c?aFdRY?P_V zu2{Ziz27;Yv>7*p=8!BO)3*bV3c;tgOVwad^!j)G%?nJBHi;d&=53E3EpzxNrCW6HXjxs5;hn z&2)zksnx4*Dk{lB*y4G?`%lJNWZGZp)PEfxFG`Fm5Xw;1?>meFHBr^QvMR}BhqG4r z)J#9VHvem@slt5=gG2&sl1yhHg^8-c0`P^)-dybKD{lAAT#!7*Y zpIN8a8pa#a5{u~j`OVy0V=rd3&@^e0k%@f)qg_B9SheTw^5R>L4 zTp9wZU+kZQg~frQw1UJSD8-!9iWW#`gIJ|eT8Kp`^;_R_ZH;`9JC|tdcI^?17yaMD z7r0T@M4-MW%> zzyFbo0r~Uql>UL9tRb)2d3StKCUS;KJw#gX#V!8PXelN<&_m|O1e&m~XQ}L|%US$1 z8LLbDk?vIxZpBnXxVNt{R7d02OKOeNQNTL&r7EHCLe`0|o08hzvRd2BTEDTnw*MqtHyBnvRfx1+3L zPMVra5(Kp`5G^wu#V8lHWs=m3Emy7f^_lsbFaZ?}4LL@uwDpcuMMo;AS9$z}P%m+L z&E5i8=QwVbkfFAmrOD1qV?X1p36)hvs)QDQD*rZ6Ij^OhF>guXuj`+mnZ0TaVk(+% z`GeEb)pN^n$LVL@qNI4n{=y5;TN(pQMd~0O^*xq4LC8I*UdP&_vg1rsG3~;vZc*{Z z*Jd11FV3U#zH`!LFm+@!k-Hlhyh*gW)|$)h>oV5A@^_rv;Zx|VoU564Ir_o< zAdX>vAmZ7_jXF^trVW=|_d`?3Dz%2_UA|NlM|yLtEr&5w zTil6>5&w)RsaZ@0de;!cg_C81IyNz#YxzA?lnmCvZ%CR{EXp7D)@ztJMegDQi_lA5 zw~}|(wys2o7OG|A+0X6Jxz53mY7E5VoyCUgFTHfNfNPqXeisO`L|&@rqm%z=O!kNW z(U>;(r_(krJ|A6J#!FOP-U~?)YSbCNL{EE2TNL^tnZBQ?pB2EtefV5acF(X;TH=-g zT2W#u-+A_JVN&fe$Y`QczY^=`b&K8f+nH{d!|5HcRf4+moI^&BR3R9!{G#UxSTOF! z^*9*rC#`sb_U4L})KIUF0M)xC({CP@N@&ONMlT)tgUsa9!@YY7xUezXx^8v=yc3@> zjym76KE0KO;y)kpT+KEfl#IE5+K)QEr=n$Z3HMA5_jA9b=Tx4W-j>@&!u76{e;<`3 ze{BVB4bIia+UTeFtL#Sqhtc;lHbVkOWimtU0XMJnrlUz*-w^y8vPTITfOOR-Ql&G{0m)JMNqq245+;)ZP|z;&(dR(RY!m_>FMm%{?;h z-4Lt+w~r7IzQzSp2>kMCA)Rx+@9xs`4S7rgMU*FSo(nH`O_s(0jOFQ8-kwRODE8b#DB-z;gnQck=HLI-@-+3IAt| z$3l6^!FhG%nFwdK{6UbaPfoxOuz}r{4v7lsJyHz8Mv+-UZJ-7#diOY^pf^LycNK8V zu&o{^@Bd8T)7!hO{~HAMe^aIjJN_%{|J9;_pZ=>w>F9e7Oi{6`10OgRS2JJ8zPk(F zN>fcq`j$F>!_D;PGB6!du}?+$tl?l$KCf%g>9}(lFaVB9_(x~i3#I|S%cw(|x0d8Z z1}B8J)oV=m7qDJ6C^W29UGp>UzEb?o5un&3AxiBtN;1?#X%#j^f3sD%a{i^jOGyBi zaZj)(MQ%*4^V7lmG6$nZ&%sE?{d@HS*9|rtl)nGcjRDoe=zYk0%Lba; zK#4(mt%8u4iVx=r(7@q-Ax)c>pLIz=w{!eK z^VX9ZO^qCrV#Z)WhfQT!^}YM|&Z%0lg|J80SvAK&`c9Oh`{|}@t1{<6x&zE1iS$?~ zygShU0)#u@0uKTo$^X@Bf;`8$MMP6wCkh|XV?lbp zE`|y?u;wiM53?Wa<)4#lyqq$=rg&IAp;zOs>DG!0ZM^7p)&`xasN9z0{YJyrI{&uf z{D2KaD-s}VL7ftE0{;D?^{cF+n(i5gR?=PgR{Z91By8w$i^bA&PmYZxY)_z+-#H{s#BQH4y{fF{{d-n$qOXmJRlM!MS0A`5w5dUgD{%+$;~i+O?j@ zKuPma-M4}{{M^&{g!}7L?4l79Z89GrX(~0k?>D6QG^PxROISK34~YmO7Aq9!GWtx)e~+Z-(zemy-MbX>1*BdpV*ld&>H1A`=Oa3caW9%_;og{ z-tg`?6dsnEJP~G$`O!#zHu~X_(Qyj9f(u$@X7|o@DgIpTIzD>BH(t^mutI2(o@UZx zqp~d{WG&E|=iYGa3v+LO2|SQEI9nmX0u=<_oba~yZG7-9=gtjjCU9YCHU!#~AL3Wi2}>^H@aVdur@pmB7@gaN7o5sD*Kk7$V5Qk{n^QGz~uqN13tuN`K$W?L5qCDFdXY+NxJ`TQqM?Sf45} z(UjNx&IS6GxQ;y<@iW{EGu&Elk2StV)$$zn)Zu+ZSb$wDl>Q%Q+?8qYsH_g`vB~=I z!JUep`>0ds*)0pbX#UKKqI=#me7L?Ds*86|{WRx5J~>a^ks5bmC!y04W?Sb*42-M~ zwDp*1utLdWl#Okz?tG{(W`}va@Wvno7}Cbmbi@6EuqbaGD)9y+7;-w0T4u`{3QGb!l0eVb$v%INTuA*L@m~br5lRnxG zU($IH#Lm|v+>_Ahv?_E$tDpj-dpF{qxGhYkenFSgZDRoUcbal@q!b1_s6%asUGvgO zsp%nj(B2B^M!2V>CV=+MqxtZ<^GZIbLLRi0RqoG9pVWMt1JrlZSR&J}3sg^gT`D`S zi|~hDme0M6TFEtp@DQlEewblC#w25nSzgH_XKm!Y>e`SRi{$NJ9S3x;3~MzwCDZWV z31w2kOISRqUw=xeLxpt;C#^h&vaVQc)94N?kUG#>6sF?%Rc`EPZ90tJp6A+0#DsZ}mix7gGuD9ik?VS&2 z%e{BKDgSIPB?5ie`J{14+52wZuHQ*5?=I%dapET;ZkI43^o1F&B;R*qTv1Dwd|xTM z@2_X#G;hV&4I)z#H<3n;NGC_Lw$n`w&0}(VPSVJj_2}Fi!s33J6q<}m`wXzN54YVs z-G3jNbCi+KaCDon34dE@06FA-qlTb@7lBd}B8rhQFEEFc4Ks4q!;4F8V&la|;+xQl z^>hQ~DfQGIkb~=ZjDvFW!CT)w$Pv!sO^i=}AFg9vWLw-xeq*i9YJ2jy)V^lhuAXmO z1mc_5XKNuahwURA#kSvJ+o<^PBuF^IIUAgfMJzI*9&w49*^Gkie%2$ImMD@ZP@eF? z*MBJhJbrQ@u|`k4cHYj`?-V1wmMK(U-~dwEOs$Q>>|nWfvzR>!Ji-5$qv!ljMEu`)=$c&YXI_xLKYhZRw;ZoQUVcAWABh%Dn zap_A@ihHx6N{mhtob&R(prNaIGXAo^w17Fdlg0iTB?%5(&8OHxhFzPKH;=&p!@VqJ ziU-JkU6(j?P0&Wrf#zB?zEQP*utH8>;NQ2f!}hcmVZMmKGIidh1HMp~3rqNypo`O8UapGo|BhH?$DIC-~1^5C)i=G~exO)O9y)({qQExkR(QKbqd6o#)mx zU!j~{U>_;aeh8%3Iw(!$>NwfKDaOWDjDgZx${gQjxs`7qr7t6l`4`6~9(FbY{dGJ$(GJ!AvUT)N|JqoATi`zGTTyit3NW7GyJ1?XXk-K6m}1 ztEC|HQN7IF-(sBb0zol#98=0Wdw~?^uQ%x(?35!usdaH0wj{pitXTNL*tWX6{?|)m4OjL8 zYhUe~OZuhJr{brU(PDVR$Cc_s%r(`RH6Rlb(f;Vx<@`#)-0r894&d!Zk{$e* zYbZ;ctMLf*rR&TG5NYMPF^0xK54ojtJ>=<=AUgxe!dq20>5 zM}6)NBK4o3flj`sJeOW0IqbHmQ~t_&#B}{(Y;vmZ&C(akhc0K-j|xBzBKe^r%x8wq zzHv->8hS@cOFx|q!2vZ(Lt=BH>qcXhO&o+-$zLy{`eHWUb*)Hg%&{g98qIE_;<)Q* zZiKI86ePH|`#p4a;|+75IkiKtIGUWUQ*3a3&qSa7Q) z>G!BWKiTZFl56x(!vy;e+rMQ9Y>JhR$-T3ziNc1^drsluWnXj5J7%|L4u53o9X#HH z_-H@(#dx`0*FNEDplMa)YPtGVmG?n;L7uoe79hx=OsH&c4-4Lpeuw)y*LGPWf!}T6 z%9pO(N8y6y!=En}2oLQZNxBs6>$6HuOFS&&d}dOk$ZN93TX!gT+Ke+wSzGQxSvXN` z1Q!@P;UB#5ycjt@|AV5f(W11yVxH0w{+=tNi#?VCH;IGIqSe9cFu!PER}9l$ zabOu~Lx6&q_Bp#4+7CT^4i$Yco2OS^B@AsudV|Qi0lG=UD~}ywmxgUlMcjO9SXybe0SH#p|?wq|;Ll)9lt;ljn2w;&`&( z?Yt^GFOo)igM!RNk6ak4RE;?|zVwbie-{3BthxM}AB{FHc=T&rnXqS>PKTGg(B@!3CkVC^+lmll(mpehhylyhYf5AMFC`0 z(lyzoZ&+HTT21&l@X+B6q;CEt=khuy!3+#E5c7j2)6SL3D8J>LOdayjZtd`J`^xJv zuQ3{YT=bpN$H^vT!{+?T&`+B5{SRL%} z-J$jJo0<#9Nyf_OpT1%vN~%3dXZF*TpTsw9T{%i|xHh#vO}n|KB{gYLO4^aa$bnu=Twv-lI@8>zT91jGJd?d zh8?0SD(1NRJr~KCu61E4aZWF|9@wM7q44~hpV`Y8kZ&bbszx9KYEft`H6E-7I<(YH zT?StNmG}jgu}jsj%_;R&4Sx?TYxsonNkXl@o(Chmj30h|EY?!2MW{r9{ly6Hq@%c< zx<H7h9CugTVFc9t=rW-Z3#~*IoPk|1kE}e@zGO`|n1FFcbyJp@@J8qmfPt zNkyd@N(+cmGGdHSL{jM*j7GYp28e{@$k8D+x@#~vd%wTuJRYAP&gVSNU$E_m*Y4MS zU)S}#?pDkOy@ENgV_umJ+lGj_O{t%+@Tzd@bBRO3l5!cT3a3m1EV)iKp{poqUb#aO zCN6QskNAR1Z&0hjZ2%PkZdnXKuH<%A$=wLRKZblmULP#O5k~o^oJhHrK5gV0?7P=@ z!?NEOam=fO8LMizroCR;P+wS~+fDJ|swN#uDgv=rsdw+5sQ(ukHs9>Gj+5&LFgmWE z#}M+7@QQ$#k$f1#Agg~$qVnH6T*=IwP3*+a3K=XGN?~EI*_*S=V%tPDQzV5e@uLf2 zK%CqX8N<)1--I;gIl=Hm0HPe2Gkb$1t&x}As-9d0N}`qxth6m@ixk;G#|=;XJ^1UV znHfO-!tPZD+ylvsupc6psVL=;Tmg~Auzu}?q3zGqrcPb7)ZCv=pbns;tX+(l(!s6t zXw#7h6aLtfjS&wM2`Mtk*;=2y^q-62F`U!O;mfOc`!9cjLa=E#OO79+b`H}OfSmYH z64njI&R-IW>qYlo;$3qEk2{|zNo*?Ds}5F_fQ=STd&(|c37_Fpz%C@)!A{&%J@nKB zF<^Mz>jYO0l-3Agc0A!Kl_me$*+NJ1zJ9SLg4eGRT9@nnyRbjBt;SeNn|Ht@4e*ANNTs8K$j`sA=dpsoW6WwWC$T7Li zlON1??6^EOTfHAuIbOs{PslBfVfF7?g$6c#Z+I_|!4&2! zZx4vzzmU10^$?fzKh(bSrr;$u!8_j~%J-+#f6an}?7wY76^!vD_IbO&87_asG z&VE}L!;_7;k*7zpoH5o)SfLvE!@Jc&0)ipU8c*#zsastedjWe+)O16wk5K<5CPYBu-Z1}f)ar7U=EnWCBVgoT z5e=V6mDd*PvOiY$-W3jaU~$-N1PLD@R$E>!w)F1vQ5t zUxxFP!#-ao9TJzBY{t4)aeemN#^g_K?B#!)rk~KTV)cs;f83kbBgAu1G1e=3)Le?S z=ujw2`Po%8+(MInC6)_1FDb4!znJgs>n<-h>q#6ffRKsyb4hOIPF#Ra22EIoh@$@dsd<>fKp-7V2MvO#y7 znQlaEsIj$)xcfa3xs#chX{BfOP}DMlIuMNy^xLPARXPA5TdoPa%mp*V*~d;A7e6j7 zpFyUZiYN8r`Dg8X&vsyw_UNL=2<>+8AATMAS9R=kC#5`xlecJX8a`4FN5jR+Aa}@s zo}k&gSOQ;{^sRXIjYZ$KSlCRnr@u!^2wM)@v*k>tsa0np-YE5Ry=GgPS@4>(&~_ zeiYz1+Ivte>(mUdHxo(iLrwA_89PP>W+29;iX+o(9@FVno@~tmo9{% zK|YY*VA2zK6q}?2sQN@KH)@~TjYfQ7O&|XARO(dhB#=lO>I%DtZqpVUox;z!ruP$f z<)pp`a{h6dz}pE8!tjL9mWIiIUROv7AW%(X(L~x5k6FdNoS;e2fgJfpb%oS`SYGI6kk2Y~j6T#Plb(a|nUrWh zciHO3ay4Z%DUR-MtiAuijs$Ne$+sv!zA}>c0rBNKs*pT|5=Jp8@$mQA3SPE$9`{y7 z;-7r4x|H=R=I|drzt@614fX7L)(m<&9y2888a32ccAdc_Z8zn0#ygqb--x z5X+Qo-(@lBizlYCZ(PQajFx?haZNWDW+C+0eU~gOUC2(DgfoBY{ZD<@?)`*ABY>xtjYe#doyZwfkn?w1f{9J!I{Iie=&4e!k=jtuRzMTKo z5Jbpm-JKNEcFWzS^4(sNA=#)QC0abhWd*wbXf{9GA7$UN2 zC>M&BH)%Oz=oPFvKl6Dy6*pIUO9d={AmEgUvvXC${YHbL!3;qeERphInMgbp*LQPFy5ALW&I6#Lx>HK`vYSf>paC&|u@X;Z}N%8W=;bw#x)!;_fOkmDvbn%4U`*tk?VDCdMR$XC8NL z^vz(fd=FeUL-SLnv)sR}Bvg|G*~!(ba|?)nXwAAJ(LTxU-gteoGtMB(*T(muaE6;l z+id(9QMMF`W~JhAd9ee19Qd9NedY@ARAMnf2wA`9O&HTsqGxcCrKLoAHxXAR1 zTxHsPDWzgXM(o;x+&}{m&-Ih#mo?`?6_-QXlc0Q{!z8mM;scr0y$sJTwEZ*W6UyV% zk@`WMi=yQ^H+Vd{%VB8u>0(WfHMq#Xw2W;JNvP`2PV|frfsL?SN{(O@>iS_*Tl(M~ zeWYUVe3+;HQ03Ve^^ORciHkosC@^BC=-^Z4@wCUd%lN#{<|@1=!LBIy_$c{844ht+ zgU4P~i(MzrBgwXB@}u}%v0)x@CbVQLD&aTIZn@H8Zm!m=aaaxW>f=WjK?>e2fDeF7 z>9$0wCrmMquMEI1Y{n+&gdf1XUAJd@a*B8GW>7Qz$pVO`3zq4H?OcKiDI`eYcPNI@ zfp_?e#aV_tRfapOXzM?S-y-cDY2|o6@Ns_eY&S^(&0VI<{rPLcJofJtfQD%2f%-+! zt99Mxu)9c-tv>YoLIs_&FXx4=(j#p3imo<{S{l+S``kH?Jro)&<>FZuxNoL^#q}ns zLgtAr8@=S;>>zoZ^5w6rBct zKREj%>G0Q@wyoloRL}Cd;%0F4Q3cHN<>1>SP_LQ4W5z`{rL;Lj=%D!fF+%_A@{s+w zDre4@wAh}xc@sW%t(af-EEys+tI_pKhpwlg>u0Wa6@2<^+*CkS? z6(nkuw*~*(0LB||C>3D1U_XA}3QpvHa(>^%D}l2_HFKZaABng=<7lgN#Gb6thaj6j zo*tB4>~=S<1zIfqzi{LJkE-ZBB3IrdGDU>^ZDWYJNFoYn{tVyZa4#~X{uNgyB~#Fl zMzY+C)tfL4Q`p|-4->PL`?^oH8WbY($f$BSkM1CXD}Q+N1$5^tvC;B{NES$ILC#6$ z=`yt>R_@vCt1rR5O)o7;LUtHMhmIf=RR+B@LX8>n4!PSIH$CpBXkK>WK zKW!7C3H$3;y1awA7Y`YuKZrufn;4SU=gedCd_QW__=0b6g9ZStKXkV$P*?XM7K3`{ zEMp9K;XIE@3^JqR+@1*d z8iF*7yj7U%B_IIKC{DoF^}(hA^Iz8pW+ly)dlHIJn%487zg2tn8Ht?W3vWHX{_uyE zGKVVbmP&nyJs}wCd+2=2aYdc}Tv?)z{$VBSulI6*`+QL{gR1+Ki=pa+2M56!4E_m; zH}m&22~}x){v1<9X>^VAb;Nw?@q)vb4wFp4T3`%5uSOwlIH{nHp74oboXE`{c+G zYN6XQ=c~Ow1)`5r-0Jtfn*a;VxOn<}d#xg(eydv>op+$wu$MXD!^i8JWw`4uAGJ3E_SeD()qbmWW@Ze)5rYr4nKnd>jkSAy&2 zeJ++0TfECkjd0Jggkjit*g30N=acF$-EW$bq|{1lc2}y5-a|>VTyG9~g;t-%R=RGw z`aPYy3tuCIQ?7I&%RQqF=6XYGEk^06FUK*E8Q*4zb}oL|`YQs|R;^vnl$c)8f|#4g zgN*80EG-FdS|k(7n_^zwMyL|Ks60-7d>>uOtawBXzWw~CJ9s9>E1y_;+uikF+3h1! zzV{xQ4qW2L=MB>f$wJRJE#bER9&eIv6wPE*Gex}Waz~fPT?P~1lHwMRdK_;1CXXD) ze`&yKT%)4{6PQ#MBaTdbsF`K&Xs3N zs~3d#KPDVI)|sEUfPiyo!lrwqW9KVCgte}Hn`qF`swiv&I8P-*{Gwc@RtcE~IL;YR zx6tYN0r19y4__}~Xw9y9@M!-gg9XNE{JYn>!?kD7<|TIh;^A>}mrnC)gA4M2om?3R z=f>of*(;^NhLgX@aS7Zf+!$7J1#eL0)Fxgc7Je}q+yCUuJE`*LKRk7n^!2Ppdu#BH zm`I9GR}u<7z5g-bQ7du{597maVv{f3?h<)^7tkA6s%kh zunNG(W*{#YLKXQiyC5RAWo6V>sp+go-XI_gteif2N0EU%xxsR;8S&18eC8`M?d|p) z|6YQ8yv*@Q_1o5|2*o9Bvf_T~q3+*`X*B&|n7vM3+&4Jx%M~V*62EBFgHz+M#l>jJ zR(?ff0z?TL5Of8lUUCM|!{x;FA^k0<6nlw~6lJ)r2oZe1pkun1HnxeTjK9?suz z*In$rvzNLuk|-(~c7OukyqbXQrOL^)gJt*cohTRi=U^CC^l2dXYaO%QbRDx>npUrH zS^?+7c1oc8ha}C$BRKLBx4+p^E*P2U)&1v^g));+6C5f-lYj80Opm*Pz2WqVYH|~P zBRgLosImrI*-JiA<&B;mHbIMzCQGGn_GR~0Fle_g828?TdOLv{2E0Zj2ldxL?%h6~ z+!AHmC-xa!aQsL{sj>AnpA!U2(z!cLETR4@)pFjC{}&E*;IcJee5y1jM=@HsyJfvW zz43OcrVcxTCPf_&&+7aq>GA3R8!G+~W(5|M;3)1&^xaN=$e* zTQE5Ccjb-sI}-*Wn!=PHQ}FZZ6ZstDO;sO;&fY>ctJ-sv<6+NXZ^$xju?oC<1?2#g z@Mid{x?O$SShPtSvXvS6CC}tIP{Zbqm8}z{8+FcV(S0!HBzW*AKYE#d9lxx$*%&!u zCZowlprO*0_q2eXB$N#2I-;EDyA<}-fhbDZCIgepIGvBdu&az*l7M4U(_hC)s$kyL zKp|N?o)?fO>;YZ57eCdkV&r~ZK|v-}s(GrgX2J`OIndnwEF z-hpx(fVI8WB%@Rg8FH#w_dAo-8nn*E^=;wzt9!JgH?JIF$iIr-2*Evpjg7(JLrM?{ z(?D-BWi%VrZ2opy+9k1AO{N~~bHD0P280IB`Nkyb4U#a54Cd%%b}6r!&-OAewS-=m^QMlbm8m!5to*6W{xSl zUbnxF{~&ab*!>q2Y$W3Ap4E~!uEASIX7weqhc#WnHui-5726cZH>7{p}(>x5^^9!3OG1W;5 zI2p}AQoaGAOKbXDLW<*KOAS}L-)Z>yM1f!Ub12!SKN=il5bN3(TUfJSyv?=hdEIwv zCCoE5t#B(t_NGUz+E4Bap|J!FQ?K@XtoRkZGuH}E)bF!NiL2K)#8Z8O=m71mR9tYM z^h(#ToEFcQz?!d#cXy4-n5H?6N-Uu{d7w^V8-3hs-J;-3 zx|VDuhZFrZd%5y0>2BPIgb_Rpb}i1!;dYBjQFiAz7X4)oo3~$n?`jtkAnY}?d_))u z(who%S=AtN3aytCNvEzBgAePb*k(RG0lsKw&U@$3gP!?l)3O5>-SJJ>5WOUtdo$@g z9NA*C-+PFB9(>i`h-*eP)c`H>lRhFepoA%FoF~g0^R?b@FOU9?&qmK8E~1F)_a%^h zE!?P{6KGco(ainAyxD6`^=jW{_6OT$FwBhAt;LMYA;i2i43B=G;ibgK!nWgzTtVhe zZQ}d+*3j8+m+jCPiizfW_mQ2B4@(obMU|MVIUC86K!U(zG}0l9#h0I%r6WYYVrxR@}io z2X)A}f?{;Q8@kgu*JsW9UjoaF@9i2r2(bQpL{0N9mS}5n4fdR6PMPb?ogbGq(p>W! zIS#`Fk=IqCm=`qWte}QK@3`o{nO6oastqPl9%A4Fb=w~IqS%#5COm7wrvVZ*-?NyB z{HphB!rN-C^@tDTt$)pY`Ps&_Syz5a9WU>*SSjm~t>(PtR&qczBC>$nDwOgK6$&P? zIOU`^x4jn>>&{g&F;jVp_FTE1!+n>vFj(bWjsE~qfa8UolAk^x0O(w{_z`5%Ja>de z7NAP42$a0?oyM>Y9q1YHkMoSS`_}Sw?(vZY z5V;4Wig1aDJXHH2e@Na86tiYjvO9Wkd6chMvhQ_ybkjXh5;>bGuteu@t5uZ$(7IR)J^#cTAx)We%lSy zD-9d#L1#niUdk(Fa93NU%y_dqsNUk+r*-sbF|ov*vAw6(l==L)J|Cz|3|NMaWL=z} z^=Q^R^}mTakv5*o8#aj6>k9I(b#a%6!ElD_=`90>hMSv-jb9qXGLjXmkE|hFl?jt< zH~I|kLk<2@rt!)NEPvOKduhwNplFE?-1U~9H=8rB)ureY>9IVtVQs#wje znViK>f)GZ+laD{^#ii~pk}6ARIdN)|yl_;aQ=*#!gaF`jj?2gb3M7JCYhv&c5zuWaS$@Ume4{coZ;F)lkC@($8(hndDQK_6OzsKnuE_ zv`2;=`vr;+`)8qFgXd|2WR}MV8;ndpWZAE!jk+m<4i8nxTV2m7EdII%Vz#fnIK`cs zNJp`Irg>k92@^zX5ts_5i(U!}p3g;q zte&hNZQ5THZ0Q+BOdK|NZdg8IVCN+xxB3ctJ72X%N>+0Q0*k^SpeVznc)h)?1w1OG zwyD}}w4hNC18T_o>=cQ`Xza9>vjT{WkEB2LWO~6A9v1u$q|{FQCU+o!N7DP#j3|h^ zsVhZU=kX&*SZT(}gY17YWzYwlAnS0sxhL3h%cmXh4sYgK&%ZA1T>mZ^$8vli-0LHK zTx1}QFt&KV8EAeSE4lRgr`bbW%O5AMf?5@?}wnRS<&l zt1YvT8f4A%n^8ehJy>q<=Dc#91!!M&8%D}yhUirGiQ%(<$+WPKSnz&R4=*N6NB@Y% zSBY=}J>HhRTsy8TqZ8~(tok52`ioBDNy+Xb?BU5Pqj3fHdMs~R zU*ArzH$!MtF3FO5NE8$x+!|c*64Jww94n~IR`C2}!D6;6>~Je_s~6St8AbN;+AqeE ze6NwNIgx!FiB#;iO@*byww{Wf|J_K!1-3*TxPT&3oT6Y9|j ziM=1y1m8krWf*=^@sjoF4()*oXAB9dD-w;lg}5)(`V*_UQ`f@_#OHud*%9eOs|P>3 ztdG5Ro#LdWPbxdvB7a2#c5X1pETk>>g1(O{;c7D~oB`tQ?i`T!pYiCBSh|Ytb8}7> zQ)~O4{YLEe{KZIsh0CYyrT^@3E=Vx| zpjx1V7?;5ZrdFlHYDV%D-~jh~m{Juvb-fYi$YGvmnI-qU(e6HxSD#>~2N|)Rw%6W$ z@;TePzqvDqTvA8A~f{t}X)wZRvb}q$rX37%*7t@=nq4Oe-6- z@I2r!x_7A7Lh0`D(NH2@mt$LMQwm#8k#^l@vR2aMY)vPOC9i9sUwD%Qa{?DO*)`+^bH%AG9U;L5C%X=-!$ctsoqnzKdOEVQNoATsj9$%4UhFL~PFG-VXkI|wj&~lyfbca=~$i9*8&iMmXuy+=lTrva^0sQFx zLju;?IZy?@#&z*3_At+{Q$p9+tZbdFgg%Ih`&h}MTS0q)<6q@S@R@8f(ny>tMq`iM zfv%gg#Y&)wJl!zw`YBREeh?DAK2N-A!5)_wCRA2@mN`-pk|Qd9WM?n1lI||+#~SH` z0&XR(l#kN--=hwst)Yp>0e9duloP;5`Fv5MIWk~s4U zmwl~Xq_mM`b_nHt!wK4$F^D_ zLw0U>c)sGkekR@IADD%KI%rF{y9=Jvlj3L@7uvuU?eTQ}-Q{4PAjdm-2err(4yuyG9Xou(byQQT{OxS?$n+T0p?B9$|J+{)wcE~9AyFMoKhIRRVGy1 zMgzdS9kCK@B$i<>_9kN@te-dXh~JETU7*`#~yY5f-@f1$eD(PHOjs z34mf;!o*gk3HJw^fEV7^$DhZLB#<~Tavi~1B@0Q0291r=}s z-oXH!e4uR(M^d!hT?)*|n;c-l@!_&TR@o8%KT6#{`{3?+A?%8Cs`Gc3HyHg1Cyu%6|R15aPLi$#cJGIIO0#Tum6jG zo|aAW3iV&3m=mQxN~rd0r}wU%iB%4g4CulAMTX(68((;y{=q9W*T$u z5e7trXe?Jhvp_7LoHGKL&dPikpi@%wZaXC9+OsbAoOV1&%)h+)i_?;nZoWI$X=4`6 zy!dh^>s4_S5>QE1eGBnUf`OIm?)USjV8jOiN-I@E)bI(q#hjAiN*Lm`s|aWCHnViL zSng2oJbDaSE(J!e*>c}Pj^~@|ID;yOU?$g;bW*gmh}WsS>AWKLywU2=>3!{soYVDE z`}Zw!N=MH^Aodb`?*tO?h#J|r&SJ=gkNBi3&cQd|^Bt&4KJro(x{CM8*n(&8{_8E# zIg^U+*qPEVWK#%vfGXop-*uvCay=*_Y$&Z^;_qQV{?8sFRPa(@odx@jWUQrcK_mKL z`K3onyLsN=R!g2!OP{}0cZ$+OLMkPCOL#23Vpm1VW4WQu+z4g2ErMNTM4_Zq#3+xm zXFoiES{Eu13wx~MKW=lc`1I3u7TdNZycx3~{wU$wpsKD4$j=Npvt19pyPmn7i{76u zDh3&%&po_ZkL-lVyk*TkMKB(?lAzXYtC=t4yx2^4(fLEA@6B)t{wZD_>MaspP}74l zcIF?p>BT7!Q8#cavpwL=c;bg=>`h^SBE^K;V7DNP&Q5=!{%+hwCNcTHa4&?qJ4}zV z;kl7K7ZtSBxsSt}%~6YLeVv6@rCrfQBAOdRC^P$Zl$TNDQ_(!pfj+#5)|uE|_A~&h5uoeI0xAce)}{C?zAIhK;njeJ5YE^y2Q4lEc>Kc|8dVD-wJ?={P8G z!mV`AKl;_T8|S!IlkFY0J!gxJ*FrA8*5Pne5Tx+qib@{4&f@b^xT7ul6k_wis6%US z%fiVDOVh`F$He!X{By%q9AS_5Ay@UP$=2Wgr*hi1Z#R48o)j^z-D_X%1`&3z{yb*+mUM(&o?{Qk7rBLnT1b(GP5jJ|>QYcJnBb z#?&@ogl1=6Fa6Qkd`9#CumI*HM(x?d@M=hR@ZmwV+=bQj!+vwuE3U|t%MvQ9Nc^yC zA5Railig5%BckfY2C*PK_Lffnw8BU`n4`du^1{WlJi}w)(-r+4s)l$T2>YPK4}}4J z!;J-98>Co15PXYVut6PHb=>0rUDrTyeN>r1Za{+|J$pu0eF3`O1LaaW=~!R_H93I3 zI~c> zKnlLO$8xAE%zZ^{3`E8QaR1Twd=7~I(Lz1OE`^QnYsOBL$3#^mDuM@3tjCxymGk+% z*$cgL%OzrJw(|PV0XSxh8>Oiy=gnuRwgf;&7>*j!x^{L~w&JGjobPUPPdiw8qwsn` zYt(2oyHWJqm#rKv^K9)hi<2!v4C1KCLW;kIv(BN1W)~fzIz_R9JBo#>;7gHR>Wz}? z%zN(=eeQ=gZ3c<#tGOIR+;P9n>bF8Y*PR{h(@QB6EJ`MsO^Z%svKXaQ!1X=R8Z;ku zjfnP%i)A&z5IUzs8P|9F=3C2ssV(3x8SETeG z%RyuZ^>!LXzxnS^5hx#F3U}iT%Cjkv4?3Blote#fkfMAd(|a@b|92X~+wOm)AzBWP z1CqN!6k4@Sxg2^r$M2PK_r2W6Dz`_Xy)w?%usj>cUi;@l9EEv#PzEWgzfoGWAAlbZ z$d?@r925OBzmd!7Fuf%8Z;d!^jql1t2{2H!G9!M#&Wyci#x-B9Gc^1NyhK?I4e3p4 zP73R-#=>)4fJfW26e=L()9kG<-c=^62H(Uck{zw0zAxb=xzp}O()TDo9>*{pZQlAZ z82;4<*F)P?bm_O`jam%e`|L3g_wLO9B%W;11W*V(D-yAuQ_}DHTT0Sn)5JdCv1_1A zdAF35AAnWeHv44t)JYSbHX3Ge?0)caNaTCc4BL z-rn%mIyjo7|!4hJU(u1ig-+#!2DpA>AY$0 zF6eNOrPqg_X*>2HlK|6O0yh1j1?hz-(D?^a^@`jK%A}#P@n^WdNxoPONb7U)U=1M| z{plRgd1YKaD=G6Fd)y(7j~t7|Bk%M*2E;}TX$7_|=z|gS02I)m(y|r>O)A+;J=yy= zn$$ES1DZ&8?C~}y|L~zxThuavi6Q0CQB0EZac_4p>k;m}sZil{@wr~Gr2Y)=IB{HR z?8cV{Iylw;dVEQ7Uh?-rzC-PbnJlLZpU!k`uJPMHUnQZGq< zo26arjt!^0$3&c)Gs!ZC>u)2+N_;;Grq=Mxi}M6KssEff-SD}~^-$qhn@_h_-)%{? zGrO&_-1*Kz=#|!B6Z}Cmc=DyT)Ko=dF!td|Wi4ZJ>8mYm#5T(Xxaoz_rt>px4XTj` zTy^2EtP?zkop`1R?R9#{m0qR2<*S$xR3iV2nxmdyz>w0%cro5ke@7=UCJMdpvehnH zx+u;a&b+(w)R`*|G^Id{qw?=1PdOXl{trOflAmtBy1L1Xt``8ATFcBedk zp?1NFAO@N1U)PoZ5f-!4`!7zwBdnh~;c6!uKrxI7(+oF4V-ExnJWzAsr^QuqS}`es zU)&d0gB^qeat%)?j{gWBTB?@!E;N1a%%scN;~r>J80{z6r9dShgTdnOvIInXO0_i3 zRb9cGnq$4U0e7A&$6lVZhVhwk1VspHzW+czy($YcewIyw4(fRKxGtt%N+BtGD3# zg?PNHpO5{?D~eNv9&jwQ4198QRMo%Fdqk2+R;<1J(m<&ZAP97=oQvt5KT$gKLV1KDV{Jfl#|4doh(MqO+c7(>E$ zWj68dEJc4u`z99NOHjal*i;2&Gf>%@F;nBdWMu$}2k$%P!w7{4aBZe+tENMYvZ7uW z1%qw?ZWcNO^2bpM`W*DWN!z%gh%2XU<+-{^MaMzFFd`nxQSVt<4kvnLyG+n2p2>`l zN?)&R8oLipo;t{bSG~M7jeZ|0U-X6h5ORcaa2kK+qw<$Dz@0Q^t0MUsOG2RO?^;P~ zEH2$v=Hw|$_MHGF0l9+wbgHj+6o^Go#0~BSC`*BF@jO#ebP;9Ir`Sm;Ea=!jNmMTX z{+Un(U!bajcV?V4Z9e;V7&9e>X=ALPGc`>q-OXHCtS>nUWayu%9oLM8Ie zs`F=5sLRknCh~WMU}~A zw;S*y3Wk=enZ9?RQ{JbupL+EjNcFp*@?+5Cjl#J;(t}qm`#f@6Ei0dj|C2HN|36hH z{%6K8U}^9gMt!qgvkjXdvEL;&*z3d4@c6R<55)UMN*1ZmEMiPR^Il=KG&1iNhB|js z?#8k*7eR*lP2f}YE}w#wPNLJ$F&=eO?H)%T*%jcdTlE0g`FWR>)xpDyg3dp?BgV)l zQ}f2_wgQM z74osJ#On3vr@WSk;S3)u>6MOUro~q+gkLlc&K1_;zw?)0PZ0+7W3;=&0}r0}7KS#B z4WoZ4Fyn3yAAqgy<53`X(=xd_{Z{*9Efk5l--k$0S!Y=GQ=?0gT9(XgIXtL0;?tFd z1#Pz~)J0DQmGraL`^K9Gxf=dD@o7m((u`0ch*{PR2-UpLaUjQwjQ4Nv;vX78oyRB}|pB;*9@o8&b8TAnECXsbR#xR%Ny zcjYgHF@~%zqZqyCJHONu3!Sz;nyAO!an;d3c){-4tJAqF^A5 zr(}qMxLcU}#V|h2=nUYk&w$+));x*zTiW>CEA zQlze3J;kM=nhu?i3<9j(otN&$R+m0al?D+LgbVMrt)ZTQ@Bza)3T#Ic{c4SptmtB} zxy_Fkd2?O|10N5_5OHe2!ZiB6LX6_|`JjMGu=)5cr(R7Cxft?R223tM=S5)o*-g{s zEYNd;okjnMT}VQ!|IHS5oIV?R*wWid>Zp&_AHlJq_ih4j zAe&ovo%VXZyx^jK??;)O7V47@CYCR~DW`50Rtm=~g3hSs;yclCVR+0-AG{cPFDS}q zdRbzV9J*Yn2y5FPy_sWFTdN!{hy8W|w7u^#^^JbOy$ggMu(i2am` z;>PEk3MhhNQ`KCoR!jb;F4F&cOs&sL*Z+5cv5@m_bgG`-e}jl>{|zEaDdBuxVt<9+ z>JBOUrO+|DrYGz^TYWJLO zea+u~qoK8JZxjF_lr9*n5Ux9%P5Hk<5&c`ldygOaf4!fK(E>^Eoc zG4eoznDmmc8Ks8r0iS%0%9$R30RqxPPi!|G*ktaMmu_t`gJ4IpcwYWlt$d}^kWBz= z`qQgoRwbjRy49C2oJos+^QRhgrLKgIbRV}7e0)BnY^c42eSaT_k=L^)j|f&Y4;4j~ zzHaS57QTB8yv^nz5#=a=VMgFiIMP{_guo+bRm+(gp(pjZ-%EoZzH)YgSab6}%3dS2 zT>cysy75wuw9oI#%NeZzJL5C$IN{X?(j1bA^WI8V=FbwkGi|LnCP26WC=Y2OK zr-JLpOGrZMszX<%2_G~=uM39qTsF10`>FN&jWbWUPUkW|ThBMtZDV6RkVppUuE+^eH6p1sh z5UeKUI(OspXb9EdD$@#0J94pdDil7eBgal=^i+1(Y)rcrah7jw>bODZYoeQz$k13K z6RYA?+muYt{;Tb5te=SW$ZNvUoyyD*^%hBgQdGrf0&FhZkX>#P>QoYS5%M%6nDEj> z3)HFLM!P5L@nySY@s-1HeJ4z~Q2s~LAy8iCi23#7<|npl(~65Pu^T6YQv!apRJwF7 zlXZ;s6nonbPDOK0O}dIW3m;{?Z14-w82`Nyuw(QK&X;)JXZ-w&(P8%JoBqhW#~eFO z3#1IJzN2j-u5i#d`zJ>3hlRd;w(97oF6$EW0!O7igEOPGF%#zVPiZgkY7qX`gyb?s*`l|7>E|V;e7B=eln6QzA4?o*jQD0M|7=++ok+RN982u52o~ z?h9|Sg;D>mg6k0*0E9SuEFHCdDm>^#D3h}fWj@Tr^HcqZD&@Ht!NU4Hj|r!2;;x8`$$`~0=- zM&LNgyV2FpUD-}>w9cYR8fn||=Bb-=*{%*<54Xtf_GuNS0q7V~Ml!F56!9L2_7=~~ z*n{&%szyw>VGU4*^no}HCk6X<;WUCCXm^W6056jl#6DDbnIIn)cjDr~u2sQe8N~X% z?U#YQV&@OSO(JeaHY~{Gn9>LM((W>ya=GGjecJ?vk|B5D-J0fhk*d942)+AD3OS-l z^gkiRM0VU=O7GtwmOYIAM7NCe;34>|?@$>&Ds7*MQap*pf;N<TckD0#eOVN;zeL3R%f2m``eo>>(UHP5-HRr3K+;4 zn{c)N*bq8lJsiwp-x(_3cHTbmk#1}}oL#RKZv=%sp?{hLvds)fV>pMW?-T50&cDA4 zRpqhL9eAnYNjEtq*lhY1b)gs@F4JdGBvCdBOg|kGw1yEVn`nIlw3n z0`K|_AtXQyDIcx%t>*15S}xK*>7x&KKD`6I5uAd~>a4gX9~sZip!;3d>sFGlHg}7c zM6tW)jf;W*waS$HVBP-rK)nqyPDu9OIHAt}3DnCH{fX|n87>d|58KG|o*Q?FlRh`I^$LhZ|yg`-Q%Klf8N;5X`BCXt~L%;FM$rSpQ;N{4h?|NPo!fg{?BPi`a z9q-mhce7V8QYT&Mx{cIM3iC_Jkdq)THFHV2~R&W><{X!`7V`g21+qK-Hr^0WDLe_50575%j$x0N&F^1^7(Tf27ji!++#l$8-kcU;tFjOKH zRl^5o+_y6AjxluAS@K8Rh;&6^;5ahxmx70@Y*O@bj3R`U#ab^=z03C$h9aNu8%sOz z{y6lV8I(prjrjQo0;ebtKPos6bDfL!^W(UO3)38th=uo&lB(?wiS90HStt+>`4G2W zYLu`i1jX#h&6HYW?q1lyMT+QXvb=j6QQx#h7mB(07Ym4+y=|&Ek)~+FiCiUL%I_hu z?D=Pi*g6Xru_Z_t+)&`Y0rn~+i}*4Lxizl?y+cLFO5_s5TJx$9TeZrM#coe~{%NqK z?+dKSaO-E@NIlh6;zsje6nf_m1hV=mxmEmN-V$6#z2};X+LFC>x$<4n#IiBb&(-bt z??UbjoDnfs!(N8A9xfV`>SoY*BWLuX* z#*JlTUnk~T!%@sm0b?yIzh|ZSL8WGUTGt;-iZ^fJA%ykBDH4*wgTi!A2Yvz%^0Qh3~eFG#+gS>PM~{Zk;2%qWBYLy1xayD@n+}X*eO)MWwrby#todZP#XW;ICynkR|72#q1p8 z5NGMRoZ{LDUbq0WH|X|O_T92n z)mwwk$-lXuAy3OAAOT;n0+2Km6c*XyMOgxn*MUL!F86*r*Tv&rdX;6u2a)uC?>u=E zF}>S({-Q1V$sEjKhq(V6e0)iHS!9t{nk%RTdtOki?`)CPoSO4=&vk8LI->J9Hw%iO zF|xz?ffdU3V1YR%+NR=Tl2ZXxW3ia3Y=<&wea7>31nuHfEA*n2WKf*63m%0l1X+~g z$OH1MPFOP<&~Q3qhOn>CaV~7AzpEwx#L6nK8GLuUC2MYBrzwN?Y$!Wl-8YZe`m@}- zTagE>T+!MVy>@gCPQ(;#maQp^l`Gc%u#D9V*_HV4<+SK=R{v)KXB^*2P=L(cNgO<8 zo{QiygVV=braAgwBOchA;l-rc0In1ITnFR;!nGp{{Qb&)_O=cGN)Od19!&CC!tJS$ zoSm;AZJPP9g6#QEO<%saNU3THf|yl0J>OBCyVx_oPWAq?k_FqQWPuEFulmJ00fXHt zpKA(2!R4mvgHygDmX2e|ON(_U+DmbLI$~t(UG9+-2N(64Mwj^5>9!#Hv(#CJUC{Pc zJG2RWM&OSGaIqr#U4?6AF$BgF?=YLeUGet0EE#2%u}?#CotulMM#}sSlCLW8QMnnY zfmQLmgX5i=IqhD}are(2A=cRYhI0CsiV1m+Ck5k1bL2jXKVVV5eiNuaAv^62 zYn~NfGuI{oJxB!R=XWfr7{yuL_i=bXDss!Bpa7R++(zp&fIcvuht)v%m@gIC;{m+% ztll-cW01%`kE^8Z!YVs={33BcuKX8!t;tixEKnQDR7XTEuJq`bS!ryd#;@sDW7Y6F zMrHo$E1kp1<|s@{8(YHNkCK9~RxVG|&#n@}-Ahc`x9ILxM(9iDB8m+36Q&-rL`x?Hb{lypmOA zv?avfrlC0fgG(*Vaap)(-Tg^gJs}m0^_H`-HcB;*+rdd^JxMP=pZF~1#O?h=v;2O$ z)sWgt*q5E|zx$@34EJ42V69)CPHsuNY8!yS6!|L2-S6+uR59~u=&AfrrP|(e9bun-K8uOyE1Y78DQ7kkYjflEs;*58a@$btifJX$|t8$ zrbEes0yN^+7Lu683^3Z(cT9v@7(1gg>)R$c$0M0uf$~@$m0?wrM|5rCOQJ-4^3K z1QQ`iko+^!_w3ajqXly*w^Nyy4;jKMGqoJy2MfMq+R~q6b2aaF)ls!-mclCH#c*aX z4I8u9u3sK?UORI&oDVipSYEZQhj%->Nw7DV+1<(xbG3&R>;I8eNi59}!{8wJgSJuuCP^@zwyK8|drm2dGry7hMe8GMT za}TZ7{U4UrTK5wZh>z(91Ywp)BI~4o>Bnm?bK^}`C&SSI-Oh>d&4?$PZO>0PS)Z~B zlum;^QuVUH|JJ(Qsmef|YE_*C@Ftm83~ew`1uA}>f~|KujZ4p_Kmh`3TA=W7dM09b zf%D$}IL#IE)RI{*@uq?Q7!(I1%;>=Xj!(sj5B^O_5&GCt^r|#E?ww@Zi$^JOo`&Ds zSJU)nr8dRc&4apdo;7N0b>8wQ;&48jH=LMQdQQp(cw#3_Pw9_FRPl0Fwf~Ofs-Is% zXu3w~{a6T#{W5Xs6@saBhF7JRNN?nVOiM)UCJ$br3lCTxpQmd3?qL5s78hdriy zO#Ajy6^my1KRpgrpuB7z#(43{4J-_w+uX7?j~@8}o!G`K-q>fEC*{%N;A_JS=WMc9@K}E* zH!W5z7+B|r;rhe?LgqSTK%$=)7W|(tg_!9U(S<=Ie-wo+9hl`pPib5txB(jo96^{&tuQ7E?2q^L%g>jG-}u#%Pi7dd5xu@MVbi_V#!SbVtqn zyIyr|f@=5k;PNq`=QHxu3_k@T*NuN{Pg&J8X_RFzwa*n&)+@6R;yv~a0Dft4#_VHx zP#@0fH2#k@`D|N#sdCSXtrOO2X4Ko&Q7*ql^T#&O)2zKU#Rg~1a`!Vgb$zcM-3szF$uY~>P-w~+w9q4U7^zW&NGXFKsbfF< zKFE|zZFA@zSzmwqg<)#@cRi_Ph=4Z8tC)8d9;b~%ksH%Fcb=6zeP4xDZda~4^(P&J zJ;Lw$vD};f8Z4*S@cyq8lJ|c>g6sQ*fcoc%Z+o3bGrkcl6We%gjLWGCILs{@p1SmqMOODI&qdtbN5(L8-_FIFM3*1V+x4qlE zcdfiV>hR8ne0M2Oo8=KWTagm4d|<}}%&pufZe4D=qK*a-TfrYrj=TToIYS2T4E6yO z?(Zdqun90ntE)jbw)cEB;ZTdnzPlbq-*1;g#dN>w1|pXHL%Fg?IF51YKRUR9v^~*L zr`?l%XTGrFgWw-ZPeSnPH&TG3J$&!Bh;_GZ7O{gRs7RjC1Br&e-LmP%Oyk8_=M*YaH9*okNfCN3wdr1B74tYOhZ5;`XHz~o~<=N6Am8*P@Td*>h2 zbjZ|!q}l6iZy@_3t|Uyp(Hl;ePL?mXNhhCC1drLjtXCi24^W-bw6Sa88r@@e zOiwI!kgdT6Q2-^ry+`CWW=hEWe%H2}<0F;2H%QQ3xeP8m-dZ#nmVR1@LqDY_ z*~(DL{xR`vVjha5182W$Brw|z3MC{PLYH))EuW%!p`6Z^uMUPs{Mw7ipi5D7=9&Lst!W!gDa>40 z`|G@cp4(vD%}3d%agnR_M?*@Z9RWW7vJVshW`~dFMRSyiY1n^Ve%yGS_E-;!(IJ>A`H(fxb+ID~ul(4%yZZ4WM?n-4VBG<9XT zD}I7C@txAY`H%M;_7e66A&j_t0%v~;jGVyR9%yq2+AeUmsjL^|!G;*k2I_RZJ-#q`A-_w?YZSgq199UI>YxRK^rU0mYL=dw?B=D<= zVR9L3y(@+KjGXc?Q@365w7wFISX3OKSbVAYu(U68X@1?^^UO6c|lOAldA&9(#} z=kt6i^A^X#{>S8KCdk7Myh6?nMI<}99z5QPA8@=jN9{``C)5UbK@C()M5(c_2qvf; zx6sGGkro2E8KQe+Se!gp{@?H)onY&>oNpYh`WD zG$8Zj-*0+II+H;pg<>a;MY;BpI{$*uIW%20QR@h$8WM zFZ7y2Z(g9>`x$|u#bhX-Rfx~ogWvQwEu{?VxZs!)I`|>GzpeS9E*@iK>U?x24Kc4e z$0jiCa6_MpK1A&f&bn)SeJ%dSS@S#VJ{LM3#>%_j?z*-(8|t9fKAx{mfmW||m9y^6?@!fEu127_bmU7o4Pti~+3nZa=u@q` z-}e-9yev(WJH+H>j%&5%uvp(`m7h5;da&Q=`9-l}ALEg>+fk`1miUfByuMB+I7mOQa`UM!^50rHN~>iYkoI)9yj ziMjo(FL8-$1l0EE`HJORAGA$WnNKcP4-+C>96O1;{6qrgT2t$g2vNPXZ+`|qiJUgC zHO~41H*O)7n`VbTnXlcB`ts^t*S5UtX__xbIu56;8`aA!d)ry#W}uSIYekVG1w(L z6Z%{RbKbteq>3l2w+nxG*JPR(AM3^;s_0|v+s9FZz!ts`*+fEr zzY+ZTSMf{_hbm9DZiQ3cME^k3aS4Yf0`m&s^uy;M`pZWL^r(h+Umx9J1IOdY;x0aJ z8mt$?6&bDsJJv|T-2bg0=RT%3y!a}0wNRHgf9Wy(_FHIc@|OXDY{$PQb17^K{o^Zr z#Ks-JIDA>+gSgXQ)>nBr=Xh}6(AY4Rd@qx|tT#S3-z-{bG9=@wHG5IV(_b+47jDL~ zR4gwO+@S<}b!RX0Bk0WF`8()O#Mzv;UahN%R`Ykuuo&r;CmFRVos(+@TrWdczWIcP z-!i`nG~P2r^YmSOM;U0u$T)|SAEwl;{ouoH+zQ`>O3VeFm{iAg`c|=$BGSxxoV~}O zzub=wxE#G}eTyCI>Kw9pLyUq(>MN=Jig<1XC_je$#9V=W`?MhfFjirsxA{&kBcq;U$0WUgXd}WXNx#V2t9SN}BsRoU`c;B$E zD?Rtr>8Xt0(~MWx_tKET{f&)5Wb=J_(0lgf^jnRt?#s3(57j=#f~4LIsH>dY47>96 zH(|rl1y}2h{)^tfi4OU-xp&XmLowIxR-fBQ7@lsrGETqmhVQ*j=(!{GEyv0OlAY{v zf!jaH!XPPo(BHQ)Ue(gC1WdHL+C@tx%k!qj&dUpplckRy_mmQl@2A^Nmc}g10e(1+ zR%d@L-kBE8Hu7N(0*`NU_X6bS=o@T}N~*3_{}m#=7|)VmFLwd&s7PT*A#K1U-j;&O z`Ri)HiGg4WF!gwFo#W&cdk%$@*&fM9$o%8I;(ZB(1B>n+Ur@zGF=9>Iin4uH8aeyn zKH%U73AtZ4tO62}yXw0h1CYZGg<>w|u;=$=*b*a|j~8u1{7)Du<&IQ95E_dQL)UZN z?|n%+3&(QbAJUGUTf1C=n3b-E?e~rSy*;*EK5NzHNL*nXM;(8BAwi;h#kC5^FN=u4 zkadeDBnC#!#>5d^ra^|puut(CZcq9_5ihYVx=??r@qE)d62&bIFJ&=o0xH{*2Mxed zJUJH%aiM79wSc~!ZlhaUv@`rch;XLTRqz|~%1vK5!L8$|GL`cJ-}=4PXHMejD)BJZ z7}S>-R>1S?3-@~U<~*7g(u@fl-$Hld@%>S`?gT=RtRpg6emD$zRrDZbgb zxNct*zvb<^{*tG;bB0sb9Ph2LT>o``;*I7H`%H5+=dTD(gv+ps2&PWU`RlNY&nnN? z2J))C>Flx1?ATMItR2TUvSRK3jyb!Qe*3fk13m4zV`pbYSQ3%0f6_@o{frH znim}Hlgd79ZbfBp2DLsO)D|n+B5ccL6?|_#f!_R?sW$R?*9o75zc>OY=({d;-fG-4 z`=O=yUb3*z{g30jBE=_t@qkv{zCS&>`*@bqeqpz}I=FC$#EhT)zIZDx@He>GOlEm$ z(*6_K{So>~^nq7w=5ZqW2A{$o;T&|)8$=^VCcPV@EXORBlqFs5PzjUH!hsV9KXwN& zvnz9zm&!4PeB{j8h*>=+6tq^K z;T|u9^(zV(SxBL4NDKG5-lp8*Y`;VRE>-DqDubbaAm2o=WIkorZCGz{?vp$*Jj+~* z81W@s1Kj^pvK#%oULYCl^Y4QMctNRMoO(XhJf&Yr`A${n3YX~mb}nbAZ>S=6;Z5@iUi(st!OT9hjPL?+i_KLx>N_tNYtV@pLuu9ua1`s;Z0w`^LrBObq zy-t@_wU7>VJLFNwT|5AL1*uJxBtL3yjC*Yf0%oyjTZ4V z+VG6uHNEdL?N?V_-uT9aR$g)2aYINTKGF}^b~xV0v~DzpSCfQ3uatSuj|H~NvgH+8 zt#;}&CnFeLiqD=%mO!qwMl;W=E+j}`U6=%@QhqzLv;R@eRo^c4mkG5o=k&hQ-o-Ia z#$1y_a5|kVZObLazIJ8g=q`GX&7I+eM}o!ul=SI1Stt@3DdUlar?l%eb4#`NxxK&h zniZwaxQ8Xlo%KcJn-eXv6^VC`B^Nus1Ooi3tdH?@?x<9ML2Oo7e`I=aSGZC(`=?4f z-Mo|g(U7LxHec;R6(;8HMkLsgrG#Y;DmMuAr{|FU*UZ#h(q>}@D%>{=o*2O!+#r5? zeIOvZEHab`7u|9*4|DmQ+EqtUf@dHeJOmW!|1`4)-J+rpy7E3Drk|N6zr-^o=WR6~ zhQ1o#z^Eu&S097oM4nB7T-^{=%G~*uBJ1gvuZFXW6gpunam|>z%ICD zQp~^{wc+xa^`1|8X*j|K<{=*8vITc=MbO=$8?LTc z?)@UKT69ZqgqMfC(r9Kb5+2Xd=dLFOC~W~h0QWr>WPp-b%c?m^BnG8G?AN@K=dFN*Qd{OONMS9rYT!M3>iu8Qk-MS&Zq$vkIBNc>5ncH(*vpX4V zZ35ZJhl&!DNK>UNX35B^YH#r)k&P>$INp68Bf~bK+0g_=S;=zS@?oQ^gj`s~!GEwj zAO+4d)j|@nbVxTk)XxciFVk2}@*JOugaW0XgLyOlMur^p;Vb$9MA!xFDO4J6;JxQj z-;I=BDPPh|!wky3J__5ma$=G4<*Y&5@{a-1CUHrn%8@6@=#eV5jAp8h z6dm!;N*gNv0HxdM1I zvom*T7u_}az>#Lg8|!B8Y}RG_2+eNwtiRb-Q4Sz9(H+Gbqr{LRuN8My!fl(wyqqNQ z?o?o?O?&)nxvHN2Lp7lWkyA6arm|hn&f*E3=PfIKiw-}~)(>5s&?eaqkps4kx6omB zuhO%Be#9jLVme}VZwm!x>DWUD`LT!o+`M~;kp zq%7KZvMaH^W7JlQtbcG~^hG8PW@y!hU=xT~)FAnN zWJ&VLF&}K`;E98jNRCY>3(P@m7rXV={zxGgo^g!Rr^wa9?7)EU*Y+^k3w3uAxZ zVf%5c!mweS8p2g9Ryb(@I$EK+!MMBYbSlu)uOFB#_mO0_q^ELI7YFwx=Q$kafzMaIf zaxq9aYz*r5z3sQekhB<%CJ4H--dU`Ec_rS^<{}#j*2SsuDSie&YoD#%stGE{Y3HQr zkl|)uqK7vkiX2wG9cNYF?{^Jk_O>q~+e`|Q64cHczoUeGMv5SRf?jD^{dsI|!>|3= z5Fq(zGwz@(3{z^cI+Sh%wN>WEBj!8_Y5V#xg!OrtKVKRGamYh;cEI_V`q*w?gX9G?rAvE%GrN!;DV+k;xKSLVf?=83$Cmy_o+j7u~@ zId&a$Gyv8$mg)E@mrm}IUD%iq9xaenfn`lnP7#kBNK?3y_c^XqF~`d&!v3{oC%hv{ zV*0ntW1&ShV$uWQ^UcPlA#=oi(`NN)GGr3%P`Nb6|9-l$`?Gf;%PRBe_}h+Ia>Pah zQ9c=rsq8Gfe8dOqVg~q;9SbHxuqbB;`<#MJ?ydctLE8>m0wA$h6p?VKAx*J2EG+gh z9{nnoMy{JS*a~P;o7A4VV)kap=rG4tzpjsXmVAC8Vab< z0I@|Gxg%HiI2&_ zOujY2Cp}Oki-jFvMh1TD8XH@nDWa@P&PG-tnOZAnLS6} zH+gu-nPypY?8@`z+7F(_H&#K(iudg)Qq`#(W_p?@&DH^CtP%cJ6yJGf|K2Uqn&Dr* z-gL`xVECNjbb1^R{hBmczQcBA=5wxYav-i5Jz#dffO&FjQxDiBkW4P!xn zy9wj@!{UkX`4hg;piKo$pN8umfxq3r;ZveyTNU|fh!L}-)2gN-tNvo#i^^YCdc_NjxF3vul zyuLYie)%G59DBat@#JwTpFPYUkfqJ;?;A;1vYf{O(%y=Su-mkLl(g|z6d*GEAuZIB zn3Z1h@2mb57Oqh1ZxiZ}I z&jFtr#up#^0W|-03CZ!?M#jZHL{T^mMu>r|ve#65btEvnt9}n8U}a}!?YP1OfxJ-stxKLMMKu^>JS3rt!;KHvh z&NLTO+hhE0qGQUt!ES8dQ)eZ%YJCSCyvvbZPmT7`#CmEkjJt<#U`uO&7KcLF-6UH~ zd+@}rsE6R}mzMF(5)asvryu}6uaS2{Q1n;rHnnr9YhRP~y;_xY;8dSdlcmZjAQu^C zcUsR&*IQ740jTq6jf|MR$+dIP9=9~pjxecK+!Nw~vT1=(fCDD(Zf?g>gxz;S>T>R0 zt=14vRdE%T0QSf>am~LdILlRH-DwoWoYT3 zliFyQKtfZHniUJSDd_@6bGV#cEM*E_uu0fHUH>-P;3fiVoj7F`Pt;n zbI-rvU520mr~U648U@n!RHXw@v9ry=s(1J^O@pUzIV_%Iq8d5>o@M6P3yALR86ySU zXOY|Le>2Uh#RFb_`CS1Hj9rRuoqHrLz*F`;MlC3mLgv!2BszK41qMnK44!Zh)Sj(M zH;I%YT8OuFVJ67Nwm`{jz@MWQJ73=9<)CKasaJ>an4ch-n2M$k=4WbbqmA6CDRT4- zg>U#CBDumt|3HNC#T&#(KCE>L^q2U4L*&l|@`X_6L8q&}@5 z>A!vkH%@%a?(r*ta$+?sQ-64+5Nwx?6PvMw=i;@gD&e-2hW(rSeT0B_c zwMu4e7V7L(hgNUmzJcet;>Y6n*?#|Fr_@2(pW8Su_>tzvQ@>Pmu}-Hbg0A&L5Is;#0uTPRLna^Sqp0TsZ>m-bLP~zDrPj z2Kmt=TL`Ej`S%o;6$fUU9~EF^D*VcLbH3?&MElLl2Qn9s0vL{`j-xtp>E=rGDH8gv zx*NQw)P#}SmAb(3{&Ia3^M>)kQO<;tc5+!rE^qUhymcyJRwX*Nr9*YH zh5Zp*4MWv_&52ZLIfZ8ARg#ls^(7Ksk8>*?nj&-N9c#d6OSzH&cf4aPPNCA8DI*Y9 z4{F!njakU?yis(kI#+5O*mw7>Ich)#(hG;+OV+1x~kfL4m zC2ZJ4Rp!1m>PMta2nha!8V(JK*ma_o3?ZKow2(z|-^VHq#CV_*Voo~Zxmq!esmJVl zDeaaC`ch7?vA#w1Wk<^Ng`MCO9_W?7AfRW-x2_xatG4W_C+hBav9RH!3~C8 zT~ePxwIQ|gvFO7)-RDoq`Gi>A0qG6v*nK}AuD6t6Dc<8i)I7cwm6W%pG#O;q`wZu7 zC}LB>^hwlR%SzM5>8RGOYS2#NTsGvFRM{S$M85Suee|qn$|~Y7v{$V&g=buX|_H7wOZ+SGr*i;yX~j6ygI-m&L*DUY+CUr8*x z4tqPabuMo%uAI%Ylpy(;$N7CVBV?nlDP{F@e)jt6BX*jvu&(Ec0kU&o$r{&Mn^nx7 zkLXe7)gf~0AxamXxO||8CNpOZ(yys(d{CgKtDFB62=)I}p#Oi>S@fcovy-@5z1sr0 zcAk9?W*ay5$pHtf+?yq(?9p=^?U5L zlBDwwfV=|o>(t1xW%94DD1>eXO?rc6^0|$ANjrvu}OwfKN1RIs0H1ZJ4Rm0k1X0i8X(c_@Y)x5C1jq}vK zIe8+7ZMDN5J4?v%1S@<6KqqS(UBfJ`w2&WxCRBf>0bB0*-D@}9&$JlY_hW~c9nBqv z2B_~euo*_bY-0jj;>o7KV zI6;kf$h%v1U8MHNMkK*EcaoOu18v&aDcTkVrYp9rYJhq2fa;Iib~kj2$PcZy4-|t8 zt%0Vs#`L*I+z>dQUM^d3?{P_7f;GRmtNStsMcWP`WFmt+t*OUSDJz7%?d5I@haJOX z%TgK5JyMyf=E7NxNk84s8^54LJON=>T$hkbOAIL=aP-}y{R+eF);TPaVWZq&KRk=e z@6ds4k-O*trkcdaYQY>w;^bRqES?K`WNq4BHZy_gRxrDS#&S}{Dv#te9r@L(vOslE zUC>e@(XqQ{yWef$opf@C)lszd;`}68()A)MGrDtpfiN_MnE{S{6Oc|jLi_5FQadW< z(i$so@+HIYuUtCwK4AloHoZ#p%B=w4ifV-L(D8zuvQouAh^hU1Y|>tcK^m&9895xi z{aX~jjaKK$;asa$4@kUnT47$W1fz98sT40H^qm)#xTj^iEKIiACFFN4fA*rx(>ydw zR~o{l>}-o=ysv*o8k*C3~#3pGdCg-~D zE+R9ThzEw{p2#WS5hsY!RqTH3Jz1eUTSkw4=0vML5;38j-4~5RubryqjAHBGG&CJB zb5E7nBGyd(cuacmLvu%h~Sy=LS;;4${+L3@$i0 zv>xZmW5a+>-y%TbkK!Zt8ESj1x3YAPq_~1-yxU|e)Sh0#SEKF(fB<>+Qiwbuh==YhR zJAbpns&n2lj(qhv0YfNxK%Q++MXD65mvyu}C#|#iH4rwe)IAXm7P0tx#Zz((i;M&4 z<|F)1s-2a?t-pN~6{raY$FYV;CDh83p|)u;&;DWWck3(3Z2sTBAbyiJV}q+4#tYSRVW`qhGjNc12kWcG0jBeyzEn4oAc3M}Y7L2?`^!rlnuuWo` zq)JluI%*e<&L(N^IM=#Re+gtI?8(z-Rdyeq``D;p-_HPJve~2N#}hL&wE`dA^4CS} z&iL)skDlk5%LdY49&=uaUoV5uW0u`;yhuQ9YtUbr@Y*LeS|?#4J}Z86PHly?ZR(<`zPUG7e{<8_7cvT z0=+JaAImpEP=ZG(+(HElKS%0T%H~-z;TomT0SRl10(CgI4No#q%oQN~{ilfB=Y!Dw z*X4A#b-;L;pZPraTGqko=V4f+4F(sw;3WAc62UZ73b@IrN+Ungsra7T5O*kGocs^= z;*j?WaS=mD%Yy7869H@Z()6?-u=d27@QKNkk$J%@j}NYi9Odgi_V0x)<-gN8;t_u* z)o}tnR$e@na1%c}78b|K69fUiy`tcn`4BK4-z|@lIl%$X@ISSxBGB+TRt(Q9E_aXG zzt+b5S^O|^?cTqzGwmyW`qt8;YB~?tSk!R-d&Gs=Lj!4I?!`S0ZK-*3kk(%ZPuzsa zed>`^i_=3(p5kyDH8ai);oS;U`KAW7j*Wz65gKGUdT)IvyQ;lxzCtuTyUbn+GI*Cy zKBvk%_YKgCjq_~eR9sxbMq}T+K@hxn`$c%?CKfV~pJf-2z>X3r@!%F&%mqerw|*PH ziw|tj@3yA<-o{{LI$z^-|FR&N(>qQrn0bl{g)i|KoB> zwoC2EciwV1Tm=8{LRocuhTJLz%GpJ`Zs^rBjXydFi358#L-}SWea5+NEgoFV#)}sR za^_S~wMilS1sF`A-w@I9qy3MlpBfozPa>qw2p7IgB^aeU^W%SIo|Yj5d6X`Iny{oM zOhev!7|E_5D_JmBSsNr^KICi-b-$iU);GG+dbhf7$23pl*m^bs!{*T>K-Qnj@FzigN+B5|8nB@C=)gC~@48-aO9%>$quW6mKYN4$NIJz0a?@JQ;-JU;q5Went2+PzOfeQ*f?p zzQ&gIDUEYGskh<{@5YWk?^xM~^LWD;cQaBw#&ya2(>J%D@uQDbBBnk{{0qP@1aMod zfp5G>CVNkPI`2#PR@y%OCsO#Y`=kE12XLP{Z+Y#+tF^fEDsRm1o>XUV7ow|$55bj4 z5RHrw+2)zH9&U2xznaf{!^d+AXaRTte+B$6yTMjYN(pH_0#yo$YFx$tsZO5NoqdqDe*S@v)#*tL|3SpFxmlc2*zk zWohUoslYzt1Li6>AyEe3DO={(V<*@uhx)Yn(6)jtt{!%2pGbaxs?4}do6Goofh0OqO+T@ zBYwnx#n7l;l2?5*=wH6<2q`-_p5teCO`C^RJBR4)mP@D9B01(R>^bd0kc{E;gtg8# zbxBIu1@Bu2)`q>Ml^Jz3tM&DQ?TDfStB_+Fw7$9P{tkU&9YQX9%Qu^0org_7LCIA> z&Ug~zEG*psF(}`&cW5m+8cy~GiaB3%>u z-~G}mdNyRVxy!%JZ<9qXgi zPCtR=*dF}l+i6|WZJEJLqzb@KJda7*u^a)BQTTqq__e<;DwXy!tj%)j--mqT?yn!1 z4mr}eOR~Z;2pa+nP|4X@2_qO%3*K-972+>$Nip$~yCht{d;)ZxL!`=j6O0~T4wLw zXTTv-Gakv@Vedu^u1ftYVF8d@W>O+}$pQaV5{WdzCxnJqL|8YSlIfmNzy0zt`7+KSe$REx$uj6hmS>OaY&<(71EJ#x4dw_fI{KtI(qYSil}wT zt9P@6(Y638&#FSeBnL;_yDfh0l+Nnz$xGgjE#>}K*lR?+ItnA2V`tpx61*^(YIi`M zeMt2nfwnjH%;Ylxu@iERIxGN*T=q^$110!eyZN!gM@KoI#g1H>!M`%#S7)1eGL~eY zer}7)*=?SHo&*;VA2Q>fOBj@(Olei;KeiV0j|)gov|qJsG8vVa<12uztq0fD2n|Q1 zj!F!RHw~{EnZ(7M=3cU)P4@B-WEHMQueVmdlEPwV9LMT}eGGhRT_=>!eb@Jze3Tx6 zz5tblnMGKMjgWEKqHAlON&4W5gMEhO|T)5^@=n{fX2<#5p1pe*_GVIYUY(c8 z%RoAY2UxX)DuMF6jNPy3+d4ajzW9|08|w`>b>KY#cCIVElA8dWngtv*0vLf}?hn_@ zO)YnAG#EU(1ge^h?HXi%`J#iY##OU;$54>@FR*!E^$(|Q>&s0Cb8xTqRCYC3U)<4o z06?IM6G><=wq}N%4aAZ zz`u@1$3P)ye;v7ng(bm;Z$1wi$YajfQNe9`N=|;q7E{h3-F*~X!8C|~G5QTdu?9(hQ@xU@j=d8}wMbd$|&zj-aiFvY;Xq~EH6WQV? zUVJ=`$+i*a%N&n-$LaW8Mws)h{bi4@`E#6IlUtka=JuOqQ6l@E%tFNlD|^I@OeY;% z>sBfWKy%W8=jUbiD1W%UO6Rm0t#{q~6OIHabEWQx6!|wo)q1{vKjfUy(yeVivpY0B zWLjMayxSYM3_|T_1u<~Q*Zb7k(7)&#soSST0xzN|p#>dy2v5`h{N)|dohCc@6m9icCT~SHfd~v4(Xq=s2))Ao8mUmzTcuPy`2i~tL+4@W8BL;RRgTN zvzeAaMU=l|ANceDi-s2SkOMUh3ISx|*Y z&lAfld=64&yN#5kPvVnG%OvV`CPnf~W@N=QUMk@6;Y{u7nV;&87Rp7X?F0Zfp-mM} z^*f{aC#trY8wdf+^D0~e~e0t@_6%$l+_@yD|lFm;JCdTY3ZGu@{@wJiG{KiRqw z0M*}WG}5>F40lu-Bls-sFRC}SpamqBSm#ItrwYXTD&{yVDT9bRBPdic- zC!l~kgj&kJ+ZdxHMK9rWRH;s`f{rxdT1J1Yu-p&Do%ZslMdX=s>agI{)2V7h+9i}6 zk|eY*s5qj(Esu<>NFUd3jiWGo1g@39L_nY+=JQ!K;X6@CX1Dq%(DE?DEzq(2P}*`0acxoBX2vLpIYaP(56b_ zBs*M9Vpep_&bw*~G%8jS|81Nas2kY=Q+mm)M9~VG#&G#9Z!3k6>K(1mN8j{si4CQl zkMz%h)=EvAdMd|KpVDR$F5h>-!3AY*28@zdk_YwbZt4*2oKiA$LLt`j%fcCnYc=Ts z4fKMny2*4?f7*#!F=41nXL?|acAQFV3{Q)uX(pd^O!Y?FJ^!6`XW#3El--$thT)1G zoSFdUqPteRWdo8Qov19VEugM`>}#Y=5S?r^YpW)Dg7ITI8WI zbkhuYRU49*Z$y~Ab!b{s~$_Ez22}!g_}mNvMMV( z%dfitPBkBI9!amiXwt>slx!uA{|{$x8PrzXwf!apmtv(@@uDs65(rkHP@qV0LJJfq zR@@;JD71KScP*~Pg0(==;O&Yb!0Px+7!dv^B9wbr$MSHQ-* zLUpV5gdhAD&Td}=g42~clPxoFhX{NzE=eofZsxYk?}eJ}H%ytP8q~>@a8mE0ZwVj> z)7cYCAtJrwAD$YQ5wJt^=ooLQZ){g1AN`nOAwTGEC(hr#Pis7zd&1_VY={DDME#-U zZx8bS$t3}MJ1p?SZ>H=Rk zg;?9H$nL3mLV))tv{1y^PNY9io^0!qy&Sg*Um?OnW7lj)!@_1ovC%~eYpgC6OAN->o z)^pi`l#2i&qTo-w%=($Kq4|BGq1MO6_Q$^g53Cqk!9550eTBn}Iv1QMj8FL){GI+5 zOrUw7fTZV9rwo8&_BIR!^dC^fX$J7nq9UKeTKir{15;qhvof)u?D2IBqF8^HUjL5J ztFcqWP|4j)(5sC#NwhgDccjxCoe>2cIDXe~q)ex_?VQ!jP|?en z(7ugtuAV90?K#d6Exx%2ns@Zek1H>K+;NflyyRBcNNCNKu}$}Io?cto{Vda~v0cyG zpryYaKGLFQ=ojk86W9CNH|$6%Gk?${_kQv0-D{D$t7NyHW)D(Fgud7Mz+{nXItUlg0sQ#^8 z>a!S}buWzb5L4+t{~|FOdv{0nI@Z~vL3iHXJ*}3$ZhHu7c7?n^{*}K!=wS2^L=FGe zO&Mi}R1Gz|T{OKg;J)C7v~5D()7QQDbaXTawd2Y%*{Mo>?++NZiSd>s=fyhKXq8I1 z2hK!geVY8P9x5@b53z=PQrcVp1-(y=KXRnsVfWS07!ir4_veCd0IgX#nb^zHu%pFY zl`ckmt0WG#F}L+!mO7jdcwrq>Xlm5FO>y<5x0)__ZLsmpfA;V?Q{n*HlN)u#(}tL- zn23FFH94hwzOg%U(xsTa?l+Z{I*j%8$(QE4DEQ+ScDZeMk8fYt;$ioGsFb2Bk9_^J zV_)on>|jUR6#Am2{KXUMvmRe`RwAaMt3ENOP@#4ML4@idk>R&|NL&^z2K)ayWp0n(RLdi z-UcO5e+X8nl9-?^AFO)+J+=`S|5$MRV;KED^gOFI9` zh2WxLj^A(DAFdeCX@8gf-p<1RgP@H}Vy?Z5)O2m1j^bdO-{)tJU!TS|31oxi=a6KH z!$8*g+sQfa0kFl^i^ey-jp2n(Ng4%FlxJEK3i+0lLJIaTBH5LqW5fIuGl=)7f);Fl zKak~uX=3B1ArP|GFF0aLLYJd6sk%{W|+LZBPpQy`RxT4ChIM%o&T>%$Id-Fi3t@&*IE^5*c7+${KK{$$(q zD_yU{K(eswMVY(xDd(1-Y5su+;>!QohqdJ?Gr0ZF&QQsmxukBq+EU!-^E#q&&VZJl zW!A{4^QXV0_UOz55KAi)X0Q5(<7yg7-deeQJhXWL9y3irXuVfJFD%R$A=bGX;stbc z*d)MHX0#AK_%e%bM~U7Y$IkIw)@pDE)ioHfaSFUvCSC~U_1C68=6`J~E9eEkD7bWX^96Gg>?_`fwSa#^gW7`t&o@`Y156^t) ztMMF=zb8=M@QEAd%~yLAC=Dnth<$ctyhA;v3ZxP(CNte&CP>-;KI7%=%yoRW{UPZ< zkSf*P_w!>-XczLNTH5Y=@wSMscoy8Lv?1_nMh&{6lxSH6%?%gdy*8T_W`(kxE~sb1 zj;fO4k6+o6OQ0k=Mm&SLn{k9YX3pk04>oSYh>w|UOHB!~<#`%r9WK#nCC$`Xa}Kw5 zdGj}QjkcrFV=`BRwki3U9+S^3_^eDlR}~dA@coYb%Ron1OXeJU_YJcp=LU`1w_PR3 zjMVnIZ4p$CN2tO#8Lg+<4uXjNx9I$tSeetj{tESN$LULk&hbuH zOg7nbAMD;bZ&E{c_9Ew#+R^Kj50l>%;S5#8gk3)Fs#mt z8sGQ+?RP1y(1mqUW&8{aEa2vSx*qyl1lEnFB8L}7OZyTR{OqFgG+|7TFg2qoOXl6T z>ExmRqnA~<_?i5Rcu$=Fj;yo`s)GJ^)^5Rc6Rdv+EG<2kzWWz5h8fk-!am2+rZyV) zxH7J!|HW&&Vq-TX&XkXyZt6T)Tx59i>Ty~e8`K?@B2QzsnHL0!ZQqmM+L^=mc?Y!?Z(g(WJy=#_EtE&XD{?e)VdH0`PJFE*bvLTD3vEL0%QQ-$y^ zaXs(kNHb*^I!n(Z^nKYlod3E3oiBt64ST+u1{*`1IH&uB4_ftu`{XCTDKY6sJ-{rovBucHY|YfoX;J^wIjC-@wyUa(J{Vgh48jp5@FWa52Kvu$ zk>PxiK5u{t0zat{zdSqr-_S{f{iJxYK%Q?mH^NJWgK?4Hj=qQ2JVtK9pC#m!H)c~~ zo-u8aAl^gxjR~r>rz3S4>#oM~`6kbzg(?G@+F34V)vH2lW@TlVyB6XR3mDHFLaO`> z(#($G4o39T!!(-z?ilmE-zQ7`bO`tM{+mt&sX0{%oWy|t`VP+ec^&G#JAD61?EQHi(D&2x7|Kn=3;%?aA2&>4LxG7fe@uBZt3#YqQzkb23jyUD z4G{}OG{4;ge|I`P8jv;`8RH(1O;bU=p!b1%dRX)8MzTxhyPqZJd+q!W!zsw=59H@uOu6@iNR4dLD&`zC~Ul>@Q>xS0BwB+-5U&MSS-69Cjep|1>#34uSi zdY=S+&#nbGP)i3zDH9DdJKm!v8zj${x72go_U}dep~IkvP2JT}_Yu$)brvtpl;_mm zl-*3Ow&&)a)bA3p{= znUb>$XhA`F1%Wksv;bo?GhFk4pJfa=-cLDVF{WD4V-wbh;2j3J#e5XC{dxX23%Eyy z4l>nLTQW1-S(R@*$6#)Fazuc5K_U^DjP?lP5}Un-MI0k!d>v!>7++uDqr@Qc0XaCW zVT4)Osz103JGW6-Y2tyiKGDEZ1bKDfj`VMOx}7fUJ6TM9q8T!PAg4rj_`O!q?(F~z zJ?$Krq0i?iFM39SK_w?gCW3;|y@#M_f;OADy?5aBB>YU>L{Izl>aX8d5ztwMr5+j5 zCC*P3eDOP=MQgwJsPO#mqcmgpX?4*sC8|@t1xb`yE;93EpgJSpg(2yTuBnf)OG${E z^Zbc!MWuX0=+m_1c7-kCvpM*&R5#9{YJ%0`sb~O80rgGZ>8!OpL0TIpJ0R7omIIq3wLqB2g zwrF{A5w&%wYlYB{!X1k}B@ z8u;JO_7G@1uN@fdzw~V@d={;D<{xfGiHU-@0xJreW1ik(n6u&9`1iGVl!T7vuE;W) zg^4xkXA7TphFV*a^K}Ke($gRn*#EA(ciBs;<(u;1-(y~#17{O>pdGA$JRj;_m5~nv zuiS`GNyfgXUBRJ6{#D#ytUn1OQPm03pEN6thQD{vB^P~$lmmuOpMqVIpQK*vyqa#< z9v=&Y8gUmF0^D_Bl=jTH5ETry3k>C@y>7WV(w~00tb-YlkMGDC{F5c8!zOwr`pa84 zJh}swVkk3Z+c5l_3Hc1`J{8!dgYlTEM{T5M8eM_ENvxi3QPq!QZth&|UTzf&`v8HR zZ}q5>KpplHAFegc^whJZBqqW|H+eV6VXc=(%etjF58LeC2>)#DIEI}~a$bO^O|NPc z2&~ZFc&#s!feX1d?qh}x=nt!8?l5I4WmYQ%+~nO*8QD8NALdy9Xu2x;k3eLTI9>*m zBOB+MadS-(bH#d;f#6kd$tcdxzfVVl^NP|`ftkd?-porBeYYW$&}UVY1a8bf`rGgJ zT{5IyG*B8M4F1RT&%IZZic}mdM0xFEL)tMSp4&onYOH_?QBABgp?~l4#_p}+x0Al$ zao9$6u2ISChmSgP9xIQcBy#J0s~p2l4KQG@+{$KtN~~I@e=Li~rt5em&ZxdRPQ_>C zS^2X_4*B;flIFH~h2P}8Uh_l>;E#cf`|6n$-d5^1iHlPDDuHj9^xuSgOK}|S`MJ#B z4xxeZF31Z?RUsNf8R}HJ8cP{SaQR^F3tD7TtZA$()1v1eWCmzsy0g(dKtj z-#Q1V#6ClDeNuzcaNGZ+v-UTGFYGQ1FL{mpy2>g;BD`INcBq!?SO8<=$t%jYgKDUU_C~`%Umyl$^YRUhC1^rQF-h+ z8~^CfHhom~Mwt`TRz<#l<0y|!0j26RU*J~2?OK@sH(aEG%w)&Sejk1lOQDISt-71H z9jLWg%Mi(PVX%3|rYL1BNiH_DpuAi!oRfIu_oyL{{9oIx@b|rb(*U{UhTSSlUWoPA z-g@?9e=n1{v%hyMhVMiTNtt>(IEuD}i+dTFLEi!Qh)=XJHY?GU|LTV%R)H3nxW~f4 zo6kahV>JK(248N3N$4Cc@wpU0LJ5>R8e$3p04;$eAWh{x|0bDyY@R0G`XSU|&^`ZH z+9hoJ8|&q!;fUv5q4`JY4RY>*^POskqKT$OPB%ZZLjyMZL^|k?$>o2r?J#Twkecw! z^opL=R=I4j8yM*9svzB*ofqXB>A=o9<1nv-Tw#f6&S)AjJf_LckQ!w)g?uerUB1p( zp1nIfdT;=^5J^~oWsxwuTO6O=JQl$5e}?3_fe38HdEO~Uz8d?E*A{uv;E)bO(PC;^ zKorIWme^hY%Sy~XQt3O54U|o;#&(0uK7lp&a)+gsof&T((T>o}Ooz?|FLT{YsDG~P zY+`7}RmchIL6P3nLcnUK7k4~Ksm{asRHStVUq;%!>Xj!^a8LUcUE0Y%WMw-&%({oj z6f(Y}@Qkzx^ES7zqLS0=tKa+UTFcCEp18T~iU9$nu?MVX;3CF*IPUPr@kE%hT_?}o z<~=>Qkj1g3sc?n7|4AWBh=~2dBEvv~!+1*s-5(k?d2q8mujN*1yG6&GxwJuOrOQ=O zBk?uDK*Z8Fa8M$%WlwGWpr5 z@5b|iy>&vq`^qQ4ynKq+a|L<193aCCv4+=mN-MUvJ(ge7USE)USB+jY6Z@sy)Ju$4 z7W{`EB=!HD9`rxXw*ONt5mTQf-=I~*3)Bt1vV-wWv5^jm(+T!(R`YTc6!w{$ik2L#maKHv}R+lTiW8DjQ%9cef~I9u*juwa+y+$JxE!2-)fao>S95iKGOoj=X*>B+d|`u9KD5NWRQRy@U#d zWMltG(4lb2%#U7)no}N4M{%;8zQc)>8o!9fJX7pWV2BWRw}|NhWc)>Y=>HVDw+<6L zeN$5moMp6%7+Dv3yRW`y;lMnXJSCx;ap2h8Em|1g`YGDhz2Fd7+N$x_lwGtycc?-v zkZO5I_V9h5MCDO^z0ADvZ5TB111*|_aH(>6%oZ?~k|kmH#kk)%QGdPl_fvaghOvv3 z!rid@u6j@9cMs=OMRX;i+xe&COX^_Y>~SZr22W3@`{c!5p1XfF&EIUn981;xbm7_0 z_|^;4uaN`itNtfnH4?SbF}hM>#XV}qwT^J6Seed$oT(4V6JnL2$FTLTj zPkOgHm0<2|OVFMmWf$JAQ3dX*?SbIx&G%UGx}9`G{ZJ2u!UygOWZ%ak%?Kw@YlQ7|^a>5|!QKdBYZp!YF_Ipu|7){9#M7-DVIp-yPb z$Qa{~QV2%dTEISODr2HzzZn0PxTB8s<O^c338kU)!YH~Ilz~*Idg@!(4CTsNRkHckU2p!{L>H>j zzDZ*xCrLg3cb{G-x_(OVTtyUyaE|_3IpDM`3`6Y38{J*|L_gl8lvhsAn0OKVI{V|6 ze=Oc?R}}{|fb|lRF&C%_nGAyM0obo~O@xWT5EhuRG!sQOsn=du0~U-Fpy-LfLWH?P z-oOZmq`F>XKv;r^(R??zlgszJET^$5`Me4nG(w7ox7cmBmH-ONE23uRf~*NiHzTTE zB|G!#IG(f5a=p5%%@@Bs7q^^dSO*Reah0wcwm$a1?n{NHjBIR|yww_&)6$HSE?*ne zaPQjgF%GwPuYHbusXMt$>pfUqec`w!8{cKfP-A&Je!uJWYTRsy9@qX0*ZH9C7B?qE zcPn{2ZT!y18P64ETsL$$-H>p0*JV0yyt_|4Vzb3FdX^$(5BTxjHxQ_K=+S<=h@Pe? zg5_6K@e6D123Qr}o8t*UK)+fL@oe98&J{mqJ5(|q?eM+ha_ zfbrI1tLMk z8%X(5FCtJHDfjFQ;15}yc}+hL&{_|G45shcWg)(`?+B816dstF0>Ac*Y{W)uEO{eo zfu|OgEL0tDe@J1}W%6c93WpRnXkR3263fJ{2;rBjwSUiCRv+4SFQSJQZMjL7cx^wW zwStMQuht`-oR?n>a603v zo1no9ZmCb2X8+a=xm21Cw7s^eC7f59U00*0S<^$Sw5`c$)5!CldprTeUqj#R43Cf8 z*LChUYBJ!;vBJ&fPSe{y36*I%=yKAkY_H*t&HvLbWPt3C~9ID<{pp;knPZ-m)raML)r87fQuA>0WV6KKfN`%$dhAWYf8sJ`o*5-KknjPc3t~B+?~Bo`InwPtW*J6lFu*0V_MV%N8e~QVh{Cp8TRnNO zsT(1-nPxyS)6=w4n3;%gm*ONLBwv_F$7tMI5<}Jjpnknr8c&=nT+QzQ;WwAZ1Y4n> zwD9#w6LdI=pPMDTx^_7L?$^$~GLrP-CoJLos|tQ^YCKKp~(MbF^*HZRARah^b1*)d zPs-{0&A2`Oz_*vDw`B z1XTnru(!VwyjX6tC7)VfE1x^b6>(h<7p#|J3g0JCDSc6x`mn3Us13QG45-fvHLrr|wrJZG1bJYEDlSA?iOUM~MXfKp+haW14B!0@)y+DM zH@eJI!0^GV4}=fjnksqXGtFBgK?8nGbJz-;rO$_ego?ttQc#r zmRo!Kgl}CKXS?b3+cU%KHkU1M`9;#3>ZC8wP#(oYB%nD|xO~~^v)6js-QhLk*h|m@ z$`4bZ)IXZqZEWZIS;0%`k5ZM^j&GAN{6~N?EyTMncAX;&<|{ZAl2wM(w}($4nY@WQ;BJ6vE8y{~-PS zUX7M2V4j3iGM8Z%@NGr(cy@)SLv?~$6O%DIPIFYn=qn90Lfce)H$lRBH2R4(kc*T^ z3qNCyzl*`nCiiUFWP>RA^j~$3eD-kOI;PKjv~S5t$;C$yAy8`+2c7My@;RH_euKN^ zhAsnBYnwB#x0&N|wKSO=dHBCs01cV$denYnKj%;I-#Nyql-e`NH(YeKsxLa2&L2%2 zwA=Jkt!+~cv>s!^hO$LA1h8l1A(gTY@g^Eet6cMHM@{DRsDrg29NKFi85kl9sjvej zc=Zca3-xQb-cQO>q$Ux9pameMdmfH|?sful)PAWre z4^X)evf&6_cFKoD;U|%3$MXF_7|aPsB{-eqRNUaHhLC;KPfK^*kINzou7G@mv>uBy z&xaMXv@1@9i)#y=m*c8g{&hy=D(ucj^EeFEg1Wb|e_1yP!02GMJeH_61~Rd~?f zg4z1Ml(~GBI=@Qs^v)%})6mEzo>8N98IiKJ;h4s;pE{5j>zAi)v7^11l@1L{LB7iOpMT&^Dmj)S6v~2ENfr zWA13)wyJUXa)#IcZk@qVUt_0WskNc9|9j8x$K-AE<;r}U_zd2P+{G!uBV?i%#Uns& zUbRsWO?#Xdcj(^x@4d|Sf9TqH{6DpE>wnkA0K0^1M#JbE)QgG@&|o$WLP~Qg2w@J+ z$BenW;)i@#VQLlo@SWuRCyzRtu%?{u1dbR6BhfZJ*S9k0uYcaz^Q7KpKl@If_MutF zs=k*HG9s@Vwz?=p;HQ!fy2%63D-_68EGK-V@75g3o8r~k4_XMifcVUly%Vj9zg8ZX zHjV%Aw$=(tY}x$`P1HT4)GnnI^Td|h4yV)=nN@bB^NP@2_ytkiQ;h23DZ4IZdH3!; zhHuG!|2k!zIA57}NEvfIoBE3Sn5I(nBoBfF{ynMX3nI7`i$sFq=UJJQcpSEb>ZK;b z{_?bEdZ{TpQdx*y+C`3#U2d7w+B4uW3Z{}e;3Rb2h6EiY1OVj}`fKiJ$01K2uP2@9Lj&UGsx+v^t z{EtgHfPGs`QaU(tC`3JINoMTdBrFaqcuU7^Ywdy5Z#0}dFqboHfQeFq33UioPw{%^ z{@g)*WY`TKUnc2B7g)l2$LU zQ?{)1`tD8R{{c)gPK=$p6=Cas0Dfjw+xD**xo}oFrIO1rDHtSdB%Ut>F|tzU=Hl(Y za>kyVDi@!%8Ez90E@<0xAwEeUKl>D*bfA0ki*WoqqJf%sr572r{k9;zce);>?IH+BEVI5SGL~62 zzZ(?$S2Gz0vrH_fjKz5QjeL8Y;T^@(2))~{Y7sBZhf|CF9ey@*9i(%zZ9w8~C+wi7 zx-wR2d+b&0_kCY#A=Zo3Hm3ajp3E(A7k`STAc@wAL@qf7psM5;vc9Hoch5_;Yo=~1 zLzro}D)^0$lFfa*4H&v9f3R<=P+xLIi286q89$`Uf7RNevOlg9Cs{8%we%lVBhtg% z*dYLuQr$AMZ@e3(LWb_Y>D#+QxtWEO>F}d}-+2sKKa!9+>DiK@uanMwQfZAvlZj!W zKv@@!Znq5x^pkff(kW{8PLZNHaPVsEU2@3a^YteJ3$EwiT^YhmTYVjQm~YJ6tQSLE z?TTJs68Do*rz}iJN$=lp2*1Grj1ey7Vn-Jeo>CXTd;AC%Dj5wpjchOx%@rN@9Cg4S zO=!D9@4^&~y3b4hhnkMojw3lvROt7O2utF{!y?Y(NX;5S;_t%>6Q3+y!q&TTvVbI! zDhe|ufB_(qkX`_QVEijV48#@hX|?EnS7qn9!cOCvXx5D>nit(J9yURXz%3pfy@@5L z`aZ5MbN{y}O(Wpi29|h5OF(N!>Du?paw9iOo8dbEGd5sb-+jkXW`}4??%4_tvw$6M z_RCX5^GLog|Fe!l;D;&IHz=xE_Nz4C$eDc-pVCHcJ+AuadgqqYl8ciLEow?M4OKFg zJLRq$t4H^=cLf^Y5lZe$3A@_!75UK5;k(vnt!x^8M3bV!lH~$}+x))-)Rg)cKHLEd zFznng!&LK^7A#RpkOxV3P$q^gM`bpUOKedR#w!!rn zo)`aPXha$<|L99y71{wUo((xC`4`Z)0A)cn_Zx8kYy{%{E*F%Atg`?Qi zO{)hlFgiZRg;3(Her7@yk3p8S?DeD`G}4N1pF#lz`ivRz)`GAKWK<0@*!S5N?mNx= z`|zbGF!zK=2wRUi$eK||I{)#C*k}eiW5q$f`geK*Xfj6ppH(e6K|KJwImi`&0NQ%D z%i-|*OrI;DH7pMr& zn@bjZEZLMJ&*H1`TB@gQ5sc8w(1+R33#g;$%}v-o{IJxP5Y<2mH*ARBSG{PPxkW|9 z$x~O2-pDE6LWT|Xe>IjP1i6!^=|Ou`lD-Or42zRok*g8qp|A+spS1I%{J)oVP ztlxyenGnPkAqdml0FblDuJsq9QSXatj8p-P8{sIZBs0JbvHe)u^9k0jl6T31r5j^v z-%ks;O$8!y3EzoNuL*W!=!kNzZ7Mja-=}K?s|T!2{i|iJyb_HbT74j(iPi>&44*UJ zTc34>dj!jW4X1n|(WC?!DBAv6hFSuf2Jcz|{M$CHlo|fu^(TF9*W9q!iG(4f%5Yu; zKQT2skz;{6vy$Azh<|Zry54m$eQ~_j5eT<@tb%q3v_&A+AFt3mm!uZCRc|qv2hl)7Zxwbo)#pmo&ABSvBWx zlOBA}j!~szD3^G<1}`x<7rNejf|Q!(ssG{j^(}TuNl3hPla2`7ItzJXbyyVn&a#JQ z?-vFcSr3~bDLY9j<-GWaKIG9OuQF`h8Eh4sEpkG< z0`oEHajW#5rK@BOi)!u*d8iEFNi7_K(;9uP1uY&WW;WMokwdW~4MWIAM1^}Fp7+-n zWDR(Ym-2#-Ml)`Tz@(H7jFnt^TnmVzI1{`Vk)KSTyk0g?of%PHwjHxDFB9D2zp0*e zYo92|ZZlbg89;PA>~`Mf3Q%7;y7gAG@HHumv>nZitt z_N?aF&jgL=B-R|gh8}ohzdopfb25LPbLuS0G$# zNZxszbJn3hFjEbA(siT|^b_o{81<0ah&IAXF3R*5me~8oa#n_xkhf6) z4x~6;;;(^_LWr=E%*loqS{(@Nh>yg#Sb$!1LWgM2_v#gDqF9Jbt47X%*FGb&j6czv=qL zF8?8xdcQ*LvA^V!^9ek3@eY!o?khHgR2Prd9N=742X3oeVPuQn=T%OaED-XhS`8TUoX}@FASYfNtVJ3&iRH@ z@9l|~{1m28)tU7!x`OF5lV#zJ@5$OT73C+fm||)L9bXLMGfBJsazcN(WV2Bj>b_(t zIS&dA_wP{d2mNyee#L8(+Itl$CCfg9Yn)c(uoujE&It>QA(eaTj9T${tmr6}aC%cj zk(C7|Ei(1r1$xx|FpaKZJv4K1HV8BsO2o5MZc+?n#jR(!)|~9mqsCYCOwEfY(8CKO zgS{z$tqt?~%H_GSSsC^W^kX(|1~%ma%k&^Tf^=XqV-CQ(p{Y-T-ly#Qacnz;I!~vc zHURv!2j0KVEB5D0^m0ZN0N$JBd0yRj5qQfEhl>C+y{eut9&c~qI8&tQVEUCa=m`b5baiOwB0`yy|HPE~IDDp0VD^fbC1eLTPps4f|~ zj%Pb^si{+^?+F0Zo~RMs7h^3cCwK^3dE)hQWk+Khb%(=SBEoM<8|BhiGWJ|^v^kEJ zwiW91Tx;r9`Y{ySQMvxlwEE`rBqiwH!u_sxWYh8eZgx(#)OaU&=w)W_?(T^(x2801 zur2!6*;vK2-2uN+x9F#EIhJq$bADmvn1}k%L*eyGO<2$D+C|~Z6h-}wwFxU+@5NI> z9cH}IRtxf(w_Zw1-~uk(K{B0AAD-r3Ex%QH; z>MpT`nfHqAGeNt+q-{ML-72;IOB4(bycIcCqL#69 zafW%4E_3fWNM=4f^l6aDgeOVB@4ZFY==Ec@$0yaF&u6`&%G#Q}9fiCBLXgo2!Pb?G zifb;RIGZhMJt}z&GQ4G$)|_=n?funi(4#@;TdLKex%l zr#bZYr1qNZ-D-e$jff)F^ltQB4Q8aOL4@Uom6{nC$zq?QEx85bp&~HQ*GeGBj1^+S zpwwOr#fZPh)yg$3zoh_CHOT*bUnA0A2HgTcBpOf(wlA1{B^r?r5JUu*D zQ8R9Lx{WGr6P|S$uuDBchez1+W1j+;9Te5j7g+!Bp(s~lcEstx`{nzhex-Iy0{$SG z4%a(EI*FGRQbrJ?{+F~Ik&Ltja#eu31_Un{MX@#_b2u>T*v$2itdu8L8tgRSLJy=J ze^yqRWnQAFPj?(xG1+@(9=Y~(YsaMkc#PXtYl)Fy;|R_xsW<^@e2)M}(10sTo>D&< z9u2ilu{RL>7b^Frnq^yYcwnDaH{Of~UdTF9r2q3$?ep(|6?uQfp!09gVln9teiLpH zq4Ax&Q3UtSJsFahSQg?F-|d!N15Owo1YcE{{N5w7TaHssBEt1M=;_v94X|evy79cn z@>IZlfxg}=b?9S{vg-e6$0LU%1}qc8%BZp|GXiB?vaIRzkKLOBqX5`M^sRnKcMti1 zv=dS48@Yc4Dy*sOSLge}O`5i9bWV(ku{HJW`gXwn!&R>gHsED{f2g0WPc{2l{;tQRe8$+q zwA+%UdU&!aZ&I8()}0p4c$0~V61<`kY3y+On=OC>xJ=Xct@0HC+7C6=@SA8owz}#U zd~sZ5k+MGL$-yc7)AAZ$mZt?`je@fN(XM>1dSy-lsrXmgQBH zFPm7I(Oh16kXJI{hsk|j$I7|}9g$UM#1ntSY0WcWBsiL7xlvgTy@ErS5f(#sr5MpN!(pVS}8A6FA? z;X${1Io;OHOgOXpH4-MJihG~9=0-0Z<;RnbGMF5<S7ZE*_Z08^KqH1rSHqR+JtivyjKlyp0cHTX{>Uh54 z_0{c195O|zY;o}KFWh=RbAQT7Sz89X+<6@baUxuM4dW41DVi{nX=-gKN-XqWPwQLy zo#jIzM%4TSw_}AWNUrjBANoMe_|;V6^47}Yh6zfeiGBQ0SPjT};|b>816k$Tq=H_UznA zipclpM^eV^WCb>)ePjZLvG|CQcs3MJo_d#LJmi}I^YL)o%CoMF@V~T*O_%UtpuY4o zYXJ;^PQX<^t*kGzARK;<2rirI7Vi@~S_M9QSf70@35Ih7a}> z{qT}i4*-6_2n+i3e6PMTX&Y1hdW{|GQBUpfxvt4O52SZ0&0A3=b1Eb%OscFGFQD8U zwbJsV%>zn|imv(aJlY}SdqXw`>vMVsZd^QzqXa~7)i>ME^sGjsuc%2p?*>~TGUCGk z!yH?03r^`f7f4nDMCKr$c;&>-6U!5^oPCIE|;O$R#F^7$u{<5&OHP zwlhe_*Y(5I`%ot?)FDv@mEV!OM{f0Hq`&(O3iaEkU}!;4gQDGkjE(?SB{j*Wc4UPt zdU~!C6)=wB=Y8}3$2bG>!;UI?2||DfVb)M`A1n1^p$VWujRtKv7tn$PQE?4C-Gb~wm)7NlTVQBJOYA0y|UD(+Ik_z%YnmB zx#4_RL8f+2%N{vpY+$)g3E<=2SEWZnI&_!rbq9S2@sK)phkSo#P_>^7bSbrT2V};J zTp{qL(@QcoLH<9lg}Z5v@LdsxV$^&7O2nWX13`n9&wfK@3wb(j-)USUdE=SGF@%H(z2=Z#s_-oETD>X?wN0Lfk%=QhMhjn=L6Dd*J=k$!B z%y>j(xEXimV&7RVbN9_No%(-2VHDadq1{DHbE&U#T}bt9i(P3ZTmogtaC7_JNkEB(N!Gru zqgl(*M=;{~{4KJ*NqX2iwZdzK3x=>&Th8tn!G@2-oO)ocFm)(C751sYQ&5^Ki(Sw`mGSiL++A63 zIxiTBX24<6;0}oilcb)|K&&$?9@Z>@a<;?SFC`+bJCjc5q6-Pu2&5MZ)&J#5j&5!# zQTu;<05W6W8E0V*Ntw~lxz8DhCUwSnJcoIv#Q9PK_zsW!FI)PwKWQ>`m_+-{q496* z4eJ5cQhF*WKBjTSjdX_~W4Wg3C$K1m5uYGo?aF1_`ztQjg6JLEz10xu?f=A!Ui#gD(eG4EzWx6~@~POQM;`HIq)J#VNaMToVr zWd4MCWp5igf(Y#TLc(m@80RIxzj0_LGINT;(9`tkTS4{3o=rF#D*wr9%*dUt3in_HCj(TQNISLPLJ zTtiYlkZmNj`fUpGteN z0J1A_?7;tvuD6Pc`g^>;XXpk&S{gx+PU)eQ7F3!+5$Wz8q&p>~TcmO57`kKV?ixUP z=`?_m%Iq}5Z zfX5cVqLz2#N4-Ap#J$2ET!I^yu%DgcH(wwe-~yoU)TK3dIw*dbsC3wzo2>tBGPnT= zoM$shvk9`PL|GP1_C_kOxw??}_qlhVAb=*`}(vxDH{u8ZSmgEa;_#Y7Z* z_4CnsujmiA5q5Tt>?CU0@F+LP#6Iny0}R!Nh1aAF@N zrkt3V)v>=`Jy*aMS5gjvH!(kx#@=ufR$mdeEh~?u|DDH*_T$kgw1wjQB~*xsiKZ2` zcWa2Xw~5AG^l&YcfMaz&O~__`ecYUJ+3y_Owpcm)v$x`6N5oaf?{RgfP~bH)E*}7& zvrKzTV)wbGaTo|s5m_jNZ&UG~3gf1AZrsYLp>K0s-92Y}-HJCH5nSU|3P};96U}m`EZ8Z}oS*m`t;Q z{C*YS`k82O0z+AOU*gki0_5T04b}oMwuoakBqW5yq_z}du^-lXZnTunR3`!j`05|# z;qOb-<0s1MTH=)1_@>xl$yJ>rBYpwQ!|DQld}~wYHj`5K=LsYJG%q6zo*kXxt8q@Q zhc6r>S98gB%BgRfi0aDoBtwTCoA^be@$X2fBfYT(d{=bmKONjlD^Lz){a&jpHh-HF zpMzALXYx;>Hp6{_qUJ#E@1MD0oWW6Fy${T~fTdtNhaK(#j|>&0_E4!;CT zzRmdbv&y)-^r*fta$@8b=>ZrE;_|AkM77)6=xuj&S3co4e3n*E0;*m~y(kkGBDQ*bS715|gAoN#}E)p>X&60QvqkhbDj= zjbsI}jghoN!6NSbx)9QiOJ#DS?aQgDJ%TASG%qhV=c?KqS9xSgraxR7Wz z7QyM+Pga=}`dt=Qd>bhd5K8D35PS&6#mL`zu&2ByLQzCc33RaDD< zkSzTIPJ(4T@%oYcY1%j7mQxmvnn^YfAQggGR@TruR^3}mep&}Ql+at4c)XqHoP#z< zL7jT&L9vjAbl8Y-Kt$)09D_y~7VBSLol{I4NWYF5j{XhAk`X%hGLB`IVR5QT;csDp zRn!{nvsxtJzFWdNSYF*J;v zgQtN8!!G`uA*-%eJ85A{P0Qk*t(p7q5SMm>qO*ZDku?e~2NXC)`wrj(j|eCJORIhN zJm9P$(cF0))r04Q<^E}p4%pqeKY=lTZ*rx~vg!_WVRs+P37;lIy`tTGlWf+4N*3p5 zowA0du=+3CMY5_6p_TU~IfU2cKZ|#&!mumvP6iG?yG_-4<^IpJZg&Ox*H;G2Tidn2 zb6=q$@m^8>cRmHv%?o?Os~e`C@Y5TAeH;%bm~xYhS1~B?Ev69Wa)HzoCrA^+^F6w5 z{J4!GYPq~r-apv;#orYyyk1Lm^C0*~`T(2GLA#8mmHr4Xr0ZRb~icv_P& zdw`nC`_*pc0wQgnz}ndAd5ZtiO%}gMKr=(>a+yKV&e$m>HbAT;Y=m`y*vSX+(Q_!7 z3eF9dG-cQ}wxc;y&iV;7f?n*CjxE*KU3^_cEibTYL_VMp#J+Zj@wYLOjC(@r{&z-< zM%QyMw7fHUwDR~WZf4`|vdJudD1|8`2A-&5Pi@p9A!vtFlUJM*xUvvAD&S9g+jhNr zNWUDw4(JheSk->?w*^Vf^zD$@Sxfok#i)xkAQJ;BpUhk$lX8JnW`jokN;%dnBr>Pk zS(GOd-d5vL-k_O-k!hNMAvTRaKvQ4ea~1YdOF5xU>8}fgYivv;MZ{|8px68_`VVMk77E=@}A2|-^F;ux{*%#!* zkS`DY%HxY1l8Bq1FC=`Sy!zyl_37?>h-5Ow{Ka0GuQB;W!)}Q$FYzkI;vg$gik$$diy-6K;I5Z2u&%pXNeJj?rvq}A(6Bc1xe7{2?=VRB? z9VE##72*r|R9b%ke!J;0f`$|CG%lJ#C{qyWp8}#uld;TBIiDDg;nA5O{@f(UI zxKz%|tp$z88Y6nuPqF+6F;r2exi%y5$DRg0`%T(V;C_@hl>qK#$2Ykh4m7FL!` zInl4E8J6%=>6~Ls>97@~<{zk%W)(J#*9g9*9xFmwwmdH9U^_(fk&s z{H3x5$Q(`n(9m!?j5y`HrINJ765f45gzamND^tpeM@1F7PTzMM8~l;dyx`X8sT|-O z8DVU!c#K&egTTaKr%Nvk3vDP<%OLZl1y+LNc6l6Q zF}^VHjrE7RDG)#44^Y#lqXX~){@t%( zmGn!u08ir>V=3lqYe zE$3~rgi%RJcv~3w=#SKrv|s{|#V)nWPAcrd+*kH{Q5g2=hTq6_ns}?h_s{`A_h{G1Yhex7^zeY#2em4OLeW zW<(m!3OfAKKpCYHT!HXb@NnucEw#4X3_IWl1493%R_)(OII>CrDl~%8adT`4ONV0X z4NL7l8efD~acT$IEn57c{}8TaqA6#a2>EJJ>zionL7ep>&r(G&wyGS&?4j0gy`&=M z*KS+WPQ_A`P}}m!nhx6yYp05>RxVjCsU60+Nv^(ThNL0`fPQ=OQz_)Pmv<52zJcTUy? zpb1DX)t;e%yDsmFn6Y!w1?1Ud+(lU^_1rv*#pq?Zp9K zTsT4Rkq+l?mHW(Z_1q2Spl|7+g|IDJIzB74Kin z1Lo((mFO*#5Na}0Wk>9G-m8e?<+d{aS+<3R2umOdS2M3$EnJ)3ioqs`Q3)w|*<~Mg zdCO#@M5_<4tis;>EdABYk}npqmZ`iC+)WDn70v!o>4b$d#n?e*@rAUVKq-8g>Wj2p zc?Bnx4S(1?mxUUc@KB*#r6D3x@2^z(ca*oLrTvU0b2V z-!AZNbI&p{$l$rr!PfWEy2-7nQyJnQ3#NX>SJe+KHwga=|@XJ;YAgRJ&BKt zR-8?u{W2(^PGs>fp}clOVcWyrv?tc77{<+PtKaB+E*5|UB)62%OnAhbGgZ#r(<{2! zj22u^v*8K0-L2x@{H=Xw1=;b#ewt01cIJOI$40a16gI%!Cf(vHZXPq5`-v&^>_9q% z>^=E1EAv<5lr3fE>y!~Yj^S39pLNcvj8oD*@~q z(jU)tW8Lx)qs_7kCvP|C@xmkd6Pl~WI?IVyx=MnSN+sr?EVUGPBZr6WRbG|dA{XDk ze=OiB=(&=^R?ph~Q^?s|k(J4?Jaryr|M}U+v={v6Z6^hs(zb@>3yB>8yFzhg%OYMW z>#UY?s}{_(lBsu_;8V(YDV+%fHF`^!h1Fe4y=p4|_*6b29lISyp2hhh#LUUUlI4}gJk`=K#<@EsXX86y1F9YnD#brxeUU%vPI6du`4xb)m z>dEqU^3w!0Xh~=^jZRKcim}hf#OCN7diG7mcNh}^GkW+(Wl#tf6*a^hG)t9BZqqhf z`;bxSs}DUbiPkZUvwyMgKpe<>d5zj@&)JPsLz4tvVpbzF*jGd~NpT1P6mU{k0C@#3 zqX4sbep#mhB-{6ZljDf+fko5Dbv@V!l7|2?4C(LHB!KXEHyNHz!vK(cT1M4_YOxc1 zuc`vV_A%H5DM`#xd+a^rzgPyiOI{1Dsh3IR}94^5Z|mmMGoZv+io66%}pekb_B#cB3oux=Ni*|e)vs848TE( z_)SC_S!xX#*i%xh!YzB( zt$X7U&+mIIBrl>I6G>;*c`?__Ul~4VCgU4Kgb0yb+L69)28sFqS$*mX>nD?ZRX}g3 zUm#ihZUUDsK9I0n70Z1pAlqRU$guA4H&;gb{_mf4Sup|WoAsdez_^Lwt!zn=ElTF2 zBYaC+h9h{te;yrhWkvbwowV-WyW!KT!I=pV!|v9!8Dvjk)zC?u6%@p!e7I#}`Kmi$ z{$Rc7aN4^iJ6T{cG`0w4KQh)mic3i-GzXOachcH0Flr62N-|(m#JMrDmvE*JGt|qd* z4Y6Y}!9HN%bwh`;keXz6tML2hYtpiMo4wFu{k_}v;)VkQ6pC_e@m`k^a<(b7z1qJ2 z@zTH{J{D8@}xH`en1(8!Aaum=!lFu%v%_oike*N-irv2^jKnkCJ;IFaf zc5gySw#-&~lk6|@2gx92lh7%QW6xGV1X{QPW`an)1ds=7=CjMeCux=SGayZqd^7?yr}J zcUP&HxVZ`x5Po4nU8A}8qV|0rL0jh~;o0)s@b#Scf`+G4rMKOyt)!``t>ep@zK}k4 z-osuK^GucQ;rq`ngb*^biQHeN+i`&3gDi4JE?-{$BWbODmUmc@Re*rKn0jL%otSfV zh5XYnnVt|PMNIEI?f2B1(`@KrKln|<+q;y|5m<(aCPT*O&69%>7tvHB4z2~Cb~c3N zYibU(evY1gretYl`i)w5jSPp5vCYK(8~hu0Po`E(VBjPxy0}WiS+h2O+RxN7|99*= zrHAE&LSvu)r2C&6>Rw@Z9WZgw54=?BXoRy^Yd5@W>QpcMNVWT|=Y-#cb&wa8&S_=WWysjjCd~~|0+#uZe~eXp z?#pW7T^EzyGo=@vSW-=6;qAUn9Q5n2rUKsZZi;X$um@`l$n)-Mq z`WgVjq?&)8zDot>o|=lriy!y{ydamNgO5D!*FuBJrU#MfyCfgiY)}(?!jd>C3I4;p zq|LG3F|TXZ@xMw^0<}CZBkN3O0!}wn-2^_mZ%PbrG==k)Z=lyD#@(XHVlD9>K5er9 z`;%;3wT+UUZEQWBQ-W3!&+fcq!fNUrSV(@>g_2l?gJjaKnJ}X<7v=oFCGia}bL&QIO6<@OW+z{lECh zrxq+<2z_BaFq@}DM$C^2&i#mcBXnmhj<)T0bNU$~zR$4uEGWkw)X#pmWavkvm5ShB ze^RvgDj-r5#ScQJu@_ZpRIr?fV-*T00q3NAp152U=$qxbU&ykfxyKZEi4%5BV7n2G zX-*gt`GXvG$sZ$f-q4Z9bNQRC0$Cd>W;wD6u;1s&_yJ7k*k#d!*&IlCFVJcG1H}TR zX9Z`0QVgfiK*=hmX`Qf>eQe}Tp{Hv<5gK%WFFaLXk)JK^g6ie?P41edDno8bC%pVM zlKk;o+XSY`6()zxOkTFf8}cm4=1yYqYq3^8Qjuo;e>Yvq6ZppPL69Y~i(>H^@H%Pn zAKdFHVRF@lsO^;fh+4P5zx*AzXCHa`IYvSEF4fCsjek`ND`Bg~2GjuKGNrTJYeK;b zd_#`183t%+o! z6H^b?UfUcDVI0!JF^5^&4IC%#(*-Q;tj%#*o4Waz3VWwj?LwZFL3pR!6PLo^Vdc<* z#|@j|65o+-C~8i8?XO44EV{qWXB{tf`~YlQcbV7|VT6|Qh5OJAvp_&NF@0-+@JZGw z%Y)dnr|Wc1_{Awf9CPbeh-v`7wh{duYzi zc*v#)ujW26k zd0EH|$cfs=1TKu3avBFJ)!MMNnr{tcZiViGZEo2+EETg+8T`|~s-O=8pW;|6COzNN zJ}KX$g^;dGx~Wl{#vq6_ZZzUQPV&?P^cIRYyBjsKy8nIc=1;^0n3QOvBNxf1y8Y~+ zZ^P(j)+Tpvp2kpQ)hj2D>uix>2L@|&6WU|tFjA&Rx1W2rx7v(5g20>{t3Q7u07x|c zL(JQpC!~4ihnvlGf2B*|j`b!D$m-0uQ}s|qTR9X{XW!@A-a`}VQpUdMC%%R+{p?rbBoJb?vYC8~ zhAsiuR}(xARRJJRyJ$M@*^O@O`Ah1B zHtgF~<@Ui2u+7ENoBG4%W9peH?&?MddGpLD)$bnez9~@O0NQqnr{-4+DnKev!V{T4 z>fIxVZi1O=vH$dA&h=qjVWh4tJmlY$&kZ3XRQaCKi&->p7~|u|udqY`kpr7b3`k71 zLH1S<{|9eRx#R87PXG=4;cEW-fcVcD2_ET?F^t7$6*^M&rDwSFy|F+1!!fbh@Vx$w zJ``)7@sWtnRN&}d#=d0pJ&;E2gDKyM4KyR%>*cwk9HuItGrbD39E_6I_Cs!Ek6Oem zHS%O^#8a&LNes!cA6Uy^cHhXU#rG&56jj_#_BeBR2)T{ffyJ_ZGUzM&+=ob>PxQOU z&DF5I-|MhtY~-5COx?!zuTdHZbLw(})oT-nky?=wa9D69a0;;RWMsM(ReeuR3|8K{ zZjbul;Z)tORfIVOvfP$8oCqVf6ir6YZ(#q$KdzP}<0Uj6Zyqi7&_$W0r`yDS5mHhu zgca^4=x47Qn=%2dT9wpTqDCWK)Gm^v& z(P-A+$sFbX(@VMR-63_|@;5?gL3-%`<;VVe9}P1ZLKVP;QZc5v% zr>u6Qd)o9LqZ$5lrmZ*{PeyCfBH!u)fgC)+%M-#)@r6)@-(=EobZT) z-r7(DzS0o}*T*12jqbB;mej?`jgF!ATdhm_v9ck^49)LYjHqPl2opNi#yhY;iPtW5 zC7Dnp?38X@b~i~Dewm6dnNpF{pE`#bNAB7c052%yt?85;u24nIi~P(Ex2(Pp>GHU$cm3w=^d>m7>I9L#g4aQ7Trj$@K!S z|DA_T2qaz?JwAFrHOEX`g#X;`6$lUADorl=HO(*Jy1@4mN?vP4-b7!~G+xODvCi}W z>ynDXuAorwbUZ%jb6}soAO5h-LUZ{55J%kxH_z%>AMLDX*kNkI?dnXkYjnt#M&lI0e)0U(3)kT%Dg)|~MAO`D zi#B}K%g=1E=`@(Mx?6o+586F6$^ zGyo3pOj)0N#7XZ!C9(`Sxi3mh@=;uZ19};M*pkHZ!Ld~1f|TdAy(lHzL$@UH%;nmp z)XlvaA^mt+viM@MREg8GRK21K_O0OW$4r0EVlom+G`R~Mq~VgFoi$yr>g~maj-B3- za)3<0*$0_hU#gOr?8E64`+Ijl>G&ANcZz{|fK}g=8Y2S9#Cz>R78`>J!`OQX1CQK? z{QI!Bs}yQf$d|f0Le??M6eQO~oU_o^z|b7zW$ z6U$$)_KefmOSelZ9P0i=C)7HZYJ^Ym`So|H{t1+>uj|x82*9P zu_~f@_9^Qtvmeg3-;onBZ$%joPmkj_c|Ru}#GgJDw4kpicv-xhCPh+DLCSQJyN%c9 zYQvrqImqG0qQ(*DEHy@+A2jb~1K^0v8YRSORt|&4BzaqWmKdYlcQCN!-~{4&(r{o8!uJ zKjVf7dK%@6(>htZ`Ax~v{a5U0s~C`Pr+*)P(2}GY8FE$b!o}}<#Kr1N)?QXT?$js- zY}nkLOlisx0(j;CA}A_W@*|=k4s9O)R}A9JyoFlu6nJ9|;6n8~yTYDoiBGYmPv^0t z_i7XmY`%i__<=b(Z4xM_dYey);5(Zl_I2G6s~gn!uyrut$|Y;otHDg|eJmYvE(rSs z!HNi535%2YEA9CpdySYVIL$h8mAGHoLT@>xbBUO0eC$O7Oe6zyF~1@_DD545)`NIZ z?MdI=I*5qHU0ubWi@dc1r~aRSG)j;Q{I^2|u?_IiqJ!Hv0un>`oedLbNW|~v*9xb%C~ZN! z%)Zqz?h3mZbBZ^N3=0^piWbZwC`w&SH`}(LOf{YNa6aK(!ltV4cggL=)MKB+lc(?W z;)?|VH;NbC^^9abaBLGe*`T4OCuu^b;CB7$T<4m=hAgWmSHi5_Y)Jsmh=}bB)7Veqzh;E5RpL@8|`Ji(2BWFF|`0tu}2o`p^d6 z$rCT*)Fqf(OLNRE3)wCGy@?BlOLcp@dvocF1%)`lzapqhI^W@pS2bxtBi zsAn;DF>ELf=l;v;rrAXMJt!M~zpQR|`1xgxjds*Vr)}6K1C{wz*G&~WY5w;Z;PTYi zS~NF|{(nlaw%uw;68=BWsfc%Oz!V$;cQCs)GAa4*!ka-|cnvlo-n}Iat!2H7t9smN zt&^%6Qp-i8@39x!KN` z_YI#bkc^R4wFu)5BU?e5eBhi>Ckx5h_j;5s<7{e6m|?EGILIOX1V?6(?H7k(W3;m( zk_W`u);=d}m-kt)OS)g9^5ZJ{5&Q-BVUYf(b6w;wcUG$LU8!YDmwlyduc`-}AtEm8T|7#wVGSgS;p8OsG{|r* zsk$WleUGLFOjD}M0RF~8*jB?As2Oj$?O3ZLItSqo)0`#oFR6Y~ZbUPf!0(G1!SE>u zd1++=5O*jVZ|51;6G^4M^*cii--L2c*~;g-SytWOC+c4o?HPJBhlnuO1nSgzxEatI zQ2mFT8bBxsCS2t^r^Mm7PoukfPpn%N;##R`ilz5~f@{IegHv1h_wA$~(X zr{d_K(lnlRVq1&Nxv58qqmRCQPi{@C(Z6oFQ*ZR3Grj{&5ZDHb*KaTnc>kx9npLHQ z?<6=+@r3e08P^8ag5uZ|lZRFYI3?p z6(Q6?X~5 zf)r+LTv&U0%EWiStBH!__{rZ@TDlN~0V>YQ`gb^qTHc0fL0{nA zW!_F7B@8aJtJC?MGYigb2)GXkHx$MB%9kGL_tY^maX zH+pH#c6?E?%<{2c{4bx7=907d$lcixK6eR?Gaj-O!c>lq?}vDoyP1|b*AJ}ln%#T? zG3@v?{aq=Gy^9`J^snI&)1TYC_kSu2VA6G41@E)qt;^8@KB$oE1}=)(d)m*huEy-8 z+GU-pq>bwnv$B8f2oejWbe1wg&`RzzxV~?rpPUFV9M_a24tbi;9eJ!c<_&mQOE!Ty z&d|=cV<(9)A}?u)&0?z1aE|!-cl{P@j(v2-U-0ZX5Ch&}l>=1-URCi3dg3%a8TK;1 z)Mf_yDDDW3ISKIuP7)7Xs4C=_)* zuo`j>C#0WO`Z21p^l&VnvOCC2#dSZ&B-akW=gEc zkB(!n`AW*mmbrO(4mI{o4N=b-z=upd1F`K0zZtEq;;fT7!}n8!p?}BP#wDTQ<9X`u zhvWi>o)&T*^{+dz84xCkCCM~eh<5Z-RF(nsz7H+INs+F0S@$Z{@3U!^7d;M1OVu^r zG}+1tLPah2XbNyThm!Uz*xtj;ZmWJF59*z6ZYrn`y5Y?i8Ppw3xGva^CKOxcYw&x? zFjYK+vRx#c1i<8i%a3Z7uJv-q34XgXG=Vn`Yu0ss5`O4qL#)5^`LZ%zpCg9; zi#7`$BwU6y&C+f2!kcU(t8oC`6 z9^Ur2GjD}nS4yj!JgFlFvD}HPHwXaadeR-S%0W1n)+u4SVEFj&F01L${`-sZ(8I)cWH0 ze(qt<(Fed|?24lSgh!7rab_iEiR08k@MW3CxOj`o#Z?1dT$BFNwMzQtWmC`k$v`X*=-A&JA4-roM8%+x(v;IxfutLd@uXe~dq& zIGw4l#8))iYbwpmPsI3w2nQV@oZ zhokM_yd4_un0KETb}D2`E2)>egzS8m*^DnpEd!`sR=v_HnkGel7qqkiuzMSN6p`Zu z=MZ9lMSEhO)B@6oNCNpfb>3kHE4f$fZD=@SOMwF0yG;H_JT`0!LBT%D*)plBa} zBZ+`QK-WNQ`rXIM=ZqBK1zwE}buo6DB+`V4r&_{-ZjDGIVv8NOFQ4IkR^0&8vCA&w zUepNXb8={#EEAWY7Jcqv7cb(~)=o>fGh_fSi>dq!fOA(bl5=d0ej2NR(H!s(`?uKP zF|1%p_Sm}MIz?l8f@2-9^%xqknb*9;NMHnIu5@&6=X0RmT0-;DlOT$;pEbS=1vzUJ@vRu@*=!Yx!2ogI@eRDbW{ff@Z}$H14-_n2k?ZiEL;DzH&e z=4Qy@r$cvUy}cvkn{bECi&-Pi?|}@=8>PukluZvENB!e%7c;6~ko7t0teFa3H$-7irmnP~YM#y}$eNcR|MwJ8DE)G@izS5$`W%YZBo zlaKJ*7UDU}%Re#Wj$3j!1zgKEuvDK=f_88Q6TE^=E@ju-d8uKC_PtEZ_?Ul4}P@5i_N742(Nr zIH2SOZ*()ZE82tk&v=YnBVPSgQ{RC*YVI1p+Ve`RnotApdS zqdYg$Of((=y$Hz(XEldxEN-;P{8TliK|8=W;MoJVgS8Y5Iqn}Zg_C)fiT$Q z)D1v|lS@*)l?wK!mb8qDMSP|!hq=A1u*&VGRQStG0|+%i2-VL?uIpgm2MQd7rx;Ep zR9P8|e%uvr2>kY9%K>zmq_ebr2w2~blEDtc2F|($teY{M zOK%w{-5avgrXQXrlj4yQSpi@D&^ZKIi|u~aPdRkHr%YX^JUH~{*F=)YPl&Wj-Dr~Q9dq8vJ~nCg%KXuwx))21e6+65(p|Pm02{ zKQr&Js|RQ+Y#GflrhhVdnP>OG&jq9dr48viIKHxaVt{B$E=d7^XM?gicK|FEI9plNpVq6Ua)=f(pkAJGOw#4F&hCqYEp?Pj=r_=^OovOO05KjOb^5<`if#ou4!2TQvORe)T+tpb z&x=ypCRh%(q?2AHV_behyY`>MV6OC`593B5vkjl-guzQ@pNsIEA zmU*8gvPD$ioV4@DzBH+I{%J?`%8{twj!p(GPQyH6wl)e~zMU^QU1=nwk3 z8fO#!kMX(%3TX;h2xt{J*0UG-6MI!*mG#W7xXy|Fs@hir7f4p zYv2n{I`Ixh-M-nx>mkvAV5y9q1|G8?Ji~INp!}aP000$K0c{J9LU#O`dEw2{sdu4u`nwko=p}Mefcs z%nL@d{N?rzjw_6s4a+o~B^Co@PAoO+eA@3d51tmQ&C6#E`PXNM@1^->_Rmc|J+>n3 zVG=E6kdA+1fS6nGj($`wxaco?-uTqJW@^7QC@gcP1HG63y=}8T|AUd zY2^m%ejeb2abGKsCw-b_@-kJ-M9}Ztv>`$mcL^oGEbotzUcZOFPEq}~>QJ5TKKt5l z$wsHIB8>f7+4DY%9G(~8udng(x7kmES@JCJP@&Ua&_`j%m(i-y`;C#{o?NK4N)yMI z(LJ#cFf+%~xbXMAg2EA-G}eyvzUB(mOwf?`Cp{H=$<$>2Aeu+*)KMfZZ&xnPOUbbK z$xtfeXMPcDNN_@)18F8H#*VRC~@ev7>}3G$3;hH4h3)TXiRtnP4W0X5b~gB ze$~ng)W*`8pr<2L!GJ2P?j%fv0c}p1oFiE})Pe*#&{;hy!NtIyuUcFjxvxEGep&cc zl$e9?Eyp325KX9j{n8}X3hwNW=h?~f*lj_9;A3n^n8Hopnocw7Ub?hb7QYe{!kFss zMVKvr`_SfWC8Jh!%%FWu?S8wMs|Kk-hG;_COD=E6RwRIF!hGXLs|pR|ioA^-?8xhj zJ>F>t&8@G7klzX&@JvtDY<|%C^ty5!3M#KDR-745h?S1^yWoTa8z71$hdy1n3d}Jz zBRofXGQAX#HjW!ZGMS;DvI9PEQ(+uEZ;3~*2y%WM>72U-(@P_ib5P+z zf)Nh*3GAOgN)OX)QRcg$oK(9AEW9lj)LLww7~vwL<-=eL`tjaue>+Oi+h>fVp6!`> zKSWd_21{pRJx-Ph8TpVS=HnK=wjiO4Ow09(IaC}c5FTyUhat{HNq?!g{!_Y($1_2E z+>rRDRqkt`J-xCt*waN?eH+5g&AP%)1mZI*;(LjU9j))Sh)R_u>1*}dIpAl*E3eN|vb=X*5mmQiVZ z3@t7h5l`?|&l_h>nc6F5`2u^4bT}gh()J}ddvP>(A7yRQ4!fuO*-0la84&#Sgr9WGDSs49y=ldb!wRPNIq^3BKU%=>U9sK&RIQ+kjwM9k z(~%xZx5livcxC<9pwxvu?yp(-1O<4XE%XCjNg*t&H9WIme~tDY{P>`qa2tsD$jT1q zZWep*+0+#zmJp{Po^U1_9fv#IDt92c97yh+M{jD)1;9v80R+cV_T-Q1Fagn7!n`$> z&2$L7J!fTkD=Ywiq%P0Gm`C%=Z`f5X^WF0OM!5}(IyVl#vNlaef8{0q_^oN0tZ&Y7 zkg`=Db}JYN9|%=m3{>kdHwMau5#eW1J-40o*e_U|n~o$#g;mhm@c+qbf?o!Re_B1P z|1s(D6yY%mt%Ilg+svmum&FZXGmaREE`sL0L5pQPiJuhQfju{A%tFVfGo+5mi!*nmsUJ@Cl%o5gsVb@ci(seQZ`|D9 zSd0IUuCoklGX5I>#z^T?i#6pQi4h|lokdOqhkmPNDI<28kBC36s2J!WQ3H! z7>s6gJ^THi>;LZeT<7im>b~yld+zf+=X^ftm)?BAF8>abPHGJR(4%a9i-^~Om^yko ze@VqB3$}l4YOF`5nO~Ym#h<0l;|wYP6eChxQt&E{(&VfY zf{$9(eTQ2}a``m9zNesKQzZ#)l>7de6!Wru=$A88*K_`z z{1fTZg?a$~(}903i;9f-!lmBl&O4}Dw&G0_)q&fPYEq;6_`s|~(x3DPxQZ_#`W ze!?wpe7y^@QPO)oDzL>iV>3utSP8%D$D4)>wHl3?5@jYZs$AjrTgULM9cgl~0_u{zVJ@<-Sb9v2oXc zP08kV)~Tm7GKv+4K0Z{7+`lcY0D0x$9jkee&v3tS;8)7Jv*BQx!<5*>mVR&0dEhI^ ztX-rBq`ABkX_Vmek*-H`TBjuxh0ldOfvhrT!UjZ`hVg4WWX)%*PRKc}WqKriL)EF8 zVX)sr6%;lV@m&TC5|RfaILlHaoqN ze>l*;DtGrsB{ZX?SUx*5Jg^0VxLWc^5ll8Q;ay3FBInL~c5=6Gqq1Bzt!el0@pt#OZU?@3yP$Dr59 zko9m{d@ad>#;hsrVJY;ZKwvMBt%)6Nc|04aUBcHWHx*>MPOWw_fP@Q2!DWEsM1uvL zP9TvF+jlG0tX}VmaRwtgfixh0X+TEj(7u=;LK@H-Ljv~!D2^TW&?-|UhyY~H=Xqqq z@|LNU+D1~Dz$l3v^65|68oipFtdD-VbGD6e8}KMn2YbIu5b{94a{qu4!&e$DS7s9l zK65q5AZluV@zMRBunT$mvt1_PwxA;3pxoT}j8MDRRqVp*mZt`q*XFReAI`r5RrdKu$dwc0(kn z8q-Z{HmewPP#^G31jxgVs13T+oYZlc*4s2Gma_>P2Y3fQ;XJ73o>SLXD&LQ`>lde+ zm7n9n_kdk`y-#h(zG>?I=LXgPp_2?G`*Bj%%={O4zN~4Gp*LD5tjn zCv7&OD;;LxD0JOo#?%Ptzr{@op;X=YPpLXTLQUSj5Ylez`H_{pld@y6?wLe{FXqFs9A>_Y99!Apvn5_(%+y521m^rJ9 z=}j?N!gE)XX3_2k+=>kSq>C(U-FI&IJNbEP-6+TH%;AgElyr;pLQsoa!#}>)o^Wjt zXBEuvv~$1ziBey4^Pyd6sbXG?c@x;)KVq5PeDFK@rJNJUjm$@o}RbKX_uuAC7WxkoR*5s8R?J zYR*ydLk$zBa=Q~9Sy(&rS?959)>;ad=xQcEhO2?40^IZkE;zPf`jB9uYP_Go zYc@Hycp`^7IYc%f^lRwinmwt2T0U)1K&h^@)hTE*ZlBj5j%>bc=$%(9sRXuuK2zy@ z*2F)o!9#H_z-|xtB0@tIYZ~|h?yh=~9G}IZyc!w9zsZq>)Q!)h;S>RdKdtQ5EvMLf zXd^yto-@wY#tO?9k}uZ5h5p83`?KzS&H@`!LBuNGh`g)%GLUjy%irsN{(-^w9+KGN zzAtO~SFZNBC(Nt-MlUuXrXlrTS&Mo!4XM$i(1$)j+C4r6wPiz+zTXHA>kOCj=e|Yt zkBAj9@q2Bd;oAp!%>2>H}bPEMK~!PfhASE(iv~3HGtFRma^Rokj=aYl$44fO#dLPv7YVg?V(3Q9r~{uf2Do*bp+R_#+&73JOHez4xHA< z#bgV`4prYJp8&&A52?6@$+)QRe9P@STtft59=0Tz+HOYMTuub84MI4y+UsJ9-68jk zJ~-FvKhOzTX!At12j=CzPSyLXepd9kCHN!X1$)L;4{5lbrhgp40?wE>A&5RbgaXt8 zbe5k^y`Rb)=+u4Ac|@wls!05vwkstxfAx$VB=5T~LowDR1X-7zN@Bz%P5};!+f@xn zNq@$BlbQhoiNndNX$+E&q}}Gi0{OP7gzwQRofB1mv*U@-Qj#A_QKS!8a@#8kZBB6# zWkJ8moK-jyZ2%KSATd(Hom&lO`bE>CjbxcFbw(-0kk6_qPWtNB-x2`KfD{r!dqm$klRoq9mJr?iYD@y`^qJ#zM z+gU`W-7@#X4hy+_j_K_xtAa4zmE0v*$3;{;{4hu)tadxZ0{-U763We|Bc7)f~et?{77B zCuc8W3O^c#G{fxQ;voh=_jxv+c=Lrrj^zEdH4BK;iq3~6Q zb%!yBkC&&(8ibAf;z?Yj=w`ip zCJwYX6W+*S2NfNHFC_gOS(`e~M%-HCm9J$x`n#1#u9T+sq%Lbh4>C&D+O%8C+R>94 zsj#Y{tS0UtUHM{e2)dq{+%jP0e2ty%{QSstqWQlrcPuTok{!h6m%IEYyZ!m!?6w(- z0(Jtt^GrUqS*die5-bpy;DIftg4Fr$c;{3g4v<#JJmb9d&u5|$HBz_;Scu>LUjnb?i z=->FA7m}q&4$!F|dtFc1<}Fj@wiZ353hI47*o7gxMD-l}Gvsbuls6E*@_t!aQ(M7U zcH$G?8a59K&1-6npp9!)zVX?8*R%HI#5m-r!1ZRS(Q4Cega0Bp=J!>YQo9ASi;3Rl z=1^4wZy{qzy&!(;8SntFsuH#SZ6obfvK1aL=#yXuNX1i>*b zLa9WDBG-21QN-;5JoTp%W=XH5zluG4_U0*XvGm=>bB*(?=cj;${@c2;UjyG2=ulua zSvfQWIt+w}hwo7rB7e11ptJGAuH5)V1?@!A+t@Xn zyh?L@yX<>rYUM7qZt#HBt5A~!G*#Sea(c2;fRk3@PnUtJ`#NJ!i@=W~TT~yQHxXH> zP61Q8LE`%Jn*F?A0KWtvQ%4@$MGx($4ta+xMz;)Ds1xdQ*=&nqh#!)PaX%!v9AG`h z(u7>w>0$}?r}NP36|Q@8{&EJj>Cqi6diO%6m``l9ZQf|oVi{Zz+?dx^isydsEGyi` zS~{zK6Md655Nh9)8xM%J7XniQS+yZ_Veu^@q;zH{&|asj ztp4`-L!Jwj&TE9AN@rH~+UBp+8ceM-KyCf9&iL_Hub}M0+{-6)25@L>OjtAZ9X34ACARM-A>H}dk1*rY@^nSOuZh5(n{hNT zK3VL%RDOXCmim1(KJ;oo8SvvykR)Okj4htz8I5XoRuNyU-xZ%aan`@mV_X=i! z9{gQy(6K4}J#dj|GJIj>L+}b40&ffn`V&Sfr^9ybznhxwg6;>eI1v_^ErHv2(MNmGUkHy1-STpPEAlm!BAo!>!muZUX zEyoEBydBAj;$=S5l!x1QXr``_TV{66fN-jKs}pBpdxEP;KEVO4uqXasBM6`2`VIzh{VDH=m3 z54J!<)jC+`84HEUHCMOb6o(n?&(p$?vhNqaYX43NdTh$O*y;pOO|XjBU++; zv-56M3G@F|F^+)TlE}`R?5N4Fq+vsuxN$fN2fkQS_T;O#qQj&JroVa*vgVa`_?C1w z{4w?O_t4bZ6>*jRwpCj;YWDkn<7IiN)YfCZ7#V1Gw_W^u0GDOM|Hcv6p!mnU7d&}mptJ{mC^whlmmLl7`X9i>9f1^~ zpEiKc@iHrbrL^8bKsc#Mn60$hJ^_gwvmAw%uy6TH8H9lP`!@j7K&Ys#6zL{!R|@i= zf&fkUD*I1{5d3NI$xhE*=wl@uSNqNS{0=x%L1DhfXGdE~PkeyU-B&Jd%VGBAMS=81 zPN(elHNHhJ%b$Y$+{FL$Yq+B*BpV()wcG=$HM$x1)mc zSr04Ptgdr$tB<92ykGL{e`Boqi%d>r^7F0~t7I(uBj9r9FB6@A2s47?O5JD`lsxV? z^sWcPRHD5jxY=+SeL96^Bgc{@9Z}9~3S3M!|B%-%0z# zR;^IlQ+g?npI7~f$_4sZw?Jp^FY;gNgdfrXD#zU@%B#bteQ{^@cl~8ycEaz+>%5}Q z-pa|je(ES{MZNO33(`_G6yF8TubHjfy|@e2&)*m5*lQlDVU}05=kW@m-TV98@{nur zacR%ekJjY2?YJ{`MI-NRw?JN&qQ`G5^ExZSQZ8gW4A@lcI}Bc3Vp`}{D3vO{*OrT% z%HAQpczT5IRB1Vj;i;XGSflTENRQx6YJ1E23dGdx65O@NpL&T7*Gzg?`zmLomqzc;_=&OfE; zIGk>)f)y?Vg;{tV#c1c&9`9c^;yoQsl{QE%>Ft7+SwB4g7Erzu1+Q*dd~5ZLNQJrJ zGpRGLedtzppPF`bv^rHww06EXeOLh|!p*L3bvnL`JD2SwnRyPN7Ez=mgd~3P62s`d zX?FM~uH8=Yp1{}mpXc%eCMV1^ym#u-1n^JJg?6JiiN|3t39_fw1+$gf((xeV@0;3N=|vR`yuSzeb&#fUlWFk7Fi6|jtgma)^*Xx zBuB-tP3gj^u`=A&qd_OlXZ5bITS7q*S8;^d*@yIdb-;qG*UpPw=-_(c6dOyS#p7ne ziJgUW)9qSIj@a=}nO>NQV^j#am|G-0JziJ7@q_2@OV|(r9sx}Cq>4M0&rXwe>K23U z$ahCf1dq*M5tr^@#zuCQL_E;3M1&^ zar@20ZRaC0`jSuMK=>$&c;nfwMKCW6@we78o@NI$xMgnWI5zLud+t6W+vjjf%p*yE zvn+7lK+5?kaDFydF^Iuh6^_*C3d3s#nTcO@Uu7i)CWZwPNt+4a>ldb&Gt5E)KX-sh z&IxzJTi|nSftB*1d?y}GCQxf0fZ4CgkhYz2= zuUD+BNV7gG5~aYqOnSvi?b z+JSv*YWnp^^(FY-ydWDS)7z*8*Qqa$QR=AlyO}^v^?6$^9=J9AKNf7$+-$Ms|JBKa z?Wx?fmJ@zA)qS8-HNZS{&|wW6MH4DDrum`o!FEK46%XbURZ(zv|MMr7*sqU8bPJy9 zCY$|Dj0FcKym!RGTLz-NkMGGxJZu&qjQdT2$_N+=>ZR-eIjl(7oMI zZPG;qVr@0*$qb7n0S;h>qZ_^y3k{qZ>m}uRWz~4_0nJX~swR(PV4>3Dhy0w=#~RAH z*s9OI_T+<%#eaWY$tbFRGu=U~2Ey5TlD|2K`clDK@_X+fJy_49T}C)xgAqJQ>Vh>6 zWbSy-ntYCzS@PWC4CIKJly*sVk!EdqTh31g4xK=yZm#6`2r^ec?Hph)QFRkK{-L1h z(|RHAv_9|S3gd3;Lw4qDmM}EXpJLsYR=mBw)V1>Y3Xy09RWK$TgqNny24?u=DhG`P zU5yOwWL9})^gq8MK1|oEmJ6}mN_8Vvv;aJ0qC1}w0_GL%TwcC>x3PW)_87ms5G3~#X`}GXcofI<)J9~0%kf8td+J~l0!#M5^xLIQrY54= zNA}4Jo6pQkl(COCv6L3bVrJ`-(*dV}*>Q@AEUE$R)Fxs=I|K_IkY`f6Gy&{!W@8(_ zkA$JwkRq@H`ud2Ai1|7JeSU`@3Vs#TNCRU5aSGpdSu|<3t#}i#+CBd++|?gQjm^WB zq=&kD=q#R~B5R3Y_q&okh@es7@>Smnvz|1{NTbR%p%AeTLtoD`$k-V2j5%)lN|Cp2eo`A){+xE|N%P*5|C*_R^UsWvv?~eTb4Li_5(fQqn{%Wa z+$?q)-+hTbFraIJwbFN=bYv|wCsx98*VSsx8ee#9WSTJEda)R6Q&1WyVvlmOgPIo= zcSe>!OSf-dbAJ*{E_WS)(``|F6Jk^`Bz5z{ycMCpN1Nzw)T=jKF!@oA+OiUf$}=sl zkxq6U5jnSo(jA=(KvSY721OILuL8B@${5Ad*28i=tkNhIqkco$%gd1sT&j0^$s=;u z03(2e-wHb<-zfL&W?gyeGx*3@h(Z0JMPnWa>aCG)F9Wn|>EI7 z4b88=w=Me(4n-;bgAN6VNE&u=ie@EBGj!nM5_eHbVfB!=4tI1%An^_34;ZRMWs^Tcq;?{U**ufz=i4JbaLDkh38^)w9C%YX=R1oI5RORwm)GqSx z*fmRbNG54qttYo@30N1TjtREg@~61Xs28m zE*?e)yfF2_v3bTcysS-74G7}}Qp&R#e54xE_!PFjRqULaq!t~-+)%TaN2qm%T*8ic zi-v>iJefHwcIQa2v z5z2BJj|lZdiPd2*Bwi`#CHiaG4RZKD;0)oN?2YO@#J3FexP$f7mD4A`jCMQ(c zkk7l;BCByoDYX_PxmTx~IEK(RRH*~Zasr8L)CY6SanYCkeH3%QL^?0U;izFUdOG1& zl?ZAIuGBWWvb9i|G5HDP_VgV(k=i96bfsl{&GeC}=offKB~M&S z7-=?4C(pmm!l}9rOv1_EE@n30sj=EAaTQJLw$|*n z0zcwB@ZXZ0fIv>=w^pfVpZz9n0u_h*17*7yg6+{uRcTxh_azg^XHoqwNpeMxY)xS+Rx5b|y9bEYbqF*DH z@3mZgrF~0gR(j}wvedjqH>;8w3i*(uW86!fpaHJ8du*FtzF!whVGD|EuB-c_q_8U4 zyOo4sFZFXYJ5PBdzRW1v3($KeFa5YyU(qoOgoz|lp}qW|EtK@lCM!99->-|xktsl< zL$T}QIBzIKI5ERPtg&yOB2UR_wpHZmr;ca=P2_}a)I>NL&EWSKA=xt7Eh6jB5gYPi z67U@0^dK2Z>3&~h3Mb>VVAz*XUC0#Mm34@mW|1tou*;K zWT4tLgzGmVC^o#i2@>*S&I&E4ZhTbN!R*uO)_&scW4gia)-jd+?yloazFt&o_4l!Q zCp`WI{1YwgV03#fi^D@7zV766QWKnlFB?~Yz)rX$pJrxLj5=@?MPuH`&tvsSPUjcV z`mb+Mj5wiiU!1=gRSIwI;JoahJKzb@EWJ0^TXjg-c)YYh6Y+1vUL#8y+nu zc3v@*S|5eT^-PK97;vc8ae4a2d_ZbKP?bSN|HjiOIaZ1fJXoxebwH3*-OZ|nPcqKf z6#S^JV}?7vpB7-dQ7Q4=aXhqEXE$KX-tsDsje$9m`~y!G{~61Zj?}*wA^m;YYx?i> z7EP{B!Bq_aIDMgYK>mr-fAz0KNPiF8y(Rr){=s3(QJDk&=?+xlugjh=m1nl<5lIaL zwW=RP=qXNVJ>5dMtLzSc>POmL?)9x!JR`yU^sv(n9-XkwJ_43TarjCEC5F8`yr)ba zH;Z+6IW=yb`|Qp;8{W0nekn4-y0Xk6CfRON$^sip*aOD%o8-LBt z-7OVzWw=WYD?}a(ZG0l51`_>l#u%Cps=}>^(TNP$DrpGwdB<4u!OE73W4uw_pkMm; zsFrf)lyxLcc*kSXnAn9Uea($V!mxuD-}DD=9jeTk0qXb5l~=44)%KXQ!W zTKQ$hs5}FH7U8uN5O|hNVOEI`RQn*9CtntR`Bp-LmV9xJs+gLvQeegV&?aZHw zzXMVk#Nhc2@;(w*RYjY>bV1dXkY8#W#(cRRW>@8$2&co9dzn7%Yd?Mr9tH$={`F5|6JY(_FaP4jb-wz7 z}1K3Bimk_Gui#LS~nNLiDKH zg0LOu^bzhZ#wAh5sJ#y|JjyCYdWos~OX~gZRLwdnh26+Pcstc*-Qyj0szI{AO;KSq zbXDl2dBHATOb_Qh%K=ru#qO-8vv+x6X|YrUGEj2X9V)s%Dq3)#={}qMu%q{!D@Mjc z`k8(4{#Ts8Hju-h#;2sSc{Vu&bekeMf=z%91i!Wjkyt$c_nJ0^_+DRBFWg@4h>=yU zjD^ri)5G*CZfj1>9QCXH5_z}CGNh;MrKxwwr(f^Jr!dw*u8gnl1Zt2ZZ^~a(UfuaI zqgM#4&Q|&~2Q>=I*VTl~QsIxvx`)57GhYCi?v2OMiZ(SSc6R_dCO68mNTH&Ve)#I_ zEl^B!W}ig!KhR|Ngg0M9NEb+fS0IsKkx)_K6RGvnHIqgHMZS7I6R(}^AU!nfC8JWj zf8-nEWG*J$VFM8Na|z9wrsGUkKWF1{nVYmh(Qvj^JR&p&{nDK;NDfqJLuSVkYp6fn z=l>Zdjm09N{qE!21D5(_pv75(Yfg7aG+as$_hdJJ(}ta9Zt7k5ip2Avm2Je@%SVp>UEgB}UHm zyIs+U*UIFT#cr+9X5yH5(pz?yx1DeG`WaDwt|Q{u0bMRM+@`_w!l0L+DT9QeycJ%VLAYzCQ)m%Gk1gQQlS-Knm7G1NTzp z$MgpyI14m?8|nIeIe5G4uKU5euOZqF8sK<~Ovy&xE}B@4c4?6KwkjD93(6=*O%a)x zZXH&%hwFBzHJvuT~M?epj03SMWK{M4OHPF$7LKegs! zEW8EV?er}8QQL{m-gIzM_PtTcz7=GdsWZDZi+)<&)vpjhbaSgMP*G_o$I<2@)!*Ry zk4^UR;a2I7fZb4OC>r+gOYrRR0wZ*(y1NS*{m#PW6&xiInisFfy~*1q{pgo7-y~!6 zw-pDn`AU_(J|YHgE)ELWwh5*20Te~+v&E+%_%8v%54Q?PjlZYr`9dPV~PRBWixfhM3^Oy+bJV4-6b)1{&j zJ2btorfRAGsKZfymb_m{pm4CiShoRinDoU)cd6$eFywdhLox1m1K`HQzJ5tK%8FZz z>vChwJxN&Z59}YCb1LkkZkyHDZB=;7>mRI{4vm7_LqrT9*%Ou_M+>ql=6#9nXhTe@ zm~-%N$Uh>3KV*BEa>d!_YRuv#^Xk`*A!E(|=mdUa+KzZeI@sGhIVxRPNlg{&JUyJV zbNI73$=e~*Vqp5tYByP3rSb6M35(u;wSUtwY*N(a^E6ew;cR0sT@=@Iofu0U=99*q zs$ab}(HoMT7TW&(ts6p7Prt8R$=;IBKyEoDj}ufGu^?-nUA0tRGgcPNRlz3P+&Or- zc;l~<7}20zdR2m^{`iMWvN3v9yefhI%&`ufGGCT4nS*|GfG-)5_I$<}DlQJ(8Vz`} zb^9bZH!#5IV1r;s)JF+y2TN3>uM23-< z;2yt8Fgi^C`A%|`scPM_?@2@Br2U>IkL|G6VB6hb!sZ$F(v^PE*sB7tr6c>*((5E9 zxP84}hAuj?{Fl^)Cf@9dUL>Yl=$t2leFF?NF0B3 zuktw6lW$z)u?sD|Ny;bsf!Z%Tf_J&438n=b*KChlJ__{m!|txiR=0U1ozWd@FqZ;D z@9e{sTA&W83(#HyF@lhG{3}wG>Q})}>-$*?Zci2CkuH5A)isC^nT@QJ(T5wZZfLR} z&{2c$@$)H&Gw3{5R`It16b_N*q=V(-!H(a1n%l}Nid9SGP4qWY8d?^-a@Y-Vk=Mht z@aOPk<0`9I@<=MtHD_b|!Jf16xtydZ!$SX^gS-@tL)o$70J@N-w+`rl9Yv98DtMM1 zg1a6d1B3?i?p5e>cffG3vz`U+F0`kquaa$j8qRX0dY{q)LO8P_#p>Nf5@S+k#IrVc zp?dEd-FV_v1B#yryV!@+aP2j4I-Rhb-cnqOLQdaM@L|=>i!P*m8V%tw*a}3F8xoq)kerV@F#2>UENuigPv^J2bOxA-tYEm z)<20~0+ZO_G0=AxqH*gJp4e1wmI-TTU%6S~i-jlSW2xZGs=s0H%fA(Hqd@h@ed^s@a?|d(&HG57Rf*Ad%jxKse!&6mrv_~ ze<|lbeX^rfXVzcf!s4=c+O&i$Yoevg3Te-avuiASvuH8X0(U8GHFC|Q&Piln+LAsR z+i4-+WAyF~j_K>qp_T6UwchbA8uo$rXxstXFEk?q4^m{vncAAZ=YnsW_yyR^ULAFw zE69_Wf(wk27d!WZPevPjjuI?O>|B*`(j*oOGxIyeYJ!~aTND0`%=!GdpzUOMaIU4? zZLc6r#pXBT`J+#UhpTl^MVwd||mdR9Peqnvtb zgHfn!!?iv8K|sU$r?AV6g4`z{6S)+lX_Kp?4?l~2x3J+Z-M>IoBNRy7tXGCB`D=oM z!l5r>{@OoBql^~(r!?@#@0H=VmCT1BtpF8MfoA0B|vQ@H5@+xp(Us0e$CmI#;&=^8gW2ZZ}_Tf zK|}f%N#!o^S4Ioq_Ltf?XV+5+|MZXpT^`Amu2d#AX+K5RaoU5jvhcQ!Z~C;43zhR~ zDV<$NRTw%5-))Vm+%sQ8C_Vl>>U;b{UY0*PZ96Sf|KB*V0Ml*Z8 z`0TaxwZT*{^A)df&lq*w!BDd@M(X|*6XZ99>#J3A6!8!Vl0)I!3MiPBz^`XWm4D&+ zrM7kTIjMYA`kfC~PVO5) zHkiF5Go>f}4~y0zw(;UNKknLy=fG5uW)6SQh3`fZzU~J-*mAz^r|LXgqW0L~ypGF% zl>g~f=eku@nvyTNaj3?~en0Xk?L@oy)(}Dg{F`Gf+Pv?XM3z^;KoxpMTL0BVYEG5r zo3BwjW#NA{kPmTbMVA(&;c-dH&U}S2xZC6TREI=e^PU=VJsH73ey0aUA_G#qyq$(! z_W;Dr9fdoA9zv5oq<@Gl_mEwWYpxb^KB__D+yMn)A2K1D}J8(E9bx~kMv3U+13TP z5Gb9BODcipJtK_N$glUHHN8Zhjm2?cFQOxki;?Z*C<7j6jmQIfleTAYhs*&o#P?8L z;>yK9ef!WF!o2$nHHgR(;yORi+-Uw2K7y1f*7oXN{HosT> zlXTScxjtQq2mKAaS-9F6ThRnw7goV|NC1NasNuUo>5Lbgtzt+#@2mh7(>+-BniRC+ z?s@k_M<~}SVOkRUrd^TLjt?9zGPTl7+dB7Y@4kMyx^8sL^ytbQ*N*cHfpSeuyc8F! zC1@itfr`LdX9B!?a|p|%q5?$Ue%~aPCdu?H;=;* z+Lo2L{y9R?*TT!+72SW?%{YT7$*u_`Y?>uFgy>si+vgWXr+)jJ>)RH^hobhko*vi! z#kwtiU*|A&VYH1<4l1QIXXZ?xHkU)i*Wwpz|=3EwXC>Spja&AtxdQZQ)N+a)_1t%t)>Gi68u2Zk|Gy2ja&u1M?1NtesZ#9@3UY z&rwb?$N@tx>Ba>gbP|Pyz^5(N^x_g*yVSRGjx{*qDMGHHDc4P0O{M0L2CMWXYx9u!biEjhRF$ z11h=1QOTcMG}u0X#?&3U@~+CpzH%hQf9`%W0~-6wF4|y3>lju2xvQK0vu+{dbPe&B zH+3=2AI1zb1$sT+m8(1@C40Rk$1ex6@g*QJNqpBxEr_^lVCl4D&tOzMoOw|n%ntEc z518MZjFMe``P9gn-Kt3MYyVt;zteO3*~u}E`G>Px$3pwXvBEqqb%eiFq_rAbrLWwz+7Gs?bBQ%50mumX+vh4vn~XEGDv}6ejQzKX?Dpl9B|GiA@S)kQ z2dm?%|2#O)ei&k<>oN9yvrKeV>0N!!a~U9Do<4~d4P?yUlzE!fbJQg14g2knzkZrG zv6`Q6yX_Kp>SpJRM4{N9#n)>$!1%0cf0Ja>wbuxN4Sg+3YAu>eCrrIQNF%U9f4G%8 z?kb^S9>;I8vaUixj-%kHFRI674p}W$j{seGe#~b$6k)rwF8~UTXbB%Y%=HTd$& zrp1NO><#(b4s*S<&v{?tb;|B_DhLaAp-iySUzZM?I^#)Uim7r>{?eyBwPt#}0Z?;> zcEz{o?ckqy9)5qPntkjH>gb35V3I$r5!K|K3dVEJeZ2nsMkX9UP7e8S)cu^Z*46($ zj~CSVoYsPLVKUlbepT(U*K9=f6ePOLvqW5Pe=SX>BF-h1GdhGnwOg-+ym}>CePPI? z&Vssn*E*9!V7;JoDxF_^WFt}hN7Df2jJm=3O7~;yZ!76;4pUT=bZ-%@A4AZvcXAN| z$!C22d^5SVOwM;Qc(o?`{seF1Xyd*LH%%{y|b}0%XMsF7bdgNcO4F z-5~Peq>C4r&3GY8&1Xv;@BBRfsyd*_-W(+=jte*kTjbUVT@B~%iY31)__iQ0CU*I% zQ-uxzUA>Fyw5YO09#vb!MjAm@~3Qq~hFX5KDQqBHwgs%qG# z!K50_y#Z-^pX8ygUCm`WE`VQ7nt46B1>4&AMQYO6=Xu3P$M!|sZTWdjRe+`ifQ&9pRUg5 zKX3V5yR%`7J3=^exC%LsC|;S#PHbga5Tm1l|EeF_(fZa%uaXgLkmU2QMZ&d}q@TNZ zU`;k*ThuE@8A9m%h?}2h=$ftP!8ip&))|4c`%SmTtkL~$o40kYMgXxFXBqDdvW8N6 zyfBc|0flC6p8H+a7~`;-f4e30X;gIg#K-M}_e33$OX?s5H9TBog+OrXymmg4#Yz<_`}Zu<8uV?6J}1b}KFts)&s&cI>jvnZ_Ad-f7K&)ECToNOoR zG);dL_ZainaXa%r+|Li!&tDZI!55DY;2zZ9!gAL?2V>#oa10H8{GjIAl^Tw?Zd@y} zJc!ZUV}YyTuzr%Vqj-GHB|&S~;XG&PkiGN*#30DXI@ck7OnX>)_F~;&NS*TvYJTqP zT0`cCWcL;WWH7x~P$6jXtXuqE0OsB>yTp!gEBZdz^Bg5ZIKq4C={Fn{Or~nGCee~p z6CR`}W9!AH1^-8UT~7`G{y-ImB~u(F?Pj&$p}n7$X-Q+}_D+LyyCQSBoyzv zeU=}$BqzY%#Vn_o1O2GWI)}%~$0&zX?XeWX>T`doto2-KL2V2*o7An=ow;1u(L&!( zWTk`%P8bEw!)h?bMh;53#ekL>k-2`BBaI#FY!vc4yjuZ6J72#>_6uANQ+xf z;gDXIKKb5f?Sd>@|Gm+i3&URx2!fFf1kj~Ra;FdrnH46?Vh^4J8-m5*$Z^xS9A@Xp zj?U()qwt8ZGf&-Bw|kCD$}}+U*+ng+mnEQ{1gFgZuObhO4KqhG06 z$;|M8H>*xx+Uj$7%V*fvOkdw;*6Lxp;hOO|UUd^ni6t7vj~?eoD*18+$ded2r#rIs z7Ao}`-HQCADBiLwZmQBtjAd9Vz3T#eD$h3~$Zk8GwSS;mCw{BvRHy4Pd;|WHp_;hg z(bD>!sFYwlo{l^Fq_AU(E_j$CXvuirmQf0e;6Lql&y%2|)_9L1c~NaGErF7`(D#Wr6!=@EMcT#ujh-Y?-2?u@sY0g8!hfwb?BhAgO`x$*N-Vr zsGmhizlA-kmky4jX*j$47`ZXfD*bSE`E{L^-cL|4S6foA{#>o8(R~T7;pg0Xw-?5r z9#^v_lsHF;pJzEHBr#_1l>-||UfLHpt0P?SieE2hH4Sn`4E5~HY2P0g4OI>J++${c zN#tCG!zb@(WUiTi7>4S>%%=5RDlOU%o=%_qB$2khKfged%~w%Ij5sKaGE zr%K@0C#i3;`1-#64_j{;*W~|)eQz|<(zQ_vNQa|gG=hMFNSCyqm8lj<_oJ$)>z@f|?A}Pn*XY5VBGwB5vYwpyTapcFal8X&xU8$-6NRf9$GzR&tqgI%_^>rYPRqkj zVS92PZzwLD|kHJ?1LfX2cM^_wZu}xtL{wD4_j@G~_yhM;_r7fBXv9f5 z6K+n$ymdpFW$xsd4?U$JP-1_C)Aj*|=jWg?dw{+@(+`Ovn}@{hkITW6URU?Dy-yiD zg#<|*oVP3ib+0DVWEYjd>r!chHA5t-D)I4-7`5;w0}Wx-iEopLmBWvZv5h-YFzeDM zVV8tQDvqQ(&M!wh{&u7N{(*RVET`%w=1gA(!DkrA4k2*-?wOoFH7$gAcy$C5&Xkq`;*g}17?YB=i^U> zp^d#(SaB0;9->f_N^HZ<)7<6&Ht{3;ZR;eJUN%&nG=S^V-Qd%^{&pNU%}{>!tA}1v z)xU;IUFc{uA}jlnwYT<-VY-1|$9P+TEt}SDPQYxgQYDoK*B-(uJ0PLIQZq z@s##5cc;sNS7~`T3=bHXa(HRj#LAEH9kCQ2rV1jd8m-tLefLJGZ7*e@hGRY|NkUWj zKx)b?s4i0Trp(<)qFDq=`uR@w@_<=562ibY^4$jtTH5VbVcX!7?()}Xt3C<4xjT+v zhPRUh<*c@L-?_C0DRRdVm3BT#LXBT^OY5``CgvZ8U(4mWRE_nPV1uW3r9r0}IpKj; zp*Q1lt^*C$1TTzp>e;fk^- z(%ZPQ>CDa@IKf+)2w-G-81bu?*MQ&5I38ZpQ!1i8zG!VZ6nwEqdhR+4(%*YxzR*?W z+h>I>wBOM>Cnk&L$rbfJI)XP#l~dQj@k7@a=IsyU@+#xk#9SdOhe3H(EuiV(M9KJSxyx^t-@>X z!!Yh?E-He3&DK(u?UHaNX|EZXWQffO3S7~IzzTVzRjeJ0t(Y}Zp{UBRH zR^&!qwLq6m+-HJ#{|!LKg~RF_$`7#Zq^u@6NoeOiuD_^7_~^61-{SZgDK->TWPEIy z!_-+}JDacUvmI$<`nYFpT5k-tIikBxwV;W5?qGiZ{peaM;Slb|%$=`}qAY5X5+Ak{w1#1{c-V2KH_WE>z&_hkW9wR*oTgS{J5fnc*Wlw~ z2vT>aH5zAglKy}-L5q8TT44}sLlk3%OT;U)-uI9w-km2M@g=m8!s@86Ud$P=)-zLC+^$=$~K1X@PuLq=El z5q4Gv;VKo-OBnI)1pt&9AzRb@0^ir964Ktu!5!{jv*WmM;JmI>)VW_?kOllalc3~Q z7{Ca@n>R7(smJQr#&7Z3zV=<3$%1fS!5MN^fatcz$KahI-d}K-I%0=smxNU|45pBrCB3a= zzZ8>idK0}z#l|vKXbBf9IAxn0yxVxzwM;0dRcY*mVD zRPfMl;Ca(#bllNQdh&!Q2X_P2*kB6`3=EBnW+8aQNny9G$URV4a6ksL$FkLP^2P6- zpq12IV&ZS#0C+D-^XscSj;wl$o}-L(%ylh`U9A`^8WY)MfKrZwVMoibqT!RHcS%a; z#o#IKl{bbMf4Lb#;U>GwV3}stu|1=SiZ?m|z?Th17Pc+7D0b<|*UL-ZI@-}XwN$PM`yLNTmr&LOn^5yS8xPNjUKc%W)(l9@8<|m$iJSwi@v?>nr+gV z`T*-pKsB#lVWJfN9v=;`%-Az;_+35r^Pu9&PdU%-J`t3G- zfp^dCj*!f{VQ18)YtMryOr31$=`VFg>U$8psdRGA+RQiSy8X6cdN01!B@R0c?bDF@ zmks|CWEHX{p5@?Y|If$5;Qy+i26@Ge!*kfns4r$0HYvMedyq7LZKl%*IOK}q>|-f@ z*z3i_4X`gDE~g>+KBxv{2l5dlFlZ(V5X--pK&wFMcNHez>A8tVGt~Hj{p}_jr$1~& z7szTnIu)kvJ&=StWdAKmNsSnPzBjnF=v?;-;{%%nKA@$PhHenV(6M>pY;i58766;g zlU`krBt)Ja%K=bYmIQ^BYrhPk7H8&vzjF5nL;W;hb^8hW2kf2% z>R980+WCDDga^0Ku`&z+DwSJEDJ8_mO-Iqc7^e)@u6cG8J^Ll^yE{Tnk1)1(w^G7s zL?z}2Y&{j%IO>K=_8sUk!lmsvOyI>Q-=1U_ys-&wyt zDE}kMChqlfSNu}@JP2o!MRrqViymK=qqd{sQ32z?0U)wW4y~nN1sV)r!zH{G8!<4i zr|4{;D`?V%#;>)PBZBaRAe#;WZ<zF6T6NcWYqJc@0D4zI=EY^XuRH@PV0T z$za)C+a#}+^U||ax`aq9hhc=u;$h&aITfpDS}@5vx2wd2ds#P0)J3qcJPd*5yNL%u42iA+3^btWqaa{? zNKCD|)hEE5jv2~4twAZMUq+zt=0u3_q7y(z_v&1xK^qWg;HH}-Hviq z9XH1ABO~8OIgwE;3ptSeVDoT7pGkIw4YyrpIkJbp$~ROQO>kf~BmGOgWu21Y78W;g z&(=E4PDHnWol!zQEy;Tefg<_KRk%Kr*LGwP1IZDNpiP_UoTpyM-LX13FA_QAQRr+n za>VzX*1NP|Z_0VJGk0mw)$cdz3wTOCmVX~7?2O12!=@woa)|}mQq3^3l}RX? zwYDXizT*pCjthjxJFV2F`xvYu569Mn862LUw0m~l6pk3Z#9ku$qsTpPo3FKSuj5Qz9`%&}5mprH+mU-C$Zvb#Msk<>gGleN)&OKJ%n~Ps8){Wl=>!cfAoR&DY@heuJ%d z=Kt+mEhWrXr%cSIX*w#)UWtq$9C`Ag z245I|h!6U43BY2jn~!Vd!N6I@GLROGJ<4h_RIzb0qz`V7wGQBcJ2Bhs(uccazn;sy z<5g#OUwCa-QGsPh#%{d%o{KQFKHoyOuiVE>j%) zN%Txkph5%GVIbM~YpO{B*u*&lFr}qcvO=x#i5xf1sf+6avnn#EiK1|A!YxtDp|>O#h@o&^yxR)KgTDmGAN( zsVe%yg&~(^Z})5UerU)s^OLiDFJN^V0rqu=VSiir_HqP>JN#%(VV; z!lk%L$&{JnczCUMhLFWWNz9u|ne`jK)njsLu#=5Xqf9F41UUsBT~CF+p&K#fs?Wc> zp1Z8S_~7Ac{rbMglOIT}7=5mx`nN=gn?q5S)cK&zg$6k18qY@iyKH^(r26!py;U?4vL4RR+d~Y1#yFbELbI?x|(xuCNX}~v>68Mx6V+IhX zy}8n`*ag0tkWrHE)O+zM-W#W&rJ!^z(FxbT2e`em+y!>ka2BTh3;+h$=2jkJ(`=%{ zD;Imywh+{v7S$PNszXdFdme$O$8hqiftfjV7x4TJ_Yb1)k7DXf4!SdNl=(VQ}+a_x69tG97}aqC)W$H#eG3iN1qjf zBgpphCe5dXG~W>S6%d0HdBNK^Dk45)fOr$&+*MewQ@Z8Y^G$yy@o1-BW6(>GBlrExs zxKU|2%@+wyR9qC9e`!2%>T@SqZC5(hG@1yHfD`%*Su+h3_UyDy=s$K3y<(B3`b&aU z?H2llLaui3=h>V=l&A?T=5U`PvHo^Qjf+jITH<`^wW2VlF1QAife1`Qw7YYJtX;)j z7KEX+R7rR^S;ne}B|6$+x&(d>s)C~PMTl=4dhwJ~h@Koa|HR@AM49wh7 z)3hvvnU$z_efbz_Aw8axp%<KOE!{o;L~5f6*=S)ce`ksLTl7mr+bWJazewAf+oJdZv4ErFSU*Q0YIB6X||m`-c5~P%R%iLo+R5`!H?c)(9RbIj=TY z1ZkWv-Sg&@hy`eS;*fa5zC!R_$`o?&bCy_Eq*e`bKo=wO2prD|tEzi$oQHaY1bA$! z0J|mANsRPSO_xt|&|R}cJ6x!1s_WnJO~a9jClhpEr|^72{vQ^+te@z%);V)`T@W@K za<#d)ddAC~tcTO1#4wvl@>ybDK3)aK$<0yiObYBwUCRma_5`8hX+p+Q#B~SABYp_Y z%VgCMD0dcO$0>cdr zGrA>Nj6mU%+n}l@x{{~m(Pby>_!E4!$#aw0rZ3{U+BM!yFvTA56O4dOP$na8{Kt*x zr@rc-(5j`v2S+N4m=0Hix1rybD&R(5+(3tdPV%wKf7sQ-w*j^F2bqkv$gMVq8sd2z z_>|~BYmI%oLCIvp>nw|v7ce|i9Y7;x(Yyc00mTtwm*0vDFX3`U9LH*zwgUujBszZ#`7?tk>r9!Ml`9JihrKK$N&T#kkH z>e!~v1ydZe)8RlYW&z;AG5ss8YJ#Hce6%Ps@u={`SZQtjt!ADwYw&)-e6Lv6ni+2d zUSso?KkwVh87?F}*!J?>ofvIy`MH4qFP2E71Fs0(Ko+KE@~5E|ViA&3{ig;1+3BTAy{L%#5hEzFiCQXhUq|A#?64-#l+01c~3@Q-p&5 zc+vlN`wJ1??ZO@!c?xm(p=sfh=}&9x`Nzx>vDrjykd^F-=nHC(6h)oVrWpbOHm-=~ z!&KR@W#&}dbwBL!7xu=21lg@(Ir4^)A)`|nhO>3@_}=$-iUnC6*HfZTG@(B|3llu^ zOa??)8>${`K}O7xmB{@E@#q@;!>JjV6mB$Gf;bW8H?2-YHw$3ownH==VZ%7s5Wj4g zmJCM@$g*>WOY5*a4!u}(pc=;Q#FtfXsy>JoL;+W#`S(9`!jxn8@ik~Bx!b2(`h`HW zUbqc-41_~W9=UzpvtDm%_hup6@;_I{&N&ihtvrRF`{1xP@Z@)`N83F z@LmNvqV$>NuqP09=Y{K8&k+BXDd7IwWkSO3ap|f|GK$j?Oj4gdzWsTWV{<;h-tFt=qKOe zTErDE)y)Py`O3FU!@sscZ){vtv#cyiLFG05ZYqRJMA&{Ksp@403I$~Qd9c2_^i@!3 zHEw${_rs(`#79vSXo45Affrm8a^29YwqokG-n|-fKFqx;6naL|u2x7f<*O+8SG5q7 z#juQ7N<4BA3zXqO;3Gdd10z;!@0F|Of3q_+wsOpcN)wlfzpB|5XyxsTbuCcU47T4hHExqk={NYckD9NJa+7* z&XUwTFLVK!1)Yn=F|2huMvuyYf7BwxOHzWbx?4No=HLAl%ipY$ukUiZdzI)>AV{p7 z2OdWaILyTE9mu{SjKL#6gmUZF9+g%9DU!=kw)3K7o>VfTUteA9#-z@C=4ur`ENfV; z>D@Gyen~Bi8Yml}Oq9#J3J&CeqUHlH?`2N>;Ol{{9q$gFq6>U$%@g3(vj zfMJUKJa2{jDWP_S`z-}HvG~<{HM$Ma-uLZEkdeKKpK8g1C&8nF z8eKDfx##rcsQ&n)>y0z{6AU z+{Sm$0;%>+lv1+TB>^TS`dWgMwN<%NVBO>%Az_{`1{s8I%7>FH5}Jw#ZyAPMe_K)u5DWDUOutQui|6cQ@WD|3Cq`KDgeIznWdz~-@ub0^w@;w2@U6_iB^X{ z&)vq!zY!NnhXSD>+~vz3ne^r)ORi*N4tXMH>qr}6tM!d0JcR1nA~ zQ&^?UxAtY7KIoZ$I&bx;S6?Ngh`o2+M)IV-OYLj$CFeE< z=6pPOU!p8;-_c8kkgB)e5Qt8nibW#|6o;O#CJ36P*e5T?XjNJQ%qO5!p2!5jZQ9Ke z?^Zh9hy!$=FE0oVsq~h?P?E&i{@4W}mZjtVz~e?3_8YcFDm}P6PZ3~NgT}#AUu4@~ z#TxAJ2~@!rn!5oJeYLsdF2dpf%WW&!_eX>NcoSdtR?nB+zxtJqqmTEbN34Q=Ec-@b zZ%J>Nrlq0E;9BPLdGLlH)JDgYfar)izW&1?Q@&8?zaQ%@zvvbo$gFnw)pqz9o^=%37j6mZw8%InWZlBXkeNngb)0II&3*G{ zue0Z`4P1TXw&v|H^LBfAYBH8?pZsSNImMgDvb2I>0q7Myhx{vcufIMqT`qphkbya) zba=(!Kzd7?Q(pE!$N=wATrA6$M%PV{8(FX#AqRT4NbJ0rFnCCej%u-Rr#&$d_q~1I z59Yvi%iB-bBx(JT@`W;jz;ZxB4n4VapUS#n5be3>I@^De^I(Fx71WqVWNx~3yYt^T z+?&AB{`0??I`-j)V^}|GGM1_{SGJ27#-=AfU1Vd|E91(~+Ja#`&nadfg;UkA3k1>l zq~+fwfXN$zF^^_v28NqoR!5KG1f1S_mPHp6H=P@~^u$_eC{fBu!Go{6kjzR8Cwhi=zKr zAiRh%ss4%>9ul4nl#F(NmRh2$V-H*zcsv#b`vvrxewXEADTmR#vzIntGH!_?dpw+& z2(- zpWQqP#hH3?z`)VhnAao`-*VMx?4*P)=`%YK*)ES^wTc#Xgo# zBD8$LbUr14CZasyx0ElMXGg%>Vtn*W$$;cIaVLX_<=?VB)_jzP>dc2H%47N=@j4jO2qMWxHcbwi1 zR^E}<9FD5x;JwzPZPYp0PSOsb;4DDL(ULY)2A@BqLJoJ4)L@Nu3A%5*vQDUn(z;~9 z%9q;`sl&f`S3PMOn;8d4v$V(kmgQ|hR@6*na>GGp2uMNk!!8N)YT1Vlc!0ch+qQAS z^82V~(MpUVVzs}C90--Zd7Vba+6g>2;?tm)A0j@hD6a($9cOf{aMoV3Cspb_c1e0& zlrMdC%%}c46Oe9)oY!Z8+KLDE3NWdnb5y1K{(?n}P=)Y@4gf89M?y3X zfO?n3I|}Co2>1MC%6&kT+9p3oG8GK|>Ke0_@3mb|UV1@XenGqR7F=isFCw(_hff8z zkxQTZ9Ll06gKDaUyqtvDppMW1Kth(Y%dgvc*-?f6inY*z8+dlT{i769+)r?G(b9bc z^98b)Wx=>USz-AGN&$L+t8GawFd+`?Rk+7R-L(;wA8dDeDYG;vJsW5gIuZ#|nUDhb z@8&l6Kq+qUeN?=mNov>H9KG~YK-9Tec$I>z7V6G4&O z%P?e}B;(5^x;HzeV=Kq#GM0(zJHCp9OLr@R^A*pkeq(#KTC(=W&wmE*W0ZR5n>fKo zDkIPi#6ZPzu8Df$v#d^6yJhG^W_oyP!@*d2IxbVOtHbrax_6;2>k6dIR81eA?1%LM z*_#{gIb+&Gb8C0X5?v2PGA%jeKk9yWkzc605SuV{6?0@ooS8Y820lmnnq1b8zZ^so zWie$X_cyR5o>YS(5YxK^6CBi6EIWrCKv~)KeJkwW+{Ak?e}IIf${={3k1}&02EoO3Tt6A?w1c|WRTxG#MAGLZ*qW-n$0esIh5sc;JB-)4C?wF`L< zp^JMn2`1$d>AG=T(7m*d6`Ya=bm(^zTqgOKz~DoEYf#~CeJ(kcx&{PJ=0yK0UHZDe zQ$kT#fdkNYlAk@F{1h*}JDfw*)UTYA1gzBcu*jGEdPo#E(SI8lnsT!AoQ*dYPvhV8 z7ZOaxLTd+!H2NxnqPuz~PRJ)i$oy~3{^s>+v@V|TeB4_xR4il|6oxi}?oYG};lJ+= zxzzEiir&!>p<2M(Kt_R@fYqz zzw%w&+eLAG0~gyD6Ut!)Y`>muE(hg$aNI4h=!e0^#N;~HsXPMtwv7|VJ_P9=Yia~o z1Aq64>5$FAhI)Blk#|{KmjiDQ(8KG~+$> z`S%{Cn-t$+cwex&A=5lVk3mot{W|?54_p9IT#UFbnP40s@A_gm zs$~)J8UHRBmks~gb1{Mqk-u`Ntp~lg4Gkr_!J?m!44=H_ z60!i>@gtUQq`F~dZ%;y~qzYSuLE^R4okp~9&2VA5urGa0J|Dd+GVYj}2M<~_84IYy zJiw830sIk5N*2RR71?l7kMVnA6Oc=;GXbQ3!uVSghj6-XXmo*{^-BA5s;sXwMpu5D zLkIty7j%X0{qxFn77Hwj9K1b*41VQ0e0%Umy<3Nu>MUZESN~j7w&10M^t@ui_<&T; zJ~SZ5Qgm`m9>81G_mZKBm+Ya}0Ey@!^ULY8Vg}@imG+P4HT)MvrUd#T@A=Z`7PkV~ zetZXgqIugTQ<}=c_uirulMA>vhWiobg_fO=R1UHK(LdT}m1P*T*?bu>x>$rl;7`;y zkS!K+XA>TcO5MeTzD)F;+1xWz_Tt|jN?9-BohS1ZRA)EYg-fB^il6n{ldg|&xGfsE zdWY)M}#Qk*Zk$ldLngH$Qy1eQx4=|TlHSdbz{wT@*=?T ze73K^lk|O5ey<-6$CjXqMW|r;#B?jDU(_^liGrV-SGvuG>5{R0$VO^YSLH(bL)5vX zPu>AS3SyNZwfpK7V6e95KI**o(#mgtte>~R0}(INF#Q!iIZu+rKZV3IT7~)GGEEg| zEc)~rJ`k1w(4I-?e1#A(ZEzq79j96vt0yPCqRGCtn!8eOH<8ayMJLJkKbuqs;-G_< z2}zrL7LR5-$S5CSgay0tU<*)3z2097%#6uEkeNhPbS?YtQN1hyuTNPCxDV3Esnmvlp^g%ey0K1+-KE)yN?HJ9( zca^RCQe=QPYwvkn8q$|Z)Eaz~a#QpPE(IxCyW7`-66|*hnmv9rov2awd{;Mb`K|OJ z!YZ47E?vCpN!3Z5(rusmx)lK;|LK9oFu$vmA@Pbf|iusRCX^Rj9x$>jG)0x@W zcPS}+-zxC;wl)F_vk?>6Vvm5w+KG}OP1J9gVRyI91p#4VLIX+;H37MT6Fw9&y_X|G zJ#j-?knIrjhTxV6eT>n>68Bf654Fki`b8aUzM(I(jqtq$)kYUXX2h>0?BcO$IG{2B z>tD&|Ud^fc->b?ooZ2#c%pe7}2js2Jr16)xSc02Y2&z8}Qc06klADx4c5qMp&T7zw zDDa}45=ErvgDUb=v3eDGC`C*U8|R0a;=~aQY4{u)0ziRy&%fZX(%@3+ormJE@=`pK zdu*yG`@)Z9n*lcYmON123;Dy&1eGZ!KdhjT`++=wU?X;ClrTTSrO4tKS2j$e`7K}J z+1Jvh>lYmVVLJPtEW{N$nJWe;&#bJsoJ4w%?mo**V?tcTBW7vo50N zZ1V7DWjQ!}gSf#}CEUw7xskj8$gZVffcp6`(Q1E0dGZ?t%wR>@@8`PBS+y~Lm!*L> z2SvLoy;(jY3)94txtX2psiM&Rqw4sWtHt{ZXH0-KgcA>L0w4GUn>56a?DoCOJ3ien zT!uSM&1C7c%ZF4_H+#Qrf|&f<`-iE!X;iqW>+mvVjsSlBA$V>R&gmudC0}Nk;o}>r z58n85*MUiMd0HmMXzM!}3=Dx74vPH`a;( zRfd{Jd_Lb5>aG3YdIJ}P5)LgevS^^ddxKb%ALbqq%Sdu5UPGc{f{R`MP z>a~ciA_<jQgFdiDgX&flm}OUfx05{k61?c~t7eBfZoa{~b( z{GuMqPMF|spSV#T?0DQ^Y%zRtAwhUlF{HtxhSqTa>R9#poAdrByJ_%yyWmJpn)@#; zms9oTW;H(Sx+(-5aPbMgEidg?J;VU>=8PH}Koe8HO8a3_h;=XZE_R_}QK1_3ozSOU zbVv28T~6{97_JVHj&%ubIJ^D>^FCa;A>G=9OZy1iD(@tz&N=@QoKzS0bBVb#0(0bC zIg}sd+&0Af_R>FtkDUjC^YSmLxS!_$Lh+cJcEZBS|5|olf9?6(XZm!&0Yiq>L ziqU^$2M6GI9r@lSAtZtKQhqCz=b?Ss+`nH>5lW*CW(Y>5`}j#M9WLYepmb+lfK;X!;Fw<*2BJ*4=xZmSoVa<^-jtsuWTh8K`jSb^0d{vT%q8Zr0nRM4XyN5 zQT7ZwZ)V;m6~K2`;St}y!%c$)zeKMisyN=$S)nj-kkbbx8E1`6Ba!x0+){)Pm5z(i zIn!=PQuXpVzdt)7EIm~V{R=(C5cbBC4{2NCY%vp!WjAU6o!F|E(-EK#xDk?N#0K^> zneEE+^}V?R*Ic-FKRSkjmXV}Fmn3Bv*Z`J~x9`e%gZ=U?Yp3AzJ&g3zc*KAm+*Bt+ zdk@8rp6?5BAsIT`im95wo&Mxc4n7$k}DL1#gx@FYk3vO_}ieq+j}KI?Dt>5n?AX#rBaayI4@MO=j?>9AjYXm`}h>33xl+R;_aj!4_TMY7u~Le39E zl|#P@O;j34EbMXt1k2bTO&@nQq;3@nwmd2h`cVjMb~H7xvsW+72XJPqC!|34e?+UK zHZIl#ay+6~tSF{{4%jpUBMCBni|3_Zyb*g<&iYGsD?%law%3XKD4Gw!q(cRPO)f$9CJ+q1=#}i!x zdN2al)4P|<_ENVcJ?R;n+7f@}Nc#kmE$;*G8~YvVMVfnRQ(9Z*n-?#Pn6Cr=>@9g) z!eDqS^}M=PDReslRv-mhA&B}+gm|+Bq_+i7BmsN96r#Un8@X|uT)o$?$4@Gci_gvd{HqEAB2ODtK1S4N{u%J_cd4G!NV+4MRSzPk!!m zwJ%#TVm{^k{;%QHm_aL>C8p1Q&lr$Vhb#F&|27A$mS10A^P% z?8Hnv@sQLkuSB)Qv#xW09MpbW4)L}oVrZn`|9FLAoI$4CrZd!dwntCHmNl|1es zQ6=Gm3Eq>mtv3(oYD8Y}WT1_AI`w|;e{#wQ@7d->K7=3duV_&_N6y^aG#bI@zPs;d z2c`>O)eMe0ORO9GMGmVY=|qh*yfRpS?ClGE##sWR)O1`_Z|dxK!zXR>IpPa3_bQI? z0E@KO_mC~^Mjq!lJ&H_5g+GQ25cD^I>5^k;U~d-#h=U^Q^Lo;R=PfIsa`Y2NJNvgo zCEHF;bWQDu(@a1fN;75mkzzY+v+#^K9gy^WfQrvW`N6{i-jf$a2sgltR(v)!QJ&5G zEK+ashd~2Dr~?^blV~m^_T<-<{DO~OH@jt1_JT8 zgskM})ZCfMfsqg@fyHbu;yeUHMslH@91lB69*Q42VDgxzJt@wa*Y0l>j}+$QHYBX6 zr1q9ObFXt8C#E1|E^~T_;kwJf<_&{CiATX}My|3))p=f8_j%x3d6#i>|Hc2xCvByw zBd}a7zvDW#Q*2s8C4aAtoS&PJF7}6ByUR2;f}3Qb+(wG-$KENbnJ(dJ2-zD^?Rx?J z`C5N{T~?|CNP=I>Z^^(W{*n;IlSG4T`U*xjW9_z^2s(-J z$ir}4OSRM_4sKCJ4*6ZoZ-QQo!itT$4vKh%0oRE#j40?o(D;z9Bi23j?n0FO0I& zlSeGoncw#z6aNH8TLTx|J`6rVDjrp(wR8-=eIMvZMk>cWGBnUg6gP30o*eLDf8}0% z4A^L}i!Z3Di%Z^XDET@~4Z7}0as3UM?u#vRds-COGeO7{FTaw95xw0LJ0Tbi;q0ue zuA^JevORtEH-NO{T)N*B|qJL<~n(j3AgubA^v4K81Rv@_bOIsP*~y}ZP5kOuba<2Z);97tUVpI(yX0Bxa zsfa++dD-_Csi74ytv(86ubA2`t0&)cr3mic?0PbJ(eCiOj0&RfPBJd-dKt}L)F07! z{O?4>(S2dyf6e@P{_o76p8;~v|Ip;_P%GnZPZEn(-u5?m&OqVi^wj@|=uSEsrUFul zX#S2buypnh-|OFa(08xbkWrj6ry7D6v-RfdMI!N|sX&f$e+d{+NpSDe{F@){gySRn3?8SqVJMd1g7)J{ETr*-N82JE9cTP>_FGTZWKA zl!--e*#j({WOMk{2~@_*W@r0p6255z<33sHgg)`C zs=^aCU}(&n4vv$KUqj2GYJ6X z7|cdviWP{Gu$)l5&IUG5ZsQqRb)oCzHo~68k++{xRU5e*|IGS2T?Mq`@SADz9GA~Q zFACjo{#~b4d8d@eeC z_*`}HDc-CoHrkRe2v_KIetE6KIl$Ez4rDTK9?-1GBHSU!i@U0OUR*+<*-IwJXNvY#~6d;AMjEhvk74fv4ch!}Q?Q}Jng z;NPcu@hbeSgqEia;4FIc^b13fp?{`Mc$rikM=7g?&x#=0&5DkQu2h*xX9v{#J=rUd zIp8-^`dcCYl;}$nd)dd|NF)koTx-ZZ%N`qZeWOl&uTW4+8w3lZdG&o~3$;&!tXuc$ zW8c-?nJ{ETRiN!!o6DnnWW>gPs0X5-F>DjW--|K2so9rj$YE5nnpGdJ8h|E=(#C~93bpo8;+Kt{!WbI0-X)jJ*-Z7kRcIFp4cUtKbGba4`@q0+gqj||^ zu@VFVq4Ud0QU=AqOQyVHZI_dbu*2xT!K}-#g-W5rhQvzx*cyrJAJP#-9A5E-DE(7b zEyIL&YU#hXK5TOyi-yu-q*EJ*S*OA_4KAFNtfbWh62UXP$64u868_a@AKuvtkKGU_ zfmT>L%w1sP)*7TxiOaZ4i+mY7%j{bDaz(#<@0S75Of0e$5(;6e7k=SY@oMOIGf}LY z-4A74Tj0Y*OvMbf_nq(7vT~T+#M#;q`LRiG_su2`)gXu%UP#QrH!;B6CE1Ib<&MHn zS4gZJXeytpjaJfi*;1gWA)UKQj=NF)NY!2&Gw-%4T%lH$QLLLEF>4cjw{mak-3U>f z`1>d0*SGsO)5%LP%m3I*qbqRk(nxmB*h)fa40W;WNFG9qIRU zzxYvSvOJVq+2h7zKKRBGp=YQLB(LeqyDC&twbF=c@ijF6)_Gs#+qOVNy_8uc>_WlOtBG$5WBK|jdr z9yrGx%3CGVnR?oH{tW$voq^cC^y22~+`KVPI9(m}-hsGNDLJ-eu`Ldn8u2YM^-u=+ zr_;Qtyur}jw(d_7-}SaB!;qZhNnks`{tDDcI6>QFr5aAe2|Igek<)*x@coV%WWEqv z$N=guD+y?e8ECYf2U*)wRICQDFB_2e{1vHe+>k$*5l0ta0FL|VtH2&NSFi1^9t&)Q z%~VNRUP%9F5aFd2A3`aV8jV!dzm71~XfFo2E-#2pTk3TCP}&HS9WT@zFur|iacC&+ zcqNk6Xe?jM{v>2X|E!iwg1ocp`5*P!J+YjEDQn@-W4Cy}!b$9{r9lK%9|>NV?iC!u zPG?Vm6TJL7?7le_X6)VvFY(oEiLK8%Ce|{|3mv3*zM|=Ita;lid+ubLM06RCerq^i zjBDXRSR0owAik2d{0$?~w_&rz>JSWcwlNQ|9?ZFs>66RtF>k^q8rqp8S zkrXd=SKseAJBH&FJI04GBRB%u99;J|jyycQZk)qqG-d>!g$uV*gt$;DQd4oY;y>VU zVog-IC3(OR*}2SIn#KH+;z23Jzkq+AO^Jm>MEFIdEG(wtsHG80zvN z;-KlOZS2@H!kG*H4dOB5FE8;;s9&rP5(nq;Ha%saEYY4v-a`T!yGu3L~h< z%m(IfqzIpqHX_ubS&qEUO9A%QZ~Y%r&_Ayz0l(3Z^E$78CQNY03rHJ6A!k{1Ha}_= zIvQ#bJw!yi<2fVMNI#|(5nggGJk6&Xsjndc9Wz)1f6(XR7U48|9rAE{?PnfJb z9#pzsj%cc@O9VI%&;Ie#0W9Q1%|0N;R@9Yy8!>NWIG{(oAzQ9Yz*r#y)3wJ|07Zsj zH|;w^-Vm1~yBNO0D4c*x#Lc0O;!C_~aD9DmsqodOn z9XrckT4M%0$xZwtww7RW{LD4iJ*K2ToS796E@!a_StYa#Tw|KL*;y4)MFz~C_daig zNJF;FX2%@ti)F`J`xi|2}EaQ1~)X^4|F@u5|i` z5t1@(93c2`fY^`NiBQq*yVRSxW4YzI{NS2?Lj_Yz#>HxH0PPjtkdN7SGQnT%92JA{ zx*U@daj|a#dsv%o8VVa*wcZ1y>$q)x0E2qDYUDZHpgMo{bG_0%jPJ@mk(E=){l1=% zcQ*I0a)}DQA$B)f8~S*l9P`enQf(pGJQTmZ4G7Ueb6VNq1*t0j(jTWkt@0!BibuPx z03%nFidF*rRw|l;n4a6IXjKc{eHOB86U!v=O>9pz_w!JDV(&+DX^39ZzsC~=?>(-= zOIu|d#2l&OrKKG{q>}`+Tfobqx_5cDI)mSudF7T8#0o+nN7_?~OjIFEa;J%E(y@&b zd}moUbR#jJsG@GpKaam`ZxeeX?IRCISWiylp7^uBL=A^1Hn+~I{X^x?c-EpXRvOC` zcxzB*394kyu6=O}nn#8igZHF&Gz|wq4Ut^yG_J-ZAtYFXui83aOgKjNm_?noc#ak} z8@u@PY?JAuX-``2V5U`ST`%OmL?TL6C2ZeE@Ve^wwmw@Ozej}{d)$myJ zf=U4X@3SotgdJ2=C)&6Z=@?u%Ah=sQo@vsfM{51OAxNo?G|o8FhHt6viRTUtQRpI1 zNjX;&dYaJs@CDLupFe5@Q^UR$<>p(!vSkoDb(Fw?uzpv};{Ay3qE7ab#mH&OcZuI$ zX_uB8wnsEEXRctyeA1QxHVFgdFBHl2zc!B6D-z;y;n8M;2D2k|w+jBM1UG_BY4IS+#8O`&3`YzyyP z&A1*tBAfVGqn@yi3rpU3lWSTb1Ux+`7l7dm1|n_=UsG_$;;$!CLL9Jd#;jtzw4tow zbSn4O$OTb`FK1E-Eg2W_8=}CHQuXtaizfnGhoWBm>ZD;PZlR@=691cRI0gM>43mqT z>zuh^6<3H96Br}zCVnQOwGPX(NeuI~<`IPrkuVj4g+%nNMl|*{rh8Gi9RKF#w)=^5 zuII7S^q&uNl?}sjcOpds{RYtE^7#XTh{GpdYJcWVk|UE*=HjWi+FRdn6nfEIyxl9T zXFNh;#V#nuv#s8$-&2*P^_Xh*B|o(d^rXlo@RH1NoNpU#$FLpY8(#Is*fY!f<`iQt z!C&1_)jLv;a~~;2Y>s;F97)iJ?zZlt^Ifi@_H#TCI2>fXZS8mWd_O|zHv>lX*UPu! zM@ycj;~xJ%^X>l(ykr6JN)olr=`McIZ9jT$r}5n6x_Ix?v)cvr>&m@o;d#&D_Epd} zKPWBMsLF@60(!x_O9YT@B7V(K9hqk>Oc(v_uA(prV5nI`1gl|ha19hfz-DsY8nks( zgH|I~pMHJqM(<<8-{gJ_L+Tc1czTo)oC-5!I|Tn?-ve^~BkL6*;DP77_i0fzdj^zZ z_$Xb2mzFU17?!K?KyXPI`L+~AQ%(O2Kb%10KA@1|wH7)sUw_&Lm*x;tOr?Cu7Fu8a zv1g$s!g(R1gH;iV{T1fA5K-C3^{_O#nJ3Abl&TXSUQgN-F~e*pcoUb+lz?|?za3<* z^5;2{8@W^zY82q=alxfgA+o#qZ@B>k-!PEebjSZiNXlpn{5LA|RLyYpb!RT7RcvQ& zhPssrUidKg>Hv|WMH1TgEgShWqB5H*skI47M?fu+)#R~R&z}_aRS#J3TI>O0S3`_x z(_-_K3<6==uu=m)Cs|?FI8O5mb~oC7g?`}5cM`p~m*nk4e;Na!SinaPqP#9rGxC>Z zts&omhU+YU8_xIclZKLA4mvC6RG7@oMuf;*nikdFMyW|W5V_Xy^;l@mlY2nNyg2@cGgRo$#^teJpxK9bCU0w##B7)yJx>6c}gM_%PnQ)g-fOND~@Cbm4 z`{%z?gJS_$My&dgluMHTvj9WZ*D?|TgJ)lcznrG~!8acLT6?id1G=6a|L~o+%y&&2 z_;+L7{ZCEGv08*OLhh(bkbi=57${8yw$7y#r2R@9^?OgCv5DD^xR+Z}rQ?&K_k%&n z!NTs%a|-=P%Y&Qu2PLZx4x98vCTvpUzlwiYr)-xx#~6DlK9f08HV|~)#i#-h9awT6 zDTYX)JC~bb^girD|5Aj*KoCf;fE-Q+;N{U)y!5zjn~NxSQ81WuZSX5@{^`g_JiE`% zp`rqxvvlZe^wAuswfN=iqGqlh_S~{@Y{Qbf=oRbfM*{pJXsT}iF~$Cax8gp50M;Z3 zI`;A7HF1e!^YkWqGOMxp_IW|vKTlGar=~m9 z`dLD|uR_}49IXF$4&@8zIj*Mb*x@&$7C;`E4v+^P@Oi{ac)sk6{A>q3lATg?akMm{ z!#f3(e{c31_YLITs3@hV0{@97J%o-~^DrXh z)%*n)h7hk2Wf!BAcOrV~T0ND?okh5d;uzt2M@3bN*AZY5U`tPJC8=vL7=a{h2hlhC zgrEbG4|o*XjsJZ5mbchc#wT*M@p;(LHTu%&kle=rSL511LIn$N~EhS0n_NA!u2*uT1Y! zz3-$xFLx~ClVKSWH~mI+!uj~hNSdDrO;#~ra1G90hlxVR#oj;8WADqIUb9y+9*wuS zn_@f|bJ>{Dq6=;V#)@>42eJ^Kdi0VvVtR)}b}OPoZw@E8dhhRfW4RJ@2y=qWQsik) zE`E8+=9(`ae%x};sX|q(b-s3*{XI^UG%j~d z3$7*zJThbG*sa{D9~p+17qc_T6VL4VjY(|n2yY#NT$(XTT3ZJZfj2hue1tl|ml0ZE zldB2WOsiMhB7$5e=JpAf5(jHP9Up%%VD4(JACuv0{X5hVeB8(mZEZmE9H3-eL#-_MCwfj7_T3byQ0Qm)hQ zk`sQyF!0U)v%GDd^<)40@)o%ta7*4*Ek=R$_PfXd;X3A;4(n=7t|Ag{I#EvUES3K% zPAl=fobHn#c&0qS}O%me!rg4!d5MntpJ%8+?#bm-gcvUYZC=3`2E zG$q8M2BUxTNUWBkVL3iX?yetU%uD&?RCN5Jb2@_DGB~Lc%5@VDKlc zd3+^<*w%#}`}1vgk3V1639e684i{~zy%iYd(t6>Tp5EpF}1!MtX z`yZY#|DuXUyKVJTGMmlT6Mc2&)Oc76alAjr*51+a+2UJ?-%FtxS60ApB|It;K3)PUZe9F-+ghu1uuCBF z8CC}aAbXp#A1=?+)T$eOuZkgwPU!+lD2^rQ&MJ3OVV}(?50_aH@Iq_Fqw~I$>X%i{cOvWOY(mM`>1M$#M3)3eRolG{)Dw zu}B34j9x!uZyIg!+!|n*>DbKon`6+e1fT9q<`qdSH@OG-`CGe|`ICxEj}O1_KC{^| zQsLT;wYgB=eq!;8*5b8a7yBFS$jM_NZj7=%4`X+y34YaZ$Bk{W{x)O7=X*PYFKK+% z-Zd3JSa`s#-u(9V-rkNuOTPeZ#6C5ivlz5A@xEI)%_4C9*oL(x)iYI zM2h%0@;_Yw-U}+pwC{sW^byJCQ^BE|4MG0;D7|@-dCAd|^G{>kmt>9UJEs2KF?#+* z5^Jj6>b`MrY`it_Nw5!gh;lf%vAi*Tke-e<_8g=))6Y4f?D}yUq{(rg*!UM{apZun zhiBnZl+2H>uYV;vGjUIu5-e zR&q(RDjOraO4+o2-QapV-V7%c%N`H8!u|ieI7x>*(udT&*jE0MrGxME_UWE(I$v=JF>MauIrU$1G5? ztn><(h_l0}X5C8gtEDB~k9o!5dG1ovogL=R>do&&>f;Qr&}KQitAdAEN}*wA?^qX} zA=G7WZ+U#j^2QI(L#0&5TPrdN5fSv%?^Bsl5g$B<%s04^RAH7)MNmnN!3|cTv4t^08@Y+-cZw_haU)zQ(-m z7E=Tu0O?F;m9GAo@aqS!H5Ddr3;nZT5M+sF)jn)j`q|GfhS zTyE^uNZT@y&18}~UZmIghRz=fy934K!5j6}_yg`oFfond>!J+xui1v{wAby+;Z>lZ ze)vyMWYf?O1%HcFB1-Wz;J?k-$Aj@=)@77UILA#j226+F)1K4Ivi9_vI8T1c4x2aX znz^y;+*e25IQD5#@{(*`%KUO;8J2g-m~)Wfkf=6Rl>V(BeZkYji_UY%F5>X)=msSi zp_8KSoza?0HFTszZJavL6#}mw-2GDLv4cXu*k&qd>pZNmBY$++H0fC#Ips$4brq!Z zhh6+y^!mrF>ab212xMbFmJ%TCzrqH+m#|;&E#IW{=>=ji@#Ef2=g|k$?&B{es=IG` z3T|6U3ZdhVTCSgm9$QsPnco&{=#Gt?7gp))E=%xJ(5oBG@PN{|_a^#&4gAkR^Z&hY zE*Ok~Zjx4i;04`!`|qLfgF&$JM}DpT7wdH(AinYS{#`~}u&&qXuJ~+;*Iv8U^gz?m z`*X*;4U@O|P1Xs7b^wA|A=m*BoQ=!G}XEvbTU+TSA0_aK7h)xI9ItBJ=&y{%+o=S8G6UQo$ifpZNYWm1L-1T$cHgFh? zCFJ}T6P|Q70{rO~P(KcAQEI{`cEZaEcoF(?c@Usms%Zh`vxIoy=dr)Pq4c8_|B z@aKKe$@2spSSGHUmyn!Iw4A@^!NVByh7Jliqh-_1l1V@G^rtpW`vWZkz`uL+Y^{l| zfUkjY*o+p*)1FKw9NBHqssAV#A|y{6@VVOEb?ayq2eI-g@Ls%Jck4Wot8O|kou+w) z{pk=6dhhq=ywTx^OlXaL&AihS%bgeU0j@XJ)&F&# z8etH~@sXE3B42Kq#C1dVJ|4B$uninjY`Eo~)zhdZj3?rIGo?K{hpQ0iVv(5HIrA6{ zvILZm6FeLA>ksuq4(=>=f3I$yTxwGfOD10E6*=H}O|aPuvVk-%Qvq8`9Jkl*w9B_O zPGKLX$3VZmXRprBPpE3nTdOa8$ufnx{wZ8@$aR#LkjYeNHf2Ya1v1;|`eCJ7ls-2C z?}Ze}B+%v;l+!9_Gv#c(IJo3FcZz}PvVmrcByIXr;zY_~3V+xP5%@*fD2Fb+?jhKH z%!c%4-2`1TeMq^iougUuUY|Yl&|d5G{LFceZ~S$!yl1j#8O3YJz7G7GeHO?rIC?Q$ z_JHuB1BQl~Hvodvu=vITesdjt`I#hFa-*$aqyw?mcf<4>*b4BKSmxvHOo*!dl(2A> zj)PlwGZ2vD8!7mfw*0T8M&6TacF{$W72bq+Z~RMnA7|s?&tbN9-X}I6ki9b3ambzp z#X92y1!jSpEyZP4qlb9Jp=zuP#2y5Q!M+~NH5v56RXzXCJ(2)k(T3rCS;wU1tY@(! zL^dW750-8GvLs;2@kD<%3*ugoobkyW$sZuc%WUP7EK;b5XK{yBf=dhavB#^6Jm8N+ z%=wl-vza`2OTJy8YftvW^KChzsA3bCM8~5gJuSrJxKHtOR;KH}?=wd2`k$wTEl6a3 zKgz0~(zlSmn7g9)WiVRV`lDImp5nvENFy0{*J?c6UJ9Mq zsF31=q83-R#kSkO4qd%#qh9YxlC{*T)_rnfBy1xye(N?rts&J*Z0xswnPmyZ_NF+L zbLk%aftq?3|LkYSsU$T#S-ZGClFLRfvk!D8LeMXdwsni$eB~{#liF?U4WflhrgFNS zB?F^LJy_l5?4wavMM`OvA4cNX5gZ7uOu{Cq{jac|Afo1{feERLQ-H5AO#!w7Fa7U6 z-p`l9q0xWxoe1j54?7jQ3Zlu$m+S3Q8>-^xPA~qZR;U7l$dE!Cq0}E~OjTH!Rn-a! zc8D*i7dR-P`tPHKtG<+PzN@wzu$QO?@0$BjnrS=!U0T1N{py^faWtNYV|7mLP#-hj z3>o1CTO2XnM^58PzH2|td9tgO6a2H`sR+ozeLM9Et_h(3aaf2%A!^gMW;op?$$W5< zwyMK-)2hicY@E;aBtD(tm`7vK+3#2b}89a{kVl|b!>gP*35=7{qcpnjJ<>)R#Mak~h|!_iQi?OnaqxyPs?&`{WTr>w+H1b_02 z?B8l?9kt_L*gq;_5W9AYn_d2^*4os-bD5GCIoWhqh2!FPxzv#Ld(r)uPGW2P4mmq| zr}yu2)2FQFrR3qaxfr~o3)F_+1+~A|E+64|3m=SYbYwt6DCyK7T0dr;*bH=>6B;MOP#y2R9j0cKs&QVAx(08~69w z-^u@vtoMIU!GjgA)TSTqn#jSXgUF_m>9A!uZ4!3iW)QtCFq9FE*hsleki_`jo%@`> zV~+;3-6-F6sk>G0!}V;EBrQH?&9~bhZH>#C>*FH{0ZU>padXv5zL@IQvS5X zSw?b!+79@7DZm=^@go)e0||P>cc0|Zu3>uYx?*G$iYWHrUH}&M;v+PfV)W3b7i<|3 zZSUhOBfJVeJ#Ak?cs4S!i;koaB^)wqf`ONt{Z7pcW|&UQu)@~kKQ9|>7tk#NFaTvK z-7js^$Jwi9{fIzS8#uT_L=p8Gz?EbyIw+-X!TD+)P4whqINR1CRoTdai~oo`7vfQ$ zi-7uU5;O6-b=L&+RR|}w2{*rLFofsYGs7rfrFO(PT!R{;FaC6?$=I6t9jL%ZXeg^9 zwTDCizPxv-BVCepZ~n<&Ti`k|`eNPakI$+AEnWwuEa6A}Rfw)>JT>L>)<6_q`UbW2 zP~+V~b>v8j8?FCV@ zQ8(zpgC(WbToiu#+*0Oyog`=T6e1Ts_k@uaJnNeAS*nd+M0X3nz7sBE#rx8|Nb+X0qkJ(QcUcBx(>4|&+hb9DsLU%8|D+kUn~X*-Hww@>@DI(j0ZlNa^tCTsP$B-|F+{ zWkP(*hKs98{(^e(p!EtaWGssY!i~7KSPXo(BqsMO511d|!Vur3lph}Z@v8KNQXyM@ z)?{z9T)pJhR*0q;myTflBmr&IqI{B})$ILY}YtI2IN_h|NA1-C6N zbZnC5I2d(33#fdX;Ei9^HX~ovsUd9A_;Fr^b{7c^@Jt&7KcD}kZ&X#GzRf=oK~~xO ziNgObL-2I@N@^+vei5?oFT?9R4u(#lueDl5c-}29Y-{cTeK3E)BCRiN9F1w)8)$n@ z7NQ^HHN>qRI{zHkttX~ADkH1rMb)hF38jx?@6Sd|vsR@P0u^+L1qIO4r+**#z~4@= zYp*_1_aHT+C+_QUrX!p>&5EoZB6&Wt@a)!m#&CWu@7ZBS2ce0DNt^&dS;I=kD!x&9 zvXILd>871|xW43d9KzbSmAc8kD8fEq#Ust`O;fhh@`%6EHJ7o+47l{l$y8;HDvf(C z=#kB}L71PJoFwT_ZwI8V_zcZjy==-w3U7-0J^B zcK*#6vuL9N*9!0D)sT20jUqb(R#bI)YT@NszMRM@%TaMn*+>O%EN5|k>x)m4s)?xnF50;Edj|3T(Kd1D7}IGF_iw)^)kzWbe6^(~$!2s;ug4Bu826CVDZzWQ;xAVJDqo$&&x3QC*Z z^CdN&*fcenbniKt$#q>(?O=T8u;712{2`TF!hBccUBQjD@mwHhtZyen_oE*{q6 zre?H0T7Fo4gF+KeykkD%O}g`7G9l} zus8FuO70*ScBp(o;&sw_$$NmRzL1)!mdSYJ7o%z>nV0Th$OdwT-$(ca73%2vj-OB< z8TM?1sk4{TKHp@%R%zDhP&Lna?i6W^9zRvr-3qwwFZQE9%qt`!?&Bz#P7t4sP&=QT zix~(5(5`o}&2~la&0Tqmb@Qm3tYw9xuJFb-gRg5{F=jo#s=rU;rMyUSVdnE1%&1}U zdK>%P?&SvuscZ8|mID$Mx&)i#Dv!jNytIW3hXZ?WeEn!>83=l5QamORxF2fy?=y4&Ia_l| zLC5Chc+6_5q^6V$`!&sKn(^FzIV#<%{LeJ{>3)sBx zS5b>|Ty(b`c`6WLJxmI#NDpg_PMIEvB%kR|536*dk+M@3hZHGuZW8!ym>KEQyL^E+ zvs`lZq&9Z<-hwn@Zr{dYAjbyL@9g0$HAg1BV67yVx{;^|WUtPVlJAahFKTMuMauij zxoS~f_#;dhpSpQbP4Df7FU?g3N^9z&mwqLIk?xgCJ)t&RpJ3O@;&U(z?MWxYa_)T` zi(fq7w=Pw>B!i|UNy3`P0(|qfn;kuUdE}BAM5}(V_LtM1?J1W$6<%Z5CY}B5d!IP; z=7$s`1YrVvi-dAo#q-EhmH=)QsU$En(i26bL>V)5icRHPL+`St~(z zk#W9a9emUIiHRh=C?WP=-c*kz&abnD>x0Qi27S=`ge$)W-6J2~%m5?rc5<>6O+jRJ0-YMf%Qk*3qy~KEUGXhWJ z;4|dKNvq_+eDliRFC8}k@3@f~M+g6{5!!zC-+u#%Bs{ObJmU;07zeJ>ldT0zoUUn| ztKe)5B1IK~V542-WOrOuHz6!SOg-UJq^RC2c?xWynQLDA>lYem6k{fOi01@UltHWG zeHc^ICR@YiGC#W&Vj`*rAqtVNwuU}2Zq85hzSr#@)N`C(Thp=Jvirvs*rouiqoW{U zCOKf^NR60VN?o1*6_KA&Rw@>V6s(Dgo*z)h-zWNL_@Tf$}C2eEEJQ>vjxXl(rL zHC$eD8e9~3#pj3HWFqU;--MMl6_)uwSAX_if=6;eJ7YZz7+K-T*kvG5-f^afRtoID zNH|=e9>*Aa7kO_NRWG?(k5j_p3&t_W75$nY4zP&g8+m;;d;5Zob;4STwBJn0sF`EY z;dA^oX`_)fNAJTIz9L;%T%)#>G8B+;!p64_+b4~ZV=9pfOiS@Sn*=CM4Rj)fUA`!o zT*NsNWR)A|cBDiHiwy``h)s}ppMj1B^THaYca&W-l6V(h-P39(7Mt#z!c*9CTWOp_ zC9x(5`IunpHfPn8Qf~_@s#?%r$;UyG6oX?fgbDDNsxbkn842rxmQ@{&ifEHvgX2p7 zzB+%^u4$s|qTOPKoJz30L&@m{(&;ho?MRPmm+kuPI^(jgXUo8LvKMyIs(so^|2BWr zTuQRXjR_XMcvx|JAg_L&=jCB!Ai;4~7W?sm0K$44+7#}xeO9#BV{+?^i-5@+D;J6n zXpU1!d@Lo8Dp0)^OZJZkH0*#ae!tg~SqAjI*3*%EwOy;@YwO!rmokF0%aG2d+rkF}6|)`k8@1g5F@?27khJJ&~tBiT;=qQbi6nk5eu6COB6u4U~F3e#>sJr7oM zA!j}r@oFyZYGu3WExoQ~Sr9?2yojxKi@XbP=!WL{W_V+#n%z-)5ByAZV6&zQtk893(%h^_s* zXzl!N=N%r2J#jkD)9U$mC{1@M!qf%DE*7nSQY1mY+7u<17n($<`mT;FEJY4la~P*> z7*#G2Xe`lDNBP&tx2rPa^)3~nnNqV{=7J4$^ff!W*xqQ>NA4351PN1;yZ|7-gk4Ix zLZ=pDZ#Cr7`cmR#vcIU6Z4Q;}FPIw(_Fc1v7j<{jh0P>Bj0yC?@@d;LokAZoZx5N3 zE`QKxPF%kyTCd~IP(Vn{=rPKxVzMgOCc*d&Wq1_YP?*B-_I#sp?On}@@>`JUn7}U< zl4H>hHUqjyFyv^eD^B-nFkn0Xymcl`i+ez7sAF!YCj15yqc$pJw90)(f@vA^GT=6r zct;9+X~5t$X|PTt{kv(zj`$Mk{F;{gfK=e*+x|VxN(FHZv*qXB({4|uTne?g{IXx3 zia{yp?O`T_oB1I(e6AWSXNONDe-ChNbBmxKwP^De&qqtTuZonkRW^3M7Q$8TKqJbn zh&1Zv8R&Q|{s!iXQa2lXjW@@)pr~)MkjP)k*y49!$n{{c;#H`6iz1(-&td0&pcYfU zU)~h+O}lBLTGrTmA;k~E{V6fG#o(gLa7R)BH3`<~Pm(Lyw>u$G5i1^>K+Si#XbJg! zJ^eOt*(hVZJk!pl}sCE%2ci9*02XOk?(Eg92)(d)zCD0w%K32Z<0I{U$p|yA#o{qTd#K_2z15&${75lavEtEuEo~5DaLF&}m}s`{ zPG(zEybo;-?j?}Fco#UG=9D^jRx?}mT5O!OSq?Cm_^-QbP!?HHA=PvGON3C`yV%P? z#(=GnMdfnb^(@VjPNR!4wSW5&Q=U2bgFagNrCIS$b)WX@8SEhXXW;a6P+*Ya;y1_e zFMAL$D6L`5I*_nN7F#3fd11hPq2pO0uBGm8T{_)zo3`VHF53Mkc}5BA%%JtgXV>FL z#fcBH5gk0+zRx32l>v4Bw)RbR3^i1IB~5sO?&!h()J-yyEYA24-^tD=x1rvwyH;$E zqbO$fC)|m+UFDCSpqF&6xK}RQr-E(1p|UI7Nq%g&72V8k)H-?QCyNcpuK~90>x^i3 zUtF(?q9hNU$j(G>QBc1u?uaAL^p3xL+mBdC<~AtJzcH+^ul?MN2!K==K(~l956l}5 z(+6Az;27VN3@BOMq~pXVV;mM&BtE%D*`guhR}LoXGQRq>q9J)Zs;e%kvel~vvutX- zUIZPfss9e%b#TGvN|=j{MD`;#wnBfz`r}dn#xQU%{eRKOaIt{MwE%bV!tMX;N-O)f z{J3ECUDKTJJp0{d7OzL{2u^R^zw6pd^BcZM52hn-fH`yfo=F-Phln>LZ9FH!P17MB z?Y3VZ0s)VKtj)rJ-_G752NFup+Phqe^#Gq*-U&NAVZRPasKK@HNeY*6rkS{H4AQ3C zY{^u=(YF4$DkLcUIqmw6mY6J;tfxo5GuxK978vR$_1IvVBVaP@=XapPUreG_OX~vw z=Xbm)((_u>;eyq)w_i6IP*m1~qfm$0Raez->-{0eXOZmE&?myCL>}RKU4zHKv^G`^ znPC>d+uFt6yx_%Wn`8=4cUpr{ytT+wU>5*KDd{zLs44*Qa}x3q{D4fqGfhZ|7e8Rp z+3}Y%Ugm~qunO@iJl}r3DtNMiHV~#jA&#J6xZbK_-mW%sar~3J6_-0GexkdLktb^OR=QFdnnLnA>BQgS`03V4j zJdNB<=Yt`H6y#(3!&ylVcL;DFeuYFt;mg@vNmAyMGC*&l9HEsTp?1uD+@%NT4R*~x zo=d9_*p*TE;a#x%eDd)mJqYqNJjX1xkI&E*;aYJ>$I{N}=JpV-uI~2yO!V(t;X~9O zuXNE@uAi8-mIKxxd$9qZ;3~Ydj_ZVwIOU45%Vo_Vxv~IqBJkJb>_i<4YQo#zX_nWb zzdn^c9l5HfXl8UWIV(tPt-NdA)U25?kuH-DPe$Ke1`K+%J4c_HN@CK~`n1)Uuy*%# ze33X;NUuFkZtH)nHJf4IMP)lyvauR#rlr;`CP8-`SZz*q2mHx_EB>VP_SjqQCF;YA zj(6#85dtskZ+hvxAVq9sYpX}@wzBX3U|FAh$7IK8^=_G+3D!|?jy8vu2%1Yo^##Hz zzAriskeyqto8F8gX?FD=`r0vE%186;vWUR*p;FV60NG4k0yRb;SMPxUcVu2_D1noU%0}Oe11$c&U0h- z(@aJT9HkN(vO{Y=M13?<1kX7-leK3Umm1fik(DFJg$pUk5HGV{+TJ%VBOez~m$#)n^FiGw865JMN__+x?8$SFK2pvk?HZ=Zsa&{8&hE zxw2lYC6GUMO6H^A#_+OgJpE1-7NKs7cIb1~VX)U<-4;V9RQ@g-+ugFT29P&l`R`tp z*O{iEuYgq;`QA-BV&9hct>v{TVtpn9-w!S9H}4)@vl~0jS^Z?|wkTC!{ zCbDN)qza^|G?Ze2G%qoHNv!kbN!4nCm9rNtCl)>vm8bJS6P>$7b+k6%_@tV{{1p>y z`1*tcman#^XcP)?F!4Pd3yVwzz5-1=p2PfT>wKTc^nu?J=UN&G*`D3IL`-@P=N-k- zTK1g5_I$_NP$jTioVmY!Cc^0~(eyf=?IPaPyR-ENHp#wnTY}JX>K@LI zSv7t(m={vxDdT;0wkvXvo@ePz6L#zw|I^-kD?H$#&<#)92KXB?3D@tianL+t_DNYu z{vM&m&+@P#lJJ#czdl>}bEO3v$pw<;V_86RW-m+ND@CTuMl=1RUVaZVS{H^o0F6s` zIR<(vdmVI3X!i4Ot8*CoVyqb7LEB2q`s+pzT$Tv^qbKtMnDBLDwG!RXX|>O`F#keK z>Uz^EnH<4!{8iLEvZ-Czey$FkaJSU+B7g{f9I~f1R)X0A$&YDl_Bk zxO(Y=bUI078#v!Ioo-}kCXt-BI>3pYptch{4==wQTfZ`*IhKJBavqZYf0D+kqQ|INoL z)qQ`j({MFxY-2lz3)XMhTzwk=W0bmG{^kU?T^&NNtDkl(68SHcxcOfl-+e6KWqpmCkE@zqo4*r@;WL9O_p@Q_&+)bZ zD)`8I^t1L^9L><@Xyl+q0K;g*1g=+a@AV++HjpuiS0;; z$Ig(gN+JhUOntTDEb}KLQ__<~Io>;BMd1S_QB^c&;l*ocz|Vep4oUnh*Lx;^Xkp>1 zEA5;)Wf|P;hk*3MJZMELi2lQB!2jawucMlN!2fT2W5_^aC@LkPfFne@W0WEwAuTP4 zG>CL;3@MQg0g2JwNJxVyAvMB*v{GX`!*Vv?h_0A>?& zYmX*#t5{!vts(r}pSNQ{TDHk)0X3&``RI7>)h2sKtO`I1R`>Azp zUXW<*x-*G2LLN9%!(K`ZQOos4M*xuX68LvZ&mlX))7cxvN$3GD_1U@PMybGV<_^eY z`!Db8Ud)__JHMe;$`Iw3Xt4{(VP7C|Izmp%q`1dbWS7Wx8A*!M%okmA&FA+RiSNNG zW$O$QH4LLq6&O_4rKw+|FWS<9DSE~ zD{W|(z-GU1pv{9|^gB_=1@F4Dg()3-e8)5GhaR+FqC8#$l$y@dV2b4K6e$w=?v%_Ra;L(^`su zSLyL0&f2-yJOjw5hymr#{1?mYFMxeyv?c@)xr^na#n76z;)DaOqLB2mciBlQnpJG3z5+0<^KwW+< z&ED-aR$_q`HVNHaev|rX?S6~>W3A-?t+OgRIQ~EvKP4a&>Iqk=QTaAq<~#<8w0p$K zIj_)TGEj5RrZVt){-sN9G!N7K#(}>EqIt(SpoXE!bVr+sjE_rOW%1iz zyx|rvEt3hw-=EJBVawx%d?X@UgK^M#XvcM2OJA5e+X={dcTA|5IQkDur_}pp$S%6Q za8aZS`Xmc};nvY?`(Cae>#vKs)Gwg!z`M70Dv(dhIDl@L5^>PPc9mfxhdK$PCq+* z=w<$9Cc>q}Yh;!lFJ_LcWg@2})Qsk+hp57t1WOMAFXmlq9ug|)h51Jvez%Xmf}I2} z$Rq7mqhKGAYQWA!lBI$Xn>Xz>p!ubB@~qVt1C^f0od3eU!L&@TV#%D9oM4I8Nf$De zbtN8uwj1qu!-_CQa3{o;(WY=!(~I-*xAWUJx@$yrW!Jhpt~o(rxjau(@Ud)p$KG+< zo`3LL-f!8nWebz9+@?U{WU?1)8E#~>OkL7eUcC{-&g*=Y7nG|8qzrJKW}S6lFP;jv z{j+P6wRfw&-e^hikXA=r!4L3D8%C&aJ#InwI{YL1m?)e&Enud~3gA+(-x9K7YTx5I zw~n)AsBsP8ztcfxod>;)B!eeD=*u-{M-{g& zu~M3>*U~vja4osZz3P)($HiBE=V&ch+-MqP*%)qRGN>vsYJeN+JKq1^9Ra)iYdpHe z(nfoDFeuQchDPv^$-GisfDmz1le`6S{dshcuf%%;8hmW1wMm6zS`jGc@PJHqhb z2KevUG7NTgF=Docf9Sj9e$C={%NgaB`Mf@WPLH?hpB`kxf`GyECnuGbUSuAFI4_pZJLCNSNfY)cYj||`Tdvkk3d~_1u6|7H$0hK(O5EpuEb}kCIrv(CP|>N z0#z1PO%ol4T2ph`ED;6T?>PZd0ryvj{pQ6n)MKF)nN^!)`K^&XZ@RQI_2*RFK}pP) znd7w#`rwz^bW3dT)%;K``E5U*>i-U2aq~~#MmfOefuz*G+-Mx|fJ6tB^E1YI z>(c~XVf6uYzMYfKfh5<PyH@(OisL|o{l+@!WQ>&JTv!o_8)gm?QY&X-978P|ZL z%$qu+vR28tOP))5fHzL9B#N7MD%A_vW3fe_BfX)iCmVJz|7?2Bh~!xNvtV-vuCzhJFassex(ML%CuKcL@WeMvus;X?;Urzj(gmuI0W1{ zENW%t)iIp21aCdA#&J6Q&1}^K8Vgu<%(MqwxSm|KgIgjy=gnLFHQ#XqUY=SW^Hw>@ z9z9lpSD_2_?N{mgcu341_*kl72>+9vjT$pmAFGnx^2e|k zAAvH4Cwir1G>(CJK}G!FkoV1WGZw)=O(*lGH`V9 z&*|&|Wsx7r&-z?%pCV0N{d(f2Vl0!^YB zTDf1%CmYUhFizGA@J1^5NoV#Rbp`4k@8#X1O4C+{1_8TBl6&Vuv;y*cg^8KfBe1i< z;+uW`dD^C}3FAhqf)SA8;ui)wHL+S>#pO4c0y_Qio0au^8RuPNSLK0kn!KE@;{0gE zzd(*@4_>?ONMR{q`!_R|N(oKvzMmDQlD|^b^r@aUp0Qur%6)m@1qlHIS#tWAFs5st z9fJ1U zP33qnrEN!e-FoXA%_dv%ZP(4850P9Mn+Fpw)gk7SG<|LNJX}_BpYF&eUa-wN?dbi{ zHva)Tir&?YVUy<6#_}kpw)Iz6TDtkWZ)*eIpQmAx6`Nvw{rJT4e3F>j_LZ+DPH5l~ zHnxXyj?<~H%6D=rPB*ej$laJ>{;hC`x1VU`5koEOClTMzZOO*(K*lzAP z{VCTa(n+|R*(*Qgg56cZH_Kk&fIN)JsyA6=o2vowzs9Zg{L_rJyIfdW5HJ1jk^AEE%v3~6I1 zbJQ-rBP3{<5JSw>KDv1)R9hlwHbK$%_8eBA7NR4@s!4CtZUNO~K<4kaOTk{hq8M?1 zR;6{_g8T^^EAuY>X^h|BBURY$>lKF{s0!fU>D(qAt!R#S??jH9XI_>)>YiKH)`Yac zi)DO;IMHuPkJv{A-zRCDDfY5BkQ2LVYW7cge8I;cjvA2>i_x1(deZN5fOar26|Il^ zihmz8VcIw`BVT26B`hD!e>iqQ;#L1wW9|N7zXuR;ELPfgdtq7`_Hgx3%KvH{Gs%BLkx|_lsNiXJ--c$ zOZAb@AL;Skmwz9p8@Mb!my?d^;gv_n%wEmGBzF%}YLlBUIsd2no^ei#ZvMY}QvT~N z>1RO%^CUMgyQuOJebC~GS0`aA$l77jweuwBVv_ANs-?MM((?f?@#}pc*pB}L%T?E^ zSnhpj^{>rufHs?qffIPoNjkw$jFO6q&Ef>0*+K*lkVusBEiP zmcZrD%*}(jxX@d3Z=M;FXzEJjaP${uF&F$nxd=Th8`O`B{;=}{V81_*b1WHY41LS> zu<&>GXY6YW><6>4fhJ#GO0o^|XufO~<%j9AE_zmcK=*^U5|Eh{4WQu^VD^5wW~p{V z(UTKu22Nkq%Dgd(kUhOO6hIIe5G2RAfy6WQS6_ z1Jm9qVD&Yyi>T`!UsWlN+;*IV29_=&;w9lFU9vHun z=HF0Q9vPJqhKNfX)c^$jE2!5p@;u3q?L`@jsuBM7-Z>L+(t^&mfXdmRer1_6t>qEr zvMj!Xa#p4+a&oP$Hz#AcYh+!I<*1}?NnRR5?yxy3e2){dD2I^&9*a^5XGgoN5y4pZ z{H%t%!JfQjQ@rf>5;v4FHDt~1nYxsGwB7^|K!3;%c!jJ>yTCq^>3V`m{za)^zqx=B zOzM9CaCt#Mxq?`(i*r2H|^)A4o2yiJQOp{`-JT0h{d7 zQBZmqKb||2zTHoq@d0jHhy)ST2x1aI=vp<2ul)Da{U8R1Ro!)E42KUDng#zNYadjH6JVw4 zP&5oT>_hp*3IcL-M>~L_v74bTFK0luwS&1UHt@2xMvjb9A7ve( zsks(HAm1V{THd<4Iy+<(-9@N{sR6$y#%ZsfEagJF?LLG%S?|!RjgCegj-yj7bd}-= z5mAd!<%v^dwJ|BZFFE;eC!on`SR~HIETo{b3V89TpfJy#&d2=IK{Z@v^5p)S%$15= zZ;Id$-E@}&BRRFbu|P!Rgu|W{D|coG8(u0-_ulU_7XEdT%h-Pb4E#5RY1t}x!Zb!o z?8hh#3WgXfi@&8TX?woa8n83z0V=FLmAfGy_ViOc@$5j?!>WEFTS3nItz=9#KyAbR zYx9UNpmFJD)x726Xe?gWh?Go(Q<0?eW~dgEC{;~!N9*!-9HA?yFg=Q%^#rul_H4jq zD@ug+{GaB>gx=1hl_En%W;bMgH>LIpSfCdT8jZCV&yItJuS~E2RIWK;p z72Fik^)@LiJwsBgEN4&1@`ay7^DRGR2EzQc;%A=u_KYU@55CKCc+T&UDZyX5p!bl&~!OM7cpHNRJ#zb}PAEvd9xXRfZ|2DVCQNMnrjZw^`5KRo(YypVX3QB@>D+v30cZL*}AA%XR(Ot4>%CH+_-kk*!??y=y6oj zoH}ZAqQ8fAfVpUx?*NDbr=ifl;g9;Zg(@F!00^vV+AmI5NDw9e1o6ZJzyiaU+v0Bn zGM_Wb(gh|i-8*>Q%v~r@)W?H7==25X+!9H!in?S22p|QMBac7U=>=C&pC%ovgmG`! z#nTic^u|?@X#n00#Wa9`i@rXD9J(24u!MuTjhF(jy~W7MKSB6Fy- zbry#(Zo&SoDVh(+bUqsFoMXWS&uzqx=+RrH6DPGOiRA|$Uf9T!6g^a@Yx|nZd_FhX zM_=r(LoJHcA<#g8a>eFGRX3594W8uMa#R2+cu9o4kk41UQx8jpVuqmKS$C-vUZn3u z*9~zUJXz-Z#Qzx~WbraGo8r$Sa_`Mq9F`8kc<-Y3KKU_fG@7n{n&M;4@XIcvJdKqAT>OoM0%P_R%Y@ zr#Fuv7RfBE2A-aPiuf?ZV57Vgp{`oAk$p31882ocBav}3a_LX3M zX3&!aVUcGF*tDinJKP*LfW6+Y$W8ZIY5uj;cjAcm=mrWm@sJZ!#+o);{4zyrCjWh9 zZCn!glp`o&@j0W@crE|CgSPj~2YVX)%iRU#o7C#y>h{yZ5LQnYnIC+3$3x||DXsTx zVIJY>j@6M5mw2c0A&pX+GL_H^JS{e9>h5^5B8$nI55?u@O^obUIfo6(oKnmmwr%M@ zmzl-q=``u?IhrE3KP~{7ukt7K^(IpcE*k|JTDN~{ z2iM2?aq52B55B*VE6eE+(y>ZR|E|6YhUFgr|LW^r_8je@3sIWbMjKAaw-w^sK$Xd zv&Q+x(YmbfNo{&l868DyH{90MSj;U4t88S+_YUt{U5TW`qA1D8nMsGgi7a@vD=arF zEg+CV4M1~QdV3BXiO^jN@5RaWTVMT? zIe+Lx^`V0}6pp47&xhW!5X);lva42XJb6+rgnJw(?yM{zE)+g;ICx0zrxN(fERV&1 z1p{cZCLQ4K0i(T1(v_eefc zSqTFV;AdR{2Ak=)#tK& zz}sSQgjZc;>Xq$VRoA%cBwVz0!6Kq?!T;eAPmg*kPX6zU(f>aMsH_wb!_NzB1>|P8 zx;I?N1ReNnl8qm*Urt_MU3r?U>tUn~$3C-(%VgP9^zv#^w}x^usJkE+fOJ zAZd#(F`b^mmz_T*U%+WYN8%c&08TS^;!${`4t(M9K{Wq||0l5YFSd^Y-Y{MwU=3$F z00br;YfRi&hz&`exUppK6c_1cF8s4kO3?!$bd?(bXue6?!ltR!JkB(E+5dZPO&__z z1w*1SA&l`~t&G{~U)srWSJROB_l6|&QeLmk6!ui76T$!HlMDs4S?N4ew3Svq_X;7{@b`fc7J)~`x#P0srjaR;Q& z*R*>#d5jMfD78nWJmljouGMUx;3z<26|x(vkR5@cQ>2Np5a-Jd@AUqHVlC zj>uG2lU$M^WB{<=KkvSk-CI+<3a*MM)kvb}S_2uq3jCziZ7g+3G?Lt3F)j2vsQq+v zgE?C{t8tH7fm)5dbDx?-h638H>Um1n5FnMJ`sv>3O@Zsgl;G)Uo<0GI9=Qb!I(7lZ-`ypXG3$YpDF8CC&FIIy?Uv z)jH_@rzqxp5v;_yNu7sngzIh!2^he|PqG?=dRgl;cTddtovS8d8(71M;;l`7bc=qo zs|VYu%_Cqi7HSc?mmCpI@H&utnhc^Jl*hu+DZhFT>n9t`UBZJ3hp7Rmmr4y1h3M% z+Au4^TqAD-Br`qsN@c5$4e$tl6Tdy%v>a-V%sdV6urV(wo?j9@tQDw)60pSQh}%qu zg^16tUZ}L#WGnb{ioHF_q=$nJ!+LgpTJwu-MY@9_nC%scV=h16Jc-(oVCgGB7^7QA zIN!IaWn8oMJ6R_%il#Aj@;u(BrbEj-$j~up4E$<{QsFz`j%5(xXs6tg;E2qXvQ2aE ztG1Y!TV`jfSNlZ3WZ#jQcMWi^KC))@v#7Ng02%i-u4f0y6EhRonXmduD`K=R+eg~( zfIZ(3j|{Q3b~|I?E<=869UIsvE$pWeWYnu{`3EyLj@LbuaNK3_NJ~;4-!`V_m{CDf zW~|$0Eg7DSl?q1mtJ27FPxNMzkW+uVGrtk?cxy%9{$U5_c*Mu+oRDmnx@_)zkSFOc znh_Xp80u=THfzmtwpZ9$X5-agW|wuhxKn{E158=q@6VUKt)t_g8*4kBm_8BR>t$1^ zrjKi%V(fUcC3mt{dNH0|$I(Z>wj7B_WN*mhw<21~rw%-QFni_I9ZU*XA|o$?fgXN2dKPqgW&&b6^`k0sRv0bJ z*%(}WgC8v2x)iLQ2cz^}o57y6j+Xh)^tl`#e!F_v#!JX1G|MH8Zrs3k{U-_~X|Xc& z``?*CK_WBwtizlbBy??ewbwa8_?qqe+JPH!7Bf5Fd8T@Opi6jKl15}N^6}%A=Nv5> z{Zig!t&QMkz*uz537`d6n(%u~S9OcqL z8qY2HllKM6k0aT1re$LwMuT8UFUjfpo+Ob%*mdoDB*`r+@)=xr$frq_ukyDqDbS!j zS|rofZCdG)E||tq$?h+0rD}S`6@&g-fT1pGb5^99QZ(==*8dwh zt@Pt}EN$O-MtW>nt7vl>So2D)rI$h!q+e4bk_3K;@4J!-L3P%NhwxYopgb4kydOkT zqx?iUBpYp`Q6e@X)bq{!$j9;%FmBy50Z_LKhw+e zAUQTeLa)j*)^jhzab7(LO_-S9*)OsA$*BRA)~VLYVRN~(aZtH3{&xs(mh{=2$0&9k zdL)vsZJyHDH^1H5M4G%nFZrs==Ipgz@xhhe;@POrDD0%X#VBZXdj~hn{I5JBSej-3 zZ$MK^b=zswJiPF-KuQ7!!7rhtY8trOZ5`!Hl(mP;^EKShMHFB;D*aYWeUTYufAu#& zaw?|u)q1RstAr|6kostNeYsG~7Zh~zgEqF$9Vc!*bSu*1!xH#o5gWwj08?gj4&HZq{x`D)in`P zE^JrRuFA#G7{ZFp53fpxr|%K$o(;>7rN}(<;S+SQCZ~_p znrCJ&w}GB1yJE5K=H#YBmiMjAtZa zR9>*-yP`13koI2QOU=)~c}&QPeQ&zR#1O7V#C9JqU zRQh7yzYp_UL-gE<5zjfO5UzKvr?1DKS$>{$01AH%yaOFkPWIOsy({u-?|}ddMB6X; zgqlT^JgwD!QiX_2u;^WdQnCdR`vJg{nH(W) zq%Ja(DzW@vpmo8DTNh_^27r?{3Y|KD{z;Skr;-Kr^I8qom79My5_D}FUiAJ3IeuLp z>_n!YND|J)M5=)!=f=njk6NI-^{?p4VlfX)i(t7v+3K&a|3bPFk=afKG&wBY3X%tx z)V~%NkJ$i690c`S%m2t(y5$FM!|C?aZdN+xQ1 zb$#h74>sLR66(wM)Pi8|^Q3r2pHZMfnLN)I={&zK20R|d7_C7T%Sl#sxw#xz} zgm@eH9}TL|M{!s69H4A#zGCHNfx$f#2v!XlJTm(}N`sORGym+v7MBFKy}|^0ACMlt z|0BA#>YqBQKAJbYThgrhs#mhozd1&FQ&MZ}r&l??POEvF%IWvzhIajETh(*MplZgz z{%@Gg)YXa3*g`)MH=KzFp=|QFHO|YLKM#Dwsxj;IXGqiYFf9P}2L*v+m8CuZh1F2V zZ}I#`)1UM*yZsoXz}r;ku=$-blE*lE);Mpv!LwRAaBr^-EniB|;8`NvifAm#&-LO) z#9oY5{Zk}Rg;p)J`kws{QGeJ~vH!ofj1I(>F*;BNm>aZva#gf*60`_~_WcXE+SB%_ zh7(5K%qE#h5&K2e^}bUAUl#dR(h~;y>HmTmHhn8hGO{n0o@GswB4E0oa`O#(>zva!K0Ey$8W$H0Omsn zK;||Boo9@cv1*7u1X3#(+)fxMbjqxc7dA;9;8ggABlOcMK=C|6__gk(r77TBu(o=a z)ld*N;4#{JrjL67!tQNrcdGcO>kFDX=fy7UbMXgk*O$WVeV1QU*Ws=dWv`#T^Zv$t zH!Ga>bAmt%;9q=k*5pg8fcew6yw2p)fmAiAkGvLX?VFcF?T~%HzAN1ucr-?I;7I(e z4c@=E7u^#Cc$`%N0c!~RyMtbV%GhWP80EBE2mQG{pF%I5C)bY+ykTxh=%}SbT6du# z$DS<-tUC+7=cTSEWysY{91m=V1uOahm^Bggq@w2h3j@$0a*oH`#cSLopH zRnHD~rKYvMJV{%NQ~4Uh6_-@OhEx2LBHia;FDpoApW)~I=|LUmdPo{yYL0*{+b!AZ zeELsM``w>5PL({i_@{C~E1X??8`6ONoV#)N#=+T=%p+rT8qFUn*NF#@Kv{F0;}5UbH%e%T)`t=E*t+$%@2@5{70#=}$Y zIdJF{u>zhJ4F-hZsacuWI-GwO8KjhbETCR0eOkBPRLgf^Vg}~qt{%pg zyFGE|ZS~Jp(EG=bBkp-lZxgI-@XV+&2)7*67N6k#?8fI?j_L^KAP#0Ip}}@8eihAS zd?=J6G;dd%(pK9VS)t9b$#MG3pQp{U)K3{F6Q4&A;j;UomRrb2GxVbd)?bf(zGt3rc zqDcC@V7BJ?3~`qo2*2LzsJpw^{6;f_eyr5J>MS#9uMfqfq-U^#a4$=xEwj)$V9B=J z5q$Sg9}u2&%602dF#tnid-RsS1R_9p*|M8W#D;z@(>WO~HxWv;_2eQbalwm$r)O%z zeTzJXpTB^~E~5{HRILT)fp2@WW9p z<+YWj>b4Uto6jAWlDE0In7FZ%-bU?}(3Z*Pa>3F_8~L-}2fV(wUZKA%1m@+zr|Dfi z96M*dL6*Q;5_L|mEXA6;q?$5qOCfOVcliOaAHtb=H${_2Z+g9OvOK>}p5s@N>H-WV zi6#9=Hhn}y-hm%`jj%|$=zK-D=wQWhRxr{LE&ViwpyDW(E5uSyIy2N~TfAc@Q__?@ z2A(G}Fo%zh%yQ>NQ{4Qt_}42YU9f^Qm;q62Zy*>CPK&D*15Del0TP4{KXmL-z`cTy z6NZ0n{Oy-ivsR}ClFPT(Y}+fU;iUY2hrz|R%Mu5tDF7Ca72;ZwCjMb@Bgx0LWP99S zU?ov6cJ>9b**OBAjd3AUX@$ssiO8IEX4#0_p2}`vh4%Xk>@$2#8ITc#MItkR1mV(eeW8$A}t`)jaze61TA+)5QnMmk)IW)+y(_Bm%?^pBSSe3A7QtXdiSdH!H=No%He za~@uk{n0rOZj0FKgGK|b-0>=I_G8rTu8Rm&yy~3<=o^==%Y>oE|%|v=r%e zCn9Bvp*LT0VIu;qN3~|>82=`jLPEtJx3pR^QZd|C>gU__;X$wd2I30st7o~3jog;% zn_JZPAK6mZS}=$N_TRU0jy&dR8M%~DiW&`L&{xijU%)PDrUx1Un%B|q5 z*k4U_wC6G~|F0K|SJRymQdO{Xk)YxWwkynHwsSxt-+!hVY}@6;b*Za0jx0z1BkBC7 zy9jX2N7nj!=1&x%7CW%2KlAOkCHR|P4#bQZyf#OcB;PwJ42xOHjdcpQfI0!5lhNLY z5;C}5sgO^0OzQbGhog(P%N*d!$sPuFW29c73TS40(ukCdjrEmGCfu&+cEOQ47d{*G zk944<0C+ffr7JM-@F(5_a)qVH=BQgT-lr3{Y07g=eS*&o0)&9RfihK1l=G03fA28a zEK3EW@5ApSfO{m<`~bJ;n4=q9m>YG#iqL^{Tb?gqa(^_!%gN};g!c6( zSC13jroxFY06oj*JaBwsgj4|Jz)ph=SD(WncEIjnDzV5$o_V>a1Mn4E3w?`BgF;VQ zd)o7N){fR&cdvG|y_ptti9Y0lmU81yyjH|{8>U5m z;=bkVUvYdM+c}`XagMn>Q|9!hzgX`Hm{WT^mt#}4 zk3kP+Sn*g8QkaKdH(a8R#gE6AQkQ8DQ_}O4-)k;zGJpJp%sE4lLvR#<%S&PcGiQbm z?yV_W@DD23`xAn;+MOzF)lwE4M&YmngR`<u${ooVmn zI|4dFc+2yF>ncyrjzqim;O+g$TBcz1`XD1&0Rhyvc%OSXFZbdmU2Cl0(4so3RZCO# zW@SE5!3)Ut`O-On?j~?=gYZZGsvxODx@l!BP^`^ zo=2v9zC$EIxo4(?6QJncx@Ia9g^$Qvn~1-9vyu$Sap@A5kE6C z!)}$N(Qj(n1tegAS1Ij_cAD$b#h3)qm3yXFn7+mRV5TisnAK1z$BbnKn=l98F;us+ zww5Qm`F=6M|8Y)m$`U;#`j3D2sBoB>;+Mnk;_sR_oH+)S=njVHL;lD97EaELbRX@e>M8vJPu1ndfc-HXOLS=cNTqgHs z)16Xfyk1?WzX#7u1-`D#V^BWy#))g0?@X?0YdHBIbW}|snyWV_3BIUz@boILtXXNV z#m1-e5Wkt*<~u@7Z10CM8s*&}XjeN#jEi^Z$E#XEzm9ghkt*!JmHx|+6jU2QCV zr2KE^7G_y;18RZ@=SOLf(?`(ZpxuDQs9pAzB5kbN*zhe23vk8Pi^jGiv9@pCUE-ID zw-=>aWJGMvYX}b@mqD@y$x{P0+xhf z3^I7>DGuQ@=qAl)Mj0IUxKoB|)u@gu4ZV%mss+~Pmh@FQj)H6f*~kEZX1Cx*&XGtT zR`oH7XNCT#@$Yc(8pU)DifGpoWH;6?iji)ac#m|wzm%FV@c}q;x-J9Kr@NQihJ^o{ zaf#=9Tz-d^Iv%A?pK!zbo-$7;zrDXnS0?b?gCqj(N`mfX=e!zo_uubbm@7MR{`4t z0xsw4sW- zY*>7boJ%yNZF>P-F;t^`xJtbA_=eKL^f*}qU@{<})v>(8(Chn`s|S6BP6DD+7KqZb zA$s|8YHpW3r>{pw*H;1(ZW{$yQZTeDQd88q@e$*6J^POhE@w(wn9z@h9FdD;xdN z0%vkYKcLBn7jW2AuNZm523-djq=;D3r9VD!UTKAoYpvK||5_f^gwZ)t zRc@5mHTuy_H(FTn21`j zgkPL#2ZXm-^F}ghyvWD5EkZd$2pg($6JAsiRaoVOsn+inxy&aL?tQl3$17#)@IQSh z+a^E8rHSYlW*td+WDkp7R)&yAW zRWCZ;mQKRYnJP#1TV9?Au?>&T_I+LGIz9nx43LM)yX^=FkA9z-ws` zvZTf>-lu))?njm9}n&jXp zGtgU4OF$u-+A4=bK@n8q_-anTwq62@hL-E@essoA{=qJGE2xCrniqIK&FZDT5LlV* zcRG{vSoa}P>>*N36%a}G{@{ciAgJZyWjc#~KQ1ulT{Spx(*3rvaFAbOo5IZ0HAFz_ zPpY0IPjz3gleHYpo}fT+%GhPIHxZT}Q7x2rlpfT`a?o^>PMv+GwN1zBP+9%ZJ^S!J6#PX~e;U?G^-5Fep)B~c0ugFd@ha60)2y~=gKxDU*SEb*6 zp{(NPM$$OOIy8M;@!9mfiMp?P$s}jxG;KD-su9jsXWu z%NLA@uqDvT2ntX=ZZro7g6hfc58dx}o$Q`H|H2md5!E+MnIj+!EP3W?&tgxUe@=iC zynZ0VZ@!f+-hx49ruPlcg5q^(^D>*2C>MGY$a9pWv z_dQmRiFjQ%DL8Na27?TsI5wr*|KNjM=W}bsF|cY|`4!KXz-sy%+Sf>6U0G|#yG&(K7-gA)jEG&q6}$R#F=hp zhxWai5%{M%dy8D|P4}VRam974EG#`PG4}t|u>WUKa|}L?oG+#(C)iyRf-2AGuGcyR zC7xVT9qe9D1XcQdD^D^TeaR4vJ`DM+VE=iOu`C!Z+rGt4^9^QXNB+>n{BD0}#Hl~| z&F8-%&n_yBNLe?s0p=)&k$4<<-;=)=ShUog&#Dmq9AF5LINUSNfRw##`UJ>z08NK! zN;?8HDFSbAo1q{vAi6x0G9@>l@>0I)&%)4uL#m3q9Kq62n*l4ox#~*UTv{@JfSj{# zlniGPdd$@e$usB*u$lE=9!g9lgSf{=OL5Xo!n&p-Vnes(rcuC#k^!CgQ~!FD*qGZf zzXm-Y+VUL9K9t~Q>k#arCh|kRGK1M?bLKG^JE(kU+GK$dbolDz((LDZt>v-1<0594 z>B-up1?%wNE_~~8QOBCRn8e5#1$fBJbeTWjH++Dv`7<8kez}>(eTJlGVRPa@IGIL# ztP&q2;RS`F$em*wFr?fTuOHj)hUCw$?eEaZ=})cwtMwJA-0W^d`0F}WRBlePHAtbg z$v26LQ?zuB`RBEht6(zUTa|bAJEtujjh< z+|PZ#G&IRDb$WDt#q3*T~FKCm>-3gjvaEC zqa5pvn&``qxI})b8dck!A>ke_$z_-zXe0cbBcxP@dc_5C98&gVEN5{lD-jI`V#>@f zDvKK>=z4x#nDQ)VBVB3*#gg%f(hN-pE*p<=LeeL8TB_qkWT#qNWO_QQDjxRM5Grxm zR!`Sw6Wgf+TgfF6>tzsoY_|ZJO`<7i=R*v~vd+(*KZ#?7*4xC`sc}t>lK90h6iJk4qgJ4n+84)h8bm+t6>F`fo;ShKIWdW zUejx56`LykkGGoz9q_0N9^rHE*5@KMP}x6M3$wu^_0bnJtC((#SC6I z94T*j_rG%;58s7cf1|Dc^zqs+vwEoxa?AEyhsw?TZaiTlkK|SwkJ39wxqLMHpaoPx zWkkkJC2Mt`-V2>dul>nuIIVx%>)1m5b$AR%b}!Y!pLN_ai(+=Ko(1Qc-#|QjlSwz6 zvQ3Ade_xY)dgfhks-H@8U`hDindJdx%LM;$lJ7UBL{$&g1lTRVnIG#Z9*KYg1+kTrxBKT$g`WGO(`Et+ITTr2q(8^#=x~su9KXljCc5#}rvTJn2I=Fqkmr(k zkf6YLw=t*v_^8$lkOdIXqB+W^;dTnS4SllBuCmqb@j~xF;^=J6X03ya%!BRrd-#In zT@0})uHi3WWN)Eye6HVLSvBh};nGYb_O)ny&R+QyrZ2sxWIJ<8Qc}LQ&?g9fF;6$t zTWyNCNIHhKLNVU?Neo*GaHt6$7AVnEDSc`6^M*InTl$2 zF(fvMBRyF?XB8-J!;R?xy~4=hJPO0K2YeNaQ~ttZVMmCnR>9LBd~vW`uBroq*@&3> zilEV{eat|n0$N1aJy zxgBk-h>oTeKA==pZFQB%al{lub;pNiV#&w8C&42Je2kcs>-g#QlU|u)b2S8Bjd{yS z$Lm0%+M0YS-QOaFmdz#l(;2J6hT(>j&HPMd3+>6VnzsrRQemNYok(UIVx>rZ$nh|5 zG51JeSbZAfq$sZFE7Me_chRCyLVbMqeI_Mm;TqJym9I8O@4DDD*>cqX=)0bEBAw#p zW8_Hw+5IEch)+0uGcRmQ5vYBeI6Hhi6%rC;*2|1$rrSNeV`ejM4+1 zCp_^Y_RT#iHmv&=Ifs7z)^TxbY`WWguBSkq-xE|r_ugWN*pk5YwDeoP@;wdy_BdAg z(^?KXFLuHcVSU}#99)9??3U;P*8Hwb(aB#!j1qA70Nd`dEbFm7Gm1Ge=aeF1>6MUY zfTVh9As@SB?Lt9{;-}%s$)MAA99VLmMP&2#HXpEBiZt|kDUIA`f30M4<;7eQflKlfURLeL%_#|X!Tj9R z-F)-{iHN;}6jyW)C?5Kh*((eDgbuzrIZ^-JzyzJ)=+NkL9pI;CvO)h1R}xi_c)}B$ zHAuHs4Ni8yQweOG?C@lR7N5ZhQdM6+HoJQj5L$dpM&-Z7oWbFpqf*7Bj#`Gh|# ziAU!Qc`gkD5$!|-u~E=~0!d{wjG9RrZ67JfDttM9m6bjrm|%WvL6K(PkQq zPl@Flvo)lL<{qwN);z85WwKjI%gfginDx2oadq-%ZC&@(PB)*1Td`uk!W5W{lZlz|@7$(A zJ)CD1dxD3+9YPb#z3qwn>v7*6D4I;+8A)Cj`EgW7nkUOd9E(pK9&y!qy)@rA`t_*k zrg>yRI2)N~1GLc|7Ea%hRE%!xoZWfNH2xUP3gM530GD28eFh)_nv-9C+$W*zfB(Fi z%CvA-6I+^;CUWF4J64VVY~^lMlYfCy9muZBI_6d%lr`LeR8)QI*^F=O)j5Z zh$6%KYVUb%$2f9C^)$Aw5CEqp%3Z+0*p}+f)t|hv!loaBr)n8>iNQDUDSaBf+>DmI zU@bD)r=+(jX^xZJV?@+Cbjhw+F`*TEOHfCREQQ77r1l|zFoA}>%Tf+~G+w^NzesZh z$DGuPI*utRb=Z)3*42;P4lP<&zQ65!kwZ1wVPp_8N&Sq2NQL+vaWRFk+-NB+dOt~K zTh-YlfreB1oH?Fv`K8`ZiTFf+U+!kV7vVI^s@bt(SeQ0wEedTopekEYA^^)Ax3*MR zXgB<*YupgSg5-DBb-3x)I}6^mW1Gv1>-5PtU)2|>;ew&+0{=8;LC&T{9oLwyxeEVy zb|5~2XNK?E^rReasM&-Vu=-^A(dXQoYFUnIjRH(Y0lcDEa6+s7RK`T~G!NK7r58Kf zqWN)7TLkdn)U4PW$?+#X@sy9ni&Q*i#EX6qS=SEx?qP*&Ouzw8?5D;rAE}R(U2q?0|+@g?m4O(6sZ8ak=CFWtK zBOIktIy?Jxqv9!D>y?*P`?C{U{dVm_h1UC~ioOg&?eL!Zn({4w;(P*_}NgGa|k|GAwGne;tZ{N}-`gzNbPONSq=WN+PJ#E3v+}~T= z;sPp$5&A?(d(M>t4m5bTWon*l@D2tl5LW=7u=(z|!2G3|Q%oe+&-CfBgl?u(P*L<2 ze*J2@sP4Zmot%V2z30NS5{>`9Z2s?C;lcbY(fKO_HpCoq1c^iJf^UAKKkG^EMp)rv zjMEj5r>{>Dhn{eGqMVJ0jY+Gs&5A0ynm-QHau}V*q}+yzGqz@t@rf$zfc3P{>QHHt z--4jriOuFafA7upg#2E%kj#JO&(BRNZ?A|H*Z!2a`EaD?H|Zpgnr>qC{WHeR+xjPo zdMMgxE~O@fdwDnAZLg}UVLY2fYyv)f)oR$dc_yb&=S zsCd_IN>87{d^nQ*D7h(04@xbQ8K1r^!o}E48g8pitz=>6^O8Jun@V0cIpyh4L>o*y z#SPU*X_3zEHh5U;pDA&Tx13ha~Gjj2= zaSGBmZGoFAHQ(FHXo#TvyhQ*F{S!TsaP;jYDj8P)g4s#IKhjfkO&GA%h?AgxZ9<)3 zd~C;51H3-dg=GrIZvyQ_{!M=A zWn*9cb+;ouboBZ9|N80DwS8elbzKkx{`a}EKPcs=GC_<8w2nmok<6Lh6<G^sc7+;ubNT{a?YX&0p}1pF0fSD*e~emK5XY^!k5v|3rPVn*+Vr_pvK>1=iQy`TR{_w zdb$?Ia`bo6A3GEW#*SBPfH-MNQ|P$^eZ;M`Zd`A}-Bmz#^JO>k9~EtH;aid3K>NmQ zeWEX6+`SK@&v6T`y`ZBC)2D~T2iXB43qIeh)*@@~-xB@$2+l5$_lK_Onbmm-Dsywa z#awQiW(VgK9^uYKcnkfaWBz?!m$;NsdIVQ#e^<;=6$dBsAD<|}!Uz3jhDx*yB`BH*@`u8effRcX&FQVJ7itS1)3XUfByLiy8pE|9=chB9 zur?=DXQ}p3nf8F&K;lxT$5a7pyKy7gmB-kxO$)Gm*k7EUg)7_K>T3STk1RR(>V{>a zMFhyB>mr6->K%=ZE-}f~$}U~{Jm_z1ir?3eKF7cHPcB`+18QliqOx2`;9EtLqxLVa z#`{Y^xht;X*K}b#{ul+PM!z^EN3(x{g~Ry$KCDyN%dP*9%=h2J&^JqHL}Bc#mSA}Z zZ9g*%%0JI*-!JuC?Tji{ye_(lK+{hwKc)PS;FpaK9zl%st+oVy?KhOSer5rPSEi?z z`FO4w|BT#~^209>Q3~USxU|G0WJ*%jDo@@KAm_;ldAjSpm{_>({4PILwunKoh~rOD z-;RhDV20M8jRRFpen0;=Wx`*1IqW_XZZ4b{2<(pc}orA6X zGA}ph8pni?VG_}`&?|EkbH855dA!@d`O4r95b;tbGb0ygOnr(TQa*slPjSR&o^#HG>^DBp`7Ftcul1>Sa1&P zMUDa2na;h<6I){e3i%%(0Wh(2&ua2)ZKAo3Ot8O}A7CVch--Hjc+$AQu{E)wn`wFV z3mj-!lTZ8+%MbErHBZG`1h#PbbJg$<$Wf-W=B`nk(AdIxQG(1P@=+=OV@2jljwj zUOl3R2?e#$Mh?XG-ZCRueGa|7c7hRv2Hr0<)o{r#n_DT-&t1=>J96mcZola^+QP>S{v8q7)YI@;-jRr6Tf($jvK-sT?80un!nQt*WJo%-QdJ7uciQ$GohClNzvUw?E`fG5v3t z5+pYRb;vf%ZA~iH3LaOZBV9dyEf|_i8mygvgNR71oJu7 zYV>8Tw*2-vlWyKZTk^eblqrHXE{eqdfvV$G;PCwkL`vD-y{2uU>mQoD;JmWOP zL@&&VG_;Vf49##Nkt9Hjt;WW5>BNlp!{<}*sU&H!BD=93pLjxjKjAYu=^v62as3)V zlED8wSE$uPg-%xMWyJ0K2tHjY%zxt(Gd@Wx0frG=7;QNhcQZAGt*K5w>&TcepiD>Q zf0NMHlEHY}fsb2#TEKhf`?gvq;GS;dRlEC(RKN^$o5uH zmqM_p?0I^y9Aq>&-Mia-`yfju}ms z zo8F&~f}}i!aS8@2I2dp!-z3yb&5Dm0#Aj=CezdB`H=AGJHK@ zZ{aXoTnwubsxQ5o(1{(f50f;12$?!$-%gQ`vFd}yujC~@0R-A$9TJ7bsouQQ;# znD}%bvW;Yz37bnd5TiFWaI6P4+!~#&ZdB-(h=@Dp2tV%~AP2!OUuIBW{gK@lN9F=m z`D#M0XyH-ysdn7=nid2-FdK*=NnV8#G;MMQ4`FmoUBx_mEt*3+SLq)f#2Z$~sM6CD$GDd>MdezXkKl1m(g_ zS;eeDSVDdWYGG+L9Vkx=Gf{L^xbm=?x5Bq{?!CCK4Oh6RTu0>3;30`R|BtUiq&ny>(s+Yfu# z6Z|t*XGxYKYY$7d&`~?I^*I+_jrphkMyxFt7o z$7#Oi=#cwO%qou!j+TDzwp*A_)XN=+MMhaEt)PyJet7r`c5+hRq@tR!3aSt~kw+b7 z8neTlX6&#z>a1I@bSNAd>r)f-*GCnvo~e)Y5HIwZaB)fd9KWnvwh<%!x$TWhe@jad zvj?T$uM&Vu+uMEMoK>zDs;+!@ba0PBt7!6As|NmZ zSwFL)kx-NmyoewH4Z#Pmjl@M_Y|D= z6n*oVvVj|$p&66HP=LhK2xb_i_h30v2eJ-h-c7VRiYcA3UTIsZJFItH{7=_i^Q!^z! zfYhT6?b*meF*vvT+~S{7S!!}lK+`|HTsJs&;}hshmDB5sI5dQ-S6N>CIY~rJJ|xQn zJzV=pthi&-HXGEj@=-qbJ}HZ^@yC_kwegfM2{;Ghqx*EGBpaIJr&O-ra${lHyKmJ0 zB+BSB2l=>Vj+cQMYAi+?6JIm#+3@8n#9(fztH)fIHuQ z4Xv-~EicY#k@ZS%adRb+IH!^Bdn*Qf?6stG#J;CzA3QQc*(`8}y>Z-$=yvX7g~#T? z?KHFcIils;4+K|{UM_@w2@N8d!HA^1M;o%V$#vy|UsDRO7Zr8fR6H>{LIlr{&$gzS zSo~6dINz$ zZBUYFKdl=)5RDwkRz((&-QgwXR_?Gwmh};1_}B)g$=T8b#D0K|M%V)>KxeG{WEPyO zvKDYND_a!;RgI>J1Tz;m0W?>Q0QlVLcr&!**V73X(yx-8#F?&1Z)}>K)u- z-?IA~GZceKapy@BfX7SCjIAmKXoSo-r_Cw!X+PFK!tK`nF(k_zmvOZcL&?-F)ThG^ z?(#kIU|V)FiK8WbJUO5`VHm!UED-wOXu{)-pnBJ?1wCt#~o92<+6L{ z%FRI@%sViI^+B_-3&fvpPUc;ukU5HH%OL>Od7t>`NJU2Iqk-i%t;XShSs!H3cLaLb zq+|ciBzgEMse<~DaDd2s_<@R5!wTEQ%Y9ggoZUzc)pcAYZsTszFV8NKV1@FCUbdjx z@*HL35F_EzZTVizwBISj0uQ!-(_^Z)mThJEbtC0xA5%8Z7|N~#p`gqWFb0zQ&H~nT zo0A5-+KGfZM$_i2xvWy`6V|;AC%F;mgC7f<^g|~7j&U6M==DH2)KUa1QL_6o&zB+rv>j_P(I-DB(A94^#FSG=?+lgQz@Lo%D!yH1{4M!J!)P!akCovF$m2#aavwE z*VPU}yIQG=3|x%qfF;z>be@};4NFdzS9_&Hy`Uftg(#4Ue$a{P(E&_tsR=aj%#ZVd z)op@5q;ep9?s(fym$_W>tG?Oe_)YBN-?>LM6VuR}BiEg#-(Ry-sXi%TJf$7;`u-2= z=YNmAGwA!^lhNKH1`7CF&+_v+)P?@L@ixUj?PmiwuGpo^4)|%~U*KJ(1PNshoRUv<`2cf)-@`2Dff{dr^jimjJWlBe zm)JLIdZ%!FPRoGy7e-rMdmLT4q221{Jt*V1ac}J}{b&^G<4HbU#;t#U$?4*aSCt>j z85^Ck{`L4^&;9-(t0_WI1GnIvA-OB6c0Kb38HxLz+Zd6`H>(Mhslnv_5FBRY$#1suI$kA1Ve@fw&L7dLz6U&fS0 z`V~#UG^ZyP8uO1=bB*bf>QNz6BsUIRI$n%NZ6!ZT&}(s_)WU3C4CfG^! zZFNSrnB?Cv!z#u4B-^v-p;Yy5lmm&1kIlmOw{1h@{3XOkOz$SlP?$Lbou9+nGJL-8 z=Q>wRLK6Y~g-i99UL~Vr5lVe;t|^ct(yH zfCT;){(88I`D&zv?i-{l3>96C~5Dn{*%dPoX}lJx;Y z$0}0E7GZLtVE&fr;QF}KHYA>9uHxMMJ)=Jl>fKCN^*89m9j+Wc7&?mosjPG1U{SuN z!r=7suEe8Ab2dXx8bOp)1H0UC^JQ^;&sJfoVT->*!UtiwaJ8|I0py7p;~PIZk-U(buhJ zN!6qGPC8B*T{<9qEC!=p-?viwe)qdjzUBu@+Sz@2debGgu;P5Sahz+&v- z>-3-92)$TuixlnBgVHAWCeOr2y5HO*3&?h_z^06F3t(rWelxRLz^qV{!Q#;~&-4EJ zviwAl&%SC!z~{n7Ze%y%1|nfBV(!{@)7p?G3=b-+*vwKZQU!0eg&g|w(?{=d;J_El z`5O(2EsrdTa1Zn(ie#1?7S_7g+x+a*Ii1>wjg<7(Xjt!k-9?q?v!!%g(zQ;!@+xn= zhwBO7Tm4DpCMoliiXw;4Td8gKT&pAmx(XQs2VH?DQa0}2lu1>!KI=7~@-2t&3jB!? zex|%3Ttz`)F&r#I7lBV}S$(nisr|7Ad2aAa^y);mKuAUgk;k`AgEb%z+vOSrphM8; zBwT}qfNN^DLsg$9M*bkbvEfLqKSGEfI1#^L=*aF2$#}0F3YKAuRPV2|%M+g7iw>lb zlbd0YHUK|vmdBOBO@EqZ(xAm>COgDKP=W&c{vlGM!S#Lbn$2#S6#HHDF%*4TBtIN2 zfCyq4(m-u4Gx}wHE2Lcl@i}H1-WhSt0T^Tzdd}(RJBgH0`Ze+jF z-rEZNE1j7q02fA(`rC=wy8}2XMceyq@%!Tagb=;A1GN*CYtKn;R*dpMI^A;3C9b9p(>GQ4Y4eh`ML6Vwuo-3!upD;Ke){dS z;w0w?2{`eagvxWBJPI7R{&iX9+S%O}8ni0)i5)((hlZTX_e>ZXkGos+ruEe3A1IO8 z^47)8ImAa_2R>8)yDmo?UI7u=E8*Qe>mR`5E~)jVPxTDSd5Ngil=rfL>ZWHDX4 zmeYW!*v1kD~-h*G>O|IG=HQL1VBfLH`L&C{lf5{Qn6}*b~NO zH(^{3SqHA_UwubI6i?0@-TiL%^3ZhGsjh=x6f6H{X2RC;BJ9SaA|BPnf3Qrm{7U7% zI1LeJr>d4VMgAi3JHQ?PHIRh<1;BNJ?0cw{9R2IGs~#K0ObXqg-P=N9I8gFdr~SNZ ze}oI`msgz*|6Z$m(i!DdkcvzvUCD_#d#WLglpPCe3S-pn)pSZKf!(P(JT!88m)sfZ#S zXvM3~6qw^j&qcSOp6PE*JZB$Jv<>tfe} z-0>GUh*+WNu&2_7+T||u~L$Ko_*+g zCExGnxFOB;IwWX>!!gfIz3m|M`f;MaRdOtHCOKXHclqI}xaP56ZZt8l=y1TsWq6tX zY3FU_EM_z^Y?EC0vsU1yVy|Cvs?=S3osEr3hXA*ax)eKB_>x`)K)K5+Zr@u$Vm^%9 zF0Q+;Yn>{YZ8640A6cwiqljMhwj}PnrPJc@r1>}j3dnC;m+4Os3$pyNUiUaeq4u6_ z|D}7I?gk;DxG65nMeW}3o@~H+9^_V$W2pGnm3e4x?;92TFx|RCgL05yG)*>Jb0AY; zIT!zXl9{StdhrhoZxmKd@xJn|_NrT3&S`oBd9KR(=$~AWQ6+Ug+kEz5;6ar07qUoL z8{BE(-pcf%-I~FQkQcnv2bU|eqv}w01=reSk!9X|0||P-?S(Tq6LeC2z;67>Uy&Px zeC9j@_~bW&aurovm=eVEFBc9!sgvSto$`E}C8J{-0lZ<)-Fxo(_r)m6#uA*e-%tgg zkKC`KuGQlfUkXW_Zx%SV>s?rn&BKG1eWs6_daEu76{h#JVzv~&!j;n9fc2k!kS((ge5^1=?}8gb<03Vw;xNo$hR%h({r~j z)Vm%3-e}JMNk*It1bNplXPCxW*m}^fYcjb?#wrK&_+wy(;Huy$WqdTwjDa@Y$V?5djOfvdxKgyq}~@V6eyC$J+gO+15*V`v zTy5Ln7v2CYP?b3JM5`Me^GR)f(7$saP#87O&5oP7)0*lz!=ONNndIIZt5&J|cAIE0 zA7uM84q}zVxlV%P?h5(NotxPE!MpF7+Wp-1qE=XT#yKo|bp>T1r^x))coC`kDTf3m-$w(t}+(uB2`#-W!h7ewjS}LtgnWD5){iFpe0Z zZYvj+j{nu9%XwCn>+od|)p7h$s5_ zF(T_=SH>CAAFh6q)@VBq;T^sRq+?l*TX%sP6i~wVT*oVGj zX$f0D^<~s?9y-&<3et8y6vUCP25=Rzn)awl&BJ+0bsq{ZF zBp0w?+Q_TPGvh;X;;|PaE`HXmk>Ahi1B3gt+a#GfPmz$Xd0o+EgD== zf=I?fAc>}_x9l8Cwx(AK$%}s^TLGsE&Xzy?OU_3@7nwwAR*(}Cxu&3tRrJLYUJqNS zCufo@4156eqBWj&8tce4dV1*oI-PRPmfXwhL8{(Y%`pb+@f^L?f4I%4z%T@>$xdv$ ze+bfm97-o$D&8wb)yGsVbP1-)I!a9sql!{tKg5LAiybItJ2gr~9G<}JEZsv8b&uYH1GdS!n+h*wonVwNr)C&Z;{ifgAD?OxaZ-mM?v{3iX*l?Sc7 z_WL*N-dYxZsV>Ujb+P+9;cO8NfX7<&?`)S@jOsiE7#W`x0HGMhLZIflY@{Y7MAC`# zV~m-izR7cDt}Fje`EVxggFl%wRG)A^fI zp%^8Fg^(?A3{?|q^mL+a&yJRkgnnGdWPUsoz`6iGc+>vgz2y9CkGMS3AHMb5vZmr9 z5q`DxD*-^KU)aA*`VFAGUAp%|p-=u-&Yt0sf~Ptl6B-<_r+If+cZz)8-^fb5yj(r& z@SR*&?62F489B<#VudRqTLRjqH@n9#`x{f_W0^FHhK$>;SsbGN{GKEvChIH1IeVFM zhND=7m!SOq#9u=kbdyv2iwY4QGF) z7Zn!Nf2!tTL4=woKU)&`SL^^uAG6_1*{E1uZe@m& z{U$Ocal3{5)Th+~=pUg}z>#AZIvxPbJMumazY2P@wCZ4VF)Csdwnw8PgadX-j9-^#OZoQY_wSet60Pp zC^tt6C5=U!n`I?$-ZJiWKpwy?6Ja0I781dU^2cx8|cXYmDWNJO5HXCx&mQQvKKM5)r zUP#%PY@@%6yG~Ck>{cV3Eny$&{+;G$nVqoO@_R7WP79#PAjCy|?F9PTArUF|vt($K zeuc%JLW#gy%Zhr@kBsxjx)yg&tdt;&5dVz`-hM9_^HY0p`{xtMG0wzpkvo7Q>-yz*wRhOyN3P8 zAf#q_)f4pcj(0kVzb!i*$LdOkeaCNG`QQ;i*6q~W=Sl`p+(AZA66>Yx}}b zVQ8}u-5SK2^U^C;{jHsfNJ%QqoTU&ckI8GT#&>V!QYp0a$$uf-2D;xO>MKFgR}G*M zcS$8fg7odUC2mIID})?z;U0S?x|7WPhvdb(X`-Zl`$MgExgYCm|AB@;lS!1e@_~O< zWV7q16xWBDWu9X8;M*{n$!km7>9MUIpL zcRwKh!J8Ys)=4wdymC^@^wR5e5$|4EuOCMf#XE6$eXi$L!fVa4h(<`}aFtlnoyKuV zEa9i5(xuu?o760w>yK-ySilwx2O8|8rRkrOXo#UBI-ga8LugOERWAw(qN|yTh=8>8 z(wfMffH^gViEySS@NeJIBIF1lVfx+@NqqZUnd_|r{*J=>;nxC62}d0$W0ErTJ-{vv z`J1T3!XiU}M(&Q@9hVQJyW$2tL1q@70O&$MN!iGRlGNGtcaY% zXl z2`z?^)cRQk!=upJk_)YP*p$$9sJs5s^8P*-mN`Otr3D?TdzCponwjwmybzgNx;gg_ z_|HUTqblUnUIMTz!EglFdz}%(D4}jL$l5*FquZ`#Mh9 zh>(X(I`}FpNZ8I7<8gFIS=UgCv~LYpl_yd5Q+M5L$>;o1$XivHbJcn-6Y&1ub5VeY zc&&>&hm)-#Zem2zo3TpZcf!&3>flfAVE?zNhIDjk8gZm){<$p+0ft~JPKv>9uqnOC zO>EjRT2qQYqN#U9Vf6(!$TIM0>;>6kv}0@qWoWC<0XONGL#$V;%(ImRjnc**X)H7f zr+w8ZfNdo^9bb_0knyTe9aGdbJ47pdOzCIrBbkYX?djYc`tpiDtF8df_xlJ^>XH>rMv9oLQT;t=QVce;d@G~v_4kb1}} z&7tm+buTM2{PFrh-GyXvG?R!F?v#02Z6Iv$J+Xd=KC+OO#ME*!y5j(NsV>fGT_(fJ z?vdLJRn3x=;G8~)h}*ptgd=_aMgw(11)$D0rs-N^t9r;FABo!sxbk{1ETS$#lM!$l zC5CL?Wl`P^bwX@F(n%+q#+%so8Hsqb3yD{*{Akg_$py~$Z3tVS$vl;1eSuvAp%pzj zHR;W%DmziFnr;2U47F@??1Ta!W}X)`y8MWQBU53YpQll zm|ZO3^7kr}ait~AJUa!IbefD;j<6U{JFo$e6GaA_zoF(R1CE}d;G3Nx!`nCyMK3rnBa_FW zP<_08hEVi$*yNo>>|x~~72cyZ5cgJ=C*p#CAF?$>%qpi*1rmFq!KUzyTqmPGHtz2a zcfLT+fQt`-b~Woj`ZUpQRAjwy%gS5!CjBu7&Ul}fnCat6mO8UnmfLSFVOy8EC#vgL zk`9e~<1-Z^0{8p_uUh-$-2N^l5_Hp`Z}7zepVm4D# z&hA#v1(nBb0Jm93JjA9&e@AP~5WA)@C_j|MDqRgKz`x#HN4uFZcY zWE$`~J!mgZN)g|f?rAgRG?H-(&ecT`nguE#QMq{AFvdJ_idWL-3~a?%hpAQ-LEsZFN0tApq(i0A^IF-Yf=rltz8rGu^t z7M})>7GTo3?->lJX)E~{7RpiL2Lj_Ue4zSoMZVH8c7RP4L)%zXON79(31F_ z>EN;CWG|U~fU+^{mUvb9KuR5t=T*35Yh9`cH*Rvx459(@5ruGfjKlnZ&N1grM4dgF8(SZj6LeanF%)lA%=wH{q9<--H| z?v|h=0TYjh^hLA=LHVegU#`F%fbF}Mr&?ZG>>2})WHtI}$O1~s zg?Yt`K+6e5T9DqBNrp?`4m5##j`5wyPdSZ3WYir|i58)OMEvpv&>0j%U5tFJvr(5x z@Cez1#>L!PZ2LcusOX}rAoi>QBYPRFd9Z+$xIV2#Mhp}GrIsl*(>KfJy!v6aHYWGc zPcLXj23`Y!a5gbw(108mEZxBpcU*j2Tk-zI>AGAAcB_6Vbgn;Zu$>yC>}FQrY4iE^ zH@9bN^)cgR+8vF4ur<#{R^$)gSJjhO`5CXX{iRx4i0&mler2d%U zc^Smy_@k^u=6;m3w)Y(;U(1y1XLTtlT5zsYU9-K|V<#h3yOd;#w(=BZ<-3FTlr+xe zxS*-#6QBLxGQ%IfcKs6dqTrY_C?U8(VY~_NpIoHbm@*VmwQKOyW(wHAM1W784jX+d z<(xBS3EgM(ce7Vi{;`y?Alg{t4`aeEQJCm`D7^I+tQ09s$QZ)CZ*8e*s>(ZX(j1?^ z=c!yyYHNp4en=#5^yV%|&BVrHT*{O{m9iyYtO*n96UtP!<*#&p2k|rNp(5Z{6qaGH z*@r+9gND#(CNq__PV8=VLZJX!&iQdlL!YMek4!e3P{A+U>#EfrHC(b8ARF>_W}7rJ zHcVIXnUug?%e&35H=m@v_;NagDT{j%4zxpaUk4&u0pbJQV@oDq3wQhgpG+J8UcR@G z>yy^m6X#3(?R2j=cV4*cKc~|WZlx!r{DVaTC})WSzDI z)vWWrB((t+vK+oAtY5bE!BZIi%Er*LMg9-9XC#n3i3hKn9I4@KZ{YUwlIox*c6aH$`kJ!PqucTWOf7 zB50p8_S%AR)tm`KzA-T>0dXC`A*{Tg=0rS3`gT&22%P%dcm3N_(uqChZHj_xY=Z^gLywrJ35Kg8aSUz z@y8Q{nDPp0T^B}fI?`Sa^&GpJ1X|-;wuNVlG;4jTxD$(zS5`x>VSqi1WYDkiw%Lw1QGYCb^Ri0put=E zFQBZS-lhPQDdz9C3$EQuYnPQa$P?yl8YXp1P4vp*{GFL!UaPXtfMbHbgisaxhaga? zh2(UsGFA#bNeraG^$o32k9EYGw;lyq1{J^kU+0$s4m1f3Eao020?7E-%t1$9s9)BT z6a>3pUma%A0-SOU7*tSPX$Ow5%jyH zJOcQsL#~jm@WvS?Ix@P`(Ul+mw`oI}HycCs{^};n=4oLU6_>;H#<0bJgPe`oGi#y` zQzIEW7G1S4SZdm?ea9XW@bZq{^lq#|p3sreWgj-D>c#VWAlBE;)A+`dHfEp8Sqg}5 z09CMkBmQujN5n)1qCUteI-U5*p#j{hC~7A`Xc~=eM@sh^-W%rwPE#6j_{Esk3~OT=ydonD?m6+$gd%r8eo~|Mj&dkwdR5E4FoKt z#x)Q@O;z1k5#}VOpKew1P`^kB-u{`U+YQnTxt4y?tko^lBeFX=oN*fSOnpc50WODD z%y>c!@kt=Zu+mRV|DtbZ?xv!I!C}@vE>K_X$Bm`&lop;opf}@Ajj*rVd3(MlhBS(+ zieZV(x}RyR%w!JP5WIoEko)!W>wU-C(^|8xm`9+qi5ihLl&FJB2)L~lWgIxQxaz3qqvT~+%8QOuLUywEk&PI2k?r~v)EQW0g zt=W7h6lbqh*)Q%$T>VuB!*Om(diU#psBj%+3vK|N3ZS<6Teu{vK#Z ztc&{&aUoAk9XWof&K_9#&0)K#XI8(Iq5}QZj2*|zD5p{Mtj9#iC9;H3IJUO%QmH`(K?Woj{$_&LMx8y-7CjJ(R2hV?4`pCWsf$r~w@WFjYsf&M0$Oo-1}slQNOK zZ4k7mMQKeeze&mTm-!jfQJ3}AQgIW*SU2RDpqJZld}w&5pLiX}y(^L^K(SSioY;kU z%{!D~)=;8>v8OUo5X~tMEFXP{cNWI1y4Agi-d*op>S_ocNbGsJ(}zz2S9Q;RLP`79 z6#LLED8Sk>ed6{uN=>_S;g)hM2XC+=AB8pTSschJ!o=hgXd=W5KW;Ed7(zsI#GL$B}s zcyfE)y6V-#y5XCPW9#I7>7s#$W$}Za^^+xhYq{bnHRmVv@}#5oCW5Y$ReV3b@F_VY z+U;D@0ThNFekIX^`XOXX32PLg9e^uN>E*j?((8A1`6+#=Jl)h-U>tuKe~edMS{UJY zT&UZ>dppS6UB=KRIf$P;cuA7}A~R&YwlzA2$sTV!1)S1yj26_ojO{CP`P~KC^k)`m z%?+3<{_E`&^~+?-e4F7wskO7!VWKs#CYz?`j{Cgm*C6u*t{BpbQEy-N?H^^+tFPv2 zXW*b>gg5SO*44$!Wg$XhIMQ}hAa%S&J?ydxqsQPc`7}r|KmPi4L$t@u*_S=WQ+zQs z=y)haoRA$BP}oDt@hpH>3VKl z^#(@$C7d4h{uwf!Rq4v{WG~Y>ld28$aJjhT9#Q{j)MapaD}LQcA5$8cK5+O_Y!?r^ zrScDdf&9*XYRd)c`f$e97Kgaq8e*o;3ZyMMIaDCYhF8j>8irRb+GV`oDEZt6Hah6f z_1nu)2A3mHe3meHik^U56?NZu2)3*3h^hR2{!0=J#ewQISd};NhEb~W!8FdYIK29D^bxyy0TOK>jv~|inY|4YD)){L8rEizPFfk>{84~ zTX#nG;Hq_G4-oV$VZsM zVREJ@_P`Go4C`-|UULqsPYFqBXh_L}y+U20BRa%^0c*zKrITQ-B%KT+E!Y_i=v zpXxPo!@T=`x&9$kqt}w`{sq36r#!ZgZi1xtv{jdl)(@x}9gYjM@d-SuIvk6jz_`IhXRi3dj8c(k2rNYL4EilHDQ+NI#P9Xq|PNBnGP-dS#vS=N{GPv%_Vm=S zwHidtrZ4<~#=eTjSV=X>FNLAOj?ca+PVsvj&|^MB6N@hvd1#_s){v1)qz1uz|Idgs|6O0_t{7PmJkSb#2o z!-4$zS^Lj@sWJn`3axXRDD3B{gneEycofe?)V`oaCAR02%~WDtN<`lGCS&?(Q&>); z^NEt{`AW}FnooTSQ-!^o-06plq&g2NSwnX*Ni+pLgU9z748Y% zrM>?C(?onK(-tws@N_BCGD->*M)aC}KsIIQ`@hA2g&Ya4#1U`8IV7up(G~JYaqDD- z^n0!dU6bKK|Llgn71v7x56iv?j6ue167#(?dVw9>%geQVT|LBSMB&cXF<4Y0EY4-i z{&GI?_xs#oePl9cCMd?s32+Z8lQ^opRgA@`*grMl4La%7-W>k`)CC?23lfr3?+{Ka zr@Qx>y}k#10r*HF&MNVB{!p1@O-_K2l{)yWs5;@dTdv}+g3m6oV77uipXLpEprIGK zRF}AIt5qW_`<}@UfOMgT#v=BKg1Y9pZpOLls*$IgN0q5@jqKh#L*MO5quMN2nY$-a0NprlXF89#25c2DBu-Fw1v2Y3jK5{!Yd{kRiN zo}$m>8yK28!OceBJZ?O#fdP)VOLr&GFZ7uUcKaB&5mo6xPkL1lS~9#jueoY{dsh?1 z@ezQc1ajn-wXwXGTgjePx`JhylzJF)OQE6_x5pTtvTuvcm*OwQK5z2}Pb}_binea= zU<%fULh4Y*@<5P#{db`VK6Cp3Q!4v^E36qiS76zW3;I3Cp=++zRoYEA{B-j=yC%PA zT|w-G=cRy!2-z%ePW7Y10TQQH?1z($6sND@s5=#uH-8clsfy)5(SR*!<7f6FPr2f# ziFM_bGD@9&>Yc&r@UW4vtbh4?^((m8!(zXV7RFkxzj($Fto9^H7SqNvQgH9T5{sVe zEqhf#ub9_c@P*X8t1?Mvo-mHcdJHLgSwD(R@&k#vJ8 z*gIm~tKWqBX;2Oz=NNg?Yy>}NaDmYP10f}4;}6|Aizt#pQ>`_MW~F$|e`8NXr9o|l z)W7&|I{9e#jW2htSFP2{7a9b71V!gkE8yEzJ9YOL;yX&V-gRK95q&+gzGFquSpaT% zAu9QNv8gmR{$P7;eQ0BW)Z<~)8an77Ij=M&(U9s$2w2Yhe*1CX@dL34&ZV}TknP5m zhdBj8FO5%42QO8x;@34sO;f00Zk5gg(Y2a2M!J3D8Uh9l>{fcZW8GC2(xc=Fd<5cq zI}=u#wi}9D5tHHKWv!^|lQzsb+1=Jj=^4K}5TAeg|Dh6HUBrk1kW11NU)?qD$*dXQ zAy_b5s?T{p=P0y|5E&ILXQA zQ1dBF^tY>gucM)*?z?wfr(CPdmKUm(bIWkCLCKH4NEyp}x1GQIPSx4^?*bzRuGZ^wsrO8eetM3)GlKdT~tTUeG!vZPD4pL8gJHKiWd>H@m zBw#o#Tc_gvze<1IUL+E}lu#?c(^lA`)gyZ2d&hg$?bL?(p`~2ujmd@LHR!-E*Kg-f zO>57OyFTvbGr%lu|8et!SaROu$nb84|IGrJ^-n7i4LE*bJ)9X(R^Taqv)S-a(9`~g z&pb`AzhNo2SC#^9ne$BYh9QFCZSs=!Sy8I>%Y={LFCQYtoJt+<=5e{ZG-(Z}{$gIr zfu}LQzfBcI{aTXuammj38P&3pumM=*Fh~ly_;gWu`~s4#v}X@o;CfO_bCCLxH9=B5`TZ?m3A=hWG=S^+E*iL!NOSIH zoRyT>@)*BzMi%-6u1nnDey?x<q+u)tPctD7t{*P)RrqXx++l@$cd`S{zfI zzL0`RO8UKD4tZ~AJa)4bx&J-d@1IHe`iQtNE;b zP6URN=&=5zK>e_hc?JpCWTmo7Q;0c!GuKrGkS8+O2G8}m*Ds=g{u^r_?!)E<{OQ%s zc~F1Qqjga0Ao0Ft!MTj4rd03QJH7gk+^P)l5cw%|ji#;EaxzrP3?{s0a$Qj{FvKPK ztSxY4`j5#h>(8Ca8h_0kbH9)I_+XIsfUdE=@<2p5NzWWDFzF63$!N7XKt^k|&M^9m zvuSuVLqPS&8|AhQ+E5md2vX6QrlyOLrlyB6wJa)IYw@3ce%@xR`3ZXrWxRK)lpn6kvgux}F)9dY!_){u$?s^d;8 z)TAIUGnqzX&u|eo-`HVWa@7S_nO0<7a((CX&B&^C^Ur#$@}npYcWY@>&#eXveUlyp z=YGoW-amb3Z*>~T2CBcJ_46y|NIfBJbl~xwXn(gG9N@`+RJ4FpV!U7|Nhyy#;r$oP z3zqy@UY;iKwBWV|TpyqZ?(DGCyppzCxDr9StIb`{J#Cy=-=KutUsZ0^K1SwK8Jk_F z{y5hQ)VgFv9(Dw@=C5{4&;M?bsXOFuY7qz71J_L6Bu{pWb%;A9n7wu1TEde_v9IQ`TsGOxFROHi;!?6jYQ`Uv0kl&p3XQ zL@HmuZ$z*Cf$r}6ZQ6Jk9z6`t<$^KaJ$wKb>FsRxzb(BR#gjC>L5>$eD@qkr3 zy|*fAkI^wX5Kb$pbYe38W3r7+dpJGf?Hp55Tofq^rDgB~2Bw?U}{ouHxwX z$M_k+@}y0Na!LvTOZA)Dtf7ozbh#+H%nKqkk5B0O?-o@dO#-nP##=j^-Gq*8f*w{7?EvB{uOvenXN-x3|I?n%*n`N zVwIS;QU>jC0J8|YK5$mqXHG_laXolkaF}^@T&4M7c5LKJ*`aF{6S0aJ;fDfI4%a)V z4ryBzEGdDClVh)PE|#Is?b+d+tWc;jB9Exuh;fy=@0Ro*itA4A=8tRDOgrq!2HO&C z`^X;c;(zwt9BKO}4**u(qVH$P>9zHlHG-) zq-WGCw6`8*GOYHH+FsON5Rt`5a<`i2>OqA%4KtCiLnA4#1t^MMgASO9k78V(d%uIL zYX67~O>MVgp`e|ioEtiRXLx8*P3LXq$i6{E_$(PQq$z@P+uA(Rt`{Hr>_$VDb~`k$ z!fB~VN(Tm-+7`^C(o=*hjZjRur@_dzN_!56>ZaWcC1mxz5BJwTs+sv#_AbonP&8e_ zfBdb{qHBOnb6#opcq{e)w8o=Lwf;bK4_Gh-A*Q+;b8x5)uFQ{ZL8iNZj`k@doXeJW zLz@L1<|s?~k&zYw!JYh|Ijitn;r1d3rkMVX%q~&5`}@mJOj)s>_o=C=J)u|j={F|I zD%b~Y8b91h-?yoyhA9tSuHAWptcNGB3|&}psigANBy!(&aXtC1^20a1XR^$+W*j9^ z{oW_Nvi3;f((I+CV1H5yYt_GY?_Kf}Z6cI5Y^D-yLtLV1LnjYk!850=hmXZpz9c0) zq`@vcdmX81?q3p{;?xRy9=C5!G{gY4Q!jv&i+OO#jQT}DheB|RQ{{^6tbSRt@2~@QJ5Vtnc2f$Hn45GjB$Omg z4cg#-KWgqXi+xu0@jxHGB=|32a}6SlY+2$rs#1Sz2+Dbi^h}d*{@eMjw}s_jct zx;H;B)gz84tZ3g(jctMuHiR$o#`oM%pQDcMKalUWWNj5XfJaTtGrV>3a^^;+R`P!u z3E!X0OdG%9b}RnZ9bj1N>6|TySJ5t7k^6B8jzUxFJTji`+!%2wqt%!2K1w2@;$tbM`-sgpWVriC&w$W`ux3<=g(2g zPeK6Rm(BFnMkHX#VDVFuOoEF0G!=A*@o8Glq9E4g<=;p|1X$zVb8eG1aJWk;S|W%E zNWp4io5`2;JC7uv9vta_%-3fO>D~9IC-@-TFoqK;^rd0Ahi{{ z?#9Ke%n?Tn1NxZ1JtGzYu*qfzZHx z4WWrDz6yNSp!cXJ2MR&OTDPK4*G9$Hs^&?0*w#o@IOp0Kzn#Pj>@Vy#Y^^ja<@E=ICjxFL(ErC_N_Fm6;#V7+j|CVt59d`9M zR7yA0*pv=|b8M;j_~I9V_eDT9(#tk$FWtL`;FZL4KyOf_@_C(8R3#>xVMn278l|gI znEphoj>JpQXGp+=kyAxj=n_Av-ZX|i1BvoLp#U2?37*kqe4_vVBk<0BMU8yCuH;vI9z)zx_Bltw%Gu%mMNtVS>9O-|_SP&r>rxUsQW$pd4Wk2?;e7E3?RR z84vjTVV9K3SxX=i*?z1CLGIkQz?HG9Xg2(gSIWkUtdW2wa-!oM;GIKf zcgJ*@9_qFB!!S%Bj5649C*TpDQNHZmE){4CCKbGNZqGnf!he`FO3T$3F|0dyw9C8w zHm`Z+DINg_Bdk}+<+}9so{1Yd*9X zxBS5SsN5L&?gJVK5sVukfEbT`9Sql$d?d^J9L2r*y!o{|ykF>;os-i($EkU~`O5aP zFUp^pmrQoj);L8gBkm^YNm^lH#Qi`-ZE+!?fvBwXU3C5kQuFKL>?AoDm%2a72*}zc zJ?<(BezDkSs@x+n^GOYnlf(jZ6D+Y;_@?oT0p=<5cE(v(-*B{V*dYuS{~k+zi2pEI zPB3i}f3-SMoysCT!_jM=L!lX6$M_3!%K9&yXsO0`^Ry2)%Zr9-UytQx7$kh0oSLQm zFEXVkzk)I37Q{o%!%X^k^A%c#jS&X_2wQbT$tV zs($f?NFuqhLwcJqtCALh8ar2k*v-Uh-)3v<;!0fbkyOvWdMFSsoAVQN&DJE40eVgX zs)<9n8bO%X*|!bS-g-15qs`~c(v&uhPDF_a;`7V0?7DN%{o59GaB$o3s6;nTV=f1l z4|`r0k=F7FBm$eIskGHR9ty}R06bPBbvCmfPn^qt4R8Zp9_)$5vgxzVmoYiN_YhBJo7F6R+=ZiftkZR}D-T*QEBg?s= zd$~RFkGsy5)B2tYS4-;G_0JxZAh&6|gcNK))%-k+TU=zk{0>kH?!-nqY3%~eu6qeDCqEbR&8GWQ`k|Jrkjzm z@%Ql`=WZiH<$8Qgw7TOmLzS9AvadtLJ>1?_mHG7$fCUEyD0W+lnd%=59i?mfO|?cE zRVAkzP2IG=o4E%d0g2Ry3depwBHzB(`mVOAjuSwzUo6{n;%smZWCwg&T>PbF;^bXg zX62M3%eS0~`9u>B&BIm&!c7gNlIiP)mE^}LEe37COzq+1lxC$j^O+t_8-QGcUTk~%c+A0V0EXvs=VOMv+fFHaKE zXfkV+?rinikOH*j6$vieY#5*DNKhgCDAdpoeHxTaB_z~PNHf#{crfrTBtZ}Z1Zh;n zU$T)cIQ3woN3T21*pi;q?~coh4GVq`J4!`abWQL zR3gINy^d$8U8tWU>U97qEA(4y!@OzD(t$xnk!_ZQ=~0EbJdXS zk2w*_!aPnJr?TJ_v~!P-J4Redke--1+y0f2fxC#T7^Z_-V%ZvuXiw82d*#rC-!Dt^ zd46%Y?NU>XbV8RsqhGf^$*@<3PV4Hh8-0C0 zi)&NLFvPKWxH__rO{czW_1OO-x^x@k&hBAYz>)3IoSYxoJa4)%rRz5Ap|Swp7imH9 zb5~7pdbjj2G}rReCr{bu4-_%@V(Z(}(|x=RY2fT^1-IF*;p}VfsKHwEX`WmH%sY z9*)^$`ngC0vPQ%o5z^s&y}elq7jK7`iaNJAci$(mP@7EHlyR0vS}BH+R>Eazy{|0# z$v|PpIaJ=#mllW1$#k@#B?or5x{o9rKD-~xbN-XTx`~g9%jQKh_+W{&-z6;thGWE7 zUn>(P$Z@_Q4K#U00koRpmDjgg6XQ=|^sFTg<-_G#G~_#t>Ifyfbw*Q{yA$O0DL6dr zNTQiZD{9dOSKq$#xUYp&OP?s(X2?v$Ext|iva&BArD;_Wh@mHh4sQ34<5I8Y=UV{s ze85je1`{MJf879?Xm}X91%YD25$(?AO@<2c3w~t=MDJr5j=(MIwEu_?C6iH)W@C?! zls(p*60K9t2XH%|#m4vX;@>W^X4}UlbENoJTk1*!Z^dXBbU+K+ezO>K^|$DjqMe<# zaB_&;$e;DdNNY)@Dj0aLxL+8P*q>|~|@00<7fUNVH zl~1`ED-4=Kgpcnjs|)>NSpOxa?1XeL_T5&mCn`yQKkPiSfKPt=oO7hTs>>OtEg0|v z<}9J}0p_)B%}i&^VtK!**&N={`tm91!YWn(5@4~>yGx1LXSLfvy08~0*;=s)*OD#0 zL-P|oSvR`XxDGJQmZHWSyt6CUry&X&@p|-Q+E-S#;`vbiW~wX+>O{^Yrco=S2`_@M zu4E7{^<)Fc@0uV<8ik6KH|P=;o?T*Gp4|xlUMSm+ieB(#0kZRar;7M$#wnVTD3@jQ zMMjj64t_db78~I(ZSiWEb3p}Sa4C2{H)C7+Y|%tc^L8cMUUll$y>8U%$sf-*q*`31 zOtlOc-aXS;igzS*V!*I8S+jJr!Lhyzu|lbx?mls~thjDbt-l32C38=V$3$IjBnh&r zIk0@1w8N4tvoJS$o6hO^eK&fm7=_H8tp|a#oW*Ol1e5mVgmKYPI)qtQ6Hgu{(fZZF zT?l$(MbIo8AJ!{YJXyZs;&d#{a|S=1+BX)WA|9SRhLsGci{*3m#MLcuO`A&PYTpi9 z6-hnK9C%zQRc^Sw`{e!TN83TOg&$d8TJ46^=-keP(c=!{v)@I7n;O*88@^UMKGtce z&^NNHwBM7!DfxF)bBDg~ReUN7p__%NTw0RovWPA3U@9tE-Tb?bI@jWbQ&zCgJbIJYQ|gX9#~Tdzp-6 z5OCEN9sMZ^YL5=Z2Cs^>%Pj?-#kmi>*Dn@ zpM!Wlg3IBpt`bSO%bRoX-*=JNs`%k3fh(zB<=O=UYcWPY$7&Bfb$I1QwvdQ%L3Le& z*6hTRQ`NJD0?XC-VoP_syq23YDd*42k;wZ%3F{A_Tyi^9@Gn*L(ruvrRUT|7cV(jsIxWWYN@w z^K+|3TVdA)>qp_kIt-q>s#5zXk>GR;JpE+htHLpL7y&3${Aa)KEB*SH>48dXY=b0% zLFClQIrFC^PAtJH$!*oCk2o>GYeL4Jb<2m~sUC1T>M^AKnLO%%-E4>Qc9MWJhUzFk|5G=!c14YPb2g_gH#u z)AXWf?7gVJKFHOMW(z4B*)tx8WN?Kt!uOD$z>k25k4&=A?l{QQc-so>b{ zqjG*Dx5m5<5eZG4kf?hAFg`%|mPK6J+r(g-YZ0utG$n&y4)l;?T*exlh0Js6BzI|i zp8q@zGjb6toVeVlyk-f}JMY~Tab~}%6`-2MwtRx%s`SK3z}Z2p?Di>v;wCz6B8d4Z zXA#Y-WOLas3*I3CTc1ca&D0LC>yd`vTh=4Y}(i55ZPcvk-*_eiAg zE}^v~`wwdlyp6jDdxG1}W&Jm>1U>3eE5A57{50vGR_&SMZ{QiGoR^b)+xG8Y`cxmc z|8J4Q?0=ChCJS7h9RIgI{eJ{&;%mY^?PUB@5;@9(Ky8kX4?wYJT%Ydi%bIW!zhCd@ zjeDcL9IUN3SM=%Ymcu_5&$*aWuAP^vw5g+S7;@4aD0_=npBNPJ>Ovxkyea+r6yI}Q>A|}#gwe&E_I$5EYO?NMlS#*=K{Q)G`BSJ}A!0x%WHMMJHayIIccTUS5N~cU&WzwPDg7g$b82 zv@>7s0fh*+GmzdGjR|nC5n8$9B;rfS8}`x+Qx&11RH4aN6A+CgyK-&v=YC?0f)Y z?4@9NvcA*3-cIb&FAQDEiPiPP-Bik+4=YX9XwuK{2jFf3vc=r{`^R$Idow5$g|%h< zu0_PkfWOkV?sl8w*^6tJZfhIbeoCGv-`-^k0mJ1@dxtyBySd6k&ZQM;S6F;xt$jji zHsZTBqQs)|X|W~{EqLd?W~7_TYM>3#C-5?nB5Z=oOe)s*Gv}1>+i$Y^l6)Lw6*pKX z-}l(W8hYMaf(?idu0gsXK*v|&$+jH6Z&hw)VUa&2>LFitd+{3~UMU^{yB-czv|FG? zkSI)SkkYd=|9-&>g3fHet@nIe)mDyWUO9oEw_IOO%d#FnMJNo9mMq=l1{w+MhN#3c zK~*=!Mc$;kX2$bEGZW|u8lPu|ZobmMP-)%MHpA>>YZ73op$@_Ngc1>Z|j>iP#|j z7qa0mXDjc!L=4%sZqG*3ur=lO)m6#t9{75{fSgG1NlSJcZN29;9vh>v7hMlK|J^=e z_CvHRwtT>KW;>ec0T^5c;WdlKz2uEh2%bI-s>>M}ixY&0rq&9Vo-Pcl_YWyg@Suqj z<(38$0lVLkz#aE_+i$onV%>!g%FbYtjIU1bZEj4hNoqDOl6#NEwznv~5;Csy{iZsY zqa1oxGZcac(_D2Ec?2duPF>zKl-b$6!I3b_|1+Pr5k`Y{Rd|X5BGTXeI0>!ksf)Fi z$8{|(NLNi(g;y6x3bVWJN0UZ%#9#&Cv2_bus%~2jW^cE}_$&w9`{JAwgP$>ID2*Gf z!7c30PyIMVuZEY=Hu_?{toE+7bJxjW z0!tM&Nof#MTrT!0!jOLYCuY2V{uj~IN3FfYZC$@3vk$E(QI!V5 zg#v)5Q7jrQu;E4vLd-_CKk$xK7u48JS5o`A7N?92*xYuMTx9yheAwPs27vbvyelPt ze5e92@5^UuKfTrQy53cll$hm9L_5VP({gn^$w)nI#bfCQh zPsC#Y5rTo)8gR$fbqL4UI>?2KIvET6+6~NF8DWwJto)7*kcSID?2qS5%*$Urz8LKQ zK%Vo`z?}&CN|1}r4-DykKn9-ty0eNg_R&5)hjSG)^8~gT`|PQ&FF0K{a}T_{@)~8E zHe!$;X+o#ooE;d8#8VxAV7<_4B(TC-3s3zYpdhe{06EN!UDpl!YNVECQVV3TC%=UINHsyLRLcxD7c{8jh z_;w}pOWP)hyQzW(cN40Hb4J1~e7HNEWaggI!l_9*oAS%wd6p59b^9Ml;J#5!v3d1c zr8Nq!1<+edR+_g2b`DCV>jT0%W33FfX@}j-S~GP9BGT~3+F^rslAlX8rq<0lBjJhg z0f}t$^C91sv*${^5kX(w>|Ij`mLWc@u+jWEkfIgdEFs;3rA$N9;)2=FHi&6wH;ume z$aE9300OvdHO`WuZAnb~9{9?2G-rD5f-Kk+*5P>6i;y0CavelU`)6Evm;7>+ZFq0u znuGT925BQq9d4719A*yjMnaXFRY^Ze12@-ZW{~V)F0W6kYdhl-9H)A07sgU2zfM9S zQT2O0aGdRNU$xPeHX7a1ZNfW6&y8HlhxLiUSi2u@q|)dd_Ms92-R)!}rIxCq4_Y=y zO_ru`X!Rnj3z$D3V!qlITiexq4lpE2fQm6yT73R4pUsgUu|Cd&tB5- z$BqZzfN$J1qy%Im{S6iy>ITcTmb6kL58JL*hrp7ZfNtspMlta zG%)!8XyD7?fJZN;*$Fed^8qQUDhX^7oqxK>f9$;reI}Ny#Pz5niy&9zeGl=_ZO|`_ zX+3MWMse>ema4${Y1YyVHm@8n?`Q!N^?KqWBM>V`VEyOir?-HNk=1M`>P!;v%IH|> z6=0A>>RxIn@m2`+opvsFJ3iDSZ#vEb6)7%?U?Iy`8cq2|W};HJfoGiwWdzHQN&}tV zNd6q7k+zYgc`4NA`4R8vv0fo0BW18)yb0EXJRS13s8VfXM zvEC$rY_@G1Ad?CHmM#No#UP-mI$=E%v$_@?kwA>q&9s3jYEZ2C`8Jelr!f&DjqaH! zX9Pmh??P1(1l-+`q5@Z89XzLuf}}P%Z<-_|Bp)x`?k&X$>v~8WuoMNtc0v!G(Te0$jD}@&EEq_28 zh@_ni09c2kxuGLdk@7ED_ZH_P9O%ytrY}@DMV@!7B0i024~%$;aF7&|!B#5ipT5pG zX?ij;BflSNkN9YqzC%iXqT;2W}=Lj#ylnbLySxGD2CBRcVohOXVOcQ@c7sD>sri&TfyooZmxE2 zl(HXPlXV+h+9XqJu0Q@W$|ta3b*!tq)(5P0BB6==Ak)NfJ(-%^eJrHSJ=(yjOPde@ z2B?UJ5KV>KTL^PbbDyO|zHmupcXpaBzDlS;!NH;S(20i-uNpXi&QyF^>Dr$I2_IYa zIj_-;aK+C$-~WMyJYE ze|U{ZDE-Vx``qLOfujj~LVwP@v+w-PmKnni?KNVZxp^VV3~zpV4^qvpc4fTUme%b0 z;Sntc88j7}W)TE1q|UzL?Tvcziie|b;Mv;u-QDWHgBgq}rT(w~shC(Gs}M#%bqwsS z-CnGFgZb!A=I7l2**Z*U;;DNQ-rofEw|sa=z2CfI+T7do3(PBj3}!l)nE(>WaKC1o z`t$uQFTuNm$9|tOZ`IngTWs<$e=29wQGP?iiwXP6j02IfpDS8}{DG5)}>tMToe~U3K)8_@w zXPT`_$lQBDN2iWwYfz#N3NFS015z4fPY1%Q6M#W=sOaUszugok^l=+j`rAtoZa8logZyf_#Y+JUN z$~LUiN!~P3HGNPj-9Iu0*GIfoYH^=<$aQd3+B0^POu{)F<@|$Y^daZ6CAB8pr}vdH zvoX$wP6VG3de;8#)P(La{4gOy;&`?Zk}z~hlcr@uDmVvPjo|pyRH21Hx~$tZdSlfP z4!~K~X$soex}g{8HYl_waKGf(BwT>c`11x)Qc&X)ZncOf=7_r%JKG{J)v> zaJ}rm8P0vrKbo176gA6UFUzqVI&)mm^U_A~45{`_XDE!Qc1O9FsMo7*Ray=`=Q_5n zuL~%5;`BMG7-s(yBvd{!WjP208qxl>yrAjih!BIbpR*en=}jdnCd}C*ET3x;W~p{$ zxG&I-@E_wA_dW*X!)?;!Lxxc?98L8hoTLF;(QJA?XlENFY8A)rmGGp$c6ohCCU>kc za-1e3G2lbe`im(4WZ&ZwCY&YPF>{vF`GVy{@m#8Hna?!C86n5|bV)fSGQme9i{ECj z$9Yq~XHDwBOQctIE*M4ca?@EYP_^$FN$`2&fz8N2f40++vT|XYz3whdOKwh7+31&o z?Is~Jc(e6rdOW26i8lUM+_)8$nX%#f!S69CKGfuAn48Lk4;R1OxdLJS%T zhD)ObkJCxih6!f8Qx3RpYki${4T?C-_8-1TJGkD=irxJ#7LQOQQt4jKRkB<~pbFAu ztBO#d4-kcM>G^>h()>g@=1$-?%Drw0<_xFm5xFt|iD;?LybAkQArq2f6Zlg#^*aC> z)6Ewo(HfBoV0%ahmUEa;@ZNrhdzG2y6YIARDA52*z!85YfWDuy$&>Ct*ZjUzv|8~L z9HbBql`VYdR8=dM-i&3)^W4iOzXq5b}$pyA{@I1(GAf&un5Xa|{~Y zYX|v968X^OaTxJ(V$cOhwpOxOqf@6JDTYJ~8Vaa`ot=$%rL{D)Y#0uTE;JLZ^{>_! zJRpy`eBJ7=cNgX=lf;CnAAc<1qWm9py=7F>f7~~|(MW?zGY}P(ZWtYcNQo$23J6HY z=oq1hbW4LE2-3|YMd=uf+$g06Be&7@-|xQ9b?$Ti=UmVCWKTZt@2jCc017Q=pKV^0 zd~rPENUHvieWz7250S&FDhKKY9X@HcggKErGSRw8UDxbg25t*5Rz6Mdq4DD}-+=n7 z+F-9um8=|7CT`6fJtRf;RC#R!VJg;`-Sx*XfZS+$HMKsP8eEl(pw}XIbX4UAupVryK4K@*6Jm+rMSk zR5nU&nl$uPji{>|mC>z1o)Ax~H}*~~wX@;z$Vbx=P&$aq85jS&B1i8HwNZLP1owMK zF_|l;XiM6_@q5NZA4nJK#ADC+JuNNwTYcX~qZ{I5P<+V0U@tLs<4JgVYuX6LId0sKq;{0OS7f1MMu0yeFGvo~mF6qpCI86}Z zUF(*mDA_0gulj-N&SyqGdN9RJ{uI401Akm5i=AuYS#a&A>}X z-?(DK2Gi(=joG1e*L@f7#p`U1QPs|V7i@Q?ISq6&X^IfZLQJ;#+6w-2wqVbW^9v^=uT zb?3vGb|!C0b9K0=gV(<(nfw#c**5}#*oQe6dZ`uaPbng)Rn(1$(MHwvrLX9q`~TXl zHeOr}XBtiATYXAF^T!Sk4IgfFlsV9oA_hhEsPUc5ud$kp;{Nnp=eP^j*1M|C~D}ANM zHA{itg3p@F*RN1YOoeYXgmVScPHwil5C<@mp4g@C<5mW%sjdgYGZfcn&o6?+_tlB> z3q)5XG@qR;4$Mj8s>mLzEZ1yG6shQ3j;_dX^IyLMM{ zbHGd6JQ4pNpqBQ=r#X$J%2YOKYFKLgy(n@_dQa%@L2pYtH7jD)zrQdflv&`hWZP-fB?JHhT+DL^Ihq|gRLu^Y4RYxN% zt6D$ZEHxG+(Dd#eKM;+PE^)*mZ*|bTVW>&>J}LlbzQh?^G-ImQJoI0aqCmrXKi5<` z2Xmr6lNqh*sp!lch%eU*w$<17G2hZ6UdE~W&m6in)PIRSkYmN!q0M3z?9+Df`XpLr zEMSBcCBehhacJ>3D?bb_bX7_>ux)6zSbAonnD_(rsjqW|Zug%+F)+E=p4bhjDqcN6 zLxUgq5GvnA<5&t>Ga#eEZ)k`3#9P8aL#{#i%)mL$_Jy$1l}hp&l^ODLJ6a@dR#1NG zUcs&q%NBXQe+!Mf-My%cX2EFSHlAu9CYh9e-9x2+^GKWpb#-D8Jd#UD3((zS zvRjyPMA)#n%OO49xnI($#`nr6Ehfq#In9)r3sjR%AaGR#sg4SJOI=YaWnHWRrYUv5 z^<0=Udc1Nn5i>RRJj(&&#VTYjtgMa&^f?=Bu*OPaQHj|va&wb;a-hsarA{U%?23MY z;4seT9b0rM1o=j3*(o{%yeZe1|E%C?kWpuVOfc7?sr}Vu=(&75Id@}|k7)0INBPgx zFYcrN{V40OIdTy+jn12;8=3PdjD3n%(z>{$2%t#+2byq_nX}5Hs{%`^WO72pZ~!X^ zyW7)3WBZ4$7jkakR}eE8f}#7a1QT~&sZ84s#lp6vrz%~8h{}5oFU$6tCch`F0u2l6hGk0^9lhv)7v!2 zo$q5RIxqnF1bsej57PlXPj|*gcDlL9zCibF^{XT^yv)!KZb|`LxP@PuWv0u z6p@0>CI%#sWZmnkpjUhGxuVvTW_XHk!{sFC-Tl%Q343aWr+<9(1RC9@}*+$f*keeNLb_Hk_ z6wZ?28dAMBBZC}YLAMETBrlCGF~4Hh$rb8G;a{qcq9XAP{%Tl8N~AQ=4iNGEdgc-Q zbzG-lgnx|BeLgtn$@1wr`?~q^xkkV-KKwEj`(Ggo7Tr_qb%l(_x)}1Qj8Q$WzLuZd zbg`BHCG?Hth_b)+pMwN_E)i1>2non~dC8jd8i@zka1~d2-VS~qsc~yIF65vB`^ddt z{_z>-#fk#-bE#ISll2`XRs$sX__sxR=E(N*#?%!PK;op~T*sNgUYiP+XYP|`pSQO) zKGVE#3&cLwQh55cZp)%&z>hWJi{DFZ&edyoN1-{M#;xzRnXVr!#%_heC48#J7T+=Y z@-1Z-^cui$L&okiCTVq7wH6QA*z0NYg={1)gdoUqg*-huZcrb#sw!Z|>$1HQzHcJi z%cbycPJf#Z_^)hzt3`gyw|{$EcwHU6qqi*rdE3PO{IGSjuDZ3LHr;$7l7 z1FGUqN`Au-?P!wbF*)XwWXXokFxj7=w(1J2${(H9S|L8O3^pw?Efpd&G>-sDFS4Oh zdQsK-b<#5Jp+%AMM(HcxX{GC)*&-_MY)v~`UQAG~ESTzlP^1!lcYvAA=2zzYjSZjCOe;Ft1fmfFO?*}V5RNZW9ycFv9!?|t9eh(P zWq3GHb${!}9YeFFhxRA!a7lh#*zS=rX-TMwTh~p@sbD|k`UOOWAyC?iiwSBfMrNaK z4IY1o+A4)84dD3B&B(eI9zuVj$VV2Tvk~+8Q6vo76`)nw5&Tr~ z5~nA5^!qBF?N6*Cr&p5EXAzD!ePup~e@B^2&9lZeT8RiEIo#u2%0-+D=37II7j6R* z-cR~)dGW5y=F79|rm&8`kh%y0^mScipjAf4+EcBTT;(9#HJkSh+sTr*+F@3D<+<8( z$}}&aVZ5Vl*=D7rSVpCMt59(J9u4cY# z9zl|Yu`;`iFB1fWq)%x&{c$8ZA9VZyL4c|eVm3QKp(ZEsEgG*Vzr~OC5qDp(07SRh zC}_B2J9|mGTT+E3Gv~fMZRHG%acFt1GqU8F4dqlEX!B5?Y|RpODm#%-;T-b z11%h91Ap{K$W&(}w}xbF)bx|ipL?DFpC@`Qf)XDDswnLhKl#J z`h^bQFPSxSn#s?j#xK%yhgXq4Avh7xIZ!EjLK*Q9=k(*a**(&?E(kv!{Ezfg{15iP zL_n+3XZfKo#RG9_AoQ&Ao4$zF zqxAr_g2P6Y5X>U@>y5vE-MhI|@*4lgIwyiN1iuXE^lzOe=Jv(!o`O)A;ubPvMOXIH zl+YP|UTngle~+xJrkmKd?mtW|jv8})!Mxer_kkc-?ac;L8fI2@ zan>Y=**YAGa;`f}z%_Qyoia@|<6`?i9@gnH@-4#(^HEV{yR7E_6vLi}wb(>2U@p#; zKXsUp4ZA9q$L_?UiYmwaI5($#GQtDaWxS_mb(-(%RJM5EGBO|cw*S26nSe~5TLTgX@#J!ImLUH4�}6L= z+IYLxh3?`N)~F$WO#c5jH~)`#ykbA2eDUcmK(%Y67e8N5ql`v?&$mF=nWMy7Txcvb zWt4>&fep8xVgo*V2vP_ge|E%9cT|BlHQ=(@5Vzy1=8GeJq!ICC{@DwZgFI+QAt>SD zLsIqk-@^UYwxd7hmi}W={;q|oC00$%5n<39peo`ACVY6L#oeg4M@{e39raqXk%u(p z(?h-XrdMe_vGlVgycxFika#0XaOCHg)&cLuU8P~~`>Kg+39HVx0p&8MV%0-*>pyi* zx8C?u4HV0)V}{r$By^UEaNG=weG{!LZotrhu}!qL)iZP;%$on{#`%tO=c#y(#E zv;x-81zl&jPlDTEo(($VLTI~nwY-tb*2~i>(Ds`%&X{7v7gFC){F=f1U73&Lp?bQb z-??l!U2Oo+rP+a>P+>Rhe5Lk?f)#oCdR)-F%4i#(Tea zP%Sgr&nP2$&55?FSJUI8GMv<)u+c)r>c+%dJ=;?ku;`#c%g+lch{~KXA1kw~T zeLFSUA;Z>q!~l9Rmri8SSS)tW~66uPx)oetOClHlX zZbH{fm%a~Qi#hy$y!OEwI~r5| zrnWo{dszI;HtJyK!vNJ{vU&I8L=vgbqsg=A`#VuG+|ZIikw@wMM& zj_&l60a-))xOlI;yJ3eO-i@YnLOfDZ0cBt2@3JNYA*QUj|70V z&9^DO_jZ`iLHD!)PpSz0UCf0MTlMWSe4fWXfuh!ya6c}*Dgxnfa@%1wfBXg2cj+!8 zu5HqCr;uNHG*@|xd0uDO2jNC^!;6V~X{L(}Bjdsu(Yg2hgI|qRa=eI>rWROC`VdrF8CH5s<(e|X9`!9SCwODGH+b7TRrxk zy4zeJ?|^3t$3rhpgmd-C!sTc#}gs!KyshxdGKv+8Gr{FGm+W9eF4C0=sLBT826AD&}BQQ#ho>2J^-+@ zqD5hi1Acc{;pK6@4e=(TpZdV>zSe@Pi;9L`BaVne;QA4AQEuc+5P zGYRr@`&1^U07Ky>p>zx(%3OF-CBj;(VC-2pvBHEk$GLj{l(ZxD3QM7NG(epO@NsPQ zO-P`?GdZr2BPLArPP8uvU!$4^W@&X(F~u4+F9Y6&OP|C_z_x=BCW-Ji&c1H2T^zb4 zygrdME#!WofD`tyruEced#%MmaRCXd<#btiGm1DzMzjveAZ z6e9^KPOz^|F|YieE`a-$7uKj}BB!}Z_$psAq?o3BA6Xka^(c$&W||ruot>D;mo`dx z%9&o+g2P7CX3{42u{zgzx1viX8IiD%Kt_NtDc1$=Z!{?fT6BD08 zr3zg7f{VNS{qNDya(UL27fCKZLSHHGA7g5(SA$QQ+#-Ds;Hx^?Cb+^8Cq#;0MsX`!7Uix4!She2?F>B@WS;lwdoPx$xtn4s2Jlt6bYt#E!PFSVP(!39rc-6YT7hUSz ziJ%=H@@rGW3~Yhrg%dX?6l&s{E%s{Nx`g&OXSaY9md>mH{#gHKy4EL-{QbWR&h<`( zArS<@*}A#tEEr2oIN<019dP5J5%PITZXO{Mb<&JMGh{Bc$J_qmNDH3;&Xv+(_IOFU zpTwsm{t?l;XY?E^>O|3mrmi`I)WSrfw?&1XWgw32aA~?Qb0V&mAzbk`T+@ku?PH17 z_$@hZ9}h-$t_ta?Is;N?;ENJIfI7gJk%H#aeQEj>Fs1-RL8A~j5I9IokbP+0s&bn} z;XfZw7_Ztcc=4)brBK0zs{gXDA2bY~zJfaBW%5XRyeJuS(yjVo<7o!nlq8HSoSAu$ zxt}79yIv(Y&<;y?o)m-f?CpPV^?|ji@uSMY2tMw?`LM|-xuG>vRFIPbn zXzvo;_I~>tM`P%=?3>buuk_3GZ#|Q%K`@pX`09PVHad7sE6&l@NI%j;2K!bz=XBl5zFx{CrJ#IWaFSyErJ? zMA7HHLqxosD(S>+`#FwvqGllU51|P3DT~h$2ZIxo^l{;Wy%WaiWKJ<2-KdLnwy)S- z#;TOZvl>hbo&V4|k4zJLfAx#m;r+b707v6QTZyxyndxJ{juKr!Esg@?Ke;9x!Vbx| zT_n?Wn@M=dBNg~U_&50L_S5RTkfG4*z*7Te7|SSQ*7_bZep1wEEz4>Fpm=L7Q)HN< zB^BFPjustNjN0|zoovk~Q!U77;Zw=c;f$Ls%TxV&cE{P8&jD$ga1)@v$0_Zgw?07v z7=u&#M#XRRl^8w#W~kJbK^#@Rn>B>*nPpP_#y)RLEPDF6WPQJNV3Pam)tY-qxACq- zu!*oHXO%Mhua>8jQBsK`8XuANG6_c*c@jJC zox|pYC!SpZmbX^c6*5yt_>?{Jjk!5yH1ooKr5=BN4ykhS9kuJpJJ7X%zQ3I&8tiYN z%o#GHhGmM|=T|Ee9auv5dP?V$!`k43r3-sA=cS15F8$^f{LrhV)e*bY6+h(0x1dx_b$fy-@95 zNNm&k^CB%2F0GZWt3`Pla-{TG_hCZ6t|c*O#TFX-nO##5Y5eEFZWBf}Msh`zWMVdF>fW!SpJ0D?|_m*k7(4W-b#ky}TP2tYfE;cA>mY^d3%5Q=md${asrcfI@I(sGdXaeAPx~kR794)^woEdYsu`^ji3i(th zQl{LtyP-FbQ^v*XO6kL=b9>A1h!%yI9cwG}hPb9miq0Gf3l zRyOqs*k9_vt{pNh{y30+N_nk49ICH>CV+( zh1pz&#%6u&EDAu7%`l+`0=m(u0PJoltRU zo!C(iTXJFle~VJqWZkxOr(bdcJ=eAxwH= z>sy9mN#`+~&%oHBoiHMgAN-XeE5i}3$Y#3|mWA13R2B5yEc#on(}Ij|!714W*?R!K4kQpRId2nU<;Ok8Y*)4zC~8bUyYNv&&)tY~(DTuh;uH z85KYIUMtn`@Sy`iIY)k4l6~xc6$?s>CbWo@PomaS6PFQNF}YtQ%9)srkIFTres18C zLLW*MygNEONuT~B<9e1Q<+K-yjgczNmrTh;t80d5lRO8*$p9+lMFDqK0LWGvH2c}b-}%vM{FSwL|=5N4v1Io6iTnG$u{}bzB6)d$GDhBTR&Lc|Mx*sd*h6#Aw&LJ6*+_@$97XQ`)AG;?rA(~48 z`1$9>yN`~D2g;uVD}>MYfProweQ^Df^-IF%a<22L?^=1(7B%`-708|!)4{*xvSLEz z==qPn@Uvw;jPv)dKp#@_>6q(JQkrFQlGip6iRSC9Q2{30_<7seEk9J21bM5jm#eiT z<0)N-Tc6}@fkO(kCU4*Os3{h6Z^1Cy{Z<-3!pJAyUCi${5N6<`eR2u&UJ^ zQ};4I52#UTJ=MbW*~Jqz73r9wz@P8ec%w~iS-e_YrNu~56MbcRr)#p@AUlPbVRhK} zD+gJgG(CMZk@lrJpEQVbC;fHamk|4a@=6b{<1wRPjZnRnCQIP0Qj*~8Yz7wfTRAfd zeH$~rS<{0KL9p35#usbqC$c!$c)-Dm!Tfwmz9gvA2RDuFx!BLVQV4JMaa97R1;5-& zRv!BaQ<9yadYkL3P!0pWO{xrD2iB6G#BQxhcE9=wUK%-I5#J--z8GS$Ok;Y_oe~@n zBN`(9maHgN$Y+b5Q;Jp)DrKGdf2qW zp~pS^2eD|wU)N*56H)TZsk3jCtjfwML@LO546MpH{T#VpbJmX?w9uC!-CSHq{9_vR zZ*&e&rQHxpIH?Y4(yaqdUq=rn*WOv>N0BXWIT5hW)EQmPw&x7T0#+Ga;|_WlOr_O5 zNqtrF`12+o`6jl5mI_27yKL0 zYNmLdFdYmn>G=uh0B93EFLA|5qEp~Dn%&j|s+@K`?58ds#lXZpx%$aY1t$!1UUVE0 ziMQ^SW8psfJHqe4)-jGDaE%ZB+6Yy9*-r(I!GAPNoj zxKSY#u9SI3JUSPpV7n@0@`;Yr7vyvD`SS&3;1*Ppdra6utdd^)Rn6jV#R9lL#PRpG zqcVJiHBz%Yx&?PSb=GM36INM`DpT{tHB?50z_MG0b@fB6RyzG|tb%^YfsdUw6-i|_ zlFxTUo8y{-A#w$Ldx|DE88otAAZXy&b>3YrZEvTTZ%D1Dbd}O(wbd@Y{Mbj^8X0JFu}NP&)ro}?euq5 z(KgKg+?~_JceXqriz}xm!KDj5aI8Al^1;ma6qUMveC|1UEZNZ?)0~yrImSb`JJ|_@ zk34NZoARC&gB3V@nEE3tVX1WW6zjYQQ~bM0XdjP1zZ9Lae4_FBqW!{&DJ=gINa0## zIdbrnuy82aB=St*|5bea{|>WoDjBk$jbPihXUiBD9tK1yRyDMA;XseYrQmR zexG@j^<{_HxK9B;O*{oqZIE4w=TYUBmVdPmH82cDu|wmba6V|l9ivB_>4REi3U|j( z9j?W6QRQX^sSc)vESiSNny>JHpBfeKI^4QqqyOAv?M;YA6ekz~)Bb`@#dfV(dg$jw zC6GRp^eNIdC5a%JyT;=ug0Q!fSD75(An_bRL7YT zsJH&zepplWxEj6I`>pK*KxKR@ZPWdF+CBZLYrQ~a^%lwcJhsXD{39*NOlf1E&vTm% zOJIc3_34{4^01qq_6|5x(=RiRAC42EfR(9?PYEON_!0cq^J4u8ZGA(chvOI@M@8c> zf$pV=iO_(97^&wVMfyizperEGA23cftmTrOo5tSama+cBdHugsNI{$Rbj%RA$k`0c zRBMNuh{Rq8?Pnw^p0+8^pA5(8X~9Zq#;1>liM*^IYY#iWcdiJ=Wrpd}9mRHQN2k20 zyNnDwy-6#$UK7mI=rH$bEkeF50;t6G^n`O?ejZ1!ZFn8LSa}?>@hXR=3oCpBJGFY^ zEe@8|&Y2RqOx+Kuae0sMdmi9&pTkkj(KyE??(YU-w6+-Vms00qo6?cj8|M27!tO7`$vnAqW)Y^~ zp@8YJ@cNwxmh-u4cwA3%mEV7KRwRn4c%8(;<6huPee=$xFYT3S6Q>Lc>l-*wr*;=< zzmVLMGYMZUa_CSWhw{=y8Hx2h8rJ>cJ^R{&Yj*I>_E<(PZ(FBF*r=_9PL2z*IvnnL zGx32?4?BM{abEVas9|CO(Tr-;q(66wFuB==;ah;k+#0JdPq?VQ&~M^eW%}a4W?i;! z>n!g&=SZRAY#&dljZv{@4QE2APZ-Vs|Fw&+gmIfb(~OUN#EewBzOCl#Cb9KoT^*?J z%_9qiJ)sGz!fP+vCZF1(v@$n$%>;#eQo(g)A#^v7_}s zyiDFIo`cYRpchTHeH$pppb4IhBj!mTP( z)?jXA^x%K6_ahry&bb_I4GnzsL^D#BZWI(RX?=%vX^c}kwtO{YqQj@m zGIa<@mNR8;`h4Y^-6CGJ7T6B`m!*7fKMeoIbh@Lrr220T60I~5GXX8wbl4a&%=4A` zVR%e?Li&56qbGSO1w2JL83eoD=Wxf6KC+blK(W#2cCMX0d>2QXBtFb&9i)6mrATHw zmqCAW0Yk#+c{aBGMVIn+v>t%Hn9qdNrfb4!xS{+RGJ&~b@~Pm{a(($K0sF~QudsU| z4<4DXC;`_1%Ec{Ci`+n?+-WMOXjqHvOvhwAd#*Y~p;KLZAVxAAs3d4CH8b>UGOcr< z&g8nL|K>en@6WCO(;8y+>#zF%m8Yx1;X(wIbK&!gEsi8_m>TSbgqD<$!_x|%Z06*{ z0}gm;=)FQhI!J4Yz`rkk8v-Ey#CrndJjb7?4}i6QmW9aNk~Oooe)-x84hM;rQCiO0 zDC2mRv9KD*vo`$?5YFg~K|EO$url~yMFj&qZUe!8G1=UOsz*Mh`6#6`W|z`lte1GsDZ+Y%XzrJV^o>B>W&r=V zG`9`9GP2r*|H;!5_K#VctAt z1N}L4_1uvGtss1CXZ;3u!7P_!QTb*#>Z!)5Ss1&q^w4zt55c5q`8rNLrsc^ik*g0N zc@J7%gDVq7)u7LL?yM|^LHQ_8Yc1B*0k&T<^nP+vEecP)#XPNAi{+gtu=n62;Xj9bZD+OCyE|Yt`-#6<+?P>fOTSa z&ysf^D6SsHwBk6-gl2hkQP9G}x;+d5>EH+Geeaw9`dDi)TTELoUOg9K|Fs5^D*@Tz z@IzmQ`Wu~@o=w%D(o3g23Y<#|`irYQ?=Ef*-pDsLDgcTw46Xi$|Hl@F=;l8B-)&(o z1g~}?fz-})byO^nC!FTS&M`#>m_C)vWpw~=wOkr^lLxVJcE-UC<rOQN+37qf%*C*KD}_F+Ad9bpDiv zVC2_o6+M-2Aav2QFW}L_A%>W=fowMMbbY~*41O>H2OlznmdEQJqiFFAoZu8l2D6#mvQJZ?qv9@)Susad`v>=!X3vNrVQNY z#-Y14F(x(-c~X2&XonI*u{dlo=(=!c-|a`IR85Yqdx4iCLjn5EO5lFc!9>5k#>y7W z*1sd^&aa3{V-gX$*e<4gc)8hdzN^@?Wx63b{QlfX0oH$bFCm*x)!FvsKz|CLa;7nh&F1p zzE;BETSwU<8zUcg;GAG^_7YVkvoad4?x^QWNJUNRqOpyPa7QrGBLF*c39jZKR%kdF zu|~=z4yS%DazUHhY&%}rIhYpopUF#%|4=f!+xu=F{<^X*j;h+3-}s9`R_Z&v^jZ8y zymp>-*l26hY;-QDIi1>+-_wHX3Ae=6`-@cPe`oqpd*^Ova^_wMzmk4DPmG`ORmvzF z)w!BzUZWvw-@ULls})#Hx^m)wBBocyWUu#N!@zLXbC8)&;iT^*E#91r%{!#=7mK7= zi)(UpWRh%+RJQYr%rdhADuQ_y?pK}4S}K(G)SPKk_AqF{zniY#z3=VO>L*lEfkl;U zrMLuQ!`}VZ$oD0goTpwxIuekn1kJKc%09^_CHaLja_WBz-<#3WypzXa{qUXl(Zv&c zfk4XxcdGGvL5li6-3-cEbe!A;&luz92S&&+VR0h${e2MSrKt7NDK^J!C~*izsMwkdEzN9`U?NcmK-&ds#f7DI zDdq%%YxZbJ=w=`Rrn83*fj~@*vee0u*vzlVdgYmh^*X6bz9Z7uMN8n%e7AI4U;$8Y zAJZ9L^NxcG&tM&z^hlrX)b6KxiVl>LI#}bGo|#c{Zlfy69Xk#6wyt5OBH*0eA$sxg zF)hvPGyE+}wYf_2DkJ{Rd(_ua4!|PYMF!z(LJxyefu7(r$(QJheB#BQfX^#boD^-` zf2oJ1~iPuZj!4p670Nom|6d$u&O?B-9*>qM2fSJ;y!9hQh~dF(V}ch}Sr@crd- zJLk(x|6LdIRn=42{sh_XtAJ|6IB&er0UF-Pg#af86Yo<@6!ouF`sC>c9TY3{kq4>M zk$H*fK?{{8GV>L$Pgk)AJ-ygh!aPO1=)y9$Dt3P)LjNRMezMtMQf6CKjkTV;>mo`) zY(tUsyf2=efp7d+BQKloN?A(Y^@ZEjwAa&b8~v*mC%y82Hx*$EMFEXYS+|i0ACRi+S@C z_9$j9x$f140&rB96DOJHesn$3z&-b({ptjYy{c`||fcp84(jH%Wp2 zJJ0-(P+>Vr;F*Ud1PZJ({^OY){^ObJe=@QQ2<>tWKDK3Hn%hmS;NNC#fv zk}iyrDfdYJ-4iMg-IlH7skS;YW$nbK)xUz^EoF<1LA8C~K}WG<{RxKJL?;33l!r?H z*2<_}nB;m4Iu*=ctIr$AgM2q-?kg!RK)ws=PZ)gE?~c3Yb)b1OujoLpsbgn3Tz)H& zMUZOC&~35(_1(?8ck=GgpJ(fx{uH7=B-9)!SXXbS*>eUxIyls73tcs9J3{_A3^)rq zks7`^?7Asf?{y>6jfc~J82<~uY1E4hg`JfM-12X)&@JE$&l0vY zo7MQ+>$Sg^hwUK;-I~Ljyw4KCWY*lO?RXVRz~K37%pT9#{Sra$w`v2jdZ z7qm^~rO8ttt&n{s+q#(h&-6OYz`=KOo*|GfIdF|rbtXd~8|?C_;_NdEk7Y(&# zX~!p7d{Bueaof&fd*2qGys7kMDCM&0U3~3#!^kmh*Qfl^$YYJOJ_Yjm0fr^d=&ZzQ8TtU2Re zo?hQo<-F5Sg&pp~$73hP!>rsaP|s?!0TVdzUl-%qkY5f&A8aBoi0;BKT!DJDO)=x| zu6ei};!lc{@Atz%YmHk~Rh&-xd|^bV6O^C&VZQrR+@q2lB1Z{3w|7}q!bs>2aTdpr zi;}j^KS`~zw_HEid5$;eFV5601w=W1V-IR!E}^zJ?B~(?M~FJ2<@CeI2w@`!yruG8 ze0fm2>Ech_CnT-I%=cQOvu3ytUe4NwXOzC1>aRDR5vuyV;-a`XF)J;UK5RS-S@wR( zr3f=$3R-uUX0)taA-J-F;uC_Tw!Du~U14>%#h%H14fo_zRqK{-A-7Xsu;DEm6t}6c zwn8v&-uB-p#FaZ-lW_n!e*e5;lX%K;aGM8TsdXR%uh`JeJxYYTD!Y56u11};kYg;5 zGmn8+^XzH%-1(@FEj?Cbdc;tY?q{f}2EQOcHGrI`o5+QFpq}iACl=F6cTlfGrbbL% zqKi!?hjS@EKV_%TT?qJH6yD6mcR~|lPB-v5pN8cA@;YrExo|FIlYV{_wJTdfy{!K; z0oO23dpnxzJn$P0mW4c#l&4H-eEX06Ci{ryv-|+rMxB}D-LXP#yI8b{Syq$pP_O2FFN=A53V~KuCen~xVe^uLF&rxVu;NnhS z*UuGHv^++&`ByCXRr_vz_@r@riXURns^?RuXxjznR84kwRmm zt1LywhW}D)Lce66)=6wGOk2sYkMqO4{t1ZFkU8-D10OA@1~MlnoN-DLoOtK_t<}RX z?d-&f&PpXpV+hx;*JXk!)^exje)&pkf46EjX<$6#v`hXz&m0$9X+w(jH2Wdn5iK}M zB^1xNe}!48=k1W|D+$O-c;)e)+M?e%v1L~$s!Rw!Ct|w=g9jKF=4;%p>=H?#`ogJum=6Fs9FHr(1dm{x%wIJ1%uJ-hfFZJH zkPC>Z(zQHS2-4HZ2NY%z|5(C3+VVSjZn;@eN*LKw@l}-BobZKF;{v?o?tC4fTV?w-LZx~L?|d#l z{L0^l!cWTViSPk`q9ZX0jXIy6#RFY-EDf4gv0zI*$g6%XseBiD3HY^wX8`c}`y-@T z5{}ha706v_BnH7}B3bb^1zsd!j+&fwAs0eG^C5Q?m(ndeV*FJ27?_sFJNJqCn#DG&0JJeza2gk0w$Xxwyz!yJ3=(o_njqa_M}6j?`vyQ!7U|8LcSx)`kc@ zf)2kN8mizLaV9oAoV5v!Ia59RB5lTbGn(M+&T2d)0Fp6I>0!fy2w$zUY52^6ykaT(f zK==*8hDPi*`jGcWDR$xG(qZf7$X1(G=j!0^Oy9ds7WXr*IJZpsv_YJE6*Z`*==Zv@ zOovmkz-=m)Kt1#M#i7wg;-*aR@yL4-efE{?P8+t;eCaixiy@XcVKJS@y@4#kvM5Kv zKaUFUg5OKvgeV%^gr3-yqUnYnk=CB{E-K+w1ScRQB* zl?V5&PCcB4vR}{ByJDy1XC}6*2lePB1G^jEJ2ePb0|7-re5$tQb$3yHV}x#TwjU9= zZ}q(p(fhd>rYk;D{s`gd3C67Ix`vNp-Z~?bRho>XhI5#kjp9$ZVg#q!Db> zRjq?tj>JA|RFdU_XEoo_t&!Xb7QT%?(h+a|^SK83maJ^}y5O@k=3(oD>it+`VF43& zOD-B*#T-{{IZOF_do@K*IA>NN+;?;M!6NYp21er;fZ1wj)zEn_9%gkSg(7MZq__|H zDr_jvDB}E_Pkt46TM(V^V5a$0>2==8@=d_}+}tC5;EDpGBgRKWT;Yc>*pYK0J4B%S zAY54q2JdgWI;>WHV%FW7SqkHrFEYt!Z0vOVZUV0ytIALU! zK|HpH9Avw0dZ)E{70_2NkJ5;y9Fcvw>@bwyEn^ti<6>|BSeYJ0B*Y2gME{Z6GCmQR z^+B#=?*S91POf^Z#C|?{v3RMI#Y}P4xd-gJT$lFwcWe}Jq&-V&gcJyqIIFSuX5KmZ z&-V*>}@>? zB3Q4`p!HHwM=40Zq)3O8j{9O3A5U)hf`i2UQDq_lo*yqmx zVa0L5SOGQ5XfLd5BvcwVQ3dKE|&u~D+n)C3^_gYwNfo<`ldJ$Mczl6FC=zBOdF z<cs|s$WGvVDa7U;4zS=3?wH! z_ka(7-hC?GN7gIu4%8=#>h#;U8la^Cm(tn}`5&ebtrD|j%iyNRj@La!q4R}0L&=ec zZ(Rw87tR{eQVESatd7m~Z&AsC_r{7wM=N-fD8kL|s-Ap+;rn-mw}$TxpNmmC?F`5l z^#(eKQAqy6=JSz~^8xsLw7W4VFQ<1cwRw{C|ACXHZjZ`1P9*s+52zJrq#^=|y^| z3ep9XP5|j5y-4T?7!;&P2}ME&>0OF6Md>9FB+`)@Kx#q@#l!Rd=bd@aoboka_Dp8> zUiW=nYyFn(Y}7h@G-wy|Da{6R1V6!`r$Qe)B{rPv|MT{!Sy$y;Xe-#m0YZ}~s&;4< zcz44nj4xH9ZUmN%w@KSL_cwnsQ8Z=t^k(Tm3|+bnCi%Ktdy1UjHpXc>HHj|m zMFYY$y9^hBZUlzyGsH>TL_})D77df-|n8YVP*g};=ousvy z_p(hmzWNbHqrl=5Mg!NTA4aYcvbOb>^Q~xl%|D$*A%n)q`j$2rEOf;mc>M)=b+P3i zS%7SUKX^KkytVg=YwOYK>{|F`PgkjNkti}oE(aCZV$8Xx|B~^q)+Z6lSl8`oV_@p> z;KX;`*2@J0kb|TE&w5bKGq zq+a)PQy|Eu$S-x?!YbPM39cnql@#TF`zwdLJGsbf-`4!N)`&65KiwOD8y?u6Oh(Qm z%`1fwTK?iD`&y^r0~9W7)kZhjsQ@WIxaJ|i*pD<7GqvYci&p^=ZxbGl`pTc3IV*>j zDt6*Ow}+oQ6N@$(Hw|TRp&ttM-zHGtBVcEu#wvTCm8?NdThm;nReZQbzg*Fa%8>{q z8Qq`0O4slAEs+Y}Yd#Z;v9;JuQ{@*P0nlD)g|p9#`%AwKINVe!ADZ{w;wdDM{%xva zye&VS?LgWGtGPoaI`kCr!vG)mpd;5?o+Z1KHHK_Fk@BqAU^PZ&#rL|5`|sCL{CCnB zXyTp07m5$cYoVT%cZ}N(x=oN_S7KeamV#RE*Nd#NO|Mp*X~9q|<7vH$Dh0%%VBDLg zoA4%+(=7Cxn6#gPU-Dl393xA8etQbS%E}g-{9Zh2F}J3tx=?vXHc$wi9D<`n12@M4 z7`;in#X{-C(+8T)8m!zK)~CTE>c^T4&owwQk8k;rPQS*pmrW9yMSSOoTEurO=i_aq z#{SAyGy9uW9p+ht=@(YCFCf(0F6&KS4o3LZTm+g^9d2SWkwpD-5YJ9J^ z?yo@oM~V4_31;q>mUJ`ojK?wQVLZWzPUMyR?W$CVcUNjDe)AR_lgWt=(#0Is`_D6Gk@@UWD2TP+qg&C(On_tP)CUmK`z-2;}M2K|Vvo_E_u4oS}Q{@uQEu;4ys9DuiUMa8ap z1;I{4i9(H?_mfp(NTW{WZ;0LOKFWtBsVTekj|w>KH$^KXaj^H^n04(<$+Fu{-M$O$ z@al;RZf|*P-Ae)~akDT4B(Wo?e$xPi@=jQ~`b{misZW%A@fdk1{(U!HFq>SCZKZUA zAIb6i&Q9;pm6zu9wjO&fmH{0$OeTaQ`i{AW%3amLDEQ_<^==i@AQILAySiG~E8_nj z9S%;Qf6>$P4$VBw9khJ4yK33-Nn}7#s=J>Da8J=OFsf+FXPI1rLB@R_L-d}aN?dp6 z&H~z#>#{1YAGU=KF}O>)PcUMO>AXwlb%w~F4suJYSm|d|Lz>9HV4Pe+FNayW69giMMwGkpoq}cD$w>v z?{A>MwP^QF>Ntfd6cwu{$2_D$y>qkBJ0EDD$83k=^4~WHF@TqG zQAnn|pH4uQLQDPWFC!#(N@_mch(BSmz}n9$JD2qRTx|+jHAkEW8NM@%(DpqCmRfq(Mz6Q@FLrm`rG zmLgH(wDmWecPuz@Nz4YHqz^={8^qpCx&I<_Uc*ZL_+#@mEK7p;67Jp*y=o3#H^hQF zyvAzIy>PE&F0U{fGoxtl`Mo6pan^7@&X89tw|dJ5K1QNO`c+_;J&DlV50B^?Gwl|8RXkZ(Q_ZB|Woq(91i&hn|X>tOC$zJ@5&)9R`!9$(@jqaU%-O~>GxbR^#%=6!I~R^Kcw)9Hy144CBI1(#=W~Lzx1-tC=aD|Y(6fusRP$et zdroQA3YYecwFAPU|BNaGIrbhQ7&{Mw;Xgp6AllzRRb0%}h|KP>vnim!_0nFbkvV$Mh`>Ei?D8) zA)jAhRmJ@{wSPF3`vA6ECP%jS!h$ZUdW7i2*5n$Wi?=pre;d6W>a_+GYAk2mhv3KT z&H#)H7Yef7hvIZffddA--*ORq9888Nu;IIDN3r*_W36YAg~-nDOe&=XMqZ@0b~qCG z8S-Z-szI#L?@$6gyoGCmYx&o`QnS2BfaEvRaXS$+7RsH2qTBd%)IG+zUX93Cj)Ao4 z)cI<5PpJ7{tEnK%0{5#7(zYUq-(I&H+x{8wTT}-Zr#K&(Pk-IhE0oV;8IL;nIy#@0 z?%?&T#r5ps?Du$b8R2vzSLfes;$^hTPgByOb$SgZyOMNF3|_QvV-hGfpX8VaiA0o; zYIFvj70|sV)tyr9cHlU4oQCIhM*VyY@w3f2yQ0`dhI1=HFJ1PPevj(R68FFt;J!-OG0>up-6C(QpBRc&Eb0^^y%z zkDJf*@(O-sZ<7RyQqmVimEE{i^ro@u5BqJE5YwHdK8Jat+rJ-OqO6l8D)Sf;O6&GO z9_ygpkTxH!^u+3pf*xw~!a0oHG%-v5{=GQO&oK3$LbkX5*8c7{0|v&mvZQ1lrEh%L ze2a+psS(5)dTNC~c)3AV9P1?z1HCE5S!=@m)`p;0vaP>gSN9v#a%C~y; z$Ny@$JOJefXAiiw$A0gJ9qnJ`p6Z} zzf)hz@w4d+T!vY&e8JHn^YGAtx^`-w9@ccB*YPKHjfXWz+;b=gQ#c&uRdm3HudUy@ zysgwvEoST=1y&qJNc84Sc!ngam_tY1Wil&SOXTde6%);~M=$+;Pwpi`V%{DAP;@@ckbivZ4n&I_U;I-(^gZ|et+$~;Xp^Tu*$-E+wr{*HLJrHlkr;{ zm!SFX7<31-3%B!H$lx7K?f#cw=$c!h#2`{`iw!QCx9+lETur#^HU+pl!=-IZdk$Zf3!^Y?*t(C&9zTc>B zG>P2H&!d||JPHacuC9L^ET*WPD9%aRsR);w<0sAx3DbK!O5Mk7Jb$mF&aWhB=wGwY z&tQ1~s^ny>^y`W)0G4D=HpD3JhoOt#Uw!8;s7A2dvQa%W76nT9s^QXM-(+HXkNeLH z2T?R<_u}s4+Mc+=$+vvqD{@`AT=_{yWs+{qud+D6J34q$0SjTgYa=O#ff^!bx; zNs>HL8cKRWVnoPA1rd4D@rqT}uc+gL4~N7zY(2@-C{C|TU^00YPqX9eIpUi=J5&I_ zr(XvATj{D@2QT8A6YgiIs?%wA%_s1VVq%voiVe|Nu#f&m|`%zF;arT_U=hV@H5X=|rATJMnO?14A8N*{jFnNgf^#ehdPz}=NMQ%dM4tt*zzG(7$jStF_( z^#9h>|EI`mUW+UNeJ!$|z2U#U|0l9((960m81&gB$diuTKXB44wE|}jJO>PI6{E*K z5B}*{Jc}@F2N);Syrcj~lQi-uDMpXfa-`V{7sx${$(Ts4JuOr3VR}Rvu!G1uSP}~~ zem~@{unQ7LRWOas_#U8bPSTRz)0-T8Uhx4%-|@vIo{yUeKF$>@?xc$Z#g_V+g_)QD zPWbyUN))eRxRS{>3R~E?6B2%z0IZg#_tjPy?d2QMvOknli~jMFuuR_}M0YEgMWeE_ zlN}u)_Xq3I9bl!@bw?gzs!}ttTVe5DMGBh?^plO*q_Zya^pgmMD96;{b)hhcj1e(2 z_w0=D+dgsAYqOlLzIWpL+#3}Q_Ik=Hke9jH_pId-fDV$3jWd~JC8)o%yobM1`VJTY z2q_3<=WgVzAG>kkHx_zQg5V63_@=m_{10^K5NmL(E0T@Hl(A@mnG}10+l{cM|5_!37Gr!%M~0#&6OFrDd`E-Dh_Xe zPoB%ia-{e(pMf@2ocHA&SPb@v^{;il1UoqTJOHRSe)V1}iC98nK5R2PUJ}a#Z44+# zEb2I3uyVUy47sUQeg{H8>6|J!mai|bAOy>$%5nl}6lZla*3cm4PVyM9;-c@jZvRxO zxUBa#Y;WV6`*+qJscNYwHfYu)Y&;#{mS}Tky zUyC*_&4;FthfBAN_T)bwY0IlkpBuSTe_pL&lSb3lb8#Gh?wDC^rfUa#;#P zw1f8Gz|bXx)x{iIbX#ww<;#hD;BVuPvjW1S+a}x#Tz_CdTj_MdI$4G#Htx~M4RoXM ze(&-{W%a+d+;L`zevZ|If0z!_KB-CB)?c@rL>yavOKpL)!-y`HaCEc-h}`$VWU#@H zr=7{-Q3*{WSRrY$H!zz;^bt(umbo9f6fG_S8sfaIf<4xo=S(c6U3mNb5VdQ39Pp^7 z1{zP9`r$3zGsJntE1nNmQ$mKwSb+%eIf$wO_GfMNFtfB2-6XDvLJg^EHM+yKPK;|p-aNA5P^`lUp3iQ{n zv&#*+PDP7y^U5QGxv57xQK22f(tNeO@i0ydbbhd`VPe|MB1<`WH~sc*Hc2TLPKPBo z^Zf1HxczbPS8#1d;!m^JO!bgTVowW`~ck?h&ZI z1Zk)zT8oM!hI|Z3?m_|ouC+5qmZZU?P@NW7ozKp`z1g~f!eH|`4FLJTZHa&{Z90%G zjFMs{FJhN>)9Azl)5c5t;T*JtQLzxBUi8OWAE-^Tb~M`C7N0w^eonN%LNnzV2LlR+ zbyR*$juHC-23uw@yb4N!E3Ej!@HbH$?A#2mTUe>q@wxLrPbI2-*v7%(s=y|qWA{31 zWL&Br^VehL=GkI_T-j2 zYs}rCIyYV@6v|yYg4xYa-)R({w?Lo-`+v@G3vHmzZZ4y#CCoIAc?Xwz7MRXIb!Lex zAcfU2r9PwGpfjK>{)lm_P+`@_hN@$Vzf^CA|IEw-lutD-D20}k#?f^4>x5r7a(KWU z9^}k=Qz~!A$tFmg%=+yM&qh{Hvip&HHB9Z}*dX7KL;~~t&9=SNR%@4;(H-Pj)Zw*K zwvRODyyeW{RYtXJ+^`D{$wN^1ELrQvBKo+wrEFBh0Ik=jiq$$#d_d4s-0_gaVf*@$ zR+coYdT$;fp6m=ofi|KD+jV)E`YS~^+<^Q*=I={>dyZBF5hk^3t&mi<|HpT|we<{)i)IB(# z;cHm{(W;`_LC4gTY!p?`$-!&nik5VgZ0M(_v2GV}6verBK9HKJ{@JZHkS-_NojV~j2@(!MTtesH0=42o+>z%d{+;BinWNhICSl!+)r;Bb zoB+z74X54%3i&TULv?|lmB=HW_?^d)ZQL0C2rt`70kRVi|^z8d)k zyhi|<1L(H?NHJZo1h389kqR1+RX0DR|5X&xsS`)6EK#bE=M^KIcV2B{(&?NcmX$6X zZSL0&WlB}`s1m{~(r>?hO>p&#v<}>diYsMDgYZa$Pnm>4Y10+nLi?g+68? zD|Hw!%vDZ1T4jaex&k)q0pE!nWpw%twY;uwGF)4LH=MtCO!@`hEgn?A9$Y^3vq+BN zr8@!;(bjaXe0)5`Skx3XDmgIzX-is7_fNSi2J9*RNlbnV6l` zx-2cXHxKwwT1ZiA9XAlvSN0JHF(O(yQ^_ol?bmPOv`z%Z!3;j}S!p32Jb=F0`Q3>Fc{2b`&jOQ7bb z#<^@j^e7XLuW!7jZm!YW@+X6Sl~hf;v#pn4;)$r(tuKHIZ5bypR& z;cV{f)$Yl^-9bStshg#aUI(Cqyx4JCA~UZ!S;LYa5zCJULah7G%|kCKb-t9;RhNN9 z&oW-$h@vFhiWz#W{Xt*`%{atlCHUvY!k1m6!j0>;o!@?C4`)oP&;-XghH@H&w`%gIf zh4f5*;SkhFb_jlttgWR~sx*nU1MERJnpiQ9Qbt7;A zMW9X|W2iU@ec$1sQJcWhFzDoli(t}ifXgng)6wm>TA5?(vw*@G<7->O-4)o(WSmAt z8<%V-(Q0N6ec3mK0!+4Pnpv8%2bpVAoKzl+?1a>IRj6O+naf!+0s@~)wZ9TCK~_$Y zvE+|gR*-ypVleyB+juGuslUbf$mdn1wZS=wdSdxViwwPN_W6T#LCyg+Pd_8q6K3ks zmj3rF_CIo18_IlMJguSHv#H~IIto(($#L+OhhJR3PNpV-2LtYV#=QHgwfw51_vx(7 zZr=8?cW@TWk>}l?oD7_qo1T1@gd&w*T%6Vy3=(iRv6rj~ZjFhl^E<4*Z63X#ZR#=i zEGKwkZdhv`vs27SJ=7MO_DgAVBSn(yX?EY({4VH~jphr8zY1&y+Kj z!z3DR`G*!I`9$Dq-KZ54y_)8_yc6s)mfI%$c#b^cMYnN@I5(K{9v46tut`bF(Wtop zp|vdZn~I>?hPej7D58nxnIwS50#u;wm5QhQL&mk$P0`Kn0}2$1M3Y-g-<0Zx0&?A* z<%e8Z^LfE?G{+5L^U{uirzB#8jHX$ye-I;&jtLa>tnr2lRp=g`Pt?=RZa;?Q=3??8ubF#IWc7WqWYa-zgiQQiEK&#K$g`s-PPhFpl=+ ziLz~oe_>)<^E4)GI1aeoRvoOwEsDSSR0Kasn5@%{o{CXF%mDRwRUpe-u(1IZbn^OU zy%ozX=^NVt{^8I16RwurHQ9&v+)QgW1x-ysujp#A5idGpV>C5uusjtT%^R|z$1NGk zzQ9^x6-%{Mb&q9oWl*e>`${s>hhwU_b;F+HAOd~xmjOeZz<$|PeNpWm+q{cq;SFJ* zjI-htMeLV?QKr>Hb3YKn%hZ&tY@g0r5~F2_V~PZ7j(*LoFtp9s>*k+V@y<%Ebgrkt zbfha=6jzgu;SHQ4DN+mPvJ&H(iD03nIFSQf;zQf%vLOx`@J#+Lx6PnKrz7sF)uT+* z;k&sAWh6f(Cm670Mbuo`o_|ck2gx*Y?;@Gqk;~q~3epH3m z+z&Sk4fIoSY4i%2-?_FqpS~ zLYUY%9b^zPgU`fkEjiOkx`Ff-{UkuGgV-3Y&ri~)9qD;0o;;4*uzP`yEO(XT{OiQb z!E2$MO>6rePX(zdj~2UBwBFhW)cPikH$6vUrjeB)|Q4LeBI zoJcWH64{m^dAMiw6jT4;vs}buoGWCwdfrO!tEGHAHh-9~+8FUzUJ;YebB$0Fvq99Q zkSH76@ba~w$ciJe&P~<@qz4?C_nMo(L1n5X7H)2>ZIh^d7?NLQ9f>l8Jlc$~M3}pV z=;b1yWj(eL8;qMXX>R2*!rPNFzuwYi)~@sW{${SG$&{tO%@kjB74t^y17mjL+4SH*6T&yP{j+|w(I#~h;_>I`$zb#+vZW7@OxD- ztaGHO^^@TG2doc}A;ZD0RuXQZKg^!~xVTj$*sIi6n54a?Lp^@Dl&cEH;8g)B-x3DK z_g;iX$Nps~alR(Y5f^1~848Xt5r`0Vkfi6jQbQ6*^Uz0r`C)fz)JwQ2m7}31;t3hw zNI-ep&Q%a+t!i<0rI8_1{3jnjR;?;THk=Oc6Nb0n|UR$Wnu8> zAkMppLFQ5H1?YGqa(Ji>M0Lm4;TiGsR|Ci%e61ZJ)jW1InAa5odH0Lam$#bB%JRWe zTc=m+>6$#;-FZ|DbeH+Gemxvc!cyD$%@*V=6TQM5?qEMh>oKasyk?QlPgs2^7g4U6 z6uHeiuR&9uTnq|etm}4VV&3TQ9m@^J90`=N`{I7l@S0=06Qs?SNe(NRQ7Flmyhod+{~^XoV85N}S?nhVnH*Djz; zl7s;wzSrN3tAMY{o#`Bv?;xbPrT^vW5?@Al_trNm-si6K8g%tA;RcxBg)u~cS_d|i{><;S@Z~^5 zwXyEzSD22qXchD|-(iBPR-x=X=6OdfsY{TlsKaK{y^f+Z($n8lm)(&nLzV?tEdRAU z$x7Zs|GXE8V9|1zL5Kd-TeE2mf_7?%3nvZw1O22)*+cwoS6NOdCc^`?WSO?3a%-&V$P(|eV7V}7vmeE;p~<2pHp zPd?y3iFzsed6(V4?^ZY2F8uIsyuvO$Kqc)4{*-j;$<7Z{`pL~++I={UR=u&OI z{S3Ag-xSx!Ce5vg(9IZT3=(>wGLs53sg-D{JpV}+s_Nh>@?o>{V6cgHeyFNQQt);0 z(KgA9i=w`eXi+ZLrTjqn#oT|>X8*f{MPPp7Vzi6a#gXyYqlCUDA?cRbq%LPbZUPfi zNR9!k_xb5;X}{a?uXdRh+LT6etLl$0 zRHB2S$H9RsmEh%K#a%xCWMrqA2#BQ00I`mpdWWAkVNDP9>+G8f84B4>rI+8vxWeWH zHuQ2tiFV$EcL-*wA5e`cPX$6?7GLO(WDQuEg+4azC5^95OLfwie}J%}ifQHR@ITZx zPjb)aHV8k9O^FfZ9w1hnZ<)<@>;(%~B|Z z8wSk?&gKiR)8jwT8-xQ;1<0E%+H66e;NRmE@ieW)d3XcA<7n*{^P#_X@y@Q}S>9x5>e%1sB!s|IR!Voy^xJTul=H~Bz|*J9 zdvyV9<_Gt<{MN#=!*<^AylNW)kAH)^x4^_q|mDyyd%MU5b%XNQ8Dn-nncywisw{| z@@?A2{=T8W=ytSo&eQ9C0^cq=WH|SW;(`e8SVBEIZD!>4tX}Ty*`zpFt#2d_eG%Kh zC;qz1{&+|HQcsObTi#`-K<{XF4HqHnJJ`MycijxhzM}VgD$=oWR2#Lv-EPOTlfk4E zxHrCvcc!vwx9eQeF@Iu7jz`!e4$WGoJhxWp&r5(Ds1iLekF#j2%3d-x(+nNMsB;4@ zmkbH{w<5X*h*oLOkxfswLY`kF+jPyCb_~fXv9-*HYjWnIUVjYue_H|nr}Eu7<&i}3 zM-H^9&;g-Ypyq%!B1wWBykpOXgQx0+$r9N+*b2uucoufr0?rMEK$bu40m~Mneb{cBp zpBsA{`1+eN-H^e0yqwuBkvmwJ_%<=(9$6waX`p;=)h6IJD%#~^IQ6zR>wb3{Ku~;7 z5b|M*?2REXMbn{}RVQ_&UjGdJbumYO-aqlFI%absZF_S$2JfnW=x)`OTx}J2Z^ze# z&v-hXhC=LImoWyHqYLBiHwl4XjL13;D*p3Ve3O(9Sbwp+A4_L}h-|8SE`&n5#al`Z%EWYYIX?pdFGt#j?)UAzY zL%iyJT}AWZphL0oJBY7@U-98f4?4&q;L?a08m#oadHe*}ty;_qzKSU}vM9UHaZh&I zwQ5%VM##dRgH-LcN$?|zrTCeEn|DV8YZ;N)*>aD z8&La+-+E+ttR&~sJu;w|@O|QCn~h1HbE#iAkJv$38fJ5TkNDp2x-F!U`|0rD;ip}$ zDN<>aZiS44@UxTWf;#n6?ad-jb0UT-hz=KeY1>NcK4v=Y42YA)E(&dn^u+PK^iF$`W>G~Q z9#082^DW|imVaHhJJvAjL${)l)0=!#%IaYSLoAWMHe=;BwdxaFdQS6pg~J=nAsYAW zg&^~RUb%?q;oIw%fq;h^{xyYiMZv|4W^{9mv99*dyX)a=JK9)`QD0>DdJ3@~A=JDT z$ND0*WP|LzEd41wNY{jKjBNj+yc;bj=uAq<5NIX3u!GxX?@H~|a_3ZjeLeh!_D0W{ z>UW+fB;*>&zjLDvS@}-QAljEkV`EGSq-Xu);AKc9P2w_HQaX1u998S*foWd?g=4;c zlK(-=E%@!(j~xNg?WbctX@|2}wRo4@Yv${>9&Ultn-sM%h~~4ep6jZzCD7NpD&8lh zsn~Yy+O)IG(fnENyEO#ITo=Shaz|@XKFWUw?VkBM8{96`>_0^}ySDqa?}N`_r4G`0 z-XW=RrP}yyLQh|}Glrs@KFMw^|6zygXJ^*U+@qzC?f$krPRFSj)v60f*q`q)gki}s z++!Tyif8B;FffDjvIV;Rt3B%TX&p`aFL%ZXzV2eP4zi2*Bm3^I9|NGLPi$OgFXmB> zJfyZa(39?fZi-5`S^<;yf2g>xccx?Q(WcYPfviP1IhCx|*_HBE(?K=3f;(q)>iGSO zN`=GCY+>PG4#nOt&(rkFgVXh+QsiU>GqVt{ofg$=~u*I{EBcaZ(>xOt+K^ZZp#XHN3oKeWv+$&QQH zz>t5Vi{}F^uUm86{n{7UXfOH}FK9O_I+usGd&3VH|H)tO?p=oED0w7z5v>=?@J=}f zrn{v|7l}tc>ks+9?z#L@J*j5GFBWQ=1|a|6>|!HUepO90y<< zn|)Ff!e@^P5p+lCEb-X@)9H-9H~~-o7Csw!2G)vdrt?W~Igln>GOB#pCw^aI=>bY^ zoHznr6E-z|0&!RezYf-h@4Jh#4e1!JU37nPFk!zu1_6eQrtZ}YDtEuQzr(rynL47( zZ_>L%qVhDoDAc=KjCjj=^19TZ9`I|9+04<30v#Nz5Co_;$l0#loa@-TnTK--TDm$< zgH1XII2L<9MucM+UDa)~24als-&}af%ZTd4V^WAxZ4r9)xF&(8_!**8Ti}%uaZQs; z=ij>NKRx-nMtpKH!@R@qjr6~H2*6c^Laqkh+%=J^)9ol#=eBkDeo|CX0SGc`t7}8St~H%_v0`w8 zqZmX%*HgqyxJ8`ES26p=^pt;Rg^ZJ=y{VSp>r{cv3zc+x;9(>R>-YoC=T3?12-|6^ zRQ1&MSudw^2S^P_I@f;B0iu^H9`^9B9~cU)bNHgAIQKdug(b*`yZB=gA;Q03RN%=G zb@AJGic+Wrix>us84N*QrfUr7zTfJD0cj9$zsG!{6|xh@EeS}(^tKj@UyP!S9Se$; zpR9;Pe>+a%Y97BIX|t{steHdME&@+j>p6ML#j&ZmIft6{GoOkxmV1REq-T||7Jgj7 zS6_R3BGKv2^m{#rERm|0JA0a(6);#79m&x4gGrtFd53fP;GJM# zci(DohZFRXw&9E#c`#Q&->y_VQ+*=6!GtC%#*|m&c6a2+*l!>7oXfddyt)zNlR}=ekY;yqGk5#Nw{-Mo?&3nt>Z+8_*|E(3;k@r+z2C6u!^5E$4GnP<=aqg% zN+eG$Gfd6`h^I5>zt#_Yo6iBW=URV(5PIUNUTpf0#r6xMoRvC%@@+6ZgI&Y|;Y8bY zx_K1asmY<~!UZTQr}M^3gd@CnDy9_RC6c)rZgrlHVkN4&LPTQOewAsBHZ-5(ugFtz?;a6vbIp48jW>_GPBH-7T29bWz*=tlam4NU0ZX6~W z00w>}IVQWN*|KprR;hwyAA5Y7jTTK%dP>eU2#6*LE3w(X=Rq&1VjY1tGx-wZx~j^Y zE_o6KPuXw|I}onf@PTQpJbmsXt0=S>6wyl@+gS_y20ANJbG7g$KL(50oK3|2#tURA1baBK+QE9#v#H{VP@g!i9zn%jc~OUx$l9& z5Qb8&ef5CV$0F;q*2I^rdG3~ofG!tidCNB%B7PJqtX@#Uu)<;9!w$zhVTZ@Ld6jegc1( z^>Tql%Wg21a-Nms$ID(5ddJ|~GxFZni0ZvYf6HS`NM^%+9o^7X>q4y}a`vNCNQQBA ze}a7otKb-|S|XhOmhx1-df?K$zABsHp*Q;Le1P@fI0#=tNdFcZ)!WDbr&UfbwLbc_ z3NC=8Zb;J!O49xjYqL9ZwC+QU(+&RT0``$+sp-jd@U(7wPydvTh0^?{(bcpBMO$90;|rLT-{ zP_`*ev|Pn1U&g|$hD8x~&d<9Jl(ojX_KR1hKIkuC%Ob;x$+^1W7jB(x>xVgum)HsW zuEPrdwz&T>k}p+Fb{p1o%s`EdzqgVUx7~WEOS+bHOz$LY&ePQ%=BQ^j)KchRBzz;l}n<;w%$d6K;9F%x= zxNwtZBd99YI$0Fl<)k|dO3qQDEt z-HyG~%13cdVGrDQscj|YbM!xT@(GV56w5^>ynYt$y5=x56-9*dyvNqmlxQj+3=oEL zFZ|kc6zLrDy?uT45Pqgd13H|IcvdYHY2Ho2>%WLJ1eN?y)vr@f?C=9Xe8;PWciw=K zro+c5J%TiPCZ>z7QDbfMFq(5lloHq8UYkmx8u~jatvK4QTOnS`m^>HBfpv%oKCS zZ`CZ#dn{FSLJV`fg>t&M^Tyf49XX>3Uz+8&&dT&N zE3|s**jZBIVIb1`^UM)>bM`i~e}#8&VI-QCyR}(!XEIN{%jrV!rGFEv^vzYgdV3om zm62Zr>`mScbL!Q#BZx!lYPmOU>D&Th0iBHHi(@6k{1xoj$%>YI6=-M8awgP?g?&N2 ziEk0=`g^tJP|17!MKb()U;#~b>inMRJ#z6!ofUNz)b(yPiEEWzjam0k=9(hQ?HqjL zXv2cQJ;}Y1AJK@aw$wG%1p%1D&5`2-*rN$*gSa_mN`UX~oHdEY*cMw=`%k&eFg_vG zu`x=sywi`k66bWx-0(-b?IX4Hh=)UbOr#mAsnAG&X1_i0bdmND^Ao0X;Kfqd9|7}{ zB2z%2jDG}|35smX{Fi^&&c{khkF6L!YtCbT&(_k;{W~daNm~weY_%T(bw`CLpL}?% zZb?Nt`LXJiq_aeKsIp!!(nyM&&5D>C`tZJXiaMuhUKlpFS-AlD^F_gGo#TUzn$l-0 z&z}E@=>e$5$?=XNp)W)#HVT7U-E~i_=JfvJ+#sx}9$u6xsfseCB}Gr{|M;_p>P1XA`bK z>fdN;*;{ib!kc@fp|0oB?wJ8xLrKT8qwvX}X*`a{Qw*+s^L-LE@y4*NhRK>C4mHiz z4%L@*1Fz>4wLpUn3A2j2ri1T7iq(;_7yd&74*L~dM+&F;3pwQG=v9w@Pl!4 zqF4u5Uo>$3F74tE)ieK1rBT@Uh65q@5g#mp~hE^8Fk@ zwJb`V4&*U1v}82sO1&g@9Jb{~w+A-XbY?*E2sPT>zapCqzPX>Q|CnXerbONc}g*6^)t9LQwHEd z>70mb zAiV`xVKxY^9saL2K%2XBww4Y;jyFBC&$Oz_2~he|TOSa1JtFBjw1&OyaY3vh{ogfj z&TL9UH|Z#$PXzn;_5!ZKCLuvr$EkiASb{65=Pg1uYb#?U z+IjSo_TrU0*W}T4Htla;xVUw@-x;mpK=!Xu_B$7lUczVFN(J4&`OAKJb@}CR%iHbO zwevNnhp$UL&(oDtIKvOAH*GE_N=fYZzZm&pr~k`$1xa-`yzJ#Eiood%9Gv-bv+DU_d*E@YT!^Irq(*N%9KU28QIy-ftF1!GLA~-3RpSbZ0;jfXd51OPR`oD9k~vRD`@7hLQK0V#RnquWwb$!AlIQ2l!r@d{~N=X&|4grrPp22 z|31F{*2}~eSE)Jcc z{X4gD92%|XZ)tDOxQaTtd`B34-Og*B@~hzb{A|cXwLz9O4hlCnhIJ6N*?#r>gKQog zj85f&0Hjx((x z4P-;_v;(I6d>&l~VxP^;q@_8TyTLND4UAv<8he)S?fJA6Bn}zqZ`%#uHvCXx5K6>s zE(TjHJ3087wKt65-s_C-la>e^DMgQPcI`y7pxIv^uB z#2k+K#~hUR;df9d-7iZp8}P&WDBIObH*t`!9a(@-u@Y}y5-P?m$n&9k@BIp#uplnl zdi}`qGiyrYhve=zQPzs*3GKuhit9;kD{6S%sd%_!-)KNfK?i@>_c-z8GYa7pmyFCl z#K^K$KxncmFhh)$uTY#=UJ!71HSKQc zbM<=RXhmO$Sk%i_`vMzJPR_(b#HAHo$ERhvS=ZnRUF&yt#$-ua2lN})1=yX_^?Nft z_xu-ikE0i(B=43EU3T;W)au%Lx_tRc+P;SMK;%-n?g2IgipJ}$Fx`6y=pw!Vp*N_f zdjJ3cV=CkRl?ND%DfbhA1a@_QFs=Il9AN9%%A}KKH=`tL2s_?wH)t)4O~|6MUn6)wo*M%U|^O%$d8=CFyQX{a={U6-gGO&zwCey=|nW z<&zqlMS;|}g756ygg!NSAw9bP%@*}og}3_v+xrROK?j6BR&!yHum(bVT%jqiCk7B1 zjN~-?1$2a?v1hPfWS`q%PtrCUzX+YXV(dL=Y3 zx989_mf!WtbUUvcd+QOM+B*;4c&A-%0A(4LWyEQddH~q~JX!|xa%ef-mitrc!((9@ zk7Wj9Zt41$0h|WI*%I{Qk3XJ1|M|}csMY#&Sn?^#4W$eEem}EKngG!i@{jo z#S%1Dp--%wNOQXOqXV^|7oGI?dv(2@6i^XM!Up03V&yuHCl62`{lweiDd1eJ=AvKd z09XUQHlP@pJa;XhL$3?cZD*adL(@5*wD}P_pAb*mc!PQkBzD^60Ez(;V?BFOU$7e2 zOX2XNuU`M8J%&o>Aaju)g$f;#^AIlJZdJLhq?1ZJK3^~ej(_21xmHf!Zc@8sXF)uXU7}v7fsgpOWo!cq%oy_Z~V5~d252b7!Xsp!6 z+c*AZ0HNRg&Ud6oe(qn?N`6F!;=boYf4xq3kxm1h2Ht)e_y>RYN7A4AlmB7e@jv~+ z|13T8>~nS6k)vLFyK9;?)`hP{1NGCt4ha2P)OY99>44DvWAWriKGc_~XO?m$AVUw4 zN$Wok=b8s}(C~nnhoCA`DlEGOxQ4RE<&JBy-G;Q4}1Pp^U=oK9{ai};a z3(GU(cMEttBT$kK9A_p4PTo!Tzw=D`sz3HsX;lX>QvyOSpE#4Y1&-MfNQZ;QNr95% zfKmsL8?uBvt3$^{0gfO4{m0X_wGBO7pGB{Oxx-0-OHWvXP%?hNmx4k9{)RO|>$P(fDSbFx^XVbP0f#&7}b{4NwdZ@Cf zKI{txgyqLQ9S%$iur)3EQ4W{{IGB)ZTLNkW_MQ|tYHLHEc+}z2rT|kXPGZe)G+mVi z=U@87C(_eTJ*_f;(pZ1yP-Rb6Ate!?o0o;?gMH~-aSjML2pCcSK!Q%{uoRHX4zvPm zOF2=W5%Z|Wv`{)0l*TjzO*23@CX@ODc=y!(WnBgUvH~s#Yku552eV$!=BXX0?kag%A6aJf%=(6( z4$VSVh#P)6Pg%EcdAx2x6vdS=x7y#141_+)ItS2r6xo=5)p#9Bj@}GJy~X%?`wTKA zVs9l=8O6&kBL`E_VvJD8+LW`-^19H-^!4NQ0-=3fpm~H0K|_`d($484sU_EH{dz5v z-3Xt7&}E*>2py-~FDR7rk~!{q1dUvMUCBv!G;^}#=RQ{b)I4O&-y9%xp<6^Apw#9b z!~GaUr!_s2t<^GK`JO`k&>kxoM^iCkjIa8Ci}e+Xf7}A!LJjYv&3`o+h z`@mw>Z9zQNk9bE|H5+})ZAe;`ajifvMZfC{Om3r2 z4v@Ub60g4d2-P1nZq+)^U%+6UXSws(Feb<&cDmkjUDpLS@&M=pP@bC9mn3GV1$O*lbnWW3=;AfqPv}M+(fY@8u+C6qOfQ`Qf)1dA#y#I_WL?&Kg6NQ$26=G}ua9R4fG;q&_EL$F zLC}&J{Q87=a_@z_fV#21y)9tPsZ-0Uqx&N6k=FEO5PgZ`^qCdiGa)zkQ(JLeS(HW0 zwe>Z0(-zMd)j?>bN0`(+@xV<+_(VA)bJAu1l=V^oy$>5Rc>MZubGU z_mezFWNG}p-*Nnu(n(xv;G33StmBTbj#;OKw&u)%ES`LaB^~o2Umu$55B#8aosx(7 zLt_wJ%qj6Pui&S>7vLvx1EvV=oevM<-h(Wg+av^-<+R&3J)kVWQSfMc%Z04LSAPSH z=t2Omk`FQhU32Zb?*#>m{Enf06Ph@gF{UkofF^)Kw2k=gSOl9!Do@WN$ zKBd2xpM3I(^o+j1z~AQ3Bd6=b%eo_8I?LnGW$qJcmmxnOWUT7~jJ;d;4}hTYD=RBC zK-oNKle*}MIN(tLxLB;ddi82rS`@H$DFbVv;eyHakvg;mFc&)dg98i=5Eno+FKxXjcAva;@O!L~jD94q0aNJ?LJSyl19yp%85%oG_&3Nq)(k5%s{-~sN! zllsupzUQFlEp3nwoqY&V{ZLlQUDHU1DhXK(mL#;EXwSf7LW7S9uU)$q7NU_GurG3> z=dcVdpgUl9;>-c&`1qJ!0MPxK`$0R@qYZT7F=*?^WrWd|o&j-RgADfYq8x{Ayas8D zHs~+1Aq(?@wEF^2+C|IiO+w3Sp3t~$;+Dre zsc*i>=5$$~IQ3iyJ}xK3QxE61;Drv$(E1HR{kRTcJFXlNm@?B^ckS__O&l_MUSLU+ zmoJgoI)TP*5f18iDMv}~ICb2Qvagl_U2N;`EB+qxoV4!THoUAq;;+?N*0TPfJeRl2 z+Ua3*x5{^U8NOQHucz++`m0yU>RtSpY2bGM9eK>U|F#qNU;eX?q(AnaKit!A_UQlU z8@@HY_|nTg`EN$zP6I-}@4a7}KJwE)-qUqJ;(*0(r+c&7xt%iK$-IsV#=4XHP|DVU z#!79xedBKi5c>PR_q)?y{I8qmz1+ut^?U!M{$5;v`zpTcd8dK5u?8?c`CGsG$#{lf zHTS)x+?rU8iAPJ!2+X zyMYfH`v8OVDFbivL*=TC0Aia}RUYlDaGq{G& z)t@+_LoyxIEX*&;vfqO`w7FY{Jo5q$Z>E{~@pSf{rS#CdABfN0Z*0o~^umg8s`(&| zgIqqXPJ8i*b{)RU-jJ*!%Swt43oc*RftC&qCj@{3m^_9RY7NCJ7cUFEv?dt^q88}- z`h_nE{wpg^5^YTn+h5jUB?n6@3j${gcqBMDj4t z>hzhgPCYg;B@D7Y126E-IEPH?-@e8Lfb`0VlTv|3Ko%1LaBXhr)48$=Ju}V0+Kg^W z#?#9$znnhy;SZ;mU;2{3L$aI*_)G$0Q4(v7Vi@#8|3j;VjuoYP&IbYo z9V3*1OOc56s< zZtg>L{*X4MA|S6;ZyBkqizAOm+hVIYu)cAOb5;>y?|28nfS*Bo?BD||#y19};zAtP z+fHngWJj^|T+eG|^Z=nfU(kT$R~g_`_#wM`02i&<2&y0YnfuxsibL=&X@|t?>xUWB z5`7?TPu;RD(t}-}{xrv$xnWtU>+2x#oUfg^jyLUb4Zm`k~iL92PpF#0*JgY(^8)`V*z z9dno7M0M4z%Hm59Dz9EB3%ckV1gsDEWAFfGxn_(VT;HqdZui;5uulEHo2FNR%ia^3+0f3&-J;2G6D`{FUH^E?1 zz})$n6B@?@0iTy8!cLkJ?Y*+{C=O9~Uk?pu^g`Ciy!Lx-GJ8TP)BEXJ0e0oLb^YJm z1e|i97o|?5%NGP((lr`DFrQs#OuqD`7t?|)N^k19S&$x;S%8Xw&N6kM*j=TUVNY7Z0?&k$Z=2H$M;HRGKxda;AL3MqMmc*}`QOXw& zWkSW2W*Zrm99W^v01kmUVk_R${h3})(e(vukrU%5)fcSNjp&{TOQQmQYs@F7C(=U? zK9K(1@BXd;WDDuOQ!Bc+QohFKngC;?<5RNOcqRa#I|4$luU!^MXe>Rl_6;HDar?R5 z2iV?E2s?|=$89$B%ll^*ztofIeUr6KoHf=46UDk$IUx=@)<2$kQSJqlxxPVH=1Ccj zy~z6!^$kjL2)|)*mr?Gy317EcwoUs^yF3KYkAZpaL(FgHc;!v!dhoF)59fZAv@Ub# zvUXU?UY5Cihm<+)I%R0xmORS1X~`@5QpP<_?jJl$?{Y$WfM=$G7oIfblmTq6ytfX9<9( zamZ?!Sr@cP8X0h9zst1q9R_jn<9zd`KX|Vj%ERjh1X=j9!>V31Lw@dom=geY&z?OS z`U1cUFL)p)b<4R#)0C0#c~yuLQMc)QkCW5LW*rbZZm=@?v^OA{xx^SDH-L5Yi??NE zAXoECBXXb+E z!DW5141Los`Z#y)T*%8@Sy^7u%k)_;=27X|Y_`L9)mcD-S3OZ!Z(p{@f$4^_>vD7f8!M;?n#zfFbwvUj~B z{o>F5i-EoWsekyf^yB~F9}X;gBQx(bAoQt|C&D7Mua#U+-uwP(LYW<{o#L7r-wyeZ9BvGbop5WM+IXY7kzc0vEwpQZ>*ee1`zrK@Bg~= zlYj3=>yCW>@h8&Jz4AB9hUyJ(goH`v4x_>O5{^$?JL*f9@#DNWui~$nrVRp=X9zx42 znICUw9!AoaKwXgbW@f!HTz?#Z}EZ`{OqA7 z4nN|za`X(Kr->CB$W`ZM9(w%W$Bc*GJ`A8R(g?=^1~Q5rJ?DY-q#n30>l2>$+;ew2 zch}u%bb3h^lJ6GyXkM0|^;yz$C(`s>N=ql_Wr0zEq)~vyV*!$yoz>@Jbuc(Cq|7b{ zH?oAIh6CmY2zo-m;w^P!QWgg3(TL0vhGunOx3&(Dc|+JEwXZ{>?X{cniS;!Ocl3}S zD}y|2A637nbgz@{ul3!o&x__jbx3$j)?u7hI6e@yhF`fNM> zBtE7->PSd3>%dPmktf-wGk<_AR^|0=2w(4zsfmAW!8y&v{9BR z`%p(+H_kjZuclI7pG|sLtan{zzKmhbzpfZ)swO}7gZ_47Frx2u#Q_oKNYw&>&+6rh ztS9kAA0Y$#S9{*0Cmi~fhZGk&tnvoxx#C-|uUu`|uh|YO&-qX>hNgD=uGOS{XZFxPjDQor-srj}(S-W;$x zKaaU-+#db291g2F6kzB|KcQdOg@3+=5i|cBHxEKN>3Gn7kn5EEGI{%VP=E8j70he$ zeBG+rtaJM#ef;`KB8Pn&SKWoE8+m?YiJNxzxUe=!Re-|%YU18Eh8@;gu3_aNOz{H{ z+H)2GSby+veSpJbx*q3qcJ-x}QE|j#-b7wi5bIn8_4?5PwsgR3Wlza%DQ-IS(=#V1 z%e1+%rtgK={ZaHPxsg5g236Y+q2X0I=8)q=LPqF$@ht$TTya zHrH>;+Vfnx_wKv&3Hv1hmGcWp^Rp-8%M8l`BF*ZBsuRmgx^}Cs_ybTH)BVAgUV7S| zxRj>!#fZ5%mFwEQDX{JC?q;;RxuqACwsfB`xs+b`;`wx4V44%M^mrgp^VH;Y`u)eB zNUQ7HdMRs7SBBmNufFQ)tNy(e9}d_679ENF}-((}*1pqH?=1@6^-hLF^&vNSy= zi{!hy_;Wuss_PM8=q&yygi ze?%W^zRqYxGCwj8V&hesD*6Fbp7X_9qA>spF4xuZ(^8v#FxOC`v$;)jybervdwA1ZAm1*?DTmf*& z*yQ#!2bsT`+WbL{uk!55xOG{E^rh4Xaf4#9Yz%<; z?sKvRt?M`7Sgh>=^o0j<1FoPszEnjX&k>LpQ1j)>m(zs{7a|Uj)mDZ9M0-8a9y$kH zN`DNFMSkP}h-(Yf&?2wzF6+4-)Aya0O{ zkL!A#0S$HNFV?dG=Atj^QO3OkmX$3le9AV-ALQVPBSbFuojmyB84EnRWDE#NGq>=J z4WM4i41`8*z|ig&vf{C>3=kUmZJ8TjI`b15;JYE~&YSw0mw~} zEF$`8*KMbvbH6BKJmH5!26P&Gm;MN2-=fSi6XK|69~o7i;|`I}x`Sul6Z5`JoVF-0 zomNEN0?SOr-B)LmMqcwNL-KLR&RBaMyRYsqH1Oe>5cePE>9KIw&^7wb^|B1^hxO`^ zdguumn1h~^)~ETJj&PWxy<53k(F`khzQbYd3@aa&KZwsT+F|+d7*sYW&+YxK&t7)4 z3y+}&Zuj4j$4~`t8OcRpb@@;H)Q8jm{?i|+(}zV~ zO*@D2>B>?%Dj4gy=&A#a9hZ@MW957^fY97Sf9QL^D}C#?d}Dgz$*0oa|H%)h-~M;M z_r`Xt?%)4uVU+Uoi&F5TUVFQ1TB)@z z{%SQ)Kb7f#(63f?cNTpIgzg`Yr#|{WE0c%4Y_JA?5!WF`0hr;_*|@;e5Jn0B4vr;K z`2&4+HS*w*`G|W}&O=*0To3S)fr^x6E;%gIDta|8j6E{`z)uc5$5O2Za0@i z>lEl=He)oYhxdRFPY8s}VNFXqndSjO>tX%m zi~v0|X=ZL(he7$Xpc&}3mu~9Q^Sc5IW05heF01d8vd}!HL$(nCi?CL-E4{{Hj=(`T zSJ(AmNPwrsWgW5#ptQZA2kaYq*uI&r$-2(u#I&q6ZVAjJB=$ZBMOe+**J0O9fu+|K z-x1$^9RRJ#+O%Yuofq#t(a&hA1BB+&paMk;s4eW1z&bj}8)!-P-T18{of{H6Gu zJJz59DsAZy?RS3b-=<%A^poj80BeBIvjPEaZZ?*Lu;>@_E|jXnCWVYPd01j>9QtM) zJhzDBSuudAT;_abReZd*M#3U0<%c=9nPmt{$-%)z=2O-!+bZ*W{ry?9&f$o5Q;LJPk z^Oh@@@tgTJ>A|r^|5bUtFT2k@27A6xM6nG=y;T0j&9u->P5N zZR@L)gL;GA;QqG9gjTD)aWI=YH|wBI4v)01gVi#KUeg-V)6+c{1Sj{Y4099SH}c+? z^U7cMb69yvOFS&P*KJ$pk|{4p9ZHKvV&uPXk;jf5wp#s~JJqfyTJeav#F(OAdw3Uf zwgy6ruHM_=ExK3}zD7~6*SU{nZvN7TB&tM=mlHzhYQ9u`^z1=)?wj!OiE>|L3-f6d-U?uED9267BH^B(s~i;gkHuv5RhR; zdGOoZ*w%f)3Hg<@u6u$TyU(Y&c>$Kk^iq{B=G-Uj>m?|_PFn&(Z>&i&-J9NA+elY0 zT~u2m0y$p_URST*l-1(RbXAt0Ck3Ql)t4aFH(yTk0<-Mux;{TOulgJ5(&a1a!G4-v zm=zE@r7Nm8vd8x=_|&~X7Lu74rnY&zD;#~!3Og9f`i^0*R89%^MhCJQiC(Am3H9wA zfHV!bDf4OnGKRi?&ivaHP9Ma8fKvKGhU#nzq;yL6h`azcC9ntMc0%`si;L5;uKhxqnx7GugEXZV z=XUo5SkwL1fyR7q=cd})OTV<+91L3K;}G8N18naHgq=m`<1hmbm+?=}eK82UmlBp9 z;E_G~Wt_C<13)G`={Bf|ItC&+B#-(ygOFU;Y4a>Y)0Azw+_JRgr%lUH${&sE$2@7* zJSek#rgNTUuiIfy(m%^>I+r^gA^Yr*t+1qr*3L4OA@N9S%cO0mtzYU6lHWYtmh}-K z;4}S=Yj7NS@N=55?Q4)8e|PHdQ|dUc42hRuN%OS4$V1(BXnBtkN+ojn8bSSa)oa;ON z$BHqaSAffStnK0fMFWb328Z0pj6-*{X>jW$ePs$DG$HZ=48{Xk#T#U3-R|v*m!4-( zACN8}Kx9J}fY7uH$kpw5E|vYKPi<#CIN#}ZNI7|4U$pH!^6f3J^=MG9fzVDPGuE>K zecPh7>y#l=foC=F_uS$hsJ;Fuw>+*N8Tz3NJ)l!OKw;!zPC3t@N&}%86VEMZy)Ss} zc&r$6`huq)i~(}eo&lQhG(b3>H)&3kp=EHMbyVsMnc)d<#+Wt0JR{E7GiS(SeqhNO zAT)K*FCKZ3)vng1<^=kpF0#XuIOXV#ej}gtgNz0_Ti&vae$wCQ^QJ)2vOGqX_uQ1X^*?*q+Xkzw4LdlN9Z{Eb-C#s_U2Q^B{^hH0&u1u(9&l@CF>f$c!gWn>geIIJUE!Wv4IXmGXNW zEHi26MOdw2m$yS`%6?g9npjzxLQ8dU<~#I*!%PM?Udr z0N|{Nzx-D|lpcNTGfuuK;hhMCel;C`JwWJJ(@sZwxCV|2#yXtKom1L@#_pW4cq=7& zGl0-b1AKrXBBbeygRgAFp*l=(l<(USIni5V~J~PkrQX=&2tM zn|a`yJs_71^yMH!W%A`CTyQvgoUAeqDp?-($~%}*iZl<|@znPr8YQ{jAdArXL3Zzh zXFZGVa}7TiWjT?mbiof%3K!ih(!Bt>k~jlR06J$N8FJ(34+pzh&Q}M7rhX-3H08dM zm-91F8@j_?0HS(GU}*WPFaT6;qlZ|Q2stFs!3qz{Q8N7`Ei^EnN9Vx}hh1k*ospHG zdu6#%pQcxOYJMUuEuYqB=NHq;iBoA=0H*oH$#m-MiOeUB%OcW=G&&&&7>BrVSed~! zJS69UVM}4W*(CX}fyi9rpqS6t@95K_5(V&x_)C-?eMwX#jxDSCpNbQg#Lei?bp(8eCC(a^~)E9 zr``}?N`P!xl=J~g96m4v(rti`G`6f1<__bWN4i-%UQ2n@^6x!R+5$%ck`*G0Kl{Gm^IeDgTxeU$j%{h-Y@ShO;;M7^0kZ%$s(XP^UFDu-$_8|tY6FadPDVJFS~>ah{6s% z2V25MH@n^ssy#QMvfZd!G-doBdKPGL$Ws+hQHN zKs|y_y@uG6$e1ZJm+_|c;uQVg-5V9(c>#3i^>v8rY3AgPUe20I zs{%9g9@41x?frcLlcca~SM@3Q8@zy}`wG2aw54l5FEIg#Ml0(AJ8x>(S2uOfaWI~) z=>@Ef?VAE(Pp2JS*VnGCrb+co=9xxXw&o#qyq^w6>fJpc@AL;-^ zq8{k}X5T#xcH zUdrV-p*>rrQjs$$)5=^a2*(V7%q@xWEGsNEV zod-YqW%1ano<)1fYxV&?A3-4}<}q5J86xsR@A-Ie1<9J$NTapsZNV4DWHp>t>% z$t%6fy}w3<;-}<+e0Ia)l)Fx*rM)UvwQaqT>wS|sfo?s&J)h7adb9l0aoc4(?vwR^ zZtUUdxI^e(tAhtTExWH3=IMD&AMlJXd6t`YEoWP9rz6yU5uyGtAuQ_`9Wo7&@y2Hxg;c|y1U&jwCGY#P|x?%aQ+b(aX594hfKm3_X zj&|WO)WGfjJMtK+;B6r?);|CC5C2fz*Z<{j{aE_MqmQM}KKcvsGCT#p{MlbmfAPQl z-kRpkh;%^cH$%(+|8L`{V65Y!i4HV&Tt@1Rm9qmvzp?u5xOW=pH1PT~aMWvWcTIbJ zdVagtuAkC$K_$GlLiQFAS6055E@{U^Ls=r65<{0xeXHX079$K{io9Yekh@+?`V(ESyv|QDRL(D z@`LBxKl4!vMMs^gqSAnIdC(0Yl~255%{e|RDgY3l8$BmKIXRwApIa9ANEV=H_4#^% zk`|V9ST>!~L+^M{pcy_BkEJE70Lr3@cmW;)3_YuZp;0}|-`SBBB^@yFke*IVOZ~fh z+i|#ybtTHibf~nh&&!YMbM(k{LxAMbX<2jLSWUa@*V4hJK1X}?Qh>Ae_NUX>0teNPbj7- zS+Sm1f3Tvsy$67LOO_4+a_JCF|E6>Zy&+)M^Upq;KJg15PggHqNSimW3!o*7liT^z zlpF-?3mAls0ko7rXss9x0!Ql}@vQf-+E@XYXeZo=fzYI-Bmiv9+ff>n%Lnk1EE!)brNe& zVUKQdpJcOa03+JPIV6s3@L(UnyNrD1sCA@uUUWl+Ek`}+)POganw`@nk1}4jO$B?! zYRjKJ#O7Afl4R!SUv+@R{EIcFYRotvKG~9e!C+u?(5@E4)}r1Oa4usDd!>mW^KWi!>16%6#)Bk9HZqBe;4U!4t1NKIV|q%7SI| zA@f#hsO#00=vA-xrJ2m5cRa{5Z-;Ke^V#|BFw+U1qKNfE9>M zy3kYCbx7Ow()IRNG_jss&mncoxOu(SP%?~W>weJ%*eHv2V7ZAS>7HJS2^V6kJOozX zymwS`WsA_wddZcVUmsR_JvAl6Vp;bz=en#*zsMB#Bc)10zRWA@RPxtE%pnoidlkGh z|EyQ;O<*8D%KcD58+FK{oUxbJUNtu88c@g}!f=8eD@4$Wf3#HbiM)zV+kx;IK{hcy zDKK%i#Q4Dd_XUWB`3^{BTi4_ft@XRkEa__#3u#|gg3q27@JQC6=VWboQuhGdkL(HX zd-0VEX>NKZozaU|6S|ie(|y67_MKfJk|%Uuu%iuPaslwdZn}AWLtlK*S4q?_ULx7j zHT-3L)j^nLfplln6#;NJ*KejBy&SbCF!bj7Mp}~v=*``cw6Qai)-_E=bwjfzi_^Q} zhec>Xcm?{^J%TzmDoe@hs<)?og?oep028vrmS41zhIG>zDh=JEFO8o9!F?2!?n1X& z!7(QkjZl=a&uJgxK4}y_8h7qX3iW0slTlx1XrplTe1=9<18Gfr@{vVc(Q3iO924Dy z0M5Gt|IAF!27m|4-HS^zdTH&tzLKH4u<<TMFRPp6+)Rr284^>ggw*PVai~ z;dE+6<0>#1Zhco^^Kn`AUYJQ6x+&zvxog+g!rJ$Qu4&VgntNK4KXdI{g8sPu-0lNx z?k;pD z^t;Jnt{7Yi*b;#1=RWtj@CF!@2MCns34m3pLz>X-IE1t1aYz}SzHxm8Xm0%gG`96! z0MG`RI^X)DKK$^W-fJ&4ydAWOi39#_7M74Pvil{WO>dN4_zCeFUZeag!`7c3`bc!Oo>BYx@9 zrQ!D5Z;$;!Zd=r5pJp($+ol~HebisITLWRI@kwJ9iS);9LZ9lmB!!eCKXU{yHUMMv zgN(h>E5K;aAI60_mdj7vU}a=w+zo^_pxc0Bt{-G{n>?$r4hZ3GfHN}S%{u~#CC@6o zbeDkrdIq&tUpNyD4jscE5H#%pvSpr74n6hh{}eq-TCi|IoTs+-?EWxU@zH77>Cy{; z2J13ksE_Q7K|bE-&vMca_|dLGsgy%UPrmUJx=7KCv@jIfe!K3 zxBKOgI>g<7UuTTF*aBm6Sm6FX-1v`d}+wa(9x|sk%Z!%T?S2r|XFxKXxgbC2t<}y;l zz=Q_wn+C>v@13}(-8Vh||6V&i;gJ?5fY6)wRG0ulH;&&mUwwNmGtTtJhp-XE6@+$` z(_?sfXmp507=dQ#a3m2Jm=jYfC(L;kms1JYsFf$aMZF>@p0CzrmJd;*1c`UDbO&$R zCoI}2WJO-G0MymHYC4rBK%*X1>T~Kkl90#psdx+JlB{k5tSWR6+dz&aizP~yI17CM zY*hhedUT$6>2Gr6rjiW;q@;G-19Zz_f`CH>C=!W_<0!>y&U&fkK$-X^ZlvwWhf8Xk zR*|bmAmI)Heuvf1ZXN1$Pwfi3JZNVfm<)w&muwr_yLC`DcZ;xOo9zS=5?EOSw8gwF z!c+l>WgIb#=wbOG$i|i zdiXzC7ON)-B(z~zV5Q;p8b9ex;HzPk^&_t=Yjp{{!{_cfP}RAr+E>pzCkX^SP2Yc4 zhOAkG8v|=Q)Gyvc96Sw&nOOKy-io`H3J85x_{X3B9Qt)oHv$k!s$4HQ0kUJ&dr%L% zA_7Wrbd=@|x^4vQH_m&})meOGm?RLw#yOZYtAu);W&&}$Mt;yy2Zs#s2OyEvrI?~f zXIj$DU7Fj?%kta=Ce3s5cx*6c(6d5-7;FBA7019^DC*^m2L;NaugS8yG!d`Y)aOVY z0bnVe+90={PvdpOp-ZAJ^%K`GGLz(~lvN1%&?{EI7;6BvML)~#s$Ky^b5W`f{21UW zp?VP;r4nP619MfXGVG~CpZZFhWdn*gcWFH8>3o=0tHG?2j2y_}6^*@&Vxv>)CmtJ` zya7Rsq6NN z3`l$q%s;dYRvkhhdOO=IIlvmsIgH( zJmO_jFp=%SB1RvQPyHdk<~U6Z@cS_bs)b%K3}tDP!&6B^JIa!B-tN2;8h7Y%x>! zO#w&R#bc}a)5EGYYeUcUS+Xp=Ky@d_uPC&Q4CuureNAF^w=6yjP|-dVrqAe!dx%c< z94lYu68l4uN;uC-;Xz0h&h!G=77!_NaAf z?b>zP6KJm>fJ5&X}aNYH{==Q31CdUKXYWHW}^{H}qF?9;;doij-$;iAryH;*CxP z(yg5@^I8riyylbk1 z0QIRFyDsUiy!PX(J>`V?bg0aZSq1>r}kMtT(+mXx>*H2*Gpb;olf_JYMUiZ zlQ!XNdg3^@MacT$wCSKBZs3&bpS1=S)Qi-LReb;S3IkCGj zoprpL&Wg$?^9%4OmU6KIebY@h#gI4vP&^J^?w3J($U(k+$y5=Sxvur+zM?a{t^RJk z_0|DDZ;N?huD(Pe$P6%Mna$^x0i@gRCQjVi7bZzUxQBElleL>^#fEOTL zc%TRPAREA3fY5+*k%RisQtol}H5wb#pVV|}-*Pyt(WG+Hl=&KW7>841jr{hsO*tN* zq`{KN0$?2=G_pVsfEz$LvZG%Bqjt21haVFv0-?1J^9#7tPi3h_PM_!J{E!KNE|!xS z6XJlM6X3XJ1sdI1ZbE~g4J2l~krnyz$PO4fg5vd6uWr3y2hiAKVO_x2KxnrKfAZ}O zj%9q;=sA>u@6f@Aelw=j-k!e`BlF9QIUwmzVPkLN19h#UAy9B+E- z*daQmKHj>pt{kFM_kqy;V$3}Uk+nKrZiBXo+gm2m#GP+CLi6)j=OOKk=G<38yyeR4 z5qEh`pYyHOLsrJZbA^yJ@_QVtEA)w;tRvch&Y}D4{#z&2Fuv4Stg*Rl#4UH8?|$WZ zv;|-01oGmElaE8!$nQQ7R`qXrX*2iKciM5&5>l3@qa3`DDogX8qtM_y-#phWQ!LaU zk6*Jsng_IbyqY!-@{^-Kj@O4(KDE;NI<4qh<=6PsVy$RL%WqW%S4qg9I#;Ft&~KL3 zl}{u#FAZ$$-;tYF@BjahcBdV;4?q9$cgxP6_49MWk;lF_rk}polfxH3cYIm)g_BMW zC!F}@GJQ`Ytj$l|bC0mwqaG0!Y`vBC!&`(q?zl5tbM1BE>VI7qu93g>w%f~f_`U$4 z7wU^``#tL!VcTsM#kP2^^sj4gP&?Pg_WpJ4_3>pk_u=ZlTw30*$a}=&o>Es%9`ZkU zmz{`~?#ipKDfdxi&eM70e0kh!4?Q^S`^=}uIDbz2!B4{XPXBS4CUV^k|BidgJaatl z+oZC+coU|_{Ydl)Ry|ntiF<~y~MI*%fp>Z?+X9APR5dcb)NRHtE*L8rXRHP zj`4nKf`9z;>T;Z>YVZ1_-5;;^9;@f6Tk2)I=@Br0z50g#_4yaZd#~$`70%OdB={}a zZd;w_&e1-3ZkVC3wcT~s@^H&-w}o47y-j>?3YY%w_oWP@@fgtKPO zD9LX4_f7hp&|9W=++m64{*%HkJMR$tG+EDU@3?bmod1_y{>O09C70FBqq1U?$ap|w zGc^W_7cDGnuhui}n{K|POpg|srQZRIbp6<^)I34w<8kb{czNPck9=6X?&fbfFYfK{ zUa?Bgv2O?$UVLfz`;}LfeVr+tEtc-=mMyc#2N!cE!M?Af!zgLmF3ED_FNd-)xf zY!}yqrTTq(=bd+jKmPeI;ev}UjeFeDWFD<-x?aZK?^#a|JL_6oAmeT`W=sn=+;~%5 z8~>#>lJ#-<-788Kn*svX-5*GI-Nq&5>{83Rp#mK6@Rzm3_&4YPae9~{uydDw)DLQtx8?jT z!s2Zgg}(mYu)S`~Gv{p;twr-m^x4yAM$3)cF4TeQU4Q73Rp+6;p|JAq)gluBOyDG}Lar6vhK>>ac%r8QR0|N@A;3+Cz&(0K6D>Rf z!0T53Iy<_e}g{e(gItIt0qryzkbgWLTS)ZvDVG z>&It=tN!-)@UN?`mX%5|kQ^LB0p(5Y}zoTuWDhB0O~<5vSNLzsLsP%QE$pZK@>TR(?eQ6ULB7|W$AYb+|t1+CCu zWNdV-74h()so(+$q{zCsH_7h8vE<@h0^3WaC5w%_n4HjkWZTc5$Q8PQ+Yu7 zOo%!sS|i*LrF8U-*&;p~>v#|n%Q&C}QpviLDgZ`HW7@7V+NQm+T=Vfrz_`4w4l$8| zNrmj_75x#S&p6qV92?@Cr2U#})Sp;Hy_lw`oAt*f33y8i8uUi{MOgG*%p?|VCZF_x z?nx8c!$S|stZSuk&E-S)=qJfWJl%U}J980eOglAKn;W&f1ca`olWa`br0E%RBScIiZbY(I{A`rUJT~X9*9yH6VaEeLc zI?I05#$TCH2M)Pn-KOUxw)BaUkEfr^wUiexxw4Lm2*9ij<5P|J(FXB<5+%+9r+Y z$9sENvPchWR_o!(@H$yj6fj9IJau$U)orpzz@mk^FAKypYiiJ~R@RmWLXW1IaA2~; zyiOLGJHrfFBh(v80zY>O;H(#(L_b~NrY^mx#8)1;M~~<*9w2mY|FA4WOVhGwyrF+2 ztiD?o_}0qWq4pmebaP)P5cFz3xh{3|u1)}z-aY}JM)XpaUhwLZ)#x>A2L)sTXrq-% zFG>x_qVcf4R6$QS=su41O#sFHeS@K|SKwZ)Kiuo}0d+2RuTsG>uqaI`q6ST7*d7P4vy z=zF;yye-g!%QXU;Z7E*Edf}^2mYt`^rrWjeVK2ptZvdm$uIY<>+Pk_n-Si^bBtX#U zNbq-o%sblCr^w@$Npt1LEA~LN&CYG?18lE5agIy?p*OqvP!)JIAavbW$2GxgLs}5x z94PYPOWJFSuUEnxoaFpm4g&MIa=mX!-cl9ZE)$+W|ariLD0EaGHwk-Vd zkADnTTyaIT>o~@U{Sr)#gQu7Ddo9AXs!r zz1+F)s`6=;JUJqF0jn55?q!x2;su$tfV^nrX1FQA8(e0Tta#;P&T0dUj-OpH9d zM8%6@)Psk|(QU*El|RUftA-{^#fb(P>?ucg`P?9HSo@fZDPCR&+-6P>9rQSdE+?d%gHZ#?2?0efU%otA={7hz z%B_Avk4IL#L6@EzGX#1z;21D8`Ueb6Kd^XR1-~)|j2ZoB-qN;t6B=Ahh%C9B%+GoAwp9CFar~JJ)J2ET(j)-~2LfFUox@RxNgAO4s<^^DG6NDbl5 zZ+J~O;*GDZqZuvn!h>EN`<&B^r=6VMaqhdXf6XD`MbAGV0+OBIEact?aPx!{zZ9;z z=GtZ?b$L~w(t~&1UC+zf!=bM{D7;={%WsWV4&daw-v80?$1DEQiX`Sg{C^%2KKQPCoV9;p3nD zT$yeb*_3Uub{%@i%i=Yi1OJ-IwPMA}@WY>+6+ZigFOLc~tk&gvXU$^Fy7k;(H1~ra z|1^B)1B0^s@x|{QRdrR*Ll3zh4=i|I$~LX-5E0o^#gePKH1I`LE%{2fsD~ zQICGh;o-T@-e=Tn`ZpI{65jX0kB8g!V$7y+4}I`1;m9LiANF{{Wyfqwn zz<$lD#Js=$?H}Rwy58^7%P+WRK4Y)&u@AmSXCpGG*Tm7sFPwBrIO*h54nX|ZPW?`N5oj#hyuZ+LpW$A`b@*&uAA3G&_wdBWKRSZADgWP3e?ENm zly4D@?!E6kDjcx?K6R>1y`{O<{4j&I(^SaF^W{O*FY^$e`1Bz@{W2gbcpnNf-GA{#HX*}eVU9|%7_ z^XE=Bgs;*4{Me(8DD%%f|02z!qsz1-ygbKCbatxl+JMbD*ug{DuA4whaEF#$+Dq*ck2pZ8 zWe#rb#o;IqzyZBPR|L)Vl1Msv&@B*hr#{`;E@1JLsaQtr35&K_APY;g^`oONELgNK zbjnKO7IWr?d2{E{ zC}201r$=<4LP)zfrW|vdYol#MZN)K-Ma7?TfXd8>Su0a{gudBf`BJ<|M*fX_ObIxy z=AiQ&cb$}%WXs#A)yiYiPM&NTuU$tiNmM{T#%>c1BXvO1dY-HmX}#c(HeIVx@5QwY zP%NP|-DlUYZ@c+AWLiR$P95ujxV?djT&tP`;|4;TA2ZbeS@LikP6DZ9J|)>}G`0v$ zd)0nXx8fqQZY(-!N^3!!u*_lfD&A4QN+}t7a5D1 z4pSUjJwT0puIZua_{QslYr?uo{Y~xG>V^i3%UM|#Z3G(Ua|J?VO=F#^)!L2YSdsaj z0ihGe(f&5d*NhtZn9tU2k~z&Y#zS*X^E=6#f^`2+y^HwEqFdA?n(kW#pLmUGp2b4O z8SCFls_*F~9ty?+LUUh+uI3u|42){_Vo5>TY#!9Oj2?@(7?IF&TDn+s=wZw$D-RX- zfTTn8*a`@p`T&pG987E&h1$BtI!-&*J=Y_2@I@DCpCV|9M5(`Kpo;ea>m9yPFVGcE zx=;OxOk>{wT;&JqsgI)fdYee&!;79Cy+EaVdXMg@^X5zsb7pmh)obqzJM6q|n5_ev z6{`h~ZSM{Xx7toG6bU>rvOY|k(iUb-15_lCvhK6p)4Bz0o+41R0LT5ZP%QdxSsd;Z z*aBO~?H#)B4-E(i-KqIBS$hc08(ALi)Ba$CHUsMgf}W)7v{&`nU#u4Z2#e4oTGQ^l zW2L|@%OePSL~AOR{n$MY3B%s6EwWlwDXg@evW7jiP zfN|+{ih$#@W^NIt_skB<@4_Oc`l%PthDLhzb&(P6=aTgEwpgfkCqh%Nb@5VmB_F5FL{|O-U18cDFg*5w4zqx6xIKI00Jl0@M?K~fhY$u*0`|P)jyu9_vLbfvwbzF0uDdQ; z^2M@lt{3`CJ)QyNI&>dsx7vPQ-}-O}s1?92K;5n8%gg#5aq<8-w(GY#-7(J%dKNOQ zb#+M38h8O4Fe^Z4K-|`+_2zLwUciy?13+tekQG{FffffX;7Rxq(ogzq0IoroZo~cd zbsw2j{+PBJnk>&JZtrrpVLJNa^?=Zhu>t_hSONy7U+8hp>^XW79_w>6B6yhoSf8$& z%P$e6_q5k=c`KP*P6!S2$@&9SkH=Cqz;f~d@Y+F7yXZLg?i+v+#tXUanJ>f*hK7cI z;@m#qO?1H+5~odj13b}D4u*z~G92^6a{^hAn`?HqtU_U#n)!)!adb$V%o#j-h0cyL zoUbvD8*>d1x91~ZUe_}(>%;Op-~Gr#_`6@OM_YKD=T9ETx-l<>&@TNY%)PG>Lf3PD z2=lnhW0U-@vx7^UX-DV+q zx%|}2^UMdGSq}3-26V>!!&@fW#8t;Hsik$?}M~+?AzWPUh}G#mrVkS0UR@4htCb;D0@b)Dw{lgW((X^&FMRDwp9{Ol8t8Z&_r;^$@&54BpZ~HYITpN6IR3*e z%Uczk`LnYl?^fmG1!J|UKc4(*8vvmn{isKVH@*JV%i}J#ko@f6FoNmIeCj z$E@}!SxEk@bcZGN@j5IizfD&Ak2&&9;R%m>bXo0nZ#pWRf5F9NdSgWH3lRFF$Da^R zIq7pP!M9cUSofdz;zI(~)c;eC-v@^uc4!3c6Tc^p7doE#oZ3r6dEF1b_t@~#7af>q zjTz^6+Xp}Psqmfe{jeo%eysz9e$ERH4&OfIi_zM8%SuH77LQ+b*jof_eRFul%U(1V zc`OISf8v);9+mbv`#meX``EXZVB}GWv%+)E{Y`k+`#wA>=s52$RRKaj{;|7-_X*(4 z7XqrT3WWaUncs_+sjGCOrB}&_;i0d8O8`9H%whfbyI(&^FRjmPR@^d=7f*NrWn;SP zedfb@p@bJ`nmMpazrXlbbuU+(ea?B|%}2en8F|e6&ey*bzb0XVW8QUK_{mRy;ba+3 z0HI4&Ohg_48Ymx6O#q=E0HbjqM3?|VH!5%3K)096&z!?C=9Hex1szq&*`}^Bu zVK9LenG+rQ+~Slevi7JAEOh~44J%wPD}@8H+&C8LCUlL#n5EIG(_}r(@$)L^lDY6Q!1BIEAi%(SuIi-hF8XH-(ZWqX> zLjdUxfLa565v0v0DR_v1rDv=4*`ajCCP}CiV99T zE~bX?YaG6z@tUhX+-9g`ORYu_W6TScL~t7!X+S%QgOFt1i9U#=$;Fj`!8uFjVrnVn zCVu9dQ#On1sH9nTLtdQE4Y`dOg7Y?JHso*>pu2kgnT&qB@9r;S>VC#rMu@pmld$S-Uanupm42k_pBgn94pqr%To1^t zb7G&SMt$4$mg9>WS_2|ufSl+R%@ZO=Y%uZI_(13cEJ#w&UmP;fUd^ZRt?3JmByT-Z zPYz4`71wlp#|wmJ-p8@8F-`NUmadI|p6BsIPMqa+n!KdbxYk$aX#}sHHhf9ileVh^LPJ5nn3RQ;XQKG@yjT&g zg*Z08wv+6Drf~_V4PDK74XEXCFHA2Y)$;CrEJ{^0Nr1da60akG0+F@;ssM|_$)P_y zU|vGc<)lB$%-rN(?zsADT6I_}p&v;;xVMEZW%+K3UZ$F(x7lY1+&nzII?UZtFVS@lhaTP_ zm-XP;bG8!bS)Yp+5H<|24>M(Xc=Dtny;#+uJxGUMz|yD10f*?Ns1g=^Z+x?+xp^-=}_Ulle9(K#p z@p|a>5*G7vsL6HYv8vY>0w>MJ`N5>AALgjb^kPA+rk8sk!zFnw&%Y;?yV#36{Xjv3gzbtKYNW~aVozfj<=!Lft?VqMi)t5f>)sBZgWas!I z884qr6HvXUM=zrdtO+w__UPp@>2f`LBLRWhr)qq+)ILsMFwj>#CTXnN^->wvd8e#_ z^Tm;FeIaCUs89R6j&SO&4@(``%>Hid18m=u;`KiPgx<_%L!-F+&A6p8Q#o;bSqBPl zu#!XP`+9{5d3NO68>~b+Uc0O*nS-bKIZkM2K6&Ue>N(#$EQdqZiuga1i8{G6Xv+E3 zFsIGqWgA7`@&k19$my$b*C&L&TF2=;v<`E$@%Fv9I=-wB>Z%@;h{$YTEg&LipkU*a4OW5DH)vpz8J4UmtF~@x};T1;7f( z7!Q~h&zv(r4^RMop>KdHnLoH(9^&@Up^scg!~vJ$x88c|=&@joH#pS%9C9Fr41n{H zAFIDhmoAO{02E6*20lieYp=jdS=6Bq0Bhk*+a4E(ZUX=y2aUb@`UD_Y`b`~xs{o?m z!;9X4g^|bCqU$G3)L-x9S@+d2r*~PN=em^9mP6;eU1SB^i)T!sMF+?WfEPUjB1TW- zQx9Hwo93U-Q@3L}Lh3@3JMz&pa|0mq?K-%}1F&a)p;yYy8+zJv9pZS#kMU)`02oGI zbWcC<^nr08B<*oWCdPwy=s$B8ofymsU$;d*^9MS->D)Kw1a0G}hb-vO^OLqc&)|vN z$bq+R&;zn~JlucJqnR^jX-sCtI*bQxQ^))Wk&AXb@8JOrdG_Sxann%8{qZv9*-3&f6$Zb=d!ttoCoD@BdCp3wbX7j5O-pEgd0sO*%A4gk%WFkD zT0UjDYsD9uY8mNj-e|m<(M|xNbB%3&@s0gEa`V%`f49U~={)|U$CaII27=mt$#wy7 zk=<`D{B3yc;cs(t)NqDg@H*r4Z$vT3PYS|%&7^P-NihMYUb z;u-tDKzqmZHIlrHcn*ZV?)n=8fX}=1o9)h}cj+1VhOo83qJZO{@c75X^U}QjI|Z=A zT5dB}1&_6|O4+RLc=M`lVA=eU5C5OCdaurQFT4B?;ompi67JTEomfU^9s-1|x@)ez zF1+BSht^pd&uOY-aeo4#+3TNq`ZpVZyzK3MCu3Y!%lb3p&NaTx;zi*Jk9~CAHNo7> zEsKtJjc>}f09^m#jMM5sgsfYC`}>sv{?dENClgzIm- zDgMUZS}(6JlwY)P>+)VP9w0PE^8WFUf9ig7XIQG2rLoA2mGAjlyLQn_DqQoq!z%G} zU;K)2?R7Wg*=0Px)}iHETDV}VSbpnmcZACfTiuX;nvuS(?orH#YidTjXIr#@Q#{>|GZj`euf3_Am%S#STQ zakx{@(U#uD*Sl7R*#a`p7iQ>Dk9gc)l{&>Y-BY&O= z@tb#n=E~Mv&DUJnrUa?~CxFmc_CE2`A1_6`^ml&MMb@jo@_+UBbjJ5F zPue^F4$ok~leMh%V^2p!@l+4V3_EYd?u9&7`S@gXgt9{5Iz#&+s+I1s7NA=UihCO3?FV$;Dx z`(|oJXi=hrKCc6T!9J2XHeAmS4)soSu@1S=0tz(Gf?okhZ7V-julxe6mt+D|l0ZoY zKp{u8dRYJ@6L_(9FimS4;6W1+S=O!yd;mG&Vu9jVgl@D%NNGzK3*q9vE2BW!kTX>P zpAK1A1O(kKu+m(8!jn(GPmzVk#oI0p3$!sD)_6~s_2;SGI@p^rQybVt`sC{rfq~jW zm%uZVWktG20H{6zn+JPW34lBj!OpZZRTiQ91xm&m6S|E+Cs}P09!UV_0j05`B|ZW% zPtk)7tOa7Ru}jvZ(c7RbIrVCTF(8mrr{o+EAbC*Vx*rnwXN5KqtJbX55D5yVhw`1O zGb{kwy56;tMOGp?*pZ*9hem*w`7G=Z)}0lfDo_p&lR5-|Mm5MWsZ;tc((`9b75J%3 zo7(kJAGE(gpsHoJ-xaRXCh#Xe_;IvE*``mv^J2i@V6VVa+UNoD!e{D^!#55fG?hj+ zaF|AA22OJX&|w6n*5)#0ojQn!AX$+)Z1%u>!w7S!-qq%Ko=dM*2;E309+~_#j*T&|e{szz`eG~A z@J%l=U=??qKFSZdIWL;w&mvW*W(>zP_4?VHp&^=uL)N-P$qeV|@DDEw2 z&_3~D9P#NINO69z>$VyJ6)KF*+McSfKLDhdqX)HfW$A9cz63F=NB3sk&v)2<2OR{A z=mn_GFsVycAUijNd3uncMCcMona_i_OSa*GUICqZ!gPURhjs7d{?FkCQUDqn>eC)V zU*qUhy$*r$d9f+z>kzt&>;5ia(|~&2sl7%23LSv-v2upH^nh?s`vYDk;svGkdUsu=CqmdrL%55gkC6Jty!%@1zCZfD+`f# zEnOAn%$=?=+@LRM2x1=PrB7XY$!u8rk?G>A7tCgC(8G9u8%fS~?T=Qk0vO$?2ljI% z5Y`-f!|AJ@oJ8Hs{%-68Y~MrT^*;fG-ppo0qqxtWbz5Vma?<+F8qdC~X0h3Em#2G( z*70~h@U@;;x~vLNaz0eVsf){b6UR|zdP0Moh}*gCW+60r{c7Ai08HUc?|ir8(D}_m zgR%0mvFf?+u9F{1=XHtao|k)B56R1QVt%HzOzxjUfMHcn8F?J);q$aXZ4UFg(B)%H zUt;^^g6`g>@$~)0vJzTehqW5xi@_u3$Ne43I%%mx9IMs9$^STRP|=z#HnkHNB@pQLGvzT{&If4pU? z$;fq=H77OAuk15F8H)^=-1;;NI&iAzst#^ z9OrpZoePwi-f=>^yj~usoO-V7c+MXh*U96ip$;-K2hhFem&e+=@|afpn(F{wILqO9 z%+#M;j#jj-@^fCu>v@7)$Ur^Di}AU;2VF>vRA2mGJp5ezi=uij2qdwChgSOLIRw z?Ub-&+ijc``+L&Kr-m<_bV|I(l?6p)w_P6*KK8+Pha3z}Q7h|@lvM$01b1w)t-Q4_TZ7Kk=1N6Svo_mz_ z0eJ2Eyq7kezg3X(rT{`)F!mf@{@ORg*S~d|_T;ObU51Ro=Rf_ihI#m-Gkz8=m6wEB zq&gP&7Z953=&J(SJ$a8OWYUEI*b(dB&DIiLY&i54FAIkr^0K(+tE;F)t808ywuMXp z2mun>{q^rxh7W)I({cTBULNkb#}mWbk9t$sdB+{fY%KB~{OZHw{E(5K8zX^L zyyxtz{rseG-USym^s^*VgfAli#?IH?e+Zm>;7eZFbe>eNb$Ic+~yx6q=KF@Gg8DeSvEl0n*VP0|HIQ`ov>lwg|lJ{~E4Q*z-s<`~VE=u>CqH&vpVy(BjQgtjI&&u{_=-8gRl`r6x-nGP$8^NOYq50m9%o=i(rImVDgtP|u2q*q!9VMd-$kMI^78(yT4^i7>={PY=HL1;KVkgVuF>ezB7RHisSH~1R zU>8V9mXfz#usF<|HAj{ir-nJ&kO3@S-`}VFt-}nx(KKxuR{gMIBWpW7(?vTw^l3wc zjl^zQ5^R%&!9jgSoeer0HLR@+2^8F+P5GdJOjvq`U&rJw;kl-UoAjm_Z*>E|r24ov9j0QDij8NxkX~p9{7{Gb+Ac5_@eu)1hS#i%)`QYP+6=^z zWy-;@a@mS-yEcmF|N8uJmEJaAw{}4Ca+sz=vmw2Wy@7UgIEFQ9m@@~EgL%Q&X090V zEQfj4BTq%<2wr>$Bj6PV#1$5RUuBHybhMF`!xxQI1j#6fMzQrb%`2{D*C^Vr(2qCS zY@Yg{WV}4aqO0$3PM!Lma_A3w9gpKWwxj>dsiYz25~eFO<+wbZ>7YMegedBkRUI*K z#p!w;PBAJTk9;EW(!j=b^f$?x_^M~>2o|C3kTkVgFSE<@FacJb17EmPJH=y0{L`rC zTAAgcy}Zqojuz(1eDbv3$Lp}hp;gR4=u#eCTWLNQELJ+>t!_gN|~c5@XL9|%*r3@v69^+nYs->)-BeMoHuI_^Fg}8ax^Y=Ax3@I zk`kaOilHy~6}(u9N>FvdK20;zxn0uKPo5O_#__rFT^~jB<73%CMQw8^!twBoD5 zD6_{P=`XJ34g8v9aAS)54A)nZeM!!{ps4}IQyUy^vme`_^0YppJMUlMm*_e=C&hc8 zzxcr%06@!J1{BTP_g%V259whM))IIN9GY(3rx!2KS08j!o;*2yo_?|b&U5F_)NM+@ z*s0TGX}L!aX8{z+LUi}!(51E}jp%C%vh=*|qOAp{T@%~jixIs1G({GMHw+7`p#2Hg z_xiqdy3Y`2bbV+nA93>`#6f3|430a5#-J(U zc9i3)q093S8u!ontZn?qnMX<$eD)hl=eFzR zTJBr%H!r_?E1ts!Jas6GKr*el{65ZU&C_z^GSv0c-7Ut(W0a2%ic0-UVYB+J@^XHT z0}{RS&O0Mm^~x)+3|C)$bp)&ej84x4_*y_u{LRd7cD%uG^byb}@>HE=CO^rW0G8;B zI_6E9xGg~&2+i+vJae4(2;oVa)B&i06>Gqy$Pb8hNc#(3e4eYXSkMMmi0_hxAp;7j zhc|eZb^)^5!=LK|2T(9xrOM+V2mZ7N&=eW43QRljqCR?o&S1jGr1)c9ICPoQ4#_8O z5Q^ud^9|^P2JiV~e%6sg#@3dOk)P{~XF$lkaN)uTh(;gul^5Enhy3&p8A#Ixa(Im0 zHlY+0uUpDoZdoa(KJDHp>*9c+u?P(~-8^Xv-W~ zJiuhels;Jwcr#`OL>thFF7ZwSgr+@%racD8N}G%^z-8K`9gGJs*N_QXcv*hv$@lys zA32zd=)izd#$oYdj1nw}^PlSsJ;Kj4)+6=t=+yJTI&&Z0mpr5lI_fZFaV1TWs3ZTO zUC$@$-})w>a`y|F@QlB&5%@sU%)88ep%3Qaka{?`Wj^G^wzAN9Nf+oN=^r}kA*Zi( z<_dIp>wvV#DnUUk?J zWjc?%;Cas$aP~cA7GPdLy`#COJbCx2se9dpz-RWhvwG#Ha2T?~i3>5vc;y$Ufo3FAHpaa+S0${f?uL2(K21 z&<@MdFO_`v)v@O}y)mb@i1x`Nps3YP_A2}bur+`q$a_>Cm zEfGv!rEAqzmF}LTpSAZ>!{QQ zKlskq0xz@JjRur8%{>h{3%dBcpOpYo>i%s{jbe%dT68EzP%BS`d zKRkb33v+Wy#qo= zj+H;-13GP7AT%OGO(=9ni6To>L>cOlu;Mr&WJ-XN>KFiB0+cvx;m`~qbODkrdBHdJ zv#lLVhH_Df20|BlS0>UVAT&^&de>~++9D8(TH+sN0d^+fxWF%fq5B0$rm>#xY5Kv$ zf#bBW&9>XCH|_DWFb{s{L&D72GeeIoI`iofjkM^}VPv-s2mlUGl_h8_Z4c;x0gy5e z%4g{i2=EY=6|pqaE(^;X+)NVCnZq??;1lyB8@gq2PzOpnG{hR@%o+Lwt$4NxU^k$8 zz3bM56?ZQWYXx%R0IO3V9Uj7PShYdpu@0*vI<$#kFearwaX(pyP{KBa<*Qce(?|Ug z&;)>MNOcB9KUIffQ#eFY=8WkxB6tdL_8Q61tsh!brU|SiStMd;(&mx zJyYPGbvo?SXR&_yi(iJ{UU-RkLnlzfhV`2J>jfy{Kw`bJ(m^TuPe5p=Bir~VKNv{4 zjMr3o&o}BYzi7iA;p7W|mI_93^$*-5q2@xm+DXwK&Y@E&?RgasAW%y5$V7ZJXMPS7 zt@-6Oy?*3*&Excc>~@ny){Fz-z~bsjxuns+_=9(vy7j0 zuePEkTjW=6ok~)oaUMXYvO3vo{E{A$90>?**n&yye^l=pb16|n*ojU{(H`HxHukX`r4TOr-0DolV?0KH={}O6rFPa zU`}{^JU7(7t^vU;Qc*TsQ3rMFlUE$`NMjZMMgVByg&gAoLaQR6-toEd>4__LJkGtZ z(ISUsaj2Yz`>%Cq4#=f=Y2mrXu`yQT8|y@ZVm&DC?Ma5T_N4VDy>Jz4@<&b4GULgd zPcLYZCKp+_!*f5Cb?#V+bqk=6ILmX7?$JGxPbl7g>n#Gw%+cOqitf>OhX*}qr?Az$ zAOO&M)fMn$`mC^pUZiT5WnehZo4-)|h`GA&>pnSjw*b`B1&|e(T6>H20zgmc>IgHY z378^a*aqz-xYpV>$ae);q$6&M5+?%n)#TRealhs$Se$v2u0%ss&c&0Y&q*2|&@E z0K zJIHET+-^P|KB{+BfKve&NiEKCIC1bzYK2ZqhuD0GJHGls1;?6Q5Y%7oyW>@Vc8c? zJDwjNBkPQQ<~lXVLp*4`%{jK@*H=cAalRSOQ6*nNS|`@k;P@CU59d< zX&f?EjG3(+BP0Dn=U5^(kQ;ymyz$hyBLKk6EyjaQ{AL!jaY4awIcfZ^Z%iwF2 z5Klg|@S>jQhWR*;c0G4}oj6T@@Z?*s9((H9nT`-w4c#`O>pL`kl}BWxKdwVL`XlW= z(6_vQ$cT48%o`f&`6Uat1wXvggkw3&ZQ49EA89~5YuC1U=Crw-%n9Vc!Jo19IJ=MJ zyX{F@Puuw+C+9ZJJI{09+|N9O9vNsm_vXXA^W5b+u{`gF&7R=mbI;Nj?`D^>f9b2IhEIL=|H|}ek%clI^@}r3i^d~N_udbD zES&a(pEy~DRe&0nw%_@_50~YwB0FrqT{!!U@0G=O>t(>lJ^5K>`o2V7cjzm^F-IO= zviR0_e-J+K(c{asBli~&`prkZGn{?Sc@|^T5R0teKIKbwmZ4kexH=a17ZCd7FP>0m z4f>B){6#NQyk$%fv=#9ZS&RM9``+PX44Yl!6l}`2SWgT}2ZXu*fiDaHzUh`aIa?(F z^#1U>r`gB|_ovZ#hx5Ply&s16%YyxQU3E@V?|}w{9?imh-p`l4`1#=j z@4@I{a=$p|+;GHE?{adZgjgX5KyJ5U#mcas#uf1E{o$(fxz$=xz19IV|LBafMiu#r zOV5jE876x8WA+r*M0k%D?n%2pK78#0Qxjc=)q2L%AhFTd!V@;BWz*IpN% z_u^N^-&1A9Q6jH-)yu=NZ+mk|!8*-)U3Jy|@>`J?LjI;NoNsK$Z^u9X?)iqnEhF@JbmP`?{zYUST8^0 z``?IhWaY&*gWc)FQ?!4}9c$9>HNHKe<))afFpp8!JV+L(yn-x?^Na!mlC z@9&|wZ|zS2p&Rvg&B;eAvz+3JbFh)8siQ-dbl$Ek7NI#P0SFB^FCCgFA_vGa0i@d60n(BO4;{{k4@r(Xk%5+p15|Ewmdho` zMO(Q%91O_%;Rv8*aTGX{hvQRZow-|90K2++!s2a~L?F<>&~SM0Lmw(|^b}co*5^fa z1LyD%KysHX1qx*o4=TF_mf^s1t*kWydd6z%^y#y;QJfwRWL61~3{Z1xea03`&|NyT zj9_Sqw@#n7r@sSOh}PVhJ4d`Z{1ixgkcaBxw|x1suyWP%_)r}yhCC=9kTs_PJ@{wy z89#3?9#f|1fKK439)X)T$U4{3<#z+=iuGjBFlxCInZ=`52WD(cI85aL8(!;m2sBA; zx2x^8;=s0j2wh=iYDg9g(;-o}+G!KWN;{eGr{Dh}ocpVD!}2@$gsTq2hI-Z4J^`0> zh$0_LB;^JDR%Jil&Q)7Jx`B}2SU=^L&lQ+g>O z<&O5Zt&JBMlJm6)AgvsSqAcb`9crFBjLJuUniEle4y7%Nxe~V0C-Qq-T+efYI`Aev z9#`x8=+vw)iFcwa4$`xB;FLy#*ywKj7NJ}5s?X;>lw7W}#yqe1qf5t(@OoPC)Ag0E znVi2aw^1HU=WTe7*RJifZl!q$C9>MPW@^iG#JPmcyGT2Bb9se(M&4A(5e=@1s(0VP141@S4fj--5`H7=Qc*8NoBg@ zj!h&AuH<^>>yrBB!5rcWA+7Rw4WmQSmWlo-UID-=vxRfJZUerMI-SDw;zj{#mb9MB z=nL|+HUWfYT_XpNtkSE#Y~b~TWlHDX+8^)<=}tY+=n_bISce)5xENGzSYL&ZHAWqF zY_WxaKGU?{(B5g%BmqqHb%q`RUpuG3q)nf(U#NqgSz+}mSy=909eL?itopj2s@;M9 zUe(u^CUpO0e**Xzpfg`vXrGikon=(hjo-#MI;6W%L`1qf1OX9gX+}zSj2;XDQE8Fx zknU~}q+>Kl_vp^S;J^FD^StBT4%^w;_jkqT>gsB5FJ*;Q$>O*098gZL7A}A41WcCB z4a%+JE$8(b-K+$yqFika{76=n-cnusq8AJG?FT(2U}TLbvq}_tK*E>y^QyIuPgJ~Wzo5{{93ntqyFvv8vqQKUZ&hX1S;y$lUnc4?Kp9Bq3l&p_7=J@SN*iP zR+jt`vGcKdy)XWWw8?2MMLD)HMZi@p+z!Q9YO-Lae{V02PrEn1zg-nvLT3#@EE zPvE$ytDt_DfEqU)A|o(Yti1a6)RZ2+xBO}&KY?d3ZfXbO)!w$$cELY9&ncMk7E&HI$5wLw7xSk>dUYCc!d*7dh2b|>P)H_=g`BU+{ z-dqdL1O%YHze7LU_}i^fQ}ar7-qlk zBe~1iQ0$;P-{gbH>vLfb#tQB2O~L15o~Kb=%2FpZllZm+1k|a-yevrhC;j?9G!eH; zIVosNq?9EJ6%+fnzCvbvJx#1p-Iitz+b8|ZqAb}T>m-%XU*J1!E;F5!XrV1Fm zNOzM6jc%<#DUsgvVy9kXF!>E%@yZj?8fH3iuOC{5=&oXO+0D+&Q8p8UMh=TC2+xH2?O8GXi z8LK+Wq&pg;ojm|@=z`d;&e#J!FdO=8xG{2!RzUJU15|ulM0^Vm>y4ls;EB9%lsGn~J#AbL zRBAf(4*CWuGh}cPy4D%rZC!bab4A3Ajij}~&g|*RFGUUIbq-n&wY?URG;XHpbEVO} zNMI;dK+xcwOy#18`5s-w>L%EDvs3co9!&WQb-uPg8bMaA%ZnP_~0rK=5GKPac;aPW2EbN+=fZeaJN3htgq>HR)5rEK?!dq zimxVb3bBUz8UB;wJgATT7ypyv7)+2ec~ci{=Q;F5f~B5-9PL*`fKq1ZAI7X31j8Iy z(%i-87@pcEw2KOq$uoRqmE_u82Cm~IJ*|XC7gcmF`su^JX1dKMVpB;j^`UCWQ$8Jb z9~_)t#v7(D$(cifExSqq67mtfHjJo?^%VG0wRt0cmi=#W2UHsur#u8E7r2%4b&Xwt zlawlGq&6{WAy-kAhXD=u!uP%BWRCij_fRfVmnEm@SgMf7$fA3&?3?(oYA5^)@TriF zSwRK6{=4HJSv%=6K^;|UPKc!dm))-Y)lUXBnqplv&@p*&jf34(8m7rpV)`oQq}!94 zsWFo2HphRUeJEj(rw{*Ym8b{(9yxH*2n56sIjzSo0qhTa7#I{BI`|t#n6taDDzMI&bvHk$7C@P$& zs%ElQ!~ucRMoRc#Z#eP?VqMbxoJWkXgMp_e6>G$q6|yF7zlae_GnKbv?7O3$qxvlc()id$ zIi&Nlf`x9s?1Ox$rRv94MdIK2K8*?C#SKfV zd#Ki$Xj(J4gW?KE0;*k_`eki(xNZ|w2o1ufKp;Lv#qe=^%b$R9HzfCcU(>F%UWLOz z4&S%L?39b2`nhT;Uvx|jFcVqVqz$ZB%m=%h^pf)`-<3_^t4(1DuV{76b74&Cv$-Co zbA7gQ>q{T6xc5sddnJ%r+Zda${v1LfcQX_1)&5Dy%5T@GL)TNFd&EE>pM~%YGyP~< zN{@$3bv6(Kz|Zscim2{jMVeC?2pBj&{RZU@sX?%ro%`oyY)vx9%KuqGT1z)YuB$fk)8Ay!z4g5nAN@sUFD&z^k4Io`9 zpeWHnrg%P&isLtC+`V`Hk|yqGuH6Ic;|#Q)l!vIVTuSTPb=k|2JDJ-K^lgc}uc6|A zp&FhS<#BHwHI+(}uX)=zh0FM5aVF%1LzIi>YYWc0k`p&NRQ&%C9(C^QsW3CpR@S54 zj4WH2Bnw-nUK<`<#x|?BOt+UoLi$vpMKrYdXDF?%MpiT8T_q%rkgNc&YemfWCnI(F zc%X)EV{c5mY3r@}tZ_28%9_LM=~bNhSyt|WO~Q4&{Cb^{Nc1)>qLF?1zxFZYg-IUm z>VM8Gd#k|2tm14}tHu zD8X>TYj|N`&R2E`I(az%f9T28e`Doj(esAN}#_7m8`Zrc=dnaVg7U>_i9+dggbt-E+dBKPK_)E zv1O8<^plGYH6jN629Q0|@97mk`+|wz-5rK+p0+T>#l3=y&(KX*ItB4F0aQ`m0cX*^ z_H8C|8j$(|_%Wa16Vn=QRR>)5Lya>1Ip_U?kE`vZl~RPRGqD+M7EthQ;QDvQJ#1`g zs3B0EE`V;E9O9|K^vy_wTZs^EAidDDjS~0RVp^R|bQ4w7+XNM8+5p(u*#74<=$9D8 zw6fgDoYl*C@yvU%pp5~0F*_dbUz^lyfvtbA1M6UImg&@uSAJptt ziD@g;p3{+-^8EmukN5W9^SeYQL!W=ms-{F(KKu=T39K7XQ{5;aIkih$|DvCnw5&Qr z5`6k=6BHe=ySx@;0_Z}o`pR=blys1e$ah+%>ByfTfIR<8=Xex2@oGiZZmRXEV$=O5 z{#x=0vTW$Rm4|&fF(RLIuy94cgLKc_WB8fXuc`z}dT!}CWRa=)_2F_9@tml|K4_P$ z#hUZ*{5rLF#t7GHpWKiU-oj{J>Z9f$UMWTxmvp_G)E`N#zPi+zP6bnY_AUC#D3Zvj zW$F3R1_5+u;W^5SylY!Q?J69MBRzf8&rdj{jYrNdTUdio_uti*)&1dCRts@re&5eddrT-y5V`1^DM&|^bb2vR)PZ;k%$NU zp0e~cr~hLC&_#>(4QlpKG2W)1P7t-V=G$4j)!{{AWOu+B|Q&z5Sn{?CTR zA3lXYK7>=UEs^0LR9ya34}AF_hEsyZD`+9mPg*nW#Kq@`qh~R?sJ+Z>2R25i)V_&i zMf$L;N?qlj?kY*uybNLn<``ULU0yCk2>gy!eW6qOD1yV=cJs*NDCc`pGhh3NB%(^} z#9VVn1@oFU%b%gn07AnEBBHi*zSP$3*~JYNYUsVG+jxY^B+9>x>}oIFFPTH2U`0CP z-lbQwPCD?1EEMXEdhe zHlC&A3GJ-&eAj8C6=JUyH*6arg1ya~%k2qd|YZH0VA{}SZxuXX?N1~F|2cDn6z_hZYh**AvD@w_{Ld6b{Lv;DQIlkUSXDN~NB!%=hCGZU z%D46y4r$BxD_~F2+u!vL&Sg}XD7eh*(z{#PaoM}~4yeyimO9#>rw4<$Mbld^=&C3= zMJAwBx-KkRN-8*l2!tHxmOA1he2qVACPfE2`U5I|wx-?Ak%}4@c9FGR=%rd?2Rd&Q z_8b@vkZu32U^)yu1x?4u_O&tPMy-8-syVaqD3KhUhf0>{(noZlxhqDD3sMZSW7mc1 z1x(V0xs&)5V9(lzpm$(|Vs*(G_d01`jpw~`DI;UoF1z-w`X;AhB;G{4WWP*(Cbb?-q57kQPsK&q)hyvy-gs<1lFn$2Q-?9%WP=c7AU#-9hU^jF z{zhN>`PY;uA{vP%cXPmNpYLQX`980gk&qPinzz$AJ=?8T#lEuP+!<&bl~d>efC+sy z#-H`6?0!Wn%(r_$}V-rT*vKAJ`ujL7>@C5Ofo6xY3&y4#-_&)92j7#PC zwS};Foq=^;h1nv#JuZ!nj0`lp(iJFSr8VxFfHozkL^yVj%#-hL=*k5qAd7Lf^r+e1 zW6my4uDwKm4ckg~ng8rs~1ml9#N{jntKN*)9D)rF=50iH& zYAN9dQqtdI_%#MEq<==97gn2J40HU}qtWueLXH%ZyP%3b;Ov(bK?d>xn^zb?jd9(d zGup*sei}r&LN-1QgNvGW6oyppj7z_V2IBwf6QW9hJ;!oj%~2LyQ5xRz|1e z%H6WJZih4mBhv{;!SPQn%%1(7}1tBY?4(Fei zOEJ4Ch?e~@y>=YP7+RF@i`p7^9GiQ;RP~ZCd;4R=&O&^CKx^9}4q%srd^BU0gO__4 zT`n%2$35~3$oEqE*1Lzl2oBUBa*)xID!=Vi-q7uxYdiC+8n5Mp`<~R5g!PsnQ!)hB zTo_?{`b;IH7o{W>^GNSnaRRek+U{NrzRLF0^L`c<7CW>1_Q>=yckZ*a=?ZrWfb{ir z#K#ep%jf1BnS(d)c0RYtPRY~xoE4{(GLa)bf$y4T5(Qv|?^J&rq{p@sW}|ajHL5VV zfhM6Jv?m&CE2pGhfntn3;$LQo>kEz|dNO%B-eYy*XpzUNKr(q;5mlbONy6gOeb0c) z;h2xk2Y?Se#7z~$tcyH&DwN(~X)Y}~PTqLgwFv-~c3K$&jFUfzYuY1{)_QE?O30EU zFk#lNtj=`0qXtCTy|{>(IqBp%nSZrlR6ZGKuPR!2^8fa)nu9N20qTKv)KOUQhksYP z1g$`Addpe#T;Yi?jV9$)U@oooOG6P3hw%UKA%T)-XR{(1@)tX6aq_20bZ@$OKN4|;2fIk$*sSt}H!Stg)gs>tf2vk%_5Xv>bBf*H=s@rU21 zWZc7J1BO3*^XRn9z1^<o&d@8}d93-Qeh1hhP&q^BZOp$u678U+XC6*GFKy0`GMw z+tI&Pg7C|f>$tcU(ev1TfW$!@x(Yw4ey*;Q8@E!^$w z1$38$%zB0%mRG$WHGbz3NrRH{P_)I?+17qm{s|^eXQD2u=HkufUTOg^9oW3)j=S8j ziqR>QX=Tky?sNCOpRBX(UJ@LmErqOZ@ZwFNb}HLtB3ZNB^wE?Dhe?agah^vPY&U}n z_)Q>aO_{ElFfOHoG_?{elnYmbE|-%H*-i0_zJ$#Y=Ir5u!pD*Cthd(uUU=RQm}QVM zjrO3!JMuq4QW2uzZViHJ?0Qi-cg@lA=VzCH5YLaA9h>*aGWq^4rl8nD2OEd895n`s z){;dB2+Oe9daK%w^^@ukmhV@!o^0dK(?#5Fl6*K!f9F6XFK9A|b9oy7ECj<_)@Z9g z{_1h~Py9R9OYklY*e$V|sq>8z>7)SFHn^`$dn`+OF4ct|*UF!xer|2eFTiy7-dj7R z-=DY#O9A4X5+>frC`+&NCU2%ZstnJ^m;Lw$>LjNmT}CrUH)S@VDDaGH3Z$6xwqrvm zJZbMt5%3oMYl8#U&j%FJ1b>m|-`LCb-{JJHO6!8Sr#7REkx42C$G|jnVg&k$ufNZ~ z2#2oKGr&SAqRW2o&SnnXi>dv7>gspPMpBMpf^Um<~yQM#tWc z5t_TsGD@oJXf!+cFAG?;NvJZ!ZMICWGS^H8(|;%o9@lwHdN{sWkDY5{r}8j9J2U=I zy92}kn2wGO8zdiRJ^dutjgeUO^^o1_s^~D+*8j*aIM?0?6p@j>!*y~{En4ECPp^|W z^R!7R=@RvA)S>{B%>Gij3PY2)E{gG4GC320UL333-u53;sv(EIgKuK|hlud6%4l@- z+GkIAm@g%wrC+omVnaTh`H1zvFo#C?Uf^3X13nT(S5itIPN+KErgmu6x#964RgaOp>RoiHA@XsQ2Zn=Bm?Dw!+z~FOIk7=p=4!`_-a_P`(g~Tsd*vfmH`aeSsAI$RxQ>D^B z0=TtNY3c5HrAb-spM-1X?Le3BXZ-5*R-?p9OzUCvgZ$3}?7254Eo25c7T(-rIN9ql z#Z>CNu?Vp4C|4z_RJznKI%5Y(na|ewA|jFG!P$l39xT z3cbJn^SCPZ_eIQbM?eMqtiS%N-FYuv##BBTJic7h(WD5V3J&h+=FLZszi#+5&dRGA z4k(jHBULARZT&8L>@6gsL&YpV=Z_FcS*T=2d}{(v>_6TIF+tLK1Kr$P$$P}(Vm&*3 zET&v=1g7zZ#&`9pytmLHK!9khA*z8i#VUX}n9Ct#-u)AtQ>BaT(C&b_pxN1wEFlqD z)+qs4LHig@(OZmWg_^vTm7=dwn*mOL+uY`|Z#_b7YIz!jpL*s+^DND{j^Yt5$}c8z=)HQo0oR{X(X7egj`gC4Cvc?`F7bmIf_g=m^x?K=LZx*b}nvVS?AD4!>{@nJDc z>+>2Xr}$v8)w6vS2Rlj%bsMextySg)$_)y@*NetJnwL*&#K-PrmQV4G?rtpO0cbLO zlQ~mk_S_Ik+O@Z{*z4H2woo(l0Cdy6 z^x{_xh8-S?;$~Y2w%_RyknD=m-@r{JJWZJ-Y!zGdvr zLVW(g`C1PW=)s`A=Q(z7UerH}ON0tV-0w zc%FJ`oKi6S2=K!zy7)dt#hxJr)F|f!*6a3R5nRV5k$EnSuhFGcvX<|=qV6uJ_8`k7 zJ3KSWv@I^;n5ehkjs#>Vcrs^Q(wnN{xl0})473%aF>i)W0FwH5a6iAuaA9058`VZz zdQa6Y?=bW__Ur!gWb=CujOC+Lo{y2L_UJSEl6)KLK@Zv(A(yzs{JHT=!cMeNN^e(Q zjnBT~>R$D`KQe!}78M26`L$Ylb8qU>#P0Zy(q_uBul~ zUbF=j?=_I7-yeF$#+(EI0K%^zb#F&{b;*s=;)HfNqPNY zC2rS+STtkQA|QK(f9Tr*j!M!IbM?YB8=YJhrwY;KuvXK8OifBW|4x`nKa;8UC@0?N zC0aw4|E(h+xfVw%0(H%3W;J{6Z-5iZDqwpz=Zfk#%_ra?F-IBoi1k}nW@UTe()(xB~)BE!O8`rO`)X#gNz2 zbf%tI>Mf2Va~Bhr&_6hfA~L&im|6U{)$Izcmif1v*YmKwwcz2!le%QSQKl)h$Ib2> z#mr6U%!Z2%P>mn}>!D4pUzQB^2iBI>^g4tSi*$o6)9>KDu4#Vr@%wCx^;n2`2> z2!ztxaPZb<6TboF=!h5Q77Isp+J8%*Bi8V#V}$>aUaE>LlXE>=t?&gN0sl4*bGN=5 zp2Vl()&hyY{cr@o>9~(oc+HLe3Yd-dxqwq}Tnnq2U|!K=W7jrfhhd;Ay<67g90KfW zSUUE&sobply`Q?hy|*K85Pl@V1s_KCbCT13#*S=t)2?ZXu+@!8FiZNG*gqsPXH+Rlpm5w8BH%|-Z9 zX>4`B-okem5_2YGEU`0ZZ1Aqm1%+@Z+mkCH`>q+Y3BlvL!|nz_zgV7ec@|tj)*B2d z52719CQMAnJeFF%W&A>(%@15KR3Hqh`FGE+2VIv#OZ}b`n%ZvMzV5>~pCa<@)MT7{ z9~}@WA(Qkx;bYLCNV{FyUA464J;*9$T+FJd2Whp6R5fViIcG+a$~UFF7GoE+6W3$7`4BOzpJ-iD z8auSX+NMxus*}a0kn-3_Yc*(2XnheLWT!}b6*nbKA?=5t(e`0Df3OK}Y~KT0A;MNs zu#xX zH?VyFvpAllnR%u}&eEGBqg6Mp+wP=J-JM3-WOTX4f?{lGvpJk4!7B#uG9v$D4``nE zppDeJoYUI8`CZLVA`dgQk85|}2+mc@&n`Ant+Qn-Vuxo%%VA8)tN(`3@Rk;X#~mFl zLZ&{pV9QvXoYQ@~YdCila5}aWdR$TuYEx?rAZp%~ND7ky-6U11t>Wn&R!Lr?&*oOk ztqcgE$;tOi;6)7b_)c7)r-i4A18QeP(jUxeY~Qne5z1@l*h|kmZRg;5vzXR- zpLug=6YAY@6cr~01*=hXl^e9bF?Rps%NLm*vwV|%Dgsf0jLS$en<*?E_sbxCMQ;_9 z#23c1(B(uv4I6K)Dx+^FC5SO!t`=ik7cHRv_@uA`W)_reR`?Mn4rH?*TdzAUfK?ml zmVf-Pb&*5$ao9+W-R^l0t4gP$*6Am-lbKAIVr{p5}Kg9^dczfEf5D zBn5FxPeo3j;in;%xa~PF&P2k;mcV0W8Gl(ZhPU0M20u=sBlx3-2>~((!-go0C=EopymeV>C+QehJGZob}3yVHOEDWdyKNw)yiJ}vNve9q{LWj z9%-`THAmD`x=_Y?+y}`VVOuU0rd>?W*(&7-9u`ELG-t<`Sx?U#N-oam-4I^NNf91njykp)XA+dNc zwxyK4w74?LcE~mPf}j?>^86m8#+tEZ*)U)~?Gp9XE+L51WW~rAIm7FXb~4kZj&uJ8 z!)~|Q=S`qy)~hv;wUl@ipUGxS@TTNCbwEkAC5MsOhUKR(hXLEoX18lB8J2b%tNEp{Fv~!+U()?xbL2s=>kZdTsI&RRe&m` znpewQ?>xe#-*ZjUoBvtc7#Gg*Zsg<=_>_3L$51-;QaEC+k1MS^`MACuO~Jc(Q$ncY z)fG3>Y(XJGy!h2yk6^c>SX!FIUMa5+#g(u6!9n|=XRbc&(k*)c2gtWL1*P_>lldz4 zvN^@yMi@H_uNmdvh^R;0SiZS$1g8m^Do0#kWdT~cdkKtd()(|Z9h00f+7#7~lKB#U z3W7<-4JfgMY^sJNrm3ZU043%XldQY~X3+V8f%@GV>H@OAywT`=#A}y=!i$%ZD9*a_ z=+cboY*4pPT{LR!DH`AO(uM9^Z zF>S0T#uot_Eg)1j9TDu@f`Mb7^wFrAu)=p7L2%Gr19Y;OO1C$wGA*?5#LE_t*^d}? zb;LNBv!g@S*b0h2m;Ek0&qYG)7s2VUdfk|Y`GaxVj!FD1uTn^!gE zo~br`S4UcqzFjm4uSpGJ$r3Eo^WEB$?7WRBRnhZZu|h>a_gfhnj;j!BKncGo%B`m+Pg#u)&s|>qq4A6|4BU}d0DG&?JX4|pIssY+c zb<2NH<^c7zsZN~E*9Ivz9dk+7X#F@vJv2qA9@Yn`vn6G9K4a3`B5RZ#-WO`-sNVw3 z!YFw;l6=pOt)ycQ1m7qIEfpA>ie+4=#$>@I4ln(f9_z&iY7Zj`E^VQreg#f-!Cn>_ z$sGXZ%sF68$#B1w5X`NSXzeAw<8CBA{z|06)&@WIoV(w%d2eycMBbV|bfEjkzMF0T zWKpLa2&1~4Pfd>0j4G4+bEc%X!=cJbSo`k2K6DtPO=EwCcjJfM#iKi#*HAl2=`~pL zwdPqU&fL~>k*nWsT^9{rM5)-)RN%EK#>>N&GX~*U%GK?U2MwF@>f%?1oz5a1R|f$B z!*;8_b+vIG9T(p=58>;IDF1|D+(@`v4F=u_2njeVH|kS6rk&v_{-mBebfH{4wDX_~ znTw*2WIsrBiI~O>LI|Ho+z9#lB4^tdBc6>`q<^i-(uz8y-D7}3x_y_4_I;Q!^evK1HWz7&f^mBMau*-+b}4 z&PA<`)d?To{Icou)*mBskkP%Tiy#jk8N})756kG+DP0$sJiZ3ES1y5i z1>38Cs1 zp_LgyZx8hlbA*0FPQyBIkP^K|K-2mDi7NZ#erscb_X7Ej2d)S0Ye9{G1w3;?9I4j+ zzx2d@_D{&;k-3kmj?`#WY3s&8yhKj%o2$_|xeuK! zN?nCv!`J{Q)XZzTDprU)%(I`_x6vc!XFq7G}CbyAeF0*#aXfH;*Y zV_Dsl3*l61Z~%A}bp#qDcYu_VK!Lqh>qJ4f@@Qa|*2n63jDb{M=892yw6}R#l45FhXA9MwlpujWtdPO3 z#&JQ?v&LgLzRz9r*?5xDW`$~S2tZbn@t@#6CmcBet1X#W1Qi@`9DaGD@w^jBlUQ?_ zrals19W}6fqet)cfMuTQV8o|dR?fFmGOyhu#=m3VxNK3RWy}29eitFmwlJSkJT@Kv z3+~I?&T*0__lOf3)f+&Rb26PP?p)2_`=t1MMnb53dP47o6Po#ic)Q;{_kRdR$k@MeNFxr_H`U+CItNkGvi?5-8`F zBB||ak`kqpK+22FJJD#!`whumT@Pae?e%rE7d$h32e#wP* zpaD*j-Olo7guknO9W>}xVhL5gL+Nj+QB(pi87m4y0S|-L;wX?2pcxV66yYL(K7&rOIrUPUgmM(do$sd5l->>GnuFtc4 zIym$YXoqHG^7S@-Vj49F&4gIKNV;w2nA@HxSZ@i02WyI=$I|!1;5$*>zObf{&9M6H%^_p=^%a?N|J5dzk^wr5QYu=#=l##yUxg* zQ=!hLHB$i;0Q`XIXizVo5H$@n4E!##HTDyk3tpH0v*z^Zli{n)#W)*=oPNnjLW8!N zne_w?Jv>0Wd>deuHqy}q>z*W>2eFlMw6=qwF;xz+lg2ep}Ss1i+}Je z%<%e=Z8F(^*O2WS9$aw?(1`0_lewAVYFr`>o{i)R$xh-iW%OkUdHWq|1-z(%hHu;L zn-oROU0ChmWE#)rKpJ63xlUeZ@9=lrd-Vsv1O$?YX{JJ4B;RzO+-(@noj$)?m3a2c zMv|A%bp!%7D`#5|S!>P9%;9ZlMmkWbw0h{E2m&D4lP*bc1D-OEh$` z%!++&s6Nnpd#=zahI+ye9`ERkiy7`R|I9m2M)NGR;p4P|R7HgNt|@fHICOo~`?+ww zZ)8_iO&#td7OghZRS(fx?Vs`8Ouj)RK>geUM5;&ho=KVQE;%Q&&1An}EZuooF6{=_ zy}3LzE+(KN-~ziwzcG>P23I0;c$9h|W6?yFWu=JTeJfhj$xQ7qihVkQC1cpB{$r#I zH-a$8$h|x1Np#p!=C|;ZLrV#fd@+wWoaDPW_lng(UqT-#a)}y8b#Y*`#>0QfWZ%|v z+jEPoP#Qte&U@U16R*y|*cwT4Oc2Ai|Me9jWz3>``IPM>>CL@Xv|Ofr$7X@YQeb9g zct+O!=y^uwy)QLmbXwN^xb&V&>!qR%?5!;arYu>LX61*;MSsMm7S=xgW@*Y$ z@o-!ZK4k1zl<)S1XX+FzKQ@BRPmqK^=-|VDDbXq=9_L-R%z56h!yZPO*W1~G@*~Ma zFD|vaWl%E=Rtw)xq{Y%N!YY5A>7oV5-}lB;l=v4&1yn+Wl43P;N6dX`@u!;?onUOX zYAZg=Wq3Z0)^8=?N=-9<=XuBM-ZouD>VX?%-F8fYOuc!F*}g}4jE$Xnzk~FkA5hns z>18)Otg&r<#tKw!$g=`z4F6i0?r&{yyn+!Lh?;~Tmxhc{sr)mG~0{^&{5+SGNTcm0-ZMXL{2^6)tkq3Qib z;jkcQgtQu^B42d1)bUk66IHb6;p*^xY-Nb4_nybVOS?Mc2c@hk=B z^yB6~>zfRf3Y`9S1VMDe;YH-OfrIy!Tjlq}Zwy(uoh`-NRGkkxKC>65{9#wzHC_Q{ znDy{u!*#;ze@}MWyR@uk88>vMVud5!v{JfzHj`%oCo?X_t?;(f-|IG=x4-ke7i6w} z#dibM7aBQN_aQ;kDnta8kQqL!W`7A{L^k>j5tH;C=yw~B6hddcbuOSY680%O!Nw@B z2Xxi*c_ik`RyTQog*8_?blk3* zH!xoZ0?1*AZevNqsM@eBl<_I>!~cVqQ**MQfERYrkiTUi_Ksxez!F@hsWgkvE6FVT z!DTgD+SPlIwhlVZLG@KZ1tY-Z#rV&8@XfQ(Uc-PxhS(XJQ5Rs46V1+R^WczvtNPk@ zqX@o;dg{DQP4Kk1E|BfjXNabih&`WX6C;I|e^uEVh}S@gySI0xboz}wFqbRR7HDm2 zq5a992g(7dgNtqu0u%Mk%=rkbJg6w~FcTT6sUyvD2}O(xLWqCPWT@WLCyCzVuji2Ra6tZPw-B0X#FFj%1R|dX=W8!&CV>>Sf{4Lc z8nyklzg}#s0_Wr5Dt}&98}8nZx^KX#>Y~z5?%ULs`J$~AXbrxro%qbLY-~vX09@vB z`epQ^1#YE$j#2kmwjb;c_#nTsfED&hbY-k+`v-DU+JcdUrq8$=V4!Wt)n0DJEQqK* zCU@M>>ilEsSDMCASMA2Z`qT_39g=+&^Z>f;Q$CTA)2rN&#u~evE@C+%H9Fy5@%Q0N<2Ph7nCV2 zs){*MhhLU>*^li!@{sCVi^>JCj6QyaL&LFBEs2^A^A|H96gpu^mUg8!BVj6Ni6-4R zh~|+*Ip6<}ob_%Y<*6vB!FFY^pb&#T<=Mg9U~XR5xN$n(AFQIY>T>g*mU1+@@~J(7 z9&>@T=wDAs2TyM}`o!H#hZ?WDh8Z9bIbs!$@_M!;g`Uxcr5rqfoo(ZqPD zBTxLK3wTIx;fRAL(j8pE4&_A9IMD2fanxmY_(gpIt6N}_pUO})L^X(?u!!x-spW|V z9c}!zo$N)n=#3^R5*CokH*||VIo67sd9=b?=<2Axr~ToiDwoTsalf4vL}(k`;5cYu zP-R>ymMZLy3yr3ZMDHR9L7Qgg)dB`Gkq=}fbxDpw#08&dCj+9zv>K0z@>9l_oO~_{ zs?c0hcl(9TTCNi7-L&a13Nkze7sjof-jl^bm}rOh zsy1(bVONEn1l-b0hrzmE-*u$h_)X>nXYpJNAd?HdNjq8D9pD|VL0i5BIh=dGCiUrd z9<-BM^itDFB2pb!*j$Nm1pJt`cp6k|ymn9%U=7e7o!O2z!#5=ca?$Ydwqsy;N;QIU zy!gHs@ruA<91sDdsBBp+smhBUG_KK~4afXhRpB9hT9bK;9J?o5D+?Zi=Gdi`zm*@B zz;l>_mU*xE!u6@Z@!^Eo3fRU_wYdH+`8k3hAM`+AepH(=RNJoB3XL~HGN3R!rWm`c z{B2_$mEi?A*+(a4M>%beie9`r8brBDB}gcdr5qAOWE3>MeRT%H0HN8wV*^Pgk$za35p;rgy*Rw-N> zV;@4h`R7QUF-BnZqyb!%Jn=RD=%6BjVm#lOxm78DkbSmL*97(G@!Z#zCTQ@9#l`jSw_Xm2dK4>&7P-=RF;imZTxzkb1A z0}xSe>l{3mC{zbM;i5>!X5!$PeIOSDD1XV&@JCOGus(M{AC0GT;XMrIw2-+_+zk1X zbgfaaAD?Jiz5K6r1i4r3#4Omsuo=v^QSIQHPW05e=u}Dw|L5{brS?Hmib!N*igR@@ z>cQSHp|U>?DaP!nBVWrQ{h$4)cW~lADSecU-h-_!UhPPo-5}pEr6r(C?tz~i1xQSv zz78qvpjg$ZI4nx)6gCdro{3gFsCD-4ZS1VLTg?60K!R$ZCO$G5d+3O*A#aL=ADd`G?iYXrg~bUkaRj`$So#_^-qtzPLi2$#yX0HQF`pO_`0g zin=zS&cM}$jDR7#buyd4zKMdzb{ZUH;lU&QUCVWCn+$DrPd1Ar(B(|kMag{vs}ZI?Oqlr+=?x<5fIKD*c?IrxnBtvC?uA$d z6rhz$E|!4HQIlMHriKzy&?x2Blls+PaO-;dvsS!NVfDZyCjV*k^<);)jr?7ir*W2^ zpr#I#E&11>#s&U3pdYf$(@y_1AfS-@$zhMa)AzH;qROkS_6w*V_e;KRA z)gSS$p1di=G!rjo$x4z%%4#ibbX{mVDu zk8h>DRJ=DiH@K!T-Y3#y^6tkfe3nkWxyHf3BsR>ply$O1qgO?9MFZqZW5h0Tm4;kc z;o`c&b}4~ASDL27ud9!w&<4!-Xi5{>(N?PF|7u?AD;#Pu(9;o>dU0J6I{XjPKrO#< zXzfim#gFYmP(|Pq$Je)abV)8*i3a#2;0{)XdsJ@IruAA3kt{-+aU47##mUL}Qndif z-B@xQi)2gUGwKJkdD-*PJylj&g$2PCqC|v>j#x)JpyY>PXc&#%I{L$ z|MTnLhpVo-N=NYCAbwb^)S{~DTz|(pfwnfQzhr$zaaG{1*rtz;8awr8HY{W>vLK_M zeR&Kz4h%glU^eDiOD)G?Eh#RfWYHMZGDe3>Sbf4tTWe32HjI}nT#fW;jYx=YN@*{s0 zE&B&a^5+nF&79lSEdTCE_o5lHC!HkOsf+gWOtvnn{Zr`2da`&8pU=+Rem}ia@^X#e zALaADK|2x{IQ1VE?r9_IbY82Qj38)07F@0?^+%+mKTYiH=<|Fj3zRvvu~8;9ytit( zwNR}reS!=;ACfFJA9~&AzQ3l7JMt+*FXrPGSuJnwI~R^Lao(e1>7ZMt8nM}P|D)pT04TV(}j&V?(R9x31#|A|BZPN5ee(W zSXJH%fxy~`&f{fLbA~p(TRDE7#dfT6vWuFJ3mZ2Gn5#`(n}Gu z^3certU=!{0L|^%#MB!$ZW5?Vyy5RJ+g+} zuXZgM6ktj3@IHZlc&~GO+~^X#SSY3yt++XI>N2Dua7`z9e$y^jCZfhh`Xzm8@ zcJ&#+cnKE$g_;+Q2oTL1bF%Dpp=!tMb2Ghw?eU1u27oyr^z0iGxx_D6rPE&uH{~5rq`S|FI&43JkaX|a znTP#qI`L|r0bZtUM3d)L^Wlda=4;tp#_4%E(yHlsJg3dWrm>&bVE~)c>_h9z`pSLs zh#Qc|yNG8an_&&=!Y4hy@;tZS`R19|WBE*LnJgzhx&xF(pES$Q%eyS)C}S|6X`Em6 z%^M#_dGo-x+yG1gw*uzn{pt(L(4+%sGXT?dFdyNaWu8vYeb;L_$g8H&7A|yZa43Cb zU>zV^0JeaXvDS>`<^}pa&PE&@_2ZC-cQ$bYIRR+`I0pDk+kDX`K&8+@PoG80%mVYS zUcEY6hNfOXtCWY-nJCe4lG_aW)a^|+6%8;^DJQ9m*xD>}A} zw1Kfhod#N)hI<4Z8-xyD;T^u>0IVRo79KCCVy>(9?F>O`Bu8H5O>I z%jWe`&NBI4aJ%w!hoSccAJ^-$Id6xX`ED!uZYN>)vw51%zGbeB4aPui^9($2Ja>vf z^5{=F%UsQmnc1IezRN|80 zei?RUh5Y$5J0|H?f9s`xEpq3)*{Fe;{vA0Rb#Pyj`P{Ql50BoXc6|I>-u|BO#q<7a zyPCLc+0tR42_Q5UKLNbiVXg5U@0}hz)+!L1 z_ul2-`dZj&$Ca+4A!xPCtONiOfBAD~lyd{Jn_0xXGXOPLHyseV3da7xhfj-uE|+iS z@BP?Ehfja}@>zW|US4K30z#Ado)h03p8d?4)nD{~$YIBXo7Uc3 zmfcq1_~VWW#|S)_yGHjo`S)a9RV(u|4QAx~{goG=U#H_sF25?g;x%uIbL3nfjl%pE zJm<_)!yb>^y)JtW2wkU+x(J&+c+S}I`}L{MIz$F(ZgA3_@-MmIys&2Vs>&i z^ymMtj5iCs`V~iqqmOuTnSF1!2+eP+pM38!{ig4YGGnEl4M*Fv>85P#HUh0Y+p5KR zhhKZyg=O-HzJcui=zZ$|z-4A7@TGG;6&|_!Ze?n-_g_gcO#rYspmDo9Gskk-R(#&y zk9c@8*u!sWPE)Xj@~@qLVL0KiX{_K+=jMRW(`jff z|DM!9`RQT~2z^hgedg<$142*Lse#aZ#N^5y4|IQ&+bTL2I7m zZyOJN`hhW^1w*V#a%4LonO;rYIs~$skk#c;0c`+AbqcuDDKJeuc3$IZTp*lzfRzQH z0?-4{v`uns6{t!BFLVib9VP^}+PEQFVeAs{1`CT@WZ4J0Fu6s*C@nIn9iy6HZ_&k~ zTzjXiMQdnn+%z1mTTf01*ep5#RU9+lE`ZU9K+)skt>t9ZE3lW+!`3Ach0~;4u2U87qBK*Aa{b+_cQ@l01s^3rjia&Ia@HmqYZ zu{7T4Z}h8Nk@=RECd=Y85lCZhI!=-ynkJ165OEs6=^2v3i38H2m(-$|7Vk;ozK07Q zZ3c7~V_tNztty*j0=S_XWQDv=XOU^6KgdDN=#Pb4T>`2lAUeG5IKmAXonpVfKe-=k zF3Fglt0{weaM*Tj%|Tzsw6$VQsHQ%%8xhhrF4fxrKpgc@0HM=!*Se68?giwE&SJ-G zbbIHVbyin80t>Sgjf2#Gq`6{RQEU{LrX2t@5i>0;s^8Uy@d9X&bm2C7JgOG%L0$Yf znn~BVk7$$IB^k>5BTq+C0Q)%8=Dx$^x*cv8ZwI%dmX_L{IHtecU*Z$%uhld4eV&)e z!;Ay?=XH?px(V0rdf(fouC+@<5+gk~Vv+cVVL?j({&L?TYmXLcIp!N@K8dg5w8grj zEEb_n6iX<#q$%`A+pFWRpq=8iLMxg^cSliM#!^p>sfm(LB*+{C8p8shjL)MT0$rg4 zcuhGdQTW;GY^ zb%);lBjJ{zVF8jiXwK2C4@c|5UvIow;1nI*J*s(%HdLkA4`AW+Y@$z7zo!0;&uHn9 zXASj4-AQNtvUc37%~JFGwcxK#n&00W1_kzAvUs7uL3f0k1j^~v#;LyE0qLM4{O-4Z z)X5Q8gq|0MRWCs9akXngo2}p;M|OM`5ysIujD0LE>l6;ERuX#%m?KH6O68)h1rS=Y zPi)<+c}4;o@thiCgH?QgQO>-Tv~@UwkC~q_254Hh+B2lN2;_aT-rb=-9v@|{gavFY za;mNB`z|cKX%4hex*Zr?APdjK(v9SlY)sbx!Y|P{8qxwlKR|f;PjfAv|K0O-T1K}( zIs(Ac?r{O3+hz58zQ8+O^E7AEW2&>QFMO+i59QB3H`5E)6wNIp000FJNkl*+NIgr0o^q9XAjtA}EWpD~r}GMe{$nWzBeScJ7RAMWDp_Kw+Qp33CT0H{38v`*Vr zoIGEqZ{+7Rc^F#Sz?>>~IZZVTU7qH6wLEcnLyPZvs$ud0*aFxBJVrdt@c=+4kRx#e zBn^yAG>NavkVcrx^*HSGs=Rss#(P`$x69;tovL3HhAoeDft9%V%SR zvI!su_;|bo&>6^yrD8zCfK6|_@x}-^#X7Wsz?8R4v>BI!He-VRl%$CLGD-R8dAPrtwy=eh`!Z=Y~AE>-D&jRx8{zQoV;$dZqBbY_4#0A%!mg9aS{ z$fXT{qR}T;0%`(~Ok=~mDd+atCk>a&N*uYU3yaWsU#`;;(ex|jxzGbLI?nhcPXBU| z4{!33*}6wY!l|vad0sirx;2l)$~F0bx*4a`s3a2Owb=f3kyXZ^Tt$KjcWiC3N5R}AsEQGzz%T#tRy@;aPuog$}YH63Mg zXL+iAPD9xF+e*)A^03R3hCCj(_{2%4-R?(^8^=AaA|E|}C92^}cE9Q)@Bu<5lo5 zz0+%ywUEcR{kLB7*IMRWXx3?9rhiAyItAQ^1m1O*HQ_tos9AJm?(*3E4$}M5-(*{F z?5U@mRDx|Nb;`#+8BYDgnRN{I+Vhd&b7!4imv-Hsua978KvdgufFl7(R$ViYWEJ2| zxmGNG?j$1$=bU+(PIlR;T2+_{AT%IR0GxK$e*cHz#Yeu}(WZW@Kxh~=vS$4s|M~9l z<*%OKls_3eu3Qn$IPF8>fe+ZVr2CuZuKVo&^f+fK6N|u|0jQbBbU^5;1>&o({XsbF zWv_JchW>p0o;mOHX9fVocK0?QH1o~3ocP{p`+|G(bAX_iE^$-heCdFvJ+~oHv(>)% z*$=MJ9ABsD74A)MdshH(+00=D`Sg#xzXaBqt{D(|w}<|d`rxc`z5@OAH~ck%p)m@w zEmyUOYuaY__&r(IgZ|+G;j3RbJN~9Yu1)%`f9Mg%1+1mcl*6k2%a1<1jvXMzm%sXr zaZXy7kwv=oyYFKkd~ewIpZCsEQ*aIlJw+vD0>4YIz5D{58ahy>{p=UN3`ZRMYMrvR zzD(Oz;IVt{5q|dbU&?rj*ZD*E@X7BA2OYS7S*(>!91nT$KZY*~fZM|wM&a)5Kxo7~ z_&LuE?|ADQEOPkm@BbLz=dJ3mEVzw8tIxJ7i`#~Xvpc9 zSH3>5!J_KuL;A9j+yDPOEByH{H#EwsOPd2i*QsMJ@^{w2{|5j7|NoTkB;Ei3KmbWZ zK~(IW2Y_WsRsO5{b9Pfl%PXjBTc>4tvx>ifmfv~o^68i4<_zTMa_F#7H)xQ+n5889Q ztE;PMo_KAwLTUU*h)XoYeOYvcu3CRAOMg-swL)0U@~P3B7B`i5*J&DU_k@*3J!I1V zmDSavMHhAj3yGSgOQFqF(<#qCStZ2e@!ZIB^az2i`zothkn%uG**<;A72TwT^YS07Q5=3>A4RbA-{pZ@fx!YBXr zUqhetu{bvyR+iM(?3CzgVR>mWEG;gCYIUAr+l1@OXr#qBjnJlCP2;0JlGPQKqrREz z_(Yhlqd50fg<8^v{$4oORa~p<@sxyJy&{OhD@^mfG4GKqNtY;6k0M8nX}TXck5IH4 zkK~lDU%POijrcF>KrPgym&iL7w*3QFT-2uKWR$hucH$e0#R>i8*Q-m(Yq)MRbe4FT zGV-qLq86_T6Rj7P8LmgWaan#}Z%>WHcyyeP12xEJ{-u6*1?DL-x{k~9v}&xTIVr+( zc4?-Us>OSGmZ!PUnE&J_z16}}B3ic}>AnbIrMsg0K$qlQ4a>{SAsl_NYm5iF#6#Qc zOz*I{w2?9|hpD9H7)AMA)ASCVkEHb1?NXk5=u(}uUXnJg*Q4gVH0Q~)<31xEP3tCH zHgmnvHrE)g(QZmN>yQ=A6v*6&C+hfD?8+rf3wo03vzGLRk>TNRcJgc!4^~iIjlR_5 zG0k;ZYAlUMMpyKm8XGz4iD8_t^wG@8*EJD&aW^H6bGg@e(v7^eJ0EeWRKm)N);O)V z75S>x9c3FwvR`d_H7#tJGYI8{+=$at6F!p z9`^Kfhwfgj&wah2TR!M|;J((Yb-1^CAdC!+sXN`FN0~j{YFGEhit6?CvBp!s5=KTw z!iw5nS*c0?BVll0NIk4*?UXRARl@^uuUXStM&H$<*2pETn+xKtYie1$l~s*otuLIN znvDC4IjyN@C#S;v++sL%=vY|NEqQ)U{p;=x|9RcDTF0l=c5j%TnGGjSp4Pq~=o;3Y zR(pXs-f<}E^GtEySGu|0Su9aA`I-}zZsZDK*N%zMr@h0raqW$U`oqNNaF~()maB_l zMfZon?YqJb`D;FZP1v`0zt;Q3aLeH%p)xoWPEAgSvyx?1{Fb#}ip=2}uVsY6snK{Z zO>;vkj9Kb>lsU~)b`ZKRMX&new_4LaOSy=Q%yGsm-}5@P#nrYH_bS8M!}Ry|goXJz z?RC1ew_1u*uUliyo`*fzV1Hj2U=C;>v?_T|otg^$1KJO1zc@HDrtuvJOUtv`@APSp z1D*Dlnp3OG)v!Zzh%MH#28H=k>rsE$(+j0PIIMeFnnO_ zKJ;MAxuuW&siv{UL^{VgJl~FZ&rY~ie@mWk-~Tt(`?1TpK9gH-Zsg-`dP3^hm-Ah| zUVfZM%%%7vpg~!dWxcf9FVi%*HRgSp)^#enKd>(0oR`z)aZ!k-(f7QaJnlO1wWl5X zxDM9aCElm|)u8TwJ^Ec)(CgZ*Xq|E$%D7KC&vb;e=QMF#H*1*gf0iYe&vEO%9GWL| zl(B#G9+Kf=J%YyNrlGBL0}@%J@y<$Z@gdkxyfkBUhwlHhew$Be{Xcf>XgG4@NH}@&WH^2L zbeNl)EBa3V@$`LO&jzT2qs_g0_lAQ94~7E=4n&!dt53h{`?V&bBY460)?06l>B-5- zuz&ylaMe{;1!P5b>L6E~OZBC1_t7_ zhAxPEoZJ??aSmgm{>O6UWwgV5JaOVg90TSmW5Jl14m~igw1qsRJ-;oduP@3OA7u78 zk%vR~z1r_0yXA+bSNkLD2EO>kg~hO-=Q)fe*NQ#up)c+u+;fKY+k?4{XCC`LgzV-; z9lXaBdGNGJ9<=lgIgkt4@wsl1-*nW47TN8rE7MumsSVmm*9LoKo|n15(9;g|=$L12 z^qILppNW%)_c(YiQO`2wvN_-VblM@bW$%7i{ya^bHuEqh^v61+-2C%)Ef;0v=b`Cy zSI}z%ZkxFKaW#bPFt2Zw)&0Jqy0ByOg^+8AI~Y@>lhPsK)HFkj(L*r zJmPser?K8V4}Fagnm6~=1wCK&+^{_5zF&y6+br{Hmv1_kJ9NIocKI$RG>yZ&EH5wT zJ59alS;*5gYU0_Buje^@i2wTEA2!QQxCJ$Ep?^niK^6S35&5~#`uXsrCp@<3&%59I z{_vdVy|751OXU9F`px0$*Sx%_a`@Jx;eikT{&+7hG8K8zZ#*|V`iH(R&k8r)d`tL^ z7ri9>>nHzX4gEd7;cnrnKlQ}$?f3hZraDf%{!MQQzw^>pI9Y@TFS|6n_Z@H2UVX60 zBl5a8{8_mA&2QE7wo^^{!^1=2agTXa_=z8TY}mGKqN&V@yWi&l+D9~>he7*q|NH@y z#PDw4^zGVzHhxd%h4;G0H-xvn>9s``_r#|>?U~`9KKk(@k2Q?7i?zt^T-ss1d&?VM z9lr7IU+?NM{LqI#8lL}KzZ;GoJKmH}TaWtw?+MTOrJvXSZ>T6^9e&EweldLHV-4Ag zLPb9QkAJOw^v)vdLErU*;pRiP6zTOMpZ?bmg;DJp6KNhiZy?sUiS-gmya zNE7*kSG_j;@$26l_jP#zd(`{g_uk>xp7YFb(Z0QTQIrR{%I*(d^1|?l?|Mj){VTum zTj5>rd0&yf5Rq~l=E<0U@E`su{L!DhA$h`cIqkoY?GGl&?RYLI37&{a*O1ziFPs?AIUq;O_{}{>7gSdv@<~Ge!9RzxiNz z#>8(m+p{h1mE1G!xW>`L+ur$} z@ZbOQ1!u1bndkSt&%MI8YL0&5-#!)o_Jbc($}wuDU~0IoIFs{{E}N zm#(|MDW9{Ghd=DW;i*6Q#Bk*uE^jJx;wex6#qi;ee9XxU5536-0ADC3h#SYW3JzD)6L-_k9gF2RnDvI z;SYIGc*XDkc2ixhiC4b*Pr_T?{_ZvR8VDJuhv?d1t+=!9Q}_P1hwAtJ*@8!To-7K3 z@$_dryXhWp;vL(!h3|dD!@@Iu_NR5`G~nzQazEm}RCeWS{T}yykj{{1%4ALHzk2su zn&wsce%nN>#3dIW2p{^JcNf{8`RwPyqki-!igX@%?JHjz9{7O!7g^lL-}#=u4Da~! zzYIr?9xL+8k$rpj#B1VP?|Yx{@;`iSxbdb#Ws;aK_jj}FOj$1W89%AD_J$j8TGI~w z<(~DJ(%uBZUwZEI!(YDtZ;Lvf|HqG?4DWdNdv)*pU|eVT?OJxY4R`%ghHr#U&@0tbxGF z6PO6DfL6@iJfbWGK#BV1k@HloE`VaVI!$Dh)4N`xTK_Nn^2J(p+wwDC2qKaGQn!&t zrmirmJZQ;J;Fts@&eM+9dlA8(w4M5jcA&sTu&%hgj% zvwA2mP*azP0W#NCb9WhbRIrt@mQLh4omYh z0@eVy0*pN%ptazq;zPYF4;}~$0u^6>%@-pbpc@`+ELEjN@tmI1L9f7;RRN#+)K(CX zYC#8`v+^8fa=6$nV3>{t!h-5`g>l6IZPmhJby^2kfTk9uALJSgef`5xSCye&9db%9 zI?$RH2&<|CusMO70B-?`uBpERlCRR+AFjXdy6_o+p{I06H#a>6!!RQN9zY?yPRPQ- z^7IB4QwlTB2UJY9W~ z7`gb1Fi66@uFvgypJEW{U@P7QSd4b^wzz)b3$Zu z#3pE^u0DlMHF6S1`q6O0Ff=>elUxItlaxsd&4jm4D)n)rw%k{BCXNI8cgHAW{-u6* z)p#&US-p<((=;?q>V1pfG^(>XXPq@srwP-@sslBbmc(kJ?kwR}%-DffmZ=WD0A z9bS>iXE*W29EXA1DPKqF;Pw1~(C|(Bhz5VR(=4~30EGmJqW(8mmEydRk~>d}L`GQx zYcA`cKc}o~?{)w}qkpxWfnAflNT{;Cmq!)-Mq2_?RB3Yk}<& zn4_k8fW_mBKLQ*JKO6S#-XD5<^a4_KK?e*gTFa|ytEQK$wA*0&r!g7Snpj;_+j^0y zM=v~WAKw;l8%tU<*@K86?kfNjFH62v(WPZUeFO-t>#wT4#4-w z>2l~g&Uc#7yz@NAP4BRrPnt4&mpi|l&gsmPH4U&Z_g6d9Ii!rZL+2CX@~|AI4&DGQ zLco87E+ga+60jC!d45ix^T_Mx^0@u7Tv5={AL~9|&n!T41ut&Cse3WsV6~XgAIs=; zsxBV!zjiM5aWU^aq>TEhfdpRUcQQalz?SF%Z-813gueOanFJ_vtxU8BjN1 zS-{E$Kd>jl8_Wq{4-hBy0qg=;1n+m1ZaggEPzxasnccud#lPhLhH zJNQ{%`T}1(^wt{ySoDTRht@A3Xh7ZQ5sy9yJ;rW>5T31^`{S{O2L9GNAbsYh!O-p( z_3+jmaq1ahOx)u_+sNd3<$D5cQ3emnm=k#7cz9Y5=FK&QK9~!hBjiB~FUHg$f94T> zbaXWGr5$vQTn3L?UbjUE4KH2r{E9m8B(&UdEbHUyKJY@vfcDqW`Z}>r9YTwv4YxyE zc^ui`PaQ(akr8=44+!Zq;8*JzIz08zgWGi6*Dz_~PCLx&AtUKLjET~ps0Zaabg^Y2 z?e@@}+s#ADb8k7!%c12V?YP5MG&!Bi^DwWQ$8#FXiR`&YUK}rtR<+M(%ovA!EErRd zBmAl3FpraGpXWP{3~rligZbr9yxaWMEKIR*N2m*P78dw zGhBMfC1L+X4PYy4`9J;hzeEt4>$U?zQ~uo#`_AwOzx%@Cp5;2Mv7h^&FNVWg>SgqUBgp< z;g=&Y+>M_L5Slv3{hqhKG3?#5+boI@02iRjN&POk;_`#xii4NNJz7CfkG$k%uZ+O) za=z2I1*o(U5Slh#@VsY-ANk=QaC0$aj(qapKNUfh08G)9D4v9!0fLT zAoOSd`+ve+?sBI>R^&T$%i#zBJazg^*u85RGLxJ(nCH_MiFrXBGRBQt_ri z>EoJTfB#qSS_Ae6sC@kmHww@>8RyKMWPk)(J6=)%%xkwE5So408~^x~;hXP$Pm>p+ z=N>O2w7SOGdtG<^4FMpm-Fnyf?b#OhxHtasE5f&Y^Sv!v5z-%CFra^2SKD+3ze7NF zuEX5|l6!u>@ONGo-u#w#6!prH%Pze*y!&l$2xI!)Rd(nFFz3wdOuWxtu9rRXmo@;M z@&d}e?s4~`Y6l2isG@D;7oPr<@U)-$i8bZ?HsStp!;OdHZ-o8(_eH()f`a$IR4N0Z zS>xXIXRmLX!_a;4nrp-7KL5pVTtMNA4_p-QU4T~YSeKa3c3TAqyHbnL5dqTA9c#!> z|J*O-Sw)=vATM;~x}xyqfB47YRj+w{LAPF{1B6~rJDsxITLZ6pMs9(?C zOi%!;AB(pBn`3D3V@ehJ-i+q9u*L3TNspO$1wq*_w2n$)}hD4z>r3{e_7yX0he~{67Z-; z4>Pt4R3)IVz$}XbAq|ExfqtK%ZpV3ox0VZipHiUz}l)F>URlfwJ0mgvM(sP zWK~Dt9jr2*IC415O`Vl>#({XKIJ+QAKz+kuerZ*fo^_}spmLAe>c+Cof}~U$erOR; z7lvu8Dyvp?xFx;z_NlFIwITr5lE6P$z3k~3kk`RE77zuby4UoyH^%Oxr(xn-SW& zH|PB}xJ!;W)$?|6;k)C4= zyX0K`bzes=)&u1ufcjJbSLq*lcw8OWTIY&xd{0U`NK}mZW}Lak7D}DxzGE&}+)S>K zlhVGorBo9TI+DVfNa}q&2vVH+_|ecF+QdqK%|9bjp6kixMBa3TG_FK=O6J%sBcAswsRUX{sj;L? zUP>X)Jxv@^z4NyS-P|rbTRZL>j1^;6)}{6YaemQP_*p_ieDgI#9{no2K3TCF(i(}y zWaeVDDkw|Mqr-z*lLh7wIJIBk2|z~tFb5QlMz-rganG=%6S{e9K)@f-cMF6$pmltB zMBr$BCzqmFiuyv_RtZ5MS5hJ=0vn!$aTCDzX~9(QdzuK#lKpt3yt{@ zulXpI=pt~hOApb9+u4jBI74TuGweNhF)*%o+M^|xt_td)_nNFbvme8P^SmDVVkw-DA9QP8u$O~JZACA@2^in4 z7yDN9)e2Uq2?2Ko_0rs#vom@*Zky)ULRefqt36>~d@-z#7t10r9FQ0Dpb{T|Eo(l_ z&Yjl$8`t(D@gEboz9!)O)akRDXWOOE-J!Nr2_G2$mb%PaE4a`H*#5m0_Z%G{^wydT zEu?+Qow$GNl8tLnGeMr`afc$0lg{b#biBH`4ans*d7QE`Kk{%nT^?^$<^#}jS)PW6 z`Q&lal*>#5Z+r5HyDSg${02`zbg4dv9e9JZoHlQR8_72>$4#5k@JZl2%j5P4H|wnT za+voi=fz$V?{dox4LtCy>yDETEzWs_IQP%xfE_pt1)v6C(fuWlw1LoAI|e|E^#BTJm|qZBPd)i#&ej?+#uiAGIil$5Hxcf;JYnDTi@st&z!&`EB&^o zUCRbfUjyXjddumUQ_Nv#?CGcDggDnn7UZ@}w2d63p@oie@{kd*s{zsI*z=kGyKZWW zHe*wfk7Y>r+vfXso@YAC=`e9x``6>+&=kn*@qoW|mxpeb-%WmTC&`|4XC0ZRWhsZ{ z@^)$G6Pkzf%4z54^5${V(?{!_G0NwV<%br%TDRpm<@Sv-=o|HDo9n~ZS`LJ!uIGjC zk-knmF3?n`-~$gQi1 ztt~m$aIws12SDfH-}e|N&nx`tC;wRZ#h-s_QTHD{{LkTMe(qUC+7YZY|K_hfJAB{w zJlt6uhFIMExnKGf?X~xW-~FxMDCpM%NkW7b*5Ch~7qkSI7EDSJK%UQ*W$X{U?;TCR z?h65grm1`1>mK3HuKuIqK3Zx%CZF)+r`;wXG)w^0zEBppzw?3L-l~bVc>uY7{e>?H zANczZx22)rd;x0I-3$;KK;c{8_}Xx{yWW{98#+Ls&-#_;hu6vir>#wYEdimie93k8 zd%yjBf$tA&*dGX3J753Cw}h9z{EyT1q`ql7&Z@XUroNBkxHGX@x#qXIXJoZuHXP)xJ zmSAPe+%DV*2u(e#)BeBTdr|m$f#x^s0NDb1{`sdpCH&y`J))@A0YVq5SU2+h-}_zB zqI@d=`g#@lLI75-r}SGocK~4j{4G~Ey-bjom*b!O_fLm6{OMc6YhLlvqG+oCp%EBR zGjs1zKlsQ3^j~yj6Ope35SnJc>!A-0FVo9Vei30KQQq?QKaZg8Xa3yJ6r^P!G+)1X z{j2}qy6bmQIg9X;#G@Yf6XDh)N3-0oO!TQg^`!8Or~gzF^XLBhi^8A(#a}h$e1LRBYPQLpMFF zYYT*~iQFEzFD3!GWEyz@ffA&HyyS!(kt;5(7}w+0R2cIUk6wX9A}3^t|C%}1D@cA0 zoXn4qhxe2cH(#Y}!MOl(CfY__>TK4jfhHg{^~|pxFWTW?EDA({9KAtieC(k@J#_98 z5IXWuUhDw<*CDAvQL&$t83@hTxQ~S9mfGqTSPl-Px^xiGr^Atvv2j_091+-QB1~-G ztpltbVaKkaFf!T`wrw9&xq!g3*j!x}AWEPWtoriFd8|No&5uPKkKoQ>dTBcJ4hiHm zEYQ=+V(8TabJ_nBu&FAGisQ1hyd35PYFfZ5w2(L5;;|%v)1rV(jP-zi1dVj-fOb}& zv=<trun{!;!-`%c$g#EKb+L@Ys$B zgg$jvhm`aBM5hh{Rs@Q!sjY66^X8nM=7%o*n5-#W=D<%D&R16XjJtqi0&`Uahz3|l zKUW1*stLSRQGb`!EI-z^2^2IW@Kz6CBlYL>sgnXiFU8NgaEOIv%VW1537`ItWD$Bw zZ{e@1@2ff(!kXr)z*CIQVr{BELJHP(vf3DHFmiP-`Qm&5?I>pPnq8GVascGh8H2_; zq9N1OlCA+bG_HYIq0OIG58zvp7W2AgX+4u3>ktuH-G?|Ene%m!U+j})FZfYMK3c#< zW_&#_hJKNup%<NR?1J~?D9Gd zHR^Lx(Q|g`{#L3M=S`NU`P0x6@+6rW_xttwk>(D7!UT#06hI#RH!s>s*Hr2&b4`-T zb6C9AwaSAEe(SrnV}u;s4|3fzgV1v`uc+qcETtey^DY&kQ3H}qocE1(tj&C;!YB2) z0feSLy63ud9r9W^>T|!!=^Q6?9BK0_$+BfU>*HUZ8)TzD?tzrWF@m$w4eqp*6xRfV zj&sQOmquG@JQ97>WtGw;P%>7^0O0b4hAzF-)T_0%NBe*!?GIKJr+jr;V;fbYxTbTpiq*tv?L7p< zke^zZ6>z&6PMy|zD`0d*^{@ba!;QCw#U(5-%3}1~ayW5nF7iF8bvf;Kw8m>)V3g7v zkn-e~k{YGTlqRp3C-J}^FkDyIKA{7DSuviFKE_6e!!`kVcW&30A%^UG=_Jw}!?-pj}L%*y~S9Cv9Q{f{!A6S=pYXukj06YE8(wJ!t0_5JY z2)(uDLs{CVe!chQ%@=T5OUl$~+}Gwda?16bb_iu2cTLZ$a=B?8nm$hxH)zV`>+yl! zKBsrwW#$WSgU}klt45oqhX(Jq^ZL{SoRw&>mYHaCz6NiRXP#~^r*ocZ2+!47-{sJJ znt1C5%{l~#&45Gpp9bTRmjm3)6FJR?yqF(v_ACJj=tf9BKr}o6wH&Ny@Ff6KJV0W+ zEf!OUwsE;09C!P9xyzhK8adL~G^}(3q6273hzBSN=om}T2M!#F;A6`9-Hi_L?k9(| zjHmk*fv5r|TYiTImQoKnT%SD>bqUF{j)@~H`~i^yRz;q@d-oRCfB~P@9c2d(9*ljV z&*sI8MZI;9t#yIS$T6>jzInYI#dyHa`k_4oWa+z|#~KUdNHgEIHWfKSUxd+;&Pl(}Hg zrvdJ?4Nvo7eghH*RFCCs(u}p+Wlr$b6N5;R7yihPCr-Q2BQtXePrq^GJ0wmSx+u2nqGgRY!*-3`k$C;5+@$ehcKuHcJo9vk%T z`Oa98PdR#rPkfY3=lTlMdS{vEkh^|00D{{_eLwJt@u6U!QT-c|09oza`>K7rkl}ATkn4F`@<_= z{U_0aBY?GY0YbwMtE^9c;^QLl8tawq9M(Et_KH`BkN(RiBFTsU?k~O~Kxmkw`xn39 z*JK%Ve@k&L1Q6PcANrl&5q|gw9vMO5tcmR$R)PQe@BThq{ie4?tCsEPoPRFhTi0>8 z86Y&Y>?0oYsP79;|LG^U1+z2H-uKrZ2rqc?OSSi&Z30<;tpT9{H?ju-B>V#ctPW_; z+sa{x=bu0Nae*V>)&z)eMN8hfj>Sd$_J-e-#q9^&zrA4xz|Sv!>C3}^efEFi+`-DT z-9|uY)A1t0k3a4);r{o#Z(A_pw0iWF{2k={JY>GV@-?s1J@>7$27ia}K7B2~ZYu$yE%P0&I2fM& z%%2V4rt6*GX&X7d{_qjq=YHq+U!i9vlP$^5_1;!ya>eDBg=hW3)5C+lH63IDCg*+F;(S=K#qwPu}!rZ;w{v z*Q32qWsJk$zW40~JAO~!_W|Fv?z;ZH-~BMXH1?ZCoiFPP0T2D&&A-Uf0YVq5>qNc= zG*CRb=>Va>21esHh|mE-uT|dlZ+vb9r1$}wAH2nbiTVR%@@f&SLjC%QTR})xx`P9EBe6YxfU+^D9|lC; z@N78htaTf=NuBOW0(PO7#D@pYiJKlFHy&&Y6q0Dt!*)M_Xv&k!GLkAs+sI33Z;*I` z?<5$O_(#YSeME!wTt0%SbT~=X$WOc?VAQ&x00(_U7YX1ZFs}5~+czXj$SYyzzMbK~ zr5A;hI#}AZ=VAevIP}{QuDqi@cQ2p{2SCHaBid+k2+3iEJ{2nKj@<$?@tJ$UUu4-? zhloAm-={+%jSq)@)dd}z2rMI8Az`3L;2J$F9~5Y4TA*e2Z;Olbp+|H>`q6qu8?*(1 zi2L+|XHkbK0B`#HD`8AlD7ys;>eA=s0pCo`RCOpk5O(d}8!F3Fl0yfKk`X^WeKs6E zbW60tQ|Sg&C2Nn8Z%P&`*#PnYK0f%@!{vDar&a~T8X6oGz)71d>27xZ4CpU`qjgw} zWy?W*LRl6tD*(8p;AQcu%F1+gwJ+=xhz#IQMJS~~(X0q$Hmy(IpAqN^&{V%Ha-KST zbNu}L(OV9OfBX0+Wclz+1Z39)n&!a*KdNf-2C&CrTIWxkM{%Beo^a4vp9gVlRk@f4 zj+oYrN#l5=?s&>+`_};1wgjo5xL<5QmxMG?{Q`0_hV{HU&@UCGek8Ca*Nd+iN}1O< z>X{$cMxIuQiz02iKh1U8Q8oGiJ+dX4y1N7>t&b6N23HFU@o!A5^QWSIq&h&c8~v-r ze$XGrS`?8#{b_W__n4f0UY=z1csqoeID9v9WxeD)sGG@Be?g|vW=>1ov^mcdPxCp? zhc|U{9#p+oIGo@A{XII-N%T&LXo(VSFo+g{MDGOAMGZ6Bh%yqL#OS?5@6k)5XE38q z^v)o<(aGcU{T=+T=it7seQ@tNoO|!}UhB2i7YJe76PVc}pKD)$;83eecF5@KwN?GL z8Y9C^+VV;E{`6}n+lrwrjFpJfB>&vet1CdW)*SXaM4N^An8ho^>(j>|q?73YI@_!` z4Ba@Hwz?A`w8d}#_${=}bG9w}7k*~7gH)GbOzYI|asTp<$v>tVW{ZIfloRQ3QqL;` zyI#`pf7d7Om*=>ANp2h=k#U{akv~?1Wp2$Cc_1#s!l=sF3@Z%6U*jcdrQdbVi#zsN zP&1)2UMyg?r`N#uP=2~pg7r`lVI}Fws}>}_C{vFIA!u>U%(<+0FiP&v4cbV8@O=W~g5dbjNObc@qtnL^&LDp!1aKQL>>}~LPVokBOx%1egY@QR zQE@RtJGm9gIlv$-Yy;)^U7SvJm2(~TP-!`%TD1f`!g2NTCx%KiZ3Y;otc+&L>8<0q7QV*A3`<5vAyH)u^Lp>o zP7;DwD?mu=Sk^BeX*CPYO9?U71MgcxB@_wN&ABV)Q8g;3?uHSD<7lOe9-$ z)_1N@?&H^F1&Puv_H;>O2f{)vd68B(dVkna@72-So@|2-Q%tS~+Ar$H-`|YRuEtyX z_Wh!0KiVoJsQDh?`G7;*E7#9I-z5yb0vknD;&O5sh(@S-j2p)yerDN93k zv^(<*S^of+xYMi>;U>V!c}1)i6DCcu%zpc9dNB07QNyDBXWvG{7QokQrbuHC$#iaT z^&%I3Hgmw~?W%Sj=58VBJ^`NR_Bh#5oYKF8tMcVUt_8TE5o@(yaE z0#UzS(UUosf&2{zefd{a{e!iQYQ#02$ie5leP96(REam+#*P+i$#Cy{3|Q>ALrC^F zdQJ?#P#o;s&)C0=wK>?gc!O*Rx#{H(`nGS^aCI?*3<{<-@08*Bi#UL6$*O4nHrBID ztoo;j=zi zd&r)1r`4e4JX@_FB}{4g(W%)y+aWJmZ{kSi;?IBrSg{%=m+pOj)8Dqsv_yM`k?i}N zTp}KfhKX1N+%l1tLXQ9&GjeKTMFNjBw|eUI99YR~ayr_4 zMuQl`fbGj-1@$?$GHB`I-ILU5($mEq!Rkk5mc1<#Xp2Xw>=nKh(rC+n8&c<#2nLHz zHFtv$fz6|g=uS(oqdR|Or?Hiv1?tjxtyPK{ojKPdQ->W0+W##;5vl2eoGXC0Q<7Y- zdRl9ZqQ`Xhv;JD04gKjp+oSc2iQj%qut|pI4@i&Ob<8aYozubV(`%-nx;oRlGRiNy z|4XYhtPTl-q9D13i@;u@b@_{Ny#>3Y=hZnBAGtp9yjSkQTV^39$1};Ndct$B(yCJ~ z-t#V}ZIlRR#;Lg^Lh*}ya6=0DMu8AQ$1H!dSD3f2w>kroStN|G2CB}AeA zYBHPgPEBlxvtUS+Q&vB4Y6oXNJe+#@>y8?$TG|Y14QB^M*s#y;`P(PgnxoF3FEp`fyXIiLh9~!^SsqUTDEbs| z;sMk*rC}(|hq21dhX2G9NC+ygBa{A)?0)d1Q=b;22U@+*wd6==3oU{;%Y6SjHOMGO zh6YEnwGMu%?-unY6|0kyqq!o8Gof)LU7WHvv7=jN@;E$B0vX{Ry-bJ$6nEfy2@Sqm zPLdB$c*X%et*cN)TyX%$Xh7?aS$}BhAR`Ha>R4x5^*=xqi2ysy-l58=VCeMt{n;I) zaLj#WE=%-aKzly_jD9!Q9jD!X3Uc4AT*QO(I|;j+{iTAD^v?+I*IHbZ#8X5>ivS#>2W@b*KuUH~l= z!H-)c`Pi`|wsMS4b3VOe&xsthRI6lT&! zNlad1cmfT)a9>YwU6b#A92%h~xSeZ|**=-mD|zHT?C^W9LbK$9t#Q{u6_NnFgSMaE zBcz%YrT)mA1XXGik@am!P#;cvGP;)2~CZjV_Va; zHn69Li*eKRTtv~t6{P1ygwne|$O z)b_OOvL}A(!HetzBzZpz0@?@gYec%O0LZbo`=b^%@z94*l_9+F2SUK(vytQ%wJ*s4 z@Xlqone;m*DJ=!EMW3bN_!{%b3gs~6mEYx6WJZ=?dmQr!VR=ndHhx0RHSr*_+hDdZ zevrarnoiHQ%a^>i8W1zWu(^iY4X>?vWPgg=%w*z0D9I%-~SxKGRg9L6`D0y6lW_z}!3BAM!2jWm;7r-{jx#XSW`70R~*0jMHhxCndC!cg+Vbq!6 z6kvmF;=6goibkH9>wVSp(??DKU z*2qEe-=LIntttD?ge3Ps$*|tN`4FXn1tZ770yp5=3Rpv($!fX@0qop_X-O&B)o2Ym z#2aAoBeespCI-IDu%GZEj)3AJKDJao6yd6bhz-bLooo0s$)(isUlu>k4%l(|)T-x;-cb25BKp2=2D>o1rvNj9KL9LK2 zZZR!G4(Dsg4m&EVh6^%BFPj7ew*Cvt314n0k%mmr&dM&?r}TJFGT!V*5e3em@tmk%H*#1prwSL|K5D^>)Ins&Zpp`pR!|t7=%S)J~j5sw#F+iz@1pe2a4sK}37yrPK8{s{PnhE;_VSZj16u25{ zuu`Wfk>S0Dx4Bs{T}rI3bsO*YvQ|jMro#d!$dTxFgHlX`9-QBI%%;wOmq(H;{5{t9 zkDav2i} z3mMTLdSCHY$^;I|l!b8$e5`?m%D>;R_S@_cr`xkGds0zwFfBWLz*jnt_zf~jEgy{> zN)tPR<~4C?3Vi$NNNpOASo>)e5AA{45#k4yl7R4Xh*OjNr-&ozP_L%>FHdjk1XYnE z+AtMX08RxH-Qjzc6#fziALwJiXm1o~I$iydNdzIZm-9L0COy4fmgB4Gy!QnDgx%a= z`qS;1$2jHXxHi=l0QIkn_Cqwe;!r`5ohCGw;NcG3^)Sw)J*ip6bf1rjN)lZLHyMEHJ-JLyyj=D$A!ygdW+?q2abPdLOH zP54^Nt>1pk`D&CD;C=jUP6+>rN?;|;>Ns{L0V%U(x=2=IVANv#cpGPEIy8P>?41He zXJ=~~SE+z`H|klucgTr9zrMl*!x(aY1ABaP60@6KQ@ge(bSY?Akqe==ivk{cSRDuR zjK)A_;tovi+gU+?|0pTgFIL>}a!P=p&1igjMlCV9-zG83?p2+X3U^BFVD7lv$3@EZ z7*h+gN~ENaUBSn^axJZ$O}I$ogI3k4l;=IBC%+6u{rWC>JDnwe4CF|$VS)Wc*>L|U zf*3TXbXqrRI;juYAab1fEcU>nte8GAslZ5T6UXPCZl~)t0pysJf{fy3j``PztlEpJ zrusRZ%Ike?ETM$%K&QJ+nj@pn+$YSA=}DTObL3VCg7Bo?v7*x@cxDqrbgt~vj5au8qj{o2m&*Ob z2ujl--fQ&mW#xvpz(XiUWr?fb)7dtx^TNwYXg#;JsR%*sSx%N5E8Qmj>8k!?{jJ6U zDqUj(0_Un%FDh4X4Md!SvK}t1r)gA{;6gE^d|3Bh1*{eT3lYY90t9h&_be1 zrN|0?mnGeAmM)N$&}y6E2fZEb92}>w)d*1O^iMM2b!97mO6zC&a8U2foygUmn5+V$ z7`NlsKabkIN|<8ZvZo@JGf9h?zG&ccB2?tdCB0_te2a4t=v&0ZE51pJJ9aqrAe9`W za&I>K2-B-G#mh~XqjLMpU?1qeLMreHxA3$qxWTzvnp6M!LMkN!KV?GR4Q!CIHL2YN zUG1n#Ux@H^4Bdz0&oderkKOGIuGm6;y2CeNRaE4EW6m69e;g!JJPxZ!`7l@9k$;wX zVC8Q7^vzg`=ly_i&O5ZGxOT5?X{{+nSmsmJRCj$RxMFY^T>!MCn&i&L+Xx)rfM~;e zycRMYv@-_gjwFeHbChICV!he4WyN)Nj%8y5Pq?+SJDlDb6Is&wWr-qHgK-fX%g;`H zFh7RlPa(o+BQ~V{pYOrtFT5?lgvr#nG2-O6eG_~v?IQ@_U|6-{ zx5IARpY#WTvw3nXG6nL1BNKIR_C0a7ithoAmKR2X@-=b%yA1DP=;MJT5LFPZWh?^w~CZtMUOrt=5h_Dg%PSr({T% zL2)tz)Z#@%9v-rAvE#v8K2-h!#y3x3K1%@^*sq|Zk%uZv#5;QmGSdy+iVj0# z1^1D}@E@I#8uu=v#xU=Nsjeh8pRk(5Xv*D(J4b$6CBO${7|)LoV$#$nEi!|e))VXB zMUcu691xedipKW~BH*{lD{bgcT;j@fUyd}km9iJU8zcDyRIQIb0N!MHl6=oh<;yB0 zO5s=VjFO|GVydB`e7dGQ(h91Do3Je>6bhV1>X_G7^^^?LGBCv%b5@6+1&Ok4U3-DF=ke)hV!{14%s~sc zW4mu!f;|iflBhXM*T!X0w2ERZ{z9IhBINJU9!=}AnHI(%Lt8a`$Oux4R99RmA(4Wb z2#4mB*l~Ev(RaCs=r7bilE(<2es|?x*(Tm{$I&mf;W;Vtzp!XFlq?gfxL zP0ySzAHP*T@IqJ0`>!ERzFpSal;}7X8J4oTFHyFCcedo6=A8ldk{>^fMt`4b7TpIN z5T~*BdaJRTr%UkLRXt~a;ZggW7t>q35Ozs!>Zqrc;ZDz)q+{(-Vlm}Y$a*eelkS~} z1bPLN%a7EWr{G)usNfGrZ$c}7J$MDVcpSxM1N1m)T%aQ!3HomG^sUQ4!4wdh1g=jk zU~jRUo!~3~(*l}KJYgAk@7TMNlN!owvNwh8%`NzRRxH{zw2nRYeL3eJtN9S^gs^KR zRId8L0zylU0?zptmUj1$;j9UMRzM%<9!josJmO`e9jC5$;(7xVDHXUOF$W)(|eu4I{{$x{^ z3T;+3q?btc*|mAign~2jo;o#AckoOWRX=sjVMt>Cyn$znyH5PIRS%FMKgBv`BLOn# zJbU)ECYFqjR98qh8Z>~1hs!BK>R8kW@qcMA0QEgxO`f&*hFyDf8G4sT?6vH{l0fL< z$DXrjs8E1?5t?TrLUctSNc9$M0^0a8J%_U=4dL-1hgR8H8c2yOpAG-AYw#J8Y2zV9 z&I)7djU4cy)96R~eumd!j6>z;iN7)h-(>?oz6BCcO+{?7cQBJ*}$MGRl$AeA@ExRZdcy*>VCWPLA{-J3BkAaiFx8x(?jZOM~It z=nsKvoq#+X_xbYKHsWRG1IBNq#NpZ5=ENo1S}@vy4V_W-$U6^bFX7CzF(a|U3czdr=C#DHbG{aMfPxJIns7Qi2(3d! zyiT3j#l&Q3&jXBu_i3ALK-ax&9mA0Zj{Tih(1ZO4*Kdy|t`o+kWDwH6S)tmFY5#M8@{e}r~(V3Z5F(sKo{ zlW&J(wR{a2EIN2PLcaUVoa68P*!yfCgqtJ;JNME3WnJ;SH}q3rC1R~=z1<7r^-Bug zywMw=y-E@!Kp8ZO5T9o@+i085+h(a65Lx`tM{oU2F-uw<0bG8aDcU~gK))Z|0o$nRs3MdKTOMiEr`dJ1mZz;|zh`XcSZEpMNZ^~CX|1w|bC?V7w(}V=-){i%i+p3iPX-ilG z>}o3pQv#0jxRLjiXLzDl=A~53TK}J+I^xintQT|}4{)?l+)P(uRh6i(M)MN^pi*&qLLd~iPbI92TA$GE9ZltTRgU}5 zs`QABopiNtx=t6j1Vt9cpXY~5?XFOCPADordfgq0SMrs9SFM|lvZ=O05UF6G4vUrP z1(1=yc0+Z1u|Iv@s1wb&{1o@xQB!`Wh>g!e%EWGxZ&5(b*kX|%FbwUMzg;PlWsAwt zWL98qCHt;UxoL#|Qgtn` zKO3(kR9-%w^a%@2YfqY9vJ4r9GEBzUd|EkJpMVNt2-=<~A&5$v!r0@~JVi`Aoyd!^ zvq~NKT~G0u$5zss2d72?@P?4W4G=N1TSG$i5U?G*UGOyB;Hb0Z{JX%Y-RAs*5)nD(t#J*kGFX_q_?suvP4DayWB1%$xb)fWf0o1=J+rqm6n9V zg6vI3RGd62vVGv2)LJ~z=C@7U>WAX87>{hC(qJQ-8S!t6(_NQ&BW@dgEIMr3`y%y= zw|??A`{M=-zMLSV{TCuR*q3{mYQo9VW-rEj&4!vxIKDaFsILJ5av4q0uc{mtPYX zW4v#%PRuTDVZsM#-e!1t=pSz;g&vvgs2X$WDj(T%Nq(pL@-)R$vuY}}iBL(5=sufk z>HtoR-X+m+`swvdE%iYCyNeNBi05bCg=ppmRNt!lN@|a|)g+T!`m;|(&3xj`)-z4{ zm&HYTR{gr>0h}JqM<8<-S}XTIjb^*8!-!o$Q1fn6f9L7*VtUvWfidgY z>|=~_!zNHvrmE3Z9q{KKhKF)8`OHSGYiNWi6I3X_-4`Bn-rKnA&(1A_7t%;+NINgV zfk6XIJ}SAGFM`UpEyh$P3vrFRW`>>J-M4Z*NmjX@9hnW!6ohI7r;q7+UY&ngHRaoa z<8zrjw1$YYNPm3Fq9FE2TL($9T=B6%ScEt?=cG&g0Wl< z&|hEgoyVI%4;4H6CeTW`eNESQOHk=WFe|-DCC8Vm7=nM_4w0lL!FP}x!blJ`Wl&UMJ4#u-}IkIg)WA8*<7Wm?I$^xInJTUJ;5P=Gb@L3Mf?YI|s zfC{T?G0;JK_zUr;*8RWRcZeH=bg!**02h!Jw~t=Df9KkiZzxEfO|i@WSo;h%YSOy- zPtqs;wnoDlPb=ty1T}H!59H1U781G5P#cFf`c0niP zYNGb`Kk(PH=dGTyC}w{`DO!LCzyeh6-UE=h(mk7O3jQ5bGQ82C)^!5JkXlS`y~brd zd+;?4)IkWxr6MGD<`4&s9eGwL@`180^JV>4X$C1>TEuFtBp3Z{@q3F~#>$WJZ}6U_ z2jIO-B)I*>Y|)KeBMt!-5Q)e#2+R7LNckUHPd53IG(XC@O0M9=!{wo*dS;l&D1w<$ zLsj3$%)~!gt!T=vThDvnj?1rwo?qm0Prrq(`tPjfMyPoWuWW+VyS&iCdx5Y?8=w;m zXxBTD;spFL2x3ob0(933Y7gH0QdIkQ1o(Y4YyoWL%lXKlr({JrIdVOa`U_Dt4S&fr67!!Z&octR>SQQ;*Ju zSkjLBrTm$41Ch|}`%W=FfRdHZn9A4#8Gz?W;er2;@191+?1)Usn*}1DQ2WitBVZ)+ zY-F~0dqUceN{3a#7+SR#r&jKBbOU1qt%aG*%2%)FTX`ESSzCv5jmIawJHf^W?h~y- zO0hPVDva@Pdr^^iW^bYo3o_(7j$Q|6CpG5UOj|Wt86~VD6PrMU=haGQu9587MawtW ztDhHRl;&yi1K}-+NZRqu1DR=+yscLE-%guEi>Jdy=1mxeG~&FUV=vY$JFELTJ)@n? z-4pKu@0!^+TGyMrHf}y*OU;TUy6z)l3vr{D;TtlA2yi84xZu&A_rFb5dcXh2Fv#Wh z`tRoNBVLn7cvp>=_n*l@s%ps`c(6EF%XfV=Ajb>bWz-Q+pCOe$hUHLIb?hTlEZgqY zenVMCnalrn{!aqIV;+!;xy?NLut_UYY1AwTF>2 zDZgIJvEc|hZ;#y?^__)O4FXKpFf>HNwreaLwx6B!iMV^}R=Jt#uqRUnw4MwCP(WYOAWL zt|{uk1*y-5@_B+xO%v{KkDdvS*w1Wl?NsPW`Fh#`1Ij(NxUNF5PJ^I)%M@Z{wmjpe z13`Nd!Iq+l@?RS3ax)kS09%f$g~TNIgRGwk>Q@68k_ldK(&uDV|DLtW0VzUr2%l;~ zE~@bWa)RX`2GcXMynk2QyA2wp3EE&pd>?iT?5^Cw74PP!MAsP+3Iv*f% zYNuX=NNFK9A_Q4)Bz#QJ%z=_Vl^2yp{Ak6Ftnp?y;@&3t48YLdoGW<5)%mqkpV+~N zMS8~tcC==}rv5G!N5g>R)Ol8S-fm@3;?Kt;HUiz!^)IAh>SmTr>6Z^rg*Fv6vla=1 zE6u79vsBVm0+%&vAcyGRv3D;X7&Z29czIVg&URsbRU6=YQo0cZ3n=JF!3}+HSx45BBQb!AQ(^{85HSve{rb?FWuv?5W*Z1bk%i#k0|n<|l05JcdFwe+}t5;PcQOss-Q( zeaWkq;jqLVrXZfLN$>RNMrZ@vjC>D1U(@2a7!|_V@@kIShZ8#Aak}(DYCmIHOescS zS6I=cX<;bJMkSX4^b@yhbVS=}FMGmtl>R9`U_ASirwrsYTwWx^+$#T1fv>NG)`-x~ z;{v@pe7Rf^5n}T?siGf^XD(~qLhf%w-f&8a*dHl9vPuC|bhLiIjqGHhKBs5;%P>8V zZV}D86nOY;8`!U;8a>6=z1}mv>+z@d1J7Y;*O*OcF98EPI~%zz?ttq=r<1`|W;T$U zqsj8)IKslao)j1C6R|y02WjimLANKR9HsbbZ-kQC0+7%J=fe$@Bs6vQsF zT^Sj_f06j)+VI*tkFrK?+H+nOgsFVNIz4zjN7?1`+A@3PX!PW`Sy5v&`Wy=RyyO;UTL!nETTc2R*n801%V^MTd40!g&LNd~KW|;f_1R&)ubAk(v z;9KZzif~m~pt~B}RaL#Bt(J7ZdA#-G)eJ!{a)U5BF%pgwQka+~zu|URw|^>b^(-|ylulvrCoDuYN&7p-%utAWJ%vAe?5Ez}UK2dBRNg3C0M_c~yLrgq^#1pk? zBkj)mYYt+=wgRjgd@U_w!)8OmL?zCK_*1NGc@?dKS!ly5nJkEkFT02R+NQiAF5P`4@PxO5eq>C1b0d;cvIu+C9d%ONKhkKO5@I#uWJCR?hLoamQ8w zA{o0_h+|!+2?80s<5@Xd6;+QJ)7d)H-w^#UT^|;)o<<1&U2yPU-j;07Iy2uY zx@94IEgf`f-dGVnofulap2xi_HBxegt-f1(QlD+^4na6(anri34fR}Kd8SjzDA|R> zSY^&75@9LHz%6AL>4a!0`^u}&?nhvY9ha{XqwXEjg~0Q#rj*56z)a`x%HzJ+O)g{| zi+xA>^sT2l`z%hL6DzB6mnVyV+-GXy?R3#u&wFQe-rCm*i157>l= zILpO$w@>81qw)rw}mWST5=x*y3w|x{?BRZvOS2g6jh1Uh6y1|r00X6%Pjl}jQ@1_f)i3u!uY8JTd{aW7$HKUJh^KLa zY9hZyPemMtR9}$U3E`1 z!yvixl43#$1~RGZEE~OyIC%t7Y)s7Y)*EGl+N0W8K%IFAQ%aiQ(k{0w)J^0KSRm^qzwD_6QZ zPBV_=0%YA$D)1tTB809djaG8I{t(u4npU633!=;269%&sB)+?176K3aUDYYSgacZg zvUwb#G$L#HgD#*9}6`;q9mWqqm^}e6x2}Z zx|(8xo2i#^g-O9HP;GxRWIHzK)GKIJeuR3~()@<=m*!NGm-xY2&|{ODSGU%#i4loJ zdFW4yf|dWIVPNY{Ft*Y2Dsk4z?1v?V*Cw0kI7WOsC6n;=D~T(9F%I2szDGgB!i z__i&viomnf%lkuOOI8?K^#(fB|EO%VkUCyM?98QlX?l+iZC@MA5wQWf4`t%{n0b3v z?M!XKy@}11VB-H)88*Le_`3w#KOK)4rn3N_3dQP`h5k4$2X4Ig&C09kZ+(Lfqx3b& z`CWC%WCy4Vun6iX)J``dHlnYgssJhjO8hwz|F9k#r?N4@$8c}m!sE_;owAgXrrde^ z<1%j&r)+FY8jFAbngi+ldCsXh8q_{m&vb_AD`La(fqy=j;iPI1WcwZEtd|+z6*}&8A84M$~USS~uMdSI|#|s;OV`3RCJdf|j>7$we1|-#D!d&`4Ojc24R( z0ze>}uI4{CPqE>8b!Wh8`uG%sb2^;-@(1wA5|z;W>&d)`q9Nj)cdkZQuQyE~6hicx zEH}oauA&iQm@9H|{BA1$3^%%>>#40g-w3z&xU^Mb&56PGa|Wuzz!J*~riAeT!jxZq zL=@@=JvQnA-;NS%pYeAi7qeu4)q&9UVtPCAmJDVI_L#DJWX|4Y-!~6LBJE0RhC6Cs zE#SdkfFU5U{L&omzV>V&0|TXw5{l&tRqd+v6%6BU_ldMb#?bmza_adrdtAK7j9K$*_-e$N9y zUejXu6OEg3HA|D~gA8HP;|-y^rr(U%mZu!8wDRZL4dy6KTA zpaT$1;!P#)2^c3F{DsbyK2Z&6aLTF~1$3$){bjFSTHq1lM2!ENR}#5>Devgv9xd)= z?%DTfj7I$U*+=N*;XaYipe;vkC@O}}FptrU#ri-l;OxQQ-`?~cfx?zjS1*GC#@&0? zTrIdLuN3LJBc;OBWW(MoR!BFkMSZ}$DKEUt8 zh5>&wZP-4&TMKf%B{QMngh2t}aGTGLG*jBjh(p~r?N^e*gq!wJ+>2hugtOJo@vYy3 zL?N76$4Qx}WZ`(cz1ay~(R>%gj;IpC#RMqK#s@o<7?BJfc(Do5YPd*lT9I-?WwTyZ znzscyj+C>Q1~=KT-5+#hJ^LwjT8HDsv6Z$+>fMF*Qqq53f1Xm_19vt+)&5J&;FJ-| zUuZlu&iM<(>d}{9OZ^Jdc{9ci+Op;%UFL?`A0lB+#B)8wwg`2vL)lPC z{VV!`qOB=v5zQzx_mYfvZ#%U8ZH8ClDJYP8cCxCJ z=7XG)VdR`=Dn*Re%!?R+@f1JQRl@;TsCqZahEk^(8Px0IHjc&nlIe0^?&I~68l}Uv zthnRc;5fu7ne&PDp?`}NQRQ4ddqzTpI!>lY*G^K6_j&l_?4z^&Igxt-t(m9ri+K}U zE1r_&_=;0Cn@@a9?1QfjPf(9?npx?Z)#x&PpXgHmQ^W};#1F@vZx;l-{SaSqj7cbf zhn0R2{H0H?v{WN6DUv_~WtKCEH!OH=97Ui7owdl{r3bXp11Mm8GEzUkjMjCV-R!=V z1B}VMN@{d6>7%J>DZ@+QXFVO?Ep54c#(g+lwsT&V>HUeHb@=trTbtL*Ih;XNw-;k; zb$386>!}2P5)ZU=O2yji)W%;u$WG3edbYZ!- z%Hy&`w0JVZ@~oXV8_a7se})RI#^Waq>EE0mvn8H^w!6^P4tKS z7B{*)@DX4uAhw@e4qe@$-@nwppz8ib!p@C=!`;_C^4qXJX%L=IdAwdGJJXzubtkE2 zKKa>3WVFvo5d81-2?w_P`!w$_9MO~AK$hE|V>y#0sb6mMxJSz;`oKHD*4CkGel1P+ zJw+N2=JgYuKn5%}>r%=*$5ie1bt5!5!zh12*Fl5iJYtBy?$9A3IgeaSgI_jcS0Y``};PGeCGt%E8*75&HZ;peb= zXnKVGBWR%xhhyjRv*N~zEUp(B)(~5A#pdiKmVEe=m zaDPoWuKtNZSbeesf%+SZ%7tGdy;w+v(XPpB!*yp;TrHA>iktl^#m1f|H6l3T5eM*> zg^d&A%RWX8w9(VK1p4EP6{H-Jfdp{`7wuf92kjOAMv=HN{cj}r1uavt0 z{R8;EIs?avh+L zqNhyu*lCDcpHfLQN7yeKz9o%y(dMS5eIgh8{CR)q-cWA$rfmT?ZV}miRfQ^djo&-h zjOk;le*4Bcs{oi{s43m#KzeuC8|AvdAVeiJ6d(G=N@wT_TXFWR&X2FUt93M?zWk3L zgzfv5xH()o5d-j8YuMG3dz!zCAO2pUp9RM}m-Ee(IE>sF0LVHc6u{-z$1h84bPuf! z5YIC#D$zV+1>wxv;s7bHk|MjscUY_zFxzy09>`!_?CmWBH+v2pn||XP({#6Mt}PXT z6&3Cj0zS~W%p`64Rmx?7e#z{;Hc%7yI86BSX9sg!VI9w)eV(|oT@c-)Hzd~TxT zZo|VPh_4f@_|zXt#N+=g*-Fsd-9%JesFA6x{P%)iC-`Ku0GyWY!W36P* zW&?77Cf^L!6$M0X)hePyI`74Or>sZ+u$A6~@T;!sfI``Gcf{3(98P|AqJg}5&@jI?68tNTiT8N!Y+4lQntI(B6-hMZiFY)HXhzCwL)Gw z@l=T)O5Uw1==V9O%rDg+tBchLbd{t<)jz8V9DH3kke*)@>ZuReqMZ$>KJ}Fox59iU z{vjQU7?>^a?SVR!Y;8Dc8vOV==TnGY6W$dC%Y*C9Epooz7YcYlrj+vFNqS!iS8Q+Dvt5A312#Mlz?%+II3CTCeM8ToyaOf7eGJl9I+M@* z8B5rc2E+M5IRA_9EZ#M+o8CcA+Q-yxXQ1^^;x;{CHX{I(1#Nd47|Duzr z(L*;KI?@*tY)ZRvt^UG?N>-d8t9x*rl9@x*lC^%Ah7 z+$ea%=!@SX*r;8vjcl`i!?KBa<_Tqpzil4V%yN8zMFac=u4Re*&WJB9Kxc$m@QRD5 z9U~CWX*L!~@43sjQF6@`MkxeWJ}*%o-|8Fk4(VYwA!e*Egk?I5c=pqY=Ifb-6QYpD zFDTEWg-mT9r9Y1m27DCxcI(y|j!8P3+1Pu~A_2U7s&3VquOol49JX2zFaPBtu~X^i zY?#48GL1he`$<9j7QP#|_O*HwY|&GR1!Nlk`0Cz;3_gS}K%75%LkM@h%!Zy5WHT4E~OzY;6C z>~iWIfOd{J+ICJb3x+XQ-XnrMr6(pI#HTI&QyA3(Z^5tjfJm``csM@*6p5&0Se1w) z^XiNhCV!?`bN5J7g7^eLo%-@RIl&D4akxaW7D-DSf4^EvxNE(TEKVUhjJX0^XHvjv zrA^21Zb>*Ywl$0r3#C-daeR9U1U2iDbVJ!}1s+;A4V1_k`PS4GhKZXFYb=rnOwwhx^e%p%E8?ZNGOw&WbR~+dFqpE-|Q(NewWC;3v*rf{z7GE>_(th1*w3 zxPNOEP50pQ^Y92~w#5&wZr>fSjD|Qh$p4SAw~lK1kN-zE8j(;0q(%!$jE+$QL_j1A zlo1;e0wT?jW(YbJkOrk2=@v$ZbdA>0J(zTi=JNU8`#bk{&pr2?`|s=T_jx}b&*!7a zwiePIa;onYh7l?x^Mk=b@AdDv?I7>1{39%!rIt)VtQBuP$^+}hfYba<|Iz$x;O+ZP z8dNno0Sq9LwcVE2rN1`i-LEeuH7GIwQH%SR9L@T=7*HBhMlU>s#JZ@zBbs#eMBjsM zjGWpS)N$UJ-oL&uF{e>e4e+#V?MH-mrP17JtY?{_zSem<%!I!Q8(rrg;Ou>wE_%w2 zIC>u@;G=o}IWn6xd3QOBLm=n75LbeGVCQ@bhQIlH*moA43I4Sg?Y%zkpRF@>=Kp#h zuzV@}J7V$xsqO7ya{4_&r>nJ<@Q6H&U#7G&)}~Iw5>65Euj}3I9a`b^?o4q>vh2^N zMi$*T+eYh~_cBccvjX>j|6NL7Op4L(P>Airsl)|7C8@wgte3ecdM-O$6yRiX)110$ z#|kYgCwBX;L!b@ZcGIyO3sZcFvXK^n9bi;~n?JcI(G)lWue=y{5}n=7-^q zylyqWCYgE?pX$m4X3)z$`+N91$UuLGh7xdT0H-mq_2Ly1L8@vxZlP6=+=RTC2icEho5%Wh0DUcNll|n|*#K z(jQjJ$#b6w%~F3!*YWS%46HzXY*KYdP8sx$#aad?{%W%|_EvXweda}A{vY2uMk3(f z`dVEY;I41yWr4rHvooUQ4KTiXO-#)3hIU`ABa`ZR%G_`nbFC0+T(dl@^nr-bEMrUk z)F=o%-_=Qx_5~4r{vgwbo)|$6Krn-9_!vg?hfVD%ud+1olzYY>-|%PjWqa507I|r< zVbz65MhjVTAQc6oWufq1+_V|^mz?#-XB7c!7u%h>2pSR#qJc;0{m6|dy5m<53q#9_ zE*84dm<*bS*RW@z{weB>r3!4&H@gP&uJB5WqNjplv`>au(Dp#Z3EI#K3je7w(B2a$EhkCmgIu8vEoB9GF3%X85Ia}GmQYfo(Z zJ|T+d^{#ad17E9)fa-|iR&fm+*LjYr6yM>V4h825QQDhBzo`UWBGCEFTlL0(O{4eZ z`o71}gFQk<-}ebXwNG8C02A%PRfwNh8u~XuEKP3t1d>;oY{b?F4qYXuQ=w?Nm8WXw z03dp`K3c)tqgTbUKQx99_I;;JSG5K#QyJ2i-9?RDccn2!aH-PWPbWA0Dww9cEf=sP z_jT@kVD4rM|3iQXF!dR8+23zRja>*8x)xRoJ(OFlRcS{%WoRSH!*vV@jj8y(>)DO2 zETKwy!=~PgeUyAQ!E@Te-a?5=kR|=p@j!guqKJ(2D>+r~KH21J@5m&1B^NV3@by*| zBWS=I0tSJ+NSlF(7=6|Qn{>%}^MgnJ-I}akOP~3MN-sA`nYSB>@bO2a85v#d{j47k zG*kd@Hd{YtM^KK$ZA~j`CC#vGvL72-A>E~+S zrcdfX>Q>%2YY*?udn;XNd=@7r{-+Y4co@ zBN1!aQ!f(ctbhy$f@yxY4@XMnHy$~Mk#b0)W7sHg2KOD(f;B{IG-_s`Ca1t3o9mR; zj~?}UJrSSW38S{=Jy81Q>ohDyTv*zDIJemT_~7W!@;Soqb$>ejM)|iQ`sMfjA;(Gs zhr32BMG~Wk?$7(iYM#e!qmJnV82wD>i4_FBsv+BO-=T3;GV0LYIAPFc zaAjb{ZAM=M;YFGOoZkPa=&`=LD$6kF<{bbkom{DKKlz>droi>CQeQ(u(UdOUM>zs3 z=ZdILUhhw-0MX!aK3X-)3kxfkS$?3QlNE1o);?6~a6ZzUQhl@;uBc4$b51NmaTD2Q zHqpSbUTLQ65BKh!upcN*g*T^at$DQhu$B<)EAjnS%#NfXzdTFc9RG(D5>4!~|1YG_ z!FF78RorZLzN&f@@#5jtc;LkxbMrp&G5~pTMWiB{1+H>kj&`UX8u&FIU#eb4FcY_C zqIT)n-5wVQW;72pd7azr;&)>f=`Xjrn656aj^&oNLng-uz?CJFam5+V|2M)2rwH(7 z`I%DFAiBuYaNVn=bb&4vrb2 zUop9nvE_YBOD`<5#8V11q5*1sk|_WIpcARrNBh_QAK2l+UQ{=>PZ}1p1pwjkAK7xb z4BM=PLXk*0;O%0l-%60Krcz-*4l5NW0NQIzfmblrLx)PHn01owGMZJ|cH8U=(L_`f zSq4xfgIk(+fFQ^u&-u}3_d#XspO{7 z$d1a}-6D}O#{2hAZG!A34q(TrC>J7)uu?Eo08ik#TeC5v@y0*A z2y{N#w`p4O4oVAc(@qNf=%LLkJo47iIDPgG;Oq%EUN30CXYuS`Qt6n=L0fAZ=HNc} z(ciLK|9yQ_695%>`Im3lGt?GwnSD&Ddg3ZE!t+81T<52>v3?&X&rYQmc<(Fs(gU$L zIB@-O;tjGCykO^}u>0%PHyOdbt;$IW_pLfhx%%@YrKkd2b$~nle{D~HwtVg_T?L=? zIQ)v=Ran_y#)dOWuUfB2CPN*qRQi>@;@u^wjDxciB0DM+o`@XVkQXZs4LmUCFVl(b zw<678YDLc}CG!y!x~4Yl1&4oa>lZ)m?P_$>U7D^7Hp0tYed&@uK6Z zs{_Ea6C3ZicS~;hoC*2z&Kj9%NW-zzWNvp>`Z3BFu{8sw=G5#W#4y`m{Y0Ut&W`~z zW0J%Q^oM-M2mO}}>5qfBGgVo$!X~rlqC{vAz2q+56?&r;hV4UiMX9lT<4nyl1&uUF%sC@~Wa3rWJdID_faPOI|f81ptbW)tvTJ-EW z2sbV!7O8_vipdz*3^z75enB;BNWRxs=Y#K2^-tZZttu`r6QLO>SN=LQaj3@`O;FJ} z+m0$?b)Wksl(k`oN z{ntwHWZ(6})SKju6Wn|%zBSgy0=WEUEcIUgI5`dZm!-qSj!Qsyw2Gk^{coGko5Qmq zx3@KdGAIl3N*#R0+`lo<;7;$K@oo+YkFbj(5G>th=<`q?ZwE&SV6W_iTqt2m&O?y| z@Q6s$OIh?O#|n4+ZcS&m7^p2N5`rd3^;9?*9v{VO;b%S`WGHG-A?gveL*}MGRs*JOi8E3?uP@f)0 znB#nEv7j*4e}KK{75G8m_6gKV2mBj}Wu3shx4C5^X`cdkH^2h(>iNKe1{jtWJ%>-^ z8qr_)oek2``p*cbY;;J>*cB6WxxbIB!plb|)_QDcO-d`7BAUIJUy9H9Uj;1-e^vc+ zYWu9c^v`zEwN)aKiC|0`(qx(S+GP4_YwrB=#bVJ}OtR3>5Kvoz)^$|j#n+L}7fT20 z(t8`TN-3#`%BCI7WTgR*e}c>5rCqM0?7zvwM|m^368c8<67qfoyu^D;34;x!5O~h_ zc98u7G?sPQR{Z-}*SyqqT7d+RLVYOUYc(RcExq~uHXOhOjKq;XqbT|$M-_iTAIZx6 zHSl6GP#F~yODRHgyAe`p~=5yX$+aPSeIMRa1d>tz~G28thbuk zWeceRh+ET_R1PC+IQY^TsJ2voGaNBFx85i0^F_xu_yj|TV9a!{0SaR&kd;?^$*mTq zsGKU6i@WLQZ+3F_7%e%JY1Hs0l&)nIf7VEx4fQ*4Hphgc&Tgs;4sokqTjf|%54apD z$KDoVGq?tFYPoLFUWCwb;yye;&S#+Mp)fB7ExO~;N%@2vJxuVu_f4MKaFCp+Uw>bP zx6-ievSrZ%D;kwPEL!1v)3+&0721qSTlXzeUs{*iOV6TfxLRDj=CmeXqIBw!UKO!EyYDbcCq!P)awQfDO20O@@(tuztwXb z4(=^46+iD=bm*IBz+fqP_M*3%t|Op%*j+dNZO{n47UE%NT%Md-QTXb#yCt|vo4UJl zvWRv3z~!o#r}!}b6{f*YpWv}CK9qbfA|}GGTQ^BWjwjWR@X4*|9=39A1Fh=@!ecw&`MVG zv5a|2=Xz=U>uJG#uXFU(l;B~}>gf&pdA%!6?~jSIpRWT9hX3c9po*pds5?75cgz(T z9N2Vd`17o>tOWc(US#61JC6T5CV(4|jxR-0P+j?5Xhw(wf!;{)LB$j`cTt|MxL)-cr~qK2J0rLm-eAb16B zGj3rK@HnC<)Ph~%&h_l2>vK>8<3#)`IkHRGgoY!qIG*eQ`ySRLz8FAuXal=-76q{J+52rE zuw9uq^pyZvCbf{dePspnF>56W?fv=mwZx9$%RDt-w@*z!DNhS4xG_S8bkNny^(fGv zK1dFLD{IT-Fa3HXMGMmT_0tmwm2ym6+GrDMi&Ywlz;B|%lh(xfe|QDIx?MU+;#KRv%FH+!Tij3WV8bJUd(0eaPg$lIh3WM z7nw_1I%-?-;&3IQ1Bf2HNq!v)sH{;irsz`zKXT$gtMjh~H@Tf>KfHK$FRn1UK>G#5 zE0-IO1#)iNE5#(rKNxG!j(6p;OioaE&|>yR>{G{Mz{_1XHKV6HPXtNqXY&*aAeLe# zO~1jrMzEpsuLH}83&E%dXGmU>Wr2hVk&P#SH@Nx3uVd$$pZIMdC>;~GI7c8w%sxkS z0NJvxL-eS$fSCoa$61$B%*R>k%pWWi&j$OGwI4F)$Ev(I%S>SXS?&~>N;ft{=>y|V zwh5YbmHeC~e4rk>gr;C{n&EnC8Mm`_5<0l4R}z~4H<>PeeeQ@R#cR%;vo zsFG@f_tI~W$;AS9%Zf#y?xoz^ZuO$VpGk0*Kp*!|$|Q#l#cdVr<(?TTLvwQ`(W-cK zaW!0YVZP=!Wn|Bz@?UlNEYa~A>P=zg71{M4N&v<<1k0pP$Igewf&8o!n(~Q+7W;jY(p6Zt$e;{U+5eaN7XH8{F0UbV(pdL-a5CLuM*M3_97Jk zd#mf4BM+GXHb6%TNt!_*fAgC!CJlXwmxBSWwZ8l<{e6q4#Zw(MI1Sanb4`gcYqeMP zXIdoTfDIF@|5p(a5J#coM`#rZiU7|b)%G)bZ%lHON;LRNobwf8rR@0DbWk>CIvmYA zzuU(b$H|1?+U&(01kHxWq`a+upMEAR@^sXyoC43F+8K|F_X(Rx@rBQ5T>pRgu!nU= zM*^E?d^0S_1d}@3T7l3m(~-3w05hMccZjr)bBa{TuHYI$ZWAp8wAJk(sAcl{OXcgs zKzm(P+1wSwFZY>IZi+gFn`zos2AAI-bg=rrjX4dyaQJ!DmHf{6G0_ni{c5ZfO%mX6 zksu;WGW=eq1pC?)@(8T~jAvmvY(wEXbWQU}vgyYrgWZEfAwC&;OZXMtmWMvW#qI?G z55qJLRhd)jM;f6rBdxuAbzLA@%FKY~>c;%D^cl6A{%b8 zNh|O;ko$*$E2isqMwWe!!e#K3P7^^qyzlNjIe-}}IA3aXAv!=)U(^F=zIjSQMtvOS zp+0h-(&dhdF-IrwUKdv&$3%KY7b%r>sU#Ka&QH;G5?=BU>btk$07GEC>p)Ymrk#ku zbIJ-pNwz;l5nI^$5o;{o^JSe-m)Zr+$K`v1ln@=v%^52MfGat+l73ia<9x;pS4bbW z`slIzFc6hS`yqD|A1eEl((h);BRPO!6xS@))jzXTV^`oNV)U9Iiexc~a6C9_-1aZ^ zy1F1{MU;)ui0-kLQSY$Ki~8+$>mWwC@TrlKO6|soNtPnAPr1#&+Gm1pE1T6t+3ehJ zcVtiRae?qRPwcJ}a)T=WDGYUY2TUUlvHaOninL8tp>-}*To*j-{wO*?7CPWsUgOyH zoH?xtKOB0db$WU2r|bx(q$hFFpKImPQpJiPp63y&`MqmxheJzF2XMu#K=$KfUhdu%-#*P*TcsQ)cDfIzc-{qTLSU&KESM9C>gr z2Wt-1an+j+QTi$IK&*VaMY2s!fEPO|u`{ZvCHHLCE)U*4uaGq5oRUa6xf(aR>}nS^ zqcZ6TXIA(rwGmf>8NAL~*@{%M+wu0tgoV)%*c4pi|MJ*l7uLCmw;=bveH+Gjw}Oc$ z@<9ou1Rn3omaG7}>( z%`EDzx#E?h6uvz1^iEUQL~8V@mU5g_CYzKDaz?Dcr1g{fvX+&>b1T$q!}2NE-G=0) z{k^>d3MxlO^MRfJz=%vWR(s}ufst?uHd^Wb2iFlpQIPlGn(J`fh@VWzx#l_uBESqr zGyb5Doq+owj+aooR*B=Tz<^aw-9c{(1tSTIq~HDXydaLmFshS~<)u6HJ6!f&9MAZ5 zP z;Xzn21;smII;_x`mGOIt{sk-=i|(-HRHu0;sPi=ls(`L|r-0Xf6cl~(L>UDZZ&D;V`M3Gnf6sVN zneq4}#{=N<1m(b!SFT@+!I=A<;-$s~(<49qc#-ZSP#5d$0j9GwfjA8MV%}@r^khZVriKFu)@R@t8r$( zpUuQ3@acScrKFgJGCGUa?ko3tccbRWUFPJ3v~LIyRmv&#EK9uyo)cwz0J;qsGx|Fl z1c>WS+lw(9&NK4W(Rh_RY9rsb@QYzlS^u`t;-;5Qo7ZP#w@u2n13Ej;^Sh-dz9~6H zQQwAk_d9#u;8*gN%6JLia~=mV=i*4P)!ZWQ_|V;jw0Nwvf%cotBCi#XDsrpI=5@uN?T61BRiw%tIQ-%B#``VKbqmt!6)p4gr&K48A< z)+O~#*bGzmV)}W3JLW^pa&a+c*^G{gRzN8-BtVB?S47;DpiR8*P1^b;nHZCM&Vuw8Q#;a|UAS#rTmt-?oBP|(K7QW}QxK{fa0 zTI5+Gyls8MB~TQaPeYQ>h6b73*2eHbku;&$f8{s>IkHaJJQe|FN+H-}-p!Au_Y!ZM zW0nVSdq5seK48;Oe|Dq0zWF_Wdgn7#hW(1gj`~zEuB6w*M9PN6gqyEX1UbvdU~*P< zEYcmlx3F6Y;0Zi?xR8(IhI$yd1>Eb417w`Bk^RHxkzjYCM;9`n7T2}~z38uCL%hl& z?i0LWWR}j$50<_&E+b+^^Flb%8Lh_8`EAg&<4bQU{&Kue?o_URb4)TzJva1 zaLy=jdStfw4*1LFhRRQYNC~1wmmo=9C@W-2HQh{snd$a6&2_&dGwubvi0^>I<7ipJ zZm0H6rUcZoI~vLmYkD72=WH@(7PED9I8M_Tmg`E2N6)Gkp>sq zAmr(1DWVmeW^$S*r+~HR8-=ALH>oXLjU1+Mi4%Gk#WZE~Eqtka=bT}2mrGU`1I8rU z8Kh&6L4E*Yv=%FY70L>b5}_vjO%Bl2hO7YMIC~aHOD>zp@i&hX_E2KLpCnJnKfe)Y zdrcR{w{--Iz_$dzaU#lDT+1cFkc6c^S_hz4^*JgCC^8xVZH>*)w{ES6t6vv${sR6Y z$A2xk*&tI(@83e1E)O;JuyB!VxMrHBHEj=yOM&KW7E~#OhuZ+;?smhzeuz^N@&*H2 zgc52fib-5pk~Kv4GaOJl@)D;PXt|I8DI)mbceNCE@BkRFCsR%xTHgJzF*c9>^K)jz z`(=#3_xDjXtCYmNvk7nfx7|lmj&ba)I`3iX);kSq`bwLWenz)mRR=4%LF; zSk_5-ulafOO|uv+jz%T#J$|JL?Cy0cbvp79tmb2F$`mQ0Pj~t-(tyMEg!Vw1`>*?$ zWNViNT-~GXPlr@9=GVKOYO~b+u_egOU%AaQYxrKM{iGgiuPFuLu z6v5L}aDvh1^BUdBW(r-n_jfs-J#HEv6#({Barq&_t1@|l^PuR*bix|4P7FQhp3?M) z1s~$tk$iC4@<+YYYz^{08QU-eQXhGP@m^<%%ij+|uXrl-p_KeS0)tsW!BqnwACEXi zuc$ZXneN2*`nsGTsS@y9`vU9wsc*JX0Bg&^)8!cP1izd3g> z7xn5nP59XV3ncunhaFk_bf1k8K*n6Ilea&Njr*W#uoG&hd_cEzt1N1F;f0dWcCgm; zSN)Esd^o)>N>l4=+LHX*l`wd*ID?)W4kl;<{cPei=qGEOXN9&lpc{8k6?ATjB$vN| zNg_a!bQsG|FHMW=AUff}7oUc)BZA{vrw;|vaY+@odxCvh9vXP0hkooPt61exNPoMM z@7N|nu+WHyFV{yqz*-#s28#uCahP-yT2H?fLFq_?WX9SL$%AaIy|uUr?bpGnD>R(e zH$=!S2!<60()R!w?{g}epc8142b{?qUsZq^XBF~ZBe2gJilENsKi)iL@pR;aKVPAH zNIv$FRnt++mo3eI(-;ZpuB!b*Ek60<7}WP+Ozni5t1nyWpX%+hL{biyJmW2s7$b4$ zD_=02S&_tyh`=*;MMqIyaIlGcE|u|hmWvg_c}vdn7;q-v#;aT?~ucEli=wlh|U5V-Jz+P!Vnbj<(pEiWwALDIZ&VnJtCd%GZ%rBAtk!e2-5^RCkh6iM;ex*J+S^SLy4x9y-i}`UiwI*y;{zE$9{I} zU8N5UsQj1kj*;X&s%lxw?082a4eMa2A=yC#=dMIxUOPf;!aVP(*nHXj?YQP5>VDzF z@GZvZs<6Hhsjfn#fB#Jg|1-6f1jlzY2N|@5Q+i<0-4Sf~rfElhOM823K3$Ayg*e7A z`2bBaKRphAU*aE`5HvxS{g*i$I#LHW-(2q_!6&q|3iu(|J}7N4Yg zdHme5K4nqcm#{S)gnJ+!A|kXOJ(`d6SBdi)E`65bn|?QE`|8<3 zv3%pAJmgQBisOl2Z4ukra1X4o3U+M-_=>|}ZZ$QiylavZe~3Sk|MMzsgV*N~gs}0k zGEm&n@(1hHDUoPRgY_28qg;*eWiBpe_mkvI{@Ws?7dHy$_eJU;il~-5~a4AcuM9i?~1@ zu?8+hY0ZD(_QNjEieP5nC#>2g?;TXP`_y^wyr*h;fJhQ+mW}YCqO}29vEDQS8~lK+ zxIq@3(Ct0}`qv!9kii*&e_V+*nGOj`6DhWNM#xdK{=Hi@v#CYN6>$7|x0RBMESE%g_}kpY#nhxK?(9ut3Fv^m zm^3mlK5BB_44R30Nt>xbw+GB+^++KKDviz+>S&qOr`F9TuSrha+Uy|3{U${{(n49# z;$`oCZ_e?iXk+0~0`*5YoB{!yEl#-D;LhQ^v)>gnjlMOtzQk0IIxY+QEuMJ|-(i`_ zs)!0R(%b!0^rF&u8t?6C%=2?x>4k|gS{A_6xB#?TDt~nTV@u9u`uS5((-@HR+hwNG z5*a5p0{_X!PNO@$@s{%Pl4BqjgChxRJIy7CD+Hx1Cp_ zk#1f^jZ*Mmkf7jZ`|D<&sJdB!rgYRQMWqA3OUYu%H(mS>Wuv}j>Fum|GY*-3mQoSv z%1a9{nWvSPJsz#gN5^)xC;VFYQV&{tE?2Rn{Od=I*J-fyo}HkLIhf~Ek}B3)KUvzt z#unp83qJS;+8MI~Nc(RgQM(U)PzC~&Rbf(nYQA{gzL>sMm3#Eto@=j5=57LLBpTG&p8gLbkRA<7ApHq`E~O8Y#p3=tA}NP))V1n3Yxwn;q=WQC_ONL9Ak zmo-A_h8&w_-1#kyG5dyyr5q^o+i>;i1}i9S)t!=(Eip8G8mu~?9)xi75BT>P_aWJS zpSmgz2-9asTq(`CMZF2Vz(;taY(+Ay_C4n$1!+SbG4I#(NA0*@8qY$Kyw`Kx&uUY( z6v4`Cu1`;1tthA_bTn`_J*L33aaUC%W!mK~-Y<`jsq-QKQ#}5!0so(3@_$H+{~j9j z*t8971fE`dHInL94sGmF*ip#YJY}HX7bRmEhD0wPEF1m$<1&i*Z}K4`u>Jt;E~_O} zO6-gMU~8SKBH@=@tja|pnmD4hm;XjZ z3kREjzGm8y;!96%$j0>Ec?Rq>hbc7pS<0dulspAd`ipHH`vIvEBz zZEOvp>EuDdk4Qv6t~^|K{V7YQHmben5L&TS6kOBxwUIQcm zN25@SC?KWmMzNdH*fx!Y(lgdUd4Sq}BtqO?`S)Z-tjOa66JXsK1*Z?~!Or=Mc~KE+ z-X#n`RkQ<1CLmr#B``?CdG|&gV@rH z4S(FBjjQ8xG+#yR&&06+paB^-$sPX(3`0LQW@qMNa{8=b^S|4kL$o(z@-#S>37Pag z{=78iXo!V!7bF|EerW&@l3tZC{6?!i<{TEZ?05IsHt`|i_5k&7&5L$JdT;?*yx!rn zb^>X}52^U@w|%=s`b&r+VAu)3Eh-{3@!1`H?L~6~=t4x*Ajz5f zfUi~w%TKI$Iz-P_g0TJX%|=2UiqOuOs4@JMdIqt1LJIUUTy=_x? zkpSOogbpI%9QpDblPX!4`llL*u`ELev!>J^x-wd~)UvTvPs4+-ZZJO#10x&CMP_2IXlTY4Kb87%uHgDfqLI=8~dklz)Q6 zf;1b_DTH9s4=CxI{-lSSx*=^8jvM|A_o>b)O+8PNCHt&{15#ZquGAEui!slWd)nNu zJdBkt7Yi3VX4T3YFmNSb%yYlPO(|G2TSF$apksL)aiY?PX052>ANUD zN(Pf_JH`r*#Edi%FGMy*%1|fR1o)h=TwXM=wuzCGxC?|1e!*2YM^slbuDmvawJ-t= z+tyRLw|;m8Js9ikl)|fhETQ_d_9##F5E6>!AH9CC8>0OkATgy+sLq|RxX)-NxFCwCw)B5 zZ8rjRCHbCJEN|WZ1MF&@ZQkvyiv?ubvsaLgc?8zZl~IJt?fmd;XG|CH0fuxP&kMZq zpyVPlA=T*-y#UD>-1LLX-=&vd0P5^mJ(bkU4`8c>|NIHkr{PMcKm(NuiF+T?PDlK( zL9K;j;Zn{cyH%vlWlE4o&9N&OnidTYC`8gUV1qwZ5uwNrj!0tW^nQ13H*&3_RM@+0 z;g!BnL+~gPEvK~>gwR^e-CEtoxfjIkIeKwv_fHN(?07f&KhbBL%N|Md!Ghrs*0nI2 z)A=lV)e#o?kv?*YK$C!k>z)d`riuElTkBp<7~?<)suVf25+EVZirIBavyoIC(jrx( zW|hOUm=Hc=kr3LM(V7sije}{qyNQ_Jwbz9YA`0S3vLpAF%T+!KWKaVb%C_O)&Z;@U5%tP^TXebp>midnBd z`_?zI;zzLAm{cfU@;>G|FXdWG&^!P7f65d(66Zco{qGb1|H%wwP>e9DP)}TM`)#w{ zv{C6_8kby17Lp56{zx-e{RDsrz;3VFONx4F!K~RPV|u^5r}lW3yQn1o>y`hDp5W_I zNy*NzqcPLn_nKjXHK#H%O*;AAzUy&obJ;v)dWWO1Mm1rN{)@saDf1h!Lk|h#;lU60 zzm+$*4=yMxTKH%Nr$|)5CDeWu#RgRy>GaxT`A`wkp8Cw8lzpAv!5w*EI?|5!ZWW!$ z!8%fTnxbMVA;%8&ygR^3BR*|{j29j&zyQ19S1w4q-$3i3!UY@* zT9TSXY;XKE_xM=nqyraG=Sl{#I3%qiw!dgGJgYw&X5j?(QUsT@ zyjX*LZ+%=%S1B-BAfm&Z)~lgsLsDe|8#s6}53!k{#q_buW8ws;FA zie#lkX(%sqQQaIH4$|0&>W-csF~3O@;Np5qLnNG}lkJX*tVB1d{x58O- zHI9YiI!)P_T$s3a1y%VAI~5KeXs-A0R?$hZrlIcGo2}d(`Vx7W7oN{e_Lb66hbykO zNW<=#@~z>a2K2>X8W(SuO%OJJR-#mA$2&E3F+L%cJpuW|rNlMrGp4z71xxO*nqy{C z2G{vI=!&2532iTPeapc?y2w?}FT>qArnQ_c-OA21Wb>=R={}DNr<3qANbjE*YfO6I z$%-^KPK*|c7@!5$T;`N3Cg{XVgr*&SkGj9%X^^XL-oa*2Fl9h*eob^;n9QyIb6qC< z<$1m%>GaY!uWw*I%f4+=d)JGVU~_{?)X6W!LdXMRkrkyL;rt*IF)g<|CGbs+`?M#( zCMyECO{g`>Kh#AT9)9hkGA*8-L4zL8J%Y3{K?B&58|H9q#PyEVaS`-lWFWi zb9DSoY6~0nEF!9_$$`mb=SFy4s-%uX_9R>ca3Z-cdRA}qhmW^Tm9dx8x=l)OR*I$L z?hEklyBjwfZ`X)GVb|Ay+Y{fBDxBOK8C&2_Spu7;#?%uabdK$p{tOS@7Q}q(KX;Tn z%h8qFp4=;z}c`yV4x4;zbo#vK}^C^8(|mSkj2qvN|Q> zOhHiQ^3{97om67T+1da-K;pph#)lxRfsuj1wYPZp>Zq_3c`VlQ#Vf)C@jmzLyT_|O z&isw1?%y@cVFhor`3;8d&3mEC^Xh8XjBiK!88QEwl$-G2a%BL&bj3IG?rab4n{!^$ z%!eBNd+vYZ;sqkkP+`LMl0H(-NA<&323&{qr}2mq>Dc=*!L;&UygtALGEWtV5>}bPLKF^R^!jmje}-5} z?J-DW?>LT*Ta%h09ex8PQu?AhHm7Qk^i_<+P=e{?0dERmq#!teP(TOIp2D&yexh5MkEawnp7b5mz?fH@$N+xLwbZo9#IgW%FDUf!FqhzHI3Y7pEW3bbt1V z4_J9(bV}BHtr}9-JkW=J!9^SE4il#~dfcqmymFHAV8%98RyA7`Ivjm6Pn_EY;Jj zpTVc|>nhpsPG)y{I7L||%VM@fYI>`Nfj8l^gV%6i7?a)4;N3^w!HB4yJwp{|Qpsmd zFYkVVsZ7RdYVA~3J9$Z_-ql5YqkTeoXFxtA72-C-ZM$Qr&B1w>BXE1R5uib8(iIKa zRHLWxR;LH=qiP7L5tF11{}x`a9ktOo&%kW47|!mHWIX3~fF)f^ zjAX2w!Ra8kVW*gDC-`FH(vAIo%;dUfw7w}|R}yY)dNYLR#cPHbrJ?XSp*1%ViwK3> zoj|=08H}7loaFXtbgKf#y@c7N?#xi=@t%_q5_-0AjLD1p#h z!NcW`Z(0#}4qxOCjBm(>rD6OI<)txN_mq}yZ@VT8-uQZ#faI2zT$o?-)M{ft{V}d$ zjEIE~6(UTlt|38FsumIA*1seH=A5Nvz$yR#Jq7#(IbNF-YVu9thE^EfSsww z%iL6@=*9|@KewTu)~dZgZR=6_4Rp6dKnpEVftX-kWipDFk^vUUqhm`H>ZJ4Ocf`C< z#;wmdEi7{k<5WK1r$;E!&-b0GRgx*YwFW!TDb1@jynAJAne8afo#sU3Xlny>Q5DKpN3!REe2XQ&UMD7BvbYZq5HaGByUqfG<8)J^M|T$JgEeWM}y{A zIII0(Y5J;LTuhunPWt4ZDO{>WEDoXcE5NY`>mE0kT#c4dwet7kVWig^MCU66B?$?f zM*L%rLy;CADWzdoO1q^CZ=^mV{(ju2>NTsNT%7vcPT7?iia&+y&RH-^K~0v1p@_?7 zD9aMer8J{ujD(yMWU+#mUp9`8v)^#&=@p3F&S-P5re!#2YEd`NREZbyg?K0qXKZB9 z&3~$6t^}}?+tqS_B~Mu!f2=;*;PQDDw_jMsL6gZR_cR9d;;T5Q^Bab8r9=OrL@ukN zef(Z%mOKaJq+39A;&s2KF7oG-u)nXy6CT&*G<_|5i+0e*^gK8%Jb@pS1)4=1zku4^ z`7se}XVdSn(V9RoGK%yp{0X(T`rB9acuP`O%_W0%p*E9(D;pBbu(>)}M47rDo4Ac5 zA!zC#tJWGO$MMB((_}BpEH$VnUkSwD!ZAlDOzLd)NcWmh3jFZsuth(=ii!6MYm+Rp zH?w8a!`vLyi5)$?JGxr&V|$1#bFD9~+6kejEIQXO!Mac8l)qvx=J4B|Lyf*Rp~2cq zb_o_fB&`~gn(+h-(mTQ&ChIEauPdz`F6ngk#V%dP;=Ng~x;zXv29Em~lor%m28=1_ zBOGK>wPQUyL^!h_eOhC6C^xf%JTw|8_mV7)4fq>$+pLJiHR(@#Pd4bpSXChWbX55^ zvJeEIUbir*FI^oYL6~BjMu%6$+3bggb*ZMNCfj(WUnWhNG~-gF{J;6v*Sc=zI_X{O zz4~zRbnA$>fdM=7^*-zPM6ZoL(!8^daMPrUY~h_xsJwreP)=CtSZYoBg;=AR02Z*P zL!UDEtSar|7n9>Hd1GH+TQ%R(BL$_GQBx48)+OU+T9MAb8Z@OA&iz$2B9#(vZNUA< z(^n_m7WQT=pox3_aN#L}$eC0JzI(@jY=iCXwi5xgxFXf4#LsZB&{QPY`*r6B+!HtY zic!D1G&NrzKAq8aBtA1&zM6xKILQL5;8R~e-E6Jf(VHpcz_0MZyK!SQ2B9OYfFQ<3 zFAwg*e$MJEGwAdvAIx$L9uc=>)o9V73!lCcudFQ$^?kM;;(64I3{QwHQ@UGI%_amu z`P3myUQSVrjGjIq%KBvJ?tyeaS&jGfnQE-xPPr~@4$Spsh#)PG@Is0nee)d@2Qjv! zp6MUm$^KxND)TTt4lQs@+9>Xa>7psC-dm^?Vl^cZ0aMY=#P>TkMruM<48ifmKu^+% zEkfwsLWhdSVt`9blbu9tgZVI@mcc3MizYC@#P=!DZWzA)#Qm)r@ll>nD=n->wkA}0 zW^M-KuH_R|?Y2wuJ0RV+C^%RnXb#{7OjdcYMbkn&pR%pH+F+SH{4kXl(JZv3(opJ) z9moVjFARxrLNUBN*SA9^sQPO4Nc9V@B-wYA^3V01`+u$o==(uevw^3jM)tG8du1SE zHBI?;bo{j{dd*&pAWix`Ss&k^w253&ppTeR5?$-^*AsE|wq$q`IGI$&h$X z=v{l`adN}Q<|tCyo6>)72LSwlZ6xaCE}b$h>VUu4|DXbnhUK>)tm|W5u^{PWq=KtqMy4r9X`!B3RBFKz^Uz0;E98v1|iP<>Hn*WP72_;mj?4 zvcu1%aug|(wyD`uH@pw^eS^A_u~K);z9+^%o0V$w z6dS(ApFs$cJC9^cKo4rj?RaWWS7FZ}c|ptP-)>>m`>U4mS%XoBs4GvW!qR;gv4{qZK9Wj10&-yK zLaN8mp{x0-*)O)zdGXZ~Qs>j{ZsCdZN7MfwRDv{{7mbXevdT4u;QV^K;gdEkgO3S} z>wLcSK@=qxu)Iu4wHbWNd=C{H$OO0vQi1PQcD(&cb&v>pqk)V{B2&+kr2gHrK<7!P z%Uxypq4Sf$L;>(ue6lWz{uw`%mC`g;u7wPO`@ImW#GN5Tn&S6+TvlRiY2~3QiK(sf z{2jG{UBK*SoT0$>wS%j>B2_4kt{ZFa7J_;I7Q!v^CHKRa=duxOoKl+#D+xuS>P2CH zO=HH_l4_h-h+C>c6A4I{`-a0CGO)P6vsB_9&h{`s9%&p9S{zIQ3;*|6ZWn8E9R`1$ zI&&Ma?u05jp!NU;Cy>R$rk^EUU-4074Ee&)i7!wc^PnVOQlPc|X~*idUmI(?NsJ(d z#vwW9-}QXp<+kE13JYO)2mJ8iWxU`J1qu5X8$>+siH9${MTIrcxLplEf3~|e({8EZ zR%4Va2)LD2HPS_j-oKX7rZu5P^GG!4U;H18y=7d}fBg5m zjg}aSf+7r%?vNZcKuS_kn$a!I=oo?^(ycU7D%~AQ%81c9K)O3eUHs1DoX2(jZ=CZu zcX#W%JD+#GUeDM1rC3(wq!Kz-^l_{>*Ru!B%o4gt)F7^_?0iqzS3JBG%6j-&E_1W;;>$jk|pP5S-NUKClgPhuc%AO zLey<-Nr^um6~cKZovZx}htI`~zB8=54mQ)kHMbryy@5^~6JNa3<4d>D_mGi)c*(D! z^xDC^U>QytVx_ud1ZKF2@xL8mmtAnXklrnx-Ap&O_;No;K&@ykqJz*A5i_#BeGIX6 z{G0UaqO{h#f4u$V3GYJ`Y6_CKd9HKY=)*5N{WK=Z(VM!zOvKj-I8F@D-uFwYls4Ot zTz;JParmsz9T_EuXs5bfMvDT7tmT5JEc`#b;YR!Sh5}l)?G0Q211h2_DDI$FrB8}{ z!ilm^wo;1;9|-zzkZ<1xw0W&(>~jSCO7T_jd8lmchlX$ze?Wwdy)mGgVy&qqY9xnk z#95fpj@15aNv}~kmuoCQuv+`X5unB-yQj0guovOQ+zXn~?o4oG(bVkuIT=XQp9Lwn zxKX&U6TS|+r~5_c>lD8a#7<9kMWvl5o=3H#V`?Tdx3&pemM#v8MJH5L)2)EOiMWHSBppcb+Y8pI*glgase?}zw^?v!fec=Av zvOWGEPI42C6<;EYf%D|fIA#u)efJ&`zIIjX^};2ml3}{K?M(t6h;BLRFGsaxtJD-XA!^CzUkk zF4E1HL!Z)hcGv&oDyT7kK%#XV1XWR2=XX_sl8^k2)52^?O`@X1;iW{&_7CE%W8V%M zy|ZQDq;P{!xO40``}hQ8^hn}otlf)gH4etGu@jCdU&%1ho9QmE2Lscg(Q5bIZ06^0 zVR8brp5C|7D^7;N-6W6QpuXWP->PDcJ=p+q6K}ZCw--IqWaW(2_zlzm5?ae21kNmi ziL3)Rw$4wH`~VdGOnw{UG$j=NE{DWKqrFgck9ld|WcRKUC=1kvC>iT`mFXuAqd`rwiH@r1&CybJ<2IHC!Qk&u8#W z;yug|Ph$^Lj02u68UV@?Pg@=%W*g}4Pr7uCz^^?*f_oaHxx|wLw_Uf6-e@ox2E=(v+F{@-VThiKbbSuHW2sFh9Tz4*6~_aTB>` z3%=i3Pga*w-~c5!<)ltN55`ipOfyjVxGp3(-uxalpR^qts#lO6i&7+u!RszshnOc_ zr?dJw_j;A4Jikn(zPDDsfg5lM<>p(r`=P0nT~yDB%`_H)xd=3Wmeu~6@kY0I8EIN$9PV4i4vTbUZBW&e88NoJ#nO=|p zc>fnay${CsHbHfWXEJR4_CG84PDP1YJ_VB$vA-Pr(e;Qt6^fL|Czv)xP+NQ{?!qId zUJNl~)O(K0#6YHkAf6z5w3r~V?}yk*==?nsivW>$`il5cg8pQJ^nmI}YxYSTjuMWpTdT^Dc}{LR zWJ*O56#8Lj0j_fze!j;n4Vel8{Z86Q(t{gVDd$ z5Vnz1%tYM6!+-MEC&+4WNbJ=gAF`|hDld6(%W#(_VDX9nnV)G1EoB1uw7iKTOa??x zBv>MC`Icawv4!(;V z*!!`T^WEbm)nu?n3>gJE^})+zZlEx~Hg0r;>95P*GB`YVd)5$RP9EBkg>d}F%7v)M z=}#3Akl!BNF7dw5mW!4)@rf_gN=X68&LnwsEj<*@! zrSaI-q)_%a0B5dNb4@_wfQIE^Jw$e>sTVDz->y>o>!y)OJ}>-r+ZyoMPZ!cBk7@p} zzCKoNw>u6cD=7>%Eah>n77^^KC;D@uBIv_Oji(z2by-O(_@IK=^^+BMN9HzrJ7+G6YiHNx0xDmZoAiQ}%eL}H)S+vpH zX4qmI^KpJx zdEO5T*x1Y5NqnsmXtO5-HIrn8R zS#Lfnc$KP9A1*t84PLU_eH0EZ^PPEKLD)jS-GD;*C@Z0~opSOux);!yQ8m0ku4-1E zl7nftmLGXHj_(%@4vL6DtsXUj(I+E4M|}!D4XX58@Aa0AY&Y>3I>+Fc33#X7=lm5J zKu*xjFN|IFVB0DYaOOeeubXDhM#h%(u{fGBe^*ysztfFvz#Donz3xnP)$t1{l_4p7 z-IU z99C?@3A5pNZC~BK%zT%*#vt*XRrwX=rais?SzfT(;XTUuJBHFkhaTR(WNM^!4&q|2 z#aH`!k$0NN^PAtwyqKl?^&8syH=sX!+9N7_Zz=@(__|qV+ADpB4&4(*0$e zUYvTriZ1D$c`3r@_ZQSs>1i_U6JAm1n&GP@HJn;3~|H0qhe0%F;B$goviV-?! zy1Q(9W8@X6bSygH(8J(5=dNzfUD^bVvgQ3=w9fx`v{5`M*PDj3-Mt%+ohs?ucy0Q) zyro)CDrH0_g`MdjW6Zim@9%{=WGHFBc}oY7l2ILM{|qKDvSWZA!coP43Z1b0yHxv|E>kzW zdxU3I8oQBO{*Kh<2?VVf(?cwA(CX1P7K9!w#B`E|s4&1<_}RuN?MVN)f6kmD05~2U zMNWm}8clFE#}OFeSlooB{Iqbm8qQTTJx%qf+8-gylo1sKZ%4W}kG8P7kOtx$)^|UQ z4|SVGb8b#J(LPl+IM|?xS#^NT?nF$UrhlsS>L*{PJ4X5a>}fPh2bk2jwKy7w`SM|2 zx@zG3h~*FIVW6^%>spRH(|0^(>L0c0Iu^7jXd^YTAQ@JGp}nvlCFsY)ROkk59tcaP$l(u}V+UMDg7MF4E@A!+#ig?hu3A(GpJoc` zrvrX+ZD*0-(HG*D7>~Ny?Vw3nS?urQE;rUf#x`{v>6L1-+^GE9uWc9J2+fIAG>}YE zG$h4V$@6)!+lFD*`8@|C({%%wu{he82$v|A%CPny7||otzBR07eG|A>FD$*%)r47T z2>jW^1720~oHa^r)2Uxqls=VmrCV#1gKXtBpW(){O8)7S5F{AUbVsfpp%_avz(u{cVBytf6uM)ZP!f|?`*&>JDj zf$l@l@^N<~4PO8NFo5zanRmxT18V-VZvJv=DW70^*6=nS7^=oHC_c=^#FvHhuYvun z02wkAHz9&qk9X`3^qR0Z?QR*aU+_JmYPe$KM9)1a{?j%)WoKZ1ll}=)6}>9;%PrQ^ z0k&o?(TMY(fIe%Q#0N-RHtYAz!jw88tRvQDmY*8)aXS2I?QoK%DB9QGwXY_(Lkq2& zK)#zY%@$wep3*+XWrJImllZ&NQI)F_q+l2iHCy`j?dFO%k=sSA#zmz;WL9AJ16DM- zHun>0D)K8Yp#KPCRD}RyD+9 z$)r&X*AVk~v>Iv55jz=Zr!2&vsYJe5)%k>I5l@octE(ffRN#r`@q0w0F6d$83Y52=fmRtdL`xC@%7jmEgg_An+N)$rH$uj-q(yv-&6`&v_t#Zl=B>rnx$Ev%jx%DVuld-<((j+J44v{n z3ix01EdTlCsQh(L!X$LB6ZeU{p(*BtyJnu)H!^?uU*E^)v~T?g%==z&f0{E+)buIN zK-;7|E`J>H5s=m5VOl~}&O=FCQA}ejgoal%7Ib(9<%oldOYJq_22BMxPPCo&8U}j* ziU@oz72PMxoNPqKB%?R9E2uGg6DXPWu9@ysEjCBOT zim2EBZdD>_T4M9q4LG>fbF6dzc=Ro<}cmJkRT-f^$e(kk%ImM%pFh#mT#h5d=4yq z&zsz+MLUA0T_u#fL601+HotS$Fg_CHfk^r3Uc>jZlIC=VS~hWZ#)jS|xX<1*2Ijqf zs9gKrbs0x9?UQ=nvl1tQlr?~(8e+jcB_Uii!Lj4%j7rjv@t6b}$A@pg1*BK@z_oq@Pc-8uuF@ zJ!3{sbN!c?y5!&Cr_dQ)rXhM!S>G+eA5_l(RiJiUTy^oo4bcAC8njmZXI9%#+|_iI zwJ9Doz2HQ$r-ugzQuMUq98G4CEs-g_XcSiVkC@g$h})$uOc0wDTbY+ex5`F$^IZVn zpBmRb_62k;fQTG>wckePXG83_7{=AP$?LU9LPkIm8C@K>-R-IvxY-&}hHM|5h<+A> z&erK0B>+Hk3I`kI@C_veGe(c?+aszYZUGx=O2&Md#fM8Dkc7Nk>2$LG#aNzs}B#v1f1j^G$TKq&nfWqF%tO24Y(S3 zoNNZLROcG*v4>qla3HgJ3_7L0eK}x@KYO)qW>)oi+NgssRX^_dB1sXS> z5^%eZJvq}ratQv*-o!I(U6s*i2r%H7h==8>) z%MC6Z`fNat-A5Mx-c%~+%uyWYQ?0oA{`I`sdx?sNgVg+;XmjOG9E~1*-`2Y^`(~JI z-`o=~S16XZI}y}@W(b_!asp1!oe9X&?3$Jww02FM>%Ij?=xoVt%;(9?>+O9%@qypW zT=Qf_s~gz~G=EmiOzCkWJ08io-|9CMl)|t7EBvQ|Xr;OTcTHj1ec^xpU*X?QolGeF zk2YXG^Wubyz8az)EEs1lFh+NAXgC@p90t_9h_C0tm#!{Ia7LnZxs@QN#iFbPgD2bLDg21eRp=>T(nvv0JmT?CP6>P-G z)^d7UlxTaG28uAY#SyAml`ia(PX!z22(JeGaf^IV=1PUNHy3f}dS$KO_b@DSYZj^+ zafq1bNM@>vR4Gz30#-&xWJ0>Lww#%fuR#}RvSQq0+qYz#6$-t;v2X2Kw3|dl=mUd^ zpxOC@Z)DH$vfs`=ZF{g8LkEvkH~ln_*7 zHkBVRS`#7a)`tD`vXvc@B`LBxPi*K_EZ63cBTxE`Zx6-`CI-uenvrZSC`uDI{ zZFA{{7)Q2H{}S>1g?7|_@7F80;f`Au1}wY3)YpJaJC(66>Oa@z(Iq+)H3Hl}*($h~ zDcptya!b*y*B>^guZxY=ibk{5xAo276Dd3=X*%gXR$SKdkMEmgrU>-fvd`AP`W*|d zO)~-R@iYqs2x^7gZbn9Lu6~cHs7%YTsf$6E2TU&yJ9>@MQ>c(&NV=O2=u!+zEOTc_ z23}EVX@GJP(nkqACR7Ajo@#Tt03;AeEP)Ii=lP5;jDas3YIl~XczesOyqF@r)8rm( z)_Hp;B$frfCo-TM*!pQ5{=M~%QCm>F=&Koewd-2|#Q)i5|BoOvKW{L|idm#HqP{fP z^!sZ!e98E)WT|raaRd0W*1N@dWLs^S!wwPyWO1zgmYil1rz=j!J z+HIt3H6arZ@v$QX*S`V?eWZ;G~dXg0g5@&6{d2Onok1&&Oq4+ z2c;JS1f;$q)6In)D(_GJ!AwBNMOuvXsZTr&vf}L84MRop&P4+THx;NS)r5i~Slbsr z=Vu8H_W7#rS(@`QXi(OyKFu|!ch8H}_i?#*%hn)U9_X)_dEHwwREHrmVk5+ke#$u8 z|NM!nTXV!;wjUsu@YMA*=VxYKAG)76Ts&^1qqtB9*iiT1Jge(Q9$cgnCKreoDZWWb zd}zLC_~ljIa}eLBg3gt9i>sfQcb!MT#)LV%Ilz-DdQ=vm@M=zOQ)*`hiwG)4Xs~9q z#=ifXv??EU2S2<=`RLAhd)3u@Xc@CU%%VfwdM7%s&izL^gi~C>%pYR=qQV;6?|O{y zRHm=h&hKpZ3K5LMRg_+8^irES47&n6g>Dkvk0RvP-pMr_S%!b{xfV;>);s#jBb&@w zGH{9|F*M)($g{p`zs2ClMp~1=7TcRd?o>~dMjKvrsAInL@K5A61=;&-FHwZrnfRk@A57m+GYS}Is{w* z3!NQ{5*7r24Bueh41Df$*@GUjmHejwlyePH&E*(mQ$Dg^LW)MMbY0TN*PE3oQPm18dSqG7wB|bimw$bABdN zP7u4$Op0y?x%(C-P$4$O`cRmZoV!AwLsA&jA4s0o=rYzZB}Xv9xtr&oEWY)wCX#kk zt2^79OSbKJP`s<9&rqp=5#6epTMJW-rkE&; z;~r9^bnlcnkXoyO%W=% zHVG}`VY6C|ODY7pXn_7ia-A!f}r>^s{Vi91^y31;(zvp14_GW zpOxYNVM>s?`0d0QM=(Nz&!lNAq4n4#etql$B@TI|1p`-dW>?Ui{RV%Hej~6Ph6!(j zoM;2g3Jm)ubB((m;-W{cof5&v+O*%xNO&$EQnj6^Au?@jLSEGe1ZZQ9eupA zT3xhlP00B`l+4_{34HZ7+}YBVlWQ5u4>lUKO-{1c-`ajFe8TBGAX~u`cTx^tOwI(z zO6q+zq~g2WD{%nkB21W(gP~Gst*tlkVM>6dw^mrSi11@4sxVf993#n8s@T`bS*PST zN?0S~(e=O-kuRTWi(im=JM(T!VB~|o5#P(X5B%Be`+Q^YkU4aCB%qy|7mL+oEy<@Q ze#&8afH=_;vEdG9q+TIt4TgD=z4c1lQd?)@blMk~iu+X$XNNg9K6@-4_qOsQ6Z+&3 zHjy-@E_GMmT8v}-*HvQfOW0OP4q3`izl>9px4wyx*k3PTps7RemuCy37m^6 zM!g%TSPJuchgr4{&=csq6uSt^E~}cTAY-+(eT~fNzzJ%{`|up-wH5PaeF*;eiWlr| zQmHB7e{1PdUS~i8fChdv4I_U5Ip#dNPs{jp3U_{btR&)9`h~oBZu#bhBoNT^#Jb||18kDI)ti{nN6u2_j2UWYVaMH;=>nW9@=>Vz zYWr~OT8%>2M4h&-bhBIaNfgi?qox(!75PeAO50bwz^%(EeP>6^R6(=?va%v135e#V zb^V4jp%Wga6I$Lug3a#y73h_Z1K-^Qe02%SuO1k;EEx{Q4W%Rxn^Xt%m6klXXr@OE zfeJvv@P-K@@?O~U@b0btN`;;uN2$hM_ZIVT>(&)ohLL0sKpa9bQ;# z!I22l8RlfDaezQ+aEakn4aLj#d#-Dzg2weG;oRD&7+q1Pa;64AU5=qmiQMT@@W^D8sQJ-EHWen8Dg5%CFsLH$~jo4v*Jw zZOp5Cs=3_tPRi9f%|D#-u9+GpwwNq6ig6KJ%zRTlH)GsZ!Ci#0?ke3Is@IvD_I~3R zuy0H%X;_o>Uy_sW_xgP^qs#l_fl!j*krnlY_}yXKqvJ>+nuA!Nd@Q=B-&1zY^qO;$ zbx2LNZ_&*Ei|%Ev_cMulkz+U>)gfWPK_ctW<;%+zi2*3*^3j1TFrn_WZ(lz@jL6orzZ$ z47`Y^^<7Y6Qp=s3s!wnOlkP8vxr#AM`>z3}fQJ}v znVPs-9cRbB6@Q0WZ!x9&;Sd3ujivH8Xpgb?_-TXpv6Zf<0yy#15ZP^_JEKek*@zeLYG2;yuMDAo z8L+Y7$JL%zVXi5(Xy^_Ktoz&OHaka#vZkdL{j1x9<5!>o$ioS>Do#-MK6ckzfu(q% zI`!8Z=N?<+W2%!}KmhE0wAFAx@zY%KJ{g?yM?PDBIwnua8y($0s{eOOIq3b;Umb@1 zYaZzmrEVkQxBG9`1<*2!>@UroC$s3tbt=>9C6T;#?zPEy+qTYoOfC6>$`8X+H@Zsu zrz$tiqdU#g?c0wZ*Fg~d6N1HO-Uq!sPjTF1n!UP-H}_)Ri5!2vY;WWz3bE?<#>j+C zH1vG$iJX;}a!;muXv+(k&e-#C&JeGY{F`*5+=}`(;eMa-;oZ8trrawbZyiZ=V&$JL z;{N$uGzdQ?x7gCfH{G$7EEgG|s;C5s79FhaMb=3SpXd9jGrn@{qsKA-?6P(Uk4e}+ z+!p#R(B6UQS2IKgwE{++M+{8<=6iSRcB}@2?IE0yr z&m>LxGw}sgZ2k9s+DExEgpP5aELAY8JT*qUTctmXzFQH

* z5`dAsaLj_So&xFA7`#n~8)rg~ZLC#9xsBt6-PPyEX>uHA!I=|~p|U7qN)mb0;$mdd zUr>4x)S1LxAnbetK`0u##@|MZm2SoiNXZZ`iaKA$+iX26Ey!^Z>}yb8qHwsOjX zt#rU$j&`?8@tvFXj@5ngwEUb!q~;hZv>VyEI&lrZn7-7!;Wn%QYo2~8_tUsps&?Y# z$4Dxn=RGMxVwThVbm=wW+t&(HQfQ# za;)1^-u_jZS`LB4jHuUw5l3E|42qUj%SFAd1cSg0E z@WkL**RA}8gA0YjB+jG((nzw|%Hw%&Vx<%37|&v1ss3MRVp3%pR$49|bKk%0D?gbL zxrjTJTs&?Sjn`z!j9&f2WWNrE9lgdzqkDuu%);i-c1+`Cjao$gJ+jg)Gg^@|UiuH2 zQMC{~@&7?)yd{$voMiowjv|pCz1%NR7ps>suW9A1xU$b~EXN^4mwM>efrzsy?PU=A z0woVGAaukX3Vh?6%>U-g$Q4!2-Azv)7nBQkBVdCPN;fy^pSLVjVp?)&PpA}soO)`R z6m8JS^mBt9csODRfY*r1v%I19Hd*ds;)0ekI9yp9Zx8gSg3To(SBEXbzH3qP118+l zJ6@s-hg#e|bqu8EQvuy3XzW)1cvJK~cnubtP*KWz-Ea5$IEAscVXIxa z@wSxcER;cEwjh6yU!>A-=d4g~E55CLvQO|lKHbxPjR0u zx+nLOgyHYf3l}~_a?~6NmaA{qa-91Cl>#eV0?jmqwH`VgNe?b*HQir;kLc%T^>CC; zxCGCBK5)zGdgF-xTfgm-RLA5-ha=l^`ofQeIua(e42HMhH_vb!z{kcc%fF_Z4x|TX zB^;3oENc>_PEWF?zj@2IX>=+tF)6P6HWe!Yej#|>4U5F>)k1A|T6eXQPb8sdT;0%C ztza|Fh8rGE0@Vgx_vbd??aeEGBhRNDX{z6Sefr?&ZTC>k`J6Txv@|wky{A)z~(UP+B;N{#cM_Oj6|jXemMUJJV8 zikLUO_%{l#o_{yf*9~I4s|afV-cRD}{|bh6AV1M^a&j|IoVl~9BvGixI7>P%QWMpX zljtYDTn|byj9Qn?Z^ZA-vnv!$AXgW*xTTU4w)S6KKh_ObsLHi9s>jN(_a*`W*)d7w z7K;FRy!E~4Px4nGmVEP|HgNX3nU^Ixxwn#RO#?h#&Us%}Mm$umc8`i-f4^r_y4<&u z_A>Zb*>=n;0~yxpv1>O}9DURIHw^yp7HxDfF}@e3+9{-HWd3cFcgjJ(ytaA8wj{ZH z=kvPJi?iZUqqBuUKKLq?N*Ati9v+_DOSm8y=vzw%V5h{ohd!-Xv7wRZgqE6yVJdSj z$>V!_(|8Pz`$U z<%dcp3<%LnXWn%oPaQiJjOb5An0f%WNrQDnr{an~uRSlG<+n@Q1R zOmcD*b~7qEvm_ZFa3v{Qzx}%N2u8Zwr?0J(<8GExz_7g1A4}&dC4GSN?VHLy%Rnh| zJoHh+zLJ){St7*$_rwe3coR9vr7aq%JZ{Q^`_s5h^p*w=xjY*Dey$r>fV>qSrR&Wr1}c1Jm=Zrympt zWQ$48wz`$nf4ulQ>G-76Kvle0Ix+)&yT4vYNd?ZA;aVau@g?)r|DKPR{-}^rxTfc# zz7lNmllI8ts%484+w`cyhr^R>r)^fhwwY`#=N_jk{~wf{_dnb5+wYUuRjXRmE>%?{ zEou|0t*VkPo6xFNd(T8@OIw@TBUY)_-ZQjXS~FH`v189565-@~-;eXtIrn)y&VS&S zeBPJqdcK}7o=3gB*7t#DV3?Zt)yT=!xdfUT${04N*RuWo5a-9mSCBCY-oIT*b5}p;h*|j*?N#+Ig0`^z&gy{$HwU32oA>N+m`@Qhi__ z=)WNRnR(P#OC%{T91oM` zU!f7ROT*A{!e6XA>9@NDq)ceLh;Jv!16$-~qU1B0 z;?`f;V{Kd&CGbU8%HG$jc+%`SH2{OFA-uBKXQM3Xof;m0YAeGP9Y@x5?8AA-O6yTz z8#NE(!63ua+tSB-5j7Eeg~wg@hsd(JnE~WiJ7ns)B6yLs$7GI1C6h7wXkrKP$2RA= zA({H}|41hGVf}_fbY`XeL~H+Nbi(jU`^1m>|3W9u{|lY)JKNpaTgc*G33~!qyijrF zw-_e0ly&GrOy^M)YPj?J^$ZS>=tbr)-%>ueWR>au8kkY_8~^r7`yJF#sJb!tYqR#x zYsBP1*(Je@D>|6euAy9O6erB=xeJZiQ=D23f9SnK5liGnYkXSTgY6k%6+p|p-7><3 zr}q-1$9|B`h`&Nh)W6e{yo9F1zId&?(gj z40%MJ4t{%h>#`KhYk2I6`-D*GDifg~`u^Ni!B0hIyw-fz=|YgRw8B}nLezFL^22{E z(*5Lh=r-9kwGHKK*zm^7@HH4V=QyfsLHeGe#x&%|ZQ7J6rtG4&-BYhUzxF&H@oVVi zF6TVw+kV;7>00S~+1NU&)YZR{6;PJQ=3B1JUdHmi6Xd46Ojq6y4#2*3{?9t$aT^ZO zeVqBZWbDDnbKv`_@J1tx6hM0!(1NncC*61qDc69 znP^F%Ab)S3eQXo=0Hz2zb1K!8F={AIIuHXqlc!P9p$`%DseqBS7V9&lS&2arzev|x6GCpp4f^14WfIx_&o=v z*%BsdyjxFHlQU8Eu8lC8bbb!KFwIG9XfNCpX_|f~9^^{&N~*h`QrmHjG3M2CC?B#k z4ArBXSRw3D3v1gk0Pt~P7&?=F8nRv*^BkkQN28;XKX!j4Ref>dB+D13$4t$ZGe9ODOzVZS~!*i!$jp6Pvr2);h@m)|(<(yO~#L4M^NOqW-h?gG^F{yxt@;?Oa99MIy_DUVSA+y1E6`1rbj2w-2C@ooq;e zfjPDbbxyEZ^~XGF|A_4F*ydOytPOYVR_V3bNC$}cXzhxxJ{8t~@>qv%gFY;*8_q@U zwP)AvvUjDq$9Gn>T^so7-Vna>5T){PkM4Jq!BZiBVJ&2Ja&k(gYtbP-g)qp^ApF)x zD=?I_))w&VVD*L(v%okOq@A*Ci+wW1?@v9Zt8WB`YTJW8_6(_9dArxjS~&PHoVSM_ z!IS616NY}LE_DdHg@e#HG{Cwts28(hnW2C|qNMGh5-F-YkrS|wEP+6)kPQqe=6^|eyH6K~m|->%HHWlLj$ z=iP?F9Q6+e^54-2~qfyDQ*u+a&6^C64Q=Wrw^!1;0W-L8Ke3}Q-8Ja+oG zRPN^*+T)M24*f8V?^C`--r1+!9eEeA;~Sf;_TXXlOsC7F|L58@`?8|>NafPA=?6RK zo8m(GRPJl&2HR8#P$Av?_rd{?i*!=&5tJW9AU-=@jntVLn++&O9`;Lz9vnpSjo@*Y zB4%!3g>XUVe8{}x3MtB^iQr9yG>4jNJvv_S0LH?Pg8qQMqpfQL2pIq^R2Lo3(uDZUp}VMMI9e4! zLI-~^0>s_z{3{Ml9)$+}`3#H1SGYjLETiOPP8 z!h3Wu!)jW?l5SApU;=D4ybF!0Ar=RjHI58J^^__9aZa=erMRCuu2E`U1)gi1yiFQR zf4iT?zhSqZ*rE$HTUZpIJ?i`#8;)L+P$X>V-7fp!o?P9$74z5RJnxC)pX=&-r54q^ zI3fG1=Ge3r?4pV9cC*oLd)}I#KmNv3r5dS>N>soPH(2><%Ib$*M?rixdbvXzRpz)K z*ArZ<2eDD`=vM@H)g4l|PR-4JJ1}7G@`S?1NT?ufwafgd_hH0=1_NyY%D2FE`0ET_ zcec-dO3Fr^Qe`Ls$^BZcXHNY~ZKmb@W{4Qp=r7IPDSqW>y;%gmUWHkN<;TSvTm21t zv-^#`LTUGR{N2vJXVlhgsO}_Hde*YZ$w)y;Srt~;#Uxa{yLvL|1NM)@?Jv~W7BWBO!#Qy3O zC{U@Q7$05$b^~TJx~l>Kp29hwJfM4 zyayzlgeh zuWsVR44a&^SJ2$ioFTs+yP;INtx)ttj8<6Ug&4K#db~6kxhCTvwio^BDX< zPpM*Ylk61FFyfbJ{XY$k^*3{_s5d=&XAJNks6MF!Vcc?&?~rcn`R=w_$;~4#NH1ob ztuWwf_RBm0kEU5kz7hH+rSoREG+2Jw@Kx#Z{Y;LVQ3glW(G+`}a>WQZH4Jjv< zCXz{7%}=IQdfqDgA{KH@ZLR;%_8H5oh=5VUS|#mP8VmC$N>l#^c_5OGX-c*VU2=W) zv6>EA@jU>ET7m_aSI-$Zr(^U*JF6gZt*IUt@T2`V?yL{@Cey)kiwk~Rn`BlG{As&{ zAY*wo;6Q&*mdN%ZwHMs+iwT8x@f6moOK*w~-N^o^GvD9~@45c2R-dj>9UO~z=wny2 zFx6kTO07o@M_D@Q7bE+p1A*?q3CQf^nnn;oqJ|Avt6bh7o(YF?}h*fRx#` zRwHEZXzdk1hU5&6M9g}icx%#7~lmXal0TNx6 z*}}rv)h>wrWR_{#lJZ0kvY>jkn zxMkltp61rc`?NbbATPQ*-H;>9f&hKjn0pYu0Nb^s_V|UL^Dg%MFohXbid06|x{Wvx>Pj%NiPk_i! zz$%iHN0lukMt961EQD?8svv*9AmMwHwKoIWr^f`$JqLDx{^%;xzFuVL3>*~ibvaS4 zk{#11NxJ~ho)ok?x;^;r@V?aj(tIw0595>dJ zI@M~F4(#3dv?;3@0xZ;+?{-aJpfs%+S$i1OSF5Y)C-QJG2Cwb%cJy4t#!$IDJlfQ z-}m}e5a&;3_v!hah%z!6dY(gC&?h(k=TyP@pHoF)ba>AxJ!9$U3oScPGL5YKW(u2{ z`(^huCr)r^7!3G_zJwRGR-)vbjtEtr1YCfh!4$kr;kudkGcQmaH6aKNZUH^N+QhRhO{jwid?YKm8Rg`(J;+M`68#`*m+2O1retoZrl9B zPkm?rTIuqUjQ7|lSSgNF4D*e0K^n1V-@D{4I#GPF3+*d)eYQB^LO6Al{BrD3tkV{W*!{k&HUy~{qcSq?`8cnYesWd9tP#1{G?^h7@>4+ z$Qm5C`(ry&T=MuFsc3r{oxpYey(wbP>X1SWZ+sU+R3FX|aPf*gGml*UFOJIpMi~%S z#N3a%?P%{&Q~Qwrf+Ra3WFdd8^@kA|x5HioX!d?h_i5j`#lQgQAHQz`_+7(HeAK=` zT`sgpm$R^x?h4Qd4tmaUWaOFy5`zbr(gFv+?Ig!&CP|l!H+Td&9T?TqJ?c1RmUKe; z100(sfc_sQ8!OaU-a66=|IrZs(WgvnLRmfUmAVb6DQEkKOG}xunZUjgohFL`x zo5{~G@Y7^}g`Fka+7pjHC`?_Wo4bUZ(x{cud=PgLd))~#Qb*(a^Q|Mt&3IdyzkN3q zZ>B%4K-*}JO;~&@IW>tDmJS_reVBT_G_It;(a@l+(C1lmLdz>bwtHnR8RNS2lr4;4 zDQ$Yo0>R9Moc;?^(bn_JHbzX@T8??tY2hPr^F25OIovT>*R;b5OR;6R2MtWOljzEo z61eTcnH7I*n{oE}l%nAd`1`?_PfvQY)%u&yfVw{FZo>niEHuFk_X z`-z*zfkUmUq{a41hZ#!45?U>MI+L$kp%F|<>47~Nn5ji#KE9!k%iz?h$U>Ugi7aRe z8W^5lieDRBf(px*hDUp)JvJC!pDk3e)6KcXH)i%hdgIvSYU}Zwfgd;f)L7fzp~@pq zGIndIIn21vM!8NlasUsm6Q5E8NI6&Zs5bg+-1`#1g_?c}5H7 zz%KJ+d-=1FFh#X(amTv+PUC!sl79OyTNSajA6qW`eOjSO!)1zg*$2x201w)`0O@YH z*3niP9#YovEDfe&h|+0wQX1&{$c+st5a*lV@<0Qc&9VcFU%q zS_8wJr@*sp-w>is$dG!-QQp+MPI1V2NzmyDr{+|I$*nF=nHI(&OMpM=wK;QjOg>hw zzm*V=2&8-8y5QlPa>F~BRK7oSHHjMser?f}6`d<7s{_pvh(h{qc&*Ca-i$Pr!N(w{ zUSuDKy-5aq8~-A@$TQ{Hw zK$OpipW?$4VNV-2E{#ECO%58XbT#Kb9z=S)levlb=cZm(Y$48ZKN}Md-e-O%v&$4{ zD7?dEv}Q^3Hr~|QyYhadU8?)rDH{<3!BJ`m52JG$ixm7eZqZeBN7y6$R#~Z7t(4WTFkP)#Q0g%zjWr0U8L@QC%or9u$`*k! zk_mHPpW{_|boIh}*uw45rcsUkf)5OmBLZY(?2nc$BwyDbSq54s)@Q8%&M}_|B(iq( zdp~Yws<^SG>RwRl!07qk;YxQ}eeyl0KCjhhC&M7JI$+>vA}wTg$ADG zM4eO%r0685qtI0_Z)2| z`P!^xmLt%FueL$I^3g8c@TGK>Lmx*QNTw3yN7*aH+My%Nuxvr#{aFNp>Y7Nz#zK`4 zkXVlnBBE)&V2a@^Ry7j!S9TANu9>og>;weH9=(qx%wXESN9_#>!s1;{M}$;nr;ZD! zs5qcTjo*t|`x3>;lG=64r`02y<31O6y!;3KdmigNt+e@j5~rMts^mrVX6)IWO&1BQ zf2F!Qvev#tx%7ql_ovy3cL&u{X$vyDk0Chyr z8@bvBko-@+6WspGRO>u+t#^E)_?X%(j`@|rTb6A7HG9-R!loT&xqud2}p5NjWIFy=!0NS6BOk1 zW(syHKdCCdGj!DKJOIII6B;~zi!rX41h%v*IH!XZx##)@k`;yJGrreEu69bc3rL?` zS>^cQOE+|PP@h9a(VcFJ2Rpg~!fs8+NsxY`@xLO1*>LKvGRh@u%HoLsKWZ)Yn(Fu2^**TJaZU zZf&|Du4^EMJkM=U6ZWp+jgtzlU0CP#9$N(S3B>1Vc;)$5yDon$NwnBB=|tTAY8q6M z!AJBM&r;o(zvTS#;%`4Gi!l*`a;<`^2$b@^Pjt(w_i%ZdSkD2U%ni!*Na||z5J+M9 zJht2_!_GVWhmKL54p3Yh7;15MaC19dlPF*4{cGcvSZj2+*271)*vv~0t)#DlX++Fv z2%j(5#&~_Bb>ARc1(lQMI@liLG#bv0*5bcjA!#SiL7B6{4v#83Rhc#S=l~-F8sxn3 z=?ADlhvhlUp0NLYfK@f9Z1&d7gACuJkpt)VvM~H$eznPm>}B_V3OU-+w|DYz7j}=F zW19fz-16gNx^L~BU&~&)O>{`-0%A{dO3f&%khf)c+NV5cxk2%mXFxS^YXD(bO2vEo zvPRtT{2kCU`@|_QCqE!6>IZuMA!(n#h}ENzG=0f=wbf?Oehk`TAeYX z%Cc6=Ntps8UYo~Oz6uR^lI)!a0^9Ut4odJD+X4tVSH2$yUi>+4hxiPw?&T(#rWTr%HLqn&OswLW%3ERHp?X%OR%q;F>%H3vB{Ba17xTidi} zuS_B?5UF$l)9&~kV+L1RS`2t=;@8K+tFYL3QvhoaUHDO2;qo3d8`Q8s4O%{PSK9=9 zIVUVac~lY0Kuy|XFz|^}?ul5kI|>pq0YCd=ligTt(h@xBaz}=a&~Ni^g2u=zN?8k+ z!B6YY99c)bg;Tb3ZA-ea4VEaMoQGf#~aP=Zd2Z>x;bq&|c=&n1A^T;h( z{ztGZ0rtdVW9dRvx0eJ=q`WefKgK9|^wB~EO?Gp}`6*5P;)BP)i$a3TbrD#g(cqXX z4RQ2d4ZwLHSY!D{prN|i(2MukAa;oL59E*Vx?!uHAmL}WC_~QOrZHs&HV5O@w$@hj ztx=I6NqW@9@C32Ikt1RfhnNjQu2Ba2*>AYqB|9N^+p=R#t;N{sDfU}9-PudBW4%GY zbL>FMddS+HrdX4RyeF8fRDJrmQ=~FwPC@fuU)uIey<(Gcws}|^{wlPmB(e4)Wo|yp zHCtPudG(Vra>;Ag&u!UKN)nU|*+q)Xoh*-T@8xf8b8%&(G=iq#M<-qUH|LOZD_h&t z3fok2xIHVEtNPTvGo2a1fedNZ+x#LH9RqbrbI1qX(S1Jcn4XfKYoghF%mh`@?}T3> z5!bN_!~`J2)#FqY!^MU_%PgH?T+4W1gPVu?#x~A!;|vcy%S!0@Z=v;|_@UbCOqsL3 zHcH{AH%s;6q38R!5EH-Jy1B;kuP;J-%+#+qugY1*nU-808-ox*e`lKgm@jVO;tJPj zU!~!ceufWm_^*m-_Q_|FrhN>8wU9tHULkRolgg5mewE%A$S$Uv{lpPIVT(@3eI}~K zw}QB9+5tg%Pr}b3w3G6I|5d@Jf})t+Vz;1Hl81zl*~ZR}q$PD}j`1I9e#q1{+f!3GmTB zdEViLvIUn^#pAsWz3oMD#46jc7u1QvpeL*0)x@;8Wr%-T5h|NZg&!~OB!Uq`=T-mZ zq0)n%z7C$IE)UvxxNVC6M|y!r%v~n5TJar~cd)qW_S%8=p4E2kRLDML&vPba%b6W; zQ6i4VO_&WZ#pF9=R$vqd1>8E(-8XD!F>|8l=w|sNC9vd3XAvu=I(P-scK=npHbg6Yc3`_Vko?6rL?QFF>1$SlUiRv*>4$YQkcn5< zrq37D9#`(rKFn?uaiaBkTUG7;PQEC?}^)fX4lAElR*f9BPVeI zu3VqHZn8c|ZG(vNdRML(9`Uc0?6_E-63o>?#iK9xWSIT)HgHNBwPQlQs7y*S-FDG7 zpJHd32mf{X%9rmsP`N3Vh#eTWx+csibzK*>z3qMb}o+QznW~adjhb z(m$Kir0v-(GTmmDxk_Fz@<*?ZxOlInw;cWrPyh@I9#e-Oy$^^CSo?kQpy$M7pTWeL zuI6_yR_%(HMh;AvhHW6)<{fWjH@CgB1xiRZ!qR)dYA3FlM`KeGJ zdM?+I!^&EmUj9na`*J{E+E>f|Ipdsd{_ z>XStBOKUm!ts@5IKJo5u3|)DMawv9FP- zCJA&Go9Y%+@-`5sqj-R-(5q&_Z1Y-Jt}Gy3$5T2kg;oBLPCP3Gzf?LDvdUsVRV zjTHk%Z67##SJuXu`%{)w=z@QYwquKEURH0B&s_Dtob(1D`3Z+|OB#R%5zNC1!qo^_ zg$BsiUdph*dR=GWmky5}KES>NYJXF;NAMQ#cTjLJ0AqZTF)i3%9a9Udnji;G*fEz} zp}Wl-6L5B_j7o#7qF?i?2kgH`w|0kqA%9^WKR$fXB;o|~u8E4Gru05EbgJbJG}dvp ze6-xx6OJi;iF8~V6KUg`mZ)0cz{6bi>T6{RD%Jnm7aYWUl%@47h&WBr`0vX9nq2g) zM_0|xnBpgP-B~mVAZ{+$NkTU-17E+=7k_)NT5>6l_}w(#4vvmoUKeX0Fh^#k7yue` zN|;xIP;8Naf4X)t;|s!lJ=>#BZPc{O;yN3(>~#cwwmaTa_#pzRE9yHOKPP~$`7qb?&>>lqZeOHtXhm$mOcd!U4;}z zs*#4UJh>MgMH2&FFlfQMQz`;}8CTe?m-ENV+5Q#x41gF2C2zskAmq_G zHF!QGZk}Pqa4)0F2j#?=^{OkdoqS}TWjo$RM|BGkdYNOgMno4Oh?R)d{)*%7RTFmv zDF)nb60>+KMLxNR4zF?(o3eIl)2e^0v8ZrD$d9;`iCR^wy6+YkAElBTUE5U8+!JaD};-pB-3)3q@x&h zpkchEujJjKRwixv;+FR6Ve4}@a(GIUtjvCRdDD}rNp$$)NHd|j^DXhcFTX*{nTz9} zX17HQ?y+hr_#WSEHSwaOXNcrZ{Kec5p^)Ane%5luKe*)N7Po_8ST0|k`N9Iu2&<$q zPh31*Bo=fDQPccqQt7|f*w#GDA!xh7aE;STF%U_pL&&2u+V^MIYCFk2`?=>a!68hA z{E758Sf22v%HRG!E6C@X=w)zcP|eki&nM&eIN3>dku&7Bb0e4j5&OQArIl-%q7^K3 z?U#_AAFn)w{0aEJ{1hMtdTMksKdNH%$`_~&Xa`>RXcw=cj1bowZ`#JIm6m`Oc0ss- z2&ed6o(&HW%NVd!>b0_g6H@1WN~Mgru)T+%CNrG_~%k>0W#=s5RZdDc@qQ-=~{Cv5;=bR>+`S(x<6Tooatl)goEe1Ts zd|`fvw&--*C(yzhikfKwH*i-BoB94&tuKBq3r%}5>vR73f};R~s67P1?bmwFa&mFm zOLVegE%#F_*Q4)|jdP&LJi3+-`~1S*EZlhZKU)32FoQf%-XgQx&RLaS4Q94SS0|oq zEAj*LTmd(z8G_S0n%D?rGI!;4P#bw^Q2Z{$u@;dOJ$E1`l>|~m1KNW@++2 zb}-Gyohx4R9COMgp#pMkvWi)95dn|h7qd=O`gfnw6VjEg=a+A1He7>R0t8W6)_n(r z9CK6iZN%P^xzyHkN2D_YDAx*109ctF@YR-ppb#m2lPo%sa;p$>YkAY->l}nVE zDLl)?=`;bG{)zDY^nUhk$?eii0_`mQ`|Sy%WHm{yxEYqN4m5<>-!<$)n6E}IYjX7I z4W_rFV}WJZ*E^5~;xI>GCV-c8@qV7ovGAZBj|zyA(+j2SwnbrX8S}h+vM;R zNPN^vo3~FCj|rAvpq7#;#^G13%gGZcivHwziMe*COJ@fid>pLL58w?v+oVfILieb> zs{W%}G~w!1rB8Kz+{s8dHeAj%SRgt7EjycEWt>kGfHKZ9if&Jwg@_ zAibTKJ$QRS7*)m_lo{6?^Hxd4--si=Kj}DpDLGTQ`r(YtG)3ZCgoeRjpWyxl3m9G8 z9q3i_-SONI`2HfpT_ME5pAULF&=Ukd4%HnimOn>&f33H|Q z#y@F>AtNQ-`hU3q@)jDtYY*8#pR5=g`jv8EGyV3PG=&5WOhHOp>4QFb3>z(e7R(kF zwDQhD7uX$9Kg3z?obrBTi!EUipwwv#$QQsjHfTnsS|kC_uqN7)D5q}G74I9LT%-3| z(3LZkG#pW%)qB%7b_eWttoW+OBxrXv(iiig$<2Lte*T^6$Vr3wY&-AzQJ^2HgHG_9 ziOTYZWX%sNW34w>9CiP}D_C;v5yi@H039@xB|_l0@x78mNTkLW_S)xD?aNc!0t{vv zr{Fye+$HE(XZ(m0EKcz}*^!}iw;U7(o0Gg{&tJGJJlB2eu*fAF9oP@#(;Rg2b3i4z zG6=6)k+?(HD#()Zo*2sE`GNhTy}d@Z*3hiG@&9=xh@=jag^**bv%E9GEB=yk?BtvR_WT;Z2<{ zl62HFA3d^gSYY$XP@-UBDcAH@3z#ekYDe0tJ&Fc_H|)sPQL2kT&|hl} zx0whY3cM<`TMoxo+L)XjIfl0Ob0^QwU%+1=*LX|x9DYiv0qV1DY_tY?XJ(8w{tM_P zNBxY7kMhGaZN%@{2z)7~z*BvmCeF0L_6Ojdkv_G~0c)x|>VbrB%{^u|NwuhDTjxhk z2caGX;_2d>iM*kO9?KcM0~xgr z$t^dfV z@Ak5l;0F;p3tjW|e{?#h_Ql%HnlTsGaFny};Ohe}wyhFpbv3)e8A6utw-pfeodXU< zm`?O0HL)RK^@C|NI9^<_0S4 zJ{HQkU)^5y`^Gz((Bnv?@Z`!LCQa_2T&~xM6T3FB1gd6QeEfks=aKPylPjsaAiZ$= zBBWJA|H%`gY!1_L)C%Ad3I;&a1EibYrlss}>oT4mzL>@Xs9&J4Xp>xS>ySAHt9GS0 z&M}3H25fZfjL5;y0&2FPR_hjJhm6{nOLTx680N%;f@+Qjl`J(2%m@(ZAuu4DW|fQI zXwE?4^7NyMJkq*WWU3CbDYiHQth-UY0x*9pNDz(|<^jq@0;XdC9BWmf^PSIJ(tm=5 zJ0?q>+G%+@TRXTwH7!C>lEAyNxm8s2GcdH&H%^ z5WFvaOGIww)oNT)wQFG;Sh2zz?7Ohetu!ku=Plk@d>*ReYxERb3H$h9z@ZzfXwEhv%Q!ENzv8nZ6IMOQOLR_KPac@ZXgg8kx0$)j-E8-O`?lh<(uAX{ z_{DWqq*U60SdCP`>QV;5t}j|!MFi?m+IAA0GmX|ax6tF{kzh1)>Kk%sgvaxR_Sg!H zFF0iMg_hQd? zQ)V`@DC=M{puiV!ga38okuq1NpVd|!{u)I;OQo#Fm3cGg?Ae|3e0#z}b>mu#=*$B( zzLcD1FaRVB-ZcUYW~}be<{YvDR`J1Hr|go0$fM$rH31FEMe~8-=NJZ3rOWJ}lc=N` zV32u?%ISzbI2MJtD)I^!t90=vZ*le(olO3*ZV}qy-4$SQuQtqVn+x5;NE_@7S&ro3 z23cbr6{YHieK$Ma(mlH`pbac!* z7rt%-_sH9sJ31GAGs;`#==u%(JSJ!PUj6W#nPW13qTAzZ$`z*#q*RX-fp+oUla0yn zG8_gN+|tkfTVrwD>>6xi$O*6)OI+v@{AL;Ym$}zXhi<=8aFt1zD7)w%Uz^oBKRPd{ zmU^hA*<9v1YesJ&)lR&E-QGH8V9*JEP!JmXeIWl}F_8wT7?xn-_RA)VCLpFu8Jq7T zjP&F(eW#+3%w=SH{OW6b2dIV%;Kq7Y6F;n75z;5{H)j;8);W4Fnoat2;8h>)=}n_dzI`Zv+^3xS--PDbTC4Vv`YwiA4pIFEWpd zo8-541)hJbJQvu{WjnjUo{8=V?HW@BlsZIKpCoP%4+!~Lg^+zr>FS%MN}Zo$RSxHo z4R0F!Rwm6_QAkcWlN}yvq{|Sje-B(U|=za&iSp$ z=U?0Q_atl+h|g)xkF2I|S!WAB)cOon_P&OxSTX(v`gqagPP;rX2nISU;AV%nr5|}m)*MS${gnI;WdB8hE1Q6C-ipnQjl8Uo-YQsGi$<^ueD)lO&ql5 z-2|8Y^!bEeE$KpJeiGxcJ^Ra7t+VD=MFJALi1VY^AY;H9Qijt_V~2+Dyl!=jlwmi4 zwY08BtS70Yjcq7o>q1R)sVqGwWQ99z#HBraU9?Hh0{$TKMzl=0TBI^$KOq(^Q$wmQ zyQBYWF*u$>=C(_42RMM>^Ka_jmLE?FnV6e#MX+;OLpBxcu}FTO&(P6C9Wasuld|2{ z)v-Rma)*TuAbi+(tLVsbxIhtQV~9iBz_fnC zDwCZ9l9L)A1cH|hWe!YY4AA{|`W5#v^(}wFS@LV;WdRmA9x%lAaaIS^O0awTRQ!CT zL*9o2&f_~#-HDTB6I8qDL^S)uz2qXWoK?9IoJz$!#Se%4SgWO$$Nu30UTTmE`4suf z!;`G6@V5)U8{$6mPzqXg22&`)d(o(^iPs}28AN0jB}4W@3bV<7L+N z5*1%{6{|z$b0KKOOeL>n1ixFlYpTXY;{~=|d(gde0N=9ueG+xnK^J zMsetw&kF7P?BcB0o1UP1IOmemHZp2Af$u38+>Ebe_oo;6Gf?RC>)D1Moz&n0AF^Z- z!I@NF4EUU~zTBYcFe?aB<0_+h^t&a@8L-qxv$XqSt7o?f@J|##`l2^7(A{E0(`aQq z{B^jSKj-2*=O>w;zJPM_?>32+1@8P~CMpwu(QU+=uw3R^x>2y4P7nRb2g-p4Ob7|r z2s>N?RuDym0E~czs`rdb>-_FVbiy4+32EG?ws%vaB{|-Cx$@Vtlm`Bch4ll+Mwnj~ za1!C}$X=wkuBKK;L5WKy2xi^VU)fv4j4~9ufv(z_T}lHbkz9usrDXp`QZpeyR)}aW&YBJ{US#v#uX8_;Oh)Mmdu!dMyEi4+v43z67i_#;Xs~4}p{KIrGe35(lpzpB zAP)UUEz%!Ec0PPgf-Y5AOpCFnx7b>m%q3gPEU)}(V}0+sKS_i8*UHV_G={6-HN0rc z#ctLxGyYsbD>m8_|xD4Zp? z^Sbs$#dof|bXq}RMrh>VM>>DQ-K@C*_)@M09x%o_04xy@A&a!9i<`Wk)oPHFIz+!V zpxq6N;_h`j7;yvwaC_IVc^pAkv!ooJS^X&F|Eomz-f!v8b?>k?hQB@xn6;m*My9!y z=py85cY=mjQsA>2hEH!PPLIV))L0A)>=i6)yp1!eaCa;mkZk*QtEE8b*lscTTcp}n zVt;_m+0d6Cpi2(ROz-RX!L|KxJ|t4Qc61J!7L72fnhL!dyd8;Nank&UOrx{LdVRJZJyPH!BKb?px!%^!1>T!t zd}zsj`-#vc2dQs{w>ML)g6ZStT#tF&TaBFQdS=@~+Ja8ksQ3|bd7zD$r+Kl5P#J9~ zJq~+)~Awdo8rL5gdTM00B=-Ue%VHRjH5|*!}%R2I-0FzCUE()Nomo>X!ar zl)YtC6n^yeI}F__-5??&B_JJxpdcclNViBcbPX`WfCwt7bc2+1cMRR#(l9V|=L~h{ z_dNG`b?^VKbzib(Enct|^F3#uy+51F)?=wi^Z+fH1_}~~##nbgzMYh^%}jb+h=6=o zldH*O-y)4!3)4bI;nMH2wszPZlMoK3lu{&??v(;FDI)-Dk87t-q3ZPnRliGc%D;k@ zEs9#nO66?+%X_(7wg@x_nB;zP*#r)`|o~^E02hnDo7(# z0oW`fF3WtsiNa=d`SkKB*$<*+y{m;Bap#Bgw)9mGffl}$RYr~MZ633DcdB}sx5zux`BGZA3=H~#PIdRx&4`?S2htbIiJR`$S zk6G=wo=mR3AUW5+WdD}IE8h$MYQs9YE_iOvvL>~#N!;<^#mn7~)2M4-*51}X;u*(I zX)?9|`hIDNrA;SXir&%Xs;1kub6)uwrbX^ZHlaI&VyN37xq)Ac>Mh`PrDJZq=V?#l zA}TfZV5*H2a{##{J{=u_T}XTMuC}GBQK-vgMzVR{cl(zZv87*+GR^8APKi)7W7X!! zQVlY$yW3^Qm3crW;`U;`f{aDeL_VC7&F29{;pN~j6W~Ns)noo64d*}d?QpMswh|89 zFO}~%=g-(WIK3>;}*9+Cgi-I2Hl|wvc>!w zyE2LsZ;Dr%+p_d7eLt4m;_CBF$)te;bchU=3CG?@#05|rnB`rMx6*^jK8wAee(^!% z?dW2+^h*`C;1Czx%jv8S#$7`c$_E@8SbM>p1e8ARsr%UJYkQA^Ivyu4cRz>feW{!BNQRPn3Gv1{l#_Uy) z!DJV9L=1!Z1v~fKzUJB$je}@?p@s@*!hX;-EVc)ac}(= zVM%2o_=OWKzoM^TYD105@K=LEPxY8uNcM4s<4%|4gpXeEO^W?gfbGc%G{s(eV6wgi z9HLd)eNhGuwK!GF9~a{Xk?PaxD!8-&)!C!HrO!kT51^|NMK_jo3v}n8}ZZDtB=Y* zBl9$nABEbav{LNypjzl~#qC$OMyoGe`ajsD2MR@a^#N+ z=q0~9rv4F#f)d%x*2p0^@rZTeR3~Mt|-X{eK=j%*I>)_ry^0 z(iu%+Q$YmHiHSUR{BJm@{&tTB@g0?~NWCHtbf*Jcl6XEUD4oPPY-xqzY@LaASu7>B%?=|Ks-Qq{f^`y1<;}2ed$uZZDBK!z9sz85ytDxZfSXAij-1|!EAN4ofFVxY0 zi$Cfd14l^8ex~`S%5Ujh?jkzKf9>-4FL2Da@2aUcYuh*d*ov!yof5K$$Dc527$n)4 zn?SE$5q|k;mBs053NL<+J;%d4Kh}yl$Z%BS8oB)&d!w+Xj!7ChlW0gU`yc3#)fnM0K&mjtdZ#M~Z7BA%Ea16$+cb7@$dVjfvu`z0~ZE-rR)9L-;nGu`*S@$?~Ob$qk|C+b370nO-VFKJf z#4TH%TiQEVY&K*k3Lp-|_fvYed&{ktka`JGGSzQ8*%P{bTYt9|Z;Jb5wExOemMI;2 zS>cNrnpvDN^~aTWE#*_Re>ev#uZ+Z(;``K}GZlFbYz-zjdE+0G*Zn-z$H01GTBq7T zRj`-Bse0t;Z1j;@_Skip`k%baz@5i z9VLc%<0T^2vrE_?o9zPX0V97qa%FLwiriR6r-9^nfBaPA-po9DEyBGri;f)Dc5NSk z^at{9QopDmF4W^6zItv32s0wh`S89{hc!d9pJsmitH&rawm+LVqjtrTa=7=7X!IVR z29Y7-_N)?Jg$E_sg60>k6w>|7@VowD&&ieryd7wNY0*`kYrNfAO^^8%dE4$`J4GaU zThPatL9eRU>RJv@*J@ilIyVT`k?R2r&d`TkOxz}E-Qvj*o&$b6IXY$@4jpuz#)rKb zy&=+W__A2QTBrtQ^R{)-Q0+I6{G=SQ2*Ct|kXJ=ClSMV2XazRR@TEb&HL&A_AX@ty1SJY*vQufOp-N!e~re@|hvVKQp*JqVI|CPV12@*MZF(m`P zI~dM&3a{|5EGjDGg=Kw(B0g1+I1?3?ox-anM=u9V&A~3#wR85AD>-I+xO`s@SzDCY zY<{a2&iFFN=w%AZ_?!V+&%~LJ8Z(-}m}rlUqbIbP)e0@wd&vhQw{9TZiQyTmvO7P@ z*3H9PG-4K9RE!&(D~Q9sJg2vFheljnjvW@pD#;_RgBADgbLNJOIpfppNfAT$7djMJ{4AL z0L*7c^8HelT<0lvAO3|oH)3D%cr5_QyXk#|z+3M*8Dv_?oiMs4QNY#BZ8^rWZ;l&| ze#N^|3L=}@Ifb8@eyP5jo~nM`x*oh?(E?xi?bSPSq86X7&WMe%FEFvOjzdTmrkl0Emw*dbLNj9er20%V;G0t zvYrdMJN=1u)M4nOf=1r<&%`s$WgbH3-hgZ`I8$%JH2lNZ=FV0-3FVo02XhCsG)vvE z#sFBhD(GVA&f(s3&>$BgT>Dnge_PFI*X|CszElTo!MHlF1kBgOMZ6DI(=h%>d0lz~ zOi@dX<%G`rcoVDB+Uz%PBnqCqEiC#`8-XQF?aFP8P8#3A%4G(`5W0K{hH3FtCOi{9 z`Qooefvw``ia`Q@-8`97y)<2;IS$wwlG2un?!KnV92DyKxDrA|C+BpkrS7*acxWsq zRUeVE9cR(}$6Cc<;*4h^UN0FV`g?2C51ZMkQN#2}lr}X7m-O%Vxc0N<`le%g5btV@ z2|0k{3)zj5aiy-t$KsAUOC0-+3nK-ajq6O~3)olw7{!tc0g+Kc5WCIib>ThN-FbuS zq4y=nnG^noOD>ofPA4HspqZj77b9=3dkL8c4Gd*hI(!rq6L$r3_1i*lBGRd~O8)1) z|D|(Iz<{nBb{=@g!-ibM3u^gi7kaR`X{gg$hJA*- ze0W}eQMO~9t!S@Cd#&0J)g!Ig39;HbXqJ6N)35ADAr;?zbd0L?iD1Po{K)gC@!?rl zPJdYP&XbA%RQ8h(RLV})%F^*%m8*{7*3&uQdlywytBuDk-{mrOSKp0|-?GFBQ6NYk z%-uNc5bF9oi1H{N8FL$uEV-J&c~iRCkAD$}Ls2+Se+CBc>o`UkFyU z6)z;WODD6s*)280lR&Dl1AZMbjLZk@U!snE>ruW2FIVrcx96H}T$gH!S8w>*VjDGe zwQj!R=|M`L^$nOw_ME9tu>LR}Xqiol>wOS6ld0DcZAbPDKeg8J~au z==~nyg@!Lu66~Q4bNeSgZG#j&L)~%^(lh%nxVDA1F5rWAKxxwWdYOlHPsfs~nBxI+ z&)*pGW>XYD-dPYegIkuE9@1tm+I=H)l%a;ts}S4(zi*P3#n%_}@n@O)2VJ2os738|jlToLNIydLO+9$e znl#*!KXSz7<7>d#@;%}%<9aPrP{N`7)h(+0;;LZ2!7W~{{H^}kA{YOBx>w}E(O@zN zNYp$7J)aP4SiTPR55T2QFZU#Djf@ypzl=KmbB#W{UmQQ~xj4-fFRQ#Osiwn)02TZl zWY-#+?)xzyfg@9S_;4QZggJDH^kRb1UEWGgycvk0lG%@i2^lpS{65CX?P8k{Y0TUJyiso6QzD9h2@}&o?8nn=7(s*?`5O{7_N#x#>-j>F#;s zhz>Gc_bRy*PI)V*$dy5r_H?E|wCB)e-}=2t?$s~t<+>}Cc&CGC)}+S={=v3R?{5BaX*RQ&J1M>>`gk7kX=UYZoQ{GZGNMdYd#0QJW-i%w6XTAPr26$-jAv&yNg3w`sS<7 zKfP_0nD|Jy?Z(FN+tE8EPPhkl5;sk7Dt{7k_p{`fHP{W5%Mzk^DR)=q)TGhEu@81_ zvTt&)9ite4OhD)C-@7p_&##4`6{$eB#64_1%d}#0kZ#yX7~N;LsXBH8D))hnbLDjyR@O-oNzkB zMIifg(*h>$s~nsRfK@=r1DQ-jE5Xo0B3vVr-{30>7^RoN1dzvCn+ZP0GG$U5l4V-QEvOO z!*haA_o$C-{d6<@OZcsm|IjM6ByW$ddgE__N>yaVmQ4J6UlMAEh7{%I`M-D3T|dGW zWI_xm%m-X>l~m{A1m)Fya8xP`%qmfMtyLLGU@@;2+%IdYQ$G2Q9~S7GIJl1L z)|Jg73~+Zm+8XrrF#i{+(Zor^102t`jeET@9_moC);2Vsnz+=((K9>bqwkP<_r-|k z5|^e}z1zn&88nqx7!#A{6go?bzhCiVyRs%#w)%Vs=*$S|t3BsGB}-*q+WWnP>7fD7 z4_59cPh2v_*}mKHSgb|V+)aozFSe)B2GpOV|((e9CIM>7UM+}HJ$SyQ(1 zc`}4}yM=998+l|xB|ru`o&iDJRvfY0ZgGyb=^Wk@iOcF1x2eV?f)8KSCi8p^EwVI< zXgP-h?WsS#PS+cQc3R44#Oepp!iL67aiR=L(kw|Tv`s(GX}bo9BisYko?Jkl8S`Xo z(0J$bvWoZb{x}-eQrC!<96#Q;Nh7zb=BHO)X$0Gj)qKzoAkeHQY1N0Qk5KODJGax3 z`Qh2-=s*W_ADlg6nwy93(4itF^|Gs1!ZCwqi;b5JRC5>bP4um_UW{>$|Ng$0soY&t zTBukBd}zj3`fTF-fPvQOe%b$ol-`1e{%%?(>QvbW3ezpICkjnDQHCpvc?Q zqr(irV|n=6%riyd`HRx}|sg&KLcOmCOa)XMQm zie7YZ@CS#0&+(a=c?QOl5iprDoODk4Rs%|>Q+M3&ER{NTaI3bS7m88%(}F|jz4DRI z;Y_4mgnB0z@(CgQdlqrY9ZdaS8lM;5PBci?u-p$^c@TyA{If&Zpn$jYmiDrAf#CeGVhe_N0hG0{!s9By{;S4<3Ol-`+3E zE(pT=7^Kd40je^D>iXRCoA@2}Xj9e6&>hAka{0N-LlK?L5rDjtI|#iUx!N~(J*=ev z!Bk%X$xXPJ7s=-Cr2^vEKUmyfQxqjNg0h*N2@x9VjG`G^l{Qh16b~Nzc)~QTrAs~k zMzD#TmbWbemW3>46+t=bD-|Ae`3d&Sm$IXoO!yChU zU;DVoy-P(WGwEq}(e(FNUB5_tf%;N#==Lk)E)H+Eu&e%a{ER#g-NRI;W+1b>M1pU5taf0rwW1!}Oq%`dCY$VKoVxKz#0r%P9HSV@?f0(wd+`U<` z5Jnf!XA&5LPit6%oD@zW985nMipF(`klf9a8J|xNXPV~38eJ_H5=|j$TCAta*4>Fu zOZWHpf%40Uk!2o00>7c84D+9+{+-na_ruO=xl=Z!lZ`QbkuJb&+@PAKUM{u8$T>qs zOA+u}rnJhnr8tyN-Cfr8YBPGAvfW}!S-hi8d~sxr22!lM1TH(uK6N-BbnyQ7 zS&+ZYe?HXA>fY{;$3{Zr|JZV3Q= zq}BRJ)#If#HYNf`8NTb26uNDo+4B!T06C#S4u{Dov58l^b*(Nyiul#`Fun#UUI6vc zPn(ygq%Hc!oj;k)9tHdcx+Q7biU$L>sC!jc$eARumCRIOtHGpiNq^$KY`3n1ND9g; zo63(cBufJG1bTUc-bR_>{HTtY^Pe`{jVH|mI6p%*0Tdl}O!yQ+L|NqZv^83Pyn_V3 z>4NNhO6F|3nK8(;VIi+@PBb zX?Sf5#w`K=B!2H=(eFBM^_ueR&(cjEz5m!b+UGdGUr!m%WAJYBABC)_l)}=u+kDXP zQYIz~Zh7auibUbC+FMv}NkGHoSZuO(9Ce1TkB~z3MmZ7Y- z1(Ei2Zi@QvJ&Z)UQx%z)b#Lm5g&j{SJ;jZ23;#w#cCtl>XaqWVnJ*s5JYCseYVKJ? z_F%zt^WC5Glgr#37D{yerICOTi{%>GMc=7ZA@OFP>VcaH4+Lha7Cu+Cw7Kwxbh^u& zdi1Nu)2}Eg3xU6o9}RjlBCVAMz9#FfJ>zQzwS<~r!ca45z~@WJtv^$vR7II-z`)A- z!LLsX?10~ke>I!oMrAUM4(sLxvh&QNbutQCdpzm!6q0jX#cyLU0@rNBaRJ=)6T}nQ zJGq_xTE@>5!3)2a#(%DEP!@Ya{5^0%43q-}cM2~p6FR=6o@htzbG}fYtI)AqKfL|& z7_5^Ijk8~x62~q1GcWUH(GNT7w9!4#A9)4Q`cN!?T~uhzb_p!SS4bZsUVk{Lm|UB? zUC6_BB8=S)ExV3qafpls3rBbDnHIA`(y8T7f@(|%|9Yb;sa|C3{DlgDyw3p6GOZTW zCyz$kCJs%^$S)*E+*_mdj&384+Hjus?E-@K+xac|Ey!ze>>!>WBW36cp{i~Bl00Tp z@0C(NSVKz(x{u0<)s!ex=D!$~ZBQd^+7q)w4@W6ignly&BENGwms)77;m$3ko|H?*_ozUq5zT!S5Pva?lArvrh+@k<|Mm^ncN-Ktw71NpEa8}%f^5j(eZS>OO ze@@TR3SFCP<;a>}+d+zCr+~EbmHs-d%jChHrI9RbRbzDT(bm#eNAS0b!~xkAFCS03 zW>Mm^4iNgIR8jHLivoa~H{KkkK-FMg(Ur z`KZfx|8hxRhsm6XG#7tG8xU;AA=a1AdmWmAF`pui-a#-YME@DA$6oedRvv`7RC+5-bBu5-&YvWw4fu&3N?p2g8HwKn>26WgIL%H6_n^Z? z7UeW=;TPgXm8lxHzM<8xFuL7u9v(#>M+@&uGh~ftJMHG}^~O5yJW7j$w6pyh7D;q! zx`fYgr~A1QGuPY`y6<5|Q~|Dlp`9f~=6>X?F2U}qr3rE^PeYluLlOPxkoht}aGdC~ zXGxVnTt4%!SN;-9sT%kid1M9J_Vo|qp6OUXW5~qI6IrtAY)AYWxuT<`DU$-Q~0YYv}V$1 zPUOEdTP@^c)9#h(3ZBiHqj@At^t(BueuhmE4`y+SOFn_ktNHO9U#;uJyWFN+L}+7p zj|7aF!U^f5N;))uQ#F&|IOxU9Izicy8J=Dhgp5S?ta@!Dv6EMmHP&c|baPt5iVscQ z$He!eH^fA@iuS)Qqc;`rS1~;}Pv^?~_z&nb2oEO1Ft&p^EPyIzP z-vhl{ypr5hMYI0oN>z69Nv9gROO>~BeC~1J@(Mnz`-THXFNRCiya4sx>mDEivT*VY}>nTpv#56=$bRJl9-i>72dez%aXGU*tIYTNBqf|Ve{EC1JTfxi_xqT-Ye-t zi6y}S&1t(`Ugw|>QubaGl6lWU{1Q0fYy&30S zJWdjk%oO7Rv6GIOJVlQH9YM0GQpo7RNtwghoh&g z!iU4123{JsdP??}ap!gMjq9j)J|L2%&O3-EJ_#eJZ0W21NXVcS)o=cuV2khj*iyl% z(4zDjy_@i5{N z;18^u+NtoMo6Y7+HcVdR$S_PF(nyozeQ_q2fqTAF=^Nj~s{Wik+wBJgXG%bDz8v4$ zzI;J4*NKp*sQ%=7keZ0eOXr+n=UdFEo8idIn;p8Rd?$>LTM{qKKQG9$N>h60 zBec5Xc4>-PmlMQ$s|KaAtFz<<=5%yEbqMW9DdxSS1-x%e(=X#&+ij&j?k1LspFS4D zqHh(y<wmmkrickbstim9hQ;e6^>JU!PUpsYQKZM%&g(}16I8!CAvCinme%UB`0`gs z6JyRdG3xf>(Zb#;i4>MoE5S}v6PxZ>gsc5?biL2LT!A8j*k8J0jE z^k76_rPrgV(aF)J*y0%KTMr*qEh?<7J>Vb&!*lkkwWs$c2XMbLO>R@zvL^jomfnsS zVS7yATBj~6yJsSIPYcm#XvEg9jhHrXr8Qp-qt@iJ7n44s5C9GQaax;vEN9&Ww5cRB2H4{$b4PBQ^wDW1--KTtLI;E#?nPwb9TyID z6;>$~>p3^8`Xk_z-SuA>$)4+*cMUh|4?&hsHO~D{m;{H4R2gTUmi*Gv9hjJ^jIy@8 zij9E!x6&m2*+nat#3WywBG%(_bxyyO?u>HHfpF zFfT=Ju%a4^(=3vNBKtRSEAB4kq~5h0v0&;W9fCdj+>$}reNY?n9xj192^f7`H!qmY zl<}~G)BRZO@~%SGm*t6^Z4G2j4k~9k%eHUdz4_ZT#XWaGl`bi0LgPGV182zp&c)RH zBuLCp1l0N1osVDoA~o98rp;wdWNF|y7TxYWfHeieRC-G-J97qmX(T!0TU^F@;?GZ7 z=fwyELAPfUzdPIqsEPJvvP*=yMeFC5djeA|xC~{v_n5JS7}@cwB!ZApKHihpavR}% z7SL~2dwCIxAPACj!W9%cQY5h*J`#KLgDsfKi-~RH_?=HXX6G?_LK#eIt2SVi4{8a9 za9ZE!pKuAdhTZlGorOTMHSX2?ZjKuG9d5wrG2tKlc~U%cuZ&b7*N1w+wVQS7Lc^dK z`?oxc31Zu|UEH#Fe5}Z(j-w+vnKRXHPd5hHT$bRF%h>RSFk_oFZdvTE?%ko{8x5M? zt<&H-j9M^~2N{zW>q=y9mvl*-Jf~)nEW(E2K)E*tBT;d3?S?%zfWbpo_0HM97)g5JuT;vGGydp=Ct zxn#}uUg4%jl4gz|NS!E2RVmXRjgd`xu$E^M*Nxbb38c=VI_>NDRa68;cYOI=nsUzd z#Gt^aP*6;@kB7}S$d7R(*VooSS`SHyde;s3ovMike+e;Q=xF$M;Ij>u5o>Ye1iZ?4HTg_S09WG0UB&e*V$r@_#iF! z?ODjHs6TOL%_*U%VLBY_wfLiNxb}$EzPf$0fkJhSK{=h@3_sAJlZv{qYsM-+%@?(& zh3fLGTW^}5m*r(Yd&o4a3}>n)*w<#avMDs>ZPFRyF%O`q>E)tUC#~ZJoT3u6BFc9R zT3b2$otM50w>R$LZ@M#XG=3VZ%lf_L)@D;`W4NM>GM;a%AE+y*Iy21p&~F>p1g=%m zmZ_gA-JZ2M;5kSt{54r=vUB<_%J8;{CY3Wg``UL{Z3i8FRm;=Alhy^dS*$LDI6GPE>&j78alfDhghZ+J z(^57$4eO;12||?t%tUdnyEVrzDHx4$tER!XRh~8t&(@yg$AGM?rNb9xMs8`Q$$=tx ze+&H!^F0k%Cgrv3r-cH2=INd~aHB=*4MFgO!8?H3RJzaj;r{Z4Th<&7-&sl%G+Fvn z4*0oMNr{Q0v?SXsB5C7`uRm_PnN|||mFC5xt$!k$r0%m{JWFiM=w<@CiH}VFP!^vZ zN4W8#8Z=bfJ(cYP@jQ?X15a%&em}!=yTMY3mz@PB+mB@AEl^r|vBUIK2398H{UU?L zw4(3~HxWWdyW3zRjL~T?vSFwcl9HYY2-34^o<_-_ihnn54~Z59>gOKQ4aZ7cUkjh+ z@A5S`drgM0;Kmg@;G5NAPc}0T;cNkeC6|6We8OyLEOtEg)sQhaL3ZW4ol)xn;+4aL zvueJ^;zoGDYI(ccs~5)v8~hnsy7(Y0Hf!57{w6LP0s#yMlmwFGKJfd^TP2V*&=bf zzT=I7_(eKXzu|a_124q!M7k#>E4CF(?)3pVC2;Ic+YR&Bv#U`OVYOn=ckD8DdsBKh zv*7P{fR)p&mx|E8YZCYr{QaPxpB*3iU3$@9hvEy65g9C_yS&qxh9Ba9q{XFM+%E#) zwz%13^2I~o{X?sC&hfsPD=fA`s(-oS{m2cqrlBvzkv7r#(Qow!*&CSJOjlxsvz8(A zAp^THH_c9jZ}`a6v=A7kJ=|+|7h{>S+WS~=*UALRCk>D}3@7!6Zm;FZpvecyijH0^ z32($!OvwG>XgOZm&1N&9>C>=L3ms^Ntyik=7(p@2Z<+L#d!sAbwP5vZd6KHr_a-go z7>VVmo+~+F?h){+{!K^~@_P4dKT(?R+6N*&QM!q+3pt`kQG&nFhd70%zoEOs*v3~i z`ZckQXQv12`q?&Xq`wE1HHX}aH?7-4cq+T8tDM|AP895Q_Zr{4$r<66t$1AnPxA8e zl3bV-*d*(Dk10FxPA|_%X$X@&RI`V#^A?^($Rb6Y^mB#tO7fj{1VOgACbV@$Z)}iw zHoWntQNp^5##!a+{3ck*R)!*GRS8Q$pjj?a6|GA7=ub(=B?@^ip9#QVM ztCp~i)f`Y0<-IssacNcjg7XyYXVv#|{bBt$H&#rj(m)jk?UQbEFZt$Y+27)bV&Z2t zgBL;&8_oG?wK-h=JCEvvk5!nuzb(HIaIYL+5_KGOqK65xHV+4*IhQ3Ib($=Po;%Tk zubRVQDRN|3&QIfspJ_wpO>L|wFN{9Kiaw@z-TrvXp%?L?>X>&i$}=JES|1WE#_Kc= zOZ`ty_prO}h(E{5={HA@)S0>eNA!oq%aoz?3lJUuK+Bj}zKA!>Q|o-dy*hX`?A5&hMGeDRx9o)i4#dp1ot$cUr0rO&4KpO{g_H>R11`qO+ z{(yahb+H}k#%EOivriR5DkSZEG_-o#+zUP{G>YBt%*0LB%SK@h0FS~c1)-VtUmM=E zGTfxF6=)39q@=!+ZtMRndyS)eW4S)%^C_9(`Gg_tacgofHWZUFB+72Y+mkR!o=ATx z&JU?I5=AlK9!~|Bea7bK5?mH{MhDL1gZ3ENUV3Sbv2Hj$F zqh3+FU7p(yon4k|)(1Sh7lWh*4HI*@X6+rfRw@VR)5GVE78a@DE5`8WdM;M#o=6?i z>_FU+a=qu20W%R0%D)n(zOBd=0DPAsouPYe^PnW12^Edfi=&<0atAEX)41}4T>>aJ zdwGc(;G?gLg=PfJe_ftPvr;GH$*|Kx%wtk9m!9e?Mq>F zo8RkPh09X+D{pG~(ufOuV60K*vR^R@d@+S6jorgH)EbJg9G6ex@~%_y)S~2#K77mj z0i)J|pY~^_2#-+Z{XU&}JNR*b5|EI#GJyGRX26C6oQzziEG);FubhRYMieK6T!z`% zbx%Y^MZ$>FsTlb<@y#=u#e;E`oWe~zmF0Gwx*bPNmbVk!+s4DXuhYg6!Rl$}e5wS{ z$M{2cF4EViS^lzIy{@?hoDk{)-^Y=+Lp8SGLX83TjD3eith3E5a-3y<2_sVl@WJ0; zT&BQ%8C>!z1%{tYx56AcP{M*odoB7MGQ%TKGB_6xZcNks>*@_qI%=xeo@;vcJ-*{J zz$H?`dzE=bs-yn3H5C7=M8qC6Z&(Dl3xF9CB2x^Fvh<6J3cab@+;zZvO<5*kx-C@w z`hNy7?|?K?Ijjb*w0pd-J&8$2xS0nZkTny1Uv3HsiK(wMS+RaE*Foe17|DB*hP#7! zwmVVMh_@-kMzh7RJK9^*ZZ*ZoFLW;E+dc5ndix@TcHX05aRA&A+AGRkqXV#<6B_Z?-@& ztwPf^_%z4g9-ToB54f))4Bfvo4IoqH7tj_~6Z9R`cZTg=hp4=kc*nDssQNEL!r?N;ptQGEmz251d zE0A4UB>q+sB|Q=hUQ7Ccz(HT@Yo^Eh50J>8{(Ep#bP2gg7?C-7xV3pxMCv^9vMn5# zu)*mx;YTY$I$s(rZ$7cX5x&u@%ZMBjBpMS|(_k21f45ZQIB+^vzSLh}O?ZlhSj{hQ z>t;w{4Q0`#vfSa76d0-WRG#_kQSRZgDwAp6m1c7m)!?-5>$;*_t>G7P8zGl3hWr{v z$tE7hH=I2RVqmwL`@qoDZoQ?PTkgc5*x=&*9>gmXBXX%I_d`{(qsrbz4sZo3@*fY` zcY!2O3mnB*KtX!K5VH zwgi{mLAg05=jrC&@5Kj2nkZ9Uut2|WhegigRvT(_r4v}6J3<}oe^nueW$10FtLbY}KJ&Z`6UUhW zqvZ>1!22k=i$D#$RhG2VddJq64*Ng< z0PDyA#8IQ)XnE}Je9cQHu@(~TlWbRNN{ky{1CiB=Dk2AGiNVDOMm`7L68>P1Q(^|2#Shoxq_ubc7 z+s|Un31lBkS}PDrK`v2k^Sf6GWOt>0HCY}u$#l83k4Kw*SSA038#kx0z9E6`bTz#H z@jm|H!Y2@e(oNC=%OjV zlh%y^Mm1@&zN*FlRya)Y>Wd9*_UY#So%F|H+f^;)>)1Co9_dZ}?Bhdn{*{r*ycW-3 z0d>U$KOGv#N&`$A8Yu?(OyV~f$Ip=o(mk6}8RcL&*Z^vRe{+GROZPB^opWW>kdsMN z689NZR#X_lC5sbV{LTXcFDQ6r{7PJ9wkL$NQ_uSf7covZY&+}XgYsT{TfKngnH-Q?4Gks_h!N04WZK8EX1@VhwT(k$0;)8)j#vU>G zGhg2SgWujX$Hvl-`+M7Y0=w~y3f-1znH??|pq{JB*N2#iwVY`a-qIiiSTpV;KLQaH zMJ`C6kuPsjdhBk006wp~?ePTcvhVIS^a$C4^d4QQgPz-Gobm5Id8?q(X8p8c41h|1L{z7aqsjCx#DlFEc5jRpyxN1(5Fxjk7CT$-I952y=VLZF+J|e9YZ{A zX5`oaL+i0yYl|BlYiE|m2<}VN~V9zLbUYM~deL`TWC zfFHxxN|>e><>j!X4-4bkH1?U0o6dnuoAJ+;Ql^Z8baZRVox@or9O@A6lhDgO26^A< z6?kO&%??k6ljm~t>~;(6qGG<`@`1CcPMZJmZyz&RRt8VNCjrh7LY7MkPyJd0|1$;C zheXC2I%nq6#B;E#74!e(^O4EQy@3&gymisPO_Q+^W5R!Idt7%cW#N?c4HM5_#AXBpd0Tw$%Y`$4t+`-LC>wuhG-bqywy*alGIPK(}Zy1sph`g zeC@**#NoUP>CYCaX|s+v#)#h>`whka70HbGw)Zv$)Y$M15?HK^ zh@%zO5!I=C7c5c0?hL<>*&d{|e}hReTHbE<0wZo{s7yp-Yp5<{3uGQSGP1J#->Z zDFet7nDJWIf-oSq|3GrVlUL)3T;KzzzZ|^^zQ+6~>_QxCNi(D`6y_b1waMUPKtv}jZrg?y4>kHx#iS~3i!Ie;Gfr339+`@HPwVWwoOa`=uh&aFQn5H|M)N;v=3t=hX6wt zLUf^+u&<7J`>AG4!;0C>*<^~ z7l9>=RSds>!g!w=J=~~^fRDPiMlg&dySf)EXQ8Hb8F%IzwO?S5kMH>uZdB%X-Nvg@ z?$@Nl9&>w)z7?xEpFh{z8Bu1i7MCDtGbh^$s_V5HMrdvMxVlEGdA64x%q}Jo>4z3 z8;skpV+;^$VQq=F2_eYsUgaIk6)cI09`QVUb71BaTfg9s3utP_p?$^XV4-$w1m6WP zVREEN9b*|%H(5z?#Sdy?wBufGio7HFUNXVwhgY=sk@y;w91Zt_B;QB)=OhwIsQw9zSAO^G-2!YC>T3csIa&E?QHUb*Q3f@c9#vBKX+p@L$`t8jJ#ZjR-H%4!mqlIrNl%E?c8f10&ejX;k5SJ( z`ftz+K~1<;*iyrn{_t;dMJ|1el&#<3?&0R^sg;gKTF)lKc=(dkpA(4%#KVRCcJ;9k zG}(V2HhML+>hx;xWb`+Gzl<0W_~_B=kbau)ITqn~=fI$oxWR|8SX_HL!iY(A_4GHa z1^=t1{cQXvF{u8G=wx3zAo!d=#E`)J{bCl+w^J$hf=w(%01B0k{S~XaiJGUXpik z{1O^HX#)U4?_#wwE(G7d>l@Q&DIMbzL@a|O=ER-%Q;rv=kE~rTUa2aO)xdvZLDI|< zUo!9C*jOds37ez<9s|S7J9d`tb#SZaw6!-gHjvVO0?3kGSuqK}f5+e{^H}$oXy{e&MJw`q%j~qNiqHp?spilh)&v&(O0Y$>z+RGv8qo0liO3X^a-yd(NF!p)_u$R zM-PIcz=o#hbi1kK=+WO`m!t_EIl`#M){P^1_1i5UpA)S6E+|&@^m?JzwA6Q7zZQup zyqGgyA8f9KN6bAe+=!O9u6;D?JRO_pjDH;a+ZLAyoi~{Yj!``-pW0PM;uu@g zGD~kkarBbhj9pjf6vw`su6Opce%Fe0PY>bqOI#CVZYJ9Y>X*_HJQDdg0SeIybqY=U z&1rx>_9o=zi5}pMo*AZ@G+F8vk<XfZix(H|7%PzEy`Ux0@HKgPpq8uGKbx&!U5Jw$&c;Zu$O}jW z4M2+Ob_Pa&YD=WDDOQu{+R%-m7kd55jOxBK@?qeN+)Ng2!`C1r9`ro?*vw=_K~(#u z5mfT9{eYhG2J{|qSk#zy5w_hyebazgJpoB%8=2 z{XO)s>7>3<9&C+3-&G52N>|^wqeipYIG^6e;Ye%cQ4h6f8NFG@F{2mhmCcPm4#Hfr zylafH-u8dtH^sV1zLOg)-N5eU@vSUIvlKLoFx$0joF;w#2$Yt0YZ%)_Ve)lfZ=l40 zj1g@MSl3nf`2*gt13+!6hN#NcHPl!@vFmT@Gcm?KG+w2vi2FRswfUYr)BXe>BETr_ z-!BX(~&{sf+%lO!u&p9``H20jwq4R7nWREL&gP@CZ`yaI_uRzr5iB4 z6H!L_1{)Q?@7KujeqUf&3U@jy`4d+H^!zn>wDj?)ZLK64KL){c$}vhW0(GoyH_WV7 z1bT_CFt|1!N`=wO*X#pGW#c|y)>`u%4zQ-GD^>Dq3q7=2i}ipG_}N04f!2IgZSRyT zp}CspR*p(UHECCqAUw8CTtLKHS?#&D?w4on{D@?qqs_U=xV(QxirKkX!tn1f$KAiRf|zek#(S!{oH z3Uh)2(0=N(csjPM>YAC3mXeg_hV>Ci_BH!T+z51wes3^Q&VM`d zzyHu(R_)K%wFa3FGHb_%HA#Yjj#n|_Oo0gP?ugcOL~Abd7KdHxh}C#Zz~Z2gdT4mQ zD{$78DqP+G0RJYO^*bTu?Ci90MFuoNyEa%HY~en{CQx(UB_l8ZXG@$D+vPrQ$fW5Q zu7HfACAwProOtQdmV(EGCE7O9__%V9UM3w%UV)l3HoZi_!M2}eV7J?!G!lt2H%-_b zYoR2ACm{E)%Cf-stKSuZBieBF)}qa0rJt^|4T3N0H_GWQ?|?gxSk+H^w*Rgq4|_^t ztQK%1Gn(mm?k4k=XYCTiH$tZ8<=kp~nR+oFYCtFkH@5K<)U{o`jlpl%gTU3NH2j2y z1ZMRk^lq9uv~r`?c6!BG#Ol(fyA;Mjb$Q>j zmTfKQ`IQRxWoH)&ONeh#F|MCasdcJPT^3I)aTBs$ZEYV)xlR?_vIyEErpU%bD}C)0 zao_B>B4K-x-S4rhdEEVp((VH_1tC48auqM6ro%CwCtZ;e&uuQnQ0UYQBW6sw0JB~8?K`up<_C( z-D;Y`#l^)8iVFty984`-;?W!jDQqcNEwsgNLW*^@Lr*L(ciDMud4}uUsp)Fa6|o8M zbZ1w<8Y%4kTR~0I_lR}r0&^TQuFcwRpwJ=$d#2FFzsbE6x4pR_)h`o^gYj^{7-QPw zJkmjJ^)0{u#L*pb5PNKUe76P1gd||c-3lPn)e~*?)1cJRp#fw~Ca4A90P$Tr;opT3 zD{ReDuk8EJi50e2_g_A@`rl9V3QtJ)^+n|}|I-AjiJCz3e!!Xfl@LJ4g8AQJ2!JAzTASMaL}b?K>f_xSQ9M#>s-I8Y2KoaW3Yb+`GO9 z&x2H4d{#xSfLL0~;}bc2ZWeIFSI7U7650gc=5MPqal_|GBsL0RAg6M&Eg1?uJ3PGG8D6F!8;W%8@W8H)$&u>=%9aehwy6jl17}JC(jn>R=2V4MU38Cxl5k_tBGM zeM2v8B1{keec)!=S-8ot6K+#mA1I!E5tu^zvDP1>$<$aTf7=4yG68IhVa1{r^_#{L zRu9Xs6pT%5s&`PWWNq}}NuMs2#bEniw-p$u^w(5->G4hZ#$btZLOGB|zh$Q7r~K{i zlgb?39z&l42_Gwub^4Jr#ubHvPvnO5g$)9gQEiNc$!*hMl-~@Rtau>qHF;Z1M#n;> zo;fr)%@EJosckYK9fv{P(~x7G1kljZ1>xt1miA{xLatcld1|-n-LEfo>*d=uEwxe?N9Nm2^^EeGU?tUxx$?gb^kb8#e?z$A>XnNT!ZTrwbZFvg+DmBLN zPOrv1&BmmfI!UUUr*|xvdI}L-lv>3t8dWu6&;gltUJItMhJ-ow>WQx#U;O-_Gp202 zG=+?!RzFT0iQ(>44Y+uJr~Ot6>$~8=AADz&X=5r?6F~U)(ruml9>DL+Cg$U8!EHL< zUy{4j>92Lg>`{XJ#tAhLu|~_Va}Sld2VU8=nGJ!kJCbyNzcs64K1RW=oEkU4(g6!fpy= z)f@+6Q1l(T?FU{Czl@e&50wuVm=BN(@O0SWQysbd_Y<&L5E46?;g)V)(67;c`*eh= zk5XhEq*l$RBn@$y`;B-~-c_S8Pc2{Mr|VGdLj9xejkf`0umTFz}vF{<3r{SVPbZzZJ)2Q zA}%VCCv9#ns0HD2zsG^A-#2f;j&t|sd&=1!yLRhXU-ZSFPAQZjiV*rXFwGwY1`X&q z>VlB`{c>79k`=Yn9^WNw+s-oo1MSwtzel@fz3(~WF#Xz=cdTDj!{79zIZPa_E7CCf ztp_I@p_^Ol(TnVy7B|n+4jc*4k@XABZE`L3#h^ju*TpE7bBpH;K4xW+I_dlg#Q}>0 z25rOY!;vN49F#&VnP;anaBanGkdt`m?{^MDw9c z8DpHwGtAD0wa(I}oR#}?6|AF}(Q&bG`RLD((EYj?MAQC&X~b47qUUm|iF@Z>hH3u} z;ZW9=9}Pu6t4@bVo_D)IgOVo^ev#}~7^{(sCi+L=YB5jNE||}8&kdl9rf~_ik0ZP; z&#uZYiJgeRJY zlk@>h4sTmBMNggvpBJ_dMnrHo?z;JVoZYs`eZc+PW)mJUGCce6S?kH2>zhcCfbl;D z!Ob%w8hItpyGH3##`PpHm0TavQAZn%%RB>8_wT1ki@|Y8z!54lD{mh?Js8}+=8XuG zVM^=pNbos$f$X`Zt$Ywc7XN)R7a}SJC!_t0fFsFun1Na0^upVPozlp>$OqSntc!;# zIW3*=qQ~LBFP|*Xs8TVKrAYvj4X^WQ1HU~y{1RAAJsStpD=vJ=oo2H$nu~W=uhTUz ze#I}F&dohzRw(~*He_cgU7~EG_F1l*LKnC>UXjGFFLC-Q+Hp$+MFz$o?EZFlr4KHt zyyNo(OIEusFTBWc72to`?!WWHeb)Ao1l2tGy7_h8->%}oS*0|Pw&j?>)p!cXzh++X z-Eix9kHmNHPMIt1vmu1z^Itk2(U%inBmnls=-c;tLJzW`4g&3eJZ#c^W~TE>K(O-^*l zuC)5e22in1rx${bb-F;4g(xEJspHNK4+kB@Lv1_@SDzjF120u`S0A<_%{Z33RSoTA zpf_?*lt)j_Hb@!Z7wBDS`$y*KZmbmT#t7S&xQB>%j$-GL)2k3?r2Cl3&Q zYD6%pY%rmPKVG;ocs1Y`mN(`$NGtwg-us+`7U&`x5Qtc7=8udWso7v$&QtnHxA<(N*WT7M)q_wr3$@RaKP zj|f%TuW+fu8K)55@Y}Y$pX~UUPfDsoY^CF@niiKA18+L1NtP>a>GJ7WpqS=Zc2#2( zEQe3qHRaw5 zd#L97v*1OCoO+@5t}DOm6-~z*ow9S|WgN>!MmC4$Z$!y8nJ}{IA)81`mr<%%V`;(rED5n;Y{z#Cu>Kr*W0i!J;4IT$*OH($;*xvp0{>=a%H zp13(A&Q-c1JtaeqF3n3f1ky@ncuRh5CP*b&{YWz=v(*L10Tw^Jqxc=>;ey1(KTOBRe#< z7Z7qS<#YW%OgZwisACKbc+FQxSoW&)fUT+b=BW3HAk>%nekD#Bdq<-@)8RvKM7#o)b|fJYpJxM! zWl2+30q2>bO*!#3?OYlNd%0R|bu z|1>9fN1VHP{^~i8pzS4%U(C}tdMyHbs3X*YS04fR9gbI zh(LLWi9AGmp}}3-OSI8xgSg6dgJ@UCUV-Xbygy9e@_*Evmdw^9pLD*a2r&N|*_a-+ByU*N+mTa08h)Dvxw=}qxTsbuc}%-C z9%ut}4gNJuG`L?7a_f-OAj)vBZd$+k&%@I#YHy9+jMJL{{7v0Rkbp@QHPTm_i$3DI z7c_yqqu5&-0*>FzL*I&MSLnHSz7u6`Ya7G~LFedz@4N2C!c{}vNb1RdQ(Yc87MjpV z7bBBkKbn`*Zl^wQ=7BoFK&gxwZ*l{k3I*6{w;6<&`X_9DAv}BtDD0@6T4&p zs;=B&zko}2*x1(FJEV`vQu?XgR>p|x%?kZTZAfne!xoCHIC?Ti9P(0YuFzAvOMkPj zvMg~s@U!?=N*Mj#Wd1!Pn)w3Xih7S7o%>^QR4lg@wr4|@#ipc1&3)E5CO-4OJc>}Z z7M_+*vKg|zf~q^OG4!?QN2=(A41R)iv^I*n^q?$SZ>BCJ*Bwob6>6KSx&@#w@_ORF zmxhRSah&Q)KG_SX$cuZW!d%9IXA8n;4=l}#(}`XPT+8Y2un~5HYQ4+**vY1~tiDQr z$s`rvGxXd=&0p+((~pTfjltm-xT#;Dc@b6kaEQiM>K6g;y{TKY-N(x8>b&*MmfY0_ zNcD_XvOB0?%s4XG(0!X{-KtOA5Hm1KgFFT;Ie7%pfAUNjS{Bn7<+-QiD>F^s?*MR` zgVT=;&`eI1x835W6yJe=Av#1Y=$TT9;$|~u7no$Ukkv*qO5qWwwBhDoF@m}~dA-mv zX+E-Jo5AuD*ETXUHZV%{vu1`|+tRkDlfstyaAw&GjI5w6{d79PBIEP4R_r)~zrJxd zx{CacOq6k4$%-xvDfHHcoU_m<*413R`A?nIyp&Az&Bx<-T8lS}>@P&QVI|-FEd3Yn zf`QrDV)tcT*i2O=qOT_gRFwy+<^ts^KNZ!?5v%A2Y|riN8rR)}`4nTtOVWWKD;57VlL-{&tGUgT{{D+SzCQ&ukY8-8H2902Gl>l~NsooQ@Y8MtPFH~kY# zX{&e!>uIF?xmQ?5x`zl`bQdsjpJ&u?9^2b3`#1Kq-)wU7b2I2ZfOJZCv%u`)4Qw^S zo2Nb|ZdU*@ha}q?rrCOTO{Dz%8X!SfFO4RWX$8r5`Hiw^I82F^*{iOz->-#l`5m7n zG8(H|9y4)O-PAD{KyAGJeAM*wKs?glKP4w`pH`y>QBrO-5PUl0R83lvMH3Fvi4z+v zD&F}nySt5eKn4kV|6HKV6*T4GsnyP7SFL!z(v-tFHe5R2V5 zLY!u$1aN09qNHl7_$ywHn}q?!v1l%dCE zyt8gmVYFv%Vz+ZgK9Fe4@sT(*@XxLh=Xd+c)&Ka`|GRSA{!aOy%-Ijbnbf6GFt*o^ z0rO>7Lh72G?QoN=cof8#;Xr!7jxZ#6X8yvSS8*Bqc5_lyMW5sG*_Wf8n+9Kh2xvja z(?bZ{lhPN*yP4D~-gzUs5r8Riv1LWaq)6#hzMIgspY6AO2=t%?VQ9L>V_;`?6kp(y ztmEUxozCOdXj5CDmgU>^#7AdjWD5h|@Vaj?Tm``dwwVN_mL8aap!Lyu<6brru12gm z>@RVHkbV560~(ulm<;-Fl4EP?$GU<= zatidGe75wx&RB!!C^3vl9vdJJ2Ba6{qrqmIt+wwg2=3^U2ZTfFg(0ny(vb~hn*dTh zRwm^A1fH2UusmH(%CqCzxq=fteOMJ--s?WC8v9@~@novkkq`1@ZCVxyA(E!%NwW!0 ze^)z=yq~JKL^zn?qg^2VOR9Y9R7|r~eq~Pxmd~$Her`$}f#h2}3x5#p#C>>91N4Vu z#&0o52)z138=E9wMyH(#;>pBZ9zIDMS5A~WI_fe|55_nA##P;`#t{-#SGbqncTEa; zZ3sSp^F2-(^L^N#8PGZsh&fwt$P`6=raQ`MhIpSG=kn%`V`0aOUq)14OuTJyDc8ZC zK&@zt)8;CnO32pA3Wi5 zn5|TF5MoH_k+#BE>Dbb9{zT#Y?!WyDDL*9H`#(#&dUOKo)c<}E*B|S^y8iedOZx@U(mn^{4%v{BUvq;imI1VF zfzgVX|zGx}gs4bF}z zWMpLeQ1npM!vGRz15b<+JSDy>hvdCm)%GoZb#=)xC;bX?b^v*pbDlZV2#o-bZ3S(v zCs=zlZaGIrL%I!jBSC@@sAnNC@vd;}B5Z==3ii%MqeAKm0q7FR!72Yz?rJ0VjPcv) zEx5I^ySQ;Iy^PG$U-#_Fg8s1C%_DImTXq(D;Tpu@!2?KTz9F>SHPVgzVNmz&C!OE+ zz`J_wh4&)a#Hf2jZ}7<}lhT}%##{v5<) zTiwYNlV9X2Sn|FM(=HHeg!vi~{ns4}e{BF#v(;Op!W z&Xu0T20jz^&*bMqxlj~xNFRoiE=>~^^%g(0*|f$r`cU-{D}M^yuL&JMHSZ6ueHfYZ`aj|U-u zbdZ;u4BCBCgmR1S6Q0aVrl#g_)rS(UZFD<@l`|(wNEi)%!9J)nig@;$iGx z2>z^PCRTjBfwSP~U--sc_wUm5mHy){pA*$`^kVcQJ#3Kx710`yJ+zQ8syFpIBz-CS z3U^~NGngsQhqfW!WsAg^-3&1# zA-vdtMbysNb!C{6n>&qskZGdw7oe!znF{Y0(=q$&1B-ttn{<#!zhBRh*M;&&jhUa4 z+ru27M^c6LyL1DJ_Jo!31@9q7F=r73ByHvK&CA|5e4o=1WS_+a5q6FJkH1%mEp3A$ zJ9uP9>!yk#JNHfZ`V!887NvIJd`Wa&`m zukY7!6U&o=c)SFyQBwgqLZ7H*AVSU`fkjQZ3|w5rmkp;D_FMA}JljVyk3?}28rp?d zeQUyi$n$=h%UXeb7B6>2H{5Ex@F*w~dT}auWTrVklT&61r>Y0WU8Fapss*)}N=s(f z^Wq8jBHbmw;>bqv5510%&X9|^n3B<(XH3M$Lz6|__r(WLUikNDVUQhBvq=UQPO z_5j$@Ij#}jDL9F}{K{_C`DXi>DDjATI*x2jZ#_E^%^DnYN zly>|XiTzZgX7<;!)P-^;aY%JL2Xw9FUa>}qqhee+~yhQ(7R$EAQ#f~mUS?z^=NU_10KY2qKq;vlf{yv)BqO3b=5D3 zJVYQ{x=qI}&NAhP)i9pyeuA z-lZ($k|Sd_KVr?T+G^VfYWrkqQUQ$DIWzY-9+1JxtC=D*z1yRZm-ugLgjvY1%J?ph zweu{*Ooc^_KEZdm#cqh+c5c5LHkGoYoV5-9?-L;g_3jiCO0woMe)ICV2KF=P zaGJbq-BANqS9XE{+M9o=2DI0T`BN*Xh$uCW?Jw!^H)pLGi zjo17||5FRJRR7ZWCFjb2`nU6Wq}bYj7WA$s%3hho-n9RRgZBRt!@=$7rz$wu{pxTFNmpWUI&q6Nx- z<(Te4G^PPQjZ|z|na~oVl_uA9cHe0p@OUPhoII~MZDA0=vjBROJD4>^ddz}Azh7^E zORGArv=aTN0*HCJ;E%E4GYy)*n-;`ze}4YAWR*)zlo?YE zcg;}b-8?@dsepMc0a>;d|GJn-2C#~slD`{&?2iO3-W?CwxBT1|*)Q3z=Oxx8CER5y z+P)RJQ?S$2O6xG*L-A!sUr;=4`G)gI=^jP?Y{MOs@4QyE*pX2QH{g$xdA==CH{_>1qiyTv z^WE#)6C02av`x0{RBFy^i=3iguJw-XYcw8%ib-ocjA#q}3_hS|!(~&Y)pz`obfpus z>Fbq29A#)f!(yq)?+#ZLk2stwQGOp3I&0`4Ipa%eDwLy>3$Qv*7gA}Yyc(V&NyQ}6 zmTFbE{RpuQByz9p3~DYebQ<4$_s&3#o9T@tIW%NqJWC$*1XsYQKSkEizVX?!vU+EI zV;5s4!mfcjlgNx#Xdg2i(VtY=EK!>T2CGn7fX}Iy{W3PK%sS-OO}qW?mwhBJca{jG z5STiaPnL>{J*&ZgOv?R68Kr zWO%v?O$~j;8mi;DrJsZp@08X3HCJK8VC|;aU;xbG!-%pf!d>vVRA4YAN~zx;;@6vw zS27_m#+`m{w&Pn8d2#Xgfl00@kS4?P>!0@>bQ`1+~u@wHpu;Uw!z%mfBQ36fBW|M zFOM0WxOU8&e=Clx?85-=DXn&=T4!$;%$eCTE# zc1)h(v8S304;|)UcIHWRmirnEhr7NYQ@?lpUu%ox7;)3#H#SWc+e2S(PxfV8kS9>X zPFa#UUu3(xPdC22S#G9AxWtS&5i=mVyd|EJtjTX-zuxi9FQ`vTG5vsd0^p4xi9;{xBe}W0tGlcPt@RM;=eP}hi(t&DyIaeCq8LGfaPM5Tw_JDYWV{AED-yf| zQP{e-5q{S(d=qz+Xu!ey9&P3+uDtZ#SqokqL3254(f^9V(FAr;afHIycvgCyI<3h( zdIAOwc+R&%F!_rkDI*Pl?E1>r=znn|(WV4Ijf|8sd(gQ=m(mkHi*638(q}eB#Z{0e z^?wkO!M1nNH3hJ;_0LN^9NMrS98l}arj;JmruB@?w8c%m_ur%l(?e^;An%y*p(UNR zZ*#|PjD!RU>(%vJ>T|OL@8?F_RxeDj$-z*_ac`@=^}zr?D%R2q{nzrCBj>Nd`#ZB2 zx*mqJ+7R)6V3Pxu2c|7Tj`)CmRTPgN*`eQv?S^_Z%-Z@2<%YRp75oLsoF=#EHU zk|$DEiDuEG7omg$TJ7t7@oK|g-R^&ymPBtS5wFRca5pk7T8pH}(FA&N*>al4N=nF9 zQYt8&$i{Tc)APnBUBbP!cSJ-Uy@*LlBJbUL|Hoi@=;24RQUuO|tQGL;&I@fN6X3o} zrMYKx6+bD8d48*yYVHyoOMVP;+s+^N;v&vM6pm&EBLPO`D2o5lH|Z4($EGIm^( zW^PKZ2;9;^k?4G&8WRAA#;}oA(sF*X1&H*MFBwfqx2$hId?c@#P;^%gmKs-PX!iFB zBfrbEa5f*6m3#4$`f!Cta^H?B#|{d4;Ry*u7zo?0)OV^uA70`db4wM z9t(dZ*{=Y?@M2?;->9^%YfTMjpRj0drJw<8g;<{nGEPq;P-|F;!))_B-&3Q1iEFhm z9>xS=#iIG;xs(Hmso?(fmYA*uTe%ncL1-dM=Rpyg@MqpMvOBw*S+i)L<>U5i_?AlS z!ZR!T1M|)09!x<{HDUw_*ilO(oEo$z@7wdbCX(_Lz-LVWc}FTL$~TguJt`ss{V&N2!qXTp0nzocl`5wGk@8ge_Bk8|HjDr8eC1LLT# zeaEEkSHN#MNQ72YVDGDy)A0s>X0kb-jfXa}GSQ;%jSINnhe!$3INr(#ez(~8t$c{G z-Vw58{aNld`!e2s;RQMWlZ3tSYCJ`so*bGH79EFpp?_{(`xyWJM-?1~Pp9l}$1`^XPG&1MaVxDJOYZ!9_E zbl~G5Db+&cILS)m;#%WlrJcM|R*P#JifGqXtIhNbzRJ7ace2G8KD@Bl)^Z&zc2$9c z`y6m~l3peJq+{@vz3`?7^uzKMRW0>x1HriNcRxZj2g}lCt;SGvvtI(GE)p5n8{fpT zP(i;KLphANhnI%SgIVU4PHD1Em^-rROQpf?98|$k-m$Tajkcs&)rL)8t4&SH`3HP( z!RX*LS4&mWOxC;CL@M8!#-PDp3G$q1gY%aiLO$2ssC&VcCvkp9J#plhd&7#hk!)@| zt!+cK%-*2_^#eq*}Bv-=Tk*m8hfd zV8DFD5ZGoa@W{yE+6Mb{rj{>U64viFGD=bS%*N4JJxLV0!)(1>kV%wsOyQ%)N75lX zB~tvF8AVaDD7{8#+GBomY!B{pHD6KGrH@prsjoPA;IB}*_tr@d0@CA^&4|t=YT6^o zwg*8=6_S^$_0wr*xWD1@u=hIoxCLBr>3}NY@(K46?kH;PW=s=3*1dhi>3uNP-AR!M zH4pUvxCj!uKUG%`a#^a$&P!Dv4tD7p%`F)X=2v&@wMBq76@A^-0S^z1-rB}RGh(<; z?|*Fb8&{GaLP)ouLq{WGg1S?G546}MNl>X^!eqGuxIQ$hZ|vSGn-L#x0UEhl&sH?~ zm*_^075S{SyaaFPFQCq!Ott&V8kNR<{sdaH9cOw>7>6z5>|Jt})_2ieGBD?Em{h=7 z!6MWmzQ-R-7zDjj8*{p-lIVJ0e)vpXig(e!n4M2==Ah>|8lAVZhFVZ~ zULVo}@hGTMaX~d6nPohRZ}_N6vFN}n*&o1<1hq0oBCjr1dtBBo4$W`0f4aWd>XL!v zLHP+kYCvs_ks-5U8z;o4%_tuVIgq1Qe%TeAaj7-}IlnkrCt{kmLfnYD%JuZk>xvEN zf4Qv^U)K8nADMch1DjU&KQi_8|H#y7Ay_GU9)lZ{8m~J*m_v)@RtO_3793bBWEIL@SeE4H_Mw+}@@LLKH>F!~ev;jD_ zT*IuJI>B+hKICQ&T*dyJW|_P|P9-nWepCDfSaj#7c-vO9;Y+j%^N?rj;iCv_qIE}j zq}vZFmK#*`Z_GPq&Fp0o^jU$RFl`fnt*f;myjKaZS@rs<`LU@yw3I}$954v{I|p(B zLtxK&)dXh9Cx5iogqAwG0PkD8ypgbvdKQZ5fQp1oMQAvC<9Bs$(9ts7R?Yoq++HGH z%^Yp~n?#5$dxM$}Y$BkqqW$Pgvlb*Qmi!l0w|$hnT? z8or1g%t4;KQOZxO5u#iGLYp3VQUi>{W?U`mbxrAGVi>myb{G_$dS5ed1df`m@-c*a zbo8%VuDdE7YclZaGMY>u&LbALY8yju=GE($cqy&TN`8O+tia!>KCMPwRNzD#h#>jN zx5`KJDwwJqt+kdMlpMsFt+A!p9PX2yWRj7iDo_PX{vBiS%Tp>7l(`Q~2m-#}b3(S4 z#4H$#e|%jLzwJQkIz&b$L)xtvd?8`iC#Yc`3kJwU&$Gg%Rxz=aH=A0q39q@Xop_$v z8wB>9b7jqM-;%Y{5KZx->h;`U3e@;K2t)%!U{QG;4$R(WQEeUVCDOnddIvQ>^YwB@ zLfg>!Wa~fM)E*?Unf@$UT6LoM(L` zcZW>(!$xGj)yD7gBeY?E!i4X@?Zri9Buy1%*MTKfvU~C7o-$ZpYj2p><9}Oo(csVq z5`1wZW$naIVE!;8d7)p1W}9(aVI{d|Y-nh7Z+QA-ZDz4{h;Ip-Nb1uGpumpVtS~GF z`w&ecxQ=R(a%%n@qcfS0Kd}JyWzUb-s$z>OBqG zd#oJ_h3=;}?3P3^3qZ{Gt78fcHMkVX*9?)mWECilN0;{3C2GL`#o2pCvmLm9|B1b6 zwN%Yk(bj6IO;A-;ZBe!NruLqRS=yqsM(h|xTbtOiYR{Ol1+h0VBGy0s-oM{D_y0cU zcR#qFMjm*OlPjO=dcR+7oAo702vCe#q=IswvPr@Li1L%i2meSl3R{04SF_$UjwVB z$nfJtSCrUiQos4IHyyYqM4^CKXp(y0$HQGZ(*rZ-`MJM2A`bn>Rn}IL>2lZ02adLk z`=Z#?YYurxd&r&X&%#6kmT&#{4p5G12#BiH=!u?k(qc>hU1W?lekQH7nXsFN%gqqb zKZ8&e7hBeb*e3{t61${TcL>7caog8`YPc#ZAROX>bN1ffjLvIh`t?1%>V!(#m^koC z;tF|fd9vJ*JEb19C3@6__rnZt^O;`UlEV1|kLNzsIBf8B<8cQk1flUz)@di@cb*ZYTmtpAwv)Shk^m z55&ekwcPv7h+}fX9Of!%j?Hp4@s`sH;v5;24zVlo@b;FqE7LLuLL#a{KL$N%UVu-O znj+xGB#eH%|9WI6 z9KbPv0k0D+QFlM(dfE3~hszpQ$ZY*twuj$o-I$z=f*t(~lc!#XPvQ~wds(u4FyDu$ zALBdxq;B;H0_pg=_U&2S52VP_{Zf$)qfuNxMGPe9QO)VWIXtO3q=?b<&Dnto6nE8h zvmT~wkHO9Q=$H1Do2c$xf*e769xEV-U1Kb3SInLgxh-yf?40+C7yi&?>9|YRea7U{ zI&jl5^GKyjoj&|sLkE2`4m_Wb0lJyGhv_Ty`925Ae7b>q4Xf!tQiW@Pr>^EE`lRlG zO|C}L)C+`#*TQ}F=Er3d!fwWL%G)&V<5Hm>3A(GX-AVqDw#x}YtGWGO3KpI_J_FgKaexJ;Ga7&P`R$EDHg9_Bot&216eRB@3u*v#rb zy*yEq-ZY^1b9`D9zc(`tazr?#5{p->B&uKUUr!z%e@-7(x+r(d-oh|)U{4`$nm@0C z4;G)scGjNvLi1hZ_b{D)U8i!!u+`+W0S*< zRW|Z&_W#n6QY2)yfrQ8AuDRL&WVVa1$D1V$t>eu<#b^w%iV7+@-2R!R5^OdI2*Obg zX}7Qt`3`P*EF!{fMTekke0l@e;+&*p(y^j+8q~`dRRG`GTY3EZK-0p=nFc*Bl4qWj zS<0?afOV`^2n69u_P~?s;R?wDn4!PA3)S^@i=yMP$$Ou!r2l~K%0TI>Qn11UomS(=P{_8e3yJy(}lh%Tj5Io5D-=B{x~Qj+*|mD96#f zVZLcdFIe4a%$)F(&*&=|ip3_6s;pLOubxyOwr+8uDeNR~kdPc! z`O{$2?As8Up0k7l)-nG(lUl>eEDJVKjaLuf$|+FD-k}hTPcWcyfkcS7ki2TA?U@@g zPVG=wCtaDh#s?=itjrJmY)bo7mnL1<*gq8}TUIfr{maR4M{P2wxMt4vN-=mS_s_%E z@xU*&H-Z=bwn|PgZ3X*FoV~zHTh2iqG%9$6Gzr6+(i`!cX+--aBIHIE;7PaI_Ipnz zZlWgJtZbS0D6rd+Fu(`JaYD^$Q{(%K@svjmtLfrok45cS*U#LYemVl5@EH{B*jc^1!;gV3UJqyXlRb$E%#ev zh9T0ymn#$dz7hd64Eu9E6GKJ)-s05<5<|JcF;P>%t?U?;hDx#38J|e<%Hw!zl!d`P z?->6#`h$X?zI49i?~W3?;%B`of@zZNUY-8f@Z&X}`r8zZ%gNRQJi#ox%a$l>q2sKX z!9npXSk2fd}kgKskK~|B1ItNX25Xrp*w2G zbsq<2{vy4k`AG{Q3n1S^{0#?87d%hl^!RP?8fmKS<<|>?KPCl1vZOSPR#I=w&ii-v zBwzSa+68!=KW(v~8)FC>Og)~pezJ0X*?h)>%vCqM8;Jak9<^-%G{)KrH~GGSEo3c; zBN=*q&kjBC*t@~&FldR~K5i6tMbqe-+0|+=1F0n`b2|HWd4;8 zmmMlXlsL3|GqiP*BsV3%v0-0Wnln(#^;l$ zfPet6jvpV-Wd@|`LYzo9s5D0L*h1Y>Dh5Hlw@={Mib21L=2+rQ+SpCCghh|P1w|fN zTvdRu#14Kl$Ln3kAVxUkq07b!D_5TR8TmGE%!S+&%ZvmuugVL+*C@wY^|Rh0>Yy!4 zsl$mBp<-*ljb(fP&5!yK$C&<6Q&gWCUj}rKD6omQInZlFU*|9Y=DK{)M6br!csqWP zPqwjmEtWd$9-F+=kE3-l2rfeCpr^T8y$Li|CS-qLxIKq+^Iu;=|HL|am7KE7jJpN8 zG_`*cLM#b?n4mX9dC#M+K z-h|!r+I=;X2DkH@odc3RzF%O{`P=)i&=sH)m%T>Mk#=Y-W;Tp^Q2Fi)NprA;QIVvI zkKkq2$eWrsb9xcotCK%e6o$%4GNc|`mQU3Atw8->pdNpQfk5^LN}|YENT>ZG^W_T{ zIb>5N#x+QORj#R7D5^>?7}^S_fLW_Mz?mkX5!8Osz6F_>!_Kp=)9hFp?8sWj zK)j&r-^x?YUP}&iCK9~Z{iGD(=Z5V~Q<3=AcR3jw*vYp8wid{L8dN)XaxRPYjr4y5 z#c|I3i+WXe$~*e~i*wWS&$T=Kk4g{-qnPVuuNC2gH9H^=%-*X;PhTJIm2b4#&@u0u z$HWXa`CU2z#o^8mKPznw%@Ab+i;RqjIGXHv)^!x_` zWLwD)R|Hc#9bHrD+MCosScSC>ycK5yp4;EnrgjgFj(rCpvM{f6nyfGXHNGm=A`&Q# z5P0NVws@by_V&;# zktH$rkQ7By*l+`18X8Q#bm>wdD)}W`pHrT)|Jgv{>V?C9u{y(1|rYGI^BFck%2JkT0 zcWY59O)?MJ#XMYbtt@%JcUErWoZ3bL)_na*J08)SQ-Ko8mL^XS^Y*hhX1#m(aKbm* z-UGd+Ivcs)mn!{Zer;P+naQmui*y*U^h1)qmTl@>#1T6~*EldmtD!>gP8wX_%mF{t zFg&a7yLx1{Ki#uR&~>eyDF6eUOyTAMA6i25Y&-o}X-7oz1=7m@cu8ClOB!YDh;Z(J zrh!%`jwj1K+^c-zJ-}Da4nR|lJJ>}k41{!On#!!Q(z58>ZDILNAMTr9-xT?f4-vx) zKyEZCBlXvh16DypH#t2@liroHZBDug9ddPv9Gst%C$5bbx&V49e&}0dT9^>`^VQ;r zOa>Wv1~oReP}!hj3oB7u{d@_pESKS!pRWx2gxp@W1zoxLFG52$@|^%44;FK3azdG6 z9(Ttfe=O?(UdsJQHu)&z4(d&}yf>(Il6hp>3KO%YLkPT0eBI_5IHSE1BXaLc5_qE3 zV%ZUVz6%R)_+E1y`6~K^9IOv(5D|{6!p~lg4Z9(&uh`t=OFOx_f3Mm3CZMl;*`18R z9N4%&VUJK+pc6#cAuT#M@UhQ9zk|AS58M&Mj#B^HL zk6oLiB!ENfowvWmQZoU5Vpv{AsG+!Yb+`IC6Jpq89IEdBvUOwaxz#y2E)BPw)Nu`T zDw1o3JuPLsmFyir&fnSZa~|oUPkneygOV*_&b$5M-Y@)Du~6(1DR%rltp-nUqx%+j zvYA`4wR`|Ru$mq>Rr=A9czd+>NSZ6Ra=@eIu3>vkm`!03A9Z^K&!%>8lYx!*4lnPJ z*kVMK8gRgfqaVB9@hI|`sPr=^AfD77I%u>t z^aK`&xA3M|SlelpLG{5ocj)1b)4h0S;^>nyv^2Snw|Ds%GW8wT5#jXfN@VSDqGD<> zem135WGSEh79caKn`uUysui-n?t5}EWr-SUs4Q*1B4gj4OdFDMkjEn;yHP2a%jq6z z>%Eau6EOBRxkEx2aX9>3_PsP>F$p;(Zc5a94sjtkNB^!Y>Bq7g`u*V@tcJeEsrUtC52&f-*iKw zfaG0BY%zJWYAGAh!V&TEty{J!b^Th%#Cs-wjnT1=)f&B28q=P_eZxc*1jYJ{q`h3i zil~-Zu83ZQJxY1#XOm}=c}72f=~#!zTQ#W>UV#|+YJ3o&?=90rAMLiST*5@3Yp)ul zk7nULI>2w03T*;fIW*H$_%+{G+RVV(WhD6(3I11E!q<-}nL=^O5Opn<)n)x#oSB%T zSu_qc%%^y1G%?`mx7-W9czWHw)r{mZy?DB#gc;A?+00XexnC~T_qFYA7(U{@ynjY? zpEfq3I0((7ZZ9ygbzZOY4U;>5?_y-){WnOj8ymbiWm->czSd;bgacD-iO+)%YJTIS z7jB=fJOv8a21@A?&?m|qef@zyD%f=)F@M`Eh_Wl`HoA)`jhfry|U*CQ``Oh3uE_P+!_wSyp1N*-%zcCIAc&`z{`!W1j z^&f47{deJIRr3jFxmZ^O@8`S1^O2T2cM5$2K@BYeq!$)#BrWraTn_+oP=Ng)AkygI zuc1Q^;`v%fjSkV}Yz^##71lK+=9R!hYW%3h0#DMr2?>%Yvtr69udZ|S`#(t;AwRfU zzM#GVRdGZa0C!jOgIk8bhp@k00pSIFh!z2bB33#gjqtH_Bwg$Y@Qg|z+bB7Mor9Rn zA}pNw>MMfg*DJ0gs;k>s=JHi_oiBfznTJF=Hznn1n(Ur0Rf1&vqS=BalD=#6`>u5t zXxp^vv2Hcswkj=)%}dkf#TAjjbh`}g{TRQh^`dvRkIedcP~^h!S;xk*<<0r75kR<5 z%ZP~oOJ0fJk8h}#Y3M7HKGRxwbHu%GO>EE_(xn#%k|AZ%dBtZpo5gTn`OLYuBnN=C z*Q#zA3M=aSNx6DxAQFp9bnh+9Bz=1$R-mfYK|s}EefN(z)$r}>vBb28Rg@MSqqR2t z)l&ZDKP1xOz}SLJl4^9N!zE0VZ;e$npSJFH)W)HcPt8M!^v+u{q{f zL4^9gR8W!Y44I4EUy;Nzy!Ino4Tc5%>XTPkPK@&1HP#lp6IJ>6#z?Ob;}Ug~z`q3{ zK7b}W&8P!q4|^WZl(QkJ+)lZ-)tt zx=5la%^9%2d~}DupjQPW#T0a0C>*u=S;{bLkuC;VS$c{;1`{3jTHhO zC2%WZor(8#3|x<=^z&%=3O3dRy&vV;Lk2d&ZUt?m~&+(xgd(U@yp!mDp zB$>0+BS-sR22J}sYT?OD`UfPORN=es@ebwZRpieLqv_W<#Gx-{=pW(oiOTyM2M-Nt@(*98)E04TpKtQaGiz%`A zYSt9lfkBfz@qR;V>gGBLfBTr*+o;LJF0q~)(&jeG3mJk4-tEmMALPNy@4rV3;wTSl>{p#@~Jgw+;s`pqAAlJWyWMpPW4C zYW<1NNF)S3ez{O;%!mZ1DNU~@^mGVk6g^#Y_E>nsbtI(&)1OK*p{ngRa*&Zcqria* zhF|Z&_n2XU28Vz6TQ_Y3A6dnCZ3ro>=UFSvv3;JJo^HuGHes(f%ySG;B3hdOx}A3f zvme#I4x0X(b3AG*Y*X3<`Gnv|9zJ|1-8q6CJb4!qPLjh(bjL_#u%hTKhJ9ZwgqUue z@-^gen<+kgINl0%gpQGfAa4O?|5q2u%(AZx17?tJMIn{Nikf?4Zo^dlZi}YNSudKVoxrLqP(BCEE1UO;$Sk+0u%Raua)xd;+PKWkYyMys?{DlMH9nIS-a z?;<3u>{(P^~{W>oKnil7v{Cmr)wd#9q-=$;&&~W7q4DJAo3#8ycm6zHgWy~+n zt=31+_k9)*G^R6!7L~1eFG1*wx=y&|JOQs7i#b0B34nJor?U9kaLlQv9IU;KWnRJu zY5xCJL3V?j!Dglacy|_bC z7&p{JAMV+h!@OmjW75wQm=_=9 zS@xE(z4lrQjT(3+Y~?Phcu|;TVW?CXzr~-Fc$i@9s>RGa%DwpC?A_;_lc zG1;9qJpakQwq(Ba$fd2GMt~EM-mh=)0d~P#;%7%BnssL-oVqQW)&g=r)Stjr4`mr2 zn7p7JT8@Z6W^HIlqZ^@+_R=EbVCv*S-u!f>!}WWK!<^tW%JUk}`}vf%bsmG4-Me=_ zsEYpAkow@KY^E)DJiajJ|Kh}?wn2JFt69Ca$J2BWg)m;zi!KDLO>Tp4K>F6CvL=^rp-0zYUV)KBTOOtrS+6dellh-O)tzf%2ZSaIZ%Sj|t>j=q&# zaFmn_Nshl2Sj#N?YjAoca2&w#=^>j{Ts8QSSr&IQw&EhaGF`2|(^C?z&QFcfR>4A* zJ`<_CV>P%u)AS=R!X{Q*LGS)FVAa&!7^`=SuO!?s8lxyl@2g8%c`x5K)}6^WO0$t1 zYxHSqO{Q|I6QbpZ(GFfUHDW%wQH3cjXPM%DyQkoiZ^i%$aG+-vY+st*Hl*)xp9K{> zBnWllS{KLQ(whn^k+v~B$qm4UjofIDZ_mbj%WXol!1>dZUsc8bn+0(Cw$f>4@v)9c zk?FFx(~Z<;6Fd(6)P+OD2OU2S9w$W!!Z7M=%ZDi&{Z(}v22sLRuCBeMuW*6$7&VT! zK_xG?UquU}T;KTtm1<4u>-9>NEYpHNk>2L4Tpg(>Fb#J7@QZrlgG2C)3GwVqsPi}_ zLrtg=sRA)B$IHLxt8r9O$ z#DRrPy2e|J)W5uU6PvTv1()A<5=m)w<{f-EtO#}-gNjd^#dJrCOX@9!+$ySg-=wfB zsL&JYO`>*gRO@cSivK&fDkLJ2K@onnQhMcjQV9bOX3I}V7U+G4NE3J^$Bxjd4PJjE z;$@64`08S6du9SXbQfBwBCCR8@Kz5Nxt?!2=I86(noug+RG)%bJUtngDD4&5whf$G zo~zj#I_=y}KHg2M(R;64ntC}8IjUU}`kjVM!0>y%HlEO2zUhCxJ*r-IbP-s6Z0B%t zr*8}fIjB(B@r;?;BV?3@`4+s2zzv;_LfDLYRNa-tK-5XG@b_7==d5TQ9yx})?oCDS zlaSCmm3om)3l74~r!JR14+8(oe2MyZGBypmqjrHTy_CP5XdCUJFSJ$&xb*h%p}tsa z)UA>S6S6l7EfOxWPxe2a3`n5Ic<4tx7bh|$XuECng3A#kGzLu`P^dY~G-=~D%QEJI z%`E5i@M$yR$g4+~el(BOFr1K|PI~DfyeF%^oQSW>Jl40ZUr?q0@=&c;qWN@3$`^Z) zsA81a*SnE7j}YLlC*-zR2qDGZ8C-3!V7x?2-#$t`71B!=1QyQlOO%HkrOGx6XZ*Vr zQ(?`TkiCDbU&|m%yM@4kL3}Xkkj_7^;xhvYa8IO!knZ|1BUBbVElCsUAjR=Ki0_(> zWjQy~Nez5%fcL<^!l$2pm)OZ{ii0q5fTzGRCyRSVyo^sn+5_0&MdZ}LK0 z?=F0X<|Ox$eRi*ZUJ&9~e0gW|TD$*=PQMa!OZlIp(^iD&^#5{gNF)ajc}(vGog=Bz zbHvz8yebKH4aMR-d3fwEfO1TOCrpjrRO z7@NYy+K9+P>kf@@gCLSw;-$e0DWWlw?=O- z%43BzkR+g(v3^mBO5u@&90k#2it%?&xn89Sg{imeWTVciW2Sfu;4vHn^n}jejBuAw z#pwZOJ;&SXrf}uO@~b;Rbl?7rzLgUqS8Iu?z0f!yLOVZzb522ro7o+Q8i-35L-XK_ zGN%Aa;%yaOnB4S?AQv3as>0^WK+)LHFd*AC+kI!aqCjV-G?`KT+vGD4fW&)DJgy3` zgYX;7rY`Psn7j=4E9hjhb_Bw;480x_n|v!475}D;Gm*+qHfh)AF#B?pOlvFg^Ypa* zPA?)LILI6IGW;-~el$4^0 z-{Q6?AbTKaQTFu*;#bshmJqk}iJz#~Wko!6e?OePrwEUTg|colvmHHreKsaq;Ot;h zK0s7bB9-pfhX>uFFy5J-Y&@ONH#nQ$8~ah5AB1s6SNU!~nP)&qSnYOZ*RP80=^)$X zE)-g2?RTm6%j%ZzNmK5n`9H8}D!uY&&gfD%*kY_Z7lMdyoXdjFyM&~N)O|mRsf0L3 zf;Odls^al3PQmFzFp(y?p@nq5mRjDMOJ7Q^KBB8-1l<_k?0cpa7@~!x*4sxUO%j~O z#mFCfep*`DFNc-3&S+LW4_8&!cmHIX zkstnbGJkrMAcg{NHF%(y9g3#l_nj_{B5`>PU4K9|MJaLNeYV$RItS>ddyd3e9&Hy281SjZ>aG zvtFHnc^u2;pGvZtf6@&?yY!~fOVoUZ!6204MZJYzSICV&or*HR&#aZA#Vq$(1t*Ji z9aLG*YT&_d>j68redF^se?w>pn``@Vt-g|yzAF?OpH>;P1iNU&KW@3Y+L~gP_am@5 zw&aO4ipNpb(}2R#WyS~2X&EA>4qyBe@v$4r_^urE7yThg|~xN8LNvD^9uu$MT+>x7$%;;S?UtP_A0ZdtVa zL&(g5OrkQO;F0m+Z6C;5%~ncvCmvB`JK8iZsjcOp)|_F!QIE2qC6Ox(2pQs_8e#tV z`&-7uc8xc~xtbVtGg1HL`QK*p5}W4p(rfD_5a?fMYo=C38&1fyUg7XOM-d?Z1Or~ zHb-F6)iT-y`0!#yh$IZUY!HSLcHiu)>136TlKq`~)>xzx^vU+3i1IEc&vOeLk4f{< zN@bX@F)Yc|Ziy8=`mL=lw)rz?17DvovFm&^wMK8e_Yc|}sRApFRm)uWH!-kFRTp;n z_^|FA4o{Q)%jecKT8>^9=&SC%eVNMS-*%!Vd>)=OZY<10Ky>ugs-i!;7#J;7O$WWE(>(P&m zP|So|dffv{iPP_MC*4L%lBR1ew)D1k#U^s(Rwcq2N0tQwCi!`g-k(ty7+K8uSi`0+ z?TDv2#2B|cUt2DOh&8#HG$>>zzwH;@_9KO_X|c)pz4OI=w!@!q2uZF}Dli_r^MN7hA8@q|q<*e(W{Sc}6R_D97-2rRE4PUNy_0-xU=cA)ulmn0;Ra~>S{ zcf&M$xcMC`{>@0V`ZU-R><MsEW<*C6~e4-B&H1ymu@sw7?}Q(WhkBuKpPv| zfs+TgTlpL^(AZc=~!JkV-bD^B%{7{ zYb+4bO7mwh zTcKQn03a~OQi({YDm$m+h3Q8J;QrUQj4w*xvTp6j-+V-D0x)}57P`YXX$h{;47Ds4c=xK? z!JNILBKJwP;As!t?adVh=9%Q53ijz$YIFFFsKCemXghC}8j@!HT4@(OTJ8KSMXHry z8RDLz-ftM>N9B04j3T_pvBpTe6938_O5-Up9rk2L`}h}hDd{~WeC|G1+VR1ULixAz zP0^rq=ACg6_%Eku(RP?Px^E+Y7XGu&`EQS7GfPAFd>49u%d*)82e~x%&{;P8V>9}W z!O3Bu)kjE*h0*=Gt$`ev{r$N2%iph)Arv#wtifC2H4-+k#tYArrBP-!JYe6gf?i|i zV4KoRwBedE?dyq8ar3lTZ0x)8>1dw%HZs7CH%n{<%7J7SF*{nT@Y}0|ug;HuGKAil z0IZ%cOcqp)YOm7S=+i--RNpz@6Z!_=vH+&G-KE`j8*HT&P`3Ou*J$qd&_8Bxr14TC zOLa@@+l$vBLsu^ZL~6dHAO7rJc?EZrC<}RblQ(}=fAt>KsKp;_BFOR2f;FGYu8X)M z@FCSYM=w-^vIKtDKsrgM@gAQniNr7du2|$Po4G&nUn)xK5cov%m!#0FR+&mg$`^{- zC4V>KYBuL~4`p2X;loLR+39QOx!PtK$asCQq5}k0*{@ULlv3tL?xmehp3Jf8jBAX& zGWSrenmwQNw5R8X@=^NbK=&tH1c#np%qzkQEuk^jAke?j9B=C?2mSqR!7xOxu)WUt zb@PGW#kVj$W^avjKlUI8S@NozJ7B}}eF2$y7rBbwIFwg7M)U59XK|aN2#TF3+n5@D z3@~5USwA;;?wx93HTZ6DB3X;1z2eGX&96`K*@T+Ipe7Nx77j=BL&Z`Zzg42d4PYk> zQ(v$&W={l`N3gGbE`P7p_o$P& z$TM%&xN7na@$YN#w(7Rf&|`pQVU3s7TnGNJ^}u{%^8mxwT`P9p5Ohj!18cglIw`ms z6SleDr@x-x<}sg$V}65!m}7?L84nw-3^R9jwg*g_32ml3fT718?3?YMe?|3$A0Xsp|jBd%=SLkMx4x^2>GJK(m(S zAh^VjB;DQ*JDjURiW3!JkT!c-T(G;h2kkf|WU6&1&t+o+b&eD&6KwrUHf2D>WCndl zy{UZ_hyC%@tJcfZlJ7u*gHO@8SDY;cO&27*1`$Hmd@gu5tHgOfxr)3uU`)U5nMsKu z`!b;m8}A0%NMBsM0N{TJTeX90UaJSc@8TR zx|gayMTP&_AMnzn zgwVIWoD*ktQ!itELN;gJ)}GeHN!S+l^z5#THgfw3)~BN-XEu!*r>oqGLYWEMhIG{r_^OyR^l6dY2?UYuBedHP{FB(+EUj_ z&;;&uCCJpEcR1*w@nL^1jG1{pYUJ-8C`j{)z{Cax#_WyWgqQ||6Ykf!ki@_P<`n`$ zMRpo=IUy(u%nq6}SZ?US{=;88=c$jyll}jgAOCyFX`zIy1U*fd$PK+`$rc0-_8dz3 z!r|I4#2^V6(?|g1D6ooO_?kl=ymmJPzcDDBxA)UHS4^o0d4@7Y((t07q_;_H9Q! zbD#mkXB`^ST}LLnmt1@LAq=G84B*{cPxv4PabK+;7nt3U&|2nsqOvtEqh~)yid(eN zcM1j0*I9+BWDS31C4H4l8)dl_`tE*A3$5vo$B|htC2UE=GKfA%k#h-2t|t5Mkx7(V z7lq_gy4E=H;wbUl4*`a>3j%^_&VcGr%Coudk4bbA;x)iEJNESi|MSo~{hSX;L~`}5 z+&GHDPlvmu2Yq%ca*;Z=Q$)WXzi4_6VUeiiwcTYpt6s_ZcV2T(Y=p`m|MB%I>@Q|I zy=BGj)tDubW-B;=&WEO*pJkimpWPA^KlbH(%kN=F-_E)<@>oaAItN$tf^E9w=6e;t zS<-OO8z$_D^v56a&-Ro;hSd7aL%$bC15}D7sKc2gt50#m+foX3Z;O0(&2QAR2hIriB?;^y{1baZ1j|zD!5wRf$&7*WsA9y293V=R$er& z=r=aacY>eJ*zU&F(K3y%VP&t+Pg2FA4CxaqF1^9VwKN+B*X@jYQ<`w5qWSl~OFdx6 z`Rt^U72{E#O#&m>Q?!Hhhw@88VaOC2XbR_e{N-GoRhJt*eHX$_EPbUTzntc$lvgDf z@PPTws8mYdTi*=q4=2G_*jr|{g^5OWR^8V;o*y~r?IgRPL$B3SE+Tm`TI{|XZ&c77 zJu(veF=4ZT7ozW^IHe&o9$XiOk9>kw0&CFdyvp_HG{4{AS%g%Mx_WJC(9$lRo>e7p zvLR)yUAC43B9(3AtD>uPlr{YkdT$dvU(11ArNPE-M5n1VsG^;9vZ{2tDyOgR6ATk4 z>|Nnt{3K+3O*EQ0TuElSbSx~eQ1-r2kYAP}dBdi|j-QdHGCvqVS4b4Mv1Y(4K3EmC zflqStrsInCipBk)F51f^_HDBIrf)8|H2qHBnBS3@1Y|y7(|khB{Bg!BI@q4xLb9lc zTuUL|wD5RdkCXqe!N*V1C7RXbKj+<=>Fo3w!XugCH`O)UYKkaImt!u@*kyn3H$vp2D3w3X_%@JrRyZf8iS3`1w!T4EdHB>LsuXNl& zP|$()Y)7KhMqTgR$!r5>2#8$khX0lBZ*v?A^;+lkcxcLPK7T8&NH&t$0P6l zdx>4KFrAc5+>Na@r54_R2AQIQQ|%+i+w=X&l{*=tJ!4^IG)!p}X?|4c_}C z%JiZLKPiN2fCU{|oFs?I$QY`vgKJRPPda~-8)j{^K|aFdNP`(ul8lK4$Oj*4f&8Z9BAoy>|YR_9$OjC1U(-XFOAQ<9rj?P}fs8Fs>`Gv!kNX z+Q1Y&u(Q3L0F%0pkAX>v_@{VzbVZr{b8b@p)U zTG5-125|H+<8eLAknGC&h-1biULmm9Q3|z(OFjP7g)CBMggD$gx}8UTkM&($#Cf0Z z@o>ZP4u%F9MPHif%`umA(KE4y2gA{yPGzV42wtyr@ut`!G|yGTkkAkA70?(bRH}&{ zcG_`jPiboso4#1N4m!ghfp(j4Pn~*M2~ZEE)2$@}o5K{EgoC&T5{kvmuv=Os|NG4S zKS*4zxglFMeS{x&FCTGQ+WkXYSH)i+H$MdQk_i_H19Al_d$<_d)l*FIe__xmN2&6~ z-h#F%Pvfp$LgYVI6i`;hLiB`$dzduXQif@P0%o>WIfFP8F6;{psj0by*KwJ*iaRQl zKk|E=b+>F(9JP%C=A~QQI9OUTt8V3MSGH$!Sfp!Nn2$F`|Co5WaUyPZYlNh3!+~WQ z>HaZe|L{52S2sQI(xK=ok;g^*Z(-3>@~ALFN1BNUDp{f5xxrkD3M0&~`eImj!I!2A z#+%==@+3cgU_}z$$xBox=9S<&qLjWtGkQqL;N8|Remx_B&Jk7|bM80KR%WNNdr?48 zGxji_v?RXX)gBqINh*|xpf#0XB1tpkYn=_{ZXEKjN;#}8*F5Ix6cHEq$+B_TjFeb&lbjLo0YTu4hITnWb6H82|*;L^wm4Xkj~lz*D&n#;Gj2qnJ*cG z0d-Ep43Y8lMb_&J$C`z9Ed|%e;4HbKdvUv-rUP+AeQGVu)*w9<%?A80!=@6(=2LjUc&rydeF zBWXZp<&^f7+9x6q-sge+0*MryvzaZ!^5w?z2J_Q@E4zMImjM5N&2^>AtX6MCNwxol&keX?YTX5`InInt6a4(|KM9o_+rhU$R;PIOVh&))W$RVO;zxa> z0hwb(_JK`G+ln!YO@dYxJg-Xne(#4?F((ou0>ox++=&(&oKP`vJW*rja4r*m3`K(J zRmB!yI%TAqoE#hp@6xr5IeY!Lu5I@QG9Rc_oFiD(c2g3obocrklSxT{G-P3)5-7er zOKm4_eIt^p`f@{=Y&7hOR+T=X-wg0*H0&3-CjEW;pQ>EZB(=drpTMSMLuLS)Cksa+ zbH?LyRm)5)H-7KQaPW;{ZC==%cml_*YfZe`N*g%kAs0Azxzg(kBa~XNt#P6~vs@%Y z_ZKn%4-|55OjV&$MF}1^mm4hkq1C|sdAP?HOoHY}+m^ zWN$+?Ef$S+ZGs&gFC-uG;3 z^!`M;KKa>%o?7$Kl4!!t^b&vtnl@A8@=U_Tn4F@K<~k;h6ZlZfhw`Qpy)&%t*PG)phbdRg5Z@s+25HwVND$T^tg*Ts$bE|S=vG#j=}(y@nk2Jx>Q z&h$%{Q_QU^AcTsqY$ZpJN~XT<+MTbmR0A1iA8TbVn0U`Gb7|zgAsL<8xI)CgKfNG#Y<7b z8nx)FEjI-oiGbRsn(+GhD=8A^Cip2I+JK%J{&Of;uuJjeOMT$ks`c41xYyEXXLZ=B z-s`uqj8TD~e5_Ae{s8xJ9;n|1?Af_yJqiDL%$|nTk}4{XtXi7`D6yJi_va;r*F=D$ zhq^wL;e!WTv%i3(m~o%M*!i?B{w}B9dqKwek%%VUCDWOd>h5v-!#7Q;unl~Q&be1+ zk!k*fY=S9=pS8iNy8LLA@VIK`8&UC%(VA^pV``cD{&+8;$?bXbL@J-*+ zK2NyPg5%U9CH$%zBJYhD{hk99u_d|ZV3Oj^;WPpVdnF02AYFG%lTNKSew<={sWkL^ zOZJVJCWxzllSW(b&LCzMm)%SPGm=id8mwmTo8(VC^MgTT&XtaSpl7Eq`M!y2U5vB|wVG`N83P*KbS|^x;(m1&Qfk<81-7N8r8GPZEBDhx!c(i7d5Wr3pMf`@`&eDZ`;VG*&ckpv^JtiY8W8GKUTIHS- zzj97iqTb%9gTuO>idHTzX$i77X|<|kzqkPdmC*GjNw0VXG{5*r7Gu#b8t2LAI4Qu3 zb@R`lh~T^TI_m6It^k|mZp39B%+2K+fLEROXP?FS_LF^5$iA1wB3MQhVUh#sc%GXC zq>c+@-um>4$|XcMwCHs}``Ye+8b>h`75UA65#aXE6+K0H((bo&#KDgkQp8`VTQ{`e z6W`vf?#L-Y>9ULuWG`?^<)~~$biMq_nufBg?%B1GPa;;E(kv$Oy&tBqKFJ`G=uQ&L ztZ~$16T4EyZXk3)a+7lKM%*3G6X_Cw+x?%dYJ?$gbe}NfXC1%049xhJepXR}l0GLs zOHI@^==j?Dr55pK5YDn8Wg<8#Wp!`MZ-b|}<>8E{{>w2xUc(LI|Bth`jB7G*|NS?* z!6GCrx@$0COi)oN0i_%1ZUziSC@Q6bbV`Yg?iwgc4H!APVIw6*=h^pnUjKNVbAC_G zll!&%!To3tuIu_-@9XoipC!1t_seJ1!|YU^ zT6o9tFK4;YHjvZi33cE)V>dm`TAMg++DRXf;)KFtaNJb8<9n_c0crdVr^7RrE)dd4kgHu=~f% z!vJ`ZM(2y+oU9RPy-vRr)< z8Xso+mt(C{{v9XBR(o#WX%Z*lnRwk57+#)nO?5+&LM6c(vYemBLFz-@XX>~~cV`~| z`>!ZjQwrTD5+42VTmE(N=NzB$f6HPPMlNuxV3ST$!TVwcZbM6dSEtT@KZVn{Kkjq| zxogxr(y6l$bbZ2aW~qV7QAW@9#pl7!H^%8gUfe&Ucq3U3uRnO%C8!@0L}Fv_rJ7*j z#*dl!%C}NnWhYG?FvmDKIPDWnJOFp*${+Mz8hRT-&uQw#>6m)mX3Gr z?u)Y~dH zVp*tw{r=SzL9GtR>*Bg;V^-aF#ss9X=&ag&Z-%_L!@cG8;ccdGB4Af7(daGgNz*a3 zN)>wt$_d0ljXVuwy{u;FjIzPW9DA$OT@HQA-3kji6OxD}u1(|{oIVdm2UAgqN$WoB zqFLCq#YRJ{#%`rKaBXv0x55(4soGOaL1nJ@=kI!N^J8^MQTmdWC==s(%7q5I*!v+= zOvaWUw}n4zZDMWVt1M*t#YL2&XNLBu8_p}UQH*k1;T*x>kXYaC-eG+t{-~0F7C$(- zxEO-;c1^#Rlv2BUy+kVpDi2-G3}6^ z#aL6!OylHCBfPc|W|Pm5=Eov`gNe?PO)*FC-*=`xq& zHgFv5N=`dy9L81gUYp5>t+;M?b;dqqElN!7?FHQD)nLMaUngnU93W z(yxf=3g0pP=^)ZIJh<}|EkB3v;#!_V%g^p!o*!2}yoM~J5aBj)_F457qt5fe6#NOt z<`BO9{hgs26%ow?p@20$)&a>4A@rvklb<$kh-6eBsqGV zWZRf3hE94mXTDEFd^V-tD8Z=HG#2tDvB5}#q~txLwwUB7-@PjH{qD0sizq#=OCJGl z-OfmVj%WIri`6J!aB;eH?-$tSIk^0|c-b!)SBgeAq{%KjHT|dlwlu6*O&J+%1jwTP z7yB>>N(k-BGdNZ7?$0K9%3Gw)s~a7xme5VstruMo?Z0Q(lrhP6S?H6M zZ_;epR&Yn$X=lNfZ>T!g*;VP?DLiDky6+&iTO7%>^y)1tFX=dhKip4PwQo2|P~*hI6^O~z_3L_d)q8vrSoQi3UEfbu zUKNcWr-pFtXrP1F$6*nLY1dPZJr9;y_ET!rhil;kk>2S-v)cm~#1E^q>z1WV(XR+U z2)4mzsi4cWD9;zkA({q7<9n`CV38gCYUv1s=9rV|ERVR3ZlU{6QFb@~Dr*1#RpI}w zEc4&xcfV}dK@4j9C$Av}?Wf(Zi>~;Fek0P~DenGGp=SaUq&aG$A{e4PMNp(2#4d*@y zmv}EzbVkIYRdox^Ywd+3&$Db73-$&C;_Xny!goqS}@ivE_M zz_UE-)TWkngZc1I5p~g|JTYP{${3*she=Hytr&N51Cst^`}O@mNp>~d0MKmL-l0pr zgz>lUmCL^PJsMbDfXh6T90(;zR5@kwc)QZapU;vAZKLzBrA~gbBZhZM9YB9Ml#B0_ z7O}}HeABsxC=khme{1=3C!}_(h<&4@+kdjfe*Lq&EU&uz>t~N@GN+&pjCT`X17Lt0 zP$gL_b+@atbM<6X)ufBXBng#p--LXQ%bYbYx20hE?-&ETSXU!<;~1DI^MHYu>WP)P z55#L1{FlZ-Ryaov@z>C7Y-FEHtZnlv~m8?XN~wqte^cKN~Wo@V5-3Z*ogh( zKC3|-t{AYs%GU5UTXT$`uUC+#OI47G`JXH42?ci|kHvY?_UbA;^*WP4PU&Sxsa}Hp zz4sb1*!N)NmXDzLq&ynT9aotXO{8Goc&#aHD3u5w8*9iI;WM6o3x`zg+GLE9Q*F*-b`2}rq?pmkOk{T^EViPL9$ZaovrXSZ zy|%*N5HIyE)e(MX^6Pv3D~W@>i_AAO5Z9K+VeNB~TZmNhrGTB5`#O>FhqeMSMu4Bj zPm@HkW&=Ws4rn0lrgFl!2wUR{|Ey2NpNWCqs}IUPvoBQnk_~WP8;*I%F(`eVKa2u6 zY||=~pU8Yx#okj5Q`z-I9s(Z)$+>+$48-N#VX&wEFsE83(=M*>YLCBHlYpbpKV$?v z*}3TlUk$6de1jytZ()?(^zUGk2SLVJnJAHI=8P0c$@);l1qcXA%ypwc3K@L%r{W3x z@QC%RTQP*njMZK-4oDZgLs%F*m0xMwkZ?Gy_LJ zm;abq5F#J1pu4PK6Kjii+3c_OHy3t&dFeLaG8~L9%5pY`t%4nE*o(Z*07oEDeQ`B& zmH;h!>N5A3oK6YHM!13lHiXhgX+7jEE*e5E*@n&Vj`UMkncgKr&BOB_6<4*Md4Ife zp^RjBDyQWu(RtaNOR5qD$--ufZCwZUp-C>v%v+}v34Kx*vw@FJVQq8j zMCS;oDm0|(;vhlI7|~yqXED;XS)rKNgO(Ig$O@A}C2?a!H~6ksG7mMy3jzsjDZV;w zbA071<=LJB<)=hYZmvjdz9mt{_IU0BR@>2OZ#uJktEMbysWR~Ec)(^t%Tx$X+k!3s zg~15B!SG7x{pAw4Q4zJY}Wp*m^n>l=!lwH+@E>KzAb55D@W7tM`;=7P$N{a=*3 zPo^fJ(4}78RR^T!CbRR^^XcP4(~vIc(T(Np^cO`IGuExygMH8K&1d;G6J_BF7yZL_ zDC1=8bfsX5XU$Un6wmq1? zGi-DJoq%>Sw%4A+9n}?c?kIZPR?CXRUt9I=7pzMOi;nPPi?@rG) zjvS#?6$(X~gln}FzI^YK=^gYN7W3M!p(~mnsOLu&s&kHe9$r3GlvKJTHapQv2?GcD zFO)}yEpE?iDaZe7kv>fcxuKa<-;McC`DXshm$?qJ&45&1MXGbHCr>2I`(5R$D+@?v zgmBKsm5l70hu$#LBs|l6Kq=&iN#;ut=ShMqa_ubmKlh>0tMboC$!6Ht?9_AK)X9DJ?b-=#Dt( zB(Wr41L_Y2)r{d5t?+i~ za7%#A0U%u(t!CAuW%)UqYh1F1hcoOhiQl`;zeTe^I}YN>4i)rc4qg=?qhuJqd zB)`3CxhVc$1yV{?MeUmDSN9e@%@vE6?3h`xX%E;R8=fa0H@A?y; zQNGRZx~L656zobh3t|@<9B&{~J^yHNetJgXeRlzD^2&@xoP#uLa0z8x8iUJ}+PY-s12!bR_qE3-5^cT9OSpGroL6f!}>Zar7C;&?zB2rZ!Ew zUk5)rM>JV|xtxZ{2-}HA-&SzXjEptv zjz&%V>K{s%pU#uFQ)pig44IQS0@%L$Z@QX>?+4M)yH9^V;LFw_`<|%lzgksvw?yyF zfc<-Q)J^-T#0ZG}EOqu*yMZqHNIy~6=8;unsci3LPm<@+3aZX&&O>p3ZnPOFFzdBDt08@ z(pd1Cs=Qig+-MMg3aO;9jG^_ZSnuDFf>BS_Fmp(8tO}*(=;Im6zb5Y~Tm2DGR*bwy zd-uqh8-CUWkU#5t{JJT1{|)1*db;m&*oGc|1UzYLpELu7W1s>&d%DRxU(I8?3Ntcb~3gRuCU z07uf-`j<#gQ>JeMpZETNt$P*iOiC?fV1Mo=-hGmp34wHbqTI!FXioUp>IdV33MW^qrZ3UD;I! z?K06~3bPH6^}%xh(cApO?c!^h zC3dRX<`8Fw)F2{uy(<#-hdNxC!0ergX<)O|x!SL0=uPl?SRuNq!IR(e)gsYktmBNg z^+Iws;M73E0FnDQxtChtA$|_JS+cG~}x@RzxfakJgOl+hC7k2ALHQ%T6B1_&w4W^w)^LGfS{;_Lx-eJ6iG?J@0*fOV-E zl(xC=8BBVZ)1rDmu0!fHp$O$W5LkcNm%Pe`t@U+6ZCRX6CRcH*@rLwe!}I>pPV!al zyht!eGCDtOZIQ}YU5nC)QJr6}F&oYkkW3zpQJ?Z_;IzQYi1?193@A4qbVc~YWsk-l z`na&}%si|xBChS^IPk;NE=Rh&>jgK&GocQLc*8^SZW%0exXc@h7V{K7ze694XZ1B# zIPGuV0P`D|)q}4oW6KFR_=fytOg7%cfAeSd!I^-Xh;wI8k!HH%y86gKx}$5`Zgpr@ zAG!SXDJUWe=oM0J*7~(=+bw+q&+*gcaIDNkU?(4G*%=SZSHjq~PD}d+!$VbyH28AQ z$_lk-N7rE%BeoeKK{HQg!hbXGI}E9V;{D8x1k}?}oaRsJ`9r?Yy$Cf5&Env$;gX3z zGiQ^WInqPLxJM~J4^FS^ch-?xRu&AQjJ*0$^9RJIM*M+0z^-omulo4^JDDph(Q~x9 zZ6XFk17BWMFUsGknSU%HxKkT{WVNdR1Wj~oE1HQjVgY?~p*FknFLHzq`pv5E^> z1mOOS6ViWqsWfNgHL~O_-@mnFN&j{XphnT8Xw&|@OV3b|nqC3W4K)0&Kw_%2RSJp% z4tm(!fqKPjebE38O2+cqvdIzFdZxSH+teNxl`Uki-aTK6I1w%v6b}JGg+v^V=06W zV)k#e$tmsqE-3fHec|8yQl2WR!F&+Y-q@`w$GkGKXQJdkZqin#oAfvDw9apF8;2|w z%Z$B2sJgup@WyI7M}$|Q+H<5A)Y?tr>}?m^5<|u8)D#mGO@YlJw-P30?f7{|UpgvcY{GQLkkqidv#i}-MBvz= zO~S_c<^1u&hxCpl>4KfOVp=tj^e0RU8CC4h!!-ibvf`~^K!t&DrPqYDFXte4l7hi_ za=O_`>-B;T$4iHbi?g*Mp!b1sA0NqMj_Yue*+E4&v~F0%XD6j<@)$oZ;hr^{I(PZE zbPDqnRB4{APr{QNlT$!sPo+-(UR3VnlKu9q_%m$zkSPB0;?!SGQ1WkB`ffe5plh3< zHPr{e{$#l5;}y_&o*vfOQqsVo-(`V!UW5Nww_Rk6#3;X=>&XI^=yC`1Hj^a=DF1=cC=}&mfz4Gk(OYdkS%)pwx*^=BycaxYl9iaRk(W zLzt1ns+z?>#X<6y#fU!kS~~8lIZ>?N5XGDP+Qu!PoJWgGeRs5Nn~IbQ|FHBol=4qdSdd3N^4A%>@ilhR8Gch66ZpU2t1 zzHMDH6lLvl`_j1Y6Gm&v8dVgre$L^iv1Z+R-{HM{x2i^2BdY_|8!S}fU-!KI%yECS z z70NjzPKteN92B4SSr!Ts=FYXcs2cF3Up;wKcMp)d;#7I1wz;=I2<9Yex!^eW1$gAwlLO7er9OWHv8tpD=dKV2xj{Ez(# zC9;b*fs}|v5Zi%y>Px3Zn6HuLVNPSn@?B=D9Z-4ek@11j_`5kd%+vW-Y>F&yu4Y|= z(iTkX+_F2{t>bhc`PWgr*zx-G2s4DHVVoal?SNG?(STD&EBB?CBDQOS0Q< z%IH_|F#_BP?;>lR4_w+`1^3_2{`qU`q$s9Jvf|~+NYj_=22h2oiCK+Af+l68=;gBG z<>k^EC{;P-USm!0&!=mfB<(vK+r@fxNOax;Ls(wvrH%WO1H~JxbtRrY{dwlzL;ZDPFXK8tHa?>7jWB@J<<*bS(HdeOEBB`kzVKj(h*#ZoE?v-Jq^`1j_V?xjU|+68-)C~I=$lMUAYjG zabRxtzs{}yQt8jiLn8ZG0UZFBCFi9R8-%zqFS#uV>ocJjhC;Rxp4r+T#8jmLuPZ6! z0z(;hh0{MowK#A!!fxc;22|T#e+&-M)!XFPtlVJHXQbuXeLi?dW)6qMGq|V>E_m=y z`28;IaU!fOa)~Xo1qvA&i>w(gsqK0@QqK&!O4neVXZjrXhe8un%yX#PC*j8i<}poh0{h^KFXo z&kdW4VvSZE>h@ue!{3vqXvEc+Z&9dyxV;)P(O^a*y>2%ls88m9`p1DA9d5iyBlLLi zSxCT2=R2`OHJ8_PLkSl@d`wXjW4#*?fK}LYb%YN|H`y*lIDb)8TrDaP@IfuQ*QR&q z6HA@1)^Z^$*G>~QvjGc{LlSdtRVR_+Q_*Z6Cbt6EJX5XH%o){px}+_hAJyP zqy@S%(w>~`V|H|XYwhpSH&1Jgq>aG|Io~0d>gc2mJVLuxsLFTb+xdqN9+!H<8>~Be zb$%D?yWcevM_#{Q@xP%Bn)nn`tMOwirWzjS*wB+kzAhXwXS+(fyPm3xdusTbBW&Pv z;S=6O#Y*7luqsdm<4~;TCHf#1`H&6dIh;~NHCd#0FJ`d|pV(liDyUekRV``fYHM6W z8O2x!=rn8deCO!M1noEksJM%3RffNuUm=~92$jDMXtPRPqHZ=<-NY6nX+!lo-Q(mv1DU?e(YM3pS(Eqf znHlyJ(QPL9R=r;}=P8)c)}<-%{QK>7(A%TZ-#wc1fipbJRey!G6-^s_)>+)D=ii3v zx(MB))>;MgeLgr_K@eXHJ70{yf{4e^>JrX|s|4?VyN5F~rC86@wXGcOb&> z?>F|K3^@Mbz!4rs>ygFBIv5xG>%$&>_d)L=uF*c*W=lK0{IbWO zn=~ic_r?cHMDu|!R#Ea3zM9-{1v&pD-H2jcts1}kqAl%>#yy{vy>>*E{4+8Y?qAdP zO`F`~oK~r9MsViildqkE?H0|SHrd9NNpj(+ri{CQyGQbyQyt~6>42w!?dZTRZ~fF_ z``hpNOGp{+2TUN|uS=C1mBEy5g8-(jk*~^vIt?Qk{_2#SMgg2_MjaJkyB%lrtY}6< zbs7c>yUZ%MZ8HqeV8Jg`KI)o0oDYX(-S8o%cEry7h=58%ZLKy?>a}NW@3M z%1h4ojpJF!;44ix7mjWa@_dbfE8A(V)NPEM*00J*jI%r@TwPsn(PGNHiSf@--6^TX zn_&I#=g4fA={LgCUDfO!HA#4XKR@f+b1ikhfOTp}?|LJX!*ro(5a79(%{q)t9TPnG zmP*dOhW1AQ>*jZ%>GaY02vbCp&Npn5KX)VVKZ4?<3OC@-P-c_@86)h+D?mf*s;x_)2?&F?z z7jZjU8n>TF-sX)rupaQIUz9_^&;1YpaynY*EeC$+3DK3s1+^FJ{>OA9c*Au2jVs*uBPdorQu z;>=*5;!RjcCTcCj92FxK&$wfxqmy*_oX@NYtWDJXH8q{hBr`%Z6Fkqljv?z>pA_QC z(dDo|a3Sr?kUoF?&f=<{UhuWk;QG14Z>!jl{Xq;kF#EJhxiA~9nzqHb9by@L6tQA4 z{$ND2WSQliGpyC1ZmT4w`m18@oqqf@A?5vn}Gmn989O{6U?Qb|g z-syV8Gu8MT_83ZBuUvY)bG|d~Y1|Zw&-4#}1`Znrxy^h~7q9WQ4)>T2d@X9*eT4BW z6La0Tzn*^xS>9~I!Lc$O>zHV5^WpC5qX!iWUBLySNM$4LBE_Bu)wZeY_ARKIPK>%# zYyMxewQdh=Tc#L#Oe`waMmkk~N*=EaCrq)p+Jp_}hOYHZqr8H9_|Utk?TwnVE5)Yh z5iQ)GXh+(2z9qBwjc~C7gnr_!nLn3ndWen@eowsA&owL6&-~(hO<&NL`GM>H(LCJV zgu^?;PC!ob%g9%EOjL z5dS|It|Rn354gdElq5^Mk2s>Lh{7ICm@kytz&t3Grs=Xc^JUK-PBx zGbxLZNawAubZFs7FH6EO1DB|P`N7CzN0^Ub1ryVaiifh?7o&l&)N)_kjU+wtsYlPX zX}iOp{f1*eT#`rpMse2-uT!C^5~QJHt|mq zO-k-386k6}Ci$u*us_`E=eBfv^Me~wuU!}ule|ys)s&cU{I{(2W0hRjM`W}kvivTU z3}-^_clm*=*L;b=+YMMQ34y}#%8Sy2`*t3{G)zn@>G61@EKf=75k8<6NqL0oc&98SsFIAwY^_Og!af)`@e zMeQHRy=_-q2^iaG##SHs9kUkMiuwc#=iXxc%%RJj+j9#He2{yQPV@d*dcN2pV4ph6 zs>7&sHfX06x0q*!+xTV|6>*CZ_*7v;+)Uh0i!?VH<#Nl+k?~>l;QACeB&Xtm*NaAy zP&i&DtZSgr>JeA!{$M2GB4kC#cA}PiK#TKw<<>&#a;ODunMBdIy?+-O>yd+nu{p>IOW&K#^{cM?y~SH|^S z@^hjlZbSa*;Ix7}sWL84v#D|X{M5zeX~=`$!sq=GxG%7|Bm_aHr>g2bTQ zqHQvGYs?_ce;zJ`d#}{Fk{pU>O!MFQSNVP&q=2yOQVcbVS~FFC*v-?)jPV8jQiEVh zEyuFI$3HDgVD{5W8D^9}CO=8$&N@6YNw3#tv-Crs#HiXns&*k)=xTa^s#=($Mo97) zjY~vvl(D7_uyR%f2wXxMbVIM{4U6g7ZX{_oc5mf^7$2U#V?c9CS~v=Xka-YuXzNm&i3ezU*#i6rT?haN5D}a=#4uO$*1dtC_v|zEa)|!Fmyv*r~wG{2a zq5hPuWwN2WW6JphCH>K2C;-#N4cB%KG_bjK_JPA7`>oltPdvAK?XPBMrbv7acmNAr zi3He9rJL{=N2=t0bUNT)7sr$hytu%n)MdWOuelMn&3p;4JnQzWpf_{3&b^!Ej3~+u zT4c5z^h+Ux;28ApesPA6l~-$2@GH5Qhi;2toA+m2>P{0c`={&E&JCmI!~1Zsvh|HvO^Ncn8WXgMv-7lk*z473F{QTfy)Dq!1Y*RNuVY2o|hDP$H^_{`=^L-`m*NNs8 z89rcJrinFMwq8CnWdDzd&4wDfOxw4in6t5iRNnc-+OphCPe=APb zZ&SvhIZWPbCeJG-I~HqqG(Ejik~n{&k#MBQIquU_zg@)OJm2(#(YMsJ zb|6#x==3fo=;Bg<)wrU1eR_JDgJF(Fyap_#`MD-ap~XwsiQKs4WFUehcg#0#yN;oH zCb9n@v9wUeY^nuWzfLgSZ_-GsDekCK77Oi6#q4`uiMzueWrp-7pgfI|Jbf=(q@U*q z_#V4QXOyU$!!mah$`9i5R|;ZKV*L>^bqNMa%Hvh|*3gobpw>jtWnG^Rt8!}A;*_$O zW|Lo_LPiVo-}Jd8=NsF$%PhnFsmH<=XMS0JhTvJ-Wqj=Q@5NxQ=o9<7=nKCqqFj;9 zVo{ViQh{YzK4*QN>J0n4EZ0RqE?l| z25kU0EuT&ZFRse-M3aIzVAP6a!3y9%#sW|VpiBwkdD3nxON`Lkn^!)FtDXU9WHkYz%m0=$L&-5 zLs{?O#?aehr)ZoO zO>63{EZs~|V%pVI>JZGc1UvDi^kS;=EK^Q@8|>a(-~_DB#ZUNf0fdh=#cQ)&Hw4uu z4figawB%_M6U^fh(aAXD;*3bm97`j40r^r-h7Wfy@&pq_+ zoF;;aN$lc@vBEeLiqCnqE;O}r8^TIFtnJFGP>^$e+vQO+!U0fQP5sbKRQM$cVE<9o z^>^N@fOrc)OaXmhJJj3e(J<7lWXnAI$20@L{J1nCslF|3$}<)dLJ)&Vr?7&gLe`U`m{|;$1ui?j|9YSy!zl??Eq$Xd}rdEST`C(Pm=4D6~XL z>0BbjjEsHFVl%KA)671%(_5P$j%%&`k zlKL3>^F}qVvRP+_ps9Y-D8na&z17?Kfpc9ZIR6qW?6Izw2tk-|sRH^d}+KdRvjm|2KqX;iET5+{pvG|(PH&nKq zEN)-S^Uw z$@&#<`!AO6TBe?p?o&r{fdIK*d_TgR9ouJC-@bgusD{*&d*U1L0kh;uuYM(%AI~rv z0lvWl$)5|)CE_8S#t7yE(UUIN&Nl;dC)81GxfGsfb>3t=U~1(R^iU%sXJ;7yT}YSdq+hNS%S%h~{Q4Ygx_o7>Jjj1AP0s4DoI zdtV%tP#iaz+l|oMCVU&!XalVy2ER0I_}MKh;290z(%GO)#z3}iJqWo7a1*LO9KCrc zR1TS+Y4rZad;fY^XJ&rN^0G5GNBJ}ll-8=&_iniW2MSrPuei7fB)r=>EyE2|gVJr0 zo?_+mE+J>vmw$1k{{Qr%n)|zy4__b#5oN_EUFN3&gpcu|yhxqAfx+q~2u7)t{WLy^ zRH3W!>c(L^FKENajB{-e6xS!*P(vl8dfH3u2Q)~m3Ns{t$G1~H+Z6vvw)g0bQ z%ZqVBNc()5Z0OqYd}v#v|BgAwZnuOlet;9DxaTsc!16PQfN8GMfM-ezn9SA{;tj{k zM>d+qj(e)(6j1)Nn<}+lNttCROhcWR<^cCxP=A8Z>hre#qB!?tXJd1tYp`&6(~Mup zh&SZ5?2fB~*z}lsh=4zC+}*+`>B`o0-)ThjQ}Vx-8p3eDy^^TcVSww1-Q;@xh*S%| z5-c6{0jI*XqUp~SFD&Hftc)gh0h*z6L_UtWz`iA9&R)KDi`dX`j=X7d=(0tj|I|B9 z!%Rue3UexJxUHp>2S1yJN5eKK}Z{O^(jAh&WWh7N5Q#!wOh4f|wk_Dc8< zZ5q3%^A}7%lSMX3;;QWxFni_TX@eDfb(+-YCXWLYbo#Z0(Sr}vLoz|S`?uBf*Msof zN#*D>nung=Q%$#dqz`|S+?#g0r)?O?OxAzr82E`9@CO|XRqr)Gia(%j8u_~Qx}9N) zljJ9L$rpqP!%!R4BBk?v1~xPP@!;Anv>k@9b|XGKcbBG`47MB*L}#VPdN~VFFLbb%3Xv zUbm2uqQ^nH|Nb5%7e|@uX0@ncKa>zgj=aML!+E}k-;2{U1ALIdJa@V@^al^x_{69* z7`YYX>A}mp8_9P4;I8CQG&8i09%`j3Y+_cu*WGJ(|1yNWeR9}`PmVgo4+mShcMDe` z17W}Lkk#T)D@l|n6s6dzN@ z`V=vna_UDW*L1-4^d?o#H-|9k;*q85RmXdaFZ;i%J(V-|kTom>-oDMRF`J>+Q&!;o zE7tsd?O-r;@`gvBB!zmLDEu*7;zvV=myJ4w%AR`pdXlGq6$L-s#J4;+F+^X-G2#zh zf1xlB4hwecXQjbja(DnyErj21@Qkur7!!t zXGhp6j*zP=P(0(<0;g?R4QT_WnFhB+6$kB+FPLs}{yB^M;hTNTVSS5=6Jz?7Ql0!Y zF2Kii(cmeA;U+b&t}vs99A7|yre--+;qqLEu}x=!jVwb_BQ}@9^9R{WMm~*{+vHB= zmgjYv|8nDwwtx`57HI%YEGzOk$s6Dy^SrY`F7 z2>Y@(9OE1Iv0fSD27p%D$dHC>9v{5@Y_0C)KDwNYY3gwL4#S!&(zQ~nby)GYN)^=K z?(W98JF#W3$~&G_3+hLUwG6lTA79Fe`^o)Elk_2N9~46!SQDl|bI@#Lqa&q$c_R6s zC)I}vd8)yc2ueny>!$ZMt^G4sQ=8?W@e0V*lDZiAXAg38RS;!!{~gpTsJ>5pMk1X4 z)$mxUs}Dl}=jN#MbiK7^`Am4c><@G`X4b`RcIta6xrzyQmY5o{t@6B;zy4mT{46?Ch3jPGt&q% zP3`eg84C@jr>E};@3G;epcOd=#tYIYq&Lk8D9n+0Vcu=ui$NIkpi}60pt^81@F9Wq z$h^Js!g+3B3|Cx^d~%?)pLEEmzma-QrX*O7ct%L!bw9nk6VYX_VNyoqzd!GLm0`7c ze3DACCGp0+7rl3#m4-!3IDe{dmO^y>Wg41rdBM~ZiRMO<FDtb zP(1!VQB&VAw@40|W7mQlCA5H)h=xbM&JF#CqFn9Ik;~nvF9yU^rnimzLyz1Ec7ehz zQ-Mey6ED##%~YJu=;4p)lEQC=g;J%QW$OeK)+)2BrMNnSl1?FxOhv(7X~~(nY*TT! z(AU1Jz~a6X1TV9bsgQB4!9sO8rd5^S(Z(YD8M5gp+Itlc|wR3I@Rv_687)a`8gH*9YRKKy(+dNCPV zr8uHju0>XM?rPul(IAN%)>Ezy88~Lk!mBN9@u5rBHx9hqxgqR9Az4NP;L)EWNN+revydE z=Q~Fck^BR?B8!pw<&Bz_af>GgBZ@ueL@oSb?e!u$geabe1bhTD{Pz<%-i)-Xd=1QV zFfx0G_#_VGC#&4l(RmAofW(F{n&(lWmw?9v6%=0%851=R{o@A@gyZ8*BIS2xKl+b+ zq<;Vq{QZTj=_?t}cFyGQ-!nArIhSU_Q?8{pM#OvYKHXqD6KI9sb)g~1lw`LBQ}}Zt zDUT}^I84Q`emdzuiE%fKN*iQdGc369 zOsJa?_z2aeIw|B_`BAX_X~oBM3%9|q^v1%{Hi5o2Ht+hmmFtBZsCO9=ETzwA%LK%* zr4k1nGJk}sPF@^x0SZo96cMT(;oX5%@~Q=&wV{4PV~e>^C*QUA<(8alMU?rpZclcY z+Y2KA_Z~-uaLsA=(;}v4fr$flWn%H<5Swst`(R;$Mo@)>wT*5k4G-Vr=Oh_qd_*2z zd#btd5eP&^&g|?s*kt79^0Qq5sd>wPtxytL1kslm*?-F&qV#L`LQgw9F>Wv$DzY2> zrzv&0GqFG}mS*6!Xo1wTR>!d;9@(+ihy~~4s;vmCJIv-A^-=FsI5ls;W3AVDUEb5S zs~GgMKee3XkWKdJ^{#AoxV0J?aUr@?4AJt+@VBoO!})VXfi>-tb$gM0(eG*)nGMDj zcGRzy1^>h zkEU6N#(Q>L)V5BVwuanc;)tSVbtcI%sEzEpur3{^OaT0I{PnthUNq_%ug_FV4T;Fk zsvO7f77}PFD92sF??)QEEncPO=T6wy5N@eKMD2O241+&iC6$uv93_>KwJ=xQF{?Jo zmsCoDyaTop-Ojf|uN|XDOR*c%WmxsxI^T>4wB1i{!x$UJFdhSdu+_go=CyzK=nuJ) z$ZWg_sW}NIUI&(HPbglEDE#7;$a&!rcl7B+f;9ea*TGFo^ zo6Wy_?3?)t0Whq1>TG-t48kw-_+LCU$!!y z7zwotaX9TZhGtem?rzJ1+}vd539a)(7x?SHp;N)=`W6*Rc%-eR$U&3VUd8RC1^M8b zW+|tCsMhI=lI)8DoP8*+K5hQGHIzjk9;L{1T+zvnF$Fw4s+E&|hOe2Pc7c?&viwoJ zgA_`cM7`(eU3*+{hap~I{N5qtHl3y!8UJ~(AN>13l(8F*josph$V5+>bas9z1~Hf+V$Z70jL+@c;a7`vIgglEl+8KGo9_X47moq#LIkk) zQlbPhEBVLklQOfneO)bTGD&wyU)kRJd-3t=j~)CE%HA`m2{($@4800ik&Yk&Qi7m#0*H!$6h);MrT1O} z1VRx|DN6657wNr)CQ<{0-aCWsq} zgHS0sksH=t!i2?gwsb~9bW0%SSYvnIsH+%c`8IZ&3!BQEdc-v`e z+rs5gVn7=hpMI7)wd7rZYu(4I>H5Ndygoil0s0>{r)c``SX|Jp%@*)BRkWoK6pxj31kWtrSK*BYuRuf{#TYZC{chsys+PX2H)4iZYgA=|T+dZE}&Je+3o z&g=TL-{Wx7?L8Rjb9%4OX0inPon>1fW)m-pa$$#gE`nFEM?lr$wU+YEg!h=I zf5npRnh2lK$tTEpm^9j=oO&i~z~yb>W%=Nk|Dx?Gwl|%LR}D8&mj`z|{twYOWHWh` z34)N=C}+iOT-Y_%hs+^3=Jgy*xBL%1Zu}CwHsAF7dlcISbk{g4vm@zyet<0@T1r)ns{ItR+rNp4D3H2}0f`ITG z&@gE`71J9)Je+ZQ$1)r882a+~uJe?O0d30%pmn?Oh_U@sk^x&lXCmYLb%MG({(E~~ zHhuWYGthij%&?NV5T}TI+g|A7(Vl#bt$?@}Z-ga(zdrfZZ(#*B=}lyjgid+nsZ*Dl zTP@7@ikTlZro}FG$)XXibs=huzT%j)q~Y1LbMX7blAdQ!NlY4UGrEiB ze=;s^w8Gh2Id5^Pw;;o=>YJu6(5SkkN>^}&1KT=Vtn7;1ewd`euqq8X>wmy$-EN#} zzyhTY8+`$#=u8Z>lGk7t1*vQ5CcWtV*bj>3r?iz2m4 zNoQgm6+x4$?$^4wD8P)~=ieNhPu3QJ4|L~Ce(KVmIDgKKs57g-Nz5OS(E4LqkliML+k%7XPeL;ex z@>{mkT(8gg(1qcS>H;udDVwRSiJm!eWj+E{AON$IM*A3TMO&d#=|fs0u1!?~G|;S% zMG}>5kHzrQ3|D`$xF z8K9|n7EXTCkL+&-*PVyq*vXuYv$i9BtXIJK{tJ_f(S35LIipAtMaG+ID}HTapS70^ zFh@{NHte?5(u4N2rYz_Yoa27FPv&0|t>a0+i0F@D7On$eHw6*?-HIZuhx@HHA^@5T zXt7elJY;x!yOEOl0d!-wy>(AFG_m$MwVStA&Z@C#$iV~{E$t>f zSu!#whLoN2LkSS7XqVFs&EP%+gKdN9?=FY?ee2e)Gd>UtDpP*Uk2 zKs0%rw`q6p?$9$aGRiA2%asCzF9E5O(%dFAwXm{Q5zX2CRKM>o9|fiGUPTF3w|oo# zs)=Oj1U(;{bvq{Ecoh+UB*+)s-S$0gDMpy61?MLMb2G;I7R~cMe6}{G3C1Q1((hyY zU5z?zw?2VJfc#2eNGJ=hd^+w!#&N99#$C!?9^|@})RrxSiII+lw#kMJc^uZywKXm} z(Z*QsZ1_=xHt!Ka{4MS{@~r;?gTAUXj8ZOhuM91oed6Kq+vz%2&mFd<_a-5kkS+UJ z!+W@1Xx@Lmp15+1Igh||w$>0l=!7eEY=5Cm&~16Wa@r|>f;8>o0hEDo7Ydg&2-);Nsz?k2QVzT&N&*Vq0IFN{yWdbgLw6w4h0zv9Br{iu3 zj{?$N-ouhExwgkO`(yo|SjxqkbYtpm#2nuH1?yTx6Qm zY?2n0?m1bo|{l9L2VnwWr^K3rj6P6a#+?p1F(<@20{-bSm>DCXZeK7!*Yunb#lxN~M3= zk(jH`bWir)+#N?_=Qd&yH07@tDEV3^TNY#gi0vPkE4^x!%`OtcdB!D3VKX8CU-;D- zedI^jKxSL_MZIH~==l$I2E>Cx3SR~&*>mf%Dt-`=0)cd2m%2+f9Fg#FBGH1Ho#WlK zc@K3Kic;i`Rl$orfTR-lTVAL#w4j0iDo`W)TaS@DKlHHo&F~RdCRf(G{*T8W{Q@-` zXG-?s0tWJDi4quc_6`^}OS`ijCtvFEk$8l1zny&tv`yVs(>{I|_$o<4LcWiBLRLb) zPMyCTA%!y{uysn9e@D6MIsn?k?7rX4pIY%(~(AYk_A&MfGO7$?kU*f`$~kUq?>7 zAFv4FYl@57``7V1g`$+iB%z<;3K zpS=+ zKBp?BHfT`30_00CqV(AgBnr{MgZ|Jmb+&1Y4JnVVO z3lR73QW7}Y{)Zd)^{{H2GrvBy^oeQ>bZl&J*(tNh&mHhXYd-kFfx%A&$i{6r zHnFj3It)KK@k$9e()5Sp5^q)utoL28u&cqg88|_aZg&5Ise};74>&q;dMhUnYJ9}KsgVAok~skb%b|BJu5 zEsp(X4f~{%B(P(`sB^TAMg{fDnR<&gn2GdT_np$}M?cvwb+h0Fj7`pHMSCdeH`sf1OMabXNs1 z3b+Nuk!kwm(H=>Z>j+hY*T1k$guyvvy%|h52{F3zIF*e4xD(CR3&M|f=EIvyU5cUO zw3<=htvCS>Yr~@#Li=ODeO`@n8nIG!*#8K6t=Y{Z6GoKDzvHLmg6!5VhBjs`jDN zs*iF}9M%ufU=JFYC|9rs_Ea^Mp#>3f^|J0K5ACLS%)h3`K8Vgs>_+$*>($lN+J*gB z!TUdrP1NukB*0paM|m9jF7)1Ply>H)0udf%1Ck!Q_f4F> zUS;6yW<;G5*piE35#^A5jB`wZAyX*zim3Z6^0L4T9kwwt^i#~sAaq?a`nt;HC`s84 zrPamHyWlsAll|{Kfp2L-$aC;<_ux-?o*lBl*En<+@JI0)246RyoN&!G^5304!7$+A zCsU?@@Fg?^F9u`b|9v+;;5k}%{sZj75)0Sboc%bFlaQ*VlP3T8?0)VB z3q-i%g#vzBu}hR4kYkssTR~%5y}V>x9erP}O||v$a03$EU0K-h0|n=4S17i7X+`#r z*mL9pXyJ1!p|XZThs~hhMK5ZyU=6!sU-l1i)d>-gT|tBvuCi9ll-%XpB`;x#rvRAI z;S3u`n~JyrZv?(88#*#m3X6{18qF}ZH*I0J* z0hfe|;O~T*UODLt-@mjsGR=>-C|Z8NB6Ta11xNjaZdvU5p%f|K+4Qg$T~VTMaU~It z^RxjQ-f~ zQAlUK24IO5Pv#G))WRC0N zfgB~(l{RMg*a25M8x}Rj`(m=B>xo|41!o|DO6>X1KkXx%`;@ zw_~tr-J--{AtCu%L}@rfT>$){?dK@Xr>oQ>OTFV=QD_d5`rm!H7e;?(dV(1(%>riu z3_twx#ifC_pT6;HMtggH!Uh>UBFXEkV?-ridlya#z>U47U>z+ccx#Gi<~BJ@(f>rH%TL4&mqiU(-mq2l6VERKC&Ajl7NZsPHd38{ZnB=X~xi z_Q5P!Z@^g<|MuZysd~nvY!-As>tDGL)AK>=g{tf?uI2YyITtQwUi64*;uk#;ZXMCYg=YS5?#wOL9kyY$2aM)v z9^5jO_Dc)SF4t;Z80dM!3VNiSER)pt)v<1=JMO`;vc9-OBN#H+SUhgDI_@;{Yp8;s zpy5@v7;xTMPu6+E4EkLjNBxP<(1K6f#VYjkleD7=i=vyNO{qZe+EBx|`j!}qX?6%C z;q)mw_l#-Av&KipRwKy|QaYMq4%vx5e%A9S>!cP{!MY>1F*{g1SRc@1l>+oTG)P54 zFvWvskQ=W|iIUwiTaUz(w*iqAVJVW~<0aW2=$)yayouW4?$3g`WxjjQ(Rz~!#uPif zkUuq(U%VUz-q=F3lq2Sh1e^AsP0ERI5;6^=1+YJ1-j;`#u7=ZZh_g_rBoRn|V3qR> zbhvO0;PLFu4h99Lyze@9isItq@K{EjpDK)uH!%cFf@eUZXJ1*V&tHrPFZ=W!Zp`x> zOjerfRX+K0{nIrVC+c=LtdHQZ(pB!Y>uqXRx+UsLXMT}HltqSmO1Es`NNQ9a&L?fL zTM#h@vLmm4(>MfE{&GvtnJ^BSqWx?&&}435@nXB|WFyH%m)nuZfAYw`geTlck3+%> zz;(An^u8JrdTMxft7vYoGrczedvVKLP{C|E%vkqM_pFMu536MkfxvRrYZh^TCHeQ&;a%6|9cVlH8RlW&6vjaJ z+G?<|o<@?jRZXo}H)qkbR2eLQ$zw0H@jCvcIpib(gdcpx?zMPTa<)vsFAjBx{^6|0$*i<&b5tPEZ;Fa~+&cKicJ@KNh-Cvu&RyD{6A`3ajgS!qi$MJ&=G>)EwHq-xI$`h8p zyq)=4Dyk;2E4fqxr!9ct>}GpwmJ8Gqag2v*;`}C~7Jf1T=@}LiH3W(KUPxk-P+TAP zm}r{cc&+f&>3`~0T-9zK^7?V)7QrO1UL7!QQv7c zM0`o-MOdSCK9{@q$w1iq4h@H#FI38x61c}U;+KX@!Y1N%c5T^5eTp>EM7QpodzB@c z%~$RveQ49cJ^co-Zu@)NWHmGDMR|$WQT4#MS2IYjtP0g~oWKoZP3=eVsLvURmnA$y zNDm3j{gIz?-Dt5hqp#hnirV5;e|)5kl^5o|d#IgIcT3-d=YP5YfGX-Rzu7}-%+laC zuMvpkI6Ydd+#*+4+ZeKjsfy7QiajI10TbZZCu6oZ@R}6i{kdbp3tLm7a`Fd8wMejsnK0VcqF=?5}5j_7hY+~=nAw{H3onID`tr^wrT^`*Ue=i4y;<0U4oB-$229Qq=K6Y( zHWLI?%{=lJFQHW0LJ#Ov#5B=nYN~k> zhmwUhkcn()uPFiSr-*2xrUh?9ssq~d`7>Mj6IP-CHxYma$`UH62qr;x0gYh)H&pGRWv$K>0shdHDDC9MVv&6eK(T0Z2OAZ`E>MJwVH@Q zAF#syAcfanT8M~`naENV>|2uv5V`Y$kzA5mp_s+0f~g$~z=ntElN7Ke3|BUVb2yFP zZgr6Q);;)rcr6!NU$ZGq8fV@}1r^Q|ILe+S#gcg=DxNTU5N*7S9#_sF{^a0m;hEDD zSxKxaxX#;FeaU;;ELE{`nU!OfVuQv`(n z_t5Pj20(aWV!MackC%@;Rv1H2VUK(C=hU~9n_ln6urU4{ox9YS@_2$Qc}l0EI1*J} ztTPE%b|CL{_;%~~WH3^)M8U~JdWBJh{HoN;x{YGEw*^O^tS0O1@(RXSBXhe3!O*#3M2zV)loEwS}7+*e*@2mPJ@Md0wWITxs@FvIM{ zz1;*KH<%BsXmXtE@VjNiT`v7&;L27)MQdY+bf$*chS`~aI+`4saz?cKY>w1Qx$!2E ze8}z~r52XqfI`i~2d2-qNyhI!H}lhNthHD8)ij!K{_!z1nc;r%RfGrnE5fBrJ8X!1 z^o)qz5~Mgz#Q7I!L18eOTuuKw*gGA1N+=fJR4{J2P%cuvOb&Fsp58aa)>5n#MOOB$ zOCjkZeu5~F+Gu@aq<23gVC7fpViqp^rC+ZGlDB9q#_Dk2Vr%?&8M_x@oZpp~rq18= zXN~PsUW9bQ?GF@;OJT3AvBiw&N2O?3y;GRr0D?P&6vm8&E!GUhWrBi1DY$cjI#3f<_ z=qy@H!>e@WNs*xS`to^ucB=e*3krebsz(>;u273AO;D@C-xNnu)9GM;61pm*8F-X1 z*<_9yU5#$f;WEerAlXOMM&$4u1y~VR*eJhVnF2V=BbbwcB^AaQW$yqF9f%&xQ@6An ztg1odr&3CH1qMqE>ccTFBsRy2p+ypt^{W*GHRZ&o$sGTaZ^6-W3d8EiS|KD0bfo6t z*(4bf7{z*E5$sDbcyoAmQ@+6)u)0LZ{!s+XUrycZF4=XWm-es6*WP zeazGC*ea$1+DQ|rIq`v@fq%YAtguBrXuBJ1VA^mgd&~tRSY93q9H?gW33%kZBR0~m zn=L=F1R*q+e8HG1K~%5wggd`izD2|7+%c1e$t?Kn_RNLK!XQE$+j}&Z@Tb~XC3Pp3 zK)T5x{@7ss*%w~R-Z@B-{g8hQxjtv?agn65YQ3yB%028Ct!5LIyC~Wh&~iB)++m~& zEuW#__>Lna|Gd=E5W+S5g5k{W2cZv$18J1yiG(oDT+XhkX^}q|Q`-~~AwMLc9J*dw zzWDc(d!N#h8Z(-BsTe%mS(*G`iA~3t3hJrhCdj)ls0Pw=!ZC5U2%Z|EGyYIi{cFzD zGq5uH;3XxFGV`rZhZ6<~^Rg+qY9`F6cWv{xQqI`L08zR-1pt zx@zprW?k z655S8L-B89VN@@V$ef*$2koFB zZG|5Q0peh4fG=^OC3Rr|eWo9P(k|Ru8%3lg)^)UMO+6i*SV=MN^>Rk8^c~k6Gw#>Z zV}4E>;seWwE=R=y=HO!^V69m-$uDVHvXHYCptb5jda7R#JeT?FRimbq**dl=o$R_q zs|=9)tSZV>G;g86th9=_zoV#!{dZmBgTx*Hiv|CAL0iZ?si#-vV{6>u5fizXT2Ucr z{+7ZxUbkw2==^zB$)g83{BiJg@_$l`%EAiD#Zb=IjvSS@#dz304Nq>;weuAcB)k1T zUN`|V)#>#GAFvZWNhL11t@|g>&co+k`+LFnqxJLF9%e)88A|4i=IO5Yx5jIhN0Nmb zwF^GyZASULrw^J|fv2UO{gstS7G4zrI`JD(4Y{2L&vc`}=D!mFeORg-DJ1Xral~Zl zI5*RfwDQWY-z)WXL7I6JLvg5!9xR1#RiqXPz{}Gu_?NW~4Of zy6g*SfzRi?Jv3jpM9#2+q~|SU=a!~LHkcc!kkgVC^wJ%o;kCs39k+WDmqje8$T=a# zDF;N1Vra_n)Y1J~%H6aAi}Txu%@J$`-;W*6j&o=Xk$AH^=#-2^nUP-gX{JP=y1aq%z zrox9(j%=0<3ZbTpd8qI3LFc&Eh9mD$(2A>*O2c1CWgzX z&ozy(>5?oI3%f#Cz1$)xnicd^Flc5UA;xX@SAee@=LX%73;$yFCN?Op`_IfqPH`Jz zF#J6X>%~vmnF`U^ktCOrhsv+(`2P()Ytt*FKpBiC*9AwBYJ3`aUf&owfSzr!FBH ztEx5>wN-fTr>MrB~ z7W|AnMTPQR6$45Ol-yz};tPRQ*KYX%(LGj^O?dhzf zdnkB~xroEnOwf#7@t13Bwvqu~`PnK+TyW#Ls52WXpgW4B!FIDb)NRO>?+3ayvQpQX z&9d_szl8=qJXd#&%Fhk72Vh9N=A2AtXYNFZVwwv{kVKCIGwsyrwb@KHWkpuulcZEy z90Mhs_3;%_=-Q61F@mvtI%`{eD(^U&7jS zCyT1 z&gH6aArHvz!R43WeOd4kQ3$5exK#nhjDP%a?hG-@oN2SO78$97K-n?&>zG`A08dpT z6OcD3w99k9rglKo#MTvv2ckmuZqsEj#4Zwe$wWFi&r&N0r9tgUcIcmEqziIG0DFzZR z8VfHS3oRLfE(ZfxqK6X^c@*rz0T(lE!tw`7H=$nh{@`tOO*grT&1YBs+m${2YX>Lo zD1nFSTiNe?tgHsNo6dG`#^fDRT9DT*Qv{x2e{JDgYgFsu+@9EX_npZ*=lP2TW($u@ zwTAVo*$?*-8`t+XBfu%kCS$cdRFn5!rE@CT@C+keUsO!_?&c(B`6Hk34N2}RAuHOL z40!j&qJsM`2dyfMz=^PPVhXpp=W~_nxV}0en8OQHkI7VK%e(qW$~V)Gx6GHw3bz}j z0{`qN^diAZcxw~1bDLVVrW$^VDmqm)`3HfBkXA!)*A~xy$VNs84 zERv;#uut+Pz#HfWZ&*#0+}O5hlSSM&*TKU+mw_rhf@OaMxbVLYVoG{y^tHJh9UK=yFN(5Jbnj zil5H-;bZGmn2Li(?Z#?KvNVv-$1r%$#)0~G#<8gR)r@mtzT05l}zhi-es>g~m(4>e4quUW`ep}+HL zpNZ&;+?I8s$*+Cn&9de?-JWGf41Q||RbIQWU!`Q9`KiuMBpcb&mH#rF1iXThZnyW_ zVAF~)!8IM9 zzpUwgq94Hnem&&v%xV`@&>-$0d)Y%S%Q<*JEMpA_ZUPaXpQr@E^Dp)pl2UF!o$0~ug!jVZFOT5kEB8}6IelK=+CSfBGUE)_GQC;p_-s#SXO_mO zaI9q}I}*lg{pKS8u*S^kf077xrfh%3a4ZYJ49n1d0B~f1E7~H_rKQ7PTG)IYR=*>* z*tJ{tKJcXM1juRRPar)e4E9L$!rz^nq?WpqI${>2+lRVUtzkJlDMJi7sg*(MX$I;y z>1K6vYX`xc?{_^pM2@pKRm{CZ7Uce2Z}ICWiLf4d5Vebo3o`UH*z~17iX3)=(Zu@|Tc<1ebaLU~$CwseJ7}{O|>gil-ssq1MRy6May&`wM7bcqx zJB>5t?c|c&_jccDxTJUNvpcu@unnF$U^V-2($USrS@UoI9`mev(X$r7@6=IQiAqr# z$DYcwqpt(;p+ci?o6HL5(myBpr;X6%8EfQ>=L#VCA2lUZeYV&!D1Hth7@o>*ir=`w z*F3@XQGjlc`|eX?S7pF^G-6Cs?gQv@1$}6aFLTWR`){qPCX?(i{Uq6NA{m|PtOyGs zRdUM=^XjR57@e9xzql|>`}{k?DsUJWNU;cn;eQf}%SEUBXaAeC>xxU9iGLKy%X8_| zzn1nzd*0L!Oy^kzKdcoE`ZiG=_mus581_Rq=N2h4$&%@-;>bJVy}U6JTG>w44$N~K zc1h>5EixY(&GBt8^lQ=DMQufpTrI;02oUf@WXWc@i zk{NL*|D4%E7S#yGvt&2ZDP^22+5vn24t_1}1dsr*rhmQJGIMw@;)_X?uGkA>As$0_cMT>hm)<*v(T|MBB^M;^{^u;ayV>rwZ)+zN?63f=5i))M@`E zwTZ=-bUrQLUd2WX&=5E!EKkbdQ#3!{pvMk5ayhmtFa)3L>yfRu_&DCLqeBGilqCo- z0-u3O5Sur$RTc7o!tSJfxz#^HUq(&I=4!t_7x!|pOoa)}*mnLBcgTV7J7Q@&oI?@F z2|rwW7)ZAjXV7-Pd~2$IB8-EqrbQcc-KQDfcD<^D$V1R42+$iw29wG_t10;QY6TMe z@k>{Z>$Ufep^IZcxgYe1xz-kvm&Ic^<0x>iF9BK;h{sF#Z7xTf$*rcm0#qiR&c6u0 z;h7dBY6}v>f)qo#%f21Mx98M~E7jnB3ZcCi}ayKXb(hZ>Nkz>ECTL(>J7V zEpaL}qNT!XEn6O}^q+jNf=+AA{3w)~G3`u2ghMA@1)R@IUlh=1=WBoW+@>TWsT{N( zNaC^M`Dlx|Kv1j<3)eK(=0J&^$lymE1u!aN`*Rk^i?kCHHG4haTsbb|pYPFc4^e^- zBIqx=+`@XyNgkHByQ5^}sXv>0+_bp6hbm>)hGA8&`Xsk<%hn~$!DdR`NB7~M#H9)9 zq)LmUgLk9vQXMjEWZ2f2n$T{){jTX@vqJrX1d>BE)&oMJ6x4Z9zUqIp{svP5Ha-$=p^NNc`oSm!l^H74|Hq{tu zxeXmQVIc}=DfA>1cOE%>>Ww78(NS)9Q;w1In=uSc6t%NQRXBkVfxV~LX?L*Spk5vG z-2ee%iD3MUoZJVKA^>}VBDU{ zY1voJiZp+$=ohVtw#5QkW~tN`Yor4!fyaO_VSUqe-4U6(a*<` zjyDtl^E^9wCAy#g#&GwzPIwTUeikvrcCW*Z+pf^3TOT?7V>Mo&pc+==~TY=y`Kia<{L!> zk*wg@>|*!fKG!<`Bu0Jkjw3{HzXKzT>;DHZ@HS=bna8x;eaI~pRF;aL-eL8f*(1ug zBJ2=@15`+KpHk}YH!H?GH@l7wxFBw5a4?OXw?X}8yXh(2WocLTAM9M`m1`i;36EdB zb-@Zy@uaCV@Yyw_Rj5(0mdE*q`*&TopLzq<0gyD3VZmuFfd9bly_3IxEWgo>X1F24 z0NuZkx%A5^b>)>h=GvA{zOlG(XwQuu;X~sAW!W9YwS?c%{?8!;*Hdfe`d6}w%snb= za*pOAi__mupJlE#0B6-(U`@C`4_DX}%-r}o)m>3G18vjo-1aZsps(jtZ-S$Iib~h- zP*TfTq%5m5jf#0P96qw-JtYQ?%!(<7d`YxfXmtLUgoAmi4L2C8vPnqn#@FVEP;hc7 zq&*7gX{0x0Hc)Rh{m0h+yPJ4nH{P91vnPkC>tU01@YCDO`%U~5%H1)aw2-qlX0xA) z8U`zi$Ksvt#*h^8FWDD-PyMPl-LU2MP<&7GB_trm2eY8!TfbqU%AMoaWF%YU6x*L8 z6dSWkw-QodN%yNz7$<*t+w8vdmv^&*YYie2+QKGM(ZUY#d3j%O`A$A2;G^$h2nx`F zBV5shkMZD7vq)RJ9d$Gk`n=P3x7{mSIZrDy7 zVecxUC*aHrQGVTD9tXoWng~lw>J=XdFMfek)M6e{2X+n`QbFb1OkrO3?mq+Uk*(mQ zUdi^3T&Y7@zQ@X^G8=RRW@X8@$1$r;6O1HU4y9E%_$?qYQeP%u7Rt77< z%=R)Mm_{AcTE<9fFb#jh@u3s9<@0p3)p%DnIRr-ZuKMq zT#+0!>m)qbcsr-?xvYZ@A+4~vXj)7AU})t&GkC2wmHqFH#!P{b!^94&Xz<=63>{Gi z7K=Ct?6I>SnZ1xUYta!lmNgMRD7#GwF{5p=*^nBE2G{{rpjWdT9pB#bh)VHHB6m>81g>gj2TTZOU6E4BzdK z;IIGK$W?uWQ4i&PHwyD@ZhfG>O zx1PuA^lRSWOE(|BYaNPA-CIf=-mQj^Wuo3{PwWAW>p{ix-1UgE zMhZN7Z|{WMvo$dif+U>D@Nb!(R9pnMXl9{jk>uf9OHH%WtY||up0^TaH+5K5t&|f( zlP4AGoW;*?&3Y)>AD(drKrgy7NNc|h>LltX%0A}kQyZ;P$AH03{t2}a$U_OnU0x24 zR*UWHe&5kz8}PnGZ{3|=RwefK^7t4efABGFxKOh)8m*Fl1ZW15roas9ZSs=;aU5H(p#Hr$@YFy9-oGNPWQDBA8l< z!u&!qSv3l37oKuUS z;PR(c3sVb)BVNx$vB92`_|GAQYey|bkbUy~pbzs}u48Y1RT`ucL-F>myQ@V*x9as| ziSSCz?Gk}wgVB2c^Yhz_;uO$8W@ozPyW&Ld^ZdFR!)d0Aw~b%YH%0+8jx%>r-Ok=0 z$QmbfBIAe?gYt37G66o~e&DXZce zZ_v8iwwSl@PNj+?xdAFugh|`{>057(CR(ne6#C^RGuyfGd^w3I{-K6lV%ms9OMBXD zXSsjX^$ME~$FGvppjpxV#E=P+ldLs+7UJUYc<$f_S5)N*?JjReytvkS$!FidccB(kDQ;7^cDUr{n5=%8z_~+=e ze&vdA@wcX>r>_;90B_$K=o(YuA7(!2|4OzTtoIoBFJDIIw4!fxmgsr?_m*%egqS*8 z_28sMT%~d7e@AllHjRGs8I?-$SH8R=1_#-fFDQiGAx8eznQAa|)*LB8D%5=%oh<25 z&pF4_J7RsOpUAzmTT0&d8QCDZ@J2=lb4}9(GWQPN*-HP6m)_fzd=T{mLNE24rAO|T zxk!mU+*?9Kf;1XPOzEB?2_j}C>)BL13qQ2pY2JU>(#++wV`w-H|1B;C&8A|1iSHg$ ze=h+I%rEen{{-rn>5lW-P{|Y_nTvSc-}XIkjIPycPEpQQU$o$NQB&eszWCWJ^4a@p z?6su$Zf%JDny1IkoUTZ{z#HRj6x)xHYO0_<)#PuEQuOzNZ6DNpXET^$iV6nIqEI~0 z;_^7&47h#<1xFx z^$Y|xw%C+}c}wV=GBIBW_Au*VH`DIf&!fATFIe9M;$Ej5r;t#MhehaxlNcYc{~6N*ik#1Y z>z1}Ln=8WfZyl;Y(2<9{4h3#bU>lyvJ4d@y{OfLsN{&Oty0QxKpS?rhPf?jM)YzrZ zfXUVZDcajQy8swrVY>d}DHH1G{-8iKTJj&U5xqICEA}>YW5b!{GzbTJ6Wq3q4VRum!;PXUP_uoKZ-dK9oa~*UcFpiJ$bObuDhdJgYdls4{5TAa^tL(U zTE zaa=4@{MGhaA|Y#fSb(y+9%fe4bSi+FcB6guvxRuO7Z{vZ4W=9Jr{R-O4L>=uz3%q(f0jB?a5yo2eken37AMW< z39HsDQYQoM`z=*YR6B8@I3_iO zs8pM4YhN&GyXw8orRM1)46mk#;6mK%(Uf~r?ihR~N_Fd4L=$DhT>gJ?_MSmaz-^az zLazy;(g`36Dph(Xf`W(?QRxJfF1-^VArwJHiqbm>Ql$49iXbSV3DN=t5JC$*^t!p{ z*?s5Pd3V3;_b`*0%y6Cmxz2TdS~bf9?Ti_km&yABvbBp^N)4mcxMG>_Rdhcr^Mb$3 z-JU}Z?oa=`*V5eoUxQq6wxojnExcH0-C|wmkRPjVYcXv%ohq2g)s<$rY^DNYj=A#P znSy_Yt_rlLTI1}M;X7^1f}_qg1J>j8NYeltQ}?M6YXXVi>sfJOc_Nd~CGb3DTvri& zkx^Ul%^t~ZKjoWYE1{enO{i_z)YMrFua{7PzioK6aqb81TX za8T{4SiUwFg}i-{=KBA8qaU4a|7uyuFPZwky6>439JE|l{eOYE+ir;@{zF5|Tvza6 zRdrKcH1&#z48tyx4)w-`+-(q$eUZ=#;0P%{9=?Y_HIY#qz$U1NnNgfbbH<968-L@o zAzvu#R;2@YtiJPNON@8`!l8m~WsJymR;flaQDKqyvA}$ZA#gV87vKkN7D!(R%4`*0 z`%crkL*z{<=+J>0P?42(ksBN`gpHD(#!iuJGmWG{k!V>LeAs}EL|I|)>tIc=yKoS9 zM@trr5xAcl$N9}w{kU}E#>0Aas+TQi6HOegK1*xkMWMYBu-)}Whm`Gw#|c18y=%1s z&`Q;~SnvQ3bf^E<}u4?56nv;X<@8=uoZGXFJ@^E}4M9sxKaE(S^^7vM(Fu4_3LXqan z>6r%Azudqcmdbnn!&S;;&bKd%^px|N7w?J_0pO^<5tVg$^QpcD#BFJt#n`|6Jvg4v zT?A=)O>gK>2C@Jb;&v+86~XuvDi2hRX}0d*=M|DU{2ao_#TT3F@heR##q9HUDcon{s3|aL+dN@KV(ul7u?N(SZ-=bIno{klNgWvANT0uhs zAv7KL6SxyLdZIZObo@PD=Q_KVN+$F5$su`YVPv#P%SGO()%858>AvNPxr58fi~8&O0lr-$o? z^BNGm5=(uf_S%D2i#Yhrp03FOe{h(UmrXM@4To1(D}{Jh@Bmc`@2H(F54TjL!|+C> zb+oep>`R%X>Y~z-MR?i1`+F1>AG8WM#6uMd;QaMzn1FV(9+9GpGPt zJb&j$QUo~L!{*sOiC{ly)e0~{SL5lb8hMzud#0maH?Sk&Os13iVZ2v>OROlDsjmEuyj zy!wudXA-JWU61|8d+sPW=(3yZFz05+9MOLeu~C({cXV|bY$2*zX^<6g+PQap-H4o5 zxvSY4unOlv6Rr;dp1HQFl837-jqul&cF0sT3IJ|1qPbPG9?3%lCFbzTa-&D?EZbkv z=?nwDC!O0@z>Zg=TZB6rTCe(Jj&h@J zN{p>6SE`Y_PWBKFR8AqKk%+i73D2^;28Z^Z5HmYninUi3+*;@(Ug}5InYICdw-Np1 ztKE;|A^9UXZcHaI2RPv}C`i~gKTXf-49VY}$9MmQ&UXr=1{vG;Cc< zjiIPkbw8j5S#Txl1uyIM<>@KW=$i3LIXxIR>0)1XlRb2x;hq>?Up+lFh2u{TJU162 z-)w#*>8qi6k#oCJ#sgz?zyg`f^^V)~B-XAi&!KUPIdVtBi5n;TX>t9hHhv^g$QC3v z$tr68wVzI*7l`_H2QU}V=G|SlP^-fez{SCXjce1t8XRX)zt@R8&XATR3Hv}#5&w;^U4_=3| z*3DGensNLvE#X9y2T_@!+F(!)Ycoh%r8a$PcClCQc6E36f|c}2uRnEp4-dn6LvpuO zGmGSrbBBV~!ga;))a{np_OTIb4>C#0^?*C#B7`C^?o76V0Ii_l3v|nJLK}}-VS={d zcesgPG)5AVj8-}J%hCxgrB2T9>1y*A1#n=R%7^5o2Wy=6!J94K62Fp_#*=N)5;kxQ z$2wA5arE2g3tjnfkNVf}iVbZQ`@kMj_id7%iO&7e0{dCvWRH=OGuC&^!=JrkAg7|1dnay$fYGU=JrLrH{Mja?$k|pf_;Kz*ISe&Zr{-RccSZq zJ&E^ENs_sT*4g$Q^0|oc^T9uA@Vc~VuWqd}5?OQ>9L4%%Qp2!|8G^WNPj}N5%82}J z#JH?V6NP>Ds(+GKj9p8C?US}?k7awMV%KGKlANtXvF@Juy`fr#_O=R)o^}PM){(Sk zyf|$uC$;`ez@^K4160i1JS|3RUS8J|^?MUvfafnWa~Mk~B)Xdpj;D@mWFptws!LL{ zc5eqXjD2`emUeUsYle@l#bb-%4kRyL>HqWM|DWc3lOEzWQp(cIjJi^MiMR_U)n@1o zvl#__C#A~yvKA{kx(PhT_n*K98XC@km${}xGgxYz;x`2rZ zW6rgk9g+IUGJ`~RPvz&Ez)A(HF13!bEc!^4&dd|0W090;Mq0F*kgBTIy^izqby8fA z-jWgU$z@9@3ZT53C%lKx2E5p+mbV{Xee%K(?*|blGQnwFRsL~AdydAE-KvcVzT40? ze+S=FhO$&jhdh7)Ww^+5DJ4R9g_W1aRC;TFJVrP=cdbOE1@@r@u`E&{y>WDGKWtVDK)huHlE$T^Q8N+`y}L zYS#REc?hNy^_0vH*?FX`>XI&!2T-IlU_M@f6)7}CSamm#}~ z)_MPN^r%!R2YEBPAK^G_oxifn6!ydgYXQA1IUw8hzf68{EwU>ctxD0Z?4b-Lx z&w5rb>fdwLT;}-7c_T}jE!v-^plUe!6X)4%>moNR@o#CR;p;2*7ch^uk;Dwbd^^;tl^WS^P!IxwKeYu$z z1J%{d=H+vZA1(pIKYPNtLx6L6({f@tM{YVAo}Y~<-k@Y`V0y6qQA)a7JNq+qINm?aw0LXwxm~aG_q7L za%b~l^Ufq#WV4o#;4*Fz7+5NlEP5-99kgGTknSXwNDXADs30L^zxhes<;=GLn74)> zIj&^Q&o`L>7KU?vO7u2cKaAVc0aLq12(wn5)weS|Ii_e*lIIk~@B zt|2yBA2z9;C0SadRt&7zuGVe#-@U(`Kna}yCuMdGc&=4jtwLJODQG~kK=agv`Gv66 z9{`mG%uNss+>ICFrALn@)-c zQV}dCb4%hs`0-7CN@gtftbL`yg3z-vZYGW?1*yK44~ntFd>_wFvyYsSw|b<2>Ao7A zo(%m<;u*ZF`!Cb2U>N^9MI!HVkhkYWly9B+CE=en=#Ko7`E=bK8zf(JFTJ)b*@tkd z)hlD+#_^0;ouM&zU|7R);D+nb_F{agi>=ZqfN@usITseVWcj!#o@E?K&lQ*$o=(ki zoNpis1m}{5gvP56ztN@2-Ybw-lhj0GPJO1HNzU#2ny+XsA7}ec^<(x=<*{9!r!huU z?9Y64|yjm0TWh)2V~m%!vq+ zp87rBCojS4@T7p(ZMBQyCer0vg)t)Oxoyd93U;P@@l|-D%Az&L;x1;zHv=#EpILwG z-7Mj>uZwIopx&F>lddqClXK)KWIzvLB(w^-CrF(K>Lad&*#}dH>%+)$V!^E5zt{g+ zy*qjf7Rp*bU-@0*v>^9V4w9`f7dU`X?Sy+eB#gt%XcVUu#rj#)yGar!4_Ce+zL6Rb9i@_D&sUX+h z&F0<{-+w;){A(EnswNY<$&OhD?E<4sb-^wiWVnOJW=eb(DMxH*Hc- z-mZz(I+%9cT*=?n`0yXE-uCuZOe_ft;O9wr>+|1}bpJhC*D;|>)~jkkDhI5{jBAG^ zkp8gDAnWW{6?nVLPEb{bzIBZ}hY2MctEnUwmi>H=f{i&_hnitD9r%SjWs@Yv$qFBk z&D@H697oApg-{U_bx3Bsi(VN3ZcNUP&N1FCoPyrymmp`;M14@jx{(>D1DR?nYuV=6 z>g`W*<9Uu}iztO3MgcF^fbajrSHYrw`p|@{FaW^M$ewt7rGqZZjsQZBOKPkffFC(I zQ3Sv)z>gjPBR8z!@y_J2q@v$>^D8>6MYb1m)$;Av+#C+B_z4}_Ed-JYx6LwZP8{H-cL zH+w7H)&{M)JwJ%I-g>#PM^ENphAmmPQpmqfh3O#DoWe$^9f%V<*s~vvbT!~VOPze_ zp>8XyBzTVpU8+DfGSc!Xr~*JCz53jfy6MLQ7s6|Urp6ECZm2I*fHJ;Lf#{qP6O<+f zMKA04LQL8}_mRy$n|^$HqJMBcW9PR4stVrn-Q`=>Wn2NF(+gt*>==sobi4_B3>TDE z`H`4RZjF?fV)D>=MnzN=9y9FBA$_WQ?X7I*o)43iMoI69PnPPBhOT^`e!)biiS)}) zP=~9-hbpdkTZ2pxjk4DLCzHzFk0u$`en&I|S}45{NF;^vW4B`>0Jq!-sL1gnTTyfT zgFxH%JRSil$ad?}ok>aqkXj^HY}ab z)r!HW$rI5ENV#|q^XUzX&sqDC2;fKmDln7aA!J%=KC|l+xFfF~I`0JrkMiRb%}}%r z{=uu8A|O}sxbat)0ikVGm-l_~@9k}hj^O@(A{-7|$ruKXt^NVo|H<Ww~;YO?&WJBgTV#`Pw>pL8LDUPmsSLq)m>N?i`J;0e1Ci$Kc^Ra9h2n5XT?@v42!`9yuYr?TpKPoKtM&@Wy*(NR>FX zM}BqM+b2eHc@u^%Pgpd-)gv!?zzPRN(>`K_LeSOS9~&dy-TVUhVH@JxzyhwE!6o z%d}f!Mj(qMaiFB6yzM4^@YynGjeKzV*t46DP&8{X4u2DvntgVLrNUY%X>uVY$Lr-a zC6_uW{}cK?P4yt zX*FaHW^7zOrt3Wa!K}npg`B;|Dy9q=4y-eW1KcGyn_=~CC9H$JY5w?`CgZbGPb;?% zVfI28A<(TE#VkJOEn~gc+U&sbT2u}@Yrt;~C;q+K8ff=lg*TynY*JjwNce)+1O|My z15TW~xR~p@zMqHh3!8|;)a`Z04<$q;^F+)M@rB6s6^x+D0Xt|C=#A_h#anE{6)jWY z(rraM!-*yMHO*|BgdHS?O_j(!XDxJO(MXEd53~TTNoJ8kRc$XK&DfBxn@9X2JvXl} zD%>5HJ+}}(o+8hq9o~1dbtyl2aJh;C$X4{QCNnD_!g2`bX)#KVPj-z-)e#d1!h~~= znEcHHm4|eS>eWazzJOz>4pRMuJ%{4HEkJMFAGr_&@8 z9W-d12G8ED^_5UwukFFVglP+`ALZ|uV$)w<5i-Ytx$QXS_J++_LOcJqh#z;|{~__eS55nWWlU zU*Gg=Xg%)}0+O-E0B!(-W+{~f;_M*vQ4l&yI3<%Q3Jc(k4Sw(aLStvEsMo%i@zyGE_j+lOyP?aw zFRU|J02P*HXjpiGBoBWa%wR)=`+As1vvMdK-KU?PRgY0IQ&Ey2e{XNqC>VXg7V>K^ zJln2^-Rdr+j8b>Al-}U&k{**c%Z+B2bs4RlX;zpV&2M~%ZN=&z<`cujwdwm+&sNSJVI3S}$?w+F8XM#|wR&-}pkfET zz)xuW|G=D76NxO;E@Z1H5%)nSL1npHfH#bK`DBm-rS@1x`6cCV%43q74&!1p$Irt4 z5}Ep}dcq+73q3bZaPADT0BgD>2EEHk`OUCBTBxKL{buAg$62zBSzJS)3nLQ;FZxjP zOxI*HK4*w34h#7Fiy^J2PhmqTR3C}c14TbdPwKrxW;1wk&!-53zxZveTaa1&rz9wa zd3v&#sxTq!1@#dFpN#!Idq>+M^Hdw4l2-akigt`FXmLp4b@-)3($zfAIeIU~uQgho zK5BvcsJJleeysBC%0%FwoW;zUFnTluYS1xEDYitZU%(e}Z_AY!YmrzbNf9BRhHs%w zU~z8#$(KJ{UDsxTTxn2&ArI}5#pnBamt0Vs1+*OH1vhE}nXCZb5piJIaPQ3QnX?$_ z$)MJ}_ZB?w$P9Xd{v{Rx!-vo>cvNQWH_oEAlzQ1zIKu(LC+_) zLMR7#_E;r_z2pyHs)|6M+z>1G*3_NzjuaLB(HcVsZCqBK%L&$7A>=D@PzUg51~&2& z#f~uVU=5}@|BR~K=dru)nwY+g5 zocrlQDwn;V;WsNT*XjKqA!~)p`hg5{_r%b9%#o5wj>%mJYX8!?9^60;6=5^!8ysAj zThnSJa~ythjdye5oOzLu{Fow{e6`p5fDG!;o+P2#-k;lPyAftNH+fG_>GIK3cV2DQ zASFhu3=p8w5PG?I@r4q53$S*LT0IGV zZP2|zvDiK$57Mp4A8+0SUmV+u-oDar3b=f_P}Ub|d5U+L+Z9U}*s2NM{!g;bEt>Qo zLliJvpG2%g&qcrN9fh+xfyUpp)i7tQop!e`w7!|S$LUL{o=ED6AaIa$SVsc|AAJzf z;`8=+X*@uGR8p^?I@+$xTZk7cAw5JZ?s|!H-gvUNFxRs8x%J5l*it*_cRNDM#HRg= zEa6E5!uIM5Oh-HGOZz8Dk?E(W<3}oDYmd_0URV}|_dE42|IS{E=ug(bH7wqhyIj$Q zZ&n|8;k3K-G57GoJX4lu*%EzwNyHp)t}FpnN1dp=T-qz+wgL;*rt4+>U>KaI^Utm^ z$$)>hzFJ!)JE!nldw)nJM$9%>MUML10wbU7sg-&=I;i~Y%h7M69-rp@w`r+<|U9Bqc!Cxdn?~E4@Q<1^jd#hR*N1q zQ1w<>s2<#Md3^3N)U3QVfftD%st;Umvz44aiOSlmU zQjHOsnkhz?#^WVi3mdX)xMqHA|Bm+?#psT2I^qSt={-&VyS&*q28Zj3ZS)npXH2YH z6=dJA+8c!-7;V&oD5~4 z3808QzJ2lM8mz!4{yp`A{KM`YulM$IIx1c&?UhWt4j0!jAL63rk&kau+-5S>8+Rq6 zf&5jh%7KMU6)*z!Y3Oz*tkLJ2bao;2=I~U}NowU`lj*>Toe+xR{83L32@;<~_T{-giVxQTR6F~9w)4;BisH0056bKFZ`CTZ{u+w2o~pUb;a zhc;~TDaduuFER1*7X!Io`6@0%r|U_Pm&WMfUSM_j9x7F`dWJpgzMW*z5got+W|ynI z-=r2J(LGaAb6CvH73Q0=-*sw&sdGFDG9VQb!#}Ru_Ac(KXYJx8fGmwwr;ACB#4j(`Oe@uE7qv5cM0p?s9{KMMqi z(BV?sT5hcVw2$c0O^!5xv4N$NzF%Up(Q4I@HTRCm+478ik8D2Y>&L1GD3@w{TJtB{ zN#RWg8>?(NC~#*-PP}TLPPuzA$k=V8bdl+B3y>plMf+wrul~BhypuK0rs5%UX!IS| zbq7r_QIh zZrQ+ywR5=0@;WH}lSH*_fl)8>MoAvb;HdH1Q<2Nv!wiVhD!cy7qr&zvb@n5FAlERD()Wd%J(&U z+!IUsX*dunnF_0Cke3x4i0ZV+?-^pOyC_0PNU|l8o%iE*?#14WmzxOB@o>vdQi}nO zh_m0NLvsMw4)D27u?Z(Y%Z9k+&)&e6qraNCbn6aR>yXuwS!Gab{BSJ^_w@10EyY(` zjXy+WW9pj!kOMI3(dXO_IobfLiguFkaDH@|6EvZEmW&5q&g;Pi2jBU5ftgor;pqqA z_59@zY)heCw}O6!ZWo1!_3dVm*kJAroCLWEg>qV@ocyWxV*WXKW~lRnG?jV%FQYw7 zc8>#=v26MaDX6k}2 zJ>hHLIQ#8awm?~(2ZsZ>qPqUHr@kt&8mk>N`;y*~2-E=98JqSli|{2xq6@UK=@!{w z3#N`>MUG3Ahb8fc`lgUFHP=;V@a#M9RLiFKM>b0FUQagT4wglmJr-tu0@Q*Jgv62rd4fM8Pq%hE zay?D&D!yzb?FBA46HCAOQ(AC9Q-QQ2n(C%Em4&b^;v?cshKoOtwhFvM+` z6{z0cWZo1&n`MX5JKx_vSCJ5V%Ztnu(Snn~l8{u|a2Z{wDdStGOIP-Z zE~L|(rwFg|TyoOxwoa$p8sp#nzx)$S<+&7Z?Kq_wF=H+Q^Dmn(qqnd^@N!^Jf!0b2 zwR2*ywICDLdyV6bGMitkUs1Br-tA0tf^h}ncOJn4+|*~Z=a$i`C3I#&gnwt;FhpnR zfSVYDu{#mJmnJ5KPB7jlzt4n6MJEP%{8Yc@uc#-L5Q#|BthLXP#ZPjqm2o2#XPaJB z7`QF6{(0{KVm$qZP$0(cr1@Dv-D2~nAg!+X6hXHs)=}ok)Op=C6R}=X?wSn8P2|%F z^)Htqi6m3AK)a0~Ba*%;FjT-Up?u<0sHF!V-xQ4Y<)RQuJJ|@3@R1yKb@VeA7@fxN zO-=d|pHA6ioJ?hZstHozoRHX)S5L~kF|BJML#Q3a4w<-`lDzu=WdM*=!|CWq;UCvR zAw_cj1=Zfg&k`k@dIh%TqkTv_=d4yO%ZmwtfU%=x{Nz||s~gt6?N}CJ9ZUL-tT_9f zwt*L<{QpS5f=_^=7^W3R@+3yIO;)^m;`{WT)|}Vw=aWJPqT7-ng+-5{z0bZHB>v${ z`K4AC@nXr*z|6cb~*7$ zYq(Zd@-?HYJ{Udhh&Yc61^{$>y8;eGQ2CSv$K;p7xSe{S1;gYyGjDa5T^VOf)d#>N zmUbXX0Kg9r1_T5E@<9uJJRR>LhZMbJCJek%#`4gY^Y;7VG#C8k+#T+UNCWO1@nML} z%6y{lLAWrDW?W7B^&598b~(IJGYp5bJP1nGEr5nvIG-PZ9y{XX=&bk|f^vcSkmZJo z`N!kPcq=_o_F8mQjjjyK9H1TV;zAQM8WU)jFD1u=`r8EKI@BmIs+;CT0W~@c^+;t* z#pZ<@J@5Yd-rL2^YrhpE$h?*(Yk7VUacvNu+)jbO*vsu7qoRnLIR%P34~_(EphWqO7YN{E*Ca*J33mC;$-iFlPv9+l_kX4l)Zw|H%(1(h4t79SEalwF9a;Deg0fymx-@r`PEhnnSr8n<2Rl zhA4J^70;%it7)QH)kUxzD@6)c0~GQwiX=XxSjOyAr(Zz2FI|S+5dvPncxkZA1un0< zK$VK2a~xtn7U2a*jX29P+8d9dI9rFi!}l*}l@0Iq#|MpzHZJfC)xPFBl4@e@u&Rw} zDibu@oCHEO*JzAgTh$i*jPz;?kGtA#S$D?W5~c*3`PpBu66c{5XY<{?eA~P&fd4My ziHl0C#nE(harq*lsU};|f&KXCy1Jr<-%8;0r|-x?8_sS7Wj4T<3MS`a21_|6{ievs zv7PeZ_ebLv&eX}&_s{iq<~t{aY9RsEizzrcjX)#G$`==vk$o%H@f2wvVsFj3Z58=Fr~rFSJgtj;E$(h0PQ> z|K2QG1xju(`yw=A2l}V^P^Z(X*x<24}vNu*45>-N9L~{rU+*(Ne5z!EoG?xVj=;5 zAC@dTE{j?3Ym$3esHSy>l~z{U2KvJ&j&!*Q!G4=`QU zStD+&QqYvC(1!OM-Ue`p{UPgrogfsJ)-$=$Vz`m0dVI`7N_7mi7oPvLM7FgOn%wRV zDV^1OLWYUcb0^CH*R}xbZ|D7Dmt=d(^t|+8doe4x=eUE7n$mA36&@_}BC#qzbGuXb z4zEsHYC_KLw~;mqZ9)vYuCIFkV>EmNyV%WL_Fdg14#}^cJ_Zz8J)1Lwlc0e<%(idm z3pfRvS9;g-}@?m0X)Y{y4LtAFtX@o<-a~j(;(B+X((3`JeE2U zpCzqQGI<>cb^(XlP5#*zaS{7p8kRZ__asD?fe7(>Mxueh$P)OzxO)V*G0q(s>r1VWYVA;UwCNS=J-4QK)@m?U1PMBVdT5Iihau-7oo$W zslS4-gs4yUEMDx_Ze}mJ@^H9$s{o&3W8UERJ$n%z@A7v)o@cT7GJmCcBmXQv9lp8p ztleT}xwATc#5EbIc$z9WkdW?pPs}!92sg2I;5FMIeEsH$prfK{TDx*DB&WCD%b;ab zMPQ)zS{+D`=eK=&@)G~3q-&vG;Nbqm^@izZruI77hPnz37>w__r-{m^i!@(N^P2`b>qF6C%aX_3ddm^7f{0=AoBG`5-3HCGKisL9Sw~^Vv}K=1NU|cHLmD z=Ty&}H;FlPRiHV4P#0Wr6%&M*@vc++-`jWodu9N7Kzv3z5osSIAqwUckQaKF^d0<2 zB-hRqjoV;=0;Sxo$=4LdHh%Q;nEs*-vP-5dPl}vxy&5Bs4yJl7;KaN8I%gRYy+QW=`o1%69K&gwG*D*(@bV5L(D42fb^#9O&VZy!YZ}^m zV#sa+2sHKAiln}}gta#;yOmD^&S#w6YyJ*t(m9w@@d~4!pfXtfa{=cO4ayFLDo-Bv z4WJeCBQi+jfP^e)Y8B)bxS!;E=1+HnOStmAvISHmR39+CaA69lk1Gas{XP12|w47N5l-Z-a4GV}7!;CCFVghl>64+KC1?YYGjQ2iEc z*||fg>)h0M2{l(vCo@10OW(V(v1;VvB~RP{63H;>JJ2 zR)5g2Zvoz9TeqV30h{77o@z-u3;tZCRj)OJ*>5PO z8w9{_IyCnBH}bK0b1PE2Ywx^rR{ydUEV!@)`{_8+8<8T$nor*U>+yAC&BGf|+Jg1)s@Ot(OQ9v&GU{B--nKqffy3QRR z;?kmb9q&k>CrUa^bl#$y;_-tVin5y#hP7K^=U2Twi|(>f~whU(djc zlhywrXIVAyr~esaoV^kEa*`29yIQ>l>{0KfP@q3H>ri(|=uHYh{fI_{+=fxPWI)XP zVk!kE_0ejW423M2`zg^QHe-E~x-HV45CvC1I)Ff>y6GKFjf%Wb#>ZCc9+vv+AS<+p zuHZgU2~ZeC9DZC}aN!MZ!R+%{eLf1SoHO3^i<<{*-Jf zGJkF78?~RDb8hsV?PaW;$v^R-xR`x_tQ!#z1ZQs0qL#V;lAj|{TPG0tNqivA_{qW8j|73FPq3KKz& zeVe>zm2Te30PJ^ie13||NTBit^W&D~EYRYvU^|c3srOcXp*$Z7?(uT9bG z_3+4DW7B7F{taakwiX_$ZuGr+@(@a(K%e|V41hHU` zC?7Dn-Xsprj-G@beWvtswx^yK%^M1MdiKvbv&(7c{KuOnzyPFz>L zM@5jb++wSK!-4Qd5C?1CPY=sKj4Mgea&}l!IA`$;E4r8Ag{1⋘4U;q^1y7j2htT z7`nFom;cx&^Xu$i$ukD%q6z@-f}5>*Mq&qggNNWxtRm``x#s^_>;>#UANqp@pw$9V zS~v@y#;lP;5TMh|^X-p{WCwmKek=#m*(F&ify?$a8RIE)R}8`yS+;wJ(N@alq6Wf}*JX+ZshCi??C)N0VZO2}!Y(}=x&1*suK33!7 z$SF$G-CC<*$n`>G+xf5dlilNgeP=5BZF@V56MgaiNaXsOU{y40-_X@wMdA?RgmUB7 zX~*PwX8YL@X=UhEx{KTIwzjo(%xztnZU4$IG>ED!fzQyix+z@2UzJ7ZhVNKA3{-{s2nzZrbVD$M@ z-&O8l)|0H1F1Tr4V>expnjB<@m@ci@XlS)N`yJR1bg=n_v_Z^KRvDrSoK)vDePH#D zoKw0ZPunEKh@?gS@|bN6G6^Fw`Y$KX!zDuYyC9nMz8~pdarAgG*B)6ng|&I+bw_Z` zhLhc_puiF%Ky+Q}O4)ACvSsv{62MDcl*aFpD)EvQGZ2+}>tW5c19L2wm;7wl6)wxU ziotA#`gp`ZV76DA{7@^2N<0NPvN%BQg54mE`Diq zKb-YK8zz4^^MGY$wc0v!rdkqtc`lK7qX3CnPuNu9vt&cXA&FGi3|oE(5r*NTGrGF1 zCopytpH=d<(AA{`w7H_-hDEfvV050Q8(x*JjWDD-w)HrZjv+>07zG_ZwHOMT)@_zo zt^F`apN;OXIE%M7C=ASY$>;vnIG|pi=`nlt%&FHzV3c@r(Czm%(aX<((?oVr%l27% zlB$UEnhmli-eFc$Z0*^1zj39+QfcLa!@>gj&9>zRQArVHOf7MG$VZ-37Z~630An*# z@OdcypKqpc{2IG`K+k{b3X%fzx=E{#XbEP&-d^;j;@(!{>i<3GNa_^4PC8(un+E3U zg?p;vNP$N)O_$@}v3p(0DBEFf^^SX1;@vGkLqHIfv5i}AG}C;ga}iDT`p=(K!W}bt z2w)jNoI;N{O>wn5tu^d@Ht(AbHZw}N^}0{HAShznZmpBQi%sfIu*>o9>!uSM3_ zZh$Q-V6VSsstyEb0P7sxsGnjY_MYyHGo)yCM9hA0R|vmvDSXFjt8r`lY^X*eomc_Z@)8w%EW5`BJ)Jgsba$Y zsfTireMo3a{+Dw5H_&GPASE>_Z{~n~*(CuoN?yA8PDoWpF1rn`7sLO4x2Q#(+v#Ck z#O^%xD>&0L9QovE;evd}W3uAJNGq+66ySizET~lh59h z56InDHI#TIcVCa-Iu-x%@phQ3AMLzU=* z=R|;b-M4#@Tr2?lKQX*dJClJkGtaN$bP~L{rglDE4fBPhFVQm3snK$})vZg<+?rs7 z;(w^-S?)t|F}@UUqh%SjFwhEX^NZdqiudek19ugknR=zB9jOsHno{o9<)<|MdX~Jb zg?J$tS%Cfx_ey|3HCysI28n3G|G?Qq)GgW7UQz1695O&9E3SkZkkC*s zGf%7c2jH$5HK|k@O>GJ~KLsFCeyYIl+Q$0jN-o8<(M9xp{9}oWd{E48t*m`U3A{Z& z$;tV{)m@Bfm*%Y42n%d}Tr9^c(Z%(GWlxledXUqPz* z^P<@Nsc?uLjo*ln!|QbQ%Ei4t*ffFnQTpeO*4M%m{?u9{N-4KGWI;Jl4eskS;_U!) z7(i$*3y2a01w)kKOAFMPZ^RXhVm2ZWzP#xsqK964uCxeyjT9BPXU#2v$Z@nbD7oV? z(MPW;l%ADFpPW+RzDun>Im_m@Y1=M;Ae&){iVN&NNEb_vMeJ*0#I8oRll88CC;uUM z;d=(sf8k&CAjvH#^$9@oeFsHcd))8cs7pGQmudrJ0pzFH;@!p^)xn?3;*q4H z?Tp-HhbfLL^4JkqsM@#>L!F0LK&7l~&mbGRZpUBvpt^{0($@7D|DJOEsTYX1nZU{x zfbxt4q^#`zy+~wjBioBrH*B2_x*p53W*+s!y z=|~00t^MY>``SSsi!;KI^ag2N%Kd4^B-QBuF!PWMJtlpos;&1Ztn+QvWKb!?lUzGd$ zABZJcGrZxdyyrzv|0|=4g!#-fz5?{wKT73;0lr#;9Iecwzn2_7x%f8s%h}$g@O)kD zD&QpA@~UiaBKyp|$^AqPz7mK77M+>HslABj=Ux6$mv2rs^@6H{&SNiA+A_sREy%$w zO6NP$Pd1a<4?2%LS3Ql}7N%9HX3xZC2qc8VP!DO|T#iP{^wNfpFE>Xpr`+R}L_ZYN zmn4iq+$q)Vm8~l%dbKb@bBpUyhd(g^*rL{>ZSGNKxeO(?^rTuZm$&HBZA7_Qe6O=4 zj(**7tlr6t5Ptb3tG34FBzgPOx6}g{$!Q(^>=W$Wt7I@npe(^+vfF%ZVX{o&rqRh0Gvk ze@XSt_}#$=#2RFv^SW;h`hA&Pxf5bk;9WB^GkeVkn|~%Vdq~Vz*sRrZ(Ru1L(UNYz zru#M1w=|Qdnu`!}bdvQ8X$N14Xih&InY3Tyc&i}4MUo8psV6b%M+GZv0-25oJ&sK| zjD3Jgd)BdTZ2_L71sWD#o2ELhX$cWYSCxwLo=B}whCNVR?wTCn5r$=*6dBfx@% z=6~?@-a$?E;kR!>??seeMFpiPAiauGq$*0U(xrC@Ep(NtG^qjU(t9T$8cKlBq!Yl< zTSDlBa`K*;Gxyv(^Sl3LGLxB1vS)vvy`Hr`i^IxMfjE@kLl+SWNWLcOR5Uv!?gGRp z5VbalC}}0n1oZXHapO3%@^X~%W zRRT8o%);u@c!Y7>bnSD12mFLvl*aXe0A>M51(UBPrG&1lJs$8-XmOPJoDwfbEM;;8UjAuG{! zUaN!T(;z?^NdSUz5uBJxDQ9y~OqMiYE>mF*e z*piBffmi&`rd8S(Ol7x{l=LoR8n(N z^ImoU96cckAMY^08`R@1A>eC*PA>)lNBz7#GHtd+lis|SE(Q&Cj`(q6!@SS(XzFTV%O;ng z?U`<=zI%v_6MDL{EIx%oT=C}lMEt^P9zg+zd2h1# zogM-(VhB79l#)dLX>+s)#&ZVjoGbYE36o z)HUKe2))W(KF6fI+ntmK1*gr9mBy3Ok@Q{H6G-`nxi<)kBn&l?ilq97^~ny2xd(Z- z1+1ExZ30rObD(;{K*0N%A}-Evz-Ee2H>ELTkon5%>|s2dXiL{9T=Mo=L0X415HPlG z#gPu!5|vaq;tMkf-8T${UY#dhf4G>)a8p&3XsON^*=H+I#!y4?UjZ(m@V#<@_m)2df{jAicFAifwwp?{23k%Ek5?*6~g)Utf zxF(yd=K!TW*Jl7~v@{3yTbD@`iMbgx`!pd@>KE&>WlmS@~ zp&GMg;Tg`ZUzcp4*{F5tE>m>6w?M_Li3?>c1Fex{q7kWi*O0YD_{OodlT%t9@Yit9 zC@{jJq>3k4c7`Zm0V<8eXGhITw8Uz!F)z`<)}!||X+NA>*bv|2b`)gjQW}?Aaoi)m z4xr>&=G^bbtY^RxH^U;SVP_1AZ!7|~qp{ta&;q%`W7PU*J_tWL>=er1cd?FbfF4(@ zi$Sg{>gy;)n1olluDjSBnNw+3l|i5T5)mOdXnFxo_`eastpAVf7buHruG$t(hwo#| z^5Kqqtog)gn;-T%9UzG!azMh9yTuHy(za{)PK>YPnAXwSxwou@;lH zIffJ8(5a@Uc);)iAF47#j@4nlNa`qo+W1l6Nt;d$x?!(ev^yv3iL$_xBi#x3<_xO< zn~2KL1Dtb~oYW%{R91^1#3_9+h?W$mpnIc*5Jxw-ENWfw!JFXrAlODJja|-zhOixI z`|e+oBR)Er6C+k%%QUr(z}aWFq43iNZ4}kU-;8ZzWYCP#VIF%+nroIr*=|V=K5ofB zpg89SGj170;7Q_Ee-2x$ee|1f;`Eol_IJ>1B=jRDp2sudC{Qj%lx;zKVgrvUj zo0W!m^Aeq#~S zUM(T9-{CoLfoCYJeYa(Uk%%vavF2J`SC@LgO%zf5l6egOfu5SbI$bO#irrfL*67d{ zz>VviwN>jcx8Q@B+36NDHSo0%m@DTadA_Q4of5m?j!r=aUYXDt+xfX2yX{AL1`Z~d z+w-M%ZpcPZ38bFEpMSxvf73*F;iAR)tf=zzX05#2dB$CF#%`JH>_3I#DTP0x?|&;4 z(%T>X{--1+UZGIMM=>-118JH*#G5;-Q2yu6%j5&_kvrq!fN?<2PKa1fY0rI$>E>T> z4o8a69Ik%_v||*=f6a$VEtKj$h8`rh9KbQBP99WSa)MyEaHxeTRUB026yQn(U{&$~ zKU0F$%F`*TO8|_*j!C;8@F#L@5En{h7X~aAR$Bz)#>R0C7EOy~3oybuHhCOC$DRa^ z`Qy;L>dly3319|(3Uc8jd!$g*sUsaiW0j?Nb7bj4Tl?6PDuRTHfalx|Y#+fYBuPXi zyrMg$j=ET%rasq}seQ@G)(4DnQ7Q`Qk(!o2*2jP%X}HCIdD^60e)v3_ z;V2h|4dx&F^qcU2IDUIDkR)?E{2e!E)r5n>8`>>B=^d6gwfSsp4Irap3zxhu&yKVSrU@1CptS*{&S(Zr|kzoXJS57qLj*1&7l_ggx5VKM@Ymg*<22_gZENj z)zYL6CAfVUymjs@Vc>p0ry3-^-Z}+umVEL4h)?W}g@Hp<-fMH225bU%EI$!GBt6|=A0T@jKvp|BI)6X{R_l7>?z%e28A$0k zEgW^`uvh(CMTA4{d?Ls{ASP}+RbNOk*7H8}YwpsHavvdWx1uVq^7l^vTIYywC(Z4V zVd0W0<#Yz^?%gyal#Vu`%nb6c&J zx@T@yvZJA+AKyr(l6XNRmW+@1+Pxv1}=FO&KO2C_d&lW*<281%bw=i zWi{|V zTmIxz*x{BHq0&!pH+4D7n^nat^iUeSVtwMzU+hXGZ7MuNIBIW$N#yY6j`&K)Uu^^E zK|VDDnR#S^Lm|~|uz6%fp-pD2V84w|BQZSR_3%9O6Vtz?ktXaM^!)9`0s1l=>#c}$ zuB*-h9(Q!F^YAW9Z&5_nF&zO|mEqOmyLZ3B5?EYdhDy$B*s{N5LUDk+x*{?_9WjA?9`yC6ZbHVwf5dDR*x8z%Q6l@GwPXQ#ul+BE&twf8vlF_f%X z0}6R1L1wX)eC%O?3#8F|iyYQAoNWQ+i>)_L(EiIuQp zY#;VO);5HQ`GJfgV16FuCMNSeG%yuaeR z;Ym6%OROTMb-4YbwI3(9xSGtKCRw(K#hAOV85{2kD5GhL#?Rh8j9N>~n|hbM>7EVtn@`~lXVBGG?4B&-v0=5@V|3U7I<@W3-}+cV zJl`&~Jb3$028N=`40$=64OgKx7jo~<#)+cNuKcf_`k%ZBKVb&yRwSx&jj&NxSVglz|7bA$4(dT z>2Eg%CCqj~c1uL@_U*wBs?0K8JFuQt3p)qa_?dF<9sOLW<$!O<V*5?7p~0qa1=Ga1ylcHs zU#R{;b!Nz|gZfPa#CY^rMhK2CFDTod*?zt+Bfo3c?abuV*qi^Ar&kNb;K>Q1O&`=ZZB zP(kbKVeh-}@lbhTMK}JypBK-B7MeS+HCQwALWZRlL`UoClYHeDH0Dtox`)|~V(t^( zxrWON1|0JUUt}Y0PbF9Jan&d^JIF2>o8Fz_b^JQWVJ|IkPG`u^$?0=Vx}cg@hlML@ z_fRAADr~RIIJtPxcR8a8t%+W0pau8dj{p#9Ha?h07lIe)MHLxBjl9l#PqTTi_Q(|H zXryhOn-zTFavK79soP3uoTOistWb zejID0w%c_ejQf2~1p8jCi!QgCmi(PmOM`d1h43ppXowq9Fq70&;P9l43YCGaUV9xD zDXMi_DqMoPh(P4WceWmmY364riG*7a{6BASKlHeKu1_1K^HnYz|G~VcZnqeb)b+Gi z-JN{2h~A@sZ?Xifd{zN=#`)2fWhiPRS_C-P!2zJs%HyBkue>{wVJ>IqhTd+&w3?Z; zvE(m(%~JpdZ4G+RaxVxfCGeg~MYD6V*KWgg%R~U7S^Wzou1N&niO1A>YS_902;>z$ zs4%&MCdPtR>6I)OPUD6Hm27WpaqIx`@Tv|%zc|3IATY+1D4thuJmG0Lf4`fmo|;Gq z@Y@&n#HAvPu?L4fdwv3-pXenm@bogeBA?|;ZSMx6zMA0e3O%BrgjC(d{WsG# zGl=@Hg9i3j;<)?uX4W~#tJ4<3+BSfdH(L*a{knO?3GlL)Vd)OHH-U)vYS&!=oWAGJ zpXZ&FG#JLNxc)vB7(kk$5mowc^Ss=*cb*_V2HZ%*O%cUO;Fd?sA0o9IBg@2@_B>uj zD2HI|mG00evVNci09g1yce8KXN|HzUp$3PFNvsK3%VX-L2hSuJ?c8+ zH$Q}&nsef#Gyd?wh7LZH*a}Hik~sAC#Iv?*{Z!0}?P%8M%TPpRVSEA`%U$ zgZbU}b5fMjyz{;=`O|=E`!34(4yvkf0q_5Y68yYNM9A+EP?nIK1PXZ3odbc*e`VdP zK$mCng;@v)I9tayH#h%V;>pLId$83$^bLftKRwf}eFpk;iW$6r6hiZs6C<59_gUgZ zVpmR@lgx_Is8tK9i}8c&22O@86B8oM=iQbWR17Fwo0d2?bFyPU6{_bxXI_mzD5RjIDkZL# zc@)oktvI`hq3wM(aWFdOP>{dVu%hp)?h(R%H{S*nF-_S)`blDj5nifrGLGHW4XeB= zK;OuTDp<*jnz|v|DabAlFx+$b`e`?Eu zrFKS^?wR+W$I(|-nBl0nQh8}IuGjDnm=~5|m{_>T&BRRd~cl};j z7ltK<4C^bc>_lSyX{h9_o*sB|FjX>m&q^EaIwl<_Qz^f=&VFX14%)i+uBecju2bau z6BouKqz@39*yPQw3P9^*z_Z!dzkqs7Z0G=i7vl@EDcsY}paQ=t@8LxN>&n>wVF55d zgQ`|a<}k3aW!yK{KGW+V@D3q{odS=w8w_lXfvtX@@ueQYgy)pH)x1+e(V}a5NO4hP zV-ukYGs0=>vxDVm#p!5v7nZ|=;z0nmz1fFjlilpI<@Ac-E5gaQ%jA=hXFXdS zfE|H=_c0!`Tzsqdec6+Z_kLX#pVY%a_KXXy1Y`cr4jqeK{*b2Gx5k8I!BSH8UEX>J zOBWe{Fv%fGM3-6jH7pxLJ;s$Z?Y`7y=%#S?8t-FyZ%Z@g?9^KGTtTbF_@AIqU+h0kC{yzJ$BQWk1=D6g#BCZH*Ny$9W+8-L?9f*@ zYC{V`Nx2*C4|H!O6-k#IMC7)qT{g3LHrQ>JgQ7xDeSWN;i_wNE>{UQ`LJ$uFW>h)} zq(XG^OHS@Q*pwMMu_90&nbgtbRnD6}LRJtHKXe>5VvVq$>}Yhd*vatijNnAuD(-41 zIu#2)k`MfXcvlCjxQfo(kp1yFW!Xg~8|9z?p`O;XSgY$2m50BA213s-B$US<%g(G# zXmvNp+w8KKfE2RxE|3mw@eNuVEI5UPK3|5Rmi2F{lIbM{LZcS4DF5IorsV?Izu!ifMytjpfuV-C@Ps7N?~k$ht~i6-y2{S>l7)8fR?^eQcW=b<4h_Q6u8OTUEH*~bevh){~*>B1(JF|;bhsd;%? zTe?|vZ{oE@LPO56=!5-u^PKU>$xtI=giyCEzWtb2$i<)Fz3Rz@H(__^i6jzbfc-aJtkfZUw<)r%tvqe z();Zts^p>N5_V}*a3*2FE9GF}BGq@nE7M-?amZT})6J_c)S|}rqZ~x&mebpylnKtC zvk!dW{*Z>U?J5iNcfxQse|XVBv)!Y#4u0*2Q1zEf&FzRK3B|olPO@w3q#jb|TaB>9 zE33uhrl9|6D#0f-m$Twk@MDR_{~k+10~S>kubF^v-szSe0i2RB;QpCYu-YvDD&^Hu zZtkp42hoa6(5`R~y^@g2TXL|4*&1IP@OJy}5!skaKnmns7zX z;^K~hWORm5_`3*(Ghn7*-P|5YiPDw|-Rz6k|4M%+0Y}uCM+wiVdj3eQG=f_uQ?UPF zZ^2VKfGeX#2`10ny_?7$Gi6XjKo64WsbeO!TW@~^$4LzTxzU)L3ryLHq`R*{lrDw7 zo(wSt_B*~TZ}|g|;pJohL&AUcsXKASnFbLW;TlOgwEM<`WKM`c{S5mjogpgu<%B-jaCy$Rp+%)5i7( zjzf?#f1Br>b&PMKzk6Mj6fw#F0(0VdNueBge>@&AK>p1;I6nI=Fhy2?<&UnN5oBlCPfTc1fBM2j zuG}mea<+4!vY&Ta;Pr`>1lp8X-2a^5Fr!IKXDBHVVS7^M<=~n-lVsAbpx~y+^)Xt( z$%aT-^nWS=Cijp2Tzk88a^CwnvX%b*rC7O> zO0M(wweQ&xy{Js_Fh5XuaA|p7J~3aEgX1|Pk(V8vwVcuo=ZULgOOB(4PLVa^S|2(L#tGpl7 z!@}~%S&pOz7}_>iKIPWZ*URPR+*wnf?tAI1L2Qmb&pvzpN5)=Y;nUz56Yvg^P`){b z=N{F)Pdpgn5K^s*5X02nT|hcZsj=P^L7`z_81(obWk5)`nMDx(*!dMF2_#O%eoaC? znW?TKsO}szJJw4rb^jg}Z>1<3N(1HNN*vI#W3Dks}9q^h*pv*Tlq z>yw1j`>phLRbdI2Z)fm<%-_1eUmWSnH`Cc*Fq4r@fy!31{VUzWIya?*Av1GvM-{J1 zJf>;HQ#45tA7|<9m(3L41n*($DX)){d!EHLYGz0tTF?O4I&74R>mu(BGp*Q7{9xN^ zT=AnN_-)Oz;~kvP#MDe3@*S1C8#H-&w~k(TCIY1Xmn0EmGE`$!n@4|DK)T*eGN%9J zdMz1GwxW^jCf(|<+vTAtE0c?8-_LMUt8;kE`xMWk55M<1NdA3KA|3GK<;bb zQ2O=!PG6jmQWr$T@)CQikMD`r_5Sp$=_yiR904SKV30mNw9tZnT5<+Ni=@l?A7r>g zZzOCCF?m;_dD#x|YH;*8zZPPf#*#fsjy5RCOhx5kzHU z=#9wy36n5DNh~e#@P|AlIQZj`rGiK9<|pUK(;vdm1B&RUvCvC6)a2$g=_cUf#1hBq zl_MRSCQ6K3|B%;lV6VW*}h&S97Rn_x;LN48WfK# zuX(o=f>t%$tx7o(&)Csm{2{cr{StoY(9->T@h~@(Bx<^ue9g7D)A*6H7mQ%p@8VT5 zQI`qqc_I3Z(^?uBK}1q6+ZHOWqt|rYi4eFLzSIy2Y?7}Td*x`N7+y~PY1HqVLHbDh z1orjH&+X~Mq3+i+XGWcfEq_gY5D9J%1V2-uyg5-=NcKarvAt!~5WC2_s}_9-aqB*A zcVc`lgpyF4yx(v!DKu#-f4Wbz{AaN%NOCO$46?C%GXr%Hbz66^*wK|pziRYqFgtD0 zM${i??Y!?#btXBYUTVc_20LL9s1%)M>yDE0ik&QH^^=##sY!}E<{v`HYdV+TmU?$K zK+?}d%|q~Al89zI!KGjcAzV)918Dl7rp$hqIJNPN)cRIPM!H=?_nEQ8q}Zq^tQ)kt z(r8g+?7?1SEi2@1|4?_sLAJy$InnnU-tDq&o3oF9?)&tY^rj^w-Op5EAuBa+eO@%> zz_o&UX;T9I1NWaNq@(NxRRT8^u-TnU%)q+TxG45NrZq3hZK#ylDb6$OD8KpJX1JbT z)orvf7dkZD{H=e|uiwd)tHEqqOav`9ioMA3EK&S?em`sJ_`th4MPAIg!cMlEmfak*|*%5+~8 zN@<@<&wN*Himtrs6UD10xd(XLsmVY5710>~8;3&S$CBVMv*V`!Q7p;N=*c9~fllm% zk2$;uWJH6wkNXNG&b*gNx&Mf4B>|wqZ6kkR50oT4Xb5f>0p`CZ7dyGxL+gX-xhDW) zyI1Ua7c|iefID`m(4rQ{&bvvcI~ix7hIo-{VA~Eo0)n=HsVoB7Ox0RjatM{0J6Z^5 z?YWc&s4Vtf*phj&%_BUCP&$OnoIp|2-_AbZkBP)x;6@2Dok)!^lO@Qx!l46<_+w8T z05ZEqJYHb<%8A@0kHAALdIqJ$0Awal3Ih05Wc+ULrORg2dji)9@@IC5o9!a~N387i z8+3Z?Fnuz;6_cCIL~u=n-lm_Q2N9=bFi41cw6o{mn_VrPK9u_ueEg&;hk#7m(!Mp3 zKP<}d7ei=PFe|bIw$eIp*sEv(_(Xg)$YZniYV$rLm6k)BzY2|R^$?xjow8yOL^2Rr?iud1?mfxL;oOv6^q+!CYubh{>($JMRI%k~Jr7#Drx>>~DK z1ot1cYH|PpGSc=8jzsD#-19tngeT$~Qp~9pNVcWU)T6~U`cDJNy3{MDl$fiFoFS{OTuiTA7o3h+)N-DD6cVUdZiX+tU;5!VrHHC91}b5~u;opR-;#YLl~UNr*W4-fCNh5qEd|c+92&cy5y&494jmb@ zy_HXHxF83glF_!fMc6~)kGk!k6#|<_*w1e&2{Xv);U6XAV>7WX({Pb5t2m`l2C^zD z#*-)tJ$KGp`@5>TL}aqdFNj!KH%=w;VXpvmSx>s!5QJrUq&a0Xt`137n<{`Qc$~oM zV*^>9p1F}_n>B;p?Dv%G8qyz^@l~ekrsOcHnx;m>@G&>6v*J(cx+LscfHX;jOxgv# zcYyff9|atofRm~~w<7ykKWT-sbJa1qo)7aZr;0Q()t~)auLOv{-`K12>wU(nU@gl# zciph;&HKszJle7QX-semqKVyZh9`g{$1HTzWKR&~;G~?)u^za_yZ7)p&*bOT8WL2e zq%pVnz7}h+K>WRYladCIy|Ku|V}|T+ML9VDH+v6VWhR?UHC;#E<8-fvVLrR=A>559 z;4ct;1ZS@YT@*6`>U37`1vCX;p}0g^s*!?*)h+;x8GlBNU`Dp22t6Sv(VruZVf{zk z3d_ECME=Q5yh4KVSb>lz0EarjU>b>7;FKJ*w;Z;=c{q+&DDg*DIu~vnYS@hjK&OQr zjx2O)J{~g5Jj4+9l^}mMbUPn|gJtSbLEAqy$KBOFnsL*TKQ(!__n6^*kLQu0QceXy zU@m31?8qdikZ^hIqP}WK5+Ti2aV$J1=zGfms+Fy|$02kuvd=X_>I1ow4d+dk{Sx2z z8Q+9JSy@h2Bci)WXSREbcbsX%9!I1HD$)+I+UzN(GWejBa2n7Y&C_w;l%*&S$ZHgbR8=8D+bw`fYFY)OicL&KeC=tRL@PpQPY~Q-WKmx$jaMMH$gjYw~8#(X0 zuKr)`J_X37$wg+`hk&OoK zT`hU*-d7Eso)ZJ2u0b1t#exf)lR?KuAv)4*{bz=Ub5%PnjryvvhE9}up*nA*-M83k zK_MH9bVPH5*%&xgoH|qSvD;BYmxR!QdT4!uf$)Z1u3!dYTGx0j1WR9`{nI`-{_m@W z!DP8kQ+#HD6|}> zsM0y#_`n<2zm+y?qZdT+8qpdb_W6hRt~wXuOJnI3kJ0<+S0`NmEojg%(-w=fiys!Y zZSf0UOO1HsxaUx_9aiDw3BGHyKs&Xf!^d>{_&dWm^Nu$M&JY@w4gcSz%>T8ec}JcTIxKuftKaOvkVATHNPAEt1;LZ+##Si~E_CG2sYGcM3g*OQU0qEh8JD2<#4dyb4|*ogq2^{VHf{iO zmt^Eofw=?%@P3%$12wI`3lU&+Oa)>ITjFn=nPoP|4)31`3;QU}g$_nN#L8LZ6YH`6M_N< z%(<2%Swz4fu;@N!mx#8G;Ew|#-A2aH+AGqn((I?rTTH8=tHaQT;C~HcS$Q_`=bN0v z!^5IByibDw{2F6Y`41#oh|@$?|LCEckFKu{J0V>h;*!yM3WVYvZ!-P3#0~%Tb0tY9e7FDR{rXcK0CGN&+nmr5CNPYidrNtkyuv~un`R_QZxkiZ)vt#;k)G3Po!Kj_~ z5C3W<8~{;Yr55DtZex=h*kj+tlzqw>Ak{mX-x~icA0M>_iP0dmeDvA)$V^sN^gK%H zSuBSJpUre^^N^}fE!XM}O!VDN{JXL72>Al7#D+eJ(1K;>5ok9?&y$}RaoQwm;zEd( znUV}8HKo_)Mcd(vm84p~Cgr{7rTLBKZpbz)db=rKGS(K1q@sy0IjlL{pw!pn>&;iOmZXZlH`GY{GgL;x*n((djU|62+rGjUPUSw}j>bs-TC;f7x#oBU;uMZZR%x3@f)r+63olC^> zO5KRgzRes$1g~xmh20v4)?O8cU8RW@Eyr#h-aoSIxqQW)wM%uE#wmYWoW4+;6Yj`! zXAs4Mt3D^{5Eb|(*A`_&5Z}_VIbVLqxMzbyS@M|m=Lz4|=682ll;@PJIQ|Zp1t&Cl z)*qs#^nq1A(UL@&Yr|Mp3h&c!Ac$=>vKfA+=3wMsb~cZP$LD`oPOO&y$HZpD=S0g0 zG{EiNovhp?da?U3Y_yMQ_~I4vuV9Q+E79#(QY86S)^7DuZWVU%Nb+!$<~yA^+sfyF zbP#E0&0p=is^NY*9rfn9mz-2KBe`FgQlnyfl zui=)RR@nu_8>{Tuq-;F)Cz2OrsJGhhsd1q?mAmRMP@L9v@45z9ow&7m?R(A5L6gjx z$Iqxc^Ot`iU0(Q0fQM#kEc-184(vx~mzS30TPF`N0uL~?aj}~M0Xj1qX6=nEk(D}I z2_g54X=*bwFn78L=@$C#tCLELLIV2Ddv}kAo3g7*3@2OX=tw(4<$SmLf@-2=MY81NVeucK%ywSPXkc1lh>H5LLjv-h57#YFk z!(4~}SKxlidhBfymx$%fj!1e_g1|cG3MTAU_m*^B@j6_@&bsp^Ew_f%oGI|>zOlOMKh`izcinATUlWSlj*%Fx zUpnTO63%v27r^a?Og~?S%hj;^_YZ4^&~Zbs8O>Nd(&?F*3pe}c!r_}knkLex8e+Jw zNCzSR126Mk*6j8 zkv7~bO=glHUdX$k5TC@MHx=YvAzY% zv2%WBA5XZCOjtA1JtszHk0pE{3!NHQe(=84XcT6&i1R<@OkBE-*w)U&R8hzH7;MA^F1^>17C2yjFm=d(O%mt_^Py+ok_#9 z^9)Pu7ON&hM!j@37x9Bb`qzN4V7YC?S9DTbx55A0{qcVd8pn5}QhK&qLh*yD7C+*j zIo?DPFf|Q5XPhKpgD>#L^wjZE3_$+_ragUzc3JuLcZ5v@2CFoPNlBBYy zOMkB!F~Z%mXZSOhFUP%z2nlNPVfaUTq&0iGEE@|Eb%dCWz?Dwk`B8bfZnJd(qI zTd-BpY@3^xIDkmZv_2WkV(3Gw8g#BTueV`^hwW|$fZ)V-PxmtlQPD$DCe6cdKujm4 z$(fhF{-&n@$G2C*?Ty=qiCupY@mZ?9YgIIyPvnk_WpdaN#7<&016uOT!K4BA)O}uL z%{MQ*SImVf?jd_9K<)55+_Q0zrY2!`sgc^kgsX4T)=Z z6ATauaBzOqD%oq+a5F5|-EFQ&wv|?Hde?!BUlrW1Bz`Q$|F|}`CBESUuYlAz*bjiG z-z>qJtt)aAk~v^Gp#M)=FGHY1W6WYvU=OSjd_IfcUcc*l{Z%*R6wO>4Dmk{}^sVir zo^**$C{HuzxcI7%jrZptV>S(|w{63+aVJ4q<~Nk#SeTU0phL>PB;xxHX3yJb_lwmP zW{?S#U7L+=}Xess;2|`pMywB#t+v_V&cpGYP@_i5aVO2t>r|L>Afw*U~*ZtR94QRb?53=7zbNmb68KzprOJ^NR-tNxiFaWkZTzt0?+>j ze-9ZFCrj!h!?_9YOlrBa%tEPzG=#cz@Hf6(;pF@>E5S51mnd z7-S!nu?0}2jB1t_?)amBwcfQVUy-1Gv2-FMjvHZg)nk2Gd_@MVD{I$ z{@FNw82GE0?i($pN1v0elR$r@nwT_YSIq*`%Qgb^T;_Rm)aLW)uMJO;n^Y&5@sg`z zlRuHhB_{5Qgp{?+lOCB{4xHXSa+ca>jr4t(F9bA;NN$#Tuo-kY|6b`39AK_HlH-yQ zcx+7)LYFUZ6*{NDcwhJ`Vj|3ddpM}HD0bYe<0E99*qIv4PCMl@T@7M>9kkYW$Ldk< z^o+2jjk)J9o-U4n26ktFlc>nx3P)Jas=&;z*$~!4?tIZMPZSAfDLS1EvBY0tXaF~- ziPqk3GA-=6{P-o(npAf7OE^}Ftmk4$wlQ23ZB5v6X4D`GFvNW8?Cc!n0dG3tih}nF zxl|rGA99ZApEgw(qC7r3Luwym8tdwmZ&f=bPl0c1cyLag&MMh$TOu`5JL%G_!`9yN z7zxv9fQ#a6yS{`-4ea`IgMxd<*F~bIaeE!ZU6oTAM1-+0e_PXtvrf3{(W}FnGxLTZ zu+9&+A=&*tbO(LygU{IF60iuoIOVmweu9m?#Xtw8EFME}T~H{#jHzP%Ao3cUaf3Ze z?>O_@UU#|Ry&Z*`-oPOj2E}Lb*C7*Zvllv&2jOFg@1j~(XR_$9uaAE$oyZ%9=Z`iV zuLzV)1Z{ffPL2xgJDC$c$QM@13bvPxSK&P|1QeB1r{Eh&WA+_0yb``Eji#44Rr58i zXF}v23E7D3K4g~c4J5zgoBMX=iNkf=Y2aWhCz*UnckrO|(EZ7Vu))afxf)@v34GRO z!y!x?9pfU<+pW;DDsCD0+(vvG30k^zHQBIR3RW;wl^wi&0=b-fIae$wDvwJ2Tz}T} zUCCULmn>%Vuz}jHg7c5^OIltp@+oZ=W0>FkN`veA!-URnv3t5L79}m$F7UOk3#M_z zp*HJ#nrS(d*ooBJRmt@<&yot#O&{Q$^4mFgr#6zh1L-asp%n+A^|>J#UwOEL;vInN z;*b=MM>oc8*)((dj)Tp&#*Xd5ptO-p*MZIW26>c*uc%_+kkrD7bWPFM#{ICf`gool zaZoNQIq=OVMU4tJQ>dxLZt$$<&@+7Z`q5m#+pO&&&Fg1UrK#Q|M@1a=g6)9e|f|H6<&ylIHbWEI*QCWQVf!HMP{yBd_yp4fKHSk|!PE7s^aR$I@N z5EWifP~5rkbb6GavCbu_&6++U;AFp8{NFGEGY@Gk+Y8cwyz_f&f<5%e3xO{-oUeL4 zM;uFtpfz6UIh=IKj_it$rKy-U7bl-AGzvN+i>};E&e}A0`$F-T1lK89aP27sFM80z zv@JXSe?$*)OT;mLq&4OEZ^43+yoHDHcDF9CID%)}xLpnAr zvKO8v2q>d7@*~sp2{QE%1xQNR>H?anF(AnbKC2rJN;=}-k}($q2iB1Q_i^tC-#K<> z?Y7U9+Td!LfBJg_2FEUA(<)< zLQC4Rs!b;@^bL*pvK#15LK{WkepT)jE>B?di`NI7zeGpWaA!pd8tpsz!_7<(K;vgw z4T>-j2K!@Ns{G}fsSCs0w&Z&%AZ+dtABkW)9J4q5x>ZMZ6)R7F69=R#bSP7)Z;~ZX z0Fp<y9!S&dR4=VXXi_*M9i4AYWVK>T#uyaUv0-w=JH)vFfpfygRK&*~lb zceaBY+u9z5T>t?=rGg?Y*xup-pR@ELVz$7{%e{o%40l?d(i~n@sX01vpdN!hz6MX9NFBHcXzXaCU+ctsCv}U^Ub~l7>6BO78y-Dzj6@Fk9Jy{MUs2TrBMhv zP>sw4YLB8;#E+}$T1fe!YQ(*a*ttS7Ev5$wF+vo1>=cdJ3)7d5+ zhvql?$<4VNucSo0EpiU|s9ryEg-eOJQI~=j`kh-0WNy#iWYaOZ#@KTB9(WS&L?VH8 zL;=vE40*6W+pcp!RGymuk{}nsN+&(%IX>BE_Dp`GH9-p6Bve$e?eIhCHg&YpJ4F;E ze2;G55kkaqY}pYJI#>fx3wL#kijlJZc-xb33Cic*du^+=V=NG6ntOLKs@RNgq1!+5 zls8+HZSr2o%5$)gkJ$Ts0r1_mV(LTg0g8OspXlQHy0%_9j+nFCR};h^bDqY^TNR9q zQE(BQ=B&!2c$m6WL@>g&y>s-6h1K$Gv4FpN7Gr?~N;_u#ek9x^L6Xg;oE8|pPZC;B z{an;_<;l$7S*F%0X|C_R?{W`fR)v(ZzbiPn8_QJEW?#!2L63Gr*|EyE1|OLO;tm$< ztUn*dW)Q-j$ytbnim~s_ElL1t}aVW}2wcnxJ(}}&88i?BPU2E2_CJYE&UuOa$3Pk{FGXQ10Cq#RL z6RdUILuiCh^uI^jG;a;4V273O4N&G!*T1Aa9*Z;V#h(?=xRN>~T2IxbKN?Sh0{M6P z$mV%!8tTdncpx@+$5J?GzC1fSTV7ovLUd|E@wmd&1|2CP zF`(xBX3|alkAEh>eBbk}{50}NZ{2>cRm!bN{^V-`xl!9TL0*%0C-NhYMWQufa_Lc! zr!p>z@1HsH>~1DxJ(&!|WzPHO`FCVo(`Qbkj25?eNV)U<4dz|y%^f*p`i!thM$p+o zj9VqDcUFZQB!yq72!Ut7Uce)yb+^2Kif0VsvCD6=4Gz;8Tm4E&DFFlEc>J{oh&XhW zzGvk==%vjpshkSeUY(zn{I7Wrt_2F!Y|BT+JP_%`MVh)n&JRW#+|i_G=}d+{xNfnd z^5-y|xN{@R@fP;-2^PjksKwyZ85?WA?#1PSuF7yrdn{*$;=30lW#}gb@EX2iG7G-l z7n(|L1J|k@U!R(u4Vea{TD;t(WjXp&JO>C43P3SH&gDOOzf-`?A)XmbRyIf^$HfvE z43QwS9N76uglV>F87JbJ&$*DFKy!hB%`z=|bWcl(srgbD|N`|BJJ;3~Rc9 z`~5aXODWQ&C`fmwq9Brrl#EbXy4k1^ir%DvqZvp`ca9LHVT3dc5Jn>~7#(N#bFSw( z=ef>x&WrPQFZOEJ|Nq-JKHo=p^Y;s2M;@lhrXBfi#qD!uNs+l;E!bpL;1&WOXrHq7 z^&}PPlgK+R#7kp38L*j>tZ0Ikwx`dP|_S%o_W-TiWN z&k6ImH3OC|Me;_rFpHDYxq<=veR|4N{(;r1-S88a#Y4G^4jf3>^O2Z zwinIkj&XjS!g;=Is@KL?zCQLC=WKw?W%=+-Y!~<-6F*i}D<&2m&Cb_cL^*hmx1cqb zzj+_FKo{2ia^IfS>tYfq4ob~e##?nY&;!eFvl3oRqSvGUb!Wu?PHrmOHx)i4Tqk-1 z&s$ZL|HG2$d1hJi|F}*vG?$LHQ#r_jc#`Z7%1NK7D8BExIl7p3SXr;JPSkd5xg6vN zUiV-g-U&HM4*1k;Z_Q@UeA87%*1shuZ%2sgCg%P=9~SiPSMGp zuKSmql*%MrOj+f?0`l`T(5XLYM7QHxb(&Wq)eD##!y}jW`QNz0IROCE`4Np6sgBl2 zsKcU&$ALB3Bhq+|58xWGl#JzcBMX4xM-Nk0(|W)7mErqiwaVIEg-I{?XS-*1H;yYBkkAAZ!PtT`f?)i2V_M6j`l5S{W0r%m^g;F|NW@~=3C=Z{S z(dn4^W^!Gs^C~h2Ug`S>V8 zC=R5p@m1PNsE3YELLGPjWb+2A7H*}ysA-S$(|wT3L1{9Teug;~hV!A)D0iL&19FI8 zH|Kokc*1|GQsCw--EG+y;on*X|8he2y?iYwW@050_#|vJ+=2c(Ys&HUf|}&z-(QbH z?NC~B{_dWUk#C}S^g#1-_IrI3hk~1S&(LRHlP8Z}-8@|kQ%#(1s@vr9R7T||&vXmb zRZXLfS2byK&UvWTTQJ%9_`jiX&j6zX15psI=gbQvrM`n~S*aSlpH60;YXtPO9XhDf zq;1ti-r6X3DUtb3V1nw1W@pLauUU72v>A35#o>1|wq-$i#Gg1Va#BTHPj^WC8$tfI z)w`CyBa-Ob8N{63XfX_1;7+_mCEe|8J>ckk8TX$iWTov57SfHdABgF&I?5OEUK zQke^O#iGB8vf!tD@oH`nv(l)CD<6C=gb&-7CSG$z)`Ot#4#WeI=A9P;dl`H-QXK*% z@IT=|&vabnEjNxu(~;?(HgC9PGroWmaCVSLq-^>$O5HZ3+LfZgF&xrZ7Tjx zkLaZxHt(|NztY!U$jjIg*R7cn>tUBDzg#au4jm%GPKGZ1{Bu0yk8iheWyH9R)nuP! ziV7`FOU^BmMyFt!P8cwm6<-;%+D#`9 z-d`R}S*XdR*hhB?RJ87t6hT_*$!TFE?yH_nfu?(Z{9(tx*t1H$R_zK1o-UU$aO7xU zEQ>dxT+f+*7~0OtJlo}T1CM24mRcx1vW5M%M9e%~7DHMt$3!jb5G56^D?cqM*taGmd$b+4U*sg*Dc%4PRDW+4Q36uIlKvM~XFbWux``8QG^s zq%;E~DB_h0OzUE_X7kfUk?Qa`y9NDl-{LRxsR05_x2dmFF{M zBEL-Re5YUSR2+ArrOAzS;@_8-)ec#hV(=f9R=`hrAI*qQRzb#|!;8^t4~rzAm9gix zumIciNzJsey3*Z%heCU1*R#?tGDm(8v?tDKLE46S<<`t%k{$?}zZoEKh(gz{;-j;E z^AGK4$<#kh=UE7J-IExSRSQ@wur(c@6^9}{CN+Z(o66j>aIaiR1Fw(vb;ELq_tLUF z2ViB+uY&DW7k=$qWSp<1$bOtLUMWR7YRa5R3`?Wj2F~U`?vxNb53vFJo_{yl3Ea?H zakT7S4WvF9+I=jhhR|bI{wjo=@`IArci?{S=6#XO6=_|$%=(tua-H@eIjG8wFIgHv zv(1ZKxG0^%POYz^ViF6r2VkbbuY&6x&2}O0=X7B%LD-EN4+~Rahi2STyZ5XdpU8~m z_d8pSXL2%oI#M=G=SSX`E*G+&b9=CIo6osdr6!566Ut`8=$g$sMQj$HyPX1eFO%$= zR)BuED$Qrs7uPn|7Eb0=X#G|$9DA!gEda(U8ZFl z=Q7YE+g?C=@06s@wXyLt4}6r0MeJ4H%C_vgcKx9cUaq&)zz-WhcOS?6Tl<#{6efRd z8cBQc99P5u>S=3lkSG|wa9fqO%IHVa3H2&bFklUc4qfNs?4aGG{OxPtLLm}!JRTtO z80`h%!S5TRP+ROTE5Bg$i$5E8@LkYsJc8?iat;d07@uL4BP@Z?unK&+DT=FxnaaJ# z*IA*}l_Y*7=4q#zC)tCY{+Q~xQt**HgDWglxtmogtMnkPh}Rk`^4z%Mw?WvgnR!;g zyL4bS_tLa9SZyGk!$M$V;$Ct3J2hJnpikrzF&*`E3YA{`3Q8mGVKz6fLhmG%9(*12 z{Gb5ULdiuzix*ttn4^pKR-`A3GZqBzSVT#Bt-M}pv7oUwVB2rD7NgYh+2>Lnh&u2( zgz=KrQ|URU!~vdfZ^G;zdfS97BBK@~+r(emm+;R0BA&f715Qbsw07R9wSem=gR=L! zCHU`T-4`)$2KR0>?tr%FFH3b5c(y{l-f}s-A?AG)@aaAgu-?^uqIP=VwxOM`qCY1$ ziz8+#s%jHtRBSJT?*Cn_&p8$JTGDRg<+E<+9(BZUm{8+mi=-SVhE-g>qT8$IGD$~h z{JJiX*5M9kv&Jq5McqPL##u@knY9P<)$sa*Kg)3X63jGvNGSRcKGaH(^EX&9vcyVy zISpz`=wZMlBiWF8v#%$03vnLp!ixK+tVKsNg{8Z!y${G-ahUE)-ba?G$vY*iKO;8~ zzOHcBO&t|L{>HSj^h|)`EI$4=jkRHvYl`m}&(rU|QSP&Ewdi;NJ5Jqa?S?AoLY;Z~ zAJ^ufqh^w6SEyqZq^;Jd+@c9wc)`EvK}>$+4XOwW(}s zaljbRzLm*-c_0XYh^C2=^r)#)4qBISp1M2NaXGl$l{O9o+2saAlj9Dvy9GI%X!f%k zvLQ^#O1oS)1%c>$?RVDB>2P?iNG~X~IqW(%zTsF87WOC8a#s6s=A1u-UF>*#`eo<{ zEQu0*JPqvO6@Fi|+6n}iy2q0R@X7x2zz{#xbcMW_3@FgK6PW$BdoZL<)jN95H>=_G ztoM7T#S%H+T3)7niz*`_!gyD8P3czgq+VY!F1+AWfr@@a?IJmE98y)1Of{ zyvheJ0S^qY6ULT*g2H;9@T}ptrz*Dr_Fu*y0?;J_QT_!e5)&`-R1sBcF^oqWV@cb& zZ%xpx8m^6T!j94Jht*pbwQEz?3X_w4Ow`a|7}2}3E|QU2dWm!6yrbhTKhVJv(&& zjW6`G9?Rn^2Mf8`&twuB%J3^`yK&ZPlj?uyZ@~M0W;j)dS!jBf&FUUv`m%@{O61G*>>Gbz1%qK!N^Ul4J&f z{8Qzl~1?4N2g4L)S8NJh@gz8=bI`uFr0=U_b{ zi0``W9Pds~I0L1e--XS-2dcCiwWN3aJ`Idu_i)K~i9XOEZJi44ITuqFFchs-odz>1 zv{NA_5WJ7%CcpmHc~j@&T+sZ>7IoR0<}r=)Xv1QAsz;Ugs0Xm9vzaUxsOVsDp9Vs+ zIrt;4`H@Laecrm^reWNOvOxIpizXY?s>H=)y|sl!TZLronR63i_+`z^3T(yz zlH|R!=hry7s8z4I6YU!9ISW7GK8>+D=gC6}N7y6X89O;^$8+?}SbTZp#Qi?S@>?#b zR&;AUq#$V8&H0D+ev;99tWLz0 zi^3fwkHuC00ptu4{bK=Iy2tdiBm4#oCwswQRn=UrYu>v=48MmMMO-6LEj&wm3Ui(irt~pSE`bS0FE%n%gwz`D^`60jwr`TBw=EY6%lX( zOo9-zfoLM(Rwp#X)$D*$rpW7e!w~&t5ZPB{xJL|4>OR|0k_=Ard zKQrMphL>Z^I_ci2Wd>9F$8x#MG6qV1;GIlm2Eh0EL~=-X<|wJBxO2IDA4kAUUenAs z`rLt}lG2X8s;z+w;ss%z)lnV%&lUXN%}>efpBD{|K1Qjku`kJDG=b_w_tv2#uo2GP zZ`S*{ks7O37hZsZcV3?Ywhi@4_bVdRR1xEl*G#P&R}oyHkQy`_6H+%GS4E?yWT0Qb5bmpC??W>}t@5Wo}r z{Z;>LH`I3KQ)(dx0l}Jcy?vMP#Wk30)DgJ#Q!KbBe6<{CLb%zux4D6=n{Kmj)ib0QIzB#8UVWK=sA+(a8 zP-_@v8nsox24@hpLSpkqDFfLMklkA8iC&r4UZV%}Igpxa=;+hBhufcP$IF#V^#|aK z{tK|^(b5t-wMlgURPd$~cJKOB?NE8xHgbHg)E=s7wYF{YH+G5~aq3i>6<$1OOI`<5Z39uDQ2y!u6XZFf zLvc!g0}ww9viL$8dGS{3#MIKi^10boXrT}_{b03khIO0nGJ9}Lmt#%qA_Vy~U7VtF z7~0SqV8&Gk;OPuE9;qS>{yq>@sZ-$4ZKSC@nOxJERAvk7C~0(RWuAOe;}4V0$f*3= zRUnpji7;C9$~&V3uqi9;!mJNnxt7m z-nIz>|6ccMSPJX`9$l~c1+vW4T;~jx4CZJJa)v;y==6`=ht*i3c@^b(0-|G7oq;2; zX6=q~!NGKNww27b2_>NAN2jooT)^{@6AbwoF85?Zr`2()E3gKbSJSpF5dyS@a&SCS zcxREd#GJ-$y#eqHo20`O6Pw=5t6VqXK8Rd;pVe7j7*fkage!tBSFqNcH#X2sY}{Cb zUQ$eq6PC68sthL+vZ2whr|3U=54QGiZKm9*P(F*0MNBn_jAXiQunSgNOFXWj^ct{?)`GHA=&z)u#h1>TULfBx0c4-kSZ(h zV7Rp)vwD=wo}WamqR#u1`ui{Q;HADGYaP7UaWkpnD{@@W&fpv3_ox`_tB(@P`=Y&<3B}| z!^u&%g1pfRtRbgW>tME!_;5~cH6B% z?dD&idCVKw#RRu_{5tHEfLJ%qW|0fbp@iG%cBEOJ68(BBp}L>CG|mlog55d7i10HW z1rA=%eeR%>3C*TWHx4XDvJ$}vEaW9%<*W6In`sm95<9E=$QJ}FFtV{+Va*<+0k_*( zRLoM-i?svxFAK5kX-dFx)MutAiNz1!p`wOCpiwmmRmdqB?I(*XaLY(LoiGXhAHn#^ zZCcSGNw^@e8P>@#4*~jy{Q-a2N~PO>kgQl0^pl4yqF6wGKLY2IJ5~>-5>S!R2CoC_ zpXR}avZgMob`5@roD-`Yatfxf#*Y17sUBgKF3u^t6x!8Gp`2wFUy}gM9|#u>u5U)d znQU!>l)lPgmJd?I3i+*nd{lz{QS0Ss+e#jj9(*X{{UWwQ@D-9Z3+zjwonh-`wuH!h zzO;R%;13v=+&Y+;$c|HASV|c}_y=#Rm4TBm(?{OydL&(kt@O z-lT|m&4YDah~gE0T9;iJi)ZT1+g`3tpUF2wjr9`Z9Nip=LG>Tj1i@eBeVA$_4Ot^)@@`9 zZ#e{^m~RYg#e@|}r&f08vS%w9r-@OsgqaBL+AJ4F=8I`Xb|!1S|l z)gSKWY}pV%zzUF|v{ZPi%04&oLUtr4xTE8Cvp-nY#C)neCuL)cj-!_}DPOpjSe*t) zUE*C}I_g-!HivmQlm(}F%;GAB}eSJM1;tRS9C*0zlVu#Y3arN|yx#e`GN zem9e;Ao2|+4UPl=;!4{p$1K1aKK$x#9I&h zkCwol`UB8GI;19paG~qlHQonm2`=-jMtpIqU}1~%qlv9xnT+t7NZ|Qw4I@A{PsHxV ztGEfd2GT&E_jkS825=BB42oU%ul!;}+ACJPvIkF}y@DH8n4?~oms+x*%gzAk_Wd6^ z4ojQI;*p+`*isest}cIcF)Q#N>d(F7Ok_&8$*9O?yM+Bg?v9{rjVHoe%S z_B3l+9s0rUR5cpz>FwUG=)b;;n-B@9yQEpXP)V-1>YnpgUb6yRJ?+}}9)8R=(s+QW zm-pq}=>qxkCsl7%WE(S*iDej?@|9S;$&w=z7zJu;6ky&C>3JqeQu z+-uf-*^7|q4c~1nxI-2sI=v1L$Bba}Vfu*Beb>G>8eFyTWn$G{ufa~aNf>o21Lmah zvQ$iDLJ9bL(#KVol7->c;QZpu0-qlSS{V3;o0F7FIf{2Z(43t9CDJ#&YNAa%0Sp}n_e2Q$L-sKA5!cs1{#Pz6fh83`DmcVJf)q0Eiv{+vUJ_N(Ei@lsc52*y*0 z2a04t&6zV1;ccV4(=y`IZ0(Nip8$j_)TgJj_GZ@Iv4z+x40C|Y%*?`d6vNPoapk8@ zXl<0kctZ-+W_GF>SU@S)`4z#%mmM^hb)IlG>2ipGNc%a9^fI=(kLBVJc?IzY z+_b11`1K=iW^E1EQ~!;5%*i>4{u@BekXQVWm>q!lyI+w$pC%OSxe>0<|-jZsu z)oIyalEVq^-8#bGmR4g%Z9P%Ls{z!r!(iS>5;ML%&7>d$DwdYf)T5|LfNf^=pz@ctmug^zqyfR>G*2h zu>r-ynrKJnY8AOQ0-gimv}t=4Ei^8K#0NL5APVbU&eG|dH|scqr4BLbpIf(Z*QNIq&JfBHa?N%)rc+a<>5~vC?K*%mJLj|1>5SSk z%S)dM(iJC=KMoz6x?SzxbTdwFM&nlyTFu=H^1+eudvO|Hw5qt__nrHm9Wj?Qt7@ARt5bPuW8bM8MgO&~fF+G66@!)CxhWZ`u!i+JClMw|Y~MFj&2f z&Binlw|Z4C7aKnY!k0(yz&~U|I`x*`h0)BfKVz@|1qg1e`iah~NqsodwI_(O%MJ(> z>`k+ujo^M^oE>R#k;mttPP-=wpho>>IEOx&Q)?wfgNyQ9^#=jca-dIAU{Qfj_MCA) zo{S$!vcWBw)D(9ts_zZj9h22!?sbUh3m*ZOcJHOT!5MdDCZ71#xJr|6fd&ige{4De z`p3HfDSF)PiPkpa-iZ{n%vY~CK4xZS?#uoRmUH;}UNNRK5HA6t*hzg{ z5SHQ~pB33Nk{_+OVSfIJs?$-4TcXXm(;ayHOxSDOzm@upYjY#HX=g;3%x(p%93h!7 ze)`ZGK%1-QdiqEYhzU#H;-PN8g(jg%zuteC?M03b*KmIEoycH>E?P*`172tZ^mV;F zzq8{CAXlYwdzzHWtRf=Va`tzPc9;C)w>{9`BlYjpMK%5J$lPF$keQQRl7I*P3UV`r zI-TZWg817((U1jw-@pw<@NZVzypv}@-N=oUtYM0*TpBfAyb(Fm762f%5(wyhRf!N^ zBpqpL2$ES9=-6PQZ?qUefyjpDX(h`bojT9usBEO4-_A(*ILH&4QwY3|r0KU|W0B)p&{m3>^R-S4&w%zy zO?*26vMH1qx{V|?(v7fTT!2`Mra(SGX3pNo%L?OPCQsa10{pWVvN;bq9&n+X4Z=K| zj()#D_$xn=0+DXK0(_ewI#L_C+WNr{>zfC4(2{EFcZ7DBAK?M$&d80%b3^z0kZmK{ znCjYJ{0pTj@O1OWAvA6oHez(;rtzzZ}>)u4<_Krs~nXegu7QKU>vx4pw

U#DetYV^XD6(#ObY!@ZXHckPj!<&NK5JX7{qD zrY4j3$xvagr$5$FJ+dYu=Or(dvE#~b)Z<1hK&{{>6_ZE%WV;WPh-hUW@Kx7vyu2*F z)%KYc^YYK=28TF?k2kywx3;|~sB+#FQWAI&)&4U0YJ2gKAK-9{IY>ik4IT?)*n4}< zaG2yXEml6Ea{@@)CP<6pTRAs>P!U(Dq(vO(e9u2tO{h0BP?|Bn|3IC4dN`PaQlbIr zv%a0Q?6&gGURIcsitw&&(*6usZMH~=Oa%;!8*NeEC?2hX^hS=z>#aY&fQ1v5N~I`~ z9I~Eeg;(ZkCy*}kykjN7Y!md~bhc)|-Dr$p_xW2l(yJdNyDNOx@}!~|=z8#s3F>3e zvMQ5PR9C0)IXR66z(2JMC>?5#db|gkwj=+jvAH5{<%;fD++ebt|D+D3s=RknWvz87 z|DmE7dS0U89pdt{4vD)>hKgJ0ZvAk{DXPq&tfu;M(#MA_FUK-6x=+%jk;hPNvyA%( zv5Vpgn&{2p($~O8gh&i&TgiO0$JcAY7T%?3dYnHfujlK?2_p}#L+k8D@w#eme*s911HyUi*&RJaS1dWV{UxZu+rWv`tPZgX) zIQ|t%y0lez`9+1#%XU4V(ZM#w%JYz&b8fHyS(=>gn2$DCi9iKFk64fk>!sBTp;mv% zij4D`Pdd&K0v!U#!~*dXh1)did09+a)?*LZ)yBkh-$1{Mh3$#-Xtj{s6y^O#zFhf+gAZ`X2NIwB3RyJ!}i44vqm$_y6cGp($aR(cDVSTt!inb-cvyCHhz;qnX59sOZqX#!=;DfBW1efpiVpqV6naPIL<#f zv`9m@eU*`YC3#N`5b>_t4yZjSa$vCOdijJvhbWpeBZNdewTTAl@}$5WbgXa%|Du9S zcoh78CMdgPeG_oj5zQsk>7*t-|HDj*)#_cq^N*ynBuNq={f8S*_sdk$l~qWs!jbP8 z$xxyKjl_Eipk_Wl@rO%H%z&`^^2N@u#m@ss`YFoeE!_KkcYx?~!6**q&~F_Bpuj$w z?Azzj`XDmvd!p(`kI|#BL55pY`w3KWXUs~bXrk}Mn7l$GhMuffUy$PJ%E`iRpnrU= z+1rW=FF$g{XdFrP^pvr-vrRhHRH1>iJ#%$I?uitj=sp0gyoyiklu>&jb>(eud;4KP zLD~Hud;J7Lo1hwW(bUku+A&}Y zP+T5uB8#Rk%A=-u|8%W4=#%UAJ(%R}Y+lhpoflXQX248X731-C9%&ZEfQg&1J37hG)0Q;Idta}I$IzKZt>L@a_mbr?3y# zuk_?T9^GFE$O5ELye_jH9^j=g`B?JaQO7Z0vFskL{F`@>wS#ZpPyBq`>Ecr?28ppy zxN6+y^{vJwNu|gw=t5H=wP9S5YpJnWHs;&6RdOp;5kQ24HfX6(v%_xiPZdNdD<=T} zk=c?GC+hIO7!(Q}0nHc0h3Q8-!V7?-GqHf#_`9~h(LKaZj0g0w2_c+g0{B?y43)ig zm-Z*IFSdfjmyOWvdDD)zj}2Dm)lF3#XAO(Z=5U{%oyp8Q4NFg5+I-dF1*DvNKK9WZBh`D!wOx2ysg#xTs=|GA=#MzWgkfY3^PGt=Fyn>N1IifJF8~53C2h z1+)o0CZ#TNKcB%faKj>=-I!ATKv+SGOGn@RRW*&2;*MO}@#_??P9h1A`^dxZ-y>%s zmd49M2;U6LWgv?e*J6TuU~Nr0D~uIFJPn}%oyNYIgAg6H_W9?g(qlTpcd=UO@XTZ= zFMWq>>0JjW7TU|Qb=N;amn^kwntqo`tM6DvI|3Ae0s*oPi8gT@Nuj_@@$}<2L4FzF$Sm4p<{N<8M2DfgJFMqepx{&-$H=~FhuC(ilYvw;x&#lUQS3ARozSl$`$cZESGu_hA;Y-n?VhJE@Q(wq4ywtwt}|AnykEYfbX z990os7+(AyvCArl{75vDfl3$8lF;KKWy;@@mS$V_HAjN!OE0#eA5c_gFI_73HYMT< zBRjtrIu3mNt2!<}Mh_NRkT&OWk#Ls93Ocn(CZeMgH4bYm!j8Zp{Z4`9560y!g4MOT zYSD;;YW8psoc+R}9!zt*byb32+K15P9k`Uv`fVX2w4ILW=iZ#c;R3q-=F~9_-V#EN z4d_(FQIJu6F(Wx#m$`uYr{ANbI*Wlqyu>4s9`*eeV_2B3yDP#=8 zzbp=-5GT$OELG!26I@rCon2NOTLyjx!^3h&cFK!6l1-bC=G`~K7s(#!lVgs1`7;)T zu&Gd6uJr<~wL67&a{GJIYG?0;e`M1{m9Pq*U2$K6UIs%`5y{x<7}pHR=&}n*Fm!Mv z_E`b5WfBIVDPMfTyv{ZVMT*zoAT(J8%J?f971*PamQAmj+h^PR6FK2pm z+Kbqdax%-Z;#z!~(Wd7f<27tTvpY@hX)>XyMhvEZA+{VmqqWgkk`p zl`&)3A7sTO_8n4cpZE-1DnnuHS;VUSdhho*lC&;c8?0y_ei{W~lEB;_Vw57zF=9pk}IOF4+~&RbGZyeMFYaz-*jNzu}6 z@79k1jG%aCxbprT{!J-;(|zJnVPfD3`C0~X#O*9Cpl2sFtDnCv2J(Q!ifDwP-0>xC zReFA}6QUUqlP5uyLi6_HE$dw7vzE?pgE0%*bc1~EBW`t9!6y+qKY-rzrDktHs@!gQ z+o`76IV(&S?wU!|t6y3;a)BXRO>|1KUmn_03IS!qIEcNd^WSo>l1Fe1l>+LmbJ>*V z3+MobN>2~7xmIYz*(Z=Cby?VXvINdh^R2|JXI&Q$uH3txvw$+Z4qsMOQbt8P`6oX6 z*kyi-6L6PVv^CO8Xo+X^Z~K%%>`K%KZY8bR=auMq%hwF-Kr2r-1O>NY{%*V#52HEa zEC3xnD6+6hv>3zN1XVV$AFAoO8f+!NrQsPwk8#7?{`F|0Q>rFHn||{!1gmi!^Yv5m z<16kmN=54Cx~JDZJHwHP;j@gt<10iti7JmWRtO!Glvu zQGTe}DGEn#@ShOvg!^haNwRe8`s*5t=4Lm<_nH{3s@<&4Gfhii)n$pl&Ako1^?vtE z-=|C`d<~5L;p1FO`8@P`>L5(%w5D#qXg9;}Ru$B%jhD8Zqg+n>hhjm)Fy~r0sbEU~ zpr)!S2>n$oJ1lWUNq9>_!@lyuYfvvFhKnWpnk*pdS(r))3Sh2k0sA54YjQ-f>#qL^ z&VKl@e4s=!TGY(GlSou~sQxqJn`Kt8ER|H*wbW?K!8jk+nV=ti$Ck&H2fg^fh1f#P z8Oh?;#MAAZ3=iJ!hdp;|hP+nhYNJrwBy&of4xdk+!ws1^*A0d>eWrcOxO=<2Lx*7> zP~b+>xRKby+gao66@UusT;oYaSy5K2enUX&`&kmJ32eR`CQ=LAjTfjj_Sd7B%oLV! zvk;o9SmtAh8=>?Ukrpa|QDc4s18bYVe{@v4vp*Ox6rl99=A$g}W4%qjH2ZF;9t|&( zi)Uj7%o$&gjYn9nyo;DWZt`JrVIQ(^>_0C!xb|somg2r5Z^n%KliSauuy~op&UCT* z2%k^K&*JcJ88=1U`roHNvCN2j{y~j&tR7MeoRAC7{6X3?V}}ado9r7Rf@P~~OSHe{ z#^1*r{w!Dc!4SU}FjAN0bcaTB$gA>gs84s*;hpcwdSCW(XgVi20A{PIlaerH8^UO% zWJ5zs=mUC?V0FxmF#6)m&k&DbFpKNUjS5~}fP4D06QLZlFW;ymSc z6vUB@=ZM@O3FxXGly~rpl0uRim=NIjZ45sJRpkJk`#zt9JouQb93rF?vxF7qT09>0 zdzQbg6XHl1^A+-c)O}rTM-RrrI*1r9O27D-Ft!Bu;bXlz$D#KuubEhrYgvCOnSaFUzv_$13-Y@a8dk$_ESv3xFsfX%yvVl{3OTC?v^+a^3$6*=SwRYJ zmz0tdUY{@jwp`bt5g}JC%9htLDi;F({P_=a#Y{;wLRr+Fz-5pqyuHqJO`~Eo6*O$v znM_W9++jx9Tbpn!4eVqtG#^o~P2QY61^2y>>CCL3m`p?Nwu-=2(8lbsN_gIJRF*be)&D zJA9cc^65|yA+r;poN5t=J~SEQ@79G6ceTzZ-n&!-0%wF^;8CI zEhoC#G!&y6woUpMWd{me^V_zj%rhgQyJ#FAcNbpl%XyI{C-)k(Av#_A%ANWdt8bp851y zgHL&}U%e%qVTc2B`61qIDRcX4LFA=vpgHxIGlNU}N#XU>vuH`|YqXSrLz0D6@Uu=s%ur zo3=dQpy<>lsHel|y##ekxiKApAVkhI&6@-l^AE=56gM|4(@t*ZyREr>w67KE7aUKs z71t(z7BrlhKeWt?wF({dE8p+=sp6D6fRoxjul*rJdp@3U8C87p?1ug9UE}-W+S?8f zM_y!qRTT&|0+oT^kpJfg9g8;P8CQzqpqz?&mRi+~sH=t}(wk3RbO2BOI4~ipVh0e!pDu1jeJStlm7y!iS4nk9wGF|*{ z*+`!24U(uPDs$OU_rU<^dR6LvlDDUwltA~1*O|KSzel5k0{nTFeuW#u$JwqqfP*8R zH2`assWzI9T2jE`CGk_QBJgY+nM|=a4bFYyo*8{pCt^K zAtDPB?|313>x{KDPQ#Exmn@iJRi5OCZRvgo>`kch?IQ~PHGpWeO4f0mXbEJ$1)w7O zKIV}09iPV%MP%50A}-3M^_1$cTvDyz@2vx&kE(aiO|7?XL!vfF0Nrrf`+B7k){o8H zlb39Ok{sWrUt+U0nGwy+@Q~tY(P?@cY0#>2UPxV$v#fGDwQTVeY2JNN_CLpdRm}ne zVcrg`S54K`|NQEDS1eIB{$9+Z_g*QNPNyt|?UQ*AB#h{R+OK5*-AwG#Gfbcj6f7Df zbE;qQqgf{MYhE|-AFc;yPT^riUBa+E!dV|0Fvr zZbfyU+l}Yx^tzcKq$cW&mWQ%WWvN3RfknR_&zv0_n-Uvupg%{Wz^Vfe2j*3>(Ga;-x;OlAqP3$ z%B=UGDtiS_(HiP)4k9kG;`9m%s}Cxq)_#3rLTxm9xWv!jQ{WWGVO#5tYR zIudHV{qE+8BgG#-WdW|Ys?k525G=gCUL9#oz@-GHQdOd0@M+N?D&r5!eg9NGp)q4= z3MLz`pga2#0F$*f)+rfNR)*}VR|}|sJFcV3YwBe$DoTYD+~Bq|I`9DgG1NQ%bDj6P&N**< zpZ#sme%7<@wSIRp82#?zbA^k0%Vn+JXSvI#d|$4QqHjDf^Kw_yleip+SaHMRZJ`fZ z#fW=BDtEZ`$*=NnRaty@ACe6{C^#=q7Nj4m;@Wa8mC80>+x^W$jW*g^())Mn4HHW% zU?_BqfA9BqF8j-sl1vp>N_mjE`;qyNEDnW6B_3Uq$mi~VozDY)N#{qAw^;-S+zs1_ zSxu55YF-}V9qEg>r=b!qw&lO$5f4v4zstNP+Ue>|HW!~Of znpfHDCfBw_)C2G{&nE2#xuV1wWE=W48ZdFr>8Ah9R*Q}%36oCi)?D_-t$3nbXxTaq z3DfEeq&#UWHJI|~U_!Lt1&!gKqe>XqPaibq9hj` zp{`MC)70HV-z3j^qLg@LNME0J%{rA9IDjtQDmpY4tJa@JwnaSGYQ6 z*2a8QjbV@fVTEGI3`mDJW7cJ3^S77w2PFcYh9y#7hk6z5*k=w&lIz&tH{Y+u9h@yr=X+0!15dSX zy)kIH+wh2sgcvyORIA_VxZJfe#_M({(Db@NuHZMiWYhcvay2sQ@=C5$+LhNE11roYaI9<@>}}Nuw@!FJtTKGE^9Su z@mmF&^Q%NqV~?5|T!bezOKUMN8+pnBOja8=Y$u+nGFAKkQNu!+3wip@M};)twXq+t zbeT8k9-F3S|%) z4C>r2Z{-|-jl=u=FIQ&-B zL!wNvAY#()l51OR+e+Mjd$T1#MxDftYCW~n%B-K0Rc+f@owt(?N&`72y#nmTF$5sb>p!A2?vHw*w z{GTG?bX*(v!p!cBfV25e7nkO4Ngo|3+{+}}tXVNBHQN->06xHnXB?6bfs*=g7;P=l zerFJxp+Z!Qf1rQ#|QOft52)K7xB)_ zM4BOoUd6fd`=1kH{s~2;vzHo=j38@^LbuGv$JlrG?mEi8jj@%mFH6diVE7$Y|b6 z#5g-hTWt$%4SecRArOD;q9bWCcCXSO7En=I4tkN!G*x^zn_ahggocBoPyd36!It>$ zu5R$~#3Ofww#jNQ*k;l5M-*AFj`Eid{5TkYm09eN5KX|ot$z#26GpiHNrIK!Yu;PT zbv4HF++4tL+XF_)7x3Nb&isb%)h{&t1hUfuCoC!K{ZaCy+C0^U%$XbCp|8c0zl%up zyCm)la1toyR7X^h!+3d1KvVD2Xm`=bZ0BAabOfJIXlNo&(C29d)5qCcvTwi{c)t5= zeADR0x@Q~c5BH9fQ2NUxOcj~VZ<|u8k>y4LTR_qWUql1hj6yxx+RBv8TO2#TL&QgH zA|#Z%?mcJICi{Nz_V~C@Qx&*(`%xHETWtfiE?`o-Q><*_G;>ENI%dH%)CZ1SUSPk^#w^ zpb~0dWo~fyvo4vCCn;GQuap_Ns+_R}s$yaX2B68PiI=V>-cFBuZo*H0DGi`Bo*sMEK_j#10?wdh@GGyUQ?WQIt+*w4aZgv|WDdCv(ASbg|chUkx@i@K|jU z(&k2i99gV5@IMzXrHm#A%}ElS2ZqKTA6)$kP^8?Wy4|{bA$n3i=f?bCQYZR$Ic?w^ zLTj)~7tiG?QTA)SquerB^y+=6TNaeCa$A=5Ypm!R@=jI9LOZYU~t%R7Jy0M$CZ>X z1m!p8?QNJTg?G;c4WiPWrwyix8F>`73J)hL0xAW(l0xSBnGTq%y&kdHwQqIGS~8oR zk`E-ceZM3fPx|;bq_Lbd*uc}4;W+B=elPQvG)87F4$T>U0oHqlQ-WpXURxnlZp{V@ zmWLr^?}UKG9BMY@Jpab;&kFQ~tA$T)+MNx~O_z9_%9FaU z1v`xvAlOg`aht?6=@fq*Oy^AA-C8o&WW1;P7qEF(wkfUq6Fp@w4tt^gVvhhqnzx{08(Vz4KCD$@E+NJIazrg9Ng+3^jqCkyky= zH`bVRXa5rH0rQmtW}Ux7M+P4e@Oi4{lpwAUIe7`Dsa@b-h@jpO9&cnoL9 zw$0mt0<~n0K)RtT`bf$YC|H^5gpJqSW+NU<|hMba}>T2dNg=$-KdJLK7y`KNZn4G zB^KnGXPEOF1`dDpxUD{k4zEBbpH!=3>26(bpcgjBJHPy%)kr^XqsxHojE6hnltjiJ z~(1Cd!dExeQNEl#AQw$~d?qQfoXTVDYjK&Cv=0WO=7JTGO;7^?u z6|UO-pd=c18TrwbO5k2#663L|r`+ZOA!QBF=kT#_Ipg6y7|cxG*d&YQpCp)r-9?46 zb}7GV=^X_XK|J`2dDe%{4yEy`H@t812#M-wS^B}jcTR(UD3CAp5k?Rk5fU~ZjVx1w za~b5xf!;4I6MrYMTRL@Opnvo$C`x$4lEO$D3oVQT=5z^G13ZWo@85o0dq;I>g2c^b z%wvx3ZOaD43eV-u)7r& zJ#G_3SOuj9f2hlS_KJ5lT3+E<#Y_(kQIl&DBtA8PX^l`>K+R0jq-P2u`xGR;Bp4!|%a8*>qPk%1 zyEyP+qcGzACzhYm>PiQ$jmp2UcczlRjsL9P)Vev^Q>Y~ThGIz?Yi>R=gM90nl z$s-=h-#0~8&$$XtDZ@U@BMnR!h7EK9%pt!K5&QzVpOqYLa3$5*$ zr(h+Z{Zv z;w$mG1r2-dq93g8ey$Q*b|tCF4(hl|oOt@A!R1E`*lPlE=kw6VZ53zAB-N^cM+A+O zgfD*lc6sV%5PX`jkn&rYRP*WYNs5`8G-2Vqhl^Lt(XZt`;2X&)m73a1X_fM^6Q*0X&pwWgZrk0+^sc)xA24&syX)bAjW!rT_htU#;;E#6( zkP$WKR>2OR!HNs%VU?-q^f4ufqISJTS(VlvZjTBni#9j@@(z22ut2R_$~$Ch#89Fu zD;sR2oKcssu$CUMT0=CC=@gJxIS!;;h2Ng>8#;G*bzplAub6fr`fZp~-^n^meyYx4U#nmn4Ywq-&FAhC|nF zVi~Hws$XeEli1btZu{L?8sBy*mf7x|M_Ct9aV*&P)5U1BpjQXZGY%wajC{>ZH4Ut{ z^K)M3-+QuVLxxnC=LwUfi_N_;2_wJtPx_I1Ue1e=ZCg_tbvr|4QhSWi#S1zGKBzVJ z_E%#?Hz#3>6|z1@S=c?Bj=q$EbCoO=Oa2i7{_!XfO$;p#QTlmk|8P(DFt_>k+|{G& zU-{!33g&-aACD`kIxBI6eX)xe=cHmU%$Zyc_VKJ)h z-|*F?v!3sq)GtH0W~FAJSL|ARq^C1Aj7JGcx;+h3SMVm=jR1$x;~gd&S33gI zxzu<_MfveLhMHfHJc;{sl=*B%?y56W?`$!!1N%GkRsx&u5&wKQ9#gIM_R6RKFzUvj zZ@u^${ga~7jUs0eXMv}Pny#I7UFD~R^65V2Oh8-gk^YG{l)itbXpbRy#tLC z+x_!#42Mp-xXf&G1S_vU-QM1HbZ#$T*a_(8Kqoga!9{kULgg71I1MqTh1HNumgSdS z<#{_?5E1WtRAonZwxa%Xyb%8rX7F-{r%=bW?5XXb36;MPv+!mhdC_&I;sUnXe2<_1Gi zCMI`a<<0ZU(s&J2%*EL7dGq2L>*cs~{`1U;%uV_;k?B%y^iX)_aLtuf5&A~@(WYCx zwlG9E4H^+>VzN>S$Mp8$tx_ef=n7Q1gKT-geIv1)Dj7zC=Eagm4nBw1zE=y} z@*9P-i1$0-r7?0?7`r?I{Du|~WpMo@05%i;(gV0muniN#A}q-ZG_#%3GAYjpecs72 z5P&OT)`S*i6j^z?@|>jL?CkkGzO0-{S(Y-y&mTGBOOTadAi~zJ!Dy1;AE;8T#E-2L zpUloofH&6U4P~`_?TrOVJLykyC-SsU(^!$0wl<))C=xbU z`(85Bh%hfWqUu1yB$}-LuU57jnbuQ^+wZ1z*8dbTz+!cNy!2oQzQ|uu-Z1-Z0|%su zhn{Hg7v2U+gpRBYqztS*TU73BL45Y9;?d#Z`%rJ<%HfYdq>53#vL6ik{YnZS9}#6& zGF7@|yfDgql1)*`DNCpE76qGTt`2|sy0fsJaY09WeKglic>Qc~(P|y3#SrQ@TeZJK^ss5W@6kC=IpGsNKDH4ijE`N_+cIEm7I1H< zZdBw?j1mW#x_m7sEj1Z% zJ3$YU$?2Fa#7709g!KM}yfgHedPB~GSG)5`<*K60fe;_#v}d~pnK2?nl4fOPQhZa^ zte<@`Q{!18^=I>bcsHxmbgy@C?+a7x_NG4pJHH=#B(=IOhlsDHpGBET zaY!&eV%;m1^)FeUcTCiMKxW0rBA4t7Ae!UlUuoBRCmL3OlHNt7?CE7*{$ng1^fdM| zl}kf{-hqoxg!+hKe*7fq8I}2Ng2laXGA6gqRdV@FsQixtpddNGxVMoKKhwo*zR|m_ z+3nK0uJ3(SzsbhSgoHAE&dX5y1SCO83HPK%e~a~9kOBX@-=3pYJ#d1bRYHLzi2Ej| z-lIYZ=_=aRB*FFi=?}(shs3wizycMC-X|ahZWaQ&WXi(!U?Fojd-u6kw}#Y#;$%+& zb;OlYsOi4+BmIus^h5o?^Z7&l#mj}W;)>f-vF**ru+mo%9xamVYJ^cVl5;nnPWx5x zaIZConTz%KaIhr5!KY-^Hpa0<8l6pb^!f@a?-hvuYgX z6A~-Ia9_dBiRQ;J6aOv~!>M~ktKQIr3W<}RNzthwv$%9;+AOizIh!jtJJPI!d%nYr zJ8~~vA-CVAOZ?k+vdEo)EasT{)~`&wAM{9j+w23q@L4XXdN=&_%C#|eEl7_$^?mr#4F14HgQ@8qsHue3Ifn&bw_u?9H?`^NZ8Zq2Y-vQ2QaEUk zMs1|f`<{_~n!Dcschb1eK-`i{_t*)Qk-hlEkS8>CUByN=lLyYCv)fnjR~D%%wHjxD zO~z>nv5rGo5BR#!ewy4o>BQ=PMn&m(NrBj^aGG>3KSlo=%35@}7VxtwLvH!-<$7lM zQ21g0jQe6jPSys#Tt#(0wk7D}bKZ2!?Db{$q6Sj!EbPdHp57gj zR3C@Rv`?ec)s#H)x!Ii>7=^D5tcwgU`;KU6=%lf z`!pIG3a5ET{x7n_KjYkH(AT)V6#dirlCS3{0qqKZ&b9RMaGYT|A2O4{M)F@jO2R8q zv?FK}^{DS^@N@VvEi?|A;+?uYa8`Ye%Va>eziIXKhTlk`;#@})?f>5s8UMo#5&oZ{ z3>(F!@6Na<-&gpbl-#Cs{hS;e)IbyyPLd#UK`;)5dxW@hEINb_7fY#x-QUz$QD;h1t{yiZMjP4lNlyzZ6Xr>#w|sxI!B7>F#F z(V6tdXn%o45+4hUi6%Dap>D5T9d5I@vW3K}DgtUiDvq5Z4g?1VM&Fk#k@M1$a;5^O zm{Fe+IjfB8Bw|M1I+8owSxgkJ-nPV>;#aZ#pcgR8B6?VEVjL|1Ps7<8NsYAwgqxsX z#&`ZMfw>->W3?NOlI!?kK5hl&*BxXVEZj0+taeQG7vzDqg2e4y#!4iFJ(>qQ6bfH`ErFT`X40lXz!aiB0H zVYfHhv)Ey}LSYe)gNKLx?IOC82TT27;*NrWWY8EMAi=ceYD(*^p&|p8;v!;tKN)Ml z@NLl>l`AQtsm&5W`uZMALFnPRAD^8S;Q+ys-6rT-SC)%cV03t}BzhfvtOEMNGzMWm z37Q#MCAP3t7`6OFi>lC{9Vd5EP$^bAkpV{5qVeQ;U&e8L3Oy4)dMy8zQ-GCu)Ve2$ zM$E}j95We%5NW$dAJDhMW2u@7$`;R1QgR<=;V#H9!{H>Hk2;;^ZL&E?Yfr}vDAKt>4vG3$$U*p zCd28DT0FB;2oXW(*y32cV)pyjs*yZ$r*c!Gc#2Y&CDcPQlC#66zsVl5ZWiaK78t&K znR_+8y~J>HukqdB%YgQQg~-(wFsqHVA@F(V530WvhvE5#eI-zg_wmi<=9Q zZUv*=a^AXd}-B41dfhfg&qPZO=!N9cbH*Ck!@2sB=rSi3Z9xO;Cif=5( z-pP)#urae|dy|ZFUz+cu$$TS)7L&w~`7Rp1#_9V3;rU(Mz!KLPvtb|^5tjKjC(y`$ zwIL85u1o4C6U@mAxa{wZ&yQmwG0NfHCgM>N-@P`CJoaF1X^ACaao9k4geFjF8@(SE%k zH7Rx2_R=3fG}TVNy#4zF1*JG`8rr?$dZ;FVWQ~T|=INePZiUP9!0+*A&%89z@Y19h zd>=#PPFg8q*?qxU=9}_Y`et?JmHdFnGrliP4Q5@l1`p^xVYmJntwGm6oXw)a^}BcO!Z#>7cPq!s#EKzBl2ILSO$0BVr;zV zrVijka>;_LI3Xc#)lKZ_5#`C(*W1LAiDh8b*d|ztI!X~ebKJQhStJ7I4J>~+}s4z_5O2^n<4BM@K%?t zE)A$x@+PW$aLxnF78nI@9NLfZ%lcbb-p@{$ZDY)}C)8)nqCz*2VHu0DCo4;i!_L2QI>9p73KA-3!H@^jDw4!Idj4wEElcNnrK%2V5 zV;gsC(Z=lY7rUzHmC`Mt*#E4L^i$-~0yrD;#r%9tx)m4AkdxqY`t!dBI{&wDhBk-G zDO&x%aK^LI{}ImUhFl(keA4vjxl4dsK;(F}HS5g?HLk%8t*kUUdfPk30yBmU;+3T_ zF#C{)80xbNU*URL=yq-orbo8)C;VCNLiUURHvW4r*y8DgNg~yS_jg ze#tsTC05UWL)wV)egn}_1P!SFz9OMK5oiDMJr`5h>y=ecuTyarvmzg(5Lx`bwgH=Q zEzt3v<)|BhMWn$!ie*DYd8V)-UvM5ioDi5rJI_>mRY<184pQ3Q%{W80fp_#U@-uT8HKioggC<(xk5&-E8-~& zrT*s+Kb$0dLJ8)yR^$IXhl!iu{va{NRfQ%vR5%r>-d%~5p!RzRu14dMFfJezUzY^L zZDEU&*Zq_&NkypoLPJ^WtFXdTZr6q7!RjeifoJ5t_*rVqK#@UqG_dO+aqo)acunaJ zHBZig41UCV;0WpN_<6m;qjzn(X_y6I?7h(ED;qj~{~9?bm5l=8@iXJJ!4t(UZ=3F|-{?tA zZ;4Dd^C!Q$Pvhhz_n;X{LOHEr zt9lEK69kyYr4p8Tm=iq~w$(pP;o%fR!l!kKignf%SDcz;;+w@v0JRGFqm_hcTDb|T zprZTi+4wv zm=2g;I%IDp$r=APB{~bCI9+Nv^>&eWHzljw!w^69XMxpyzlY>(y(4C8AIEW|>L%Nd zjDX{)S3V6uKP0+p?`ApqZlL)X#+2kP8Qi;a!FTmeqBR{q z{qAmrOsTRIrN;s75?$G*4)Vm`$Pa@@Ht5ic6xbLKtvoUd!`Ht|(q#Y3Rj73=aL26R zVeYvkk}EPI{4;!y`SLu+mLUA?p4Niz<>1ck1#O46Kc=L^wC(y7kMEwKnnt5?Jz`pN z%XIp+!h`aC=up<*`qT}{z{q3>_9QcLd$I_qti0JD-84DjMbMtUJN`{_W_z$c0}*!~ z9VRtJZR2U51}FO_Q)Agr`AHFzB1??#1=Rj8A>Ve0p;1<>8o$W5W=RNl5PI5@DJlxAG zj*WScSgz--5?}-9D3|9MgfvCSw0($yd>f2EQLLjFqphpC^CV=+g%J!H$;!=`u|4SvDU z_#B~sV8H+S)Tc=upqy1BbTAb%dY9=%>aeF~WX~LJECu9vmGH`Yokqgx31lnYC0w}H z)wff*Del>gMtd#z7x?VgO|Ovh6B>`>>1Dod@KNASA3FeG^Q-mh7F zKGEGD8LpDZ&8y{>Xb<9kweVlWpUXEJ$a%>tO5^$Y#GNmQX3Nlzon@zzosMPF(FyLc zXOcuFxbF|=U2ip}YCn{7GvB(AmY5c5+4sxfs&C?`SlaQnO>#4H@_9jqoOfYwa>du? zzLw8sc!j;U1sL2J`bd!3N5Vv)!oqg_Fh`AP2leVk*o=;o$R{#f@$`p~K}Pblk6&(1 zghq|&SakoR+X-(`2r4F^{$;b|s(%VL>0&LfJp4~8w4Y#NEc34DP;fG2Q8I6R^<3Li zO3Jj{lXpXKsMZm(qhJ5@8xG`Ip6U9h!o4~&ku>01@cm9K#ct)k$Bo|^?l|rE8t{Ht z#%lfn86$Qm;MMLQv?=NxE|wLLzrCB%?)v9eda==66i}&2t zpNul)qbe727pXFZ<9QX!uKWzO;mK{aagtG!JbO>SXXBslq$`F@E6LCd4W8eY5qAbz^d%dE6B zr>xs7+vMmLB%IiY2<4v-QwJI^pzq7I;nJEnCswy?_5q`TD(yrWCXfC<#~(*xZ^1Tl z+;#F>C1pha`4G1<_|NW=-T;b z32OnX;%2a>=ueKf7F_)l*@DY%6<}xQW8y=wz|_u<#Lpm()VXR{U9AzVLAp#ISo&Gv zN_?2&7mSf^E6R@V_IJ6KKv{kO^;KzWsg zmt1e{Tm1vl%K8xI(B)aJS+7e17m2J=#JBU~IlRXx2me{EL{f`gA|5aU2dpXjfmT^m z6q8(b2WY9Yy3LP-f^z+6c(?@bE0~CP=3|8ZD}_-;rs^M2SGJ`3N803NBW(3k=}H-t z6DAEbE_G}No1+!ZE<~D;um_`^k{8)39n9R+u%F$Jv7}A?XOvARp!5%#1YfPNmpXBCphiC4U8W0|q(FII{6zapt?^gj2h}RPR9o59qlH<6o~- zIn_fJYf`~q@&kR>kDdX=eVWJ=4ltQwI6J$=$CF%Ie-`{#8Td?WZ%|}kevOjP6|WZ` zA5e*q0x)I5TXw*tUWq%BfJ{R!YqkFE>52>0QWhfA0v>o3bTdH+{3NWXXCr?oAz&~} z5SJG&a-JeVZ!0zUg7G;mOOwf`1BVEu&M(H_L?#GrfK?%L9pg)HG5+#S<@*82~GRN z*!PxPf(Zx?22UoM!2UI-F=1#p>Ivb{)9913V`EcVw=L-Im~Uj8v+ zL*BY4TAN#?Ra>-WDIf3A4POguRVe;05D{{#YEH{ufj2Gr{o|teOY5mHs(67i{a3Z_ z$0?P+8=v97z&?1Z_u^7&gY8lPMe^h^7nZGz$wz498Nb8p;fv&3MgEb;6=!Q%>E^YFUtu;(UaSyDm z7(>f8Q47-2S>4|?UV1vR%HL=tB|n;D_o#I=ks zVhH^`+oHpsKbht>&o4jG&yI8DPpvq)dPHa{6sT9gUT+y)B6qvYYaiF!K)Ce%#EJJU~>g#O|vA&XVH*{l(4!!0?JNgxgmk{Zz)OfEV;Ct z2}b_F!h%!BCy()yZrIEn2H4y8M$kx_(o?*t9elGQI3A33NaeKR5>aXW4Hw3uV4A%r ze?;He3u(WAPwr-3lU>$3Or}dUltf0}o%MdxhDw&2q{Kl_%;uzK$eDV54|whHX_4e- zc5`F)n1`^#G1U9IzR(K#24~=k(FK=TXIxjK2HZ2H7ZgGb*a9rw68zZ^?Z>hwrli+G zN(DZf`xJoDzM&lWA&j&wL zFNCuypd*zmC_xB~cCQvif`qgVoTe+Ut}X1hBWx(ZA93RqUE3yB`~io1N!O01rJJug zWT}xk9StB@B|bF&<+I9t%S1avUXp4QOvBJdLUf3&8?+}Fxn@etq5%DnI%PikjklQ{ zS%;aSzWsA{`&Gt-ADFIp^?tx2iMc|i-%`p}WcZE}&NLZpHQ)||0t$_&+XaWY2+Pfc zzvBaz;^XOFyB5RXwAG5WBqh_$e_Z!Rirh*pq!iqHwsYfvZn9l?TbS>!*x|-n`Lx7u zZWVSZz9aa`l3Fccm5!)5?=o)hip#Oep;E&~vZxd-RK}IsVy}>K`+Y%e!9PPNj7h_)7uvO-@c7e0(G^m3-Z!aNR3yc(Yq%&(H?|uqdO-N?3 zJ@c@;YjSaie@!1UkSX*uP!FzRwZ_eJd-R7b>6I$Bs*}`ABP|EIqmQ!V64f6AT z&830PFMR`7hnr8?&4^65w=7{W4hrp^uSv5D@v$pK?p0m2I?3>V3f*2b{QhTwvv zJ4V#1^<)ymP_eDTTnR_1Jz36|r-933#Mv|!_|kQd1+(AAD`A(&+%AhiVDB%;wfWdRK0tx z_Gr*gi&P9L(yhgvYBwk}Sa}iA!XvwF)$Y@HBU|B@FE*aCT;u1q@vElRCcdCHF2HOv zR&#u~m2Q#jzm`dRpImxLwd1^VB5As$oW9vsv`;d&#eFj&`ut04Y#8Z!rXVCS@X@|c z27J4XK(Rx;?f9zoKYJoGGo=2-|JgYGUknOyeq6NTqY2B2cc*FHe;tw;OG3ykGq}(N zPax!z5oi=_SUWXEVEXKXvc=fV4};*klL&n&*nMzdG)OXu9}r<9zRsp89IDE?+iCVW z5vT{_ExRnXB5)9l41i1qOv%Y&z}-v=NQ*xT@8%2QH+e^Xa_6w14llT?&7zZu2A}{f z0$pY!EB7-G_dz3^fkwt47gz9;7Y>6dr1v>z@?=%tg(QbOpsNI2zVc1(?~cv!6)~eOitu~FZkbMl$7-15H1%Or{L!*6dJq*`gV4j0EvS~6FrJo{?PtaIxzGF(8i~= zt7_&4?l=gkAsr@H#$NkD1Lt&C=k9M(2`msKkv1HW3QW@7TfmPeeIoh&hUD{>1pmq?nsI-)BCFgE5na>!|$VhxkRbo&{o%tY*m zK1EjhmEDDJm(46`MJ?g(S4Jy}P~eHik_N1a@xy%O3v(U=`$!e}xQ~=uvw4|W4iGzn z*(;T!rL+7k3tboZQd?55^JYiSwO{uM#jAM?4SdD-$;%a66F6xCQAlAs8{WP@vyyn zE%z*CBW+h=3eU>cz7`B&3MZeo6Q$td5fmFDw-rY}&!lR$+IOY=+}gGL($`^~|4qr` zDRbW~+BU{A?E-@Dym%sjeLr4I%*9JsfU{~-33Zeux1I`qk`OGJ9)Bn-)b*Sm4`$AC z_%)pT()2@RtM_*g57gf<6S#6kcxnHq1`VdKlH`+vK-vBWLYCqDp2ioh>bS8Bo!8Nl z_7gXaACYhg>8~11xscucl>2<`p54LawQnSAq<3_;m3*W(%8X~DFEP75YYm%(k}s6=5~CR z4r+7?JtUjzIdbtC&bdY_83j5b#||{~YT1sGC&nKdE?%TB;+D7tUi)CAAh+y%L6~BS zvqMADt#34e^Eombs5pnWVP0ilrSOPjaP*6vy#4w`hCAiM!C3^&kGPI-_o4d^>1J8& z#GclKFC|Vb?lb2oahDifTQhn(?Nr~9Vs3V(0_us{A}95?T%NvGTR%bG$f7xRo3i+( zc?kd9lgEN2n?NoLf+(y*g*^P?;kCrWeMRQ$_lxVaoXrE&<`2h$FOFF+pPec?U!BlT zDgjNN7_jez45+jA42JRf^}9U4Cj6Rq9kx4~s#ACU)gz_uY%cKJ zY~xUgPs988OStnvr)fihgV(_Ga>l(|d}XOSif($WYc`kN&pHnKqqkxNcWdkL>5kJ4)ss6 zn7k0Z-j`kD7z;BMb&idvPA(Rf6%rURc0& zNd2)!ZC42@yp$%4U#|xyoP$PQui3ZUq7HIw z5l-;$@ytl=KwRy(S2^mB^jMr{uqwgUh4}QVVaaNyP36^GMs%l$bFkN{Gx^3h_l-dn zpM!V)LYmF(yQvvksE6ohzjgxhp^S6^Db5SI?--LCG;=aGS633!qifgXF6z^cpAug0 z5$+CL_4sy9dkncVLo--Z$Kwpfv~FrXK&>-d%s&V%?##*c*f8&;E;jnDv3h^>KT?Hz zlqOu$Q(isaRS06QTPUG+l#BBnqx8(EB;0aVd5_e%0pBuRFN*i zAI#IyD2~CA<>+Lz(4q8fefHld?+d`3d%CkpHF=*V7*t z|KI2oIIR#!``G0)PW8WE&CmUh8OCwLjS4^uD*=pnz&NCn$vr=M7VT=%J#`k5AYkb0 zR0<&Qx0fVK4nfjSx>QS;2F?ZEFhoXy@%_PB1_HViS#f~k8?foRi#a=8N^1d%4cjyNN_f#`4MaIQ39=l}-oI41$huMP-m4Oyb z&@xZwrcNE+CzBX6fEILl5%6B&hIWs2t2g9p<&wJ8om^fjF<^;RU@z%RMxIk;gc+Eb z4{&E@88e5)*A+hfwf^fPz&y@Y>*zgGJIv+U0`z13Qp^z5Q$;d2)D{xpcp5+klyIyh z9A?Nw4rci2I$?^4eM~Wx2Z-_GxyNzuPJ=P`rX-`6X>A#+DS5~m$*}L+dq${cIQE$k zNwU>xBm7|8eYwWgOb0gcN#u@IUY=tAQTf2NNUOYUAU<=@5IU=xqVMZgOi|`B!`SIh zyx{9fRAc=>=eniU5-S4+EPdz&QUv`=|9V9Is+mRm;f-UuM*38Cg5#xqPyqV4gV-ar z_cehmp6|~^@ufW1;G!pw67vj~cW3J&cdjWGN#%D?-yaa&?11~}LJ9OixFtRoW8lx^ z0PFhi$Dw_!8^^)JR@p`@vNgEfCTTdNlMjIn>1hhXUT2(4I-VA5b=>Q zgEQQ5BpbIUq=hvR(K%u_N`3u*1li1m%s%q*TpFj1=|vZj(^)1kj3h6eGRe2yfD`wU z*q1&ZyTKlh2H=d|d(Cw6d{{kX7AfTu$t~$ua@1UX1L5qazO`SZWq21=8)*>xVDNtOByIV_JiUfBl#a)6GYw;F>6P)7i?(SN&Xdt)*2_$UZ{qOGV?#%AY zy`OUDez=o6IXTZczsLQL+&mV^epoX3Uf=MhOHfiAz|&W@r^A&_w4u_rF_~$Ox|6{) zQ~%rghGduTNh#ocvIS9jm0m~eiveaM(?+! z(P%v;gYb3~$@i*|6*Ib}-PvtTPpOgyh(vLPS>_EkC;&&jebA5>XiQyY%?IV{^s6rR z8`~vEc=zEvzoWy%Yih68=9&uHoH6$xB53F2ECU4MU^>E%>wg?Kn!`HI-$nPf!`7AQ z&Bm9i`?8Mzk?_9oOJCQ4cSoFlX*?;@U39AChY+)iD_Ij`sPgEF$0-4FiAzn8@IY;@ zPdDPH9h3}TSx!3oc`R>np7vfqmkqC`0$j%Bme2+7KHqQ#+DCoA*irR-4yPNnJ@{JN zb(~{xxAQeO*R}@kKOKOOo~BJ_Ltv9hI|9ZL4Qa&?TwPu2vvKTbn24h$Og=>R9Y^Qel86RW*=C#C0%2iwp1j({CeNi$w;dj!D z^KZ%{c{pBQ_t|^`F2N~s!fMjx4m>|GxZ-fl&0GP@w%6G_`rQ0W6dfZFG`>RYMm&D1 zJO8g;OAaS?=ip0uXn8O@Z;Mdq-%Od-D9W#-uYsHmYStSZX)pqI|SZ5UTyCv~DJyB(p!3 z2ig6tli8RU*MVd_^9kFat$T9p2P7Xs#0wVu?pis*^{LHDZ1-`8x2TPAa?iZbfA5&e zI#USJhECt0&42)~x{u22O(O6j`A+Liu|59sq@uA3tLgy7UUV zWdHn$71ryVIAlD?%y)!wg=>uy;t!7cS0JEK3jNV_1=-0tLAN(HxPFP{LOiUb_2cfe z)(;l#c3SO#Qg+s_%2+SQFW*m!2~-A%jpmOwm{3gILg5AJ5<7Zo#xafWTM|_Z4{XGb zXR(_Wp=ujRnyBGl@O{>C?@ju{>*7IHWYHb`!NX^M`@8Ki{lU1~0ISpZm31n5ve8NH zhz44v-$BFvgTUgnco?0EeG`aIIc%U?s+Y^3!WF0~;V8$M31@^r%S2M`#}1>hWcFG< zi73&>1x|6E)uTA;to+-$TOYgeCTo#{mh5r+8%`vw?LX6sS=~z!5PG~ZQJNQH|NjYE zPBNn{h@WT+;xh7hcl5st3{|N3Be^sIW*>R<;OPURRL^aU9x0lIcecC9w~%w^VjNWS zPrjS?-Y-DMFy4)rBeehJ+U-7o;awMVP<=0*4i1*aXxub_fdXJ>CP$5j!$3eBB0{A$ z+Hjw^fh)7UNyqwTY9$Vfxg0nAos?`oMwuuEXLy))kbV&$-Cx4?$P-{C@VTCWsP6ST zjvZc2k0FB$@iSZuiwx7_&;Q)?zf-8#2Lw_Rse`7@ranidga||gjX#k9g>Dm1(sun4 z$Hkq;2&yc22j~mx!KNfYJu4mCfnRPB2x?Q??S4M=bsoU-ei9!|5mw)_|4EttqiTeE zuso*e2aIR^q1)0f&Rd&}+0+WSapzdvkA(Zo7~d}Xhuwohu%)8-POu1Jrfc5x_Tff5 zN)dqc+z%H78V0!n-_ileSoh@3W!x2*X|od^Ma!5+x&0R9jE<)LlTtO(N2fTlLvtoU z7nnX6>hc>4#kiOy5~kAKTW-XM`Jgf$Pe2DDhLi`T4#1;F0NGJ}P&BQaxVTkg#h236#2%_&gv^tbkYent|hbE z4j4@_jNcM-=^{k^;87Am-zCaEo?bA>@O}ZbMSaCKRZDxi<4q5sZh14MR=R>2u|<;9 zaeRXfC-{h&NaO@dMHYq)*Wqyy5wG{a@~<#&agUw9Fv(GLSZk`vGPH$0u~s+(QKWR3 ziu)k;7_;4h#+W4GJj#bKPW_V`T_JZ#C?Ov3AWUmVGTrzK%g~{{t3b)0kZR!7(0`xe^5d zN~fW)%$Dt?r|L7#KtNWs`c7j@+eL&)Xf(b-TaWhN&~*hsKJE%G?E^ zXxkXg{P%jCr?WUcnoS0_@7(Y64)zW#1>!b+j-4mO@`{b0RMx7|oIcQBX8C~1;z;#9 zaB%aK^^rF5PyPs$ZSzwuf0muXhz?i@-H+4&U_G)KPh z^F24FNau$t?D0;$pzDzFPxT`Y0g>zIdShGDzv#NIht~|teDyWW&;CI8=1qz_&^%ii z9ymIJS*CQ^AEeD)+NW5iSXTKvFtr6NY*J83`tskY)?QaE!PlScM0vvJO%VFYc#w9S^-|IjI@e>mxo{ddW9f6jMI zg+HQDC>cL?+Hv{e>ic~O#w&X+89$$y0KE{N?ysl*-aOovcVU!oC_8GZs3_WXr*I-* zr1#b~60vj@GMM+GY$##_=U2 zQRBviJ~ha8aeIy&N(wbSD0DI$lU?W!Jb7OmYn?eG#0~R&Zx%apaX{RhSU0wjT0I#y ziG6)As{4>ByeoYeQy=1z=`Y%dx8NbYxeo56$U zE(7{XH?S6xSQR9(r@86R|_1ZSUUmI7o?^7F3 zSWQ$b>4Z!qX~cR?U&U(LEtb0~(+aXee>IUvA6JSIZ5-F`2*4*UhKqc-{dU+_w4sw; zMhm-sGnYn-gvm?LM`54&MlLC_!wFB8`ESbM0&AZ4j=r$U0MJ;nZz5bn^LOlSnXa@^ zL*>Lqo7bg{@dk97x8nqMmww)0k!26I3x_5Z55Bt;?uEA{xBqAI0i3u^&Y^veO4}6c zyfeOm*600Enf_e__gF{@m~jY~=3aL{^wBq>SI+wzJL(-jVP*F}0vE%t64|8*jCLE* zftn=0xDAKSyUD-uKC+!`mI&QeZLXXDXLiCl>3=#GBWrm6&=u)>xmWShcmr|YgJhos z-gNrpTs?|KmZPR0pEBg=*>7tQIfv_fzdcW(C%`&mNA%KPS5ph92x3w20bIGSl|-vAQ*ME5Am$-@|&5~f6V|aAN>3sR~Ds`8DSTI5Dd(r zG3(ZB=En3U>iPjNQ_5xdE8jH_>Jm^^rlB&m)8i-s1x;b<{lLs;35pg<@Ulu!!f%)_ zVbCG+qd8fA%~vHgn7H`5>>n2gn+{<;Bx=`eIRWBr0+@oy7UCvg%GG^*eFi0&B8q+z zsSwpxL?Vq-p05#pCUREw>qblVb)6UCE&AhhouGOIyEHcDn5`eg6r{!QUQ|%&pH^3i z>8$tG8TL8`FRlFGZRmT1aLp+Eb_7$!dUx-@|7R7XDal%a7 zCw*p7t>NI(aily)o)BqKoxMR0_ zldc^1u-KkwSJ~8vpfD3u?J&mKUn~e z;n6XSclEwvPxk*AHpm2&e_MvaqW!HpLnnsPX$M7~lDGtk<8)&mYw!glq84ly5s zyCQZ$vH-=75E?+!^vV7hUtoJm&5<89oK6MY2RPvT+cFdd4feTXz>{l@`IuKoyu zncNToCM!crsn5qnHgomnL?)jXA|z@mE$9>+&8Sme8$-s22cwfmN5*D{eSDzx%)yA- zhX!4MrD!M@?s^Ho* zh$y{qBcS<&k=X~#pq3g8P;k~v4}xRCEGb)HJ5rs~;MHNy?0#T zDPhnH2KWSpC_TRG#2|0n1)k(q$O|c6;|FZHbYXa!ZYDWG{b-H=$jRk3zG0T-6Mf>` zZGNAP=)OUD4*74@rd}2rESyH6RM0h&y8x+?rHR&rd6B}=D1-8 z{f)9J3aUkxbTcsokj|RijcC>?eSHrhupVuPZEh2z0~Xo~hxI8u$#pZD%`bv|#wI5M zF^{m3VzH)N?tM|(gJZ?U`qNuiLdj}x0y?lhK3rVrdmtCyb4MP3A*S1~@ITfyx!tm< z@*MY%qboDhMozaY&+{eMuOmkz=AA&>UM13~S?O{q|Eo{}_x;9KZ?9=iBx&tK3^H<( z)Jx3ue3Tku%a@3sn2gZZ77BBi+gbLYU0)X3R%cqWSi}!+}TGBBHKL9GlQ2P zbh2L5!25S3@UF_pCX@Nk-bZc&Ct*zt-HPZfkArh@@Z_R2IcDf^H7;rD}q;6{3f$GxTW(xfOo zRWc>c=O^!le%&1D-mijWLfzyS+2(d~KD4Gzk_ATE+N%cS9@>s~hQ2Re_QycxSS z?O@H9sexHM^x$&nJMK)Y8LO<(9_mNchaF*`(EF*>=wxfOUE$x}&Ym~7J$JyFY&BDP zX_r+dzajBndh{LAS8C(8^aiv!9|TN8@=d-Qeb;-5&Qzq`rEmJKkFNiBr^4nxPQ?zI zG0TITt0fdh`W&;B@V}z`&vn)w;%^SwYj1#AK*LKekGWfGl#QJ-ShZ92vF3Kn2GJ(* zAFEfsgDzHZ zesN6xp)Qv5woJNjL?D~33k=%Dc6P?@vW@1%;VI`auRg~IH}*2w3U3jkyP*m}(Gt#A zQ+id65L4ohtPF30IZ#7uqTxI#GjjYi3B+B554U->3^UJa$QV30O$#w4!uAN`jc}c> z_x6r$FVWmA?`pw_^axnu`%q7sGYl@VzR!X(;_y#vR}$6`%?ch1J}*F!4Qcjj#0@<_ z&Ilu$ISB7ufxbuB)TTR?mQ&OVSO1+qp-a~qpgow`w3>wB9`6j!-KD(}yjsrCg`5I| zxnAT~Y~izsb(Iu$Im7K@P?SsL*}Nn8Q?qJtMpt}*`+j*ugC0)ulbCcsz)d!FYXKZqvbIg{%@_822#kS#P z5}bWY={2A2aX$MAp`Pr=EHr467zWw~63d&^OTiTJx~FXM1CsCXqtc@piTCS&6&pXp z$PnWm6_MR0PJn1%4#lT*e5-Z-UE~;PC~&lohm4hJTouOs~g6O}@Wz@HX3w zyU;YUeZ}IP(mSDs1w8}dsW{Tz*wUnWq6>nL{jS_@6~2v6dFLzN;VI1NA0~7S{?jtH z1V3gD0?O!2wU_Q5us6ZQQI)u+?|dRph(F>TErf;H@c_7ZZD^f=RxU(S{1&^nUG+EE z?bhqEKC}X*Wqf56XE-D;59>>Va!yy zq!;DGZlXR)>*rTzN1SjZ&ROCR)Yf@cYf>JtZQp5v9EKp%VJM+46d==xp2`J85^K;FY@c4yRw3 zE$g{NQkq+FdGuY#_E(`bNtXuH8VxUE3S&Z&%meL}bFzwtICeDjUT9gLh#Jac>$IM} zbsths0Ej0{i$IBZCYv75kYYNSe{Ba^Iwx>&dG^a{2Lt{S-psG<*K;${-^J`fED-H{ z=iE={PIec%T^_{uyP2PlX*v_K-q`m(t)xi;z4KGyIXgaWt`sTvynPz!U}Re1I(f5c zaFg9#AhfqdeA3>VVpP%gu>WdB3!7ekygCd7h zse=y<0xRD{7A{_r=%ZkoN0~3}9WNjq9=DbvqY~rEMFe-5k$0UZFrVm2XUVuzd}D2? zJ1QqsVspUAq!ii1QJ5WwK9FZx*Kto>G=Honv+$m(@}UmEg}2-(DZF$_?X+H|F1;ha zZJ4Ze0JTXHwg5if3XXkS~MRVqBv`hsUZP-jZ#Ky$tE6b-dWe}r+-fhvuxIV zQHh!GgT1@UEqBi9y69niR`TvB%R{bk>Kod7E)T8^E+>7dVS|R*3y+tnl?Uq3GD)qpfdYZR zmV7Uu$hPzk>A34Kp(@I&8ydwE8Ycru(k*f&^hzzCO*S{l%#K~s8r?+)&I$31Rs zybY@(Tr}FN9Gu^H-zdG;Z2i~T+c?$NP#{piaMJIu9~w!Ku^Syoy`1n+0C^|~1o}(1 zqth0zt+$yj3pespH_;SxL~_3kLgGI>EJyJ0)m8dII0OtnxV#YDPTK?;O{msRX$SmA zXEfjFM@{Lr-sqng{IB&N|63T-mgVfU5PKqk-wu6k>vy!()sK4h(ET_j8_hs2T`)qt z0r0~LRbQz3`ZQ8Y7@wek&im_Hi5@u`L$;)LRu~sy!75=9RJao7Rr;a~S&r32GUpN+ zwmytcK}ZSs0f;B9f|=!*ehg+t@gC&#B;Z=o?7J+GfaBf(zT%t}DyjsJVTk1$2UF`e zk^^RGu|C8gFgAlaHk&9BK_wW&-_AuHx!%xW&A>i;W%F>v9-;+3>#YfOlb?|;bK1lSJ$WmLhqKL6`| z@wDPf<~MU9j8x}IGT@qtKhih3G-y!r0tDsI*eh$@#$f!7~9@s?)ZV5mK z41k7ODF-(IN?3z>-wb`pz7F-I#Z(|m5x~CnQ3J`#@L_fg265boX1v(XXR+;W9Fdv& zKvRPGRsTu;o0L6L(;RN!e`cu+pD_4Cf^b&827l4pLD^EqkMmQ#L&ql1O2MCDXjbA-ova%;VO{y)kdQ_60@`i> zkN6EQF?LA(d7MX4fprdn&TK4FFXCrzZRxAX{sBi&9)S0I9_vE`ozHFmNNDcY|hQExpgnthoVlAChCTL1xB z0U59>E`12Sq&M+L3hZa9!W~Vv!R7zX+Y^822K{)S9N}K;jh{)Hu4v-@`?}vBEj%#s zh{Pu_z@O>Ov*&EpihC6!sIX$On7+BSKOKc-(c;B;eEJB*48_80e;TjJi(w(39hpqt z68&CDyhRUSeZ7HU3L+L)4pL4A;}m(7!~viL6>~r97KH1CxGIYP>u>bGC??~L2wn^0 z%=%D=NMWB<78vp95LW92JpF?riTcOEaX4?mgEQ5MyPu8x$AW>h6_&V%JjP|ngHl`i zBK37GyBoi*6t^xFk%F${yoYir!D*M+!1@&R=k>mM&ttBfMV3FbkJuZ7#=lFBz9D(( zO`MYpfrWZxJf(?i@wTCnOs_o}Y|ho9bTcZmFc$v|(c&rCmiWjijm1zmdq9H0X*ce$ z%(OS~zH2Of9!Y%4hf*#}E**;Ei>VN~#?@0>fSss8UoxadUkW*iy76R20~#d&GY@c_IB(%7OVO=4PVVg6bE(6zw*V`TrQ$s*$s^1}X<4tqvd5y3oZ_MK zU9tNT@`b*sAFYce<>mI#Kl)*&rzG(g<$73uUwn+a3=3Lz=l4L1@n8;!7fqr1Bh~%cGtpaI>9_;zy&Mj z7m$b<7i*_qAMR*xlvt}Sa_kj){&ZJ=suOq?u~8au+!#=b=uUUi5f2#d6~&c$ z_&JE_rva_U;kmAU(tI=1-&V?CTW@~>l;C%v^J;dLa@%0Q`|I+?biBULY57fm|tmnY)$$(;}6dcaPz`617|<)u|i&BlHaea4Y? zLgdhc>0`^J3%zoZOR&Qn2;1oTTN$&u;Y)N=mgS=#dhbhR{kS5{p~(p+jx=UArC#H+ zyP1&)dJqX{Q!1^W9910g?krTO95a6o;XRfvxUQ~Ty^yDF+;zL02l@O>cLF_~=UB7~ zEGK+qohPQEH@1}|ekR0yqZo@n=pV8}2sLKfwpe!Ne(3Ca(~)-)zA#@GP;_ zh@s@bxZ7K9lR|OgJCzj?=o`=>pRxV{8bRfmCVg-SWsceVEg^jO&N#W_)Z?#Zb8`oJ z`-`xxrLo-se|xC)Ca{fv{L5korfL1S6uY`>zkk*h^3{sZI_mtCCwK}!yy6Dfpq$Dk ze!v{C>Rz!k-a-1BgKBMqsBJ0NDfMV}r(db{!{7#O8P{K2b~pCXZO%@<{_$lA&1bbu zW0jC&2Sk3x@VF4{v(8}kmf+CA3MkPj_9S89}KRhob1D2POVEUyg?NBS=R~r zIJurapzYohNvR}I@{>b%CN$ex7+;l!UserZARA@W~ zYVQ1g@gfswwDvnwI~5+6x-YyHbMw%ytgvt&$EuR2zoGG)UwbrbkUeyQ->s7;@HC@> z_~6Uz(CsaJrAEVWblbf&V7@6|QTp|X`r~pkkxU4 zb+!*u?we&c!oiwx;ZNlVewFNMg=(7T>w7ogbaJI@>^amdde3w2I$6igIyhf98yDcb zAOW`fXPr^?Q4d84!5Z6VT{DCO!qpq~ zDbO7H4X4s@Xp`@U+aqCk)4cP%MbG@Cz)2ng^1|t(zD@t;a<;d}BjPUG9XAZi+iS^k zuG)huly0RkDunpnYsY)m`QUvQw#NT?aAO6pLy9>=I|#?mZ>_3G5VD>zlc=?=z4BLx zysrinLDhn#IP5>Fp0QZVMfULp-b&jFvk)d~DNLw;PtT$iKxCt8MrAnKp$_^CNeuYaI#|;YGaq}% zKAGlx=y}?oy0Aq^fl-~MkpbpJp5yLRSr$vXGLPA@N$e`fglDI+G*ub@K@$p|N8nf~ zbWnxNDULjE#b(r_BxEdmUL3`tUc<{(I)az;ii})6el|g`nq9qGk6tRVUuSqWaiA=e zb7>e{V7kEh<=WHWP9=L8oI)*23V9_hCYQ}@w)Ca833)YJ^RX>>aG9zKhq#^6eAI z)00&AEfFl(RIx{6dXD=r96=nFj#(t9Zn&hh!$SJ4>Mc$cQNgSwpY}PBkf^aWKE(S> zh5|x*)$n?2m;BP1v6DpRhj>UP4zQPnJA^-!^IKvZ=*fAVf(+-G3N>X<+uqTyhvc8) zPKR1IVoIy)><#_O4jpgy$lRI29aX#qq~lniVOtZKt@?9Ga=>@?s?J`o89&d7!v?l0 z5Ltbai;I;U58pUnpQ;5hBQtA~6m4fx4PpbFIhAm0LVV_Q0zb8r)}5->d1+#PrjSxQ z{82|xZ+5OG$2|W#4Tm27VmTUxYoMT|S3dC7?TQ#l9%Wcl=9?e(7YXK6EulBBeuoW( z2@{Y7F@kqz&zEGhx!E=CCAiP_M$LN^fUkyf_#c;|gR8mc^lYKYatt%D<@L`x^UpV~< zG_`AFRHO%~7a0+xY?Zjoev~L{b8>8y^MC1?{|@@TSaMFJgrHLJ509e}^TY=NHIZrE-dQKc|(*lBC)3S*s>hVu9wRBy|B+)w5AJn|jgfsUTM z6^4$TqR#G6;loZ0eU##Eh`#VF_o1ty0^i$5%M@}RMB8UwPUN6fjPM0Ve`y^HssMns z5#coEksu>%d(-rV>N;0A*Th}^t%;oC#z9#2{Fk3>U;5pqat5Rf*voh>^B?(2Jvg4@ zgF!XF@KV|EbmoRg7zyRVea79Q%@AKWhZOl?77whQBob_2^}f%8im7{sz|hPiLrz zHq$2aIIfnj+4euvk|k{)5?U|8xQR)D>$yQeR(d+dBVA)(K5H9g%rE%YHm{v`2ng`l zQ|TAMg1Ghp>Dp57;WoxQOCnPQA7NU`UmqNPTpy(3&Z%#kE6U9);yWHJzF*Ta@kWWR z5jYKhEf3usLF|d6=h!a4j!>lP(6?$n-%A`wT%DSc#Yxf$Y> zk0yE9nL;e+G?W$)3Gu;TEIUZf_e1G!wv@o10Q6%(V%58+`~nZ{JdsOpb^4ueI-%V zQll^N_;7j7^!#QOltl_}t1Ydm6J#|9f(}p8zYf)C_AS0jJgLc&OonR{^evBVO9YOq z2R#PUBeJoteZfh)NIS{oX{|y*>Ts(7pqTZEFT6mS#~88a^-~jdeM<4TgI?ik3_@09 zJzhn>m6CAcQ}fZ0oQkr(@*wgVR|yf9ml*j zc)Nu$NhuLEJ?LGixT<6>p~-uEj=8|cbmFMLSiu#6bGy>$L?K*ZvRFI#>AWY3=lLRw zpws>#>AmlQ9{)`*g1xjR==Xy2<>s!=?$*&T1{aR|{c2%|9O9C53xjJ{aE}^{6V48Wgq{0lGr2wvvF&kZsi}dw&w(R<}Jk8;qCn<^(SR;gR=hVb~F?!gPx%({} z{@&9t?{V`D4=mXuHw)P?c5mj`*>pM=*HT5~T57eGk|{P_7~Oq@C7Im${tPg^#vfpK zYCKv+T?n%lojEPLY%1LPZBmGTC^6B7uk3fVA^?g0?U3ZLD|U{1jFvm^cphA%_&qiG zHH=FkMUUbxsse{SE|sgkC!1cL;0Ry-_5I&XSHO;Sg~#!Zbnab7y8 zQxxYM&1gsk`0eYm#CKn~&KOryl1-lw_(#+{_44QZ6iM+Y)^E=4nPiGV|ke4J*hg_)Bk#We-Xo8Fp#j1qU>nqlNUj)YQb*)yr&Az*GsLm$&Qs}rA`o(6(3 z_scEGt6e#^7nJI-kX>_ybZ^Gh)wPvrrkJuZwdfwEow7c={9#O@o(l^FSWS*qCQ z?p!UD1eX+?v2kIm$$Rxj;9Ae$7Jq>-=GJq^Y~KsGr1+AV@#-F7Yo zoDw@Z-g#bF_FXOGb@g}xVr*|g^0TgL9mls5JdpXh+-@F`4NF$KRDAYB3V$(QK8;-C z(!k3+?4??LZ{^UA`g)Vqzx`zS%Mujx@o$Qq@D$`h)KR68s?aZwya5#%32zzS<`L=@ z?NF(w=(QAjjg?4OF^aAIu2;dnCm_47nwpQsdHicTdk|h`#H0k~{h7H90(Rzu3Z@rD zLE3&==KkJl)E*W{o$2MZCCEE*pzvtTj=LQG8VfZH6roa zPVPa2=HG1{l#mJuy-%4fo^NN%(a72M>D+%6hG~0J_N5ePdntZCE)hR=@%1y6#drsP zegADYgz$R`Eh*58IkI8qAS=-r3spd*$EH}7k;&+;TR-yFQu-$c z;cJ-3wbBS1Ce;z+vOpvdG0xIR@r& zyK6wM6rtxGy&-?Z0OoR@oCO1Q%w`-R_yd$~xK>u}u~)_7(CE(XV#Oa?aPyxCF7QBc zVC2#K9~ZicFk~zf(6ZPKLA+yd% zvYTcfy`pNZBZjl%fQa97Voot38~BUbJ`*b@M?XAgIP<`oc>`VkfS)s;^PFo*A&^6B zC?8W-_|wCP5QpfDiTNi(CX=!beqybP1~K*!CBuf95-AgITYITr^Zw)Pb;oT8x~PLv zG8rD#hmfJ)ce=&>59%qj|;UucycS{=y0qb42`RSVQX zIvDW~x4(^g#MKaNX<(K;9JmIDFjLO2eYW^niOtE-_LY-DbFJmY*1mQUJ?T~LWCzCp zIRwNrm~~?0YxY&uC6XhkTjY&Ifv%LGyU|{I&CRejusJSLS1)w0&5tW|YE_(6cC^G{ zS{ARoE-%NUZwkCaB*$6lgTO zG!LrM7I!3Gx;+Oap9*5 z#%U`}s^=MbyjS81mwGaTJ$E@Lkj6?Aj`f?Y8w#F|+mo#{&I>n(Z4?Mzd2Fuf#=(mcF;ZhkL=19!f5rPmMu}93`iSi8CO=XVQVQ|eF0f%Y&t#Y=UBc`+5VuL~2jsaq$ZBkNF!Fyu=1Lj}il+Go5`CG!?)7a+=g}c+<9aF0m zpa{NY$v4E;8UmAAc;oG0+DF$4cAP&u-5(?#{;JfrL=>ThFRap<@>Ns+HcxyIJ4)3p zOh3p^M`;Vk;r||NvN@iwf^Wlo3U%S7^llTEF9UV|)b8m!8d^+jH>V5rFbVoKXf>#V z)4l%+4ZoBcj`yPw=V>;3A$E^(5KqigcSi5>%d2HLRf1pI5Zzq9e93JfO_5thunUKE z0@pQK=^&S5rLZjsNPLuZQJeC_X)Y>r<8Ouy73?<%Kbfo2Wwr6B#L3Y|62`3Agr-@8 zBX)3ir#YfV2K92mIFWQ_N;E0y6Ay_Q+<%d0@NkMq4wv@k1?aZN*f(4Zw6lqKti z;@qBE{4ikD-Ue)RujPqX4li%{&yxU`Lee*3i-^1J#YspL+HdiZM50fBWE)+_hR=WG z%l1Fbd-(q?Ul8@Omv3EQX0trVT8Jg$U=L1c;vt~1Rz6T{?3ePGeQ2{w?SdFn{66Db zg!;Y}RYj$1FWxaoAs6Sg^6A3tF_y;ZC3ic1O3?p#bXhS>-T(d(HkF(sO4mt9AtycL zcplZsW(JjWc|=*`H9EosRw7SGrY;8k$_~rbEE)fXP+Z+w7IRLG@blll|M7*yq(Q%i zj#ZX`V&^5<38N4=fJ3S|WE6w)LAwThH}>v6w3DLiC;fUO$ggy2W}{& zgs_Ea7E;!sUBF8t--3?+Dw*-cV6H& z%Aq->Kq&e42|)o75Wtd&q=?#d&f%J~ehaOG{mjl3N=pjcit!V#k-OC}OkOrXDlNnm zyzBk?I=3!%WF=t<&rBb0x!?1H`77@*tCgxTF3S=}yvlj*ZdJP1!6_g0!eq_;@L_Q* zJ6iqnc#@K(VIsh?e9fa%j&@1>6idGJ8YZ&bu;7`gA8NVsRG&8T%*2G^}>7%AVFKB${2NLyg+selkN zn0@j7K+juPcRH7T7s&?R|@nhXO+jKEi?1qbVY<(N#PzdqT-B(v{! zGLtU~zCd~>vS9s8wPauP@p9~LT*+Az zIEDWtTDH)s-CT*Hn8-o$L2!B(ph|fmd9eFkcT-=Wb6#Bh!VeO$pR&K&h0KrGcvz^x z9oi;B@1*;ul#D}UI|*EGGux*T(Oj;vK4GZB*a!ezf3anckcp2^CL@+Aq$4KCT{Tyd zGpyEmvQ5@b-@L6dnf7JLXvWLJys&9tm?GgH>pU}Uxag z$3%GR7$gcH^njiSoL3fvZ+1Pt8qVa7T)j9E?FQ;n-9*&{yfS>w5E}K>Hncx7hg51O z>aCtfVW-h=XVSxZyh0&MD=#3E|CWFaQ)ucZ$ewYucPgcOmD2t4VI>7Uaz7&Po8BiS z6}4974n$))s(MmgXyjhThj~gmz9~`k+xLk^G_-3sPR0gY9rxGi{W*KT>t>>Y$VkONWI~bIlvfvHau)4P z0Z66lKYmj%nA-V~+vI-Oug`+0+_I&Lii2IOb4c1cQLxaZ^nFIpY~vq;X188b?tc>Z z;f5o$&;!^P=xSrZ+#D%S14HP-I;ffBo|mzC5Mnb*GfD25Vun_BcHGBTvZ`(#LE5(U zJZ>AP_AT)Z|Ki&|R;f?^C$)iShAYPg+MUqO)dk|MEB2LEei`FZan8F}0aC(fe``vd znwERD$cnp%O$n&0nOvsqWxvBWSV{YB?LjO$L({;SKw;w2RLT?d?UE(bRvIKMf4nev zNzTK__!Vl!Sr$}zU{4ie2O|Amonw=cgnp&h2Uc1Fo!HBaNj^V%Z-znTH7+)Z17vO_ zfO!k*7HuS50#8kpns}n-aDC}=CLK;yOk3Xu4rGq>MESWBg-%Lba(#U`vm!IjGH6DY zA=cBr{u~eJILh&J#Dl)TAax((NYjlfrxM?|oppNA2~Y3T^548Pc`F4k-k4q@XO?`m zOTg=&8WLkXbQ_8FQh`Vw>3yBeJH{OPLo@_SXgPKz$#CGLZQwad-DV;jc(?ry;c}mX?eSzimtuJtn{&X1l4s3?C9~AD9C;2$3 zFKlU>*rm>Yco_vF81J|GF>5AlbfiMl$wsPdW8eS5#}B8QODkx;rUoTcVLH>b*zNa%%rA<1#2RF@N1 z)+xWS)ZiImWEDjYm*1U+w|;S3}90aQTmC)^t~lzCA_npO81JLc77+{+D7D9IZL zd#T;8CkF+8YTt%d>_J>=xPef#J)kAc`fa{)!zH}9g+^C+t9pKo@HfgQ3;s`H1y6W# z6Z6JW)Q1>Du=B4E_2o`hVXNN_PR2Lf8OCQ1J`J1@ ztWlf4oUgd=77i0p+Bd=5O{f1>0!s@G-b){Xxo=vIl!xC|x?}}74_Q>yCOFopdfq}k zVoMFc%xi5r()7=zdm)44f|Kbwl7_LWhOiVUjh61rqy(ELT~XkL%A+p=T8!ml`r&0N zog+ASd$q(NX|So;>fu`@C+p&{&D4a)*0U1jdSmKvk#F$JnVU>xI(&%#ld`dd3ZsaR zE7uCA(EtLR6+`v-4S3>?oAkDF+nRo;3Mjpba6#*v8#e(%=9) z?nwc|tRnFt$e|C{TJ-M|pNG<2`sW>Kx`ml1*&_c@K?Ay6U*dk(x=7WK_+}VPqFWq} zlF94;_qgfJZ<$lgH)vJkg=K(;G`$~3P4ny%_iI(#HoiSyAmEW;{WN0470po9$CO#t zr+T)S7-VH2H)a7OaU46Nb^~J1h0sP_J zYAgIV_TDob?(gpwPJ|!`Mi9LRF^Dc|^fIEC88vz*T67}OYY0Xi(R=S*^gcRKgJ`37 zMmv-Hxz2sg`Tfp|=e+-4*SwgE+27greC%1@^;v6eFeYXdfIU-LF7b?jmP%2YQ1ThJ zQZ!?@gW{hrpM%6T>2H#tRwPdOiL{cm{Sz-E%&`EK{2?A{q)db3Ycx2Pm9MhJT@m6W zoGE|{W!qS6iGj?CpY(K{5a7K!X(w%4W?LUXj7WdGlA#6M9 zTTQnQ>lXHD({IDdWD?>ieIlh85dbK(E>z;u46f_$UqWiwBLb&4ST|@Ab62zWUph5) z@|l+sg7~}v4$E;e%IG3s3K7BhAn}AJyXoLS3ogFEu|e#iX%@Fm$(j>s%E%<_RRQgo ztxbz~3pQ!~5eRUWo&+kRhFu^e)O)gR_Z8kYm{K;uwxDJYbb6s(etGd}niG7ho^qSt zLh!q%GiVUgpBO~3&q$ZiX_L%?2t~7$m9$#ixA*Pzm9x+1?q7C^_f%A^Kozup{G4iX zahlJJ;TK6RtKl)rRb?c?S~2x($eCXHb7PYHo|1~pdSFsQkVTCuyRQ)J%2l{Thh3no z(7!kmpz)r;LYpFvSGzBvcCG-6fUR@k4FqLaW^X0rMxjr&bgt;P32B;PM@82)bu{L?pbtc$hq(BEJA?1K|sOc<8JR4 zXN3-YFI4;#LuBTpHi$SgS?qfOXx0;2Bvqq@_mW~@CVZ~9K7-D(4+ke|j+zZEiITz` zfD1;E^ehNj%e0tX9Ap53*PC(0+d zDA%UfQ!kA!unX^~UU2smBu1OArlu4b2L9khU%QuB=?^+45LRfQKqKXQPJ*ob*3{TY z=tLk=211vA5SjoH`A~bi*^3I=TSptltH#z42!GcB|DNs?%ChL5a1{p%PF@^(!ckuu zU?fz=GQqTnj?NBOx)qpxGX(>Vmdk5aSGySDoL%x-D)mLM$n`DI4Tj$|_Hxf;;h&$3 z`e;bX<5AtRx?6gwNU2;>LA=u^7Ktv&u4($4*htLq&6nI1NOA>SGm^h+A*e#NyBS<7OM8xjPnd{-?e=G{Jk<<3qf-|h8aO2Fq6#zifB^lR}^!T6cOf( zWj=i}`A(s2pH!!u{pp zFxgU*3(eW~i!Utn-df87?(O=;oEwcgF1L_KZkOT(jknZS(AuuDxl}o~6?!A;dWQpm zf#O8#>kKq^^7{C;X(S)x`>+;=9qA3`?d42cgFqQ+NIx3 zbx*$7^+HeYsNwjG=#Si{B6Z2H7=AKZMLrvWKJl3%igYza1?yGih|td{7n*M<%c3|r z^5k78MVJZ_4V5&W4C|%qn_mlhxiK(g5RX!zpP87j7C0ct4rME|wyxb9kQtrd**HDc}MTW5HpyQW%x*5_WwrO-Atk%zMUa4JZ|L%^kokF{^5C z*N`Xo?SY3yu@%BFs3Y}eq4E~r3gwdbs0Eui>5-VGwhD>lr{>VC^7JX4e*lgD)Ji}Ytr*rGv#;7pw`)siT zwN6*Mn+S`~QoEnwdzZ0ViTmjW$_(NIwKBZt-uGPUoD1f{^#sVO+WzbW%ei(28g};( z{>Mab{_zOF#6G+Cv7Zh$Qb_F*st(X#+^PA)e+4WM?CRg~;li23`rKzBK$QXQ{Bs32iz z-9=qQvP|du0k0ZqLUs~;!dr#Uz+z`%fKMWc79*Noyhl)fcu0axH;*-O?Tb4bHMKPy z_Lv|R=|M@1X&Rwg21HL4mm~n42P^vekI?mI*+w#WSU>LLd!ZfzB6jDd7J4gx0#-5JkUlFI2Y5{RcfH2>nW9#CiOUgx}<+D%$FWpAX6XK`T49ml?a8 zajT#v{8iFP8|k2c75Wg{+w=mCa70)G>bXNk3Lfb8q_LKg{1p4V ztffgbD{aKeJrBUAa^SDpIjrYg$S>U5exb)qZO{&Uw$F$+iumI}Cu-E8hvexNXHSr5 zoQB;=Vd$S#x#?hxHsRTCC1$r%jTOY+xpxuhuX?Mk`y7c!CRpK{5VFpHok(00zeS#B z+_M(36N`sajKprp-s$c?QFKXx^1cZDNT?l+^mk+^;_n@5Cv zTGG5pxQ;DElYW^XXL*L*&9=L{TLo?=TFp z?7oDbUmr;hRwD5^omfEoxo-j@lbg5oe4+x@H*$MS48GVLjAK#YhvO|l%_8b4hjQ)4!UW-lx7!?GCHDX!g|MH0z(>kgCnTugE6lxj3UAt(~@|FKsmPjlWrW ze95=Dwp|Qp8U!3p!bLP%E)Z;i>a9$12?dQok3hH=XTZ&vKb%ET1_Yra=QkLzd;6Wm3LPl(~H3WTK>V`<^audk>++tKS1o zO$!f$vTE2_D)BrPl$KjR9^@afY2__0G9i084|Z#4cTBj1$h8hO76vQd`xj$nX7Adx zSlgYpbcng#CeEwcXWANFujz!x-1Rb>|GLT`U3s_{J?GPnz6my@n7E60OB*>@O#|owq4&D3ZN$C3w6rq&W8a^r{SZzp3FIU_^jvZAdiwz~Gd>$ZbNlnM4@VDA^y?^mz~n65 zyN9B@J@*(=H(3TNzTkbXJyS*uZ$FZ(Ech4!@NjuZooKCYF^a#FPS-JK&xne4^ADjq zRS*Gf3vLz^1l_N0kUN=C(!F-vo>a}a!cCOs?tTmUT?&dfo1kpa6UqhlK zHiM#J5?v-uSB822GYg;ze4^jWqZMh8+bL)mT z)WKpqd5;1156`yzG#|P@N2;8)JH>Af{f;3cc#gpdmv=MDfBIZZH7f4^Wv{PWeW7HxKJk7NKyXfiq%Sx(Qo^mBjXzOd|9Cb(?P(^g41k-Kk zY=EIYGA6YTMGv%mN(9YC`fE4Xyj)X-qu`A`%yJItiDWjNgTmLC(YEalO;QB^PIq@F85-|R)+ z8Qk5)S<>omx9HXS)d+i|mc{88^``dvh4ARrxvka%!ii7+F95+?IQ&b*EORO^mH#DT zR*&5_jn~rFu(DJ0rVNO>Roedu1u!^yPrbAg6iDcuy&zpK&rg_SI?y@&b7Mp6-=we@>OnFO8X4 zE$w~qN>@10!~s3&k2q&QoYFJ`9Koj;!Y@YPA85nwi`JTXYi&v5mPaTWw(qL5=iH*= z1Eh4cSxE?$MH^+94+{d5d;~{oRcVA%?6?N?RK5yCk--Tn0R;E7iBgQ1DkT&q8y-(d z5W-k@^8nlNgPSTJN;JcB(s^fXKaJ3#o{A;e7q5Qa8cXR9VlV+W~rm!4o3LVd{OQG8TunL>X&7$?>6GaE1(LZ3ik`>b8T@GXpYGiic(K2 zx?Ftt3$i5U8-b(|mQ&iWn%MgV;drfc0;%vqbUjP}@7KT}p82PlG!`l|BK)q^m+9-9STVMN(lzQ&J!9$+Hhgsp z&U*02f$uzv>W}pBKE}x=8+wX)aAlF}^Z{;rNhEnmw0T6ie&iX@@va$^(P81P(hxXn zyxpD#SO8grJsvj3h;aY!^IZ=0h8w>Hz95V&r2hBGaVV=c$rhnVOTP97!W5 zkxU@99|Uj8#Fw(SN(0vQNqnX)6(2|RzLzrBB&)!pva4`-#=oKP5CMJVIu(7KYri)(2q>&9hEXtn(x9~DEBAr50p4w2jqSlVM^iC zPcL?ttO?qGpV&U&7ln;+0j4yN9` zav}CjgMxm4a<3+K`IEV6i#)2C_&IS`xk*k8v9=l2rqVXMBVCTDQfkhFMr^t{{zNRjP;C7m57&;%9yT=suHLKy1ODiRt&AJSBL-OSIuMHmzb0md8`w7$M z6H4)my+^}bEfrm)WM`2?SyqAYE0@VmgHTtuv4uequY4g|aUq0^9fWjHb?M0R(3$1H z>i(DZLRk3x&ZXGt^%~7XMg~yqzEXvBch-S)h++FmhrUY5Ef6zjulzjP#PiI8F zf7FGRq)}%kF+$jVg+s{eUII%re=ES+ZGv_Gy(kXGvsz2gC3Q)%Kw^bOV^Le%k0ZeK z(BNGa`hHE+fx692UH6qOBAcygt2W%yEFg)rzX1wI$kbX1hO-82vRtXGd9Yt3g4Z@W0J|1{1OqdnZguhpCJv;l@Kc_)%(EqI=cx*_+Mh^Jq zG~v4z7b@Cz0u&*z-grEkE=(@v(sNEx%$1mT?&E&5lNuxzM+on2nQ~jVxIV$-%wgYQ z<2-{3+jyVYjt)*-T=>>P+it5^+d@i{%1IJlVG(W}(~q`o5^laKX)p~-@%%!1bFg#S z5e=h)CZfD-3#>C1d=6UeRNbFbXfAhno;Bwji{;*EYk1`GW!xeULR5^&px=!-KWyDS zot4~n+QIlbbiID#4}cShO#V@}f^E!c2&Oq8d1U9dF{ihtMYaqhI`}b$Hcm5olWu?U zJYV&EWvt@F(ffAY3|#2!?#^tvi(!2)T&V8DZ|y zUb0yxBM}hj+|(|YLTPSAi&D+s3#?ndEwnYvhD}wb2&^W>6l*W=;B{*4e!IV0MCG5) z2M)DN8f7cP%%6$24}y1~pYkRTb@QCGll*3jj*+=~m&GCF8M9rN!sUI18J3i{*2O6J zr+n99lvZSflE|Qxy&2v}t)=R<^gxEFlf9pQuFmX}MO%H>UyolGTCOo0I%)2kdZ27r zEjDV(QDKN$CEE`zivDH2>mI6UHVs}$$ZLf;B12}sbx$+8GmkpGL@yLo!(-6=Z*=qO zr~$pn-|zJ^6u==}-3Yb(3vkA6Z&waEhUs6(DtXbyGOsZYjDmlM%ana`+9mINF#yTo zvk9qPgxvk4!RZ6^(#B7qbp!+gCd?Ic=ws(g&^@az+<){;&%j6sqHC>aD`$DbNu*x@ z7UD^4gcaqqUGvSG!LK!>{ccyASe-~r$_*efvU4FF_~Q<&e(@+BXx{adyA(+Xp_#xY zQ)ljHfL$eA-s5K$#}|})Dipv*e-Ab=fLh6!M_}k+f6$_2myqenW8B*=ppJL6#ygIl zh&rp?E>KA{9Z7B~qF01+Qw5ptjmC=wum#xanWudh6qdHC!g?P|xJ2KU3}9x*>3!R2 z+HIT5WJFS~#Tm3-y;Yq~OvQ$SZ5I>&$i#pzAkgeJXjTSyE_Mv}u^^gZpukj!hwi<$ zaAi`7?m$l>kbY1q%=Lna(IhtLqUYQC6mDWJ0Y-6pZW3hDa;u)H>}}kf6%5`Fn*N$= zjS*^K7BMPjpCg-iq&JbaO#}{)y+@{E_C-<<^sURJ?lPBW6W+ous#P5sArH{g$)q$Budo)msH5;bg{Af#8a z;;fbf^KO)AyB{Y0v&`a5Wk9Bih|d#62qn{AoBMU z1CPCh0Ryl3qRL4UfAV2+l@W#nf@MmQu`9O2t{PnWhhF8#7$>y#{*FcNegWP(FOJ=Y zy4h?l5NO%9P}-DyD1;tM7_m&U8xbT;y!=e%Vh$dfX?X6`{z3I{BCbd_3#riPfyZJM zk7M>G;^cRK3~$rp&in`Qn)iyg^Z^Abjo_J(+PTd&O)}Y^%~XM>Rv9m$$rL;8?!Bt+ z4jPP}hr20=TsvMZXQn|=S!U{{<_)TlsGn@EsMAWfO{dox@2OgDVh>KR>wZX?zO5*z zleofkpC^Pu^~;97u-k{{T9!+yjQZlbwHOQtsir4C{9Jn zc`1v>>?_Us)~-qr!ln06GLL0RKxzS9tNKAJdc z_#>(?&1A=9)In)&LB!y55c+Sh*jM7y!R2M8P%B|T4F`|`H>x?PsUDGeoTWRE&QW){ z65i<8)~E^`!^xdtmc*}LgxDm+@nO)`Bl89{N( zu`VlG*t~gvr5FU91f|`h+9C!mXO`tJ{BQhky#b{MRvc^~_uunI!wgR_YKTFhebAEXq zsO!bGmYkmv{%P^s`8KhrFz2qHN4I{_%?nPs-Z`B{&%DKiX-{I%>4Y104PoplZo6tt zH@fXfNKNj^hD=!?wOf4pI;EEgzK96 z{At-yI^HnQf`y)$@cIf-ocmi#F-UNco_HCIh_fE)l=rrO!~^nB;tsQHA429(z#o?S z$5BU$Z;2JKuWx$vw>1C66e269{@rrCdt9`YEV~)YVSGaF09ywHi|!I`r7#b+SEtw5 z)^R%2IYvh*F{45!%^v#7o6PTbbi`Hs2V-YHe)V_f81y+6a$@n{YuY)zj4x5?9YU!Q z*Ugu18gr7bKPn|5v_;`(Cti0VcQn&X=`8I?s#6S#Yl|hpQRJ$6-y+ucyOisAv2?v! zpJ}hNX5~3E=&TbD-r};8ImiC>4icglTpUt(GYcI`~H7@QSM~nBNYJn7K=2c!ZaFGj6mCxw6y3a%oMoR&8mRUk*E) z#Js&(jG@NTfR|8wP&LGl5EoqjdR~;z$FYTCYe1lL&aDc6xeItt+y4d5eDp(W6~};J z`TAKwxpIQW@aqQmw*2S<)k144B8OJ!yAV|*AI~i(33`SH!*@)Gc6&mV%?KOmjw^F; zv1kYu=)PDGJ|Ya~%tC({jgz4QOWnIn(R5PwP!2zJ!d5@d0n7o>8Nxy8x<`jDx;ou=Y5D7AwmqY*DGg zKx;1bEM{zjXhI{!mwDvHlv6q;Je5fq8Q8lCSSsebAT%qnb}=0e4p2#iAXsr9JT>K9 zP?oS}S{SD3NTSuFg64YP(ZVw16KZ&!<{5ABCCk}KwsPv#QCLv2DtB=w@T8Z+xB`(V z>3mBt*Flc+dFs1{mh?Uo2o?e0%iM_jh&R5TSt7(K-!PGg<)usiD{msdH8(XONj6v8 zQ&N)AcDB!iz1mM#Uk3~OktJhij3@%6f>x*W;gAVyIh^1YN~W@6w6%&Mcsv}{gVKeKUZ6SH$iU|yX$ z1QNs^ZLU^XN;OU|F{7QR8Dozf%+Iu)sw19A@DUT|S13h(gut?g)SY8(eds_Zxv5O= zl

4BPHFApJyJO<`R0?ayFZ_58|>H7SUg2kI6#@>e#4v^`=nJjQ%m9n9XGhw9IU z^a~-Pd#thhruqm8KB<}(JNCH=5qMi@ud(uot*@wqL7yY%#6PkY?ECL`>sY%IuvkE> z%s%n|l(i@|SX*Q^zI4n}P+?dSOHOs>dCgBA$*NR+$zNd%|2D#v>B3n4iU z97W>aVv*Y~nvrN!&dMg^Gc%%)mX+6u=kx=-CTd|r9uk2)suQBaLE{doAdirdx_4fNGgp-kF^|yN6HB&v+5zOTq7lpPhf85Ko?(xUU0YP0amBgTd!7=|RcPH0 zKMtknQY=JP2bT6p7xrAPMo> zUq0b=i^qU_B{yverkI+1Q4_Uz5j`Ha&$52eTHuoMM{#%79Qo%v&fFh(FpeX*cX6H_ z#|8h3QQL>l+n5q-ZJX9eDXCMstSu_+uPba$JZm3-T_@aX8mIe|i9gQ)7%sxv&=@A! zjg27p_8SaHjjzTfXB%yYuMFo`EMk)D7!w@>UL6ivef8rCe!miLD-b6)i)n&^JIO{R zknlVOy(`USrT0XT#7EerWiH@+ZhdWj9xsRicBISIhX-*kUbjyKZ>H z)WdaAR|-(kNMk|vVK%LUlE3`Exq%j^2PH=vnGMJHzmjT#3z)Nd8E{(dKqN2wS?9so zx+-92KF72BX^G+D*H4Jj%RX59H-R~&3R=v!?Yf*JcTL=fJX!B1M|N{5jBt|Gm(Hdm zf??J|h*^K+bU8`;xn2f`*hQtkuFppC%2<*fu#W$X`}5{)bZ7>2w#;=ydy*mL1M%BmMnZ4q0 zjZQ*$JwE*NyL>%y^*(NrtuDikJp77PT`W-&gWtoF_qI`v1ytuPr7L!<-@2kMv?%iD z*kvkqPJH@mPug_DKdisyfUSBQu-{-`T7E*Wx(ghB!7-`$n0M<>m#k2CX)oM|{@q3f z5a*aD>cq34=IMyjrVRLE(S&2h8acgW*x=A|Ra&foAuu^8L{vvEUao`E`T8aMIm1tt zn7d~0if2#B9mHrl!!Jt0e`sLgX>@KRx~;b8MwhUizGjFi)9URDG zog?nh9(7y1&^3ykYW`{jVHgE!EEYCj73s2k7_N~Q*jz|Jsu@ zp{^_f8~xns`Fp8X=B*PuKbBV^)qPdLFxGerl(Rkdh{&M{L4E2-qzvPW2 z_|`?G9i=?l*@CXpxGFTCjd*<3m(=Q0%S%{2rK~r~=n(J2=$kHeB!^TezUw@B*l=@~D7g*pPH6QN21{1ff z4?oEHYfjUgGnH*<%z+#Kz$d^+soTZahf#inbt%F2OTwq#p+Me~PdO#9xCTz%P<0{G zT!5N0NIS>U(tN-{(Zt3&E!u(+FrI78UiIEuA}g~e4SXMhSWn!L9gc#$_4IOkSMs*Ik*Nfdsl=qU#X+OcJM+z}QcDOpj6}T!DsF z4PkQ_YCCo4OQApVg#n_)4xzt=s-mMQ;J@@a71AF5PkG_3V$TCGlRfN@Ccl+9w z*GLMp{~U`12B-)yc0~4I>NY817DrosgV1yqoyGxQI`ljLwj&Bi3CuHz1bZ1t+DSxU zSTub2=Ng(i2kgq zs&HpGi7oPL3u1hkh^QOkquW&TP2@c_U1|Jw$o-E~)7tz!SvGcTBPP4nMvkE+@OQB} zobmNGM311AVt7Ov#7&JznO~*F`W%v;5S;(ly z*en0yNE7Bu`hoY;;6sx{!aLv(mh`t_Aj0MeC<&n?&+;a(qxJ8=T-T?GB}E4cSWDwL z_{D&HWn1b-mrFx%hUL%Z7m7!5Qtp{L!zO7b>M}8Oo+oQ^Z!fGlyN3!qV_w$3ChEc_ zq)V)*cdwhOOPQT&JA4>X636|L=h=86-Vg*>U<<6SPb3Y|!mYzV^Zai)H zobOL8@3Prg=khGmI0Humn8zh9y3I^WzJ6Y6HyO^^6X{j3ujRAMV@zU^&5xD&>-e?N z_U~|I8u@~=trctFo-Jh$4$;yH*YnDv@ZT?ILhl?F+gOh`Ya2+#E*D+6X6+b!bXI;F z4t)CIbbp3S*_3I;%DJ&p8n@vz+=I-vIBkvU#p2Ur0vqc1R;a_))l#ozOk``X(}ei4 zy%q0@ORqQI&2Dp?X>EqR#ioNMk}`1{%-#xe;*_%)|8zf2Y0IId8!1DbPSo$^Oo4L* z;67BqieQ>$oyL27*E=IS74nvNx5M>~MevE?bIfz%kyeyk6xhy+Q=Xz%cb0|k8+`5b zbTxmo`AK)>>%+~wgXF#{-Qw$Qc^AaqV*DE7`rYxB%98eJ42)=sv(bnXVf(zeiaOGK z+dSdnqSSUxKx?t7HqX1u=Qt959S0y;&-6})wzZ~!OmF{9eq|q}@N_q_lsq}GT0FjV zbeP%!@7 zDgE@z!bqw>M8@@wKi`3Wy~C2GNEkdj{iXP89Q!QK`0Ju5id3(BhT^51$(MnC{1l7z4kzCV z+XeTo`Jkwp*0vvQC`B;XHGl`_ng?ek`Z&I`;RO{#k?9t!bJWoW_GI(yMDJPn@j3*y z#n8)W{kw_?^T8*0O*b6%U0!BBpOfGn{#qgAO{kiNbo$!T@YkzGr?gJ-iLA7Efx!|| z)(V^SS)S)RmTy@&_41M(f;U9mJGI?!t6Rv*5f&|e4tX)D8w%|<9|I%iN_7)2`cEK z8OsuhbfVm12kQ>WPmdME-A7M#o31L&skrT$^oJ@M&LZr(DC^TKla$yXS_?_Gc7Y@8 zurOuiF5&Y01)K%@A*Iw^&otvIs;d1HkuJ3vKh$Jq3?`Ty5`%W9|3>HiH%S9@pTWGW zAxMEr3_5|pgFSA&KD8?A{@RU*b2__&feLc*7|cf0z5?5FtM_X~iDodbU0VH0{b1I( z&VR|7uWMR&yMM_U5`T|>#m6j8axQtLAw7dB_ToNy@~uC2#@5<*Pqqj?OwZuj+VX%` zG@M_3y*+}rjX1dp+xis+3-2}j%_zqB%${RNMx9XEvDiF ztHjgJZBOjSOsVn2`eKf4^lA|$f`?XIpe)Q1CK~I?N8^2+omJ9A03CT;?>Dt-i;k^Y zdxL8nk`xLIjIi;w&)pU*nV8x(+u<>kwWk3cr{Ig zn*rbL4hG|PtAHN|=_}EjsKVZ}?A8S4G*>muep9u5y2?=fxn#eV>C3^eJURzTmjSVE zV+w67#{iY^4OO|)?Rp6VKQd@qtm>LTx{awIo)c)V(g+CawaT7K0uu0?;F;)-eY#2# zxL;YERd9+z*7!JW)qvQ?a!X4F5E{+r#$nZkDqHl!ntF64BI;M3?8dCxb#Q= zV^V)Q!YL)-{V2u<2tS!bPI8iDVm*->5 z{Ekc>3{@q3eAy%&`u-da*|)DXD&xk1d z2xc}+VAo!t)yM4Y&!cq6xWr@ zDaXSP0y>Mtsfsf~6toONo}3%UhTRW)K9PV;2t8lMai7wE_G0kuPnjovaMtL zi_5e|jMg`qZ};DEqI02Qz^LR!Mj`+%N*w#81j_B#y{S#@TnvLC0}Evr4?SPv;-5Ac z*yXI*(s2=k5|_QvZ7(}O^6xk8kkllZ#EvTa-UVABi3hC_r))hqa8XXS&MHPA&d=A7 zNvp^MRpKtGT zDGeN#pI9rIDj2%>cx$+6brr?b9vl*9Jlv8-z)^`W5#|1Owms1Hdzq#BRKO%>*rDC= zMY{LeYqmv@Edn2@8*F$Rx2C5mm0ay{j2NgQ|&dBJQZ{jbpi+vY3iV;^wp4MW8~ z`Fpc%mRc^KM(HCeZEw_S ztcjKuf>Ojlc;|sdyX4I^Oz- zH0fE?Ur9P$gXLts;SB1Kg$qp~2x9A>{h-TlLXhdZ43)t0dDZ0gTgpkz&Hx#4Q<2ng zEfEdtKx=CC{c}n3FWYZ@H`Y>MzdWgpBabLMpn?Rl@ExWw^DyY+fg!O}y(X1H(K4fU z>h*MIM~CIe!$M0;_MovNd(jOI#9 zOM4uDyB;$?w^y8RJjD%HC9hXPLAIqT{bc4H3!$6@y*dyKzsM1u(fr|;D;X04j(rI^ zU`w`~9_jegr|q^YX;rpyu9Q80-wj7<-AE?J?%E~GdVV@_6n_}bhxICygwU9i2M!CF z8G5o$stD|=;bl0s>KuM=huZR*w7wB#r^J4eEoe!Mi zsw7wGljR$3A>Nt~iU^i*qbM7%tLkYuXhrS;>RPo3$v8Q*LY6M?XV=J#x(D`%Z*9Mj zgc`HX{^r))m1~<8C9`OK+T`175lj{Da))Y%t>c|+d7&)cB9kxw%%EIUm_5Zv)VZB- z9^n1aUi~!c*-cL&a{8~o3V7d`Z`AbH9gZt7$FzT9(@XUSP&9wYJ%TH~Epq4N(xP)G zSe73U;jP+Up7hog)8VpcAa}zqufz=uaP6{}EKI^dSuk z*ZZ+B#%sE)xQ3Q%4RLX0L4ECi8?-_QUS1sbhnQ^*{a?ChN2+Kjs_DhJ2YLm8m&p7; zF7H46T|?3zP>7#I(kO4n4f3x!T%iZw2|HggxrYDy;yO{EgT{y^)<`5(+{1C~Y~ZDu$)?Kb7UL-Wa0;QIma&YH&-EPfY*IL`MjCd4X0JG{#^j zVrl-*(WLJ_phR7qKc0dBt%t&B>9x&Hnz3APS-!j%F6$LWf4{? z;y=sj0~(QR$KT1S{;dr<1H6BZeMuL95=iP{iFWq7X#aEc$H#vQ`2?-#H}Kz?;IAV8 ztB`;Er;z_s$p7nKH{d^o{NEeoe|F^mK1JX^JM#bf4*JiI{NLNff1t&G1F`=NTFBY= zk7mn$^dNc@fWti2Y;NG8KwbU_=1v`xYKlT``i5vQD5v8>gPBTVN5kdaq$>*8iC#-u ziBF~0({70Yv8y|i^yTd;7Gtk3Yq8V$r(#3iY@*KC)M-~rRqp85&9bQ}n zR-d$-20j+{M6Fa9-EU7%lavW!PieGl#7zviMDYlPY+~{W=Hadh9IH}94QuGKe2(7B zjcZgR)2OKn3Ot4nZOLwYCX)W3d3S#ti-*G2>(Fkle`6h`ABkL3Gnj9q1w* z-tx&pWJH2=Zz>}2TRs9V(PI97a(fPiZE278>Wv-R6O?y|G+6V?W1`_l zhjiu$v%g^e_X*KU!Mo=zZ*qk2l0IX4;InElo1!rV1T1;~4gyIy{6)hux%ycDM0jrk zDqoG=Frg+7t~YgZ3mWsiC;!zqG?UfW?B9I$YAoa3A;~A_#+cb7jB(#r$zp~ucjc5G zITRMu33`{I&=3RN+9;l&DN`4{aXk|=>^i*ZG8RFl&K?s=UV47sUEi>5LLIi3Z-NGm zK)t*Pb)Bt!vF}PWoN!@iaeV_X>O$GHW0rt}^$kzY7xt?nvT{FEm=D+aZvDj5$e*Lu z{G;NA=09&&I?&6w1D4@7IGKIT6#DP!TC96oAl)a0 z<$JP7@;_Mn&akGotzAVFupm|hq$nZ?2nqty1rV zWz3=>8B#sKt!B$iX8Np}Z$1h1c0e2ixkitOJ0r;|?LX7v0`&S$$_~!UK6I zVy!(B1W&BZ@tXIa3);8{@R6T|9JiChlqGEwWx>kYOxa7jEe%{~%(f!8+MZG$I2m0hN5g2H;Uc3mC14vtntt`s0tZ;IF=X0MGrE)K~D|-fnfD zsnK?9|C+UR+v}Hn95DG{bG|gz&w-p>ZrK3JlfJDDenYXGod4wgK3*BsxB==TR=0Sxfp!1vm; ztXDh99$SrF*HW5=gl`P_-n z|0Gzz+MJrd_FX)jZzT_&;BC&83t0U$735iJ7p*>glL^~s2xJ)=JbrswW4$3^ZwX-2(TYGcm?DHqFs4p_ z9c^NK%~eq(08o)E<*3_9OVZiXfn8ZjY0d%ua)0PKR55HfV5(KNmo~vcl@XRd|8*CD zU#xr+vjmc;%H;vX*=_rW3&#H)P)bgRWN_~T#e<5t6s|JI^dbDMwySF^1x_>(w?!HB zNQxJ}2(*SY@Qm+cJ)dL#Y;hz0>F#p+(8d^kaxU0D zdkaQr1T~Zen_q*U+<)lLMUI#LcF3);74h@@48};5B*eD=G3RYb)N{setEMf(a?gfxr z(*t_4K(kMhtBBFCZp-L#Z6$7XpMDxB{YQD2Kebh@Y9U6iCkANDWoN>m%RHH)!F$!E z8(ou!&Rh@*Q4N}HX>Eu8E*0&5LZu0tg^3A;Q$0I{vGHjYY|%G?>0F#@^Bx2i@9KwF zP;EW?$~wc7m!4ywnkvk3l7Kt>JG=j%56ySkHahpw1UxOb{B2PJ= z_xBkeR9V^Wh&zvv^RQk-di??-M#jaET`)nkX?sRhLi$rm5(vQN(|Lk*oB&*}>o%OO zOl(*Ou2-Cy6ed;%istG66=WVVWzwimSNZAL%g0;`!|d!V(#>aV0@ zA&5Q2A?1Ik>HqP8a4jU`D1cCKv@an2A1brYE6XXr5a(a~}kE_?b}D`xbBLXOpt3m4Eq< zC4JWJp>KL|Y_-50xONT!UqBs&prYwl80o;RN!u9D`)ljTYg0op+i1F}iTRs03BAS``((mXWbiA~Y-BPb}vm}Y5?s6!*>p=QbXNT&o zZ_r=D5=IGM#Q}hEKKRK4-Kc%)L~6RHIWgPSDEwv_zb*2!AmQOV(wAhGx%4=dN~66+ z)OzE?i~N6~`S|7Eo{X;bR+tSa;LG~jF`m-1jBhZg`=e7!o=lwTKVd3sa*;4>W*`e- z2hLp=wk-ajKXxFtr-iXapV>zke8kHFKv)UWzV{q0UQ!rgvuY*A`yNpNeEr|a@&9}X z(G(gmdS$^%%b%Ap+Y-AJzPxZ+EDD?MXHbP}U02=sHaY7pX;Y%{!Wn>yM07K*G^l2a zkO?Uk$%6|i4M}|S)@Ri%2mqr9YQ;r(wz+8kIn?$THVQ?D2_dPDe|QNXcrxboO`{l8 zxy)c-R{f0|{gM1o8sg;js6(HcMcDR!q4`Bs==99s{b|9d4_UMNU;clb7D6z*~bx9cDkZ8X==8teA8!T8LOC| zSS=d9th%x{3*8`3zIN5DeyJk!S18c@ITIK&>BOK1X3RJ2*#-fx65%QC4Iabw?=MsO zcJ<`S-Y9C5eTSYPxq|_+8R-AV33Z-R-_!x0o6p#WqkW@FWag0*{4@lku7pyzKI3u` z)&>M;CRU$FRr)YP>_kK=hewq)?zYDjEPpZZzT4c(Sxz~ja?HCybw{^jz68`5)6|KT|5`;PNayFNqfrzkzP zrw;emBK-|)A?*Otpa9aovPx<;yyH~g94Rwm#qYb0A1GkHWm1zdj(Q=_{XG}>Z$RQt z-%8*Y%gb}B7JM`7Cx<`R;p+)$RD8Vh8AM$UUw`jEM`B=VBz3K=Irc$)frUwRkBFLk z*Vhdtc{A2;KYq?tDiDI&KEvp=qtXVOQ(j)$xV!K9UbkpHwV#@ApZe|D`NHKo3&tB3|K zIWc;>F#-}XK+f^{%+_~Ly2ecz^cG{R{^WscUG;HO46zNu;ROMcrBL%`!m-Fu85i}U zcm8(TI?>$P(IyFzSGuTayC?j3PuC7g;Fuf z+ktb7C@%^!O~9v2Li1tR9RcR(KGNiAV7LZq&tyb>;&-yu2Q|pIK(}(b zcsS$++d$HBBX`HsUk_C)YIE}C9Xx1%Of%o7Lt!&$3ZpdJmKvms}PQ9}lp+BB!f4)yn&qG{=^;f#V z!K;rx-4<~TXZE-~A9=A90)2m(H$3n9LjV0X0}j??;Q8-OF0|f15E9Dy`MSk#lODEl z)_cXg&Uc%||2~p~%oV2vSkup$JvWo+5%9s}7p34G?MJ%SjusRd3#!9bjMe6)LqYN% zj~`@SyL`iWLrm1iSUcu`^%onX7}nw_C;IK4y(VdL-fMq(N%lyhqg0l;% z9!Ihe%YgmD4ACDC9c2D~`QP?S61x;Ib4#JDvWZIbj&$QlLFPa?xir-U?3t>B?wUS1 z%XyIbs0{$SZ)P`zp9uoS%Q*8fm?#=ESrlt_N>#Iulh)P zU%iciK{so?>T?z5n&qs!GptZ1CT5p?lZ5Sx^eTYNANJ3mJgyObl{Gyg;MaTB@VmgX zZZEzw1R(CS4{>;jJldMcz*Tcu!JBaD?+6!opL#%Teqw^D#^h|+z`2>3%Y}C7r?L)# zZm0C#@W4Q!)qO+zy=fz8E0k$*GKJqT!m((RS0kMLo{SMIGY4z@ zt1*8v29kU#>#onudqw$JnS6nXVI*H$d291f~%%)n#)E_%~LEpJ~sEw);If|JG7bs>k>K81Se6>!Sym zLoeOoP`E&OG-b#En9O=A>MgIpqsPEZIL%*sDXKb&|Z^sMx+>y8+8FJ?_^VP=n$g_zbBhSL} z84vG8Mw*O8=5%az!s(F==HdIYs>aKrs8yt)D8eSULVYsMzzm4Pa*`9(5-Wf3Jalw} z?ydPJlx#mAm%8WhdeX9bI8K@7ElIgG-^rOf6T*^f(^;{R5cQ_J@ZA}4?&SnYQ^yw|9^@3&K2+0@SgfhgHkrjnQG@bx>Oiq8mG z!rcQQ9Qy_>9eTJp+&TZ)Y3~yr71cBZx6|0YPHa-nrhF+g1aM`LZ`60{@2k)ZIw-v@ zq^ucTm4j+f76}B~z7hbgo82rGrM|uM_3(THJD6q=z|0|{1Q>&cKxb>jB+c$F%@GeK z#NMJ$dfRUc^9%LHEVt+TK0Xs3yIkFuEci$Su)(q1tMVs-|9AG__y_uM4!fEY&vUP+YW*UfFDA>jUO>bri%53;>|VKDY4D;84)M5oZ=> zsW@b(=LZ1gKXx<$j)Mn72M!x{GH0==b9UtRI1Btt*?)jRh2VaaIS0(w`bp0-VdgC9 zr)%!Hf96Le4^7?yMiPI(T`TVK7~m5E@3Vm*d+}GrM6`fU(qq0-K45C?X-j;6UuFR& zz+I2!d|*>Q6E5*yI~jeaS!VwM+4h>im|lqisIUM2X;6<<-RZ|P?%^M3lX1DNA;3rk zffeNYRsjM=C7=m>mjCWh%cV9i{!Ph78NhX%{MbK&#T{m5R&~w?LTC2fN&qGW4|(Of z{{W57*nM!CG0!*ny}pS^zewF$ufTm4oWuqB%)YDGN$p(imw`-C=&qJcpWXPY+1)}1 z)N0p6SeRI+Mel&5%;b^#25UI=`T9bPYhfdMI`ToJD^}LDV6^u=Gan_Go5=MpPCT$5Lw zI^VcUfhi+f6*`35WUMpD_qM;w&`@|Qi{CSG2-x-04N3G#qWGAIQIdy`Rimj^{EOxL zi^DZAlMZj9IM@p7{OuGzRU7W;8`J7ZFEcdt9J6pYAt{tXP=@}dw(xO{YmQa(I1DJw8Zq-D+^DP4CR4 zbYPAZBj)7!u6ElibStge5QkrE5#aZBCv_Xn@73jrx4s<)0sdd=Q5x1|vqFU4^o+gm z2Ok70&FxXwm5~$nci>l%5ri+n!WM{NsCo9dCK@^}o{E{%fjd%MI-LWNT|T~cjk%mg;J^pA+^R&nv z&`^Ba=3z&W&~|gR3-D3_%o`V6VbjLa_&py*q11&{m{S+HP&ui0BQYumr^j3WrA2j|0U#oo@}d660D9jlX8F*NEis%7o)*@fh&5W`nvp1$(bj$(Jx zRZ{r4N2V8APSr|;U-xbG34PU)%Hs;p<=QEYZf1&nx180qw8|#}?=o^~gM3Z{9(QF5 zAN1GiD{?WY7lAMXt+>ec_b~JM(c#I?jtoJKp<|~fEw8fbawuSCc1O#ahVC4m7}8aB zAHS5@Yb)$Y`zn+8^jwxIOq%8OlI=uP5YC{n#FwYM-)laFnU~#5E$SdaFhA>_o{cZzkhdCcJ0QowS*!#NsNr?vL z@@Sgn$sm&FCX8rX2lF-U+KftaPg0Hz&=TE{lOOg$mu@EVluiiG$m$&v*0mOb5w;3+ z(#uDj6Sso!-{=wDo2FS)9)^Vq4|<&wj`GM5SGd;gOiP7CZ&Xntq6*#7c?^a<`3>*T zXPbf|+H9yxH`KCGw~mh-8Vf9E82C*L@c&biLXm>c>@mF`R7~w*&RPUznCEFb6F&PUCVr6~9h@rh4V< z7#3w93yC2T{FH3B?zO0V$3TmSG|36- z$2PUcou=KlQs!0pTpaB$Ro*ZX19%1~E@82eKDj=-BB@h-v|Aj=G_GGzX{0FRFHz`_ zr)wKGfb>2fva|0W$>!xt94ow+Sb3Ls{_=`*Zhj?;?6%5Z%H%Pozv|A5J~RC=Y*47F z96Y~%e=Y1NE-xjGN~+Sm|GIs_jUjz}I8~S1=A`UG$>Vic zb(l>B!%LG+I+D51^`v<=5rW+02D3jUC$Rf7*3qwL+oNrYFFBQl4QTqfO4POBi((xL zOMD_2+%n&Ncrj{UG$TETIVC>s2KvEPShd@>j|6a_SQ(s_EpCVIi zcUBKn^uYAx=$P3^#~0q)%ZGx7b`s@LV(g(zQq7x%ic8}8QFYRZJ{sBF z-+x2N4hLW15pOZ+5WrXI#@G}62aajb76Ywd04%hDv6VU!-XiOll zF*SfekMj5a@mESVtI*YMQ>^yPHMQtLWX`)CCX>6VlDOb}4ZRWlgAXYi+^!s!5z%Iz zWAW4t$C8Q5aY3hexQt7SaGKz>0lZ&5-Xv9vk(V?yT@?c1msj#MqDJ(20=DbVwPm{X z3AvDll8)=eq`D_g%f@=Rid)uMY>0G@6g0Y&D*MenL1v!;VJnYh`M#|y;Z_FTgD|Wd z=CDF2mwb=|l7k^*@G8E$D{HC{i2!>CQck8}PNvAPC2e=W%NIHo#K6dl)2^5RE7Gpv%*}1eBH5dy&_EQr1M-5swq0pp7Y%HLqS6|a z^Z>qLV_D((kNoc$>klI(=ByU$U;BACye_nt-Mro)&*z4R+_^S%`j-|eLD#a7-B5Yq z2Hu*#Kfx2zVWVeMNKv zcPbDbaHX8DQ(MtqVf$S82=DgEG=jFTVf%L?!zfN~M9>@Ik}q5B_6Vdn1zg3to_KhSPkV5xWi+2R+#j*WA*i- zZXL}M+dBiPt#k5GT)S^k_cZEe;i!U)OGU*AQv6Ev&sv+U=Ie)MK2!#dmB5tHBv;Yxmj=5!bJYx) z42gWDeOhY52w4q<>~ya?w8G07#Kq(Y)yod4eK(=jB3oxv-IaB{qBW*(JdvOCD}dkwSAN1ks(S@-ZF9 zz%i154;Yh#Y7{-&boVtoV`ngEDyq`Yfjr)j5itHBe*Uq1LM6b-oOn>MPwwYv_9-*A z8L7`-(uC0RF3gX4QyML*GdIvd8#$<|LY!OsNtevBCQ6tLYcWc^&M9uucA%ytlN?wx zF3V}nc&D`6R>HBNRmdBF7YgkBwp(3ddIcXm6!KFwKR%n%(cx{(VF`_w!*8_KsCIs? zB+8m9l72|6q2eRpxF6;o?uznvs*uv-zpwH92ig59e1~IP zxw~Qc9l*NgjX6J$9dzXkM|!~dC5u|x>smnib?D7EV8>4V)TfNM&emqAejijP&S9-K zPi_7f)l*EE;^7d@#%snkv)RwGmy>(OzoSH{nBt4vh4Pa&9No9CWG^y1iHDh z!q(c!=<9q&A=9Mgv}e&CL2L26Gl>zgUC;E11&`LVT8O84pN}N)skv=H;}Vh^QNhBW0SN&llF9AK5N|BgY9;r9Y(44FY=( zZ_Y7Me)!Jm{Q**UnGlu(m@8*~!-G8YT-rXf>XKOwnjV7x$J^4ZW zBa8X`viiLMtd2Apofl%2ry(>V$WC(J*f3ek;pQ6mI2ypQQ!2cCDc$6;c}=&9Y4)AW z8e7oRt>Dt}wsovqwW1Kt{}1*z3Lv1)+TFIUeAJyH)Po*lX+Q>$S@-rP8LK@by^t*s zPR08$ux&60%AVt5RHAL6-@Q31)%`q>a(Gm^)7K}D*G}eHqrldmn*M`bQT+x<>B%(6J;1%3Ze(ybTKC=g&wezVy5 z>{#1LIi^0nxh#}9-r@JLHdrX-3^XZUQVJ#Q7hmOKV>TPZV?*w4*W0~0hpn>KmhDkaB4XNqF2)+t9^m+iJcWF_ zAX+?fY*`Kzb_oV~?DKgsRtLYmvs;h)z+w_nvHUV)eei}eHZOSGntc~Yq{nxUMN`=4 zv4(`;rQ6v?D&#lvMUT+zIKYtBX@LxB%mr&56eFGc^%4>Rjya8(vk>O}H1f@v_w({# z?z;f-7mJzb1eC4Nq5dHBXlpu__i=P6-eDlBExUyBtS`WL&h08t_jtBlBax1!Tcm0} zi*Dwm-{ceZlfQ(tPBXY5->jZt=Kcv8^KVtK60B(LOX1?E!q~I@ZzXL96dq5 zpB|R6VHBW}TyM(9Jq~&}ESWp@Cc2kefd$G?4vzTX5ww^Q^aCecT#m4AwhW}<-ZkEV z-8x|dvoH3u`-bf&;z8i$0{ry5dY0s<(>9IA)$0e5gHL8l!fZdDbGa3u9CKmBh;MKG zTN_R0*FCGPpS~QHoU6my1Q=M=!tEoK+#Z`~$Nny+&eJT2bS5$QW>JJv5b2U1qIE82 zZ)H;hWZl2DmuqCdy4L#z_bXs18$>cFsZ4emF9C27<2MT=VLcOF#WLu_iEQfiLga=_ zpzx6{WFGpr$OzQT906%g+WY99C3BV$OA(W82p{Lb(yQKEta$a9uU^Cg<@<3QjYi6P zYZV5n+}U@9Ii+#5tDc#Q-nyX!5k4NGD3z-0@<7@r2in(}Gs7ZSPQHP@Pw=~K3T|ng z(`Fo&sj4qEJhLC{oEn0~rCjA1o>EHo;{3d>09LH2=@BXmqVU?bX|C7Vy!P;{VZ+Z> z5Ow<9%L9tMHnVM{G>Yri_6T1zD@L*v`EN}7+Hoc;4Vi&0Q=i!IN@XB4vWEl{{ADmz zEwa`eJ8(>SJkkdqgfpc$^o>>yXJew=_2=R?bw331rMrl0Q$E>y+pQ0_2SC?VxE!Oc z{ANp4KFX<>i^T9O8Z`Hvw{FrA4jo8-xLwZ&fG2>IeJY$voLGMQM~!p`p9}Z4L8?82 zBykqV!nVV+u+S~7jNQBd5xEYvd0W0=o7hEyl~3x@QOs3P={WG>adnnL$)lcli<0p+ z^gWhT>Exb$_{_J|$tH-Mj8*msrjHkUwcsl6u?+67$o1s~4Iwtm+3;M{q6f0Q+rvXhKIlj(5QBxfapLhzTNAJ@cU?w_$yxlbiZQ->AmeJKq9r~F{CF4vKvoYIN)JbnsqLsptUJScdd z|HUJa|H`|mblK{3TeP2y+B47ycYn@x3%l<{V4zIlDutB;${0hwcl_S|9X}lMe`MsD zztY){z3iia4+Pkn<;M=I72Y+`KN;NgpbZgU_5p51O>H;{@0VdyC;I5f4aPZ+s7-d; zCSRR#F&@(>Jhb#H3zAdy^?_lGSGv{yrn>XBh7W5UkpDa@W5e##3a=vZrHtcmvk@Ry zb<&+3J5tM>G$%=TrlexVS?JoXAqDA4#&p5DgAwE(Pukp11_{3H-O}^hW{%iDD6-^SOJnSsYcwhnMON}z z;yxI~MnV>Td@`VzS@^qcRLmfd+;NvO7@g0Z$BIgP6T>%m;@fuy+ZBpFZ^AbbaNuBH zw7yxk7ioc5!+)7GbFAfMW~VLSVFqhZUO+;W6J{l&YVoJCM?!$TVOf-QuE8pFpqOVQ z33`0NA?^238SV|w;rxM4qeo!_6qj>6?i#e$KeeJ{I~u2EdF~TEH`}~ur_y6K8T6;+ zK}vx!t15WgzcNIClCRaE10K>Wg*4)?N)iN4=ED^he##no?1v}s^`{88uz|Ycstnpo z|Jmv>jTd|<*Y{~)%Nm#a>!Pe=Q`~F=qP#vku6YOG%37KF<{!Aa{|8s3|HT!c z#>1)ZLUYTwkx{a?k!eSMfmk8$Wf%>3(?CnKRoDQT8yg?*a?4e@QQ19LN!j0GkCg#7 z7naXAI%D^d1iYgaJ1&TycH*#PVFKPOCs$yG39-&&nwT;^00DB6ikEn#&wU5~4?qz_ zOTd5cllEha6W@hz-Q8AHe-GctS;H9$9dA!JE<}B5{pn|mD>zmQ1 z(_X%0@h97Anu+z2TsEY5#Rt%333VOPo4g(k;2n~xWZ!!+kDUqgy~P&IZY|9p8n=ci z1C-yKF@0-?HeG}=8(&tSB?^0mS*>HPa7fQLP*L2h>bssE;J@SnWc|_a@{%xtD!M!Q zUFGIS1=0CDO%oNySiu))X{Dap33dKzP4DfQSEDO_o4^J73Xh85lV2|T&qvz~RoPrm zZVZT;xUF!$tSTb`A6VJA1Z-0LyT3hpr-wp#f9$#YPf?{Xu~ygldn|hs-Ykg<_bQEl zaDEkJm8Q*MshX^znx&yHM+>m6UG0JtCXONmszC0kVf_I{S9Pr&J_Z65k4L|!!0)s~ z?{7h%+#j$`Y)VpO$h3-7qm9Cf^xp*h?q}(ijA*Ar`WK8PzdEKh{H9L0*fyuj2Bt4T z)(~xu*w}etXf5>s+}b$xPvn|+$tmdp^x~s-rizz<)&rQZm}W8W0^4Q9`~Rr6eS9^h zc^N4E=`5y1e!M%cpY#_wC?7kRs>>0;pvKJ9wJ7q`(;mgVq~vpNi~37#BIZZ~CFqUe z>0BwtHWzp+a^3rcdL{}AlCK4e*=1szWTY?MX#m%2c(ue^M?2{2S-LPsyPxz(UI1Xn zZ^}|zYO=h8QGlR=5>74A{W>-Hyxm@Ft!DI*&fZp$?2;*)_$x2B+l)Qz@*^J!ltc1T zTWgkUa&jI#{17@c8_+w<$n=?ek(c0mWfD4Z>yd<_oNQqhAs7$nx~pY#4mhfpJY_z1 zZS7F`U=*3^&fDrb;Vt|wIHw$Dq^syA&8AKgFj|?iNvb_27b%-b`(;tF>v7_=9;r&3 z2pgPwsw&;4kt_@)cwSE;LN6C_82O0ASOJKwyJ<*9&U=DUIVzIQsl+nX@R#bjlCq9PjmjHZ5Bf zmy{xWo%F$G?(h*5Xui1$?bD)IX>X8ZdlWJ|5!{yWY6KxUY`wDkYG8!4r zaSndcco&?{?P-6D@&Lqef%RpcyuF_CAU}r=zYJTo`NP_>TK#r5Nk=Iw5z2M9;#V|< z>7Wu1J22lyXpsfVntP;F2%rowjT0{N8GWL@`Xs5X`(q_XsIbddSt;Ymi1Hplp&$k}78>caFXe-Y8%cJ&nAvN7hY-D-Ccs8S)q zpexRpV<&!}5yRKRkMg1r8Zv#3T|%tZ+OO9DvQTrY&`7k>tRTLQpnI`E8|xKz|uOTx@jtSbOGmT?}<(!3i6iFh@*rW%ip33No#Jg{)m(fECc9t?h%-_I5ZH zu$9TR9SPVJzfs52;UkB!-|TrGji7tY$YRijr&w0kD44sf26`kNhgXzI;wSK?RG{fV zDKd)v*!)7BEj2;0MC)RKD>d}Q(A-ypwl!_wRtH9d|L6TZ)&oe7c?EHcjvm@IqG8&m6dzP4ZP&ETN1EFesZA>^Qedn~o|l6P%Ia{S7sv5IbB(o;adN%q>-&E#75`9$kEQ+Gui zyz>YUY|z2I+k%YScY=M@_}2wXxqyC*9*(Y746Azm+vKSdpd8*4|E~8>bI5=Ecnh@I z#2SU~o=|%hI#5vZxbl!}s=!9MGN_~fWVG*PU=vTi$^ByOW)E#K*19nkeamiUwn%do zz$oPTT%H#ui#O)!{HY?!gON^jStG84i}sZFdQEh)AW(cwYk2s5E{Hj+m+52vv>zi@ z*I3x^*a9X1`xXHLCw24k_ek?~yOngi`T}J+MC!DwUWwYg-=WMi%3VfNZ>sGvIqQgX z#5!W7-qPglwdd*Mt!tHNyKhM@idre<_Wt4>pc0LKMW9H%HryDNFv79D73JVHaesw- z-E+G)cnv7Wl^|m?Ud;4nc4tfW+(>Gquh>n8eelNHO{dsyX!{443i759vc0EVNc{eE#kGZ;b3-`>?smpy zJHFb8;sm9Z7+`b78hed>*-PF>XXgJ6ovHz*{8QZpb$GAUW2(lA{-n19>ljWY)lVjk zct?+o)==LsI6!d(!nNk{QR`Sj_Ujj)h)p-|Cb^H=kl)u_#PvRdxf{&oYSxXAe;OxL zHwOJ$C*n$6N)mKIct1@oX`XxodkV}ojx=aEo=?o`(TXd9kaoQtru@DSvF-Lu6GUenFUwdJYy)F{KI zy1|kr5O8PnE#3xO*M<6s8ru(k3VxsF&`BF8>V9UG5%lB#*(3@uB~baR5`Ca&%%@OW z8rFx2Vs{g6M;PR6_{?dp+jkAcVA$jTq9_`G)2i~KO?HsZB0HU3o3W{qAh7AmCy!#L zMA(U?#}|F~CIBI4u6)pvH}cZQrUDysl}kRPTGwAXY#k377ccp=KM04_|s zwy>Zz;{H-n9VB(zObxILkwAZ~wAFKK>dKPF(UD_CYV)PU3zq|_`4%@YWMmBApk@uwu`G|gIIFwZu_oEC8+g&Q zW4~?D&&Hz&$f{1XrjP}JhQ$=;a+&|sxAz+)FYot^i3Cmi$aI%+tvo%5x@cKE zU%ON@t|u<-^S-A3=$eG78o})QE5}N&x8PfKjsLT zs9Js*OkdIL2%Lg-Tti*7`v_9?Ggl41jj@LSW1|#xr>U=w_-+J-4s>4rwzXfep#XyZ zf9IGi`NHFSevgEw!rS{S#26`$Xi;#rW9s~v#@fBL&r2B-zs{~9N2?XU$NcC^O{N(dU@QAR! z2TK;-12;i!uJOVhDiJH}^4* zTpE8yZC)q00VD~ux~*Iplm5HefyUYWRyW=KR=4y;Ls`Ygz^(#PY=C)ANT48)H~DH7 zg}P(QHRJ4tJsq;F5PGot%(P0e;nHC6;F*M^u6nfDn540H*xB%r*B8f2W74X@ZsFsD zg%kRPYtm!K2K?PuKE&0I9Z8~OyY8lMJyd$XH?15ton};LA{Kz$Ek=graIHjJU%4x> zE8y(069?x-YuW6~#UsV2`*jGLvTwju;>6hZS?yq?b$?8<47sfLDr>Rk;-Y^~w-j_$ zqaatqAPo>xwlUYwOlIFBwX>7jPr_4yP;TI%8YlhmIarts&(T*)$3z;mCa3?%TguR6rt`eF%DM@8`o=46pBeL)G^i zi^LXoYMi>hSK}_$NaMQI01-_cNUereR(RxWn=H@n@|r*$AD#t7x%v2h{jnoi#qK|r z)497(uCU8!9MV%^sR2q0HSQZQZwk!Ex2zs$iCM!S;10J^Uaa{$u8pk-Y&6{G$;FmS z^5}cx>cQU0zt^s<8hr6h_4&3{nOh!^l8UYh!22x#`rBB>(?^Hu-EsN5dlN5OqNxbH zm$!{B4#S+Ks|B`o)~+KZcM^bL`DL1{u;1N*=p_83Fz`j-4oBS`7ocMt$mL-b0D;xw zu#7wF8?nebl6{i&8P{v)*xi!|asy}f2D^jbKXn93mxeNhn7d9JNo~H`_cNzrvYoVQ zt-b0OU&ahirFg1l)t^OVm2wv2u3{Ty(B)V5-3V9tI-qEES;Jp7qfvuSYkk^Yp$R#d zj{R24RFporNqqU<%D;(b=j!{;S98UrCiqgEk}Cdo$P_!ydgE=kpONftHBQB!z-1OB z0`RYaPqa3{_6I8-x(Q}lTR|1vw3lrY6hlixaqqSaA$Jf)-@HV1UQ>#sDNWJ>&j#;& z?;H~A4US2~*zWKtx%Vk7WNRe!*%tzpFChQ6=5rn0TFhLz#t2%}9J4UJgjbMF;wM&~ zy!dHul^lo2WpH_3;E$8H2m8;D05@49OYKywFaN0)>!?!A<1Qw-R3wo@Ku5ZSoZx&0 zJrgh-_G7KBjUB*VcA-KX|0M+j&!ib&!t2TBX&#%hhl}Gyz`?irsXqW;TApag*aOIJ zv{!JATei~9%xRods`RD@?t#Yfx7F=!J?7ULv@U;0W#h$<0#$qkpt#XuIEyOi%G6w| zMvqK?4AvS@?7$Y&yVk%{@Un_qMRE?=0beZ2cfeob7~n6*0RfnN?JHL}wa{I93CrK< zx*~a_tMpLIP7t>#Wbg+yM_gLYee4jBfNm#gZjhLXS>maxej+vxaB)hN6w6uMxu zdg_a$N@c{}F7@uxF-w`v75zN{EY0`J>Oz~?<|!I;fpG$#^=^Tg6BlA$m}^0pJ2&O8 z>cT_0O^5x0N4Kwb=s;~(ZH+b1?6BNfF8p^I8j=q*m`l7*5&rj{lm|4+4A$!rE30o7 zR*Edag1uWm^8-LugC}jKxA87~RPip{=(nDwltL)>FS?UBVm`>4OOT}I7 z_~`5!{aw!03e*H4`8eb10-DWB-!BA9$D0G~3;S&h*UX4t2C`3(3?k6FBkZFfXgzA4 zeFA9MO4e_*k8Y4t8RDJDa@B6upzm# za@3P3=Mlm!LSn!CqA>3!mrQm53ZuHiEB8n>iDTz3sgyc5T6*<& z2EO$GFD|6WIdy!X;HJ9$6Mz;{sX@WaOeui33Lm9WeqHloOcA3zYnu$MX{UD}_-vyuulC0C--RCDU5>SjX$ zQfA95ZTrTSQf|OZyU$&DeS0iQxH}{;H+URpBity8#&Eu&B)kJksS?GYVHy2aDu&xw zb?2wwS|2p7(z-v*;!lmjXb5jM{$V-5u|f{0+lctr?>F5LTq?l-z@Z51J`VqJYeJJc9dKv(9dk&_x;4`fhwEPht}(H`3HV$ zMS!0xor2R8JU*Xa!q()T^3k)Ii;ZYXRAo%@*!k5NAbQ=g`M=)=Us*wtXNGDag2^h5 z`8U@-)lLLq;+B>7CTd~^vwQvP&g@PY)prsaQ@WSyWo~F(PnGcudveoZ+-3Xc`Y5Nu z#=I$@7?ZrqV-53EorbuI!;bQvgb;2!(OypaXC9ZMJFDIQ;)K1^(m8rvl@Cj9gF zmVD;oQ4_4{pi+$Sj8|Qrq5Bz(!+vk*I&&6Hu14|cpK}a2>%+g&oKC1i6+F{}P_vnj zD*tsCKv4FJ%R-A$l|YR|cKn08F=*)c9nxzaV}VWEGv~Xp+OoGZssK^|?lt9-woBZ{ zmkg-uUfgI}=SEL0?H)^#@9nK27}RIt9+Yd#_U`Tl{kuaXn=JL-8AtB^7h>`2R97+h z#=FB5zKpU5ZN255QU57Nz^j-yU?b`jXhh=l|=>z zeeg*|kLJD{8VCe9+Y-wp_Q- z6Vn3H%f8SU4MnfT=;|-3sptYt@JB|BlGS29JVai1L||iIup*nJisOC0|76Fg*Vxp! z`#b>7s@mDNZl)q;p4k=r2g-_obk0Xk!AIx;B@Hx^a;5EfiE) zybRc*JP%s4phUz>J!2|Ya>v^eY!t84$Ci8H38o$Kb0|A;?k`O`yI*z;-LEF_T?-l- zHfiI036GOEs`Gg^{nbJ@Y@icchz{AvpW(FUFb0pSxU4&C@7PZ5+fHBQDd2FObNx<# zcR1kG-#OsaU$OZe?El1mXTOp>%XX_g#V?u34LU%VXJ^{XR!VO$MXyUtbf&?{?viYK zy6N?fTdc)l6PuYMMjO3u)Wz#wQ}bgBe(vJfbWO&^A#F?9{OgLt&+-74qU>d{_R*a~ z!9Nh*56frw=RJKxm^Yjc3FcY1>oQZGUu?9S>z;1y`xW|8@ok4XaFEJqaHQF*&JY90 ziDuTLW+fHlvQaAZ&{d}>z8Hmsg)b!4cqif~ zyP};DC{U0;iN^zquo@j&1G%K%bUN@#Dfyw6v|^RJ0OL`%Cj4j^Nbbd7eAyhFOr?F& zhh5-ZpN+g5w<6w8BeSk&lSxyO{U3qOxE}K)j~rPNyN`KO|BLMCfxcIbpw2B$J*0%* z%N5|{&Xb61Dx=m$*G%I!F7F>b2nLRVrs8=2>Y^r>gg);BdMMH9A#^6PBH9dikwK}k z?Q9XDq{71!pa66509D_ytF==twFRc{B)f01LhfzOdM&7tW5`3wC$2SlQ#7FQTXb{) zm-~PP0@;yCsP+s?A+#F@egFm3+Np3KpmfZt0$z!9bm7JIqCT{k5fHy7l@q z?d6J&O+{(ebS-%*38%iiV-4k+fYwwYKw$&UW+j$SfSN;RGXx}Dw5*A9q)*0p(PgIW zCqE{#wd+xSeTG;@(bt~EN$46DJBoL=za7|VmWxdj2dl1GHv}=hI)4TzRq2*fz1#?O zlPB(?VEf5Pd<%J`y03C1fnM_lS4tq(-Tnmua%46|?Nv4CyO-;moO$M9_f3JuAk!02 z!kKVtyFA7KP#tv~zDfNPol>U&biOlW9l7);GjVY7Yra}qsdX5-Pn*PKmmfiq-Ad;| zGjcRSN7QgSSAoFlPP)&rGXcSIXM+~(RCZdQZa?>Po92N_na^bomR29-Z&&EZ*m5ao zaFsrt4AccAdP$wD%AiQT0?W7q?s5yK8aLh!)+N|r&l$M@a--4iR_*Y$GAkh2P51K@ z0o3RZCA>V^HL)?%8+M9O><65rW=mrso+pIN}kBtd~W%%UMT=+*E0)7+= z_H_r{E8Le9+BJJWm=RMY6)pk~T1V}0(xzc8fe*=+t$v8nK7?~bF<-4HPN0fCep6}I z!J_O6btZXm@n(x=LHh}K3Og4yDTrcSbcPWDj^K`asaM_PJGRP+664o3ckJ2OiMdqa z1k~zVS2vlnrp|^0+y&S-M(w}&m!8@)WtX*wG71GAcNdX49!7drRW_#Xu`%W;%WnUN zz4s1>b6xkx6Cp;;=t;B@5jCW1(FPHb=)Fb|LX_y8VUUI-2%@(Tz4sO(gp{88h!w?*81*eScnGN@Vp8a`tPLv`12DjfasxPhYNx z-k0x9)~ZS8q7Na>nUMn2GgX*>rDgr(2h) z5;ll+H7Rx%Fnoh{)Lc|mRzAJ8Y{kNlF^_v%b2DS@c@Av3-w(Lk2YmDf_E|X?#`|yA zN4`pdF#2A;=yOoDe6bZX&(p_#p~o_(Z!m`3ZSc63Tgl56B%+2z~ii&L( zvt{P)CB(5jZ%}k6V!T9jM9Q5(*-t)Pq_MQfHTl8# zDp^O|wZtQzZbGON!Syw!i%Y_6w|VBDJxY!mhnJx9`tdJ`CA9lq6m^7?ccr10Cew?P z$&D|XoB=`JMfT3d;M(+}KI6f}z+L z|Dm$}P7Y{xj01(WyP1NN*k;E^pdR&RXusZvsrdY^Ehi0DF*iVj3u287G<)ZafA%vm zV@dfpJ&4Xf%lWlp?t5zl{VXUxWbl-l>@fZX(DD>XLB);j(yj)*|I2|wp0JR!y!_T%6zHKo-OZBZ>SW`v>z7*qq@E<9MSyUx*dw;V zd9Wp?#zF=g74#N8dBn(~2*a-Ky0q;{(7SvNd)77xBOF}epKu=&tY%!Fsb38_D;K`* zSeeVf@w0!Z-qu7}9v^D+vn8zF9n1g|1Bc}uC$R_98eiijWemtGUB19w#^;ZC2&zYr zQvymwO!@eV+v6$FE(hv^=!>9Vr^SeDDHfJ z_>oqxQG$)h@(lO?2Wv?y)jTS8@rE{;KzEz3#>?=g^|&}zZc)bZi3fG%OF#KVJ{5MO zj6%E?B(Cn=n8)HJ-~$kV)Bvl{m`#$6SWKkfv& zc8!luJ-o1Ap5y?Pawl2GzhYa|W0o4~{UOw8SSo4fMbiQ*sbg^oRP`Rr^nP9A?~>i3 zl7H^cDEx%FAW$giKI7&RgDz(;zjEK7>*Q_cj$DGngaGG~RJx)$ z!BAMR0?)}e`cVVMb7I?C+Kl!O+bw$to7b0(NG&SctG}vma>2U}Ht;<)O z3|!jVQV;zYCtgWcIsWi@*ar7end~=*u=e$Gm47!A0!|gbRE{zaU6S}I(JqYGhWRq$ ze-tWbYY_Lbc#A87{{5pVXRsZ=Fep|0*-v3mX)InulIDl#eVJG93Q#sVu=2SNWag-l zEqx6i5EKwBX%1%{f9!V%?>P-9am-g^-k=Kpsn;J377t-t`g>m_{+LM+0l6e*IRq=3ur6|wr5ga};Cc>258vK704@YJf2=1X1kqDE zLl})sBl4QaA35BGeBn;IUTle?X&!X4&lf@zc4&5q(vIEpOzU@W|8AM0 zs$O-{Le{K=+V)!C4H{AYi~0H`iXN?jWju5lIs#r%g6?vQ>P)Tp5D7ADO8L#jf? zVp!VH^E)-iB6G@K!axOZ?~5|^i+wDLC?FOj<*tH)U|*X1_37kLwo{Ja6Nr#nk($b`#i5 z*q(w&sRJe$XT(wgGv^JitVzup6nPW~K-{=Y9TKxo8>HYs8xX1&u`)$q%V~EKQhG*w zyvQPS8Ul>JjWneWB{S}gqQ~KH=1U_In5raEcP#1ZDubop9KfDOTBDXL- z6g<6;9SG1K&ijm*4QsvsUuwbfcaA?AAwhbfngE8 z$FSQR#G+1A5p#$$;bX7dkDL#X+FSL+aqg#gPEaC+YrNFBZXzAIFz!tSgy5eL006r~ zPgR#onyulK^kgvgpYS|ADo}GyxXntt)I#qcNFvEJ=Y(^r%74PL+-s^OhWwDMovv+} z?On@B78do;-g%{(=qdAfN7T4_Oxx!ienJ)&i|2FE>mG7M9k7~Or4CJzKm`TB2K);K zIUJg?8_0~L)!D}dST6S;fDQ3P0J8)z!?5BmCm)_Z){PgP+mZnr&IigaB+S>z%kU3B z#v5%Beo+FJjC-KIh5%>v``a{pj0If18 zw4I2Poc*@(Uav!(VF2|dyj?koKAnPmfPtcXvbz2uib?fk1qf1nXwLz;tK_?Q%3i`i zG(l7_>4@-@#ZZk((DXwTa8(r_1t{@YfO$EQPn=W={N6lP-m4!AO3-7CjU^-k*pEF@ zF0KxYO~E(f*+#z;$j(8vBVqJ>Vai%7Twyd^hq5roW4cVZARyeEWL22aQr0W`VvvuxGq8>Rso5OBR!d=#TU5<+rr8l$n- z(I3XQrFker;2LyXt3xhgD!ZFE4o~SAd`=K;_NFghNi@UTh}B!%8^73ckYmVeQ6eZI z=`;M|+>Uvk{e69=_=49QSW&hipv~rd{+-EeZo*@u*E;q&Z67~A9pZ(w@@2K`EV~`Vv%XNFiB8iDB-T^Te5{mwjkrT> zHQjR=;NZL;Ql$a?U7ZEfbHXLjrON)yxhdxK`aerul!+?Oy{YbBl;;M3D3W9DJV(^! z<HydC7{W>X;yx z01aFgL`*q&ZK7L>SFF2X4QxeHJ8A&0N*!FGWTrEFEW~*)@T-{=lfb8>AFaiB^jf|g zzm}Qa>raQ}F+vq@d^lN5g^7h1gIG&UcO3<2A-7$m_(&F_gdPxpbd`6E88ynph>*NdGQvO=>T`ueF|>9 zB}}+n^!!$PlJmqdA^a@iTs3I#aT?cD`{|0{!imZN{f~e_6ttS>y^49ZN9buhv)LNn zo1xgaNV8;+#o*8?wsT3fj&P-n3z9{bQa0D`{>@x4b@xiu82}dqz(;&*?Wm?c#SPt? zZSrvW*#E#5m41Sp&F~5U33C6EA70t%ph%YO;nk=!FJaakG3F!$B4Aw$fXNk)jf-8$ zltck0*DK(r(mDjjGYArUgOXSG-OoYO-iTk_kp>ZY=*B>`jW4RVh$}Rr-zAIk%QYG@F0tY^tKdw@~h4K1vA)@DC zQ_u$pQ})otxFPeG;aiK(HsTs)q@qJx@CGF78YKB8!Zovx3z%qUkIWl%iLR&08zKj)l%9`k<2{I(Z3GM9;W1fTt$a{Y0K zS*y^xu5v{zbw@fYIPJ4P#Rt(vCLGmJ0eV;57vkJIL^W?%mnpm(vK`7hw19;#N~0XE z{+t3;J6r=K)guXXF~@GpkMF28P(UGx-Ue$k&PVbmNsjmWY{^4&AdOh-Ogmg1J$G_= zeFHi_RlbJl@3)e1HMkSBCzu9)7LBKtWkunG8p)ol167#iva{DO2tRLs(MWum3n&*)zUGt%s&Ao4Dn$^5ZsShng;JT` z;z<1MGHbh`M<}+2H{cXWMo`Mv1%1{m$vNEWFn2bvZ|1tST+^T2^q0+p;*`X6p%>qF zWbbn1as9X-M9O$fDg#uPN>0TWo}VE5POs4{=PFwuaL-Z{$R-`$LflPx;V$lX>OkeV z@b!`ku}w0ytv{k13RBr9I#%1Q7kP7GB} zFQHN1j=@3{*&3r8Yz$Dg9Z*(ghxp;_#+K)do6L+Op<}!+>eYG76bNqSvbk2DiXS3y zud)7MeFf~pSr7}_1n~y@IHZavJ+D{0HZ@pr(Y}IlLQnQT)Zcu|JBO91MKjPW!NresLU zseG;+yIZF7Zb;krqU-C;dXEqI-+?flg4KEm;)Q+Y>?QuO)?0E`IncCx0KxbfX!YaW zQ>HFWbM}|3y}J+N9j5y@=Ml9fU(0vwaR4y(P#}YZ_T-UHh;99~!RTtNEZz8og{Av7 zOO<#UYVAdZBzG#p+VQDR)vTX16Z2bLT{4&S2&pnUFB`1fIRkP&q=$|0$sD-USnnM_ zY{rPpK6$A8E~^AP)q^2f+7axrSn-zkmhENAyHZlMT^2(gDp(l-ZERQ>!O*;8qJSiL z=d4-I3bRzgIW7QaaJJT?$NE7K9sXg19Je)vZXhFDY{viaU;ia2N>nfa-*uS@*q-c5 z6+x#(hOWb>5Ly{$s$$8nMa8)Q_(?d$!yTPG%z4@^CH1q1vJ@_1RI+;sMOd3Y*|O$U zj#h`Tv1Wis^DVKB0dIHu=)13wb+4IJPQ{l`24-u?9iiIaH9emfRE|28^YAgK%fQ~@ zVTMZ1^3ylzfW=lnHaF%*X0dO65zJSPS z^9EYv#^!MaIF%3iTFR{nitC)vEkYx^uysY0>|wL2tC;UCx`H1xW`zao@=kzYRSFOg zo8rtoGrU`5kOdKJwW&BFye?sOt6|Pw(BRzthvEpZ_Mx$A6<9cVDmeW!5!o25LS7CW z)vn#08WbTf>3cpK_Ecmas-u(|ES8iNz`n@AUV#A5RF+Yeyx@KpiBp&g0JX~{;s4;3 z4%*sGwKYC2imb)(ywzj`V#j*huBIq*bTC}yrsizZYy6xI%G@%P<=rx`nF_mVE2rB5 zK)`28ol5Np^62pEIBwg86i1F?uo8GYhqe*qgFPYL{YcBZ4-8h5cm@2u@UGC6HS??i z`n8|{vxQUc@ckE`fBvOJ`;b2aoM^W$JhX!LX7We1oUZz4SX@Sv1H|hPFkZ%=#=n)q zTpAd}g!^wZ+#Pp@UcrK~)v*sdZ#n1=e-#w!_h!6XVXx@uTg!X+gIxcEx7n6U>n$_n z)AOK^%03_pS%2S-8|Xm%A$$hw)*upHp?d-JPwVf8lQ&vnL)&2zfk973x>9?2a{k)^ zJ-m#e10V@xQ(4JKhYxR=aWsa>KZfs3&_Iydu)!Aqx^>c(8r17!*26#97&L@39p)$a zCN|jL|E9URbgn!890^dnT#Di9`@VIV*CFc;Gvh(PF*vUKpn8LbCTwebx+y_^YJRG^ z*&`K|&Co&!Q09OaoDSpJBFpzS=<=97YE{B&$48{IFO3Nn_^{+PmToU#5K9d&d#;{0 z=Z+!jK%=-o)6&F)p-*-MHqOADJq6~hR+WHYK??@JF~?G|Mo<9U?dosKhx62#;uCAY zIIt?}=N9Iit{`=@3L@8F>yZEuBRX)+`GsSF zs-}(2b)E=u4uaeP6ksRSIAH>g(f9F7`Am}<%Kc73SEoetn1JS;nT=7{CpZveKB%<| z$iOl2UDpBFddilHw0lmYFa|vARGv^FhLszfdre>tJ~mQNlV5$Z_rMKh{Fx-_!eSPl z5+vI*UaibwVBY}nqNWQ2@vr6-`q9_BZ|39GXuLnmx%~foIDNtd3$m*+k8j){k$Td$ z*Hu8%c=$qMsA5ABzfp2>J>FUJ-guQEZwnx9jk90e2QKFquHY-wK5;ajZ+Stv&ln+Z zf&5vw`R9bnSi*#30(y@puh?OB9Dm0lE#eirsrJK$uB3e`=wC@8F=gK{-SKW-#`P8*Z#m{U*u?`-Nm?@{@2l0aEkl_&9u&nUc`o(;UJ;NVDnEfona$V(toCV3Nglm4;93fw;PF5Dcwew0sib?#;h1QbtLFZ^6jJea-+1edJo9myH;%F7;`F-$ z!^&7igYZE>BH-6OCR5B8GDePd^Xy#|Ft%YpVpN4#w8u=K+D>;gR6)k->!|pfjs%5= z#vEL~jsX%NYPZJ|nN!>cH9*#+!S#|^un*vC)@0?cR0f`wd)P(zLgl5XKP2Ss3Sdom2t5A9}>6wkaWpu?iJMZNfMwV_|W!ziG6%~k7Yrih^8ZiwHoPeg}wNyykLCEOhrmW>*KnNe>ywqmzS3eo%afQ z9ow*u@C99-Q0$rX7d3&2WB03i;xgysaS5{yzbu*MbPm4o#rzm$(;AiJWZ9`#)RC5Z zrUvO)Y7T?lko&uvw`hDodWwxrElHg2(ZaDKyulF0UFEZuvdk6{l6&ptEb)48kbMby z8e9kOSpXa?fFwCzgamHE9QC|1*;D0>)9^FAFW)cy`m;lbI=b%74vSMdoi1W03uR?> zzJ?C(y`_evc+bszROC`J+cUu-gga=7gb5wy}9#2xy)Rj2VZY`!3;Gf8-X?6uOT3O`^ChGo8d2h4I&LBC)i7CDC7kY zSXjq3vc_-sK%H{abZuwOq=Jh}B(daN=!;d46suswWe&lpec_KYXRhTKKBvL9FR?_| zix)4HIk}W~spB!ncVY2EZh`>oUpd@kZ=xp_@}r1x;?s#dm3@1L(>`2tUS&9+pZ`pu z5Y^he1S`aAKWt{CoI^uHqnuEOGT|cC>y-#dIL2##r{&nM+lNA8YKtS|U5>r&?@xF*gQvmKh6U5&m!^1B?1Iu&X7~%?vJ(Pq#eE8GYn~C|L7L*dg zv`oP5TKYMAcVl$tK#G11D~VLdK1*50m+LSoql{^r)?<~(fZ8j8Bw@y4DMs^i`>IrJ)`wvg3VM)J`r34zw%=QS*5OOeYzACSmrnQrML<*ab z?7rfb2z0v#B1U)y-!hikQdY%h@0A4X93H|-=IFIYKEH}1utxY=ASQWc!TuzF17z<< zZ%o!^XQn-SylBg*0ct0?946&vzaXlCUQgP2xfpcGqFEW=QZX+1h=>%M_9a|?~$EGEH(8!!Qps0Jdid^@@s>` z$s4i-j>=z?14A#}=WSS_msQGgRaVvJ-lnNNv6uKvM5-@mLK|arQtmWe;~Xly*4UNv zY_Ui#<<8a_)@j|$YaT&<@hcD%7pdjZ_za&`1hGWawL-RAMEepMT?EAWj1%RQ!uzi} zseeZCAuhmBidhgAqn{_NWNNOLDf`6(7>j^Jqot>QlO8-yIi2d<0504Hl%V`#t3b*u zeN>;CzD&QdDN zPs5#LY`@~mBc2gcI}2Y(E`sOnb54~M57!=3B3F-g=Tsd%1<6uSceqW@_kKvti_I_5 zC`mku1#NDjQ}Sa!%sNjeL(}C9n}P+gsQCi_$NY=+ls;E1fM9XH-D_`#eZ(^z%r23U z0L$w`S+Uo5fcz4|nVC}pZKGj!+XrVlMPoc7q&rE&jI|K%0^59&8~<^UaBU ztKO%s|LG&%DPY=RG)irEurGap_3b0huadvlsQgPM{>wxG;L=({>?;ZW_1%H~5`X)% zx`7J-Ou%S9-8;}Td)8un8tj4f^>7ZTKU{Z^BEp>t{UE0}6KkT6tzgXAX4n_X?$NUU zL`3j5f`1*7umzs^279dg0iHjEfPo@7@;g~S6ai43V0<1C?qoCr#iIemlawU#AbsNd zZwZmVr>oytY@N>}5LkrjX>2kPM@~L_4q}w25k57P66oPB3buWAcb|U$r;j!Y-mpTq zmoC`u*2+aY8=T2_I1UhDi*&YQ1Oj(sYx4Y4QNYB-xE=eNkx6wGb9&JsL#|eQe1un&zn&czjtR$*-Wj^Qlm0J2k$& z^j%&2YrJP*bfftZ0>n~EAG4?=*(Z|uQzPYFgkrMW*vA*Ieo)vwzfd_R*t!(m8oV*5 z!*>`D9|DDmdmq~K$2$%fGUx#pTgz!AFJg@1KmO+5pZfV9gfRgU^(lzg%Z9~%u%2em zuz&K%AHNYV0gp09f>&{}`YxaRPwV>A0sQchD8GnrHL~Ea@-+I{-rfA^Q$MGO7dp&h z@9;7!`!v!jY-kLpX~{?+3G_#EEQDF?_3}H}_LK3iCVr?S4q^PRdLvpEqKDVaiqo{8 zh#?6fjCz=1IJz=`8z=5qffWm1FkrElIXZFqKXCrfmrP6qNgz4j;1vQD!kiFf`GaW( zA+@*z9vnT%qoXGa8Q`jECi?S9{(VI!X`yg_QvEJRIJ(?8OKzW_{^dx}ByXtD`!}Hi zA<%OCS2F)T_Fw$x1q~F=E?mC-)(_=!OamwG41g6o8CS#6L8M(=^X>J%&-qC);mn30{DSO|3{#v}s&%%(iAKm>> zj3<)2aM>!9<1`G(`;L0|79729`U8mrg%9I(01e0}xbMKmVxO^ng?&Hw{(Xo4^&c}$ zamc_qXT3h6gsB%rynnsBy`&I-3Y6z~s`9s+a5SYE6ALcWURM`~#7v_X3F+YDBDxf~ zP|98htoZo`F|Zcbb0lz4JH_kb5WR<-m?$J_q4gsXPTHPM1%+#v_DtS@qt!Po<#Cx7 zmFo>HH=Hjorh<2|S?J-UJja3KIWM2`E)t1iLtTaAGVQZWU}So}j2`1fwz!p^!i78N zVz6S?B^qEYp6UDkp;8B#JpLJY5~{MzPn7UI?l~1DE{s)What0D@;kzisI0}lXq=`s z1lnFd>|n``%$Dmc$4Pn41D|CSedEzZq6E2k7bGsz!nDA&`AJR8x{#PP8|i}(=#Sr^ zEWx8PW8A=6z^aboq;@ReNtV~^)|BuMVyx_^abawlJkWp`lMHU61f9_mL7b+o2iorc zcB)q%q8Fa&fRpmvp@zag2!v6ZQo_T zT1dE(;iPtO@Fe`^!q91Ckk>W&>whrqAf#4|0U99Gq^>~;FKM*4!)aQ7pzUP7T}3g_ za$c<|oRsHxV0Kdjn1In z_ebIAEA2C~2crHz!v)k!;FHg8JYJ)LYmk}?;^dRlfKOHmPF){Cq8hULahmp7HHg4> zPLS6i{K~@%UQoRce0;~Hb+x!y{9DB#$LdE zmAkIQb6$1Cw6|OdGVrp}1EO^8%#~S9Zs2rP>SoPkQk@&SO!er*6yu{!rej^sr`o z$z>o1(Gz?_fD?;O(E=8=kjmUaGjG={u%ZPoy4ACp#!(Me+DK^HI2&l5tFd;*r@yiq zK*qNkz??k;&CpZByMqYo-RC=dGqcv)AY;pVsk_1p_m`9h3nRs zb|xZ*QWq1TLSeFk><0@D{$aqxY4Bno34C5_FXk6aOao-MhVI_EBq_<_?zvJm^4>Zp zvfGzp;4Cu8?067PCw9e(T8#ZagyTr+TKEp-a(b|?s*n$p%Xc1seN2N+$c~8_%ksz5 zJ2+(<=PO{(>>*XRJq=1nC)Wb1PgI3{PWSpCUb_A&$B&GDi(4z_lQa@_%e?OiE{Yj% ziAa`2Pw|R~@d(=~rTAyed7aXAX=4n_?s<0yjy@AQgHv(_`b0dRWjQ*sYGk(6{oKvC zUX?eaEd#zI{R$pz_j^PYC(0f8&LFdOx;Jt1BIk)t)58s1F%u&yUN-V)U&d_&xYgZq zx~kgL>u{FqzmqKh<9Qiw_>BOW&TLq&IF@saSKeM-FPEq~X6JcQ2nlOARu}JX zpR(_x$`!*&xkK=j{7_Ub3w%5^=PJJ!`cb(g&sPn3ID4$4)BA{rnCk;U*7Nl+DNdWX zwO0(~|DT9qYh(}oEao#|{qh@;u=3e{k>f2p?HYA2XO4tr>#PACEceU8$vZ(qfDYRG zI}fCc2bh@hrnlRz>?k0)t;>_XUXIed2^m1>UpkX&4a)2O|)VAPiRLC?midSD@`&&+s**d_x5%(MF~ zYs4)WQ`nDpR*Vg4<#MPPw`92LZ7)&xZIiA!IYirb#rA+)-G}fPJt6;=Q|Q*5YX1K9 znalU^riF{JiB&-XoWzOQh5Bu# zb`0y^WBQ$X8j?LO{oPx;fr!(&RvagsS@Y7j6oF-n-CfShdyv|>Cox0d~H4A3!` zz_y#&ch4D1EPpg0K3@oRHP*)9bm6+L2knmAV)E))+4}lTU^lyT{`36vwQ7gmk$lMJ ztDK<|`38R3-}$yKqcet_^m+X;-}sp!{QZtzjD2ePuc76X*Pi^>ea-7xwJz?~YPj;PP9ev1btYw$29?-B>li)Aj?QrmZU>EVFfrqay#MX=0T8d>btnH4*gyN@ zciqVWjn?m!`oS#5@09w14Eq1El=|bQH?ymYF!VI-xws;pI|1`1CVl^Dk< zKqnuq?GyU<9k(66i zBXOAJ%=0yJE0Qes=^=JjIMML}UJO}+!cMKqNJN3>`PZK=u2r46y4XSWew(-B7`RK7 zZz;nm3DO9$zk(FKKPxU^(ZD)Flhga$ZlgKpE^;#4 zkzd>}liBB7CI=0(t18$7tUc~e%de}<1w=$Zupjft&R=Aebk=PpVJAl{R*7eX6H(Yw$%e`BMhG0o>Z9 zpG@vD7oBBTc{yJHS)-a-|G_)Ck=%_VhK=na-cmA|p1pY9ixU~-BGhv2KvDKTNuXGSy_QS%VE0;iQ$t>}wmM$7ZB(NAE&stl^gQ2? zFxU3ta}EE5cln^JhHaM!^wl2B9{yAT7zN_AB>LV(r+~KI@83rrN=KO+dX7AD8A;gn zQ0^}BFh4uhl?QIs$ki-xqS!kwaQiE==CCvJw8@i!Jc?g2V?r*ax=C{CLB8vg|(!C-03 zAmAeJ)&rF@Mzc%91~uomzXjwlEL9vArG|evM_~Gk&iy@&&2E6TZcYb_F^tt1+F^$* zSYWrSuZk11{5*GOT@k`qPaTcGMYQ5M5ok%YR!$GoASTt~)#7odxVfF47r8TZ7e7>` zX7Tx^Q%T50;|CgA1Y&ABA+{VrXVDOAX)8cJ(^J(Vb{Z+|sH( z;>#?{6=H4*=*aUCNm^^cIb;fh<>yGrMn%a(R;!v5O{VJVoJ2!*zri%9^h|AJ6xLVS zTLnLw&v^16t-6M0aZ;9MVktU!tC*vlz(V2*%a-4G?woyy+v=E9@pdNP_L8Z>F-f;I zW|6g>CGd2@e?gMa<-YM_e%mM@SU7=I!Sg)N2FmFBph|}j9Q`2D z1E*>_@pxM7W#_Fa(*U;|F%eR-z?t*+hUjBrT2|8Vi<{TUAdjwA5<|7TAkfrO6ou3FA*x)@j3F^Z_qRXw=gtNh)x8|QOXmAo z&|F7gb=$OVoBw_+6qS(8ij0MpMByZW5Y=}=dn+g3P5{4hn|pC&7N%QK?0B*R}LZv92YW~$$u?ndz=vF=(bPm1!x#yU7{ zOo|n2b~n9Tukr}&XefDGI-}J<5aXasZF<53!m?~e(S?(l)1!ST`tt-8?bh+?oQHZv z4RMuSU!l!fkz8GE=RGCN8fb&I@}%TF&!BB}wbz zG_AcBwu5ovcL(F&=)~_1#)F-ues?e)$kB=a?qK}I-Tyhses?e)OznO{d;GZ!{hBgG z{D$^8SY+`V+T&NT`BNqQ4efETgXnK)kAtb*Z)lGLson1qi-W1%|ERM!dV&U^9E@kcgwK zl!PjN;<1F*Ds#&zisg?tL9OqZ0{%+VQ9Z%O zJgQ7nOZ~S3Y*>(@_*a8*O3y>n00fbU#C4Ws{I~r$fe4AmAH`-r`@|l|&(bCEt@n!v zzT92POR28`3AO*hascVd6W4gFo-+%{#`6#^_N=S;sYI5{$;$N0oc4A1^a#CC%jriuB0*2s6Vtu;0*sH zH5{!3k0cL=HBbau9MI4J`^z)Ty6 zFv7yM{jUNrf$fUylIhgRf?KZYq!P8YPB!&PFGuyCxj}FvcjKzwE-M_p894JVsvqPJ zXfT#DWg6Ll-S_x?m`-$cnqs`%))>!7hs{3NjyX&XJ)Oq!;QgVrSou)KUywd0L~TFLJAW>LAvh2e<#V%;iAB(Fw^?=-;w z@LQ7dnd>w2*7|lg%!Nb0fETEm;5Xm<&v>VQ1!>yoS4&QZZ0UJ%?`4$f_}w_I^X$yV zE!I|UJ}VnXQx^PT_9vaEvG1V9ajD`&MAJ4B=!LF0V^PwXL)1Q2{O)%|i3!4}vRe5$ z0{QV1+G>sV;(PzqGXHC1H?9Ma?Z?mX6IAex1aMx~A-oirI8;bl)d$7ta~^l-*h2_q zC=3#Fic11b{q}g!e}gWZ5G-Ak&t0Fu?%~^=bN`(^U~zz@)&B>3;8>GDQ@JS=oYbvGh}4I`b)C7q5jGKTEz5WNV}sXv8#{V!(k`^)hf!j>6Hj;7%nMK*-$_mN`S zFK}a=hN90#uFeK#Dffzz4sPn))#M4!!B1!!wKP=5RcwKLoX)MsPk7?CGvj}&@N*^9 zA&BH+@SLaegJWvhYpf8xZ0lnozd~{!j7A)W0LGk+w7iO32I}he$xa_)BN3WOYAm(KDs&hy?m;`)D`rVla9uzW-=KA6b-UCd^*z5I01mdP~;iL3(nl z1XSoA*U^2@{|B&+)A-<>2u~hR5y9z>1nTXR?1OydkU-edBdvsgGCyQ7<*xb-OJ=`U zDp^?ZZvo;zkfr*ejiOxDMG$wxC@x5arRO)Hm~OXM9Urx$+Gj0ZPTz|oz5l$udr|Zu z%-*F&^7Gy|X8gkAKb5ig(*#)N58m=BuHQASR?8`=zMksPl-`r6ak4MHtmrXANz(n( zkgBA9&ap>0n^Q$fJYhYkP`t7FXQC%W20$Oq=+-1AG{9P<)M>900+{vHvFN>TcsK~z zZ*KvZ_Ce28HrKnr?lgXSdk_KJJ8)we00_7B^nDS-B!MO!?f^3e zC~vHOsmW$n*F-)2P9zOi`EC1YF}Xf#{pb_8n9kb)(1&a-z@$Uhp2%XYjc}^CUn4J- zUeAS#+@<1|1`?cFqCTr(H*ruAW#blymK%!*p2R*OeiH9QMOPs)4fmH5LS&MTdtXoS z*Nk$+%4bDm%$N|M7J^X%R*+~it3D8r;DnsGAcKo7N6fH`LtVFe?CxTpLg3?_2us)U z8%Rgd2qDNa{(2SrzQq`L!i)Xi2sP{dy?_*;XR^+{&M8E)r za-U#TsKH7geBX-&|B~X=02JSTp}!mZwn*`KYJv-nIrnI|XVf2?4xLN(VHlnneZ|f;c(?MhkB-j%|W9 zgj1y{r##--oXU9_5<*q6>Q8pEn}5iY-pyc;4gwEf6Mnb-=WF@5SrIdQil-#dlN}j4 zA@2isI^0E^vUe7n`26&>936{`tOj}~yE07a`K<~GNNBsKtSb$5itlsU#~ELlu9&Ot z%r}t}-p;MRzq7fr+7NEg8~Q24GKA#F8J!}FuHv16ZPl{bp{FMbDzeyl@Z_XUiIrZ)IA-+6*ya-5dJ{5 za%^kn?<)~j%)LB95VjPyDKD_I+?IvdBAuJ49;fBgzu#89UU#?oRamE!U2J{s03fJj)yYLm-U(!nLTrvL|jAPPsnXY;3vpMhaSNtS`m&B z@0CCs1&efM*USoKC?@!PIC1gr)2cPh7Eyv#d0sflQD(i{QE*hfKbe!n$Qy!UOAEgi zx80pJog{xU64GXekpT+UYu#dETbZ@RQrt|;f?v(s(Y{II$oUEj_|>&xd96(V`x-D}*-21a~xExNLvWXU-it_?Vq z=vY^EkX!Y(&*dA|AFbGa%uPH{l@#?Mj&-TDRE2$Oreuhik-27M{d;i9RCd)BPY1*r zvC~jnjTd5NLg*)Za(I7ijK{4Rwg-!1x~~PER2%MnUp4PjQ!`NRP{8c9`N?{&wfgt_lAIf*aXQtFZFN19J~BOu1)U)>FH|j zRaCaxza2lHBoj5pc;oOEIiv6^&u8(L3B0y(Q)a2?-0Di~x!>9exp5Hh`G=VqRe-%L zY;J5(r}~jB_qJlT%fOl#E|ZZ9D}0}BRB(f(Zj=|5;jQ2N>ax)kH8hsrI@T-hGqWG& zsMvb^%#2WcI(3@*2NQ?RtT7>`0IvJ;h86mfwU^4X1ticlg%)&Eb?HW&0-5s#W7Kuu z$}xofl{NNy8Q(LKNO-yM8O>KFJBnSF?)F*aRNdK{iioMO&ofX#J7&q(5qGHv;j@vD zz`031!z<_j=?x4BGc(nAG_PLD5gwGv+H267Mux-}PaMdhjDxziSWlMFr|7%_| zUNN;@x4EL80@JP0`SEyP@_fu%|94>t?zEFP^pa`Napw$uL^j%03>~Vw0{qEW)=U~6 z(>Qvp&2AJgyf(&f-*B0K#!_wJD)8;~t*D#3iE&1jQBy+0LorT#_1!ZIt`Sqnq4Cwe zoj2pHan`}*+0MaI1Nk7Ax1%E|QZ;&nfND^KEt^dklE z_hDRWi;|D2kW5oTcQmqfdjhJM9~i##+L;(p2dfmVC+|Qn&&1LXw5C6^G3*#Q;OT3vD1$86DkGRu%lVpN( zqeMg;Gw0A-!^3Z{SoRinZ=&JoOCk@xNzretfB$leC;XW=e3CdLWBJ4vr}{45d4|b{ ztUW-4+FoVxU! zdc3MJLPM){gZ)$GGfd94hpSblQh41@8hlyO|58>k_nATL+MG-&)M%!+$Rl7-1GCCs zF}%IBldI~B3Oso^U*ZVirUwZLSHQCrcs?Uvb$49b+%QIJJR_)9=$gBTsBQ8aqXN9q za9!7X+hcfhNpJQ2Dmxx&>!o(M2q-}}H^yU^Sj?K|tXtrE6@6vAUFl%ll5+BP877xx z4`AyYlSqQj=&(&hOfJz@5x$wF&sNZD1pZ>KBE(=^DB(jF25YgR!e=_

fyvaz$L)@E-8Z8S6+ z0Ygbp>__9OztW$+d;(=xala=&S8z3bD`k!>azfvs{0F6+eM@dV)=z=;mITuC`>V;; zOcGK?^?O=8iEu)j8ECGH_JpWqX?HkPVOYN25{mR#kqq3Nt@fA`+F^Hf3=zDxeH^?! z@zlN-nEp+G@sN(g5nAq9fAorZJIB_K5CtA#?!Kd>r9;fZN>JC(Dcy?kShr1aAq-f9qR@-~qiPd$mW>d8-WXeFr@oxLxLS^thVUNPCoJ(CTq-1Mb31{hLhzc(+st{ zWrbTH-L0uWP@pTL!@1V&X6}s*Tx`jrc2-LtRn{P z6V&&KpqA#N`h>F>WEn&v`(~M&s%roTTjb%`I*+MZE+fXE1CCVCexCF^0^1b zZw`qW@)A$-ZdpaH)RcH3Y#v;K?7pK?=ni1^_z@g}R#@ILc{(+=Gw3!qO8=$CgjHZhB9|8h{g;zDFV%N$vOt+`{YkYOrMeO^!cD6q@%M7U`WLKB&Ga+ot=3!+grQGRjZU!oVG*}^zCUCMF&M= zNKw@uHP=vts-x5tQ>Y?oji*kNFl|QoAFMB`x+28Nyc~^nHFx3858@!EnDZ ztlwzi(STR>nLuj?b=;!D(|r!P4K(S;&8|`5oc8gAaNJp#0fVWelF#l)w#XN@A%{fi zJ3ifTk-lQ7UXsZgy_k4Yhh2*FjBA_<6Q&9DreY3 zIppVfOf8*5N5Qq=_%nfmikeJry!i4=Ui$E#ty0Ud*C{IAo(fjDm2MMtgSym_lmJOY zVL)0{z}i4{8EnDskk5b&NZazYwMZI#@BDWtzo^hR)+HS5)S5Nv{-JSiB`%5IX&o`u zIOZ8o337}zkF&_5)P?aFr}tpwpi>~#tLkeLrsR0Az%b(sNHtCJ7@oE4dvAGacgQr! zhW2{G@X#MT-X7$_)Air$QBxmXXH$ddomEColPUI$N#T24RXw$4GS=Om<)_TajA;<4 z%_?ZhElOr33S|Faj#`!A-BwlTvu32kSJ$hRkeP;9ew&RmNv)2PkBUgpX1cY13!qCI zei&T34VrYOag0qkI~F#;A^4q_l1(cx2}tk56cO6yvz()pHWpj|L?%RsoB+-eL_A3j z8c=J^U^}prvqg}_!Z6T>>}9d}I=wW1`ef#*OVEvQ6oH&1IMizHF%Qx6u};mEHNzCnmc7&HQ?4O zDYYY9BAYd29z)djOkR072@|WJvUV~x z3Iuxx=kzFr+Eut)ZgJ}OynvkZM_mKDMS(=6Bj#Tnz1@5$_TMtmX%r00dxSVdUezb6 z?tQ&4r(T0v+YJne%ii%p3?9$nA~0n+zo1z~?!zF*BuH=!zY}v`6|EHue8k8TozW9z zkR|jf``uRPu2YH{ypoKyv%^?nLmO-|myHwcPYB>yyvGnQko&-T6@86SXkT5rGgIC- z`x~Xi{yBNQ>t_!Mi<_^YIC5aG2P)Q|QeHvCUs~m{WNABlEjtZ2x?kWNE7}nGR#g+G zn}-^1fY!*2d;Z&7^gZu%{8;EoPO#bQYU5N0(k(P^T{x0_t5ZL9Chu;lyM&r&@dl1n zG6f|g`p5}F0rrRoY0OHsK%MPMui0q9rwJjsF3C^%62w65%uKi<~(Oq?NB&?>N28AWy zsxYjvLg5Ns>gLOt>OM|z^H&X z)2`gjsn)xuhb1VXJ#yYC`JL%g(zEB}3z)xln1pf%znPq4t-le?pSPURi~a&Z%d1P$ zjjCPRKagorYL-2(T_E7h=Iwas?i1n^6BFikxlo{p*^7>+_%phWW42jCuIXNk^q@4y z_&_Ji;>)tKvhWO$05c zW(@pld+o`Ba0@MP5WlGpM z#HxO|O9Kg8KdBu@aP093QQ_Mu)gWVnTYHf)l74^EdWzDaUjT23^-okPc~)e#R?m>q zn9hjs#DqL*4lS>Pr)!f7?_ZT3tEIj&BSGKk)@@#nfItn15+1-}BSryR3gnHNET=|Q9VD0S9(Sc>OAT_gz zVFwj9)sG-;dO9Rh-rHw}MlI{feJYYJo8ApuXyjcB{)~Ad_O=5sUVpq3i}=skCEsi> zw}PP-AFUEA;O?+Z&zJ(^4BbPy)E5j6|JAeLGMLupq5fgbEM_DV*X&o`-+7M~E3#st z)~8TJkgvQ>lL-J+E7r9;jhye)Ja{=-?`o8vhLX)1L;?G{ z7>Wy=8z$%YyLyb)RMVwULgl6S_!&+3%q&a!%g(Vw)H^r~yV$9@i8;v9!ujI}Ck*Bt zr*A6exq)T|jlFefe^IO8^AR{OjUgBCtKj$_wUoLSOuTbK1#P4ZC)ms!CSqd)H`%=v zn0d{@u%_zrP~SY`-1z1maZZy!o!-LAOrO_ShE9)>Xjq*xexYfwl61@g))zweGxQ9z zQRft)DoBbNPrCr=S&yt0g2gO;uahswF07pgan-5J$AEaHe4YtqvBc&HxZ$S`aTZSA zOuizLf9T9|7FQ`j&OpQ5AcE9Q?COW>Lt0p3ZJk$57kZjlM>2ub&(tWg0vxn7e7q?N=RdDvM+hjm1{`bsQH1?GP30(Q<~Ic7ueqi@2HoP$ zs?sQn^4{$+7d8hciHtcA1F?wOrMBs*&xwW*zSQY2Oz&;LU?fWwGwky%Qk^CghOeuM zka6wFyK95aLedYd#cUBwxjY*XMW;I7v`9CPKON^# zJB(`+$aSZaW;l82$R%)Ch0;*3f53=u>(IQNr1LcoN-5eBz3ytLvufJ2bt0U^e?#G& zq~jSrEvKd ztllW7vF$^@Pbk&+01;*3(Qd*7fP&>dsQexLbKs8lKy37jet>TImXMi*u4xV;kK$joND`iyRG ztO0vQWSRtS`Md;N*es&hau5hf{M_);Tu4{Jb7N(eB_Hs~CxDeAKbVT(ygd!Ts)GH@DSj2o<4VSCkY(dM@ov%r4NvbP^*0&#oiZu35* zB{uW)SUQhfT>|XJ#$>)3`k$SRd66D88XO4Vt}R?AK@H&3iS3&f6s(SbEshY0SL>^XGz$%)_gppc`{6f~2gSfi&VBZ7j_iVW5mY!IOzX zz}_i;XJtv!)COeAwd3@T3dKuheRDxvv|>E8ft9fZg|~b? z_Q7M%O>FmTqC+Xg5e35t+{=!JHYst+1=kc`XDErTKR_386BfE1F$Z;!klMv#k4$!|(}jEh)`kc&LqTrynY z;R@CWSb&RMnPcmc_^-EEPrGAQ`8B))X$58H&FGv2mi7blq-jEMjz3Xw292!L2A%fW~gQbng958G@LlhOn!1*#z{uH~B@2 ztgW>}IEk6I70wdHng{(fkPhot&YQ?T9O+u1-faij8f8HEq&Y=87_6l zNF&`$@a!J+&Kixnc8$xel2?cio^w+%RD3HA1#sEz@1Odmw@C7~!Q|0k4!B-&C%d7BV1fA&L2~-U-IG`4J%`FD0ayV;fFg7n(w}?x zl9|Tg*og|_NX)TnWavrBxvbwMccpl!nPM%sW~_gA6$y# zyq$MRI%>DNK}E=WSVi;*%Jb*#eF(Ij6afAQWp-@EJ$4*C93lM@Rz!HoLRJM9@n2I& zlHhI-@BfZSurm6j-t$2T#!Sp3NFRxeZ{V*};3|rp=N{dfO2Gy%Pw5{G;taV;(~UL_ zK-^?kQ&``C7VP~6E^3Y;NMrS##r9h7FS@KFCe_6pDRwKbfat|y?Xay)|MSbPb~@9< z5usm_2@J#c`NY!jNdjn5XWC88kEg7a&>i4}7=E00pP_(TNOAO|+Z9cQ!L>HNoZM|a zW%%LZVmC5tM~^c*EyUFZ;ll<;1z&i86Wm<9)_~~f?&?~@02JPUVB(=w_7_=58iL0vOpjPOGHF;3JG(6%HuNAdy7f z(0wD;ZO=RE268~;TQd59DV@|X=9BZ7RID0tk4wDRRRx1*jelQ+*L!tOBEAe%3cC+1 z9Tw7j;264*BkG(ZSg8k)Cb0FuSI#gC7w6U2S6={|DX{DKC7_z2`1HL$e?2?fhuZB^HrR`d@8Q=> z2;KIrms2mex(vA0Q(!4OHmX}Ikfg&q1SBUc>%Dag*(1}7T1lSy5w}B__HE8Mxw~$_ zB4blf7-_NTn4=UTV@e3M9^shRyc0K`TNOT9ngd}H|`dLIO;e)np0^ZevetJJnf; zUfV=vK5!V?Sg^%QrBvwg1oe+?wfdAcn#HyXiuFc{HEYmphT{<&oBk&S;A{Ja)CwZQf4J^k6H)LG3oV-EfT8iuOMgY z576)Oe6V*>T?I1b;dSW!nqkY!)6V?4%wRm4_5N=lQMqm!MA(-EUunP;cCV%SAar_6 ztLhtSpw6^a>p&d@;_Pnd(jWDzn(!C8T~2h;haRQ zm%H^e;SlK>JnNQ=I&RoFHl}+NQ&i_(RJ%)nR%vIOS-;u?e$8E{F;jjxok_@Gh1?mR zc72RA(RiRJn|#e<(~G)!6~VkGF-wqx zV{|WBP5^3a???Dc{zUXCtN8gJRKV6g)G>fwfZOwV#O$O6Pn`z-!Do+8?_rT^D&hmo zXLqB712Kr-0(~lXT6!m^8Zb>76jK}lN}Yi|eYr@$a4O6`1szc=1VW}(QGjP)YjuvL z(HvcUK@4qNl1VOdgsb7Vr08EYV68v2;mOv%YsXVxQL0&Hvb1&cg|+)Z-Ij@j8%5lB z`6#NLWLWvUc&N$VE)uqq0C=F~Vx}+X&E6nS+k{7b7^k8!g15B^vq)Xl7QbytVf2`2 zi3pf@5Yx&QUdm@kgqP%iBgxe!LC+cOO2oTy#|-@?b{CpeANPJ9T=U||6w+L{VIe!` zV>EpE>8lh~uO&+Q1wO@eA}v9wKT5-v|E&QuW;j==jYGt>Wl98yNzZLdk@X#~)e!}< z4N#v-fZUSYSI6F{-l?Q+CtS;Nz*rYm9y)wo zhOA>eb^w@BaeeY%e5qGXYaFBqPJDfX%`5Q8#0v)WjO;g_0B6G3Vw$+tu=e^`MC5D! zq%=T^^Khpy`7|34FRUn2>x3Um?QS8w5o4cQ!EBDcuvi;H>>=XtNQ09UnvYqZ9*vHI_I z>HL})h(oAvU4!ctQ6?YuwT~BQ`qhVvACw)vci8ymppJNNf%X}QC?i;aVT_;)4=T@o zG))|%de>Im;QcXJ0PqLUMVkj<_Ji7Ha^DKO zItXM_X5e-ys~^{$#D2lulPG$kiCk86UB9_*T>Z+EnViHq0K6Z=@YhrVg$<7hNQXhu z9VplR%}%wocLG_M?9g)CRG)Cz1mq@$P>maa-XeUB@oiMEJG(u}7Vp=w<6PQpJw2=z z;7X~6*KJJs;6sb}FH18B%M_et`|k28Wz_1hLkCL}x;s}j2bApM=CY;pR|07@LO@uA za_+YH?{ZLKoTc?=PdpjFiSp^nKK~;8pEpq5cmNXd@vSxlb$wh4cmcHQU%r=LtRE)| zFeE+dwCM;-m>k>4!w~Z^3}drGAQs^Z^^59>brgXjj>}*mH29G{SinqYe-S&#OedbQsVI0Fb&GDCTwc-<97E~I>^GI0gcke}idrYrlc}0to2qZ~yA`;KV`Z zE)evscmx#GPV@N=cs12llk=jHqwxBjE^4jcWa1Cr1*yM9(eqMK89o^K$ESmI-d_mf zu2z~3rEd>eY*v4q{4E)Fk#A0w{5a|T>a9n&T6|v|EfxIt=s6#|Z_j&;kbl`{ir7rls)XvSS&42`8g=;N+&}aDE*e15Epk>QjTCJWi)S zdh}Csuig8)vhvoCxZ~fuu4waNcluA;I!)WHoWFXt%w>O?Y;*rX))xeTCRmruj_U^@ z*yf-?W>+zJXKUUg8e3v-H#3TQ`~f>wPt3sXaDte&RZ2F8C)z9ED#8UEBjnZ6$HWtgFtAb7-+y9>Kwi+5C|*R zMp9BmR#K8m#o5u)#?Ar+dj2*p0bN~f{eIxJ&yeI(c?|NWj;~yipJQgcVI!BKqeXg( zNsTXM7sdiJmX<=bTgwl8RiJ8KLjBJEh5A-4Rd`q_8709< zdO8XbO>?Go9qn9SYrUA?E2{>9sWBLKORLv0(w-g?YSH$gfhz9qZL)R~DLOHHQ|DBr z`gS*4z$Qc{TfpS=fUyw0$j3Jvgf@Xc7Q$jdR0H?KMMINbFHzUf*fB0)zQzd0cUM&I zpQrXEGclt@+xw8c&wc+YhGE@NkRVe~FqxLI|B#E-Q&}SZ$@{X4Ymvxn)^(eh2~nJT zbadf-dAkrA)h|tY^{lOnxl;&Yd3TFU?7; zy|KM`X%_zRTH`F?+)uN7=-%n{=&XdT9>--qdw$vJTgek(=EdA@jRBc>Xlsr1R!o^StY9~AdPstHy*yLmhkws|0rRBIp}ax{Z7sPwdE zLhXGqmsEG_tIQ=kA%YqcUm?AYicd0CmF1P_#v6@&^>{lrLnruO43Z8A?U0*W-JP9F z{rVnKp*J&TqWx@6?jOelP3VJQb}Mo}1i2g6>s}*CQK9F839XStjd6N{c#F~dn#nzp z#PM;yN#JNBS5pyZ(!{Z&Ft_NcpvpCC7Ne-YYM2KJAV&rfq~9qI#-8V@#&ZZV+T;HPcZL4y>Crdj>i-vmmy~@ zu8w_)lM=!P*2g^&L_1_fRVktlZCj$Q^bX)@o{_O;d<6`j9kOu?5!b@MF7;&$Qpnrx<0NlMFBC z9ryQ|`BzS4`g|~qDr}Dj9(W$4{9)&>6IvjP(7oAT+V%KGf$Z&L3;jPG7ejXmP`zFu zwYGLse-eWqGx#;;7vzDkwWl}?+4y7knZs~@$p2vYal*yLRm&C0g>8Y# zb;?D^)ouanIPCVNXN*yhWl<%QeLATiq#&g1{oGrbJ{Grgdr8}w&x^Yz-uJ^r#D#49 zV+eJ3{BkGk12o1yzJc}pStOMeRr^Q1#|aEtY#yrH+0$Vn60<6)bp0QUSdHicbgvpO zJ|RoD$Wd!k8<>23n(|HKO~N|?X-R2z=~UB1Q!zam)GfJm`&X%g!38ge$?f2O6J1n7HFkyGTEh zespAxD#$IUF4)z0r$M6Ot!H1$Cm+~r*$25N z9t$G0T_R@w-WtlX>AF&nZy z7#;12cdTna4kB-5gF7@BgwF8$p!<~g1z#2iH%it^R($tEi@W!2yrcSOnA71){l)R^ zUlX0Pj8p5chtm31`tthR`q&>nVx4Cfs5Wkv9(%J`I+xWSw@tEB+h5VI*#3S|bMbiE zpg(2Rzr!!g=9_{Eg+=3D@gcqsk5@!lvUY*?s_2VUvDDVo8N+vm_YC6<`|I5rV(T{> zWc;>#HGd_awEj9fcQ|P1A2oNGsMvZTj^3oj6Y^k})XTDYdjYrCFnmSgUX zQ5U70t1OG6Z{ku+xu}i61Z$0mmsIn8b*$O!U)fuV#LBozqRB#uL~)~^B9)_*#aY!K zWMc_)mvcFDdrMh=S4}=FBPJX6#@mkN$+r;@zb`&P|{us!UQ!0)8eJs zgcA#*nR^;ard>}%mLXqod(c7_inR3rm&)_L?HTIc5Ug7fA zaheDvm-o+2GEh~DQ{>3ff3I?rf)TGxs*7Q>6)r6=!=2Fb{PWkynou`I0 zeD;w)_Mc!FKQV6Vzgi*r{&^o|97Pb_kSs!E{D@#NXHwEOR1VKim_=mTgZA*b6;#sR zKIPd=ymz&ss<bQbfPfSiGtfmDe&Ip5(6 z4cn(s|0ZwTlDfto3KYcZ3i^!|G$7ouIsko~Qf1{%lRj!IuM? zhcRq8t}F;oU(U0iGktGTW)d#g4QjUhPE8+{ZB7#=Fe9{5V5yC5)uYZcSKbG>b)}Pc*dhRH4*XPPJPLYf19CMNpmMt5c*ajKc!+Y|w{-{Y0~ zn0&W+`1ylvJY!PQyuQB1A(yj{#vj<@{n*ro3%+%uUq>erU$MJg553AOtej6fHZpg) zQ|!a^H4!jf-&ttOS}H1nn1E{x5GoQ0=nim&1iZwMNdN2l8PXFF%J2KgAW*0c2=(tX zO2FsMUo`N#8T028B_;%f4*Yi?czLEH|Kn+Fa5~CAuF*z;??4i2lCrYEr<$3wg@uEQ zwWDi*eV8C{1M}r`9TyOYi0Z|bLgi_1=inmbDf;;L6GFiC&29F_RKFi_g@``ZR#c&qbab|$;$!1r<9IBF zMMXs=;%sgyq$>67?{MHh(Z|-Vt}lhy**!cw*gUw|9G$J$IRym;**Un_xwu$?Csi(!ed z{}%|{vnGf7jJ_a*`jl%hJ3#dcG@)f~R~iq{HS->izQxubd55*# z!q-7x_`0zBLVRv@UwE4>!6{){ZZ=BMfAjP*b@k+oPUcD4c^jQc4=Dk{v72rnBP-}6(M^^88RoS_;tVfM0n>BE^ZSHnkQQT zEr_k1)Xgg>N;qq~Yh#U15XOgnsUQhLLd6IFdv8H7TH~j1)8H=4#E&1%#bbK81nHzz zV`Ay(cq@cDm(My5eMYP6cPAl58s#H7ib&RK2*I*JMB_MW3Ofu2+csko5BFEs)SR?P z!IT*KcUS+t-=KKZ7{y-`>H+aRJqmThN9E<^ZuF1*94)=i8nT&OE#y}>OEgj7p_FdJ zNJqT9QHjL|@X}H)Mn=Ya1g{(rwPZ5?-jV+TN%sNAf>mdCcWiPp8Lsq0x~%N0_4ita zi6euuy=du<^?PlZ{f)nVu6*9ufGDg@RQO+d=M@z>uIrNhCvZkWeMOlyu8dn`0$~;w6t_b>^$nfjnJFZQ9TGM zEM)2I?@vhH+OnCLn6Oev6KfFKy`V?3hF*wR^(E)gWo0oG=~gfmi%73mNR$T~UwNBd6~47$2JlZ~Pfy*ge= za-5x?YG()ebx?HY(*#-PHN52C(vr#r>~HbCjSD-qZCoitEvw;82Kr^I;~N=Qgp zl1ynv^Y2QF-{>*CK`60+aq~!-WpAy4$0X?R$6EsK@Oaj9i-^A)n3)Ua_ zIML3#*CFikNfNTMvYdE?vtQj-5`wLfWo2bmRkS_Z(95jE?NQ)$TeX|Qt*x!-A@0Q9 zH1N|q&WiJb-(RO;3VU2x^^!jZz-Azw{sT1wQ_>?Yr`PZ1#w{o}MV_k3W5;8qFU6;L zGd&ou>#8Q#TGGv}BIk$wYOV4%T2L`6&#x^#gkWL#%lm(i#RA3`iloF-yDg(*Fh$45 zuTTgWgB{0;0xmZ%<1hESx6&KN-+~_!z~%b=_7CdD4P5Ge@7F*lkjhod|7=?LHv7k* ziuOdlBN?)_GwHRO!mih3@_ptlzn^6UxE)L7sK!jRhU8`%@J|fWUqIArQogo5#J5vaYr4ptot=)=SRr_qlhem| z2AiWbdZ;46CQs%59JARd5Wl<$UGEl@@cR)bhTRIZ^n_0~xZ!nqoYbg~S-`&pzcuSq z{1%%gcSZ>xhEE}s#!tC#E4hM{Sc}zB;F~?HD;^tDODp&ok2yTy=~O-wZ~hV}Q?YL= z7S*j)W0*{kDK6NNkGng(eS(t#^)VgzX!Uugv%!tH3+j8UqN>Z3wGw=5%LAN@`Oz9w zJE*`!(?{RtiXWB>8cCz+>TdmwW1+VojdbD8;3dA>Z7`^hP6djz7SiXYJdKOYiY@i^ z%tg}qbG6Hvti3yBo@{^Y*|1%nvRny)e11_}=4WTwJf;uB`))CYjk@}7ysXNfzy871 z4{#t8oD*#I{FYKYNb?Q`xJphcw2vOYbEDsFeI~Ph^+{eI`4e2&64aHgY_dlWS05Kx zs8+R(W@9;z^%rkb?Gujj`>oyW| z(j7q8YH2x*J^mg|h`ntmnwy9OOSd$5zL4IyY zeHfaK+IoDJ1>wFyCsATmhE(H}J_*4Id5A^l>wy__JCkf2%4q6KZ|`rV5dPtgpBftb zi2k_!)(h7C-obaDde}XZ$ksXOWt>ATgSgS)(2(#_jP9wION-cGbPRoVbD4dBh^a@-R)^7q5Ij}XyIJq&M4h4P zLi`Y=r_Kty;qtnrI6r*`=|fpJhxL*zN!ffQUyrmT^9pigFR$#+o_-B>6QxrAQDx9p}>BkeJj zSA^ErWoui)v>A*X-YIF!7(6rYb_^IXz)OKk)>_afosO@2CZx7QR;-XqE#lm`4i0+v z+maQzJWRZn(&~vb&U4AutE|{N=b$;677SDPj*>C*F~dD%TJo(!N0VJ7I#w%{$FaDj zHWEM4oP}9HDIZx#v5(_w4@IO)wFAVw*=yE{4SFiu3v08ViG6N*>Tg)5Q#z<-9`zyE zTzihfP!Csv(y7}eJAcK}MQJzwCtKXM^iFs|2AgLn$H{i_cf3+Wp-RNrT#Gl!N{RME0Ol~pZU!3IWp{vIqR_m0fDgPO~3oMU~auBy*y0|q!HXuKo>FVm;p#te?f5mj?+bN=U0gX>;Lf11@)AK0mweYDR`gO=F!#X-u%&VnAuanY=oAJWLG4Y)U2c27$VkW`6q*J)=rRJCkH>63bbDT#ewQg%{A+q7x0 z_y2O2V*l*0&hkE=g0K4>Z(Qk5gj=cUsL&MefEX?XPp)LP{-~8t-j-nL-o(4DvP}%H zrLDP1NWu8<-Nra{!_%~naY@ky+Z>9NM-;*iG#;t$frnk3+u6N3<*I%4n|DaX#t`Mh z-g$Y7`*uE!JhYJS$enCg5_dhcllbg)!^Z}(zLOODUF@|d9iERhUC{x$d%u$*tt0rZ z*!Yqst-D>-jC)LcJbiZpdlmK1=Me(~VL~Qy`_~(4fhDT0A zr?9cHmn)|n${3~r2ZPITR;14VXhf^K+G%m?%qq>#QWCCMM3N#Z8HyK2A?n?ct(cUV zoBKp4mnj*1oJa|_rD#BrMqC$nuE>?7lN0!>_g-}qhZ@~jiI{6 zZe(T5vM5>)FL{aDsFj&=XP$NDjPMM1f5lGdB#@6k-$GQ6l-=E7UL_yV8jKM|5gwWl zdX<=!Tbza`J zr72(5uJEEjlG#DhKA6SNCXU6&t>UC!N@qO`Y26{?fp zpQYR%lbGg92_9UtBf304{+Iw0YB}Uz@HF$Aye#Tionx)I^msDUPt*mw{6bZg4=UZDSW&1%osSLXZ-$ea(J+vVA2 zQ59ij%7HBeA}zVBqoWg(3hSR4l9QKTuHA&i{`_fbmGFQF?JhWqOi&e8zb^;4$_aXo z4ZPVcX1I+f8zb_3cH>m5X#tHM+l7F+dXCD|Qvii(L`Wj$QYY>OIz&;d-qNDSa4iRa zyOSP8$pvPca<9&`J)XG8=`~ln{8n50-QrswF8x|zhAb(#l3dX!X@hV8|4>w%^~1w> zH#<7O`So4KyrdJQn~2ccN&G}SMWiuWv+>Kl3iCdHNR_DCP;sT;N(~*sD_DYXnh|S% zLzN*w-K3tzl*C^9#^ zdQG~uNDOeo(VPy`0Tvln&04ilciP?A35U7M4KlBb3gw3OO4yTpnzb1FkmI=28l6&; zA=^$@XuQ3*Mn~?f1{bX8bZs>cquw-JKGM&-TwOg&t}UBx&>k_S$3E7_%K#GfIkszJ z>Yu6eNWdhZ?~r9krCldZP2UDE$f%a1bQJjHEBko>HqUBgH%e& zXqlCA&3blHrpL~#``Fph=JG3SwwHMPq=CooVZnsRaHn1TPfv3Q;2Z}|?c`QFo2?Ix z?08YhZLg1C0ca|sTD`3U>zWCEdMDju;{(H36gjnIS($=y73bmfC(cppy!W5@U;fY=xXUE`i&R9rQPP?`lGj2J)`f7=vR8bl1^{q`vd}>Ro zSBzWMDz);ls~K2Rd4NqCGUNO`w%cO+OJv@~l$m;D#F<%!`TB*3ZmI%|SmFB^iL1N& z=3rkFCk6tlIU`^-1JhrOr=&dBkt6yzF(vm}8G#Gtr_JgLxfhybm0;&k)$;na+H!1N zUwm=|&#BF_x8Sj3znou+|BK1*hA|Q4y2Qf;`p*tw<&MRuep@)5?MpTtXZ}rUm zo$@gy#yZ-V5|TL^R7UN(j(u52#$=16i;{{SDho{dEO2Oj#s&)~bOS-BPzvwoF|o09 z9Ox}{CQN@q|KZM+3NzTs%4$lko0Q+-(C{mi`SkQu zRYSvqnXl@IEGJFVW3<^NMl*+Bacs`-#9*~}Zof}>=VMDS`jnrRkzYmC7Z($gT`agi zLsfBx*$HAwtGw3L%WJKOTquVZGWuNcJ)`uT0u5*e2dD0yb!ebtx(@r0Du&R zxjfYLOM&s*7$-OOOIXPb#*3!>Uz0(Yz>rT~5W8Uvz7R$Gu(5cp(cKJ9j!FYj2}5ke zx`|8UO1hz0+y032rbqbJz_EYrUb%$xg`@Z9?oS&-LXF%-Z6&T>*sQkw+e!FcO()wg ztajk9-=|$0f1T!WllIB6?5Fe_RUx)!Qa_(DkKxEjCzhfe*=i{}Xs1cCyiMIDn z=zdP%KAL`DP2fuL36lR|Q)flZ0^0G-O_nP_vX(_VjXHePs&ij)#vCy25HDMi7;};ze-FVu=xax~cb8gpFD)k+9d8y~ zdd&HGI4&=Tv(-ND6TkK)7W1vn%*eA{Xq- zu)1yAV;)=*2!`$y@DzL1tapI{I|~j)Ace4dp}yOQMrA*tmi_>(0PLjbWd3!2#bP|G zp83MJH~ZseQL?gcuSrGe6+hDghEyo7?A*)mxW`@)4cqofgXMUJG;dY0i(N_KZ2!Si zJTd|Jl+1}>zvQ`Ms)&xq0ALm?1XZFYO${>iEa-{62f2oekp1x`{&y2OtQ7q1#&_tC zL-&|5thEsskd66lp8L#AG{^vV)s|zB!fv{tM7_-ZepBl6qV=z#2u91O2_sD{=2)?7 zrN*iHEQ3Q~obH&;1R^;H&36s;{`)w~IBSVH+r#<&xRv##Ik9~-oqa0jwnxSWwl1CV z`?`YXvswGSFSH0IW)WrpThw-nhO6PHVlaT7CGTQy59YMcQ&}`wAXQI+NHl@N_S7Y-~~DaSTu1OFt}Urcqcrj z?5ku=GFCSi2j$u0Mhdj}*B9%|dOmRuLiPA3>b=TvnKn5^jf%c1O3ogvtdG6v0HhjA zf{}lXLDR}-$P%z}<>r|zv%5GDU+tZ361$5l0|C$21e|sondhXqmr6K7kCQ)qSRmWi z+i<%+X}X^9tA&lWOePDuEH$2QW4nj>0Rh`rV0om~_{cXLQrZTX;Lz4K+1t9w_wGOc z1UgLo9@_EdYltmueB~uC*|c%Y5Be_<8xqKUpHB+a>cN@E(V{J7Q#)l8d^3kwciFU= zlv#APJp_i|i&KosunEGNtoT^pJGPB5+8pGmA!-<1QqjKhy4o=~#tuHd{#2q%kyg`} zO0b>tisr0)mjKN{bY}I6*M5`B%;w3Mhi_fc9!^x5%*4iqDE)eGwRz_Ov-t#s6+os4y?2^LA*=IbFWI%SOAujMtE zJ%@^#9Itks%F4^e%gmmtZl_$C>_)!#QDf$ReqzCTVzY-VhCX#au<>*y$>K-YJw6_v zjl3N1es^Sett3jHZkEpXBER$FxN!DH?fruT`?-gPo)T9FY1f|pL-}wTnaJ`f-8h{B z(f%}XqvKg0N5PHUue99ULli!M$6#^1HQ{dXy@e#%f9ZqFR%J*~#pe<}s6*jM=#dES zijYRG_~{ZsA}=If)V~=Cy+Z<>+`K3wF1rXYH654D=RoC#j(a~_zqlBdTYpFyTF*&i z1H6xw^DixES@QDo6?)-_0U64;>FH^DjWRtE#(85C6KfzDqJ23Ze0LJR+)%DSv+1Bu zm=Ep?tl#x(ZxMlEyR9BQO0EQ&q~J+AtmmKgl}FW>MHa_T8S&_!ZBKs3GeJMD2_T=0MH>q&OG)p4)TS6bP%D#TEyR%M zHEBO%rTK2vA!cV=?~9((+$3qBVN>q{5GZlj;TEKmZRAE;p*3@E?@sHAb?o6hCsadO zZtFRHJThy@F*80X)^O54NFywnU4K$B&5J;BNl%PiDV62b7=-NgKpCpcpcSCQ+!tS$ z+DIMCX)XY*Gz<8qFOlISVx#YVG-^chQWYRs;<5$+-ecuPY3f&rmCjg(&HM)sA9lZa zXlOl_qI`LNQZ*6@(9eiaTw=3oiseq)+>0S36QGQnK)*;|Ix zH4lZfAkFJhrg>eR&p?opoE`tst7CHN$ptHNVNE1!H|sq6Dnw-|^b~%)7$x3ycjapq zQ7_z6{$T#m?a~G}KGuDD(B*!S$A?$Rg>9gs8k<;xk$D)w!;$ek2kSNM;8woSjXLGA z3L8pMYoT>Pl4S!;O}eJ@HEbV&X=QFla#qRnMB~EMFSC1>Py1GWrhb2);+jFg<&#oa z*uYRHk1}ZKZrR>nP_VQMS%s_?PZe!X8kU|}{hDc7HPtI2x-?=tVp)_} z)Hh`F-h-OZ(%wDcvMZGYQClZR!x&ckt{+UcvpXP(aOV_Z@rzoQXV zb@e6J6Sj&SLmvcTxwo@Ck~Kp|0b#1L;PQi=BVVoLW|-rzNe`udvGc86 zrB7#ojTH~*qS+nKV%&Cm?Q|jSYvXe)Y)Nb|1jBDN#lt~0Z>pwJbE)zA>Ku_h8x``S zLeQahn>1q7-dw2`dp*lv!lOMFRNnrsA45uxN*hCnXu+zXN&8OvwWz&r=>C=1 zJT5u8w-eiKL;m=@L9a2v*E{JAv@|-wIoXL@xlp-6YD)rvBX!+MVbOLJ@hQCQQRkTT z#q}-ReA}$q{7K!@5#cn{RKmgI`p|Y+%i0=$@Q_Ghp9VzKCtr!bZwRyNb5eF{*4a7QFUN^TjkVVz zKEI0CeV_CqnIZoAhne!YblQw7zsn&{_Xl{!A38vd zh~$2fljgsHD=Cb$rh9OcxIZr-ll?_!o_4ibj4t|%GB1C~Z32+8^$ zGJGN6@+JN47#N;-=Z1gRTYTiaOBtFsx$^XSF(Cq4Niay6iM7EbYhC;Hux>ve3?lT| zuE@r_al)$dXgdGQdtwn0bp#%_pZ#t|#|`C7pYbFl*FeW4n-e~7+v9zWn10hIyOZ96 znl0LkT3)beks}^3R!u%@n#L$BtLh!o*P*Y6&Ix&sUFX0r0&%|xfiC*=)N_}Y9i-aA z)FH@|lvf$ysOeRL`Xs6fS&l=_&RiDT;{6qyReis-#m@Fcy%6P(bqs&TXsxbx^qe+W zcsWIiHja31md% z(LMrBvi+}LDIT-;a0Su%7(kamBry!l1Z8UO`pSb?$TimpG&!;AUbh^<-G?F4>Ts7* zOy8kqnW#?8ZA0DbpqIblQWpyhc`i&xCw&uE1k$ob4XeLkYoE|5eT!$@06LP>(1`nm zmd;+k`*dIf9@Oh(3jygCSgbDFfErKJJ?0+;O}%-OaVI_H{BFHcF@jD$z5@s)Tiq2z zT3bo&e2q!46eG`8;)e-FA2O#z{y>O9;cPQy3a@tBeaimw_$H3r zglK*bm;tEUrne6GBmJg;G@~7+JA%aYzMFYcTMwKoSLhiwq@>-}-~Rf{8#_3%3kz`* zHJNKO^e(+j6MZag5w~9#)d)8b!` z%l9tab)SKNuiuSmaILZ<3RLXbDc>j~prD34W6HeVEgMVQ)Tq7FjSOsBQC{h* zg9+c7?YI0EO`MRW+yS~$Es2WENBM6^W0vC5YCHAlaT*+4;^)W>0r!6?8O0-}_6%*} zC?+)P%Qu9F$V-|E=U`W(W0U#q;>r}`ovn$o<-K;wyXzzisOjvrYmX;@;IJMJ+D_e0 zqx12E)l`jjv<^zI5`++t5fTm$Nh$n9s5Rr3uizYssI)jS`*02%TrZTqv?)kjlF|SG%kjk z9;{kI5LAtifg=u?*O>w$WveMh<&y9cEU=Gbbs}NK=kc}u8@=5daIVKKI`RHiwF($i z@WdOP?boj~)zx_E?StSYE2LJ(J>VN(f=vu6CPj=&igg+&?tKnkDP}+vv>4(RZ)C4u zUrn0UY;{u}S&t*GWF?maQw~H9IJE{|7FO{_I#waddvn^nyjKRs$CREc^HEwRSS`d% z7&*jaQ!th0gr3`MNq^7khly^vK@%EkBh8-e9SqeZ%?LHJDT=3r!g%`z9drT^DmyW5 zF8o~{C#)ssiA_X+tFZ@NsT${|W0_ugEZe~*_tJu;%7;wbyMY_8ee_;s{< z0Ko2Mv#wJj$KhB(%yQgm4HrbB(T+_%;harC7mq|(UCaPTF4RJ5S6{tDVB4Q~yIVTw zJ{E*D?Hxi^SFO?0f$&4X=_2K|wUyuLazb}k9COliOU-I3q<{;(Aaz<5bhc4Y6z{ay zCTnjGP4?c%Q-l==Z#P~01LaRA*s?N@K@IH`KAw`}Ks{hgH(MRcny;(X&TIpsz8v}D zi*)!>2&qG{-*1c?x%BdKxo>IPz+zln2&h0a$vEft!l2;d-7>X`>MXMlsk}&Q&#_(n zZkJ2|1*!bT=E`o1^Fr=ZQf>Edt$YlVkLKMH;Wm-t-PE&_f@7pA6^cb_$|elohMxiF_X*Ee6yUvEZ?8&L*7_IhYJ-8@Qr}zk$)LtqAX_`2u;Pr#5@Lyhn)KaSAUUvAj4bwME5&rmVXc^ zmtPtMT)KGyJbl@h!eR1C-?@{{eXic?Uae;82Wb9=FAR z7#6Jp$lLBj-|OWVf^H0zmN&e>#8l0HoQ?Owu8J2?xS)2KX28pAnMM#EJ?4Qr3b+|F2X~rPYOZN@zpqjRXv@5@oFx2EuJh-%J(q|W=_<0G>The{K&WmzB zRiK?(Nam3_EjIly(6EoXb3R-p^M;JeyWzs2hlqG~=vN~9Le#rKyGLiStqru|MXGIw zj0qkAYpWi$1&x~C?5Q@5OOVUs(7JmFPUdwS>TeSx^8^d`qpFcAl9Ubu*UjY8RtfJz3(L$s-bPCUAQlU}& zL%@||jf;yb1~J~1v`HwnlqL)}JQhg1I#+qNF( zn|Z-Yul;;%vbF7!wIxSMIQXu;+Q(kFezwfGEMI?Gm13zp)L=Qw?prP4kX-vsa2U3n z%Z+V5e|36H;_hnzNe;Gp`u>0eUG!kYi@$H=n#Cv8&}{j9)8dLi`q=uhudO3UcgIP- zDJ3)iTxAEL)Oe_Udi06f-RJm3+IjDLk*uQIZu)-Mw=3t-phb(7dg)SkL{;fraYZ(l zYa-6pDAl&m2f{2_t|wK7^h(UpX=6*??H$wgK>3U>V#Z-djs+R6JEIfarHflzbKHVX z+3__>Y;tM0mw%3h=2^tcTCr~AR2>E(7OOP&!m9t+--jXjy2@6(zCbyRvn~^ zE^xXOyIj?D3H4wx7ywmjh8^3JsE(?*J2{njc>E6fh&pvdQ-2}MLMhs5$kp)z;s+M{ zOP#X@2u$#~W{Nx8FCcm}NmW_admkv;CD_H~ZTj^yoXe~&f`}d8_L_)&G$a@`eJW7u z;cdl0E+(xy$UBF^%lYz{CXz|U$Uf&Aupd2i}Csm4hK;WQJLmB_DTd_ZYc8>j`mDG7> zlvQ47*0Eke$lOX+ao|87sEeQLg!cE8_WLXas-7a&aGl#c{YG(1o#ji(_}yNA)W}XO zN<>>PIkcCB*%%SNoC{qIA9?;EN)v>$q zJu5R)s!#MpziCnT?JvNGFKy@M;@aZ8{5;rr6Hpd88dmeaOu>aZ`!2kB*!79ite$$V z8GNud@b$(sz{iz@jO!+aM2^7>m~XNu*42|$h=!9{=UK1S2?Jd^uf?|ajiHD$mwr*J z)Tr*%olm^$!##LVRD|BdWR;$QK?L$#K-gE*Pb)r zJC3`}$@RI1o|ezJPjv#pp$(5~Zv|!(psdzl*7ra$r@+9_|8%(&kaj?6VWopVdT$$B z-PYp-1NX$L9l)NstX*?S1{BbHk*m9omwZ~c838OI)d*jBP2Au`^+ z+gA97eZ0xT5t^8`fNFdXIb`KWIbZ=V$5uSZ85O^L&R&q#gN-|QiSd3icU6>3nLZd& z^)i`YN~1v-i8?jSIxp{_e>z>Sp6nS62_x0&ecE1ie)w`xM07@BX1OgXH_twLD$R&) zXjZSNL8uT{s5mM@z$>hphmr*RRYDKNGG{5JRA=CH5_bGabC_@Sv+?OGtN89NolPM- zhk?*Pf?SJ12YNyxXj7(CD;qetAR7TDzg59NNt?jpsuv zEV_&VwI_5>to0wb|03&lA`+S326|z2#(eYR&DnsU}**J(aek(hm0b&Ee@1 zrN%ADc~D$KPT^hmif<($85K51ODmJ}Ex~lGtcvk0I)nNNxrniip0Cf|$B6lzb=>5^ zyV;u#3x1KkeY^IFgpZwxDQ15^(hEh}<)Ejh=OYmBV`OEm2s&6fE1^U}y{{Jtay1nf zw~V@-VeiTp^cowyi6Q{`Wi03;6_lCCkx8#)pFQkbs$;4gGA71AI$dF7plo4*$Ou}q zC7AUyfAK-2#@tIPb#)^2(|AOgzBFIPW)jY~$Ycs0RZTO|7-uM3N zlP;3Pi)ZHFTJOjlCz!P3MAPEh@Yk;M@LU&89e*!$oH^{#IT`o2^p`i(W$ZRIFcV_X z+{^{J1~cpMJ=|uluu0{BF(vztqt!qD%VjX2Gro<1EJ`Nir zXReTiZwb;>)T;0M`}e=@yDUKUVej}`5B>t53PgU#Jmi-84&S;A{1h$yXgiWWE?t?7 z3moF!z5m0R*Vr!jD+v{^MmTE_gY1Uy=p)A$I&T!XHPVD@_g&JfHD8HYT>CO^C5%3@ zKI-Wvcs!c8hQr&8cuTxl8B!KLs@~aT2~AiPs@`{*zd$30%b<}@Yn7hmkiyzdJwf(w ztZ+?zKKHS7nma3k#`$O z@J_5Th5FXy(K0D}Cfu8F9xw9lSg2c(ttx!LEy_*6&8}QIuCu4$DsPcee|l=^bvXo7 z_`PsNF7o>7oOzwvklF7bN=GL=L9kF^EyNE!-cpp1SM*9LytMmTcxfJNXQ)C%*z_D{ z@B@-{ijlo{>PMUjy^UC2R0K}~4hdYo4R@2-OD9oP_XXYDLui}@^Scy0C}7l1`<>p@ ze@@yO3H?cO;M)K-jvt6t&Tb2a3=CRV&}7X($&8Cdf}vNbpCLbSd@P+G_fRi&LLt<( zd$82`6lNaYGo|u)&OTD{lk1IvY~mUj!P@iD9?kN36NQcLj?Sn0E%kB_0l6xzTciKyJWJe^8>mg35z36GbF7|F{dab)kVu!ZrKX`_3yf0a1T(S z+LCiaki2@zU2W{bm4bR>R zdqne8$Mnty?)Noj_hp<3bxxN)<>F_FUfTFkREqEkFZ^Ba?i+PiCyCqE(-f;C9CWpT|K#VeP5+#05BvcX@ zlE#awcuTwi8R5~JLi|hAN8(J#!RWZ}x&;2fDG+Q$q}^yLZPh5c{TrFLI3Se-uoZ@m zVAIbF*eaKTzQTQf_@!AZJ+oY0t{45b6M=%XfpY)IEHN_~>A;Qt7bceYH_|1D?Qt=z zT6@~T<6(`S!%boIZ8SO+#SNqu)l8Jg>4BCNyst}t*;X3~R~&-z?|}S0!%t)%hN%-wB_#**elwaNyJ=rLC(C(592Wc&;{>A(}GZJ0UaY<)ANl)Bh&ikL$$nXD76|fg$OAlh<8A!vr2#4cmAA+ne?6{u4&lIMoA*+cTl+%}jLNZZu5MNlDCJ|J_El#|ZTN ziKSte-BQ2^1p{Q&xBH;3LsVt2CS1h&51XW`VOrzsl4@iKkC-i6-imENL7#5uicvfm zodBL*HsmV$-S^kFOJvF4s<)sY_g{X4J5)^xJI%T6C~4kqQh;ZzC8#n%Qe*&x?{)fWG|O#f%%!^cFr#9g$ zHZ=CnhfbH*)mZ(Zf9&A`A z3(}SB_o}IRofhm|a$D*5FJk)(T{^WjuH<6j%omfC}8$*vQPze&(7-352QL^IYt$ zt;5mO~K0=Rq&l7Be=DsZ--)C0yuu!N*xbQ z3ecgWlv`ABAP@-_0hWB%o-=r~@?+EXr??9;{OvVP4GOA|I=DbYOG9H~mpfw>FKgNK zpV|B$X#T(Nf$Q$@l;=>dMMU6`hB=(vsR1FsxKEYvfX+GuQzvk2B)aqGPgK&tSx8X> z$xl;01!N>tQ~GpqV|8`)@pt{4NvJ5dZ9XX10W&|fvaq=K+M(jge?0f*1xW zDp=@hT@iVRv^L(%&4j#1r2^Do2ltPRjO=lcul&Ea{;z5j|4X3e>rpCKIXSs7t3mRh z4om<}$*fwD^}qrj__xFE0ow2N<1sK5(w*|3W&XEjx%)<7N%)zBBw#Hr#h3!tV$)Yt zPXol0&JO)hkgK_V4HL2xbNUX9iJkr7<)JJjl``Rq~UI; zJRoS0C<*e18(L)4fsqy=*TdTSW2r&p;{C4@sqpUwMV?X9Ffz&lRRDCnbQ&>gG167B zv9UBxYlV7@ax`TBgUtmV;j12 zv0Cc&T@LWAf}i$y*W0xh*5QScnt!6d-kCVTJ1IazOxdLV?^ch2`HS#W2i`MAfWm5@QkBif~bpQf^+|tx>0l(*mu}zml=dcmG2qD%Q zPdk6$8l;S=GyMjeL+ED}^nbR4_Ykvb*5m@oZ-V2D_ zKApxfHa2EzWp%P$>g0bI!~cg2 z{jioEBjebym+!P(TrlPq7L{Af=h*}IZ?_yccKSf(X@MA*|Ha<%)%-M&<9&R69aOjv z8eNVw_SJvoANY@O!&U)~bOaGW6Y6z}hR<4rxtI z#&rM?$Bv)X;xWGe0rLw)(yrkhr zU+zByCSMhGk3}SuDCJ3kZOfS9m_Opg2ZEUOiF&x@C5H7-{j$>QvCL$PcBJ%q1}P{|<01v104NxwCBIfr-yS8gg~S z?mgbhfuVxqH*VZGuc}%D4Ik*50&b$@Y!p);1?GYzzd`{HljC4}PX*^wQGAQmf2}b7 z|Hm{q&TY-KaGH|gt3TJrk*F=leUjj>gJ*!I2asUl)D@c6Ft8E`CRH^%uw8|-Pa6B^ zi?hn)e}!!f1-|gJVpZo#fmEL$lr7)*U$aC-2_)yUcJ*8iN=K~OhmUQ~BK3SEHFm2z zRKKhWpeKe7_csNnrd)XzE;|H3!C_w3m>hbkq-ExwuI@AU!OtdseFy`P0hOg5N}|ht z9HkaOD@G>BtT`{KOg*OqAEa^^VxVaJc_QW-*xVuwrE@fuCOeH|g=MGxHoo!wt9B`V z>6ba0?$!a!74yKNkWd?Tt8~n#%01;)>QeVpuH_HvWIc)Cujw~p)_WVi#olI9d23@@ zrd%0_ESv7c+pYkKm)9A+IPXz!*#H3euvUJjWw+n~<0b;-oZzCe5T^*TV{@NZbOT_MoAj5u+ zx2|^(SFL8rd%GX%Ll($8%dug*TNBHG6ut+hx>USwiVCB<+dLHCo~~3ml{S)be6}&S zcDwq+hY!#VjYr>)_5rN#HroI1-P_(YEUY2g^9j=4J~vKM)9#>v#ATKFeUBYr{75sh zStq=`3zt-Xyz^+eo2?Q42&~%jprwaf096&C;Ktgw=W9Aq$Z5APAi_t4P%(PK`7J22 znV$DqX+Irgi3V4yZhcD-cdM}pogOLt%M2g`-~R_gRkm#%Ze#&3*`UjO)) zJynZvAPlFe>fp+Tct&~EwaVyNWqkjQiF(6&)m=L(%XT7`&F^B>$Gd9WjNd6tufF}g zBTh`okZ_%#I7A<}K9AUT0TP|oWv<^#{zT7`tZQp_y?y9b#*)5jC$XO6VtTH%oI1YRep2+pK5Q^Xvq18x z;eV{_OJ|NhQ)PYE>bqUVu-i3Hz zZy6Ypt6P0jyWa0Me5J?6H-2)1G+Y^tvUc6uK<`PvfB$~H@@j@Z-AdLU`q_c0u>Td;!JcGA%dn4VToCriXAur8q&1oWS|7`O+ zmv&G&yeYPF&?j~Wu)pp6`P#~LP9A7rLd(YsA=2v}j7EaTs_)>$s<o?DM+Ly7Q}FAaw-^ex1melc6J@6eTx8$wX`lC-y@w=ZzwA*@97j_&Gq zZzWMMf`8%^!;QPd4fe+vWlIOy3g-c<81~E2o%WDOnV^{BN=it%;rIga;;EW1YjSV! ztZXSs)MoBJA=7Zheq$=T4QK_Kj198~POOUg+!qpWf>*}5B$fw&3yB$?GY3e!Qa;0N z|EppMN9I#rxw4wIPFa?6gNuO1W)5q`RK}7KG#cMAf5D*63IDnnUzOvZlys(cG{d*! zZ`;5jTEYh}3Fj+iwP3ev1CCI=0V5pV?Xz;3iK-QFf z62v0*jmRG<5OUIWLCkG|NKFp~@1h>?ycBxSx{XVW7{53WOP}*N7FC``_b41tef0hH z1x}J+1U={DN(qwhm+S4peIKs;qo4*Zk)Xt>+iNcz_~N4bGxKN0kgfI)@N?xpl(!6x7GM_%!Bb?0$6K3p$zknrMCMtZeN8{?C$$KsYeWQgd6b@ z-@rjd@rjWalI!pVI)zw2a(nN$iqF@($}7b;>e$`HM*%`A7@qpX7rJ+*22=xmO`^Z} z;F;Epb7g=CmB$Pg`~Lh@);}3OnJ%2>2AI=qR#w-jBzot`-Q=qDn#Z9VGo7+br*g&2 znql3tak0O8l;pN{*LfMcATsi``g*Uf26OVPRi$Ux&Ay+ZkF%_oKGVOb;3@bk{?-_;A(itvUI{cjD9qObQc!Me?+TN z5w3PHhuH4{&L{sa$-flTN@&W&rzHoq*KFOGoPR5Zlbo`G3v4IMwz*bcWP9UwnF$&o z*1$TvC-_EW^tH8eK zi{|OO5759G$Fw~oE88A@W{vx@2UElwUo>D!eO+{LgE%F|zsemjv372djQ|%%?OS=+ zZCFAI^+Lm$Ta%wv>J|B#U3DE<7K$BV7*Pxnk|&^jG4@X zX$odJeNR&mMUhh}B|@#&Kp2^`0>h%>9CKkY?e;sh;PNoAL{OQT_v3_vRaYsxtc2#7 zJGFHs-*9H3<3g$6X=C%MW!ZO0EIMb3IrqNj{1dq`eIQkbxXx<$p{z9MraYk+g3-Rk zS4yOVEVX>=N>9AM8+GZ+bmxu7|CCKARFa`09=e4O*qznqKD9_BZ48H&{t(guuv2m$ zipBf^{Qj4iFCLW@*z0-hJ1=cr%M5YpDzcVeI+P0x)RE|;z9qgO6UqQ!<6a_S^4;W9 z$|DFoN3oFAGX++Y-Gr@)i9O?IVM8NHUK}a&eR^lDzrB6neWBeA%k1$4?t#*cJhJO8 z^i}=<&5>aP>-nCkJp0yhY?Nwve|b0Lvnaj0V7&urL#(bKjdM`y?R!hfyZvHi1Zf3S zSLqYH&+LhVyfo&zfKAT|IMY39tg{!SUYz=CwQsB5!E>Z-xuiwM6@h0m%!_d^)PomOzNzOb=$*+LytL z5CS^Z@Ot;Yv0hjf@yDisHU^IWvGBqbP~^HFvO_wox>;D4ISF+r;|;(1Q9}JtuX`eV ze$CvqE_nh<=9q&S#JZ(#V(aZE8amPe#XbwH&FimG3(Vc>(?e5YBpQSo85ug4$Ji6? z4yZ3#vweri9H^Y?d3xM4Ykg2Ycw#6pOklvD@t|D84R0q=>~doGu-=T=;SATl$Z&r{ z=9&y1D`KO2oo1OdLq&L6rQWOAX%DWcj86QyY&<&XOHi77i9mP;cN9T-4z=L{_xG@Ok(zK z`g2d!ZNlc;-GdK2mE>B^^!Pp*oa#h*;Qm0nY*&XC_3VPJc3_OcGdT!&_oONY1^uCO)o5Ey*Ydcqt!l8WjyL{DKBsvELgl}Z-*Qs4(G}`Nz zrLMaxmUg@F{`=pd%E2J`t5)hhne(x(?#EQS5SL$`WDmZN%CvI-j{WwC@x*Bq#ON-= z(=wHPA16)ciEehYl^nn8-$BiJcaXQI*lKhZL~aB#(a`L(6+KU!YfcC8@yvB^cJw(SfenoKZ)4Kuxd~u5km0SNUg~DRxXG*MlwZuz~=y^^`6s$;jg)O3ww!Zul3}+x1OGJJ{GehdrZgt zbxd7Rovf?NJq*3{t*Z&l0E3S~#B{+47ZC=u`sb%pjBhL4ojojdtZxB5oP_$e@lU4m z_VtP39;L)T88^1~Q?iwn7q;TK)QIGQ@LZZA;R}X?KxWcP`>))(ClVDZv<$NhVy;ek zHa#CBl}Xf3x)4RZa)Hfu`es@g$49W%{WqIE#{YTm zLDxktD-F0;l+}=)T+3!(dgZLXT5nzh5>W<0$leLbb76BYB8jZAIi)#0c(^t7eoft* zburtZ+ybqV+2TvRt_zY;@i4r#r+zy`6_>5ilBD4vIII5WwQl22BHj;Hl$M}`&B9-B z2-Tb>B3X!B2RBrp_`pu*N%3bMlJJ|#yC-u7<}W%g7p6JbSGUuw_Iz*uua6^auWH=A+HinXxUH4rHZ7Z02>NU1WMk&WQOc_7u zzdiv2`pimqh>T>8Kj;A~%~lTWhGDnV+*)X^CD!nQWDJ|1TA9IS)$-6ePlUVH=Vj#{ zC!Sqqa=GW+`Tf+l+3uL;U118lI`V3(q#|QQ2bKjJGiAT1z(o~&iG#0jQm~2`*G7b# zLKF%XN%Pv`px{dDtIfE~ad)Q^oj_>Ts!3s4CNYeC^5fP((0b8>REU=Kd284>$h#NA z2bv`E=*^@kyFf26wud(|IPy^gj;Xe$oIQ$zd`g2yZR4??q_1>;&m)M0l93#pDKsM1qiNCZ2& z>X8U6*|1iyt2Dq&$dT&?ZB-d37q1VEgz?s5uQT^^7_z>@&$8h+vN--;m*_^R0|$;` zY;H~|Bp2thHw*+;-{>k9X&^6F)i1343)Zk-soy!TETr`52e10A#~nfW^_1qT)y7)d zMs86Yl(D$H(dXk1Ei*{us+-c-`%8*#izeDew$PIBA5ZJCUvWtRbuE5fp8U#ZL*&fW zgFzONy+~9FHGvl5wXwj^JY^^aN0WO*4&Z*z$;B$APhuc&oDVUrk-UpuzxdXjwhG)V z$s27Gpk*H|yH{4Q0&FZ%B36@C41(7T)=q)ZDG_{qxMrkUN%zFvN&q0 zMf(yq^j9dPuBdan$-AP4NVQJYh1!gWfUq#GW=DIWH#B6Ru5pY+ap+7QUTuKmq+Cgy&&~zr^eEy3fq?HiCK><~1s9~j!+;8&OHY|rX9=FSL1N+kOY&y!TD^sJQ3wtsG zUSE_^!02Xac_>qh#&53i@2?oFpZJ`T9a;r--ihmda@D1RsY(PoM4x?9C;4OS`$WzA z2sXs+lWSsyY4a$2O^hUvI8Ab|`S*CWw9XcNe}JF@rT7rp@&n2M#y<|4Iln}p?ENlc zs;^0FZoM*Nmm|B_49QxZEG2|RUe{)3s_$+u1Mx*fcvuC@buwa%T(?>hB_*NtZ~Wok z?vm%QnAhoJx8KU?Z>!rh*S>wWlpfPDmC&=qVb@wexiS8+#(I0yVkMZKfTP(|7T=e- z!S1a29dfF%lQwYsH!1%>6s}T``2G#qGr!m(^stu9wUgPOo+OSxBKCt49Q(ut7uXdy>b%G|+!BCO{ zbibHJ|Fncg1e}K0PD|02zDJ+^bFTp!)yAU$n%AtRjLwiLyJl8zHaHp0ga#lP(D`E!iMG-Bytz zZhVFaZ7)25Hq|@3?tqXTsUrtuoW(SUFU6JKBQd*7@Zd!=<+F80Cs`qzBQNywKvXYo z9=Nn#+RePWGE5QS%ls;H8NY$|kQOtRg4=EtIT)ByxA%bSD<)$#`%?cm6$$JV)>GVT z_6&Es0j+ZlMJhN-YV38bzIa~tZs{%$6~{wJdpetzq99AI4=Xy4FXb!L^SV0@? zLrb5F?`|X}EFe(fiV%W(TQRRP+}eZaeG#TzSrCk%)<4#^jxWV|(EQelVWA}ZMCI`l zl_Sw&(Q^Ku;$RIH+#VvfENsDI9X1JQ%=_%sr*zQ zG_!KMt$6gAt@(%1XZP2N3P$5NzN&E&mU!cY#75LYsR|zcn*lQl-uAuiq`WdEZUP3#*lHPd%=8q30nla8OV$ zX>i0#nzL{M_8UR;8egAz-WIngwDf&ISJ=!#_Uy%skH5n7T${6;FP^h@sW@F$;LtD* zkVytU4VE(sKG`@}tcgX~A`N2@ZO-LE<)DE69xVu=aewAWK{Y>$`UJ8X#eFUniIDG6 zPsx)x`ETZ&gNJ{YsdXN4LqCeD5PWO)+FFvZ6admjRJeM&%{^8@-0Gq18Of+@Av;3O zdk%Y`BJys_ob!}6#$I%nx+T^p;D|dzgh2qJfSBq#f8y}-G{NEHud|Y=_JxL3NW?L=EsqMZhHEb0cBrIYJGP?!u!zOD)@y73z zT_mEunMA;l&hA5NS>4HTs1?roY0oBRQ}0TUWq0+A39NiA-xD-uyTI-8k&{UK&w8aKC1K)2$ski@fX)iq|E+F7` zD%`MllZT4PU)fx}e5(YP%&OtO_!{@1BCV0Oo()@CTI*-<^WX=z??w(J8EGh=I`4Aw zQEs?ZW!2C6xkMbVyI-v_m1KO#cAKOSpEpereu@Io(?jP|Z64M&>A@r_V_yp%tOtFh zFLQvGyiC%-QLh}4QDnpW(`s3A-w<}P*|x7wSAbY)y0FyFU^({ZQtL0#yW6?z>b!9{ z>#*#45a`o1)n?id61Bv7Jb)N7|1>xc|0U4m`)_mp(@?O|Z1pXz$g(p^r^&GE>Sz^O zP!=&KEBi3^u@n>(pxm#LZ@8q?{!Je2A5Zxk^KIQI?arsFj~}1J&e2UcD9e@+BNU`r&D%LS|-Y zd{VZ-Dkp_b?)6{yJ&gjEZ!4kBt_3oWV_W005oGo8!ZU>)n;Sc}z1J^76a&Btjk?{i zDz?@8$stee`Lf9pV}Mvo^R!YeDZnEUsLGS&m3#tP(j)oWsZ?A0xW}F@k#Aj#%|Zd5 zuF+nPZ|f^)KBywYrzH(T)0dg{PQ15qq5X@~7M=zmz6ZgBv4R=F&;*`D7xu|))~u7~ z9I=OAL^s*nt8R_182d4ajo1BB&J;Hm0%W5*%p8j^hSEGP4b5CDBA<_=!#o%=A@uuu zR;k`nGMk0H8wQw)i-HmG*WkE=YU}b^7PRZNJf0IZ-kYqe`JhJ!$$XY48-=|m`n_fbNj+m-9L zt1bq)LfK7VX-2M0pJGTyKfgXyD%f_d$lJAc%l;9|DFPBS;f4qtD24s#OG7qTv|O=0 z@P@u~uS-AIP4g{22gd;n`%*6Wm2Qk#lh!9b2lhvE8>lts8Lvc9C0XY=xo0|CAUUNt z9=>R@UBLBpZMS>r%&?$k<>)j>Q2Lbsp1BNdQK1OBazr?0Rph(C=b06{r^Uz7*mdaK zai$v88y-0*i9`+xJtcJ-fX2(Em)6z)xH{(tO?n3^e+{I~TJji}rWkQPx^gR+1twscBdyrs4j{mLYz z5qV{(uNSpvVR!HL?%Srt^z87LPS)VCMfWT6IjX;*E6cKZj7}N$^7t1D39c66URU8? z#FzdP8IxcYpk4JMXty;QKkkr{fODA{bGqvB&ebmHA+@;qEJz6}fuPg zjH1&vq}Vb`U{jIZI^?uxSR%rJR|`khOpr_7XS|R)k@YZKT#ViTpLJMwp zx-ru2Des}#n?+L#;KWy!-q@9o37^lV;9?eeaEH?lSNp|R#SRJ`&gT+Tyb@QOkUTurqL-ekAAZuTNR6@W z*Ii^XG7(d7&9U{Zb4UoD)h;kDqgJxkHSuyU%Cw0I&9)a_O%&T|nyQMXF7~IgT>Gbc zK#D^B7;VW5%sA*DqAU)$X&O_vo@G`}J(T1cp{CVG^zY7c=P1-liuO3=Y54jbS(CH5 zmwsjFUlsp{ToC-=;N=mg;NAsnbAPwbXV-%{ESE9s@nR=TzXO{JW8FCgRmnirn0e|& ziTO)=x}i>32JV46EF5pK`gx|LCYmd+TRS)o=m9FTJwW+Wdh+}0VsQP#P-eR=Ed%z$ zikyVIbh&OgWG1Rp!Dz3e$-d=RHfRdYT~@*L1P=LIyd@hiL1dHC<`+wBbZRec=W$pH zpIeU|hLv|DgB$b6vc3G;k!nJWt|v;Esd+jW!3cz6&X7?nrT%SQPZT_CsR@6t*P!}? ztR{yS*$7A9V1Xq*Ulf0`)qBF)2vlcN*uynGI@C5McfhBaS@M?PP3&rl;BI~I5sPbr zp}1G~_&;u8l_z+$wppv%HWyD>IHwl^Wit!n$%Od}A?Wpg3r3JyNuqKXW?8kHmA~}? zg{Y;=tHnL*Hj$0S9yctKA;jT5Hr~YwR67CEGTCEHMfE1J&To(f0Q@q_H{~ zidl?0(ByCp{cd@He!sJouU_e|KZCrtafd4h_I{u-oQE(m;N_Q}R$^&pQ1cM~)}LOc zQe{p=@CwcJ7HsI54!Gj*gCMZ()Owdj-r_?wf>k^lfo`@*X#x&Y;Q7R!S{ zfwxCIIkVi+WRA|d00lxC|yyO`TIB+R!6|Shprs?2_h3+pcc*vVoDu$(ev2a zo%I2)7ejPQhxoEL4g-h)X?Ts4CG9qk#Fo692Z#wzcC}neMD4 zmkZGd3(eM0@3-){8vd$cVD;iEe#5vH$%FGK->SPP+1h4`{Gq`Xnv>i`iu+_z!|X|594-qh*ywz?zvKu$96 zr>AZJ;xQG3B$ifY$No*tPqh=3{D>{B2(W=#SA86Pl#&>=8}jH38=foXEPT0Ptn_r} zK)+&Jht)r%m5p@QVhduS#XlbkF=PMr^@XVPi;y~e1vprvZjoh?B(4} z(f)FzF@R=?R_o|lNMkOo7QD`kl40>surG^Szq`5!

FPC!4zxv25aoY9o?lCc*Hk zAZ0~H*-enwemigG>#bb9%-Y&Dy0u|)+1iLFO>xYm9sK$CDo_i*h|Otj6fQC6g2C2d zpi)b%xiWGarw59Bhzu12kz@WLY2jo>SpHm>~Xp4AxD(YPCp@2Ae0N+%@~Kz>iO zlvSwQ#b4Ozn&p>D;%Ch<^ed-~ovo$wmf&Em=+y43-Zx#M8p&&Tuk&zsm@z_n8BVkn zxoUa-;hX_efXj_%5%HZ~y_LADACha&TI$MDg0N+h)RyK|cKcJ2;Vz$KbcvZT?Oq*1 z$S&yPn)L*b3m`b|XKL>4Sm807Te%xmw(oL{nIOpVufp5}G50cU%b#|gYZ8=eef@w6 z{R5ahvHI>RhW%=3BGTfiNogE|OdGJ``kszISKe z`)EJ;uVzd^nWF;oAd@q!T>#pG9&J^!JIi#GEwTV#E=LC{@+#{BM#ob)BBdf*==z4M zpgq9_w(=9jNphiApD+fCz&guS9ee0a%(<)+10QpD_6c!!+MvD-&Lyrc+J5>L^ z9wK}^VjXvRyTUl~&URh5fEF$&6Xgq+Aze(5UVGLKhP;PXPE2QY`?0@RKEVtR17OHu z?oW$;xgWw?l`!8O>e>7-Gd93(cT&)ivwPVQ3~h}1PAG^c$v%<@C~D9IJ;b>6ZB^mv zP3M-@uqLN`YBUOTI24@c8Aj5gNU!lb=PUvmBQ=DJU(A zNG(k*%oD#eIT6VPg#iG-yu+?gr+7R(VgmOEXU{5#$+M2P3V7(Vp*f#WFe;EY!9&G7 zEKB3cS+mJC;+@BYxYa^RqxD^PgRu9oWf%q^MNh#gbnX&E=Io!|(zls{f)<<9r{(zv zaumGwdkhhDl|gvP>)fYtL}#Ea(>WzMpIQK@N=F~l#^NQRlA@_7%+hiWHvHvDK(2YdGpPYssjF1^ST-M>Oe zrr$mrpr!^o%RGmd>oT^NKNPSK4NL+FToX~XFW}Fz0K29<^t2@{AyB0Qi+S^jWQH)i zh{hA?JfSm+s=KM?wrmbkgP^Hals>Xhs@qSXR?jpZ=JLjm@gfGU?v8#F^Oz-_s&EV% z`wS~2?d}prg>u&Nuj8jGzHsyd^_ol#AkZ(fPXevK#|3Q~yKtOzWxa^k(@!cDVanDY zEvD%APHZFj$;j=SGI)Zi;IakUb~Tq(0uSUUbNqGezZbv$!#C1Tj*yJFQouowjG)`z zT}yX@r_Wz?i;5^Oivyx*i?5kW!(&bKNB`102Qk9Y|0#csS3|zIlcib;alc=>NKJ-~ zP6giC+ZfyQlL@ztWg{Rh4as@iQJk7Evtnue=#RdS$olMf z<3LCf{VcL_^YGpNSNG~&EXki!b#7UCVSV1OYmdr>W)FwkBxb4a7;n#!s%RiUw6S6caG2>61JKrQD#xuspFKGe6eUXi1dF^3d6{w zhy_p66~i;#Cr`lcn?>E@op7mdIpur*#QI7LEXT64oI<sOP3++9xf1Z9YQ zAS_U0W6-y0Vm-0`QM{Pal`xEPQORRdRdBc0ASi@{H7xGJq@2l9>JGVTLs^YFfjmjp z3Q${CQCT5TmedQ*dn;GA>OuccTd6BI_bRqL=L@r69B6xgr~f8c5~4;HiG2a>fe#_+ z@rwNyGhp>HU0o^7)iS3sNrAk45NFK28kfooKZAJkWKP=}QlH$Fu5TuR`3ZIEoDmeM zGYlleZj+X{lgFcy{r{m}YfgL0<7sIND0E zmzHYahI)-?2nDUSd9FZ6*U*( zFS`CoWAqBZ+P!CWBA3-FyxaeZpr?9rQP+a8b0sn z*QvUM?kygtO^ZidQA{<*v(6)5_KoKrB`{XEJwJ_Zk-4_1MXSNG92CgnW3I0|HI5<` z#qefjhHWb=hfvP>LJ}2p)1{pn(}pRt=@QR}-MmjGyNX(YF^jK1AQYlz7Qx*h#2hP)1A{!O+q)~qW8chCRs{X@%C>J*Vvuo z3y&5Kr8E?ba_4MsEG(E`f>X_s7=ZAXfJd2^wR60gF2pIw$`|#x@*w*@FJ}VOuz(Du@pW>qwR>dO&Y$YwkyzJ}V1Giy3U!i~I zvG6KuI7pW{BHy2i{rjw5G|fO(t>EY?$U79h((*XnV_fjN8Fl&MX*Z$f{Q8JCi3lB0-sWsXC&GIb+f=wgB*H`@)Z7>(Ba`iLX9x)Re$0zm#8j{Igk{ zzA8Zry|W;ap18Im`5XA6|8Ew6zYVwt(69HB#32hk+sPc`%3(3Av&X_Qv?$X^mUn)8 zW`?_UO*wge%(@K|JQ;+S`v3%O3iFMJ2ywG%atkN}6ZK2+Ue7aOKZe$Eo8ABngazI2 zy3LRMHm`&yuk(pp&vHnT$yr`|$#X-y+_RDaaAzd7V%#gR3fDzi$oKCKrOhkmEbXun z>MtU=IIIRHQlZF1l{;ae&*N9kpUc}_RQuQ4>Uj8iJ?4J{SAV}BA|Ji;+3^28+0YPD#*vGwUU7FzG8h=Pj=Eei5Id3U2M)Tm7txWi#58eI(E=y^$ ztG)>&l1uu}09*p5F)-^-N1zvz*qyh&>f)d0#4_A|2ekh+E{ozD;J2F6Pt>e0$ZAe{ zM{=9XDCssiRAOxQz@&lk(E1WAJ@&BHjP6>YCd=h!Xq2W1I#EMArwjSq5_w!N#R+>cUn9W^@lnBr;GafBrRii~Z>4$Fr$rm`3wBgM zIuwU81NtxVTtQTBjsj9<(tL{U#iUrUDI!6MA(Jbg0cnREO(hlgALLQQCW}VUZ-UkJ zO|~$f>sZ@+c-a2h0)_sQT@m065l~yy>iB5R8i1_tU+ZB1PSYvkS93wS=d@pKSLzWi zP9d8(C34rN1cCl_{bbnasL(cIyA_DPC-_TTr}dEmf{k?jy!wdA8^|EY`Dk!Yx)t)kWN5D^H?K$13d!m&=jB!PaERqmM;^g7z|@ zR#A5E6Y#BpFw|?s2;A#3$e(Y|YJqP2WHp=LMaY8{)3!_#k+4RFFZ~Rq-}k>3wd-&} zLISqA3OMe7X9xLsEUc*}Z16<7Uk2=Ae_CS~m{F2aNAeQh2iX4rc;R1UFgSV9 z*V7y@N-qam2m+z%>ruDc0v+ooUTS-5u@F%DLbwT9kuzYA)*)sr_-&iKVT61#l7 z+M!M;ughygC1qdYv+r;K=8pL5Y-wGNRdtU<0iL3mE>b9j?%UAukAeHK|LYC(+aFjm}Q#R zwV5pWEdJ>Jp0wPl)3YzWF3VPEyenq9)Q{XdtT~ZxSewm33Gg>j27Zm%>T(0TF&jcM zfJc8?*9s~PimE9kE~wBETM+wwRwVqh%V&TQUN6p>5%B5+d(Y;5X$wVG;Bc^Xv5ia9 zpHTB=$Eg0xTB4G0sVh;(sgOO$(Q0s6@0}3`F{G3ltPA!<27`gD13ZZKSgqYC`Jw+A zK`*Rj*q>v1)${5pT$wcFb_PdT^>4R*h3ulrk1$}bXqrHcIdlC5imKtV&@Rof5`!+n zvcK7BPjKth)dbpk5*Bj?j3#QVjw+E}NZ}M^XjK%FVP}wQ0m*?hws^(7T+j+1V=oSTo`i zt0HU_mlF-S5IVPwy){z_vg&VF#+e32NiP6%;??ii*M&Nz0S`-dd8WSMehVY);zhiO zpb6n@X8IJyO6?RtdYHwP>);-w=Oa&G9Q5Xs*jdk9N4~t#M&M?0dG;c)`r=o}8{D%5 zNnk^JYIXu)|C`u@7{FKVhWr${#Fr-r4QFL#*8&|$$bbhMR!ZTR2y<@IrzVLbiwK- z2ASLxQX??3*9I^s0h*tAnX%QOp}Jlk!>z~%Yx{PayyE9R&}st`>NtGq4or)5>bB|n zt@jsL!X6_t-XpbW!ez+K0!HTAK8l~ngqL?f&K1;L#7zad2~k(lm!a!oWjwsDmO_1| z!`jdkNPr7jYNpa*EJeN;l}`8io{~w;Y*VO1R2GX{xYgCize5#pQaF}0ZB|uql2;L= zJC&bd*VupEk@HoUkVK-P)(2gAR-G9pW^4LnoK{Pr6~2dO67!+(sjo_~3~6m{Ki8^+a(m z@t$9kFyrtR{~f=qHaOT=i1>aw`64=o>*4N!u?y z{iAiGB|5ZwqKyw--M|{na?CEI4@s5@R+Y`s39M&fZPbS0il`%T?^|xHIV_sw{ z)W4sq`qslGp+5&w0|Kj$YQuKt)Nv!1weaEccCexB1inJgt*7+qQk)(r92XQ}8)LZ< z#QK~<*jc(z4nlx6aeIeV9IH%_Y{7-NWzqc_{^pqP*Ywx{>{Z9%)ogZbj>mweLf;YrODw9EYu>|JzO6~ zy=IzR$|}GG`A0r4IY?TAp~ZC{6(1#D+06ad2!&*xok=~-dppp}m%1~AQw&8(U1Qj9 zn>_l$kS??Mt+&_X!BAX56Ri@0XPDq$fAG1(wCyN;fU{3foxiF6s6^omo2~m5jHu<( zRo^c8q^JLkC8Wx;e5!{~19K&Mof22_oqI`AQ?pkjKSp8 zpM;$aqw_QSH`+Ogyiwcy_3YK{hDW)z&xP>jL81Hipf>YK!pe-uRo2OFGZ@B=JwU^C=c>i>~|7ma$-6Cu4fSoj(-J}|37@~SLSlQE3Ay>`tv5I zxeZhd5!JiepB_0er;%QTu?#oRLmc*sT%bL24!(X1z1Od_C6*`;Q9oMDTYvKiZP-)s zZXx|J;j7!JeKqj#+QQ<5Y7ouq$UXvmjZ1erjr0x3VzC{FTFaiL`AIPP?6O~d+m$^ZSDZc`rT0TfLzLT8%z7x|t$jm|3cCb6*ZR#l zmH;vS7`^w7$xqf^$3}kZl&*AbEL@GBcvxMJmwC7^ZGJ!frYtK#UZ^2W{xTjtSLFMa zUOV)>?Dc6+z$d7C68YSHsn#kWjDMXx-=$9Vaq4jmz{pUvZ#b|dpd4V-*_>5ZZ{`gCgWhy!YQv# zKyx?z3tx2#Kj;p-fOmUhdc6B{0l>Vt?&}jONdx@|)w`g;26_e_rBOHlu{m+` z%98nm;uY7JQgc2)II=Pi~%YpIu@>hdp+#|co~cB$4j0QHG8b|nJO_v2GmsGw{NVMAGpxpBx_c8 z5D+IC~J4 z{k^D#N)I!dH;5Dt+N?J^6igF-qW1nQi@yIrg5J;`5HUqQPk;YYys=M$7JReS2b+0M z`sZ9P>xSBWk{G`^mAO{vk7#}>ELECtCZGhO5ue!5I}Qv>8KYt3DLnJi={CstBtRus zkXQF7N&wn7x$r_9eGR^&-MQi*7(a~6Ay2Yb&3kVwv7llodybL@-Rwb<{C8tdz-OlH zdxZG8I14@YG>n}f7eVmLx1dyU_f*h1hAx?d>8B3O%G?D#T!L>UEl`~iH$R^kAccEb zSVPCF6A|#T=_pFk*v*~;q+C-|SKo0xHl%k3dh92D0Fb;Xy zyl9U5C<4=qhyXU9pyb*8pH|hx9luhMdsDXFz)#EM15o-du%y4>-jfd2A_1-2V-Uh{ zal%8qbQo^4@-v4}lj(y(yWKhgeR#(sy8MR}^N-xr>$fEycu>1P=yG0lKw+#GZ)WRc z_%8#1qK3L53r&h~6Q$?ImCn2@IdK!{t4rMGjrG+8$wkJ$etk2^oq{?E^6lXR-EAX2 zV3aUHACNsju_$3+(%95tB?RzdhED2SDNzgO)?ynE2O7`gL_axAqzHA{0|uQ4`(wR_ z-jSNpFX%t#WUFLo!M_NK8x?%_1M2Fvz}ay#@AQjS6n+925}19WsEDe%pC;;_T|b-7 zijk_~@EoN&-#m~UAg)uK+s=ImSZ}U^m{gim*YHC0z^s^#Pyp2SNXjc{&5JELSF8rd z0}gIEP@Cvrkd*s2r|X0I3sa;xz}~yw5;9cwmvt8V4cZOttF2ugl;V!N;G;ay>PCE2 zC+B%7flPV==XJ|J;+6coJvos~1;e>Ng~jZ;8fcyS$e39~naXd-Dn_>YzPsWqLYkS4 z?c5C)i$OBreP`mG?bBu>dIkcCbVX2#u$)cYH>xB&zJ2s$W>yUlbeIHSARliicyBE& zc$0``8!HTds0>i+Q5zU00I>5vvwr{UQ(m(qpoLkB+TOOAl3q2(ihnPm;?pL<*j_BF zN~3Y~q-_PLv47Y37-iR{j7=C_-vbK(lKLpdz^{oo>8@_dknjW;(abS+L*%DjYyV8h zsH9T?s3db`?h6rFR!^T4i0S|%*hU<__webM0h{aJ6tM=(k#`TDo&`9`VywbT3#MU* zD~CeMG-((Et=T?H*o2wnTc{R_DYgDo9Q;=YkP40pm^?JI5fiMEML9DaaUV`wcd_d| z<#|KSLLen7(*Va@(9sPHS3VdNH7?3b^_tJF0-#e|AYgTShEZDzGqW2|qG^WOFKi8% zK{L%hKU|z+0{DIF%(uZ*YjmF?HCiNOz4^K}j-H4e zeq-k!Q;OCuu9-N9qA^4oRQb!^lbO*fX@Ey2O53ZN^zew({D(Wf$5miXwGvdrX+Z0j z+(c%PAOo)0!4O-lVTi?O*koYg@=%m}!TWF(&OiVJ^%dV7|GSvdJMY*rK+woaZe!G% zdj3CV5&s*NRD!8a`x@wk2dflQXGdvdZ@FGmq_P(U&S2nMy(R+W{z8l4wTkWumxAuT z`0&?1O_cn}uq~%}Qw`5>UX0>Z5zC?yp>bpfwpCcjaa_g5#w7m|U7udSh*saHm^Z&T zJ2v)|PQMNHrY&8cae(O~8pczLLk=3MRf zpQ)I?ntkVlyE3$Su)v_d1~DqPWgW^BXGB~8{};0)O0pCHCb1%O3;0`Tw8%f4?n%vfBTr_HSOZ zKI0^-(QSf>gCcACFQUBtN$r2U(z^xRQK{3hG{5=efBbRZog}O6Cvy)e%EbDLW1Axy zoip2CwZiT31-Rz%EaNhgD{A>ZDy{9j~f?N=WV_0 ziz?|fiqm8Pvi_%bcwJTr01*u@PQUOZk7BQ?o&;8c1F7uTkYLvC{oiPs^fWN77Xj6< zsW|z-#%QCoTh*4bi_N)bOEEB*I;nESO=I~0Wfl4nr8`bR;EXT+g{j?t_fD=0<-2!? zVC4vc*xiMYiBr9SE3->A}7g6iRDTUu^U4P*O{{Aam#um*vk*4@I z?5&`?ual0eKRVT(!qixC+4h&r5+pn=J(InP=+$7vIY=q{OJpSe{7_nZ+?s^gKy1(!9FFN&q{Xp{Gf6>COb`)=NJPv?Ml=duaD-olZzp{5e zbHlh6vICQsJi*-h=5N>RfBnKgKXA7Vtnb9lj8=r-47&Px^by{(U~-_?QM8U(KCif> z&|+~7Q zF8v6r>sBZF6hMysh@i%3K74sc-Q7=>xxb7i_owR7fd%qAD=ixXw>>xs|ByP4zH4*5 zK~t(RjwVTTZ|Nm{7tR|a7QZy6CoLlK+mf*6dSJcwVL#^e`b&1vS{}tdv2@dNL2;9q z=!p&8(XwJ~^%V1~=J>ye704u-KTU`+!{fEFY4nm5^GuaF zZ00*aQFkRU8W~=WL8WX7Ra|BGRVbxDY4gD-@J{66q;a$eLv&t=KEO;i9_&pGFZ&fh zTvW+8fR)4?o+pH|SquJaEx*oEEvFtUIKFjT-YcIy`r?>kFS(9;#q=s@q3!cU0|RNO zbsG6nEk9cK^LhiPfBkF!xe(hBN{zWTSB>RgI=u> zC>Gl-@KEeSfixs)-FpP1wNE4ShUVRGOAg)-+7=5-P+SE2 zGDH-9S{J3s2I!Za641VBJ7t&ZNpCwHiZcA=^73eIzYo7JEo^Bik?V71cL1(~JffaY z+I2f?fO0*01i?ZrYeonV8kIZ#s5G}2V-)58i!_Q^eP}xq#QvEKy zy8;1(K4?-Xyk4Il1g}SayZ)I37!*7}Uje@A&b4d5?+@1;0;f?ZEU5>a=B=IBpLW*&shs|N)#VP{sCcKy z;ymihAY4_6fWvPa*8lRy{mp?*czMnLzEnHO3SdVco3Qc&fCI7Ec+78KsCF@cjzegR zNO5I~`OD)0BEKD#(6Ip)523N~zyS1cQ}lfO`+5uv9DzU2?!aT<|Iol#h2Oo?T^+zt zq6-;^pXb~Hc2jb;^%r3-|IJr)k_N!DpY6-JqOvRW&bOBXTAzJhCg};&Mzj=NC=||pH z;35@PK;&u)SOSP3&RG4Qj%E5!Ys$U?-0HWVA7r}&1WAj(_S?aPu8&7ZoYP1|AVdHJ z4-Boj@b6>#i>>t2_cSj7Yj`7V;A5%>SOG6`3Vu33?msb&3IVv**p6sHc0S;%=q}Ox zBs2N<%lL1y{sDZ0+Gz#5SHPj%&6Lpo-LpvY0_Xt5Ume&rv_NGq;=jVi6P>EW-B|nn=EBJy06*lOz?+OKJb7)A`AJNv^vF9VDTbe?yYY&@q@NhjYqLo^YxY&s{QD z#Eu}(T84j8HXa^c9NTvZ^O4`qX@n}pO__VIA0vIQ&Is9WiDjSS?HW6hUue-`OFSUI zR%r0u#qT)Lt8q@9qE*wqrO z&-qLQ`YoMVmYBzxvOS&4wz5^{F}jNv?5jPA)yt*j85N7f*fk!RXS0o2btPDC#d0X5 z{QWs%)z#AK@|mwNjNw?^khx*h=C5kvrhJuZCB;#hlA$g~ba$K+F8P>-@gp`&1*E6? z+g>Yv*-x*hl;ORK4=VsJK2~BIiDagj-(XBnSg!>SefNXLw3{IkaXqvT79?O3Pe~cH z04)4i)cIE(kLGV^v_^b0(wp->ngOVYH<`k1YYqt6WA*}1zZxU8aqekxP43)LTbe8x z-*(G`Ygb9UvjTQQXO2zjntkgM?6mpajpzy+N^hGW#lD>;_y z9jN4vc!ud~Y+-o>RZ=9nJ)o*`bSQ-Qqahb|X3b9bKoK z_90(k;5recP28d=h{J~?t&ERRhVh9S(P9wh>XowiH3S;&WV1q4b4#H7n!{*Zi>!L2 zoWZ+lAGC|%6Bb*R^FjoSZ_k7hvkb>uV$J`#&GV_Jz=*3M$};{g{E~(# z-@5oM=a`gU^cWL)(eo}w1Olav<(a7+i`)4ce^A?4J0;*`_u)Br#Z9nGDGaglV!xjj z1DD}S{4Ch}Dx;G8k=(sZbnVpkk$IuyemhAKKpJ)mHz|HI@CM{gY*@sl#OvO053LoR z-uO%&x=D(!RwO#bZ$!jP*_dlpr?P|3j*fFxlMI}e{t$mvd0a(6P`}y)d8}(#nW#+G zL7V1rcYhP^^8JBrM!3(8~~3p14J8zehKi(~oEJPJZ4ra4Qcr z$A&V$%wL7I{5zuCrqAbP9Y3B9c5*%nvLl=c$_KV!K;Put<{H~^2^(3TgSqVf$hp({ z4_W-^4FtHnU`8kKi!DC++wU@U$kyZ4eWH&)aXN+5G|jV8c5&dYik$gHYgMJ5a!SUi z)odGX=9<2qCo>KOm^{aal!AFe>VO-MvXnn3ZVlP{Wl+Y*DDAx@YwBE*GG{Au%g`d0 zmy2;~^`}UUronn$klh=NVUO$fXUoBmxb$M|IJt@7Gs{Sv(w;LB;AXLf0=spnP=_7X zRhp&M+Q3)@suk)q{k^=)kKbesFfV~%O|1fSuk<;Gn7b7EY}Cu_Y3ci!+s%8bjGH@= zf7I>16DC2AgqVRT3VkHVeZ;pv_>)p(i61S75MBhrmuO5^!4dBuxy~XLE$;vlO9gGP z;;ZUX9t^ein@p$X8Gyy_6~ynXX549S<+<0Y_j6 zdM?P&t$IMb-YBfloMg}5o5*s5j5 z6+x94QjU>M zW=dd045c`HI=#3`u{@*~>tSm5TFFVLT1gA75WCZ?KvK;Y9X~!+$gHH?Ub#bIc#y`? z^NT3qS1u*xwkmfj^ldJWNSxE7zDl}5*uAos%dJK%h$W91qW=i)j%;1_?SVtrFUsP= zaBlC(TVe6D?&b3XjidZ9p9>iyRVLvs%H#$QSsV&u^Hv_;K5E${E_$kyrUD&-(pW2<>9sVzB_+LN$|9sRy>g=hnZg47rot+ z|06qD%P#0Oj_pF?_76Q$IZOdJyLbuqy~wJ&Uz3(vOnLBG>($Ro;Zw@kC~cA=84T^v zWM+rpgB8)H;uY8L*Umj1R@6P1>L{Q2cy&6?dE1ya$;TZ(c^OWEUp?>8y1LAp;CI^v z^7-aS|8shZL)&F>c_TJ^`a^TS&R$|eNP0SxaZ5e#i69H&9~Z^wGm006Z;e7432-@_ zCo`OC(emopq<%*4%c*KPUjg)b=0x{=NCM2wbL1nSG>QJDSOcdS-h_k!rC4+ge1DD> zrx{-HS^8c)(OY@pHe?+VjIn@fJJJgu9*o%lybHU);B>g&b}QlA@PM?^;^Yb?m5*ci z{_cj0@}QpvdSn(qyCgH9e2}TLljrO+s<^TTo2vBum2$izD@jL1r9TevMcgGn(GLSQ zhUk-nON(a}-qA zW^gLc9nnUvm^bh1^>Llw{^%ufZ7j(#(VW~V=(J1AGv_|;(6;LYPd--XR9*S3fSmNl zx9FDH=S8zZ6E|9#t|+rRAGlBL_m~S)iHTP`0>-%0-erdnc;Yt69oi{zxaz~cxmQDw zcC9m5WM_((WZqnv)9t$*6i8&gE?+DXXT0Pp+3Es_ul%$ydZwppUbJ7&wOvTC1g3u; zNiOK#OzN@GUDcC4!?G~1K{E(RcdOuXxLxv8QLNyS@ArO@uS7cqd68JW5d(toTIN*`0$V7v>tROH1)&MK41IAJXq3A$f3fN4mM-1pgdLM zlIWBnkhFNKIp(!nTgx>TL+vJYc;aC9bGgWs(wMx3u#GYaKUo6aW_&*JpwmP)ZZTwpRoWtIULa}n*;m{>gH*0{Xz(G~#DL&ZUFhV}S+%7V|8Q@o zXd$*|V$XydLLb`u7I2iz5_G$7^$YJkKk>;UpyT4tTqg+le^X}VTeMx_lf+DHC0B-`p2yprQ&r(_YV5AH=ehhG2?^-y9 zbLN4`jT1KCDVJa-)#|>-SRH(+cUqlHlNC6&%e#k-Uk;gq5=I3XVE$e~QlqYwW#q!+ z2-qPS28Aka-j62^)B<>={`wXAo71EqWJ}cv}*hM{M$>^b3Fd5n*})`%Qsvdp$D(vZkLgS)jilaB(M7L zqmRR^z>}-SJk#KF(oKx!$=V(H+LgP}@>gyg|A-v-U&rA_8xG6wJ7CNezp#QBCFTmL zWd&HWL6w^?TDR&$t4iONPiNx3sY6b@{8s7X>;E#7l{pkIgBzPF`yrI?DU7Bp+QN%7 z5P39-nGEHq*B;fx1-P=PdFA|NfDoXT6i+s=UU?A`Kl z7$|r9|fO=|*MG?JG zkyM2I?Z`xZrp*M zhph( z>;dyz0?Pv3<*U8>=ojE|k2>2Az(j`@s&=L|x7Tsm;PLIQzMDbahcLj>$|)88&TOHd z;6A1<;>5zDJf_ZDT%Spj~5AZ&N zOt>%6Ch3bBB|oX&m*2Lyu`ulO4fJ)~tkcJxFnQ$QK)V1}y{w=q?q(Y~(JP27Qd;?P ze6n?tL!KIVVy#n7+c~r3p<1 zfOznY2Meoej?0mwuEw6NxY=jKw^aG^WRa6Li!*R#9TMsN5N?BEPIz8WV&52DHWe5) zUPw$=Gj}PAy7Lw3+({&cA$X=~#13~3Hb??sk2xB)X0}t|GOxdq7=c+QWP|x$iA6s< zm;TQsM#k?#K302mAaIeYSI|0~)y>9Q0;U7*X)&m6q4fGW*@-XJWwaSu4ibxbOykW2 z1$)nUV(-}gmCVJx&hI&`Rg%y7q1`Oy(|VQzQP0X=ie!bFI`rpXFEpc0f8zedXAN@5 zpp|ZZUtxhu{wX7AABTSL#C!_j^av#9|D@gyR@%9LO`F=yY#%)rjmLxsjU?_7i5XLc zKYlt1^3M!MfC_h@iPk}|33R^3_77iGtC_o1<#<~($pBCLn#lx*;PK~UkZP>!Idb>u zH5_itz$HhWoe+KLHK`MCNtV z?t2PZZ-LlM_SLehAkRLh6pgsJZ$6RW#4+oHhjk%kz`vq}#JpR^LnPlR%VZu3+qq!I zrMZI_4d^fJU$12P%TG4FdyD$vGg)O)9@OA?J`}NWTmShc-!$5D{)Q+BnNPSi=P%D7 zHL`v9c`aLhYfauYd&^k)@Wn=1-Kf6upo9Pwe4~~dd?vo3va@PduifbKj`7|t^}4ac zQ5cSeeLT*&=*w=F5D}p*$7{0>-CK~-3LNyzF$7R-^z--R<-=XGFO3%ZV7I@#%2SR- z^WIp9J!kOxz@@|HP2Dz^_Q7rmG2rW=_@eu!a-xUL;ZE{AWH=J?k`>JftAL%I#a^5PSt>sJ2mn2wLKe1Y^!eP6R%!*HG8&xmv=cUs_ppG%hX8-W+COA zmri@x>9=1cP1UOM&$Dg~$t@y5i_*$vJ(WD8_rLUb)L-){MGk-!3gH*&fi zd>(azirNc-Sa)ri^JEpvsDUcQP-^I7+LyalFXCSKI9iG0IuAV&|U{zmojXk1BScg)!A!A_gQfZ%dUcFrN8=$Ko!ro$^wka6<1fVe`> zLbj5_l-3?R{@VI8pXQ6drc(k`qNuh`5Wn~@%9OlIPcKIuf^}T-SR8?PO!>ON()spX zK*G5Tn32QhAz!uS9)Wh>z_g*X`-|dUc4a_ljNG9lDZrD;LZ>okm1Cz36y~jEKU!ag zl|pN?KArLn)6N~_Et*Zf-__nnr&69@uu>Rv9$q+9a%1bd;e&efP(3`zeQ$uFdav~s z5eij?7gp?;ZxDuXik=-4vJ<0qLBiJDTd2?K^eQ|+P>}eMeSG_H3FlSuV3VhDHQaBU zq*#7`==Bvr^)IJbnoqsXyw{p{hd=7R`kPd`kH~`5Q*Y*n-!7Fek%_}NJXC4UBPWM1KVhlzuN5G2si)Da|LHM8YseRBV`0a`ugveZ&a>@^bwA zzc=7|W>S`ys_@vGPJ%$)n=uEaVkkMEhyvQ{u3>1NPqV_zPsq z)~ULzLS_N%x+#e#6B@*@IQkuO1(+Dl?5)(9O(4%`KHHZe$WD5Qas4XazB~h)I1l;_Zaj()q0#!ZSUH_bC%9-V%uhYYR^B!G_<{e_`iO-ljhvI+p{tYjHALZ*%pu5H3%fFaX6$zANw85ruYfV@vVYM+7w2Ppi=`s`MU6%8G z6jyP*p(^p8$Ic~>^<>U<^YcZJ5sLjciIPjmtbOE&ygfb=Ca_^|YWQY_1a^cmZ^1v37P zb(-mj+TGeZ@%Jx7c172OLpBSTx#Tzm(aOt-CkmN&htwH?$v^>>JzGr83D+w3EcFOP ze2P8P_+sXI;lqSNz1q<)6E?`R$f5I&R7v|4Zz8r&Qp{6<>Lwt1?>EmL!SspfRo@p-A2FV4RD8EQSRD2yaVV!GzHEw8v3qVV?vPU|bdk!jz zS5eIS$`-s0Ha0UM*xYSeaAP+OnH(kUy^6GVvwV8{$*0HD10ORsc$ZiJQcOvA-9)I_BwR`wrcxf}aK*H40;L&LFu-iZHSRY3 z$u#V(EBw@)|5smGLjKM^LPVLIX$hc!&iTW)g)iQSu#!5PKBCBf|!3y{-?yWNc z1M2`LZgt4H(soEC@!(m;jM~N2{iy=Y0;}3l6;sE{PN6*d_+A~%Q+=(6W8AwAL7RrxL;)BW@m~_kj<#)oSK3|x^I5YD{{0o z&%mz4K0-fIw;RvQHc})z)j1nkajLnQ6OWk)}d3 z7vzrlvU9sG+o0T~nXXuAMzPPneYJ$}%=hhr`c&@&fTv4$gKF&Gumzx=y^62)M@2!5 z)e zpduyo!P7LJgeJIR;r?|4rx9_&Sp0JmWG+R380F)j@6M@Vo8d}IcI6k68?buh1{z+E z(MGnRcy#EBWEoZP5Kg_Sj=k^T;(|N-V|RlF^TH29v%CDGZv63|68iu1z3*pM+FsdC zsEG33SjLGxQmFO;?OIM#XZ70LUV2A$wZQ!zGg{$8V)nQP410L@olS$wX4tWwSsXA% zNYUCJIKpF9SubAZ?WH(?j3v|!rM73%+Q~NM8yvDDtsg)0b%Hk171gXdM&RuUgEH%f z9|Ok^xbdUv;>A(fR`32e!})w~?W`BdY9DA}eAsQsFDK^_cHh~3ck~Ws6Z7#au~}sl z@a?9g*W@mu7CYaV?F?=5DI5kBgxPJ{IM!K{#MOTeWhOY-xLHPJ97aLdzsAVid7uaAK?2}@y2bJqe3>K4VaPwTGlMjc|UUc0ruqE~}?+zFV1 z`8dswHwCMh6%1&c~kxBchk536EChGy=)nyOFB1QOsR1o%z#jr3Tbq(@*DX`rq z{C+&NN=o^-C9~Y9dM*IVAQ5A9@8ab}X(_{ig9_5IBb8h-H_{+}XDSr@ zmeTHA19-NdMxq5074=qNJY)Y)IIeY2vFU98zJFFf*CV`nK- z;jcC&{kTJufoP--yqc@=km6pWmFv7^Di&|gzod*^Uh{rHTS=YdETVs}%BL9a)zNtO#=hIdRHx$3 zM0-ByIay9dAsOEZ4T%(1ThML>TfEf}jM@o_Hy+W5Ntq7$W78nU5d`q=+YLrcC5=_#~<&JGPftXtX*zUIdqOx+%MEp&9HQdqbH*x8F1A<%~2}C?fl9tRMp!irwQoA-3GK-Rd*os|L*JTFltJH>t@XipEV{ioJ$Ry{ zoi+2dUKIINsB3yv=^sO50%?-Wv}Qr{)n32r)F zvC`g%()=oLsXNSuqPb~3X1Zjqnl3Xxantqz(jX zTbUOBe^(9D-mNvuuwXSoi@Ri4 z(zf*#BG0T&dLprO*hM(TEr0IbfJK1=r=(S~uOc)J|G`t~9YiN*N=a$j2Ys>-(gq<{ zOQSU!%d^Xw-k?Eq9|Ypnd*j%aytH0s$b1sH!V0#3Cihq%T@SQ-P=<{MAOC7k_D6#- zo2FwW{jF?K*Zg=Q9yG`qJ9>Yo@v>_>pX1;>GU^XF`SWlOu(DqoB2$jTtCm~iJ)BfF zdU4k{SNi+5W#7Fi)<-XjPf@!zk3!1^dpB-TZ0?3hDmz*+?+zZ1228U=gQIh8 zmni1{w7UMR+uUZcb(nSg#YeyczGI#3mogyc)QqX za8mYbP{(eMvr@Q%&TghzCNqq!yD@XFmdpaNHj1z);N%Ru|eQo z(S;(K56lTSE{44Ca*ck^k($r)UIdV+eOC-0#Ni%wi{|FcUA_cD&dFpyGEnl#er?nO zCJ$@DD|wx@jV-7`W$Njz9CY-9icnyD(p>Iffwmk>QnTo7k;D2C@Z7mJ?#*@AsgS1K z$Et?N^pW){leVM`{AQ8;>i*p*dpxVmz_rc~8UC8Jy%+sIy>>V(P9HQu=8sfp@q29r zn((_dI7~c&|JXU!E@#*ML*TaXhB1K{)7V73D1dZ&iAIpZvQDBdSML?yIg>XoNE^nv zd~7O)ZNH2@$LgwomLOOXQDm<(v}YNs-)|JIc1KMkgE=GC;Ym9bXV11KpKY3R6Sa)V zdN;rU8;B#h!trH!6QkZTpCqw+kqayZt#kykeVMiPIJi?Omt;#Cvy>QhWLy-t-fb4d zrX#e-bA@AH@;dEz`%j(Y4y*F+KX)Cr&{Yg^tOdXbb9l^s^jvMKw~{IS2EMKvv>3V_ zoY|l0Ew=lN+2_(vja&_USs`0c%3VMLl$uw8%}4%QWv#C@3@v91Lf7D{%Qov{7p=#Y z7OLS-8>&Bo8lz%_TlAvbRJ$) zGR58R4dtWerZ^mU&RfvrQl6hPuKT@CV{Pwr9+EuTaBLy90aSDb(l;44Y;fqKll@8T z`I+qJfEO5BTewH3Vsc8b90-~OzzA>atxT&2%sbCYyS-tEFYd!%bGVun)ZvX_VR_v) zVx($=9~&!iAS0zhbcObEWduM3N2~7)60ojK^DO=3&!poNVPfXh8fE@_l_N%p$7@VXSx9vapbbi#m3zA0K+O7vjydJ$dBxeZo@*MR-K3W1!v9vuHEf%10&pH6UM;~-^yFLQhfnmgOO4RIkn_>F)5c|9k~&m+bPvL3j_9~ zYS}Tm5$@u$uO;U|2VNEe=%lJ(xS`{Sb1+7OLv@t%J-91-W3NwiFqhpMX?9V9VaXeq zUsz=|er+lyG{@B~_M7z}DUyQ)rF-c!Fmv8w(^+;aV`g7IzA zmyb@!Ez@)tbM(mrk*JU(`X5zhiETam74+ z{LK`WY&G6hn91o_rjk@LS^j zt9ch^;y2&l#|4*$It%jHYyqZDvc0%$}0p^ zzyoaEJtGUR4JgOoeGWF(qQDf0EQBZ zl)nX&&Sqo&d=;#9y8+OO=R0kTiv6nH0Y|`hZ`#jVr>{)Qbfi*ETOB-=b8+A-qH48Y zQb%rPM(unx&A!aW=4jOQ3d0lR2thN7VgC;x4>8W=*8rP0|5!d#?-d;!i;zCZbLjtZ z`QkSGa>q_0>mV{qW)@wX5XxIxr9|U0hbfOR^IoB*D zBwj7yi%Y{C0(Np_VH|9Eho7V_CVHF@^`S{}vuwU({Bg9<8-w4hAUF(GH)cpohePBm zxvUv}H3SzDU{j@YqF>5;HRmx#lqaK{(Shar*SlX0kZb4f^}g-(tNKikk(uA{u00WbB=XlS-WF30wS$LH)zX3l% z>{8X*r72;GcIccBYIhoy-|7#Il}eFiy72 zP_?PFB+%D~cDWs2Up(hOFw4;lrPD}6a!H*9EP1si$xa0wB0*o=i@G#QZIOnA;KNzfe3=MM{f?v613lx)I3|{^By}kLO12@uNj1w+8BcU@mT!G`LO8#yDLsZz_*GN-@AB`<+IQB zr}lcmQ}kVwC9=!HcQ&1~9xGJO3l!x>KccYR^q(K#Y}bb9i&e$|lRK`KQEJP%LQs8CftgTkid~1@!v=Afv()%9{ylx~ zFFPMKRIWCiBI{#brjpB6Qk~C}rMR&kIx&~mRB)V=an?N57Sn3}k~d2bZI7S&*OmM6 zQpf|>#$&fYGAP|h5_`rFBxf@FzTn3`>I*fUA?NEGBNgjN{KBk%62<&u_LXZ_r$dyj zrnOuB&RY%Y27rn({yU%zmflM||EP&hV^&6J(_ViDPz|kBDGfZ&d^8^mU7W8t+~yea znt!!dYz59;$%u5AlleBfD=1j$ar~m5&**kh=fHlWCBEue@Qh&h+w$6BNy%IaE95|~ zs-c_161dd;4%0a?+V@g7EUD`H)v)}0nztqwbqkVKGgO=e&3R+I5Ue&Gt*cFL!6RNn z)}>rmiJZ2*Qkll-`7AD-HmDqf)iJ;A)Fma?7GEGHmt#AQYQ4C_kjG8_uv>dzcBJ`$JTKs zD4hy8sB9PfR3B}al5*+UJ`WTK)0x6-0I0&zHe!S8NI33=&H6a43| zQr`!hkxC#Dry^w3&X6gJYG#6tRk7?x`v?$9TCmLkK)0PqYl3khX><7;VK=+b zV~<;MtDc)#wB^BCeRL1=%bv5S{7|N#>|z?HpV}=xgDhGa3g$>Id~$bNB#o0|{xe$= zrThJAR*W(w-K8{@qu7Y|p&I|KUH2_VIsY4)(T>BkG-!WD)Jo4(X)-`jP!Yri!oZXWGpzHiI~cQ;TSUiaQ$p))*Mqv3#I&5g&D zUA5d@TlMFQ-6QgDt)2r^hPbrWO;F(JlU*kPL&(c=eJmx6X#UmHpQCSv8&h?g!sj5o zRa(7T9QHeBU7-Tx?GRhGd{BL1{MOZO!@L%klpl+K47CE`_hG_khq-@cVUzzWuIhmR zvYjXSK!g>uAHtx0KoAx9uA7G#s+ZYOB|Uo%oGs4hz3{~Vl}Y;Pwm73`W&)p2SVDx? z;q%C9G%@m`Kxa#L@7(m~RROp3jYlG2F~IfCkgUKIjeN(Y1hu96>!1mqns41Hc zlUu;i{jZG%fBWF&ZC;IZhPB!$&HuyQcZM~Yt?dRBP!K^8QIO&&qEs88bVUJ0K*0dg z6{JH{dJ7-|Hi~rV9U(O7Eg(ga8j28lKuUlBp@tF?&dSW*Gv7XEe|yY1f4=Mdn3>FF ze6!xQp7pG!-1ogq{gXFVN@CZh{B6uud2Kr4Ut`a3bcP!qufcTiki9kz&t0+&7_|Vc zx&sQ*aF+cZkRkLMovOdJao0m10)OK*u!X99*nNUgI2n(Lu$pT-93RWAJv`O1r+&3m zWyad2=K>NY4fm_nUvZ=PpxzT72`;NGBNgFiFBFH4)uv@l?}X7!4@VCTV0SCw(K6(f z&EKb%53;x=J1%5mkUh-Wj8(K2bl+%n( ztYsvSW&O2cxxzBj)$9jGMlkQJsg4i)Ml8h9pBt;K1ICk1q5`K`^J$}xheThs>b=8B zO84!~wR?gbi$R?0?|Wh_p!PMN*Dy#nzT!-&(DCT!Bs~x0c^b|cEJ7!vLmJaMln{6-sqxl+O+N^YB?ICfWQayn zCX3Z4Sm0FFX&(h$M$4^7id}9FW|5T2bPC&t)Vii$77=VvR46_jGWGzvl&h_tFZSRI z{$0<&_pXyiR<{?P!m-a;eSc8gUVV-j;qYoiY$#$-L%O+f;4((-4rD zem;7^|BKf1d;IF#b>uuKK&&iIJWaR$_?sr5j>Lt~;Vn~JlyQx49D(PtQ-5 zu%i1S3@lWW==UQj^Q<~`6*8JOc6#m+{#mZjIj0jtIuQ4PcK*w@{XM!UwtM^bC;M56 zyB??Jttqe0w*?5W(gta2X*;e7b9yv-2zeWJfLmzn@?LBa6(X3eNs1(!)+PduQ-oPA z<}{z`xnJ$${&n!}F9)v>h?_iXmJ3wA`F}%d`x2bFm=!}_pPyO`oxJ4TmwgZjyg2VF zQ7rqfzxOMjSbqbZ0B+GA74W>e&iY7}%1lJKd*;1>gtzkKBZif+eY zj(UKA(+Cl=%zbQ`cR0`cr?qcDO2Wg;U|iw_w|I!--FXKX)$6lP@tX!$^2h*A0#g%G zu;I595DC4wzWn;-48IpNfS^Ni`@;@21wtZH9S$gDotKyVB|XRAP5&SNx~UGr;70y6 z4xj$z;(+9RcANoAkMMrbrOH>y z0M!UNZbzx;TQF$S4XyoFdN)227zCThp*%E;|2%3Z9(31ze^tHn&nNSZ1C@&stqZ1O z6f+RI;bF6qN4w~j*TkskVI-*wTK0ZUPhCZ+p8RWIb1)Q&g2a%uq(B>-5ypW(#mB%l zT&n@5B`xLcdh5ovjfOJ?(i6WXZnuwsL6<;l@4Jmzp1v_8WkB zeRy0PwIh>wg5f7y00n?jTdM8NGin|S1bo@OY4g6|s_}5N&#s}OpO&Bg>i2Yp~ zSPa9!CyVkDt~r+CvrV?{m?8GJ&5Sw>M+1yL3&a_&R9YY#XC~)j0+O|Ij`*lwa9g5+ zj{e8%y~+ee<(eBupDZ4_P{41_Z;9$EHPVl>$gpBov~jW^v8izJJh*Qlbc^AI{Y~sq zAN5asSgKuEwkiO1$@C9j30=S)eRJgHQeRE*y7dDzTI3e~vuE3wE_;^vAv>rW!L6vx zH-Zt+Sezg2cmCCA>My~7pT~gSiNJ@=gU{*0^NN3Rz3dNlDwuJa%)Oeox#Gf-M{fuk zENK@Vqg$SueND9OPZMa1f;fVk=6@B;`sbeKvjsLGU~-{(!)Eb(a&GxDG<$H3;JZI5 z4|f<8RM##W5jg`W)_^wcA6N5(6*-4LRfR}Bim5zEwTqSjE}E?{f>XPn)iD_yE%|xQ zUyqvW6mY1l>1+=UJGuXmo+>|D0<7=IgY%ClT3>`R&G%Gmy&Tv&3gS7{ZxgPbid~1r z@D6&(Kn*w40y4xXgS#}U@kR+E#s8yHfa>vAQO5sx(OtaY3{vlh+AE>!)wetwQ0~*9 z)e*y<=p>&(i*kpdl^{ba)UxXf|Kv$7xbxQKFfV{FG84cC{I!LD z?URBE5UEmcnnoCYu6U0_OC2egg=aU@Yea%FW)(|-E8y?H7UK)~Rg}P=4)$y@*kxxS z8VlB4obEglHg^X6lOhu#jz?=~Dyf!eV*Li@Gu-m|KhBkvTE%M&Ng~H+yQ22%Q$2e$ z0^nf@=lM<4lW$lu%i1uZ-=Y#D_9x5Uo~3%1AJ_sMr9};agTaq{Em5jsm?E9rr+OT+@6z{BSlt^=Its=I?E zwNK#t0nXvT9masIHLwsXbWm-Ln+fvg{`{3lneyfR zfXFMwCwfkx4D9Eo@r7{9^1qoWLwnvH(V@T;8uKP~FzT`&*# zMU>|~PSAE`!#do){`28~{mg&c&Clx4VCi`A6 zVBUd-qNhy*8`WF8p7PrJ3E55AY%;diLjy*W!E=1~-P9*x(f1dmQ^H0wv09#5g zo^Cx1Rz+Ij3FDu}@_&B!-`lB=2nZT8O$7MC1F~L8ZBlJgHz}TFHs4TJ21xc5>M9vg ztz8&u3k)JWD3;5O4IBY#{+FnC5XRsMpk|aPOnH+3$GCt0uK!_99-jdgWgB(*s__Au z*)9XgL{1tiN1;LyNV~v~@=^o;t)bc&X!g?{0oL&PxC0w-la8t3FK$pd00q8WimTpO zrQdsZ2Ex5-)5P|xP?bNYtDfScVzke&%Q1nCRWVy*M)e?Qz!I?eG-n?Kl9mb26!WR} zlj-Nc1ZG>6`Yo3p1rn{dCqDekuA%w+5&80g6NkI$T{tHXsGV5rJ~jGPF4LbD66#8M z4OE!WS4FTIGF{i`e&Kijm_be{KElh$=lTW z`6tImK!C{{Zk9TRR-YKmUWelev!BQmkos)PRK3^a46`cxvh>35u7^XtIs!@i@Z^94|fM zbJ+Lx&m(^7<5f4^rlNfl7O+yTziD#TUTj?|rmmK&aE%f=Vf&bUL8d5W{(&dQJFSMG za>nCp|Dx1cZU&9WPqPR@On8DjIyzzkxm2FD1dxz=wc_;-=KGHqrfc+=AU_M7tfvSnh-6I+*_{x zdU-yY-QM)M(>zA^ZmnlohO8X`iTC90=~koET@Rdff>e2>P`Ba@2h$Au?=iY!-Tvpu$Ei1mKh@hiBL+&ONgbCr;ERR%_C$J+l1u-sB(qg^wSch*{}!o97@TjK>#H zB4+WHa(Lq@VUwNaqFP9o9QWhAm|``?LY}zV;W7QWUTaZKdWB789^&|+=6X7Sa-;(o z?$lFQ}(iC;I@fm5yQ?kNO0MpBFv{7FhO zxM~DYqcKjaps;)rbfF@(l@9EzMxL)@QiTkOX$+hKQt=Y1ElgBZ8ea#3UGJLw{O(Us zFb)2^en>&tc0?qDaVF}?_KTr`Gv0clitw%8C6D2iLkj!IigXU zBt8<fifip7|~Su>J8$dh}g>CY8CHZW;GJ$Y=t{TnnIOox1L(eK<)YA%jphKmc-duIVh}V8hs8-wZ?UMSMvbw>Yh4GggT8EEY5B?CtZ>j% zR{{4%J>C1=LneWytxSd%kHwmw@RMFF< zGv8_&Mb}z6+601fA|e^T#U5{uR1-A}4)YE|?-U$qH~#!I$@bF7WbbCt}0qz71CyUmI47vEwusJb8J03{wyskDE*_5-xdqj~_e zeRKKI>d+Y%6`~S!abpZVUQyy{^U|PZL6-Ft2C~i#ZB^NG4!Y%6K#mP~lEWX#G*$;b0eN^j>M@ zD9;`lwXq5~u0vj^gjO_rm{mbZaiE5hQK)_r*M$e&-GrFZ-rcCXJ=;s1N+wmw;!_UQ zI~c#!j1_QmGLH_ia2VN>>wMcoFZwiw0&Os_Q_nb>8d;1Rz2BNkoA1YjCJO;l>u4gc zB}8vu<7ASz?o|VTM-?jffEAq_FZ-6eX!Fe@1;BrE^F76}Vh$aPzI)Cxm~!pN)wn~G z(ZdoE)=%HLCqCH}?~=D4yL(dVOatu8s9gO(OY{{41u=3p@6nCRCw;xV?Ev&{mHb1# zoo`(_VJRxAe9TeFWRQWuJ+$?o=`3_i|9>~OkdazNx3mKy}I0p0F1;Rd^!Yv$e43K06977V z9^>-epWK_FCWNW$AIlRgGR!FO_=4R9m{ zNF(JXx2d-wr5tsyXnk_&n?pt^3Y{QD1moJUJy_tO`JMfTRAV5#nJ}| z?BPG?ite0>I~1L#Wa+y1`HH5Dw>kwY|L|&le3gWd@bzq(RnK^c zMS4Kx!D+8`EG?@;!5#QoaC&NnU9mCu2wplww*TO{-DYfWn$Jy=ytuTj{ki|qzD{>9 zFO*VZ-Py12#V_cbO?oKilDAq?izRSN+v)W7<1}f8pwZNn_4z10+rY6{|2{T0VB6~6 zG?ob~PjJKOYop=|rRXnM5-ga5*{7;Zfwn6|GW!Cm+}b1wzGaqv5C4KjQ)(e4xg#nKBcUlP}*$Z68n#EfkgzszIeD~`j&`8C--(6H4!&25tqZ0 z?s1?)i<}gMi176$q&9jic-N}((DsBzHEi)1@Xc@_(9kE|H~_dPjtIG2bT6)|%vi@h zQc|Ej+B6GQc{q;f-XR%e-CYi??Ocp0Z|&*d57a`m<@*bZB$%1Sbc+??`pD7TuG~!- zuccI{oJyyofbzBrI5ltbefva>YJbx>5k&#K2h`Y4a`}{rWum9 z>uDL5k6yH0MvqQVQyaReL`nOEp{{c0DKSWp5G0}H)5TrIJp$$MB?cwabOFM!{iaj1 z6{O0tHh#6&Cpfh)xYX*4_P#!b;G|1LGI{mT0Sfrm4K~kfr11s@scKBoLyezwxq>c?Yrdp z!6;{A7Z6CEH%1xGNzCM>`3?hILIrov-BEA5QLIEJH<)hm$E~TQmn~Osb}JOt&76hE z7Mhw`LFw1BnW6Npcf2v&(;3W2HXYH#B^w^H2fO0B&Vn^o<4aGJ>xv*s^f&aI%o09$NOr- z7j?bP+>cYulDy$B_n=d<)(^dFN&aHD_mw4z)Pmckb7Z{l>s)$!B5pDCK|<98Q`(52 z7DBN}d6XXzzh>e!%x`_~-9#7jrgW)iWi?4hwn&*ChbR zeqz0`S3%8kAIki;xi`8r7&sR%LIc0m+S1wL7o|=j#`<~cqb25a#AQfY1EGly0R~{1 z?A1MP54=n}CvITCO=#Ni%-N+9FUyDP_A?K<;{Y^4c7~b)bNvMnJYPfe_sOsW!_9C8 zJM5zuZw-_pT0tTYc&tY}nj6SDv2Yb4TZLED#P5X7IEkK!47XX|X}9qito_j3In0fZ z3Y^DShFGh(f&;=CGX#uR50ym8r;3m4lnp8F6KDnelid6tIrr~GL@zsy$|beE z;uuodezM*Ex%~b70NZ=PLG51a#x}X7(|`|qC9snV8ntoCi!?+*XnVs4Mi0l}bP<3O zQT$~GnI88$k;e{56Qrjwd(g!%AdX7{$u_Yrqs2!n719yeH6T5_q;7h}lIok>!6 zvujd?1Z?67dNPr?!mQw-{ew`GZ-ZGwE{F^)Y?I%}c;Dfa+4G+rx^BnMG!vDCnYYZf z(IbLZp#+^Y73qkA3MJibdCHU&cn*Z?QR@4;ILAm!ea@OG1EqqE;T-uN&~@7#HK70m z{&KVW&ViR%8nKE3cC-%0K_k$yyS=v@*@E~X+$;{89Yd!vCGj1uZ|Rd6|H1o}%&ABA1@%kWPS#`tzopbD|L;}RO+ znnCjm3G~TM1ZIAw*uD?FS=HLz+J3d1Ti|HujJlq-OPbRnc&H%edF0rwHWL=iIwHCc z-^cB;)aeVS!5?+MpR}24Eiw2yzFqTY_ zBBHv>OMZxKa-(7DoLPx)vpWz%%lqaD zVcnb3dXII5fEW)YI@P;kgy&;_XN++6qMW6*{hCVG+=ErG4RN9u3be~bBcwB{HYhYl z$`KD($=`pnBt?KEE+*ttUjmMEV%C8}Y&c|u94wexZ;TKzAQs4Mw>TnjuEa%EyL7$5 zRDx%ob#7mfq5czwWR`^Y5njp~sv9rROCI&EL7QCoH->>4RbxZl@WTDcfzEXr>#}C0 zlJD_MJZkCc17=Sa!Zu62RH!<$k9G8ebRsjVtDxqn1@ zI>gh=QV6U$DEGJ&6Wquv`*1-BDdNcb(&Eu|o{Nub?*WM_DariPVsf5w+XMe(#~a_= zBLt-zHVT@1|AWSx{UAT)p6kkEkIvn`VE||U2oC0@d?O>dx#vl;Ga@qfyz9lquFGs; z@;VY8N`N{>DZ(t&E}eCT?2Nxru_EtW+b+^j&DN|c^b%uMk|)&v@KNllKk5VD_#i#i z4H8TA+F)+R>Rda&GiL5Ejb)Z*J2h$RO-k9{GFNLrj-PT0Fkgk_SwxCOY1Dd`BF!$+ zc4)^f6Ro@Ne$!rK|Cu10oE9MxhK?@-xns{v0xVDKs8d`QW7iI+1#%^ZbnjjNVuZb- zcPPLTs{;CD$8+W;>x=!?0KR{>cBg=m02qxKWQQ}q3qx%r#`Yg`vsyp(vDVCQ6#Zw` z+6)S28S`3=Q=ow3A)KEO|L95^(Aycwl)X64HCTduJ*=y_Kbfoc;@uZ!EyslRd+926 z`DL|qDhiB%Q&j-K>oDYmWJqwIFIV<0K5k`3tGTWb{H z*9urCxNd4>aorg7UW6M+Z;oo-p?9&f)~J3q_x6W41zc`C`+WebHyD!pczrl1xtxADp)Bsb3GrdHNp+$!$SQfL z%PJ{uJ02Hio%j}1UNxH~Aqk>(oFBI|^|OC!j`nYKObS6p7ZdeXM-(>}vw1Z_LQxiC z#l$zIT9{AYcBj4jVm4wabvz>G6mQowQO*@1^BiVJjHfu5YDBaokrzR-V=6fD|w&&Y7e&XNwDu z_{wh!)D?`K*6=2$rL~UC^=61Sj&r6v0|72W@d0YE8aFBRz}dV>+-aTG(T-b{ghcR1i5bw`^QzY_$FS^|;>z!8~z`mdC zi&k#E&EWe4m)@#Ghq2;e_slb$gzNL;@9CL1E#?IziSJ*`LrU1^-!m-f96o(TMQ(dq zc_i5Cwc8gUV9}T5RoZ^Cx2-xMZU9=E=O%)Q&gcFW6F_bMNyvc?+mi}{*I+O@RrjE2>(N@`exsVm3{!{i?vR^k$BD-z>5z* zp8LVy#zo~}$))iOtHKfht55AqaOxDe@>@;&+mk(veZLFXokDo6^uFkR+uQBlxTlwS zXpR(+ie+&(cstW(rB+_9*X=r(DGP$vZtHf{07s5I$imRN8%|zQQ~g$=3%B#I_vZ~e zO6APnl=B4q>!+z2_hy>%=Zin`bq(m{`Ugbr223FN)SjnJw$aj%O&15-=f}~MvY+jULlfMtDh*%h zVXYm?(_#PN#qG69?qaF^$sz~KsPIz?mXt8G!-**_ixP%L9As9=QVUn2lyj^jgk}h1 z%b-gBMiyUvJF&JdarpYsbq8|lscUeh!wIjC<#FcT7}~8Yx?3CnDC7Rpf^+E{NOtbv zCyJjW;HAb-X7-s@gTq~f7<@7X_d9=k70^xKem}%yJ*yq94MsPLUd%7h6~{V0bSxRJ z=-URF=nKS=9%nnwsQ#{!x=flOKw`6`uaU(j$hmYMI*gZg*1J1}dP;9w+EZkq4{Cht zrzCnsrWU0HDuEGb7*;<($;=+-lLOU>iHp!OPMh&OxBNj6K3xVtd>w>N1h?fk3Y=Zt<-cH` zONso>Y7m48HECI$t<#?@FN8@3%7Sb))8toW|0rGJ1C&0~=}Oy)H2|JA?eDpwGJjTg zVO#V(@EGl`qz5fw7yP`==R-==ZGj-%x=o+LUG{dnB&=g|i^B|1zJ#9~Xc38+cOy;6 zi>`6`^qXwH;^1|bw)++qwEEK$^LW^q8KD9Ki;>Qge?%TbcJ2DgLdp~ZNR@b=o%S(; zMDy?f`x#5=Cxpw}o`e@^Qe~SaWr@-8G?vJu0#-+XGlu}_{z1aee$a@@W67Gp)*HsP z0T}5#W}a`0aYcIqzaw+ig@7flQ^6IAF7CKXCQex*51nO-OD+B0BrA+PY)j+ zgBPz`I=_1~Jt&1iYd0co_GHgadh7ES>(~;+J9yBoHT$F`oS9OFfNVhpP)VQI31O)^ z3H?+6g}~jLLRN9DdHK=Lhs6MeM%cA3PS*TbT-0#l-p$|>?7j(QT&nD0hh4NIt8=2* zV3CP=ILoKAl|tn$TiXb;-o!Kgg($lh49Oceia6`H9-!oAwfT2%O}SArsLzSlPXO8` z=ek!{&W)#QNO#4Smr_%u+;S%`n8FP&7^8^8pDv58b}+H1cC4av(kSO~?ocfTS9ypk z)XDxj&`%mSPAh~1?^a)4L!mK;DT&X9(K)=)j_mv>9&UM`u=O!UoZ}zV9scWKu&3$Ogy~XJ!@Msy@{!cWo8mnK3k*=P) zl%t1enFzOditpAcdV-Uy^yC+;F*a1Z&0MJ?e$*S_)S6FEp z2W@m8L_J?df&6`F)N_E0XE8Rt$Cm@kRUnCBY#F&BPrbU8!z*1 zj*e(8(0JpQj20E<#^;eENF{F zK9Da6JuSa`a=9}8zdir|-5;=eQfvvPrrE~^SR2r`j(4~DZqTkAR1mu&D8~|8bRV>j z!;(E5E>nX9R9FV^pu>r!Dv=sDAyQCLX)#V;*Mk&RE9Z#rUHiJq5>TizSjDyrQgqo0 zG9nXMl4OJ^Q6vz|Xsv+`PnUa_4LAQXpZO0%qd=1hU`%(Ta8!9+$|O!u^0qhqK&bQz2wywnW2nDfmz4rgdoy+rumC{n z?L5;YOoco614!n30$9PFb#;K|Is}Bdt_YY@Q>^_X0Bi!*tDfpYOJivPY9R^NFHwaj z_)HfF|6+ z0}@-O31AyLJo)!GpY2)T)yMN<_T+=TBTAyR?OvUKTg0vx@tgF8R_$Xe%Db=3E}SJE zzxh2@*6iKU-&CDj@^7bjeITf9?A2l=dPgd;@zU5aho03PGLMvldF>T!JhuJgb&|Wc z{C|X1O@Vpt?D+uJoJSadK-AZ%f5GpR7tA>03ow3c(<55#~Pl@sNVWoQVC=IDQE7&I0`y)#&HK z!QW>!|2GIX3*eK<2)I+f0scoV%*}KAx`yraf7J50K2904YFxt${n#1Q`v`F?GaD48 zcA^WPg1oJ>2i{=@sdD{nXSeIe!9Jg`)a|8^(hq6_;5KLeHmb>fz9K+*#xaT@^#5){ zuNt&%?LAlg%H}cRW7TQ2j=KpZ_M=h-#XRUdL(^e#{3-9J?o|8c1GcNcnMiIMngO^X zSsmC0=4~Ri9_h=>c?F33l>wl$GKoJ6Y(0yOw#@`{R9rF% zn1tZ$;6}YMqIRVqwAU$*a6Ai2L=1rGnaGCx^|1PnbChQP3xIsEm{S2I#{WP3$o~)r z4@?ZiHo@3iV${brr$B7;Nb2bS0K;%NyPE|}Y)=brbPB{7e?U|JX*qxMzXJ=vvS7~D zwr%c>`;*IaNiA7aB}0@SD*`klso@4&`3!JuM#u!v5K*p zUsZznv*21-2{7PeBb(#qWb#1;*o<^&In`WTTQjhtTqonB+bHi-&Vc%xsrxtctVv-B zFE;iFga3A3z8FVMef;-dE4v8Bpg(YUbVLp)Yj@a%tiY*8|L&`!!e8&B0(c>gdIpZ2C164Cy(^-c)oIcO7zoIxc#Imk_lVEfl*KL2q&v9y65U!f@$?XXSR=8=lw;S9~`rYq0zXpKoA7ZEwYUr zp*qUBK(Wn;%}(v*G4Muo(jP;p=3|)M2P;BTP>(g5{f9b8;>&E>jA*DPN+Ci?QB>NfI%=E zySK|had}KmMr>5Sh9>~+!)l54?_9CqHC~T?5B$sYfANzx-0v|WnS#y@%l9OOLuBf-tQ|+!q^nklMj`WZuu_!~_dojv2id4^p7FY%3g~gz} zWh9shMi(jGlhj(p`Bz{?Z;pSqo&eUtF%~Mq7kbcF)Q(UZQ2lUCVq--^YjFbwZ)q|g zq^ISAChPfMc6JLqUT;G0vw&S7yYDs*On{T`*~`Vd3?- zC;JZAKA{yCj4W2wusvRbKqQ`eir6z`lM(xV3*ER`PG5>}N5Gd!ctU@49lP0;-2a%X z|5+wGNU$Nk^f28Q-^O{+#1DsnC9onJ1+^$&6-v1zL@e11Nvr`=1J@Z(%ZJWO6a zf!k)|MaElwoRZVaTD+%pcT|A^w+tp;V2M;`y7-#pvMJY~h4->4ueoOKK)&{Q%p-C& z!|waEz_7${Ol83br@BpOoCGYT+}_o=pxB8(&|!PRFwxMA=5-){ejaYoEy#wJxmET=DO7geqw4;#-JfXP;ao!}k6zeWWC1rKs{H4$y^VJzrVad4k+i!T z=(RmuqC0%hrN_cv6Q=9}AL+A(io&3+(U%Ql#g}b%YHmxoPU(zoNY@8z#MIm?{V+wdA`$d01$8u1JV=6gIa%xei$u7%6C!dmpx3GHg@=6JQrzP7Er1 zAyM||{HH?&xi=1BxxJDNJsaw^Z)s?j)NzQFBMhHnSPaFDhB8H1<&<#=M&#K8Ts&6_ zbwV|iAXR+U6oaQ@KVN3|zy_1+o8a+q(!|6()s9qcp2zG4i!4rt1ez+k-HCWu z7J-D1p41*>CTnRq5s|1mv1#|n*2oui;c=Clx|p}eFNBrgbva(vjxsN8^)U~Q*AbKCc%A8QV!UPG42VZ%$P_V@g9>{b3`W-$5NKXmc#+|= zJ+AFqcG|A(qjnP9$HF`}qwH^tPsL^_4GJag9;?~24Ao{g)j)305y$8<)KCG#URK8CJT9Vb@*cG+TnVssUAT{1i&<_UBdTHN(bg6uAfd4#uv3=|st-c3DuiOPK z62c}6U6Pap@xr$La) z{u*%7Ua$`0i0RdfgG+z1VjcIF``fi4(2e=_mz(2v2nxD_5{`x{qt3!Ey- z3a(Yp>BS-jL@S@?tK-)B@OZF{b-k` zxJEzb;f8C&EELtl1U!xP8{21 zh1-q8s7uhuhrK4rh{O|-_{_WPV&-i(_wlS6`X1&o*iz+})=0r6WamB@+Z2Ax+-aj7Mv&yuAkm@fWJuE{ASgw>ZowWw0H2FqKoLIkW5A$#Rxbm_Wy} z#kAX5NJ5}lTF2`pNkA)H*SCgLeMC%=2X^i*?WE^)6o<{0kzSJN|jsO&)Z`k99`vk5u2_yh-12ajtD zpMHg-|K3&9WMOSqTxXJX%hD${vfXa0fc&7i#L>3Z`Un1~vrs&F;#+Ya!bO`@`&KW>`WxvoesU9s6*m06+O z{$VrE!gJ4Okh2Jxla3}&idhdNr6s|=<44yU0wq2*A9S`%GemBB51xSy>l>4zR#2b? zJDF|^lHtpI_dna-;qutrqtllnm8B3m(&y^e%-CF#JW9AnD-z4MN>T7KAztt1+8W8M zB8MD^<78Fo!km$S2hNJM^@c11zsErse9MWxW+z)`^m()2dn0RXXtr$b+xHcEM+-ezPu)d}9Pg?9ZOq z`SGm0rog^WFsig}hHT1~g(|mD^0s&vU9euwzIEx85Bz!irbO?k`c9a$8gg-t(A8|b zSE8md9$^fr0$$p0_;$#iS0-uVWl^>s2as7qCZR|CZ@7#e)i2M}j+28uV0G+z z{@iD6*t?u_=IxQ;O)ZPTEsVur3@>~$5m9IFF#4n*A;DN2#>HPIG&9yl%Oz=*iQH`o z$rSw7eO$tA9tm5F;%Ig?EMXokt1`-K)kc%DoB%?_)>u8p9OkvHpWEt0wwd$7BOSzt zGu-L4PNY)09A(95ve&TxAUsBD7$1wh5aLgvIp~8}lU4MSsH&4HhRtYY9`f&!7yIcxRBBT%x`Q7osZ^0vV`Rq<`YatzMeAZDv^z0yP*OzPiR5h~j(Ng?wo3X<} z-)DIbEOxeR7u!-cC&nUgJ};GON^HtxwncFxDoDot(vsxGoXt)rbejCAixHYG0nOBF zc6mNCzy92k=d`JZ;}p7n?WOv$eg$k5=TdcU=G!0P=2PVOqQN|O{wQ<)?{ZDlx@7BJFURYPkMPf~wt##Q|Fz8zOMaDqhN03X0M0TSk6;~@;gITme#Lzk zKW50{D5uunLn8AJt4pn=VQ1M!Ou{jl9c!JEECw-b&U>rnR{hhR(LIB?l0MTaE^>q2 zP>D!C`l5S|#HS7GZkaTqQr;PCKKb`E(@SmiFxB7spJCjf>51dP*f;hbQgx&XvU{da z?aLkO5ae3v=*ntyJyCSQDX)--_CBLF-&b^oFg%*0BWNRSYy6FDSlmA&YA{3Ae`2f_ zvqVw?aaSou*7e7iOCRT5-qcQ3$<3dVhjnY>PxQL23T^5??ii}6yZ$ohA`sWwW}J=R zn?_<8Nb0q7l@WCx`ySLW6J4&4=qr2kc8{t@RpOt=L%_9CX)sx7SLC@pkBcZ+jY&$J z>vn9fZ9#&|vbiB8A6O#Sp0qD_w8N2jx@vB~ydH1XN=VeiSp7{sfDzQ_s_uK{8t8&r zLb7Il2olrN2RS`L|-kc-vUUH!>`xp(qe zP=5HV8%PBp>&z%G6EOp)w@kt_yOYQ<4Rp0}C)@pYF^Fu9F^8CEKDvfrrE^EhS8a>* zzN!*2C(&!2)0#PN3kRtv`_=xuRM?#Rs|)e5pJcD?GF9U@J{$Qse{pNxKQU)%Ojo=I z8^@J>p*zwjVw(zC2eHOubW*p}r&AnDI1M3{=bMEZH6~T^V%?@tj!*Lr)IJ4P?%Uaa8#((5uO?DGEnH4eMy`?{LBD*_GsvLiXZy|Zuh z&PU~VNxL@bxV^+-#xRW_`kHZ3+xiq*)-Yr(X5^K#dGe}P9dT)FZw4FN-k0jzHG7rHjE-V<2U6_3G}Xb0t55Y0tHjYg6pu@6$lj~J^x!_;-(f#s10 zefF-MnADOXIS9*#7`MM&3v|7{QiWKH=n=vJ!QXg@~&A@ z3h_e_5|EVcK0;vwa6qc#rh<6B+D%WV+HmY0k4yxtp50m_Sf2(Iqc@r&1?zV@oC~giZ^D`?1qIAe^_mZyE;q)>I z1@tyDp3kKbxZswDYWoJ&s~2yJwc|H!#*)iMoe3Ybvu!(*`Mlxl51>YIhJxKtXBZr4Z_=ks9`&#_29%aJkW7fo4!9p$`sQ8sUU^+n^7m z^=T}jCc=iPF**sF1wy@#@?WfW=I>aw+=mcaTH3)Xr%_3XZc!Nj9s zEvC5HvZ0*NTvA>pUxV?I?$9?9j6)~;+R*N>wK5jBE$5UoJieC@BXj_9F*2w7LQREf zGz$roy zUQ;?8FrJ(93ZYk#6A-AsC2qt`3^$yn{n+gs;(=EVXjqU+EUkOU{irVt5g|4SAr(eCrPAkM)jLR^UNag1~uM zL0;4PJT+i7NE$BK%0IkgbYUc$v1H=-VIjnPZB9DQBRw;@nD!=<;r-%#rbGTHoL>Ij z$^^V?3)H&Z@Pc%Wntu)(UGfzt?r!oNC`}-_3+AL!y$YULZTIlsOHuVN`oXB#g4VyZ zu6*qx4%I(;m8h&z&ADNLm5q!t;=@_HtJWHF9ED6Jw|aX;ci<1uK+L;8c@6SCeYpY0bERbKR(Gj?J1> z?fd#pI*l_QRO)h`dN}eXGk~V=vHN_x)wk=qHR|jvdqn0uv+!l)&eY6$?H!^o<|lpf z25~3l-B2a|#dBD4O#T%Oq@<|MwMTu6L?`>nQE)5M4%uEI4z3>A?#-rwXA@~F4+{>ZbjiRSqB-o;N!zHK8;awPEYqKgKQTPkvjw-ppwKV2L9dHu&z zL{fZdMU0wph2ghTpyZMDp36s@ZbFjibeLA|OkJXhOVyXi1{7RNMV)49uhfR~6-zS+ ze0BU)X}&x|%)M-}sA8R}#;6y;M&*l?VTSqor#9s(GsN@td-c_zKJ2v2bw<~IOv3cr zz;XXRh&0Vokeb?1z)|%!b4P6CA)Ri@ys@E*M#^vgu&RaZ!=;>GcY-w zLTK}pylS*ZqyY4*TYHFBjr9vgR-qBzF^hWokyknS!Ieml`$wQOCUm}RrL&h77?Rod zyY)hM2#pgtt9g^+BMmg*h9FBQyw=of!)(z{K*`HAq-r@u?j7dg^~&KRM19aoVYz8u z^|ZpCdr6Y+j<=DVx@#$xy|j$`-VEtLa_o#qt=kH`qpX0&Cp zUtPO*#PboxuAH8VEJVZJQpFv&hH@!v>GS$!gkc}d->1(pQR{$SQVVRNut;8G-@Zi0 z$U$+}8xwru{%?=npP!*kp=8had1#TguG~n&@V#R`ol{P?_T4!a`jEIxywFcv`QVmw zV}1?iS&}9lAP&hW%rorWF`AX)bmYbb*PRwE6rTyiI3ze6MH-!BZoq2oRrJ}k8byBd zb_kKGo7+vZ2^#7S!hNJa{wccwdpeq>lg$iW1Zv6){?EkoCNqP$UZ>Gqg5&U=8v^A6 zZ5}x{xLm3PNiaCsCg1d4Jw|m%e9cI!xx6#mq7s+G`)s2;a%mG~T#y_B%B8{eXF5%u z7FHS}pzDHgn}CKY5kqhra^%g8lTN}r*b9bNc%Pv)P~Jl$;TlN}t-&~|Y5BvMHCGw9XWczoPctu$q;X+6r!t&0>5?an(3eZS*$?ynIFpr{ z3upVp2w(R|{o)etUOMt6hkk5RrB3#TyNe^%&Bac$SA27CBspXGy3yM7n0b=aQZUbk zTHT=K0lxbeed$YG3OPm%t#_@-JGFB|vAKqLdcK4rc=A9DZ>B2-wG3OTps}cGt;y9Rnl^P4W zSyKi77i;ew$Y$I2k4Iay6m1oEsnMZYiZ0Y1r8=yZ#Een3_l%VUt?EQ6Y6LYaNNUDT z>9A_o9zhX=#110-F8BRD@AJI(_kQ}kz2Dz|4a#+$=Xs3tb9|1^u|LIwre|pE?t#&s z6I@ZQ{4tz{E~$4^G;`N|H)pRO<;%fy(Lldv)IO}xe%GM=(|CzH$b{jGT_CIkPWrwG zG1SAYEJ!kPHSV;4RyCD%)|`(Uu*igoTlh#L0v~=h^u@7OYb2pvke+@1s$*j_wYme8 z;vM$NFzstz6RVrPy(5w$`NuF*=rOuCHl}87A^=16xrNmXb@1ittqLaI;4+SAc-t)VZx*A^+&4>2xs6}F2C=! zdNX?MJqF@Nb=r9T`T8C03)cd zET&&N?9R%3Ny;LmQ%ry_LBwnx%L(Tg2YK@tt{KNJ)4AE+&{i@cfvQ^u>0AKj<5WkU zE~{wX%|{!6d+0Tk+V-NrTfb_jytel;2anUBDz_W52Uv1-4%xIWXM?`jbGgDc?_C189=9b4dE zDS&Vvk~MF%XwT>ax9SIeTySE%+cUapn@*>^8y_v%(G%Jk5R>z7h+|Sp9%EXX*-FaK z9jrpv=D}tBvtf2m-3i`!Qd9W_sx$8CON+GibTCakCEuMb?X>KqX|8cTS%*NbOwX3y*U&%jo6 zBnJUTkT0(Rf?e>~QubBwp+u0kCk2qrMGwV$Fiem~ZyL-Nwt^#x=(!|&5(;`y4|gBJ zN8WccUgY3!{;Ykw??gXkJ$EC9ez;pB`g*6xw6e@6mhPz*kM8nm)z8@0@JD|r^W_q? zJA25g#(nBSnJy~%W8%ICTMcCOh4tddRkV?laeCUrbf4%};3@*F@fvmkjk<7_Ocp=(U=6rj!_)s4d2}hxq&aOnSPeZ6{YOm6G^`Wp$1x%Mnc~Yx><38 zxfIdu`sO}Rq<^|5I9R~P3nyeyFxQ6GBjI4Kb94T4{@2t=)I-X>dEkNKJ_YbI`4Z}w z(CQJkGW2u1l4ch_(@uvlqcw!V6nJ6q6lFlqFigVuMXmXDP=QZ9`1+c8WR>f!BU(CK z!AiYgWUUu`jaZ&)HO45>h@-fUnrg4s0tl#u`+SHmaLcW6$-Oe>Ppz5OCPiACF%DMs z8m9FK?FSz<_#I%0)u%k8oe2{24O=^|X29CsXBlpdfs2k?GGSM?lrf4mrKn!?YpT{M z6aAbl8PuD|;f?jF-9|GH;EcKFk&xcsTNk%Lb%s!C_H*Vk#4AjjaTH|#$ z?r|ZM-5b(HX?gtP7(wJ?azGTBDp|eYowKIM=c6y9KV@6`5Ejs3$$?t=emqToYR;b3 zFuJ!W&}?lxT&-s%gH9*%e(&xd8UN@8IH`^8Y_Fcz@Dwdx#Co6MEh8%{{1i`c1j3EJ zw%q_&<>IC}xRC?DLFkuHANw&O~tl+>krkA|=LX+KhG6S(xvn)ZJB1AW`x#Gcb4woz zH`%*jT2xM7)7LPSVnlQ0L-d8bk^?Q!2LZhd7Wu_!)zNJO(W*8f7XwO7LpP@J;7&4?|;4o})VJn~$RDzzUnMH?)x~FG17qOtx zSu85MSg1awDhq+`#h@29ORsVawPWVKcafx5GX%|~s;Qm@(K;Zx?Fw&a!AZ1?q=khC zw9c8aWXdyY$U?H*6tl0mUWsQi{pkTd*HPUV%&xVt& z8~97YVM@yuR9&7$u%%Z-@tSEikZ5lWmavG%xmSP(tiy+p0c z5wD#@1XEYzXYau-^&@e~V>nSHS{EU1cF&~e2Uug&Z5FY+y~eWqo08_P6zm<~jF&7y zT7H39W*P<~ttyeC({T0F>PLwBar1(_5Ke%v#6PN4KWp!^>kf>dm^Uo#PT|1Ey7P4= z+`uYHl^3fb7-qIHP6@+!x!!BRI3n6Byws*0QgMjVy}Go`Z6b+)lJHp-@wV5_ra9l03WZ@T4dBNab@q=0Gv z9ep~}3(jE3j4@GRS4W8V(hz}ObC+^vc(u|_pcV`D=sGp(jEZTmk)(p|(xLYrQMS2v zYUbNnl|>H}FhIB9@1+B_A6AX+$kapM{@id?gyKI!1cOI&>qYbK2lz-FPx;LGwyNYU zy~47}4;8a|8iYFVwKW2Gn6UiX9Dz9(b*t%zb$yF@GlF?T^ZE@*S!g87#^WS(ZAwvX zk%b?^J75j(6dKh_)wlKMlAtSf9(jNUt=_;?8s|L$rePR_=rO8r9RRoZf=v9=awLY_ zUr?9GD=1$QYnjv9bBWc#FS~EK3!H&6Kz!Q1JT){+UbbU~>!{xAjphbuY+pNqy)u0N zi%rI~h7rOi?^&$5$xG5vAXD1DiqK*H0FN>|ZgnS=%<@;xQP)>9ApkfYiOzt1tW;eXZ+|iWBN6 zUB+N$O^kG*Jnw^b#eLywmEzD=gp>)R$zGYjz(%Rsf~!dJ`tdY&=A|D7;=O_Q^meM4 zC0W$`(B}$3wS;;GE$}uZ?7M+@CBZwH&_kaQ0?BtV@~rWqBYwkuVN;1eUsj+9vk{TJ zmO>~4U$}QluvAkM;R35&_V{pTqe_rXj2U%IYeoURl1nIY+ivd8ElZdsJq{Gr}F(!4@U!Nv0Zm(J1(*@RVc)V`lTwp($Hi2R>x44Nn5*`)H6Ae|9<{xs zq`Am|QuF~X1)r01eygUH1Z8ARsKS%>PL}c7~)$aTN@lIRtYIjp?i z8*$@d(@~)G5-PDJ{|?C% z+FU$X9RW6Yg&8ozvpmsxSvZE7@w|n~V z*lV44b!S*MUTz|u8-6kCIqtLL+?!U`lNYPs(}8?vAAA*TG+-gpnIWnZS-q5R`5H}g zvV3WRcCp=(OYhS+qP~d>4D9(pHL*BlzCzD-YV#6&iDMvFC!&v45%3=(2gB)ACtXFP z2x9$jLM@Pz=48e85>=~x9j|-~TqP^#NRBMcI8UyRQX6B7bl>6-q9C!gFD?3pnUGe9 z6o4RQQ_?It`%+WetV?+PD+zdSbFpEWfCzTU7B>^sEr_8)qF6G_fi~?+zW1sI+@PIe zl`~p7&d!xv7Jm`MuZZ{IyYvkp3uvOX8C$M!1-E_O=}9t(?U4vyaMC1O^j-5iHR#RW z87#r}`MES(<@GF^GfstuE);n|CLauqTWfJM_dDX~7i^neC*A4Nv86cr)$U-LcP(O?UjpgtUuik~@wJb=7eDkcr%|!7$hFpj zO;8i17Xg7Q43dB$%NJ&1T=lPi!9LmY#zxdF#3_5#>C-c+ z@E5D0VTZvBcPaN=?gFY^USYeP=CSPtJ&>Md5E zr)zS#VLmQZcpe?ua^k1#;H*SZ#@>8`wmc>@%QqHV(X`xNQs>d^;6g%u&uyQ)RXa^2 zQS#1~QLXnOebAs=Wov~ijEwW%|F)B!ou*BR;V5Kp^@_L$j|AV7!QbiHA(1ZYfGXdL z8Y_34Imj@&`_;~OHz_q-hEq!hcFLZgnME$wMiewc9^3MD!kr228^AWuRm%aIo?Lg| z>oK&j+${Ew5p^-a>kD{-@KDbSqH ziRGL!!hu=;yw<`JthR8-Vy7{QefRR*IhY{>&lCMXm-%*8sdo2NgKn0Ea6BK7mfd%e z?_4+wggmCRu3AA54qWuS6QzbBVmWZ=)Sen;I;e6nwiVTFd%+`_a4|Gkw?Qy z&$@xr-Roo%u=|977wspJg$khH8E!UTcJk*mCDFIY!n|y(s^qgoCO<#I(vzwHJS)BK z=3LdoO;LFO+jkX$2J}^`V?QYzD0|3&s!9b&nq#;SM7YC;FOisiUTE$e?Rc~WqGcOY z!gR^u(kt@ebl>My``chKcG+f7xL0peMX`n-$XX0$?zdOEUGov>-83Rj85HF5+0)8d zL-TS)eKJ_dtfF^vOd@}J(n0%7b3hFCK%14^GQhHYE;-fg0i3S0TU$P;nuW9I!%54G z$1ZL!kFth#wCoD-rd%oE#T=;0VoKA8!sfveD z;uaNy7H`(Aul4iFfC?7TqCYm@sep@4Zgp~O)*@Ed0NzsRyZydchZ|;V5An;68`qyf zg30r)BzWtEg6h6Vi0PUw_gJJiAR~83xj)|ltXY%gWU9|N-j1ZVv{jO9TGtbieBR(h z#jU}ddAe!a`o21r!jto&Gor)OxOg*rFUndEA|rK(!U;cYxY=Fw10y)WHoZv8;`{iL zEW)~lsAyFu z`_W_wcI@mH6wkKXMCr2YhmH>~Z1yJH|upccbCzd z_LQ-F0YPg{c4DRv;oL@t_@;>XszB5CLo@OK#BBMK%4#o4Zl)m#pXK ze5V*4Si)Z+7t@74L=%+ts0xJ%d#E@it85Zf5_;Foj4;p~cQGYgiZ>YIGh>}Nd4M%# z*S&fz(APV~XZu8hU`dW)K@Uf(>m5KEO_MQ!%U-AF_yYr>7ProhYSDpBa6L_74YS8= zMD&#icC$U-lyv`)_ZF@9EU`XQTmpHPVCt6Vwz>usS9*4vBg7Z-KT*3MVz}A%$pAG= z0|%%}b3UW*gIznV@rnA9+MH5pMzbCRMPu-r6{i|`fd^0y0)dn*v^`FnI&h!P61=lD zzM@x72q)+k?(%IU5?TYlua`ijMy9s`7IW#LZqD$f9?gaw0O)2D9nnd=Oo*s)eag)! zJ_54!#&4?nhg}5wY-Uae`VT=4Rua#+P4ON$Qf>cGjkL3TtKE_e0DrdVH+-(+bae2X z63<~RV>oqFOn#u&$I&n87FRGNoH$%D`Q$k9*jnyF=oiWIxnYFS(g4R-(_Nx;G7@;p ztN#3*fzP_1tSKtKXHs1KA*gj~#u;btLm*RY9a(~MZ3fdmFxW%8m8)w4FOA)N=Yw2q zX8wW1?Om?|37yJ7(MqUlX5&%K02aCaVhs`Wu;i{udpCV2t8{4%^$DQzO7)BYv5*!?tuALBga_Hd+&~ewFSmTtbMKTOM1-Aq^H+M=prN4jtuVka zM0>=bYh3{L}3Ym`+r`LAzpEsx&a2t1;0GeDL_9;j;Tf8CO(cG=mhj zOFuvNmU)~)Ab^Ff$E*mn+%099$(~d&XmCFwQvJZt&;d(rl708dm^H3H0dxOD{kcu4 zFb=NotT^{DOYm2Nuy5+xu?zrbPW?#SXfz;Vx4n=g^&zRVo!6 z8`Uql;2sc`CxL$6kGN}a==vY_0NC`C&~Gx{O2ay?uQ@{@x2lMr+ycjM0a}9rF9F)V zA-X*GK|0|$yWuT`!4eLv>{^G=2h0=zJoMOgm|FD1v60$-tbSm!fam6Ih!5?`++3If zcwF|Rk}i;&$R$)qn9VUYRL@7SfnBt|Pi}VgwY4-o(TSmSNFgifwM=M-2W+}OCR(0E<}KNM^wy-rlFFAjC!4+s3#7c{t0 zmK)%~+^wRP7W!k>>R3o3CAz1TnX83?tSWuz)rvw;M8v3u5FQ}JY}K8?7gd>Wo;A|w zdC~3*eo9~OHN+2aVOTuUkCdR}mFCFnV*q;LQ;)CuPOLGlWQ3XOt9JvOx-b#^~{2T^3kxN4M_w|%+TnTm{@h*5p3eVH;*)fY=CaR z0o!jDlLh!l){;56k6fk|Mz1|iAULk!22ZKiyB_GZ6D9UW1`MB%(%Y|%kd3u_&NJ8U zB*0jm7?n8kaTzOlQ(+csk=rc%xm^i^*~fz+8WYEcriRg5XADoR2^+ox_dNH>2MQbF z@*lyMl{|Mx9tl0FKWbO$_|`%ukdEJ zN`eYrO&+L~_b138GoAqos}?LTX5@3Tg+}-+wjZQ!Z-i6fV9?Ems5rxs+L8r)ptcj) z3}8lndi-witB+F!x=Vy6>A(`8Oc4c1`VN76h6J(`a9G@Uzh3 zPG3{pnT5xXsE2KxkTNx^RzPQq#-;XDJxg*OtM0)zjuvRoLc>k?5AYp2d>R=4GlH&h zZN1Z*)ru&q3S3PBa5EtRHmmHtWDhsvk={OnU9svd)M#6nSTmO3Q#fr?>QxY9!DtVU zu*1yE)Cx+~M3z`KdGamJas1{)4nhUK9AvVYB-;z@B_6dfHgB&Y!fh*~Gmn^W5Da*jU{yVVSZa_W2 z1io1yI#omY;ZVTqPaIw>)fEGxY5*diZ`+3`tLf0?RGIfto}l#sdrk|t*F}X%l4C}B z%qRhM)H(CiMQK)`48?S{6iI*HTRD1ocUdOsx^)WuGEGq5$Y0(LS4BI?YgC+Z^?r9@ zcNaJq5;%zz89WuZ;JgR$qi1wWE|A;K=#Nx-jg%el>IEe^ji3%~6J*>FOL=Ra<6eN_ zJ0IzwKKwwF*hJcOL^qLP(M%^kJHXAjY}k~va`u2z??-2j8(~bZ61Q_#-nLm_%L$a? zVOlrgs92o%Y}@{-eqq;+7(qm@ROS!y_9O&WJ!wZG4bQo;0Dzhc8G}31VIi5UBCe)U0i1YT;HH27msN5 z(zj0qKwH@7QA9dRJ4>DdNiAp`8KhI9I?}r_;wCb%$1Zz;djcwX8BQfVn1Z^0a|6mq z(|K1OSQw5=fnx}-06P6bVlOpRZLaD9V;aSS>&D$mkT*4hm-$rX!&FVHa3zV48*!|9 z!j3Eis_!XL#&6q~4AK$f{>qh6iS^CnaTXt>hWk<>Yr5cQ{XJX{^L)5?Cp}0o1Ir@< zcmngm+6okDcsmXN`fOMlM*64RCHohst(42gV50rSX+65L4IYjthN1>L~8~3hfi080x^3rBVu+4+Gx(8wrdsx{CV>; zoU}d;6@YJ6+~usSTHz&AEC(Wl57kIqz@jS+$yzlDLz9}m}R@f z(%#}G2S80jony>&R0qE5G2R6=1Sv3&A<8_PwjeXTaZoW$&sLRXxf_l=BQi&9@3yQ( zv{$Dtnk-PqkN&h%8N>i|37!K%-@5@SRKKU60QUp`?h!z$V+}&jITd9Kwdf+hNsmaF zpPIH8Gc79ror5%ND~LVj=3Nn*$wCq}lA2sjMi-mj0GY6N&P4)IWiCf(Yt63YGUMqC z?Vb@#P*7&xSJ|Ny(uhOMVHLs}Kmb_k{LZfnhjKNbVDFC@tgb1yJMwt{wjlb7urioq z-UCJ=iW&yNI9v<#w~AIJpZibHIhA*!(cHO1*5RhfmQLk(wY)QK^Ns<~Qj*!zi7%H4 z;Z>Q*5w+&SpjBT?7gY?d!-3`#VO1f0;bK>A0-uIxC@@OKNHIRbd-Q0y`HWXT#Az6o z&g?+hi+f+qO%7-kflAtV(8ozKjGx!&5z=9YmGQ)&Zae*|QRCXE$gI$-iV^bt>_BY@ zGxubtjH`og+vUx-JX)SEN7(70Ia;iQ-j$0l#AoKq5TcAIWR)Y;t%}i=@CZQycv7Oah8welWst4;Q^TLfO z{y?7){(%+t47z-{)_A{s8@PqdFnb+`ZTN!WU2VaLE1T9oSb9axM$M6Xwx#pwvUM4ls6Tr%SJT5q(3(>!`Xc_c3bXBInQYJRyt z4r3Hsg7ga!U79n&sLJN!QYLbt*x+#EdJA z9$bhHhIxf-xp(`M%!nO@U(EeOgXVBRmpDv`R!8>Pj}$F`o}D`E@A@Gi9aO^Y7}c+V zNpt|ZB&RA;W@UP@$kxKz8>1_2IrL#ShFyi2Tu{mA4J#^Ev|3;s-2k&Mi#Mz=r=7Xi zU11X?kFy^OCLDk2Ocbpk1!4%y01y~={v~3UFEuc>g>%hHV4rF6$83S%-rCO68$?64 zw@;bg(SgA{mk!fsn7iFhuq`%YX9Gs)@Ao_JjyRs1mvdb{>}FaC=|1vve$rDwHwoY* zCI2|t@O;%jXc&^q_#%F2`%8=SUL%?i7@=KPT1oC*Djo5C zUY?d68qYa`WR1r(x`E^5Lmo(YmpYZQNW3xZWX0+D`YKnr&rZ+e40-i=HK^5?fX&?9 zQLsSQuu-0i#wqKykl(b&`}uu>DmBA0cYGVB39hC9z2zxa$}O6P%p1p4MsPTjJ}yOA)%1r*e759 zFVG(Am*S#aHq4_NrdA+31`Bc7~rMN0_UoRq<`7rRiBEwuudr1;|xK zy^Ll+8~uDlr2jfG8Oc&S@R-ECE|;EGR!fpH;~M29%Nb;=dr)YKcH_rn4%$VCd)4h| zNkd7isS(9@Z0=Twu79cSOPYOYyMtP>sKgo?J@U4Yrc_%WB9 zLAVOsgI*TP!T-bI*%N32(gXG8K4@d$%kBmL~bF2A_ z?{)z~lt4Rr>y2|T*uIVmMZaGbpcION0;FGH5qusW4VE}AD0b$5F4bSW`JdM+6A*(2 ztT{1Ui%dR{<`uYj_&>zQ|F@i_%N|9FpodG>$ZyA7jX7M)TN+8dw@D7q;;^n?Kg z!J$WX|L?2*r#Bnm0>rNlF{Vkn$hNExTlqID?zGHD`%>RJUZ6RD3j-uxv!$`WF2xM! z-f94ytuxu- zRPC-=5+TQug(%*Rcx;asb@tDugk8@}y=E6F*@Qt~cxD=QFUK^RX1MLFSm|!9gFsveH*W%K~6Sla>+g0W#T#IkLbJ-zNUrQ9sNa zFtd)w&VMopOR*#Ng#0?l;)TtpKR*nn&p&?9MGj^vvjEE4OldDF-B(^|Y8THt}-7f2sxQY!3WbaTUHS7uGgHVp%yx zv%3s}tJj42&eg7P*49Xop*$mc)v{Kpt+6H~*{e zh8;=U=N-4NW9m7!&@__Xa)-;*^y!HH1~|Sz;(;MMp_9AdqRGZ9;eOzTa^U>m(3)@D z(3th&)8T@cqMBP4-YfE$%sy~ptzM{VFes+j#fdI%J%a!`I)6*&ao`xB5D8GFYtStP zFj4{}6BOvY{qp|$XF!%IbxMO1Qv+|3>MdO|b26|tuAj=a6_th$&CIP2B}eC0X4L?Z zW$vYvW@eOBXi93ilHuhfVhC~!rr;K*uytcFWR z4lq&iaCqt(Adl2AXyg6MqMk<@qxOy)Fl*G!pkTA!w%CQ*EVeuXzH7)+=rlTd*j{N6Q-?@S*=pB$8_K?@V39=0T{*eAICVH2_exWFR zD8E>Loj$~lt-3TN5VT2Sk=`b_@yC0zXyJmJ)LR3Qy{v11HonJbQ7#04Ewz-EAPcQN|fbo;F!*b zup`eJMPDUZ#N(9gW-zzo?Hm~Zj`Hmy{(rx6|7NX2uK%9qHOT5jub%>;-aKLaEARF5 zuNfZ!g80#W9aLPZqfMEYa6(MU(9OON7SnHT6Y zXjK3lKeX98ZL~Sz^njAFboI_aa3uQ69APEOxcB|nA|rT@!+3ML^h`H;os=A1*!OJc zHOSlS!q$J#PWX$5c&PS==Ug+}sQ54crFm**FOHO$6pJduTohyq7K?YK4aBy}I(rsy zhrSZ^1d9aa-kEkRr zW8KU?>&1m;vk!ZT?mGS3eMVE+CKF&t%g0N6KXDm6^x%61V^S@n8XP#4iD(kdOFOUDq*zDE~H?5!*C6jgdSpC~*PR1pMk(|EFKg zn3l1e8f}Of6%9Lm>_*_{ee(;8&xV&jb8rdo7^Q&vR^0$D%#Li~@n2sV`@NO904fO2 zffwxebo!*I6!|^(>}!RJpf(o22LW(+MRleYRR7wT5*-=>;Ene$0xg2SXp2W!fWvBa zScTXWdsfnS!?5`#$~~e7^SJto9sJF=AtUwXq*98bO>krrarjy^;1&wLW`Y=Pz7X`J`bINQnP z+GZ1g;fHIP^gfMGw5`hER&ODAFmBIXEoMC$+?Icm^fw&G-q@wL`#W|7-lS;5nzF#0 z+a^IfUvHgQb1JcDc@lUEV6AayBY!zaG2noc>3l4hYz9m9u5nML^=HZ|kf{?_9DJ6p z5$&c919KU2Tg(31(tmdFfe{-qAn)$xL!K7JPz37rCtwjK#9t%C`N(0w@|wQg`E>wj zc<*j;8&r8`$@oJuKU+_tfERWPhkK=v0-r%O=ZcEX%w1q(M?8#rB z^W*Lc;3RD~8D^6GSb)j(&op1b|Ca#LKR40y4=hdQ_+|-c zI4H?sw*Ezn2V&zm0JQ*c-utUSR{pm@rz2^$p93xM zSZ#0vBaM_y1AcjnkK7WE>S37S8|04P9Wj+yi+Ffl`1X$cgYcKA!glN1`#J-6dEb+JGwU`tEn_mc30YXGR_s%lNwBy9Laq(@RbOe7W6MRKYLjEJU;l z1mFu=Y|5^^-lRNT&=Ce0(7Es;?>(4f%J!F!*hg8(C@zK>(W&K@Nmw2q$?Vj!PP7h3 ze!TWj|amhB*RSF-$JNW0NXf_ zwqL69tKy31xH$fNIu3lJrGwI}!Lp}ZS z*NZKamLXnBAZYG}#|7wyI=j+iJJ-G+>>7=6@XgRcU@29X3V&&Q>z?trw;f7e0m@-V zpLrs_z4ju144+`#Jz=UBk=)2{VEFgq;aD=~bt1re`rN{!C}Hzlk5MkF7)h)n5u7L^our*Tp0sMI4-0j5d@eH&Gg*Pe=m3+xkr0zgAHG zcV>4B7<7Vqpek%1uVM1&9eUfDstX#78~YDp+JEu8KMDdnV19@3%&{!*$=lDGk@uI0 z+RKT7t`P$A33n$Vr((+=S9?yXlcP=pGjlJ9pnloS*wp|lP`q=*jv{#r7<3~jxX%7R zpJQzP*m-@0`rdl3dzC1%$4_~LFTZ78J@asCUF{0&#+%Oq zFB^La;i#V&Nyy^feCbqiMcOG~q$$T)?ms63LI*=0yk?w?fUsq1f8xEL^I$eOV9UuV z`I}j-j#5&M+PcU|HhU=d&5wd14;Xcu3)rZ)NW4q;<>fwj%~PO^4|^-mZ+iOQ9zdSO zDkoW=_(`^Q{Vs5KNflU2nL#TI(0?gFu!o5t(Ths@Xx--k$ zJjIhagq=eUcyC|VLuSULV1*IesyFAouVh*TQO2vU*xSk`lx5rBqGkQ8%-D$7yDkte z%jT><1+B{Zly4UOX)Ua{8)NTIhDfwdjRF9Ec+F6g{Ld+_nGbveB znTFla+V=L(W>?@YZ!QubMrHg@qmWc${KB-pX+^q7rdsEZ`?dWZ4n{jsC3z<#{k>>P z44M+p(Gr-^b z+i_XXd3ChEmdZ!dG)wjL>S2$(lFM~A6z-%b!&<1Z+E>iQ3xQf(c1V-k`ifgmwgM-= zZUqXTyW%4}n{e(HeKL}3s__uv6araRcjaH7`cJVn3J!!aJA$>B&io068Lx>;E5d;E zDf7WMVkd<6W2(Lnbc-k_o)ghY@%(z?pMI`!bf3wBeqE3mlbrE7eKj^{}~3mec|G?&58O(6%@86~)mI1fpss&S0FVuK&^hbG^Mk z(&}aMGW475jZB5Ucei8TA6RIr|4EFt3)^#06PKokB~?Lk zoBclJGYU7H^X5Qw z?-uP?MB^|)#?_^bs`82-G5l@Jaaj@i#4!@8{;*sQ4Y5`stl4|CYG( zrwtPb2hi#~F>fa{z9CLCH*EFFwX31Wv4d)ax_eRXVh-WT=L-dq=upF{+TxVVtZGTM;g%h7(zR z{O|H-cM0HHt;7=v0qxS0Uxi@oOjWmZe^AT;0GHDK!P9S5rDaZt({e z@U?fx6|~xSrV$BFt{AF}%)r8W{Dan zi)}TAcWGax3YwTBPsRWeW#Zux0#x&hpF9epsNFAiU*9>`k+u-2UFi8KP4bGFWF8OT zKzk;fIsOs$4x)mY?3tWe{(h5t_{tGSVN(>D~s-F`|q@sWqZQX4{v*CYgyDv z$S(-cLjUasvIEsrC1!R{-<{{c21Z8Em|TIzGMb;H1s)oJm#-T>sc5UqGMn>6E(aeJ zsej5)zK^8>R=eYJ3&%OvR)X#e#gSvH{XI>gkqKK#)k^E}dTvj4+V(NPKqmOMJi_)x zAV%^o$~g7Cf8x)zDb)s`*!(O^|Ma_RLTPTege6Z{r|4(jZqedC#a-jZPwl?DyrBZS z!~AWJs^y@Ml3h|ya<0oPlw(sD=uI>Fg7!g6Edy6P#w{Eq62X8L1FhRy#$1BejJ-q{ z2+O)b8!_LEYDbNwIzS~g56Y2OKj8GwpT3v9YIa7LCCi|@x4B&galf0g=!G$B>M4nd z)+*|c%sw^aMlm7XI}`wf%PuPeaoM2Ln>dhiWz+Z58Z6WChE+J~`*W_aOs?iL%acdh zZdDDjP7iMf^|DYiPhM77pB+*s_+~D^R?;Z11{PHbCmEV_{_S=CAuw~!JA2mX@^K*E z#&C_uxOcOvIIZR4M84^2V6lR|hIwT!deHP2S=Dk7ive0kV^eM%$Ct<4K4L8Ze^%e8 zXM7;?;g2?WZnj7^sOe-Ohjo>8{%lN@A=>U87>Zns1SfyK$Dm83g~KXP-KdX z2i%`;c9?bA=4ODlA4)T92qq#CWu?5$8__BYuf(R}Q>yMjTn1;qiCNZv0Y7+txAcl| zrpdsu`(^4!?NZpcA7Wk$@~y4 zSaeCgfF!D&APK&EGRE^uG~shG9H}%=E`!(FDt`M7Drkdgt&aYTiAV(NL>-lJ29VF@ z&+k?;Y$od`Ke{%5?_jU#%y=~8gC4QP4qJjL<~9ED;2KlGue}79<|KkUkSv2s0%*+L zaoK>v6eU91(`99)z;zXe5>a~V2s=@x3;$p>m*%Roi(*EICUyH;_oh{0-;hkdm&WZ* z#}lS1bZxJbuKX#M|I0@e$R4eM#ir~vKnk0A$V+7#UftKhd$Bjz!$kbFn*fO`PZ3+$ zZ~X8hO}RPpZtwLU?|3_&mzfMehMHf=XCZp7^e%=^e;vsq>^QU8^(l+SNr*xv3&fBv z&tek9dJ~een|d;fNIOLq4y@h|5KZ$MqNr2I^_Ad{Hq%l)?;J;g8n)r5V=>%WP^q@S zp;u0C;@buBP1aW!>^azP{?lATkDLcWux<5s=xNqzuYePB4(|@r5wEWbw1ptf1&y?G z)%LP{aY^MpL*tBi;!;c|5yM;8$dld}*pO8IsrKRCI}gk_Sdc5lha3@!a_38n%(mB`fW|25XC%m%gMfdARr00?A_AEW74=D=#2+h70n3 z)BfC~i4doJ^dL$F!ko4{$}7^BX!wja^kj{cJlE53AdTK*E&JcMn~;|Ws`ob*(l|5M zepv5AINiQEbla)coU<*Uv`X{i^YCS0K+@8UEnFG6LCgl-<|jJ&S-?my0Wis} zdVZh(IA#*pH?xk|w2o0&-I)wl%i#S`V1#~u5sK5U`d}gi^c|lPLtMQzdi5v;RY|+h>qK#R$>9XUujq>lHO>Ov#P6fX+gg*i z?I1T9obBqg4x2fSzLEO6mYt8043a>)-acf>+-0K!%vW888*%?5fdA7m{nx)j+yQH0 z4;O`R?F~v!Xom0aquq2)let>jFv_3Qc%u*M=!20NTFo{+Zz|cn8{ADt%6U~B-g1mM zOzG1w>A~8%d`(U2csDG#B?n_Hk^>cVjW9>XZ05<>J;h*0Qnt58a$QFOPG(dD<3G>- z_VM3h39qeWS@3;7#eg50QA1bMNNr^H?rC|RbZEqeA<@&~tllGEMl7rALgpwt@ zQYk|A>`C@z?6T8BX;H}@L$)k4*0B$j>^m9D7?XV&W-!K>VaE5KK1-eRIi26>`+fcX z>hWrx=eeKjzV2(k-dE{jtgqc-B@-XFr@@NH2Vg`H5Vk?O7kzs^$Yr>Do^uqIBcHsM zC~(!kn)UQsW;<41t>9U{?AxDOhe|&$#PXPLTpDBJFK&21IW9-H0eILz8wn%QbaO)4 zlK4fAb5h~-jjz^n8LGV({QE)x0-Le%2<0RNrZ*zI>T*b!CaSUP=q3`F5o^~q2=$l5 zM=FE7y2EcTc$0#aUU{L(18K~G2SWBee){OANu&;K5S;)G2c4o8iAoW(Lfmkx zC>^Arp3lUMy?Q5|32fpbdN0p(Zwwp}7U&f-=!KSs+dHeSn-&Izdl3f>H)S=*seM!b_)#{x3^-3(HoS==LVDW z_opPw+8qpE6NOb%5440`lj~?e-Zk^nnNWoCb=}4$NLuUU{kE2Xs*c> z?!GeutU1w$HUsBj!P*4cdZ2Dzuf|f-{hm*H899cCXQsC@o*h;U`sA0f@N5!i{SnF) z?uYnf;>hmV@2ZR_I+?C^!%cT#J$-&C_*#kVGBD&t(B#i@Xd<60p(>0>vMET`H7?w^ zFLX|)Oy`-G==^}s%@tC+Zu^o2QpS37fu8Us=ZJL#=c}udEzKe#IHM>@`Ngr=;)N@B z8%ORDg=XKh*mdkx+A&f=cEAnb#{5KwKEB=-?EK1qgeqERUQ(H8;7c^eLYYb`y&ZJa z9k^}R36HoT=SzzX;IUV1_%%;bPbbDSm`lRUwBh2@ZuLF&ZN3IKOXG-6u)S3X@4!RR*cIH{H1I~W+vyH{`ieH?{ z8=83*ex3<4Y^oKsc+=3<1k*sr_Hfdjh_^4fkej8dlXvfk+RMEw zotJsrA8*6PQ0^*l%-gw9ZU3OFP~%-x`mSheJaqzhm%My(PtqGMGF`;iBg<3?!E0o4 zhwW-P=bmQQlk5dhsrQM!{XAIOv9w@nI~UnjIr2H(tjF>Cdb>Hbs-DxsKsI-?#y-mn zIe+7V!cDaNUN_1%{X9pKj`ky%W37s6WNU2|TT>|*T~tg-x)dz1=+f7Y2*k9U(A}sYo<9Q$H2Z2N%PCeuWMII!;dXby^{9xd@0P+ zcY}P&_TB7!y_k*v@cbSdGfY1PLW+5P$|-LlJ2JDmoRSN(Bq+h{jZJ{(7JZpR=&M32 z7q-A7Uw(aQFMGrDH_}?+9g?mA<0*GJ{V$Tw)lf3TCSUH#to6tCz0;Z@_wsHo{;Wzv{pwZGKY7wDb6 zzS;cDdO6H!RqxKb;9-H4>pAt8N zI43$UJoM}N?iJ(rQM+7*H1c=UBviHVvCd|#4+*^lxX+(CBe6~jm$U0e%t!Ys*ZOtp zzk}p=XR;kH4W3fLRSqWXpWu%NfUiVpmUY~)UT~y5TJ+?8Icp7V-}&_~{W88c&iblF zO6o|>Jw!TWD*Aj@y#{QaHm@|_PpDj^cl)8)o4Ankq(`%p6N%9$la_9>PDp8y>1&@b zs0W{hrn}h%CbQYHjQX4CE>?qGK{`$HXOhf&cLXaXB0gEYGQ`_M6io5wx*MBHtQ{vw zg|&~j$1I>0S{jzuo;TMX9qg@EVmmA=q_NIMj@$4iX!eZ0Bj(vt(e>>7H%M`i$Qc%N zqlysx#TE_rGbs zop+5t$Stnj-*qJj&k@n)In4~eS5;wNz`xe3-@8X;`+!$YJ*K}ibbE^AS(n<2SFzW6 zNsl^{=yhBneCsRD?;zFPQaz^p)e1p1#hBYW#6dsTG-UfKnd^&Xt|z<-%NHGM6CEWM zo3W3#4DPEuGFwz{BpMgGL%`s*k>k_MxiQpL|A}mrpymAa+^5aGxiLEwY36nEZ%O^sC+B8sjMQRNf9?;Y0Czx!t>ZmId0sEb={c9H9CDR+(8PRdih8=g#ut@J8cDO@se>~3pM9=D_c0< zZ!=CBa-o`;)4btl%!&E)1O8nJc`{#1Sskv`cC=s4ov$ECdN1p;?%%3A8NVEHXL!Xz}nahEa!VlYO^cWI??92&H;ZMEZ8R!Nr zprO`d@0708wGK(x_WwT-uzJ@9(0e(u3V3XbN1*%}4e{v~j;fB!)rdEOb=) zs!J>MSxvGWCo}O68h!PohzJ5TVOU!?C<=>mDb6{Gs|0Zblg1DGcFnL3OKH9Mjg{cg zySsIpMo6`D9k*sij=~PMRuQpa>-K)7eTj(`AFJtTWIlHY-D!1qJkfy-hxlOpymBFm z|HAZxV(s%O%y^l6Qo*NsKh3gp(hxDpMoA=7317Hd=ddVM?Y6Vu`CHFPhh_XW(j_%E zHNWHR@!%I#u7guL~*Au4h7Sxvvh`M#1| zIS@>D8R22hHtui71W#C@Kj%p|npEjXuNlv2>g0*IFuwZXt7u|| zM*BT~iT9oHj%n$epWoE7d)vku%AF>7VeUq@d}@D`(O))OtKDRDft{s40eg;a`)PHA zElqUI@u_cJw>y#S`M^VC3KO`ESb(69EV}j|a_^g+YbiE#c^O-iJbor;8g72PDlsgM z#CaxqUO;I527T{lFuf1ME(n0BcF$4tXJ1!d=le=8KHJm z;I$-b1!h=A@iE%l>{!i$9X@rE+R^DHvn(}AXXqwjandJd>(KbjV5Jr5M^$L4*JyKE z0#gak57hpX%NQyFvL#v9>z?H?vTAwrHKB>-OvZI(T7eQGeW~4Zwbtqf3te8=r*yjr zqX+;2e7#|-1^dGFi-D_iu7!KgN{^Pz!j5GW_?L9)0|0j7 zSZv%J(whjtAoN4AYH4%*B$2rm5HBjJ?EUIcSEB+G>h|8m--c`Q+}Se0?Lu<#8((Zr zG%=1MHP9X$Kh>HSjYD!qd7rv0pWZ2n@?_m>L0!BSX+8XLH*2rsdqr60^yuf!5&KWI z%^yuzl{+nvgGR&tSkiV^XexWs%lzULuC9nir452;R#AzMMP**iRbvYQmR^) zcAD@eD3uhE&w6y21zqHD)LE|Enf7+ET=TFyR#H>aRv~<4lZXA#hP?;@7pdBYd+cu- zZHmMs6L>@RP5R!3Jka{#yzIHbeJ@LOrnJ|CzZE16&SNe2I~s_YTsox`T-IBsg!WdS z4u#5&ryh2-P}%`-uYy%-H@|vy;7#vgt2CPi<(L-Eym`V1K!MN_;@Dw%g-U; zJ#^RaIkjoMgA}Ue4?>E1q)ocNhaUcX)pQMnkFQ>8W6Ncz6!U*Y3qub-8=&oSM+;kI z<#e%M-fWb$l$>ey_8lpT87q9GP2m@9?%1lc&?3>-OcQPG%PnyAg>*Y*WF z0c^pwxt0Wjp6Yi7E<{&+;?%!y8u!4(&a})XB880FhJ1gFZv* zn76+8L{fMCF_?0B$FTF32Im`n<5rneAHQ}p{e>OuZ-PH_yzwDa83fcc>b-F{q_5%) zRSt4zcCEhi%^=&F=dX0k0l}SUlekZk2YaZ1x#e)h78w~x3XW1a z4GeiqbRWsT=I)j$=-rzLv-QpHfr0#8L6eCU%iSy1m6iHNE_g=;FrDiKTXKQ&)f;sE z9lg%foA(uO-8i_U=jc#~q~%jQPs=7Vgl33DwS z&-U*vuk}d*&?slujmZ-`PLo(=IEUp1vOnW^Lr|1V8yM98ZL54aNLgq}lMA~X?OB!4 z(LU>}i6_p-WCfk=GnektBD~D5#f4L)SqKaCVX~H>`PoSkElxJLu&UP7>a8<|@DoPE z!H9!R00jiyHF&){H z$<~NdSq5Nz{}X}xx17BM8oOoRB&={0F!)gXU#88DeY^;vU4bt5-x+gB>A`%H)RsSn z;9z)A8SqjVO8-!yJwI~wsP1pR$-c<^AP1%r+Ijw#7_;PjslG|fM+4Zs^ytWv16@5{ z=%n4I_#jN($GluxI%h}_9bSscwe+e`7TT@kWPTD&%z5f1*?gJ_Lq=W~@2!rJLYDSC z+%exjxq4Rr&2)zL72o&Sbono;B-;g(+|XcPR-$ZHs_lk?%R4n35L5Mp6}PEb_sZ&0 zo2l~Pd(?6*iyBQl|0=TB)R@IfCs31EI2yDu^OjE<5IZ+{sWd+pGoRuyXFfIlvp-P2J z^+|n|y|&PaHS>wKRZv=y??yF0T*G=kTBE_X&X}=w0)a^Ky}fWc_`4;&^(2GqUJR$A zQ)D|nx5%7iqJ2fQ!_MXeT_L(@%6@<3KpA%Tkx1#Mg zz+=pPW298T{L@lS*GHsWvp(m^S~c&XB82#Atdh<`xI(H=)~TNItL|QD-Ac4mkbv0A zAvch6x;w$rFUyg!;1wB{Q%T$$KE^N{rt*frp5Mt`o0d)a4;DaMWn~gbu;4#9AK{3g z_rhPvyXmUq93LKILOR(g315cu+DI`4hVD|1RNxJHp%kE(AU`9=1d~>at;WeQ1^VN* zFVDkZd4vp08=sR7j_)FsR%{$VBorp28VNnf+A}25#kBITSVWFdt}W;eo}9TOK3Ttc z%|*9GLuJ`H`S)?XLOxJ~@J_lEfuT^PizcAXC|5uU{DRnPRY-Z8vF0Y-A(&o5KUM9P zpM4_Jxvm4*vosh98|5=JI}vFL9mXa<2%qd>J`S7ZqNT3G)**i_v(DOoO>#G<=xFYs zE3QrD?f=9a==fCey@NE;rAvD7VOm8#lm*7LPy;tZ${4_dm-g6l0xyid(w*3bHh7)? zsy4CAIGH{`HVJr}wCnZ<-Vnv8TCRJ9{AxF@|}QD#+!sM>R_Khj|+&4`*E9dA)xl~ht)kW*|%@X)s1dLRT< z8*CvTRD4jx^uug#e+b`jc^7(;GX%EPle)7K=uwq_x?P$DX&ejUZ8_KP==@YEC&6fu3p!!Kq zRSz9x-G_60OuCxr^HeFIEoTitFy`v$C+@Ss0B$ixsOS3F_qNm+kM={oOSh+BIC?hR z77;fvBZQ{x&zBuhgZo2JVq@@{ywPo}=gMMU zGY46w4!jBX0$c07$wMpfohhrYJAOq;rF)op<~%7eG@r2aFQ?(n?xDa&{Z~-w^cp<> zuyt`sHWwlHX-HPPDbGooK;}kLfn0g@&_&;T+$n#(LoT9ckTn`XU8wlDM=VoD#vp&> z?XL24&s&%j|Jh3tA6%q^L6N6Gl=P?RT(GBMaP{W;d`;$UJobQ{{AP+{`;SyDZs|xp>b`;N3ijl zC=cw1_7}`{K34|Y4imz!YQ_lGX6TtL<5eJZNtnL&kYtV^Y)(Jg{bZW_ANUhOS%i6p+Sk(3uXU<+%#Zd0=?)SuG1_e29LVO}g^#}}HGRo&B@Y|)l!>*f&24!-VqtNBgJ9O)c_JGu@@|G@| ztaMaRzvFCD=v_9o9MR3^o8#4jm{0GkpO_Wo&=rY|X0Oh# zrGATM-6G82uVtReLOOGgc(?N9ZWjY;WUvba1*^8DkhU*;;jFrzF>?pi zp(!5yFbI1var9&Vkz%vwPNNnkd5NxEa8JL`QwX73(asC~GLGJ*;~xA^42oOcQ;J={ zSqsmH9976ygE#P8yZ41AWKF7YyV;Wa#tVvR99VD2%qNrpy&(8T=~F_V)#8QtGQZ;D zIJwL6o;{bisI+6Y$^KtKu16dcf#h9Z3XfEa+7Y75Bm8geuz|lJg_|(zS^KX+g$g-B{a5%n8oE8$r)W=uDk8Mgp`Q zd!WohR-X7u6^uOC(lyezY^-$dYAK<)d`m*jSh@Cdca&6?h>0-U-p!BP24Y^t=!N{C zjd`6S47?YSHK(8T!!8l_>KQ4@6~?se#`Am{}b=dt{dpsVssXiiMSX^ZZJ1T$@vB& zRhH=6Q$RfFW^(1^ZpX-eXRH-p2kis~xruQ)KemE>;JQ6!4`-7tt>fjo=iDZJ6x+ID zjqAZk+x)bq=g59WfKR#pmSQ@is7D4A^%R>hRT?F!p`IIKbdlH5%Z1u}`PLe^hpyoe z(v*`wY}M+1D!ugGqdiUc%lr}(Ln~nVd|V1wg4RfoT7ynIhSI^OWVy`uL4sr0vN9~< zahKR7=u_F~&+sWPDZus(Gd)KGVJRUs@Ne#N=D@QDGxofvecoRHk@D5&juETbBBM=i z6*Hmao*~Z;H$`NhSoKJ~L3zxhtaO8cqlrEWn5u&O$8tge_#=e24E(M1Ip{7x3h zG4ak3KMcD4P~aslax?Q@dYdmStC$W-g;AuTn$d0!88L6din5lU3TSQU27Ajkwqd3hT&=1@Zj(pp%6yjk0i zSde0KRdj-TVD#U^xMnxHv#*QT_ZNh%NN?7ZnRv4*Hy)HZdfqR~v<@oqaia9NLu+zf zGZs4%Omi|)Fb^}W8m!3l?j+jY3ic=uzGNL=H9~aOsdQ<+Bw*cu3|2R1FDW%aze1c` zy}iuRxLT4&Ux71Wh)GM!t^A2^G51zWQSTZJ&>$j{(b;vqL!PW`q1(3+q>C{%xymMj zt0?odvzYcd#E9WV&0)o=W=+CYoK@@*W&S>|_i-lKwy)}w0)fpMp}3fZp~vyR#5dl&sA5TSGGu}t7iX~BDyyNhZRjUewq@&n1Rg)7^#B1cYhLJdEf z59jFQS(;hE%=^T}=RV>ttMq%zC2r}WCRLgZ-r}oWa>wE9A78B7l1RJf1vBvLFy!Ys)()ZNOCUuof+7?Hl#7}v@H5Z5$TP#nsB>(qG- z03)|D3T-R$b#?vSe1Tj3PSHF7wNV*umAB||qwtzz04P}NS#4&!@j<5BXtSF~Gzyr< z?hOd;uU4l_M}@bV0b7oXcGEChx3HwRdLQ5oS-uvc@_O3$VEk6Gv-Ao%c{(o{|9PAE ze7MB}!i5k%swsw1MLBFVo)2?##}J`1|_Qq6t*@x5Hj z?VYt%0!DSC`;>84hx@n5!u!>soyJEk+Kl3-cp_IS)6DydmOpF6s@Kg;-kl8Nbtkr3 z%+49K!a=D`#lH(V;FR!=$e34qtX}&J<2rYUp#>EZ8hkZK5YLtTjL9U6mNnCIpW<7y zKK5#l$)JT{qCv}nYAQAG#CV%RZ1#-2W4)hDz?p>z)T?d8W}sM)_&M8_O|e|PC+|du zdOvSF2eEG-;r999_kMVtYHV9-f75IPm$>1Y=TeN(<$s(Xeq<%J{}r2OVaHMbL{RXR zL`PQzULk8Gk_oz~%l-U#?9+g4DJEZFXVTVvyimV`3f}6)`gu?1m9pQFaFhc|;%7X` zyj7f0==5qovF=-@uAfnmv%NRIIzIbj69~Gynnw-=0 zlk8w>nW>|Y_!ErFarT0=l#b>b?TT-G_T^7r^VADevh%Y}d!kPDFrXAjh z2*!TNw$o=W7Ea?o9~{2YH|W<#?xI9J9SvNaD87y%q5hgW*}3!j_0{7 zhZ0d}6hLEDeQ!W@{WnjZdnJ%G%V>sQ+$Q+Z%J%Bc?Ik^H7-t@%TCX!}9>p9Ek&18V^2DT}v@Flt~{-PqqC_iZAh%;?BI< zw3)gBV+19Ob8~znD3$F<^?A!087=RY-`F3+tzw*S!t#b)2e^LyzcM3OVJ9Zl2t;zE5DS|&fg&z=jxmMI$D z-{3d$+3R0NA@C-d+00~Zm=_k5rN1cNJG`D?z-0WOwb*>tg<_Xdi^!%|lfS;wOKb(; z*1|I^JAgqrv$b8MS&!$sk1+k>s}ihFYMpX4gJ}~Y ztLb_iDPC9qoJ-z%^5&VMkhXi-RjP5~!_0Td`}}tlu-~{)yr64!H~5lTp9Oh2^>=Sz zIP_veRa9X)1JF)$ONEz-C|M(LDi<72PJ@<>0zSHiV{m{*fA|TkM1KSK{Ze#%fZfnY zc!}au4tYUczr0sX8-kGB=F=g=MSj)a`lp_&RoyRgfv5&N+?!yeIR%eYb0m)Oe$c!S zV;+(i90{#lh9s9dYR*UdU+m%QylV@kOLY*i4M9$B{?vIGFFhtvV(1fX$T*|5LYjB zM>My0=AU4c2s`tjUIv`HJeO-9ZOqy{_uK(CpDq&T73IHw31p~R9paQNCId8jhjh|! z2l;zV>q6!tH{1#XB&@PMtBMNcz3V1X)fO5VGga;F*L*zq$7={02YmWYklj}oi&ANC za~c$GOfLAsThRF1E`Fn7dvZQE4P-%zE1!Lfs$CeykBsZqqF?*0U+7I(>R;+FV#Oqp##riGdgoCgbv0_hGw(%^-dqd@Dx!prtXeAC152#4=W<;1ZGmjYfw>ZaVKCiNArw|5aDl9m zIb`Tr_{B0vL98ZWy()Wusd7YOggJ3!W-F6>|F3=9q_;m?I zGIUkQsx7S{S$l5c@*E}nuLrK(++^kJn5rpV9(hsYdo8!c<;nTYcr9M~WMuohO?>-% zYilNB@)c}NPmP;K1>D!n-Z=MN=Z9?3EQoebSyQzmyqT0RRAoI4%7bu7FbK~=ch``M zaW-Y7P~UoV>Px@Cs<^Maz?1E%a?o0foR|xzCL?&uY@D%BEh&7vSQPz?%{HjkNk8+= zK^)GuxMi34SlIKajT`Z@oqb z*zNOJxoXbdvNK3mLlb+m+Dh^nw;d^7nKgy8g*;+pUs%w_grF~W!~0x75rsB3io24l z?nnfOZI;T@biSNk)yr4P@Q zCa9H-d7i~>zps1bSiVG_cE?cTHKHGiRgT=EgkEhDErxpgqlOPxBfVH0C6Gt*kO7*T z&(6ek`dxtq&hO(@5M94<)~EAhU4u=T-DFvw%jAvv@yb(iU;-xwvH6n2Z=l=*I#V(il}M zvOr(Ch%D85@v5$|Cx6&ctkX6kWV@Mgw5Sa-^mM}jpS=5xmC&!jK8@=0H4hYXS+eqy zkl~CD)HlhF>6cTZI$q#GKFDPwJrgt*xn^cazZ5oHX79d!9WLP^EBqO_M%WRAK?LWG zUEO$vw}!IMa!!V8O=#M-ceVFmFRUmjlu}Ef_bJEnu=~B^#w+Sf`)7mcr9&L*>KY!- zx8#dbyfp1T1nbV%=y9}@LXBB14PS`5IGdCedat|SESUmt%Dg)r){U4=|r@5}tufMVMnku9A={fs7B zIrc+$OHEL6JGN30kE2Io=a<(q!5vHdLd~DrU-9*xm+Q%MzhCV~I`r+9e{}-hu&J{C zJLrz4OrT7PXG3KSy`M6zRJf;mOp(tRinmmUNt(az@zr&z@3}GwqNKmEUUcle{ZRoD z*&1&Vhx`$0CG@cHOX1k2m+Oo=y*`B+m3I{>T&uKW>^kOWvJS8-Oi|=sgIEkZ+~rsx zyyCJuF3i-qVVUF(dQNA}r7I5EE*|D+iWa^;g0H?Z^yL|O|22tz^zlPiTi5qkP3Xz? zkMIfmKA$+3bvNIp&>d22Hnp+xR>s5mjr`plC4rN^?Te<*&izQzKP4}lLcte$e7z`_ z=pE0rGUzGMSwj#XqdR7}OxndG?jZ9hK4tSSl+O6K1#crxM=xhYsA1H)-OY%^lZ-~3 zR(^#b9XOpJuuQC z+^yUtD)#@;?|r^6ojA2>CgnHr&dwJSBoPhm9P@aR|2JUf0HMou-!M8md!?e%UfG}F z_**}$7>w)X0Vq>RZWz+PQbciLgVQ*P@I$PGDz+I`NQzmg-y|P=HSfSXHAqp?1r- zEx+-Xs{4b2`oP8Bg^QndaTEc@|K3@}d4+qIlR&a^c{Ik0leGDzJ&x-D|)F0o|oNCnw6S4>W2Tu*Oeh7RpwtZ0he~=4A z|A<_Wv@=J{;HvVUa0|Y|VeEgvEeJ3aQRV%S)BhBn>JViH2u6$d_LYNL)4sy%H~kms zkxwUKOT-6r<2T?pn5Z}AivJ+#l$k<3E~ebN%UqGB&tl(O5cVbemTXG?MnCF8d__P~ zfRz8Ed94fFU6p5^g(z*Q-<|x%ga`i$B{`Pi?Rk5809&=YDbGuLd2;!6(dIStV5!Ex zYnykCVRQ@;L)-XA*QeAs9TQFT<1Q8Y!fGV$ecA#wl zwDmM2ifO8ypCIwxz~J3eju=q5u5M3+mX@=G-z}p+VkwY%DzCV0-}XTe#rz;raA8Y4 z=MRt>*Jhi>b#fL3i5BklOPKIucgd;p2V(ah6)xj^UBUD2#Om$KQ_>9ye}3-|dgWyr zV2<$7#b^=j%gHqv(GuDE7vJrkWUD*0K@g`eo-?YRvfx_ja~dopr)&z_biW32d}l)Y z4^Q|z`SAV4-?|L;^Ebuac_j`q$Dq?8bU*p9sShaYi0)ufiXNa1=DM>p&wPC$?D)&* zG}8=N=>7al{goCcfhWv9X0FnUVU$c;Sq1IZusu2l&>|lnnce<3oc1Ti``4crRDp32 zzNXw6kWuwUjEm#jb4wMLdZwP7OPxJ)83}g(w-cCOCdTyRZ|j|juEWQI;J3=Kqg|z( z_gMND!ub;tNsr!hZs|IDKb_|f67zeGi1_Hl%GE1zyEQ;11K~VCw_3o^zOWFGq1RK>Wrxfj}Jb|xoRAS6b52B2Oui+OXUi~ z<_x3cE6&G0J_X+XK*Q(zuK&|3BT-Bg9bnmK4#MZOH#EQ1=b3mqD11fu zDq7>I5*rTvtszlMjSQe4E9Kk1XL|o+xBT?aCT7O|2fW;1RfekFc|F=giTN}@tsKj^lH%j z8!=yjY%f=9zk01@)LWS2z*;Cthwl?>6GhCvKrhr z|CFxZe>buJ8-;Izyq)Am-ch?MOm}6dyoaN(zXYa}v-YhBwB300Oxma|>qXly03+qZ z=YU^5mQ11Z-`HEV3CrY}HLVy!l3SHE;m6eGmb^C^FqWVvyBR#4=i9ya?=cj)`?WUeswDiY)cKPYR7P=yLO#Ba%7@14w? zwbdCDZ0;ZH*o(R?^&cPgpXmzlbY)Et`sW=>n*{wc(u1=Vk=CFDq64K$CJ2E_4nQBC zIFKw~`CY!lDBW-HfH;Lxm9$i{{r&$d(O9}@VH&Ri*U6dGGFoS*PzD|M{8+?-WK0x6 z*OF1XbKRVHiI%OcJPh!See>DBvtIss%Z_9*jE1FG%U~8egRRgaK5)}z%DD7(kmZ@b zuBa57j}>L~N1QlyQijN2%9&@}%rnm(#{D|<=}QblyRYq}@PsIWx|fAys&XmeiO*_^ z)01P%2Kg`S!vNRIf2HwTgN#^*EJ%tpuf*a3qOgZdZ_ocb3xXKh;GnSdH7NO1L~dNM z-N_lWabK+PoPLxnhq{SBnPHR_J3I(D=bxcEXRDT(OujFLk^EaOGA5Gl< z^3`3dZ^!up5SU)Qkmpb_!e;peUH|S}D|RkdOh!*$?P?&(R-sOqH79wHt652INj{5rfmBT2=cAmx!;B6KfSsu{B1W5 zf83ga^f@Ug=&J^An@mDhu>&yCYk%uleitx5UcIdQW{-tD5(i{51E`A*H>rQZG5ZIE zXmV$)>J*fs<|Ak!F7z20mRaTOKbFzXZgr{G=&_#+VkUP#>CG^h;Zrn7jem1bZ5dI1 zKAqP4>*Jh0#Dj7{-aDKBe;KBY2cN#V&O&$tYCRs7Pk*hHbDeqb$+wpM8Lzbyp0+<9 zfckz;@%&{J@VAqI+3Q?G7ywdQ*d8@TTecNeh5>VRr^2!U|BnOp zBL(CGd%U%^wfAq;`{2`&NA~j>>=5<$AVM_Q*5EUB4W$6Ft&yLKw~ zXIfbl@7bv=Emyebua@^S5)QoqFHD^4K>3{C(gnifC2_y<&94EGMY0J)N0}BPe}&M> zDM!Jbtlc_g&46l&Z@=u?^$Ux3HU`_I;RB&y-!gep$gd6^_&H<#&tqE{d;HcfjkgqF zVeooanwY5s!WZ`==IS~>Am#wEjpQ`7ILm(29F0;vuw~x4iN}6r*@`tG_^OrciFMT*r_?-{qYbNb*+saLr0^s?&L7S$<{N3gFFUStFu#{v08q zb(-BLer4HQ;G1LJrc1&zcPW>Jn|nw8%Ca-r!GV-jw{>_3sC~Ta@TFg1PP<0HoD1c| z)=|{9l-5+vlF&cyI8SVpJ_h$bEvP#ED?8P<8|>5&+>wWsGsK05HY55gLOV(w3~hA3UZsfugzGCB zxb_RgK63K`ST5^XDJ?#5Fq_Bcg?@!zrN@BiH1I2m9tmgi6kfQ{{ws>Ad zk3zsenytUUn@pi$fY#EN)iI|y!G^i(2>gnsDX|A%DuqE#277>UgjiMMU!m7&0dTYX z+;i`NL(DVY1G6sizrdVlcQM3n$aL3rut~*N@Z(jX^w!W9YrOSFiFyZnq zZ1ZU=aI-l6?P?d8F}&KzT3X}buU99qJy~K8N?QABP+*J7 zUw?DHjVl4v_QgBsskz?chY}s9#{9hYDA89u0#@4}udU!lt-UPz5PecVFh+~k?Nk|? zXB69oXz6+6QEUSm8f0dBJT^YK^p@39h1IHgZ{rz-tf%~q2G7)cmdcc9-WzBAoRX&B z=U&Qs!F#8@e)l|iXqih}%`n{VwUN+DX z(G44zFW!plKR@&^4WPXcq+2|W`AjPWUfKGCzXfA%R}4U+l&*%C=%`a%CgLtEw}dVY z;P_EGxf|ZR<%4R4#36N?qvO97PWx`QtAGLTEw&w0la(1+uaRfR;lKaRvK^`K)Z?8i zcBs**>Z%(O{%B=!^R3+W`VX<#{M;Pc50aq7BUEA@?ToR$vq=}e+_;a|{dp@s_#E8} z9VOXvMuu?4ZOtIJ;hhI5yHL|_bfuxuJhB*nPd124x~9QTav`orw{gI!KB%yf+WI+f za8IRVwA;AA=RP*%foUwwiSGkE+uRu)Yj(S|d^trV!s=@lmU_ZlVSROIU$&b?=b1Ov zo0-Bk&KB=yjLar48ttT(m_VO_>GPSD7^` zlf#2xL!)~g7p!ARcfw|cKvPZdioTQAGHYLQ*12HmzT~E#8$Qay4AC;lJ1~?e#$?w0 zpjQJUqlxjt+_Eb4JvG+@E#86B^`8G-|9rQ=@S>e5xha>uPpqF6lR10%LC1zky3uEy zij7dt@s;^h5B1p0y~>>U$!NBk$F=nJ7fvVyba&#$k1j#V=`N2-`=WDS{R(wzYwDft zQ%jjv=AO3m+HQK)jd3~&@!o1z+fBs>el$Cm8EWxWreHIouyK22Q%1;MGW-MO=};-Tv+aiY*&m4(bR5{imPh$GfX8N$yg zj=PnmrwEy)>%~8JKD!bauBHb85n8%O+0b*W*4sphUNU^Yo-c3(!8Se@ZtE?Gjfp2%#V3~o5C;S#I`dz&2CpE z*RhUss;e?%di!eTYs%Lvd=iR%NwPkHEM3?aYv-UBVRP4eRo0D)f{cXM54z7jSYI~} z5ZhP2mYmZEWB)F4yE?YTSh%iUP~c%%#VamcJ|MX*rMIoK|8SADo6Y#HS~@r2u-bd0 z$j)&DTWthau}6k1POMnD?L2XBJyDS|)mXSL!xDib8C|$XjJ7Hx#k^QzKlPbK49O1( zke3+YS$3vxgPLP9pFg5@#C7gd(7o?Dn;)^4)#94%ZFnS3 z+}m59mW4L}KsGOG#1;9dfo@2dL)?Dt65|HcH_Mxfv{QURUarsC5)#v3l1ari%rlWS zR7I51R7-*;`|SDdb?4>Afk32ngx9|6iIH;hBcG?ZLqEttJM0#k;S8q$&3a*MjZoOH z6afe-*kNjF#w7d538LVKzGe4<%cI(&XfT`&xk0}sW@aE_mX$0dI&2$t%Z5G}QMKA` z6B@J_{jr`@d1&8IKt`NLCZF5Xg4Px89r}iu9Svz^{7AF5zAV+6^<08#y+gRUv00x( z*+L2GwcBS@?$mnEjrQ649zAaM5KS?(qR*=Ns~XuiEfgOGp6LF!G`<|K4q#gy~y9Xx5>Z z%DZWqi-b<2$CMQyTpf$VHaDh2+V4DiM4j?6GGp@VRT4dzHDBbSZCSgA@FG;K*1|Nu zvP)(UA=7mMNZvOD>U`pFg?Mel%L$T|iq=D-y7iG(!SLd_oTqIZoP;v_!jYoj+OwPY zwcS)$_t2;v2c`LHyyypJGD`fR@|PvvEKhO2EF;|_oeXx zZaAOY`Z+X5-GqI0OoOw2tGDABzQzq-QUEdBB9L=-k9tP&bwe1oizHbrwlk@g+(5A` zQzY5E^&Gb<98XaH%uF+EE7NEFCbv?Zb-*msAHMwuc01BF#2~LpB%*MYLEgdvdAE;> z9BhiZWRwJpzL^>JfaOF?xsBOARt)wH^Ni<0txJK^QmWVPqAcaAAHAH=6EE-Q3ENms zKM+MqkI*(=Z#Z814;BFWa0Z-dM{@JD^1E7k#frM9TjE%Q674B@%vz20WJQbN*h8{j^ZVJ7 ztJTw&T!gBi=Z_=@5XS>5vgy~EXExEkm=PIexLZ5swWP=#9%)(GF z2gtn}BUamc7k*OdyYtBDs6v;SjQ`7;rniC1oucG9MQ26ffobfE$49aB{gAtCP5gdd zu6jwQ^9uV-eX=RX+ONj6F5q)Ro8PUPD*+GxhXDf*<=M0s8FO#R(EDa&))VE?p6-@KkU6{T+_+g1{`$NT~N`Lq9Cw}ibxab z9UCfD={+k5NEhiHRuKgO6#*%sNQrdm5J;j_1wsimgd#Qc4k3gj?_}R|p2gkc?(uoQ zydR!#{t#y7f6qO4y{;K$PI{@V4utI;D2H+rsBMOyKq4z-7qIejtk_8t56 zB&UQOdE2Z)5S8b8wP8cVAN4(x%jfbBOk~Y-gU+nJ=TRY~M4-mwpD7uc8W)yNW*t^u zDqhrfnPy|9h;D`7B|RT5GaFIdwfcbyWgz!S_9O+meLdZwO-|-filkIkn&Yo<@MRU5 zT)-TiFmvpz8h`6A^|?Kzu}ICvky9$*3d(#)33!e;jE|}4ehM&6owUdHmfdesEVaSL z8)v3Xl`I`+VINvEb=P=$mH<1ODCCoSlVL^F2;yBaeH=fxm>^^+tn9%0bxlR?S0RYPJx>Y-q*~K>7<%j=MDJ>w-ma zIlXt#>r)yt6a{g+9-9Bce~*kpji8XHRmts4t(B}Jj*gi{cPAEl4do+AYqO;6z-Dg! zK(Vo=o55oRI-Ze=3J8^LahJ3VqgW}WmF=4;CYqT=eR*0CA9@J#NYX?Gd$1$q(y7GX zWHHZU2I2;Kt9|>%s0@#W!+487cv-6H97t`)+m9RCKl5Il8jSOA-U2_BaI zw_Q}0JMvEG6Jmy^1ozZ4`%T1FXs4wm4s8%nR3@3s)oc28D<<_+UBFWbW^_&Y?4jW} zl=AC>m#StAb5+~xPw`R1!dY#<)$yM}E@VqJ%;DHWwQa*7Zj6%9(xt3U$AmV~fZE5> z0!%{CjShhr)bY|ri?w(hPvO8Xpl{KPM%5Vy-cBLDt||M{4I|06X3B(fW>+PU$- z$OndMq~IuoO?wr>h@zuuzu0tON@EZ15x!|;>tgZAl624)`8*7vzXqE(0QG@nY)fXFWeJid@zFbz7xH<4XtA8aXg!CHX{?K zrq?f4f!z@RMj5wFOy*>*!`Q0iivgRsA0;oXeY5&@)_k`p8>~cY#|n0KEwuFpbmP~% z29E+0FF}w!7sBgTTXFXvh~UDsJaY&6}ROucC!Tu`;)|xFAys(eYy%YjT_=9 z)shqNSJrao7Ab3XdH4>l-<>U2k%rrB|0$()XTtE&C?xex89e?1Cwjh1rMT3);q3ZztC$GtfycCK;|$py(;3-{$hI28mY&MW+{Tik&tP;(xa@on6f;Rp_}MLlSK` z6k%w1uPwg#Ko6d6@8?9=1G9_+)gjmp`&h-BiXb0$A$K{mYR33$R$i6&7;y4_A?N5v zTywTe)NyL%>1G$uE9tPx(Zuat7^&;*(am<(0ZD}I{@L!SoXi`2*=q-8=7bc$dtO(( zHy(*tR(CnI+3*NBtf~ERP9VWKdw|(x9(2g;x1?CDUQPB|8}A=aV$fqQbWw=Va+0yb zk5L;oWh=1ZnGIZrOmCJ*GfP`n(}PgbOHcVVkCW7t19tLi+pD*?_uRSgXqftY;;Sk` zl+=UB`Zr9A*o&MXJMA=a;9q%Uh-@Tzv>YQDJju~l7deCW_=wVzYB~T7U}r|{1k@~3 zUu*?Tym{k0b;9D2)l`&tu3K8o#^;WkBByB=x8b!}`zauGd#Yx&%fNo^&6NSjjraZ? zP%N4y8O--drC8a`kgQ?vt|UB@!4$+;-w+l$bci>OJ2BSRBk>$oy>ldrL&vtS4nEIO zvN<2?EH|%2Yzj;vL0tl`78;pAe1prnY3B*v3p-{n-R-MRNgiafi3BV^SZNGl9rI#s= z8pt2i1**a?$*tB!1;*zj zATaYO;L+e{}D^d15!sc)pcA(o-VRGw=6?4tSJ35U!;=+n# zYp>0br{L2kGIvJ*cfmSGv&3}Cchsz5D7|s#)e7G&IZ<&c`M81i&TGbaM}21lGRXSO8pS-vYn5P3TDEq1*+{Gv?a?L z-Bdu94tAV|4BZyp_*NG)cvBbzKEt#<##_{VsdFO?I_gJVY9sBN*aU=3AG=DtzXtL@V!|-K#Y$!&8@~+GI|-J-9Q$S=O6kGj(Dt zdEE0tFTVsVS1Za-a;COTq3y&Gts0Wc-Lip^^|CC3wh<}qX}K6Kn!B1jZIRH^o9~zo zadVX2{B{%m9Ej$V`|D#rp9iA7I4^Fww$S8YAb)>pZRvR^l=2I-&>7;>JU=?0OIV6l zNXmcHQ&s+cMb+p>*^q*+DjnN4$U2(1qmx%M;YV^`Y*sY#`(#C&Y{5`KXzI!&r?ksv zmHh-l4b3J6kAcNb_>I0DmbgK(Uy{t1nE}nXr8!9rf|tCU(`=j0)ZE5T`wcv?GS*3o z1+w?U$KEW{W5+nbogM2#VoL07MQgHZ4R=inv<)5Coy|aLvA~~FO9>ktchsyBHK%-O zF)obzt(mn+_xZCf_1;HRqHREHsaaMSI}PcX!Tv&r)N-Ptu>_abT^7@ZV~;gg6p1Jj zIGm%!nIo41adW>={%vvD0dW=J8k0Z&LKoLW4zs6L^~STU_PrvLeA&(r#4MMw(o~+O4vZQJB0L~nf01oaIW>eii(Jcs?I`8iIXH5rqA)Y@9qb4 z{Bqj>vc1LC8`HrP!*;TMc^z+;eMq7uNM#GTe*;8?i9i!=txf|Os&)8&_ zhTy~-ON(7o8(n3dGIQl#qu7iSrZ$i?%kN{Q(+BLv(bH&^~BMY5gV$3 z{9bKwGmisc;{-|LKi@ZzNq&xS`L%moF;E+*|WSZB@ z-}1A!&1WLit=-jSlj~8Kd#=e=-8|CrLlK_cQ=(CpOAumqru6Hyes}ElE)JMYeAb6C_z>q^YqY4FGQ-?v@JN;^q1PDA%7TFdT`jFj_NK0%^u5dIwbXF%PT!8a zli%q3X93RAeshKv$zh>ry}cb9NbAvznNzMl{YlL)4Gur2Cy(z1*y3HYDktALhR@mV zpB6vn=E}}6J;mk$9t-`SfW_|EI{^stg9EZyguxM-baxAJ!#v`cv!8hJsA<{ReQ|}d zUg2Z?_Fr0-ngZB|%^ZgkB(rWWO&)OI7E_mUH@E8l)LFE4qT;%bQCW7&9ef^}Twc|+ zfPsIv9`>7^#@t2@{#HV0GTrECSqYRAbqs@& zIi3tvW*R|5-0GjS2p-Y7m(uJ%(Zg)9u7&RI=cT(>+WG@v{8{Jn9(=jJGW2Q0##u9E zR%1h3W-KgN^w*9hhVk0Vz*~u5)lb`57?c|WCDRLeY=Lt3Ms^ft+jDRDY?+(~Qn&T> zFEElul|$TeT)U3q>n&W{lMHBg*R_fWRkVn>{mlF)6+4|PY!UZLLNF&hwXWPYhWMP; z=lmb(|9Irh^F8kSQgw8+f2nYDh_$|@DH0QzaxqO?t;=in6-6>)vCHFg1w8((l=M^% zy$2RE+f!bAUy^gpicD;`)+>;1s^ATHj!yD6$+-By_4Tbo%1h`O#+8agaV?3l^5qJX zS@il>j-wp{E*FJAwY@%_uoSpZCt^8At1i+W63;@-RdVtATk*%RG!L)U(DWH^u^*-< zwPS+{Qjrc@NpaE6eu4!7TQRkZ-x2r3EE$FGT;e5OkA1pcwHn5i|^nS4PG$T>k#E6I96HAN^u zn#l z!y1&FPF%+cb_5D5=4mwz632W=e9x6YmHi;i#i8|;!sFz81EQhZqGBg4im8DQ${eK; zg_hKF)IA#H#FF@E*Jj;69lZTRs?Gx!FU|?x)(8hpXBgGpKJ)f=lGw)6@Xet! zjrSY}gc5PGTqZh4g9>gndhD_wyW|7fLdqL-_(XNT?C;e9W@V|zJD;VLBE?6-OYfzY})S$@+jk%Nosn4LwcCt5$% z6uWLrP>*6@ zcpmii7X3CS2i|oNyhV_-5WjN-@k9f6D^LP`o=&UTzBW3Ag}BKUEIsdPx|~?ZGAAfA zat(e^LN&2ZF}b%*~I=_c@Pg#2KoJrv5x!faf-n_dv!sHZtKg4nVeV_KNNxF z$r~|5@7nbYHEc+*CGr8QzTvljx{kKy`=-)#ZwEaCBP=0rWt>Qjs#y&NoxxKLzWjo2 z@x?k0WzDCH@IGocdVXPOML?FUEDxx)a>78R_}w;qKb7T9c@AILCx(nIUn}4P6}-pY!BNBJY~k;XYzXovroz z>r)B*Q_YGMsAhlDZR;?9M1+N9j3GEKy$`8OZ#(jE(htkchu*rfJ?CCsV8#jd@s4#ltJJ?q z39!9*l_N!@+p}>;?K-T4CNed5RB38_9`r&H9|;ftUD^8&>7H^I9U~NB8J=`jq271l zH~%$Ucw~$9tVYRZc{#{b27J_gzm=-|Cl@Uw0Aj{sYP8$N6^JbC9zCr17&pwW6ve4@ zi;y&UfJs@)$)%6?+o97Ro#%i3PN@@!q4Wm>GeNzLvmLo+H1AG@fo@ld3C0Xy?h*>H zx4*gjfBkS}Bk;X(*QLY@jspKaBj_Bs?LHr{8FU=fJ;pU<|VhJP9Cjidu{+nm{+^Jh>VGA<4p6mdw1*OKW>d3 zfP54T*%U82&O+SmcId|#c)Vj#sLj!P$hd8DbqE5bJ^StS;y+AwhQ7pYx%-iTYKf%7 z13C>9Sm?kT6;G2+u*BlIpAUV{H@_|e@%IULE!TaiOch?+`C5&W%r%CFLg7#_*7W{} zzbM)6a>JiaNh!zg^2?bzsI0ZM(YHl#kE#dpgSm=l5=N6UAE7aj3@st6pQTV`@A|2i zVGnEg1n_;2f*-kW1ZIfcD0JJH0jIo$;h*8TS?nMyx^h=_#z##1JFCu!6rv6U{7 z@l|{Eo@~pSfYAUA59DZiV`v@I56b&oM);a?j>VDhyU8e{SPLWUtn(jWDmfm|f zptRA34u!6X;9C72V!B0NiBmWz-xlm!d{2#I2`WIxBz%<@{FB-q1(-ro;V+m~zbS6c zMq{AOJv? z17ZV!3;JJAbzTeX%ja$pdY)#wO{8`fE~&>9^n-po09*)e%F^1lT;|(j3huPg2OpFh zQ2Cz0mFRn)XI1=tg*JU)|;q?cd$ za<~&)g*eWSA6&!x86Y`+G zd7_LRRGCbRp|m$B`?zz}s^EQ{5h=4%n&^$s=j3P;iZ8)TY@P~Vjd-7KPGfI-YJBz6 zujUDE1UO}>r5|qS2)@V1Tgfb}FfwgKtPuy!XD!NGS<*am6bi&4W{x5H<#!;6822|* zyGr{1q{lxP8-6(0f$3nN_gs=tb3US0@JNjS4~FT1TY;3a)66LWfv}5;S;n@Z1I+K^ zzGD}ZQ}uxBk#g~LM9#iliCXA=dRRxjv)-ma8U}G&$O8p^DUNoxXpL0mnbtS_YL3u z-z^N&{U}#N(lcqJ?@)TnYgocMBN)e(QMqr?^4p>NUk^}f8J((S$t*0fl;<*vN~9O) zrEq$H`T++48(IpPV%$;~1Ac_8U?va*{0x>1DxipJ958=h5!e z?>__$U;FG}Sztrv&e#nw((@MDfIr31<}+#a7!yzu@Y2PblJ5yf2FmH6`*r6~{;a3t z@qpWMGp-}rjZnI9SM z2k!fh^Tn{|&{1Fop2i|H=#8L>49)K$Ufk~j(sD%jw$P@2NNqt!mA?44HvMJow>7~Z zPj+)IycYu0qW4`xmv(8-KYhZlKLb(oF|?;egJmnsJZbx$O}?)MW?smyXjwJ~WTy8z z;@=aX-fjecY&9sekY)=8NsAle{f=d)&VXenwqfHrP628EC?5KU=6&VU|KpGYMc^dK zE$%$5bO&^o>3xp>{3m}XU@4tS)Z1m?SeyyAtk`4-T(R>{LjIpEOU2Qb9nt%24$v~q zc+R^2G46ly0gOOk`+hz}{%1od{(to7|D#9$t(yG*mL7dyZ;yar zx0IyG-Lx7E^dR|E+sS3OTsw4Qui!!`!I=Qzm zStOdw7F00(bR#ZVNmdKT5A_DrBFmeb9}uYDn<4a;Sx*XS1TN~f^=_Lxhx;opP|6Ve z?@sfMCY6Yj>ZEPi<3E^Hg`9ccaZ;?2j{B%L^jmVZoNpfw`-(&JC*Qq5&rOhJ12J!))5ARSQ8gQPp2Ehv~1A) zH(A63bnjZdu)SL8!Y~~ca9@OB+Bb59-x|;%&@+JcC+_4wi&@>e+ReDzcb8fOKV()W z&U8v}OWP9OE;lxr9ZT_3sHt>Hvj&k$g5&%*bGv~GFd=!7#)kF<6AIHOJfJmv)_Q43 z0X<_`=zSi*#Uj{foZXPGCiI|B*e+k^wn7K1#`l3f-ImuhvB8~50!XdT!Sb7Bw+<8# z1>TcZu{A{J%>@H0IgQ`$E7=;;g^;^|kmUq@V!oG*-wLgi<>=5_I2Tm70zhj!!Np3G ztL)iayMO(@KRxCtY@fwjfG6ctv%gu^ER_O++Uy;-@<8wDVCA}0wWmV?p~*ETq7W!3 zx+ExSNwiHTmzs@Lzf8BBUcR$3FPB0`p+thGGPMcN&!8*LHYY3tZ5?z)ys_Ob5Ovyl zyk%WKJ&(S#0^l@boqbBrMbR)mGs~XqQ_bz({rb7r0C?qdoU`w2zSrVVdsv^3pxjhw zrxI%)cxenZEpG+)qdb#R3ZvI&yJ7I>O2X1N1VNX`P@3%gWZo2Pue{>UYIWsgwiF%k z$rc5;O4*j7hCV1GOF(IA%tIosgXihH%bf#{bEO2zou(}Tdd0Is6p!9U$C!_8BDeR# zqvN0fHVu<0=yq;1v_lzLpp1MQ4nPlv_bF{(pmSx8gFAl5iu`So6scRGG8RQul0gN|(D7xJ<)Wg3MM1pHQzKuG7UUD_1^*RF`#6<-Bbq(>g;XVg7eSa>CBSYB+p(tMu&HwIRTbwLq#v4k4s*{_KyQ-M;K@+bbIkg z>`NuIH=b9s9!HBmF$U~}mAWX)@$|HjCZ?qTZf4Y_%Eq;r#hc^B;#nr%qcZd=WTyb< z-przoKAiL_M(ar-F04m;tpmPI`|y!m4_T4a!UtRotGfu9TA71U>F-AH(QEsT*>!CJ#0Z zML5ZA!@k=Nesb=92@%dC?TxRO4v{32TN%`mV)mp{W6cx=K3gXk-0YlMd`E+N|)liOV0foVutzp9WD{^w-X7F??uC67Vh!@9RT^~@D zZ7+upv(P(l)c54_^osm^AC&X>c)@3$RkjPU2@d|NhgK}v-cgCkfz5k9h_U48Zfh_< z(L${hRgTA32sn!5$@|PYy&Qm=kY?gsTrhQojUhyNc0hQcFgT6A!Ab&Vd5owU+Z9D} zAtxxvAy{%)0@0sq`%RJovijZdUCh}rfK!X)mva|f6cNm@Pxh)ycWH@sW|P!dukL)v z)OggSFjnbE%6)<}C)QgSkY_8`QS27Ag%V1w1v6gwT~_&x{GQD5F!5fJET>#j5qZD& z?W!!cj5z(MN{e3)0$hw;uI?daXO}VeqLFg~_1tqJocxt0X5KpyQDg6Nx$`!zV;v1l z1P=q+_sz8a1XYf}L1L}1%g#nr{ZqkT&5S+FZL*~WIm3JPv7#*tfp^RFuq_pQi#6>D0lH|kD2Y9t-i{=n&zhe!! za!8h{B06+LC(f(l>W*c##9JC8C5&*v>?W~fWS?h)z0rN+Z+eFx#lh7TZaU{>Z=?gO zEikRh6U5{88R^o_wA71Vk6hK8fOF0zU1jI4Wi%rnWIJ>9{hw zeHcFS3bUW$9sNUUq4!oy|HH}ar}tIq+`2pR5tnD^@1q`PR$`$tQ>vigHL{w)xf=ft z>tpM^nWw;ud7D)Hu`cjrG)A9d84zfzl6Oyc`xj!e!~PP$Qmj~C_NyvQDQK}S95~0c zHzR%k>)!QTzspKxCe1Z11LBonWxsHC3L`~%g#mc4wFJdPZ=b0X2-f^YYhuafQQBv` zu5|gb?ph7q z2^yEjvQ^Dn)y4KKxevn{d_qFR+hl-lH-I*nPXB9K7W;LjHtQFfmS}Nqej(fE#cS~u z4F_=SK8#k{dph{te3z#L3^x~wVpG3hkr4W z<#Z##OeSKD5h{P7^z6QmI!c*F1xzBiEX6=+rVDUfAyX!RrX<|j-a$%6iaUwC7WYsm zaK>!lOmT6K5j&e9nYGkhZXX%yQdSdFZo>!`vQA8IoPbIVc#)JQz$*hQ;)@#4Hy2*} zme81ak>|~Rbb}Wj%M{_x^s%*`yK>8N0#ouJz%Fq&!St)>@W>lo;Gl1@y6v0+g;ay( z7)6K{bF|L;O4M0@^YSA>`9OAJhoP>^u|)vJM1ZR?p8y@r9%N08`Zo6J022{+2CBgvO9ad-ubl{H0fkESJ~c5*M}U#8+)gtX1H|~& zI$X$saRVDi{?=MQ04W_yCXDbWDW>qtD6|T{){d?%r!&t0s#8F2$>8O{i)K{--?ptT zfcm}L#(p_fG?XpHewd%iU9!MI;(MIpGdF%5hB;?utWDnB?piI(x^7ZUd77tCUnfa2Baa3fW`jB_C zALU<+%yUrTooMR-ML@q?>v78$*pFg~Q&_ghY-fVU_j?$5X7_t9WQH-UxL(4uWZd2r z!Jk(O&KVEut~F5HI^9ND5)(boDaNAe^GqT_uA0Kx89}ZbOp1V*zOqOdVQK0MZjS%=q zGF_z2;rpZ=^cC1T*;?`#v8Yd;Wyx<-BfxovmfP=wIa?yak#C$=4yZj-fzb_zb~FEX zJ7y67MzDZj_DoV;f(mfWwMB>nUm}hca0F3ZC8G_ue{f7Y`69%}KJn0;Ghm^SK~Eyh zXFeHoo-*MqrV5bngM&8XN>gO*_uh2ys9_E zc0k_Dk%BRpjq{)Ng!w^zf@1Ys^Y42_Y_>KI z062_uvg0Jcm$Mf(7u7Ll@NqPCrme3{$H$_aKFvCpF){q<|ASLCx^pg1a}oXJI3gqxciMbo3wahmDk`_*ssn# z`?GNVBF*M1LN)U7wV8?BfsUDWbX@PrSHEQe?of?3vhkYjC?fSIj35=I8SHm?6x=JuvcPQ)#RH<+IUOM6 z$y+QC9bab^Q-|MP*o2Rm9$aJ7S_SM|u|v`x)fSXK#qA4pvU*MrN6qlbh2PohB{J}$ zIXakIZa>n@5|2IDU!7m!mPr8%w6Q9=RY=1dJks8(qOJ5zmOM3(ovw&s(MA74HZisu zm01(wzldu77}v<0-o%z`us~zc9HEvbu8G`a6|iEOG1W>!-B_`jU>P3aoO#AG)q~Kuc(|CfKXEE7?Gy zmXti6?z5hYSqeB$c34zoSKqN6uPvI9f(c+$^rW-If2bL~#8iL6*WrbMR>{qL|B1lU znDf0au>FwrNnBnNfREpch*M>*Nl{!YY@l%Rcxu#0P2k6TdP0D8T0b!i0Q-HB`vxG8 z3u3pfUDg$DI|G|_K-6AwX>OaF>QN$FUkixJY>M6NqC+^xAI#&-CfF4GH+ZL0xNrzl=i4 zGQCkUa{W+K;EL1wqaLoj_T%eF0clE+b-*DwA~!3@o)N*;9Ls0M<9zSqmn-~- zl;I*B4uBA~ay`Z~lvFc`;FS`z;2=J{$wsWvb9_^~Z)`nmmk4z@0eA%_MKA!G%OS{< z8k@$zT{8T=`A(-W$NiU9cfLivEpDXbQ41IOH(|gDY5jM zYt|5YG@ScT=J*RC{Wd9sL&skCn$Z#RHOLFrj+%})KQ3G$`2xe7jC($qo%C9v9+edt z+MhkFX-}crj*3@%Bv_g33V%~;eo$>mj%<{JIwTp8?#|}86v{CvSOiIM$_d0Ycl^+zLg3vd!qJpFv z*0gXtFBWzDb(_igLq93=R8SI%Fgf8c{G20QY_H-jto*A zd2dr9Lp;~jEYt1W>^kjOhNxQ_NMl4Q$wnb&$0+7CBUwdstTkS%X0)?%^Q8e_PPF97 zcz??MrV&)Y>)8y%w|g_cYJ((zPp@Mo8Z=eRJ{oL8YO?oq(7o#5!|tUL(;i8C9b3MF z6H`Uv@!d+d;NRe5w4sMh{VbBQ1~6Pn`qb`IavX8{PDO z=575s%6kkGwWjQc8sphj)oNBrbu+z_5~sj)2u=E=)C4a3`fT9rHD5-@4YGJ#zq+^M z|GhH8s^Lwh-KVXdHKI@?$&S3Lu`-6M)x}BA_RME?1K`a|XT^)YMa1D(?7o~o2MHhQ z$zs=|CzUgqcBcPgCi6l{2^n%b1W?zd-$Y&i=RFqKnB$CFfQlx%Aet?V z-bi7lO%1YTT@8ASvawXIKI7B9CU(?m*$v%eu*LDT5rP=A5^b@*gty`vL>9B-M|WR! zoimr$gmCkpY_sy$WhQYxo>3(0nG^ORGR|%!$Ne+48fEt&+ladIu*@k~S;y=Bw5*PG zP;BV_GJbMbeO-Bt@pUAPZ#dai2$5CNv<2qY)IjHQILH;jt^02K~w;(BEyz zmKwNg0#asKdSPst;W=a3{!mrNOh>^o7QL{63wmWbCRa`$HMw?X zC23@k5cwHa^;u)Fbx@3mYM(pnIh8lEMs4G1oAYa1%J}60!evlC-+RJ)Wd$CcfM%m* zy??;*(JR_PclwaNsr>f(>>blsq_q9crYMepSOp0dhz~y9zc@*YeOyhkE zYEfFqMQY_H3Lf5MyHHo-+Rn-k8ItGnSzNAkt{1>SEv@%-WIESXk+b89?OX6+xc{$y}ArR5rGoWjSjlI*EEK6LzDTVCP-Ac%x=9cq4_aBHJ3`GlJ=TYUw%j{{0fa4!rR& z+>}!UMKND76jEwc#5=f*ulUxh(s&XAyeInmr!sQkMnVeb6Wgl2Re2A?Uxo^32;GoZ zlwtCPLVw;YD8(>)a{WAlbJ(bTtGlMsWXfS#ECngE$?@P)D6TlK;MEw6!$&8m^l5$^ zzso+vt&>&Gy{I`i9MG)T88}=O4yRYAf|m{ixc|Cxc|wjm@D!CWCKooRzy1F61+@lJ zsI!UbI+DpbygJ!0d&>-hxHncejK|@LrO|M8p;mj6RttoFEvGCdV#h67V#q8NQ^l#31&u_f$5CDju>NuOK7*4A4jn;Mml>kR)56!ohKk~x zM!9D$nj3cwqY?bvfh+l8lS>s194@VG8o|N7RMNwfF4TP1K5}D@T7!3}#E_R}@NbS< z)CKXm%+8Omd=t0>79*s0YDQUor7$YEI2PqMoj=+NRjll49R_dz_}bhcgBJyh=&v4$ zmui|zZ!!@4(r+gD++PZsUg@xv-rgV@H)OPvtf(snfnBK}!pZ~J7jf&q&aXK~KI0Xx zl)&C^6@srzrdk#sO-!uA*^-_a(9SyfEyu^^HXcLE5`EVmlo-af~fp?n|9<)T%Lrm|V$#`|C(2m|c|ulORuY zk1_ubL(a+OF1DLNi>tUYyBS@e0&D0BijT{u-Z>V7Tg;r$jX3yQY${IRu<83F0h-K8 zaQ=NuQVNT!^IK5!aVBMUe*ZsZ8h^AV9s;x(Y;C{$<|@EL$(s7?tw~^*E+w+mYXlEY z@ei4zcMAB%LMn#CU*a%r!A$EBtOtaT9B``AZRjz~SD*1tNTl@k)qgpl?@?MRKx&YRf{$(NvvNGf#-i(Zom=O|7n`6wRE`XX7ms44@9)^{L$0sVf&S z&COi0&6sUj47j9HBYVM|OQK-;%XD%0dbmHT$VV`m;+TxxTVe~CiF1f4(#%rNjisOM zZ3wTkJcnu00Ra>!Q@V1yl2&`|k4;2Hit1gXZJUQHAaF2+5`|hLmAda!Ic`vZ~mgz**c`9A~mF(C{#sv{b$F zL9DRh7;bMl|2@=w4-F(WY_DZ|gg(FNl17ra%v6GFXJouLVr2P*a`zkUE zQcea5%-SGK_;w=bYDB9!2N}pgU@9MFohl-VIbpeM&gNQ6@R;8|6AlKR5e9F~+UnaM zR@M?Li4n0~x8>lpngweR`T4$hPDQT*Ll& zPcE;*!eu3gOMZ{rg?l}jY>_D-Ov*^?aD*LJBt%(lI)dxbb}h17ANT~mh~8?_Y)k#D zTHpzD$AxLz$J1_(-8-?#*o_>nAWgDnpNi73>v(NqkZM%V06|G<#o}b(B5{w!`-__2#xg^BmdzVW0dA6@){YxPzKY1^xvuCS85ZRrXQXg`;f}E)QnRn{2=iBG3 z(-kG6wz_KsDH`cYnVqF==!MRkQjsQ_3chYpLcNCPJhr!0i>xKF4>-!Iu%;g>yaVwfzD&I4)OfQ!xABcW}wAJ33F_YM+1Wtq{1YFfuJ2jGaTX+(!l0 z=Y~iv&R38UIxC2A&XcwU%a63qv8jY=GUo)mikLF7&AASd<>Et*5|-2E8nbeR^o~bV zP8M~2YSlvRc$iY+0#!ID-YQ)k?)w{}Hv7F2Dws1JFMud_#~kNA{n4cG82+%iB3nYC zXM&z2G8Q?+7jf8sQbFswPih65PTAZWG0rklwMjl#wbOg;P05tiHC0|eDD8vT3OdkF zda6a`Q^54|B{r>GZSXRrdf#;Qy}pQQW|DF4=q!t$=H-nwC;u~8f+{!?XIa<2+MGX% zWRPHafZZWv2xO+UU|;R$^3tE_(`>Y-+#$8yreILBxkwI4U4G}nqqlOtY)B8de2XHg zKNI1F(_{F>YX}#GsYhDC6*P9wKM8bfZyx?*zudTjV*y4cB_PvlmH%M%{Ar5C=a8wW zC`A|xZ%O-_a) zaw;q)&hTQa;RBRl2gTciOGc5JXqFg3xql^>d~0;rjVn>*ktTD9=I2*^GaTZML@eIY zWT;?(DaY)FPrrN5Su{uZ=F%|`*2lxzw`$$Zd<*Y%NjNiJf{*A#Ee=_zdtj6=B~_ZeQMp#R8bjf$ebd9bL&xG*lh-vugp`)7`^CWS0Q} z8A>YSo-Xj4cZnW<_fATx8UO$gGBA!mDT_o$>?zwYZfVfR1%@V(;a*nV&ui(Mkv_J>yMI3_SB%_UnN;z`#AXOPRlAhl3!&1t88cgF`>$?N2q3pPu)c?mN)nhxCor z^BH++FxKH38i#StII*WAqFbo!D^$0#?>_6qg%*W-BA%E2mV$GU39O8(KSuQjuyzuNjgN#ajJdch2GJlTyj z1%_#iK2)|%=HC4VRc0BYmJ98vfq=06<9M+4ja0?meMvdo9|F2EL*9Um_ zc%Y0C>_=DcY@P*B9PX&_lz*@tEQ)uS+z0h*vUHi^p_-#o8K%I|QI3B7JuH?_FTn|g zC3Fr0m%G+DPJCJ@RCL>@K_u!VCqBu|9k-+M2B7$VG}HbbrpGTzK)>8)uS@LdIN*%b zJXuEZVHFtO*%BCw5FHl~Zdn7LFYkHd+gH;5Nu%hWzw`U&^Y#3wEK+h4UAZyge?i|5 z6piX*i1Kr@fsR&Ojju7QRFHv2cm{x5mmgbsbB z{@MBv1b)7xiPwgU#oq^`r%!@u)f~TJ=H`prk#7eDGgr^L!p&^$g@X3ODtI z;&y7i=s8(R~`?-{0}krM`TQt^G@nXJdnz7D{((i6qs; zLLiVHLEMt7(|14M^G|0`nF_iCbKTL#KcvR-bSP<#&=QTlkQyq*m=w|S4;^4_Sw5lQ z@}%TUh40xV#BX5h4W=JPw%>usHev2?>^kZHq?x~jg6)v7Qw7mf_x<*ga(ugDio88% zua^MBG{;{2--RrHo+UM!ZdBi;wL>rEsrV+B4IP$U&NITlZ#4Nyx$k)Y;#Z-|-+Cv8 zJur1(O;iqnNRcxSy#JS!_dQ49mkxS|G9CIG_{(1b*=_3H*LM#5gF*$L1MZfC@-qOc z?+0(EO7hu%&u08c4;;y7-QIyc30;+w{{OfSR*kMw zl4F=2thgEcJrkP(y(HvtnH3&qm@epZwfQ!P=&J?)uD|!Az#jXqJK*Uz%6J?bVE7)b zRs$1zW_u8p?g7i*cZ~IWPSdI&s1g$v-GT>xNUc_mhMoSNiNk=j^y*7<<3Xb?*;~xy zKS=bipZc$#Ad0~k8!QGKZUZmz9MHJEo4xQ)Qcn%0pW}B%up(V>j{Efp*Z$_v|39p~ zcT|(xwmuvbK~O+NML>!oARwSr=?E&lNR`l3n)FU+p;$mfDbl2aQltcw4xy-s^xjK| zNG~BkD3VaVm9zIg-`U>Z-3P|F|B#UZyzg4Gty!Kq*YCgjK)fgxV~44v0;{)|E&AU9 z8NdH0Sh?&yAXJJI@(Li%hdrw@J4{f-pb!4n*=LZ88%Xt8d$%+HZJYn`{=h20 zf!yFzU+c#IesR|Sv;ned!a%47%-ae>!Oo4}GClj>owNUV#W|T8Fu-m6h0V@3nB3E+61JPKcnm4l@j5gxD%iEtyzm3Rt}xwE6#F#{Z!3 zUw<>F3|?%UGb$#jPcnB=X){e9i)uT6hlCAEYi zPdeLB*0?Hf;?hA+`YPba%NJMJuUg)_Crf(t!u5yeNmn0MU%g8Cl|!QIxm&FUGtx zlY#MVx_3=izJ1(0{89d;Nowe&0LYQ!tcUrLf%rUcs-PU3KYT?c_S%5#l7;eXoBkmc ztpzQ=!l>tv64N-hVvvuoisvSKdDw^F23B$I#oM4ZiQ`AQ;$h2PE~KYqAtZwAu@o4nma2ybw-H}xCU-W#hbWVj?#=r&2k-@-`fl?*_LBn%M5O@MnJIY ztn{1NF|wH4%;})2{^ZfZp$Ziae*ECD<*|bk?lN%D+@{*@WL=~nnOm2_n7TQ#ZSY^i zO5Pp}=V)1)UQD*vJ9YfZXC$p+(5^MR6YPC!hDPvW@~8&%S9tZxwvbigxr1}*#YK`M zU6F!x@h(?L(`ZF8(De0CtI?aB$*;pAV+*O{;0j?9gs+uyFNBju=od{UJYnMteP4Cf z5fh(Z?|8+p6ZZ72B>G}F9qn0@4f~v{!sEBf*O`Pzhb`I7j%Rp4#9;*&U3z1LGn8{K z3;6AEZ##~TzanYWKCqxifH6L4y^v(X?-Zv3!itYuU@+>u(`96IK2pCu7Zrt1z1d5wV@)-I~mm=_$Qiqr?8q zi>CWacExXQkZMUlb|>D8Duwdoirq(;GG1ErSb_nL9$44|yN(@~4R*NGsdEYlo48G& zWTpA?K6B)Ui^Ec!_Tz9(=;j4Jj#2u}^I@lKhge=R2Hj!3hz)auKw0dfwyVeRcttTU zyj@eL5=7iQ*9~<;_-NO*%WU+WU6vR-gJSW!`1+U(ohvZD&y)w&p!oYhia1hs6g}OJ zbftI7AuUTYXKU1UQ@ZANu@+xs5_g$Z+LI@af6AKqRp~K8@oW;cN*6G|$-LbwFfU=_ z(L}>yO)?j^>~PJVanS9%%;T2J+inYwtP*1~C^9S|Pz9k+`s6wH3f>ASjV^s98MA-c8K15kv@`+SIGIQDfiXR5|NYM8oF`KDa{geUd#X}>_HYKbpLy71rL z&t8i&G2M;+Q4cQSjJPWA2F%-~tjOSlTKT3cKr;oKZ!0XAoe5C)v|O9*V8`uky|_Ky z=HPBp`!IWKcc%Oen~zBR);OEiRnzEF|K8=NJ-LleVlci5+bo@Mr)T%IZSsvci%7q& zF8?A+<7_i!7agqAEV5`{cpy3CpR`lv5>pcx-^=OhBb*H^2W5#TbG#RX+#_AC5 zaaikXOoeq{rLWMeGxD6+NBy+p^te+$AljG5C){#As^<<)WpC_Wk@Fx4uxcg-X1l|j zgs_V+zC_IzrAD8gXkB--lQq;3cUpgDhlUM_$qXs$ge_^6s@~Ix^DkeDoO^qrQyO(u z?|Pw7b;dg#E`$3o&o|kY;S`DXqch#C$R7J}xN0lHZpcga{0>qqBcK9X(f?zpxpx3A zENPexrMLDqu*lJ@j;J(c9`>JlW;axdu4)`R$7oSl>8J%&r?nYe94LT7mCv?tvbVWf zv?tv0V7_UycQMk~G6#qBAk^MAu63#%b9uP^Q)~E_4wv!m+-PoaeLO7Dc|ka?0LAC3 zZx>PAy=pICb5FTWB7I!+z6=`ThQ3#f*jf!qT$ISh4Ef)7n3vKDOS(C|gfmtG@kQoR zXd>(un!=u@G?z!T53zhwyN>2=>c09%SOL1yR6R-D%zj27HS>f~YUTwTJ-*R5_K9#! z+<33UB0yTLwHf#bjte;IsOOlE^COeR813PXL!-5=*9>ki=<#q;@fEOUQZ6D>G~T&b zh^8h_7A^j`XMnU%RR!%2)JzidJ~p2*4AU=_HtmL!Ci6tFYXq;(D4yW$2}K8BWM6Fz zmue^~L#o^&ceJkfGZW4XxU{CoyZrLpabCPQXEbEryL{AT{r1w<%NmV1>y2IQTF+aH zHQbK1gDr1oTkMmlnI#^!H^1vQoGRB%ochsSF`KJb_F<}xc}sHNZk+eV#LlrW#@Fr# zJb(jLIU`0$<|6hKWQc7F2iT2rG5r#)-^UAa2tj(UdPW21faK|y|w3mcim2%b1yZmvRDg$W^UDsqRo*9CONJv?eaoL$zPvHmP^`f-jg%ja z^I&@L9PiHOP?Z}bBp}0Af&WU$@iA#s99#1VH-($8lNemttxYIdVey*4S$8<2&%uN5 zN)CSC(YzAp`gnB#v9=Ph>e8Zdel2HmfD;8=Y7p#BJ}@G+uG<5l?5Wy9jr z9Ug7G*!dlJG{jB$eGtK$H0^2VV6Kt!-NcVsD4~E4w{F82aSL$0Q}?&5Wf9#td4zK7 zvhA4>9FW27@7!o~LqL<~fTU=o#wsNl1$@0cB30I5b3SnjMT`c1&u~Lt8 z&B|cX|FYNuo)7~9KIj<1cemKr>}%e#$9sw^b^A@PmyItWG)&eDCHIHJNeFndQ^H-I zD!ZXmGkJU`J;Shp-LA1Jg@t}=C?-dwMY2r~a@YOct)Jh@Y^(ga3Dk|cQy!^>>EA_{ z9UXN2Jg^#%ji1hF_=~e=aQEhHFJBSr&!f$`fA2q#Jy?rm3Q2ax}0gY*& zA=LE}(1sI^2t9kzBVA>rDhD+mPDB^Gsx`S`D#u49tL6R4UmjorrA{Q(2XECzvG3cvmbp)-d>5W}r%fvzMVigFe4O_mO1u@v(ARe=)$tc5BgaG> zi+x?>yhW1NW3~PB*z}X0JDDE+Jsle*;)|==*=iMHEyJ_?xA8wwuQRl9;_9getpm-p zsox4uF1lUkVaVu{%><2xH|?LGpSjy>A9im@Y^lU(-C3Gw`ff~qo2SMB?f*^3znx20g)Y*TAF))~ zD5jlQiy3v+^-PX3<|#LUM^^V%#@K2sYmMo=;L|P%*igV`o`aVj zqm+#khG(zO&ry6_@Z1}(=&i~kyRgA9t#Y>LdqLm>Sg%c2dF@`zlC)=E&1f-m7_8B? z{)*kNj`vIf11eH3lQC=gIaT)MQZvcjl#{_>$t5tc)^FhEm)5;6vF_99dhUoD)6FsR zLK$|Vh?D+5*XezFq0)W+)%jy3t;2&qU)rpJ*g|adgxa}Pa@G5TrnYw6?Ed&E`xJSG z1;l>agGGh&DMu~eYt~-fMwsf)?hayu$U3RdBZ3@6;f|$i9^+RXpX1;PZOB@S@cbKJ zd@!aB>v?)vA9T6I@-)PLo-U4UF?>He6!)rpok|u)FfUrij*PtGv8}GHnoPdoiqI^D zU+<&rf|8ijiK1eDYy=<0v~S_QykAAL5b)rRpzMLI&U(axLCij8b-1-=rue$!^xfey z?2FR8C);~<8IP0}kzbeJqp9wRxqAAI$w5X2z)<*u`KhO<1N*3D^|=yN{4O}%%9U(U z(?GC8lDUgO3Wa3u^U${HM~{@8l%&yTOr_S3OB?d)CzB&UW+Z+Pdpbm%<;B=XT)=~MBe?Acqu$>nluAWW9KD07yT(KGD=*h4= zXO&7OF1%7z|LiS15xa|-v>9E@Gtm1rJZ{C`fA?sXL#M@JS!<1Bcp1_&mVtF|;W<+3 z)&Lu)dNXGfU2{`vTu6}OZs|LYlc-t)`^rKk-pbX|(|$a%ww}83`5uH(oh*#R0^PPN zirOd6YIv?kIg8ScEeCiH#s1CyhMAN5-|>hF#sXL)z3Lf#-`Q>;fU-N~{G~AoSuIs4 zzw0qyQgPb!k~hG;Hf4jKHmeKcOKhR7%w;E&N@U5@P3G(fhTYi6V=Qj&wVXT8qcOOW z%U*`KdP?-b_ETp8f8Cu043udXMLzjt2d8Iu76G*r-3?>FE!4czjlyJYv8+v=p%=1< zL~EA%6>N~R*2X06>c*B8&NBu`+jA?7%AD`Q2B+>Bak|DjMj(7>Ldgm>lGcL0%TvhG zHK!WZ`b{u*R+KGEUD>L^8F#UqoVyUk5KxxN&tB&b95-9;o9O9h0~^eE)DG~l1s?9n z3{=5QeTFkEExhn$wny}0I3e~bpALG;9S@cTK~w3}0#YL`YJh5Tk9VGH)kxb<>MH*_ z8X#iWulKGokft47MB5%Is2LG<6|a`r6Qvh$|5S`I>E`|lRU2~H+IM_~jwpZ|#qq!W zY&#q4K8BoHOx=$bt=(-X?nDPU>RKVg>mVh}jAIx*jbHcc6BtI;2Vc%~vK6D@O*zVl zm{7xw3l6ywugp$rDwZ6MULVE`;9BDaEXOH*dUHz<=gKizSUV)_ZfI@dmxS@Hs7A*~TfUq* zw_cl-!33L?+6fEH55|B2IJCVMy;awuKcjFAZ+s@79R%wvnZDL?^>{OKr1kWQ2glCE zCGra%=qX@F@dPX2#{MkWDR5nDi{M%vhx;sTYSnR)!H{YN`S&`;r>{}SN}SCNJ&H#pd(Rxgto_-g8de|ao+i^>&frp|WS$_a_^S|9*M*)#69kM4T(wtN;% z6dMIWVNI(y%SKJf=v8g@nsSOxLRnu~IX12jvfi$5d=*3+PvP{dTT&B#q8l|AZ+Zo~ zA*XE?lk5r9t?vBr<)lI$y!17pm`vQ=>5|Pwm~Q=YYD?hzPkzJ27BOO2sikezIU2Eb za;Ef>qB|#=qNSPGxvf01k$PNv4$J6{vYMYj9jwfp&x;NG_=1IFL9fP za}?9{DXM3$25a6ff}I_eUPh|g03W~3e?6EEfAl1BUJ}MAq-4o!XoaP$(g|h3k708> z3OPaEsO9^ugL+73&mUKSK!e9-@L$)w2L-qU@Fq{oTZatD^KC71R=WrkeQv6eJ}!|u zAiaZO84!IT?z2rs%a`(_u6Q`HVW;AOH(FgQ-P3Mkyf;h0X>vAL{L*bSZDF3VuCz#u zF2-Z0kG^uV@{-Hal(mok6BWeSok>O-#jCdy)58EK%_ zNbl&eM!Hz_MnbUG!Q5WrC)q-mnEXx2^6p6M?4ntAE-3mscnj4#0#p_fZc)b#Lal8TjhL&NDacPO`)M_|qvxdL-)8~a{_LrFo zkl>PN%+~(YyhirTQ6=Mhbuu#Z9Aau$bw_t}6Ei?KcgDRk-q9m=?fbpNT7|eo$^izO zQbQn7gjyv7e8+oW`x0LJPVnWp-ZJ{wFZzo~`PiJ(&?p&j8)iF`Rb~HYAX+J!|Bt6i31Ny|~u`K899%r4)EaWA+98A(@6mIJ=qa{g25%zK^n&_9oxkdbJqmwqCRfjydhHdnpp509`$UJ~+`Xg6 z(l#Dp68mGBw?y0v7WtD#fh!;|l{1 zmxn3^?5g%FiwMt(`XJS0O_2`%TTx2(A1#5^3~q;ACV-J7U`|+ zAP8g6A(@Nb+oRuHO78jbjr4w_?%oBOAej9@?dl9X)gH^Z^r^ zUoV~NfRspU*s(w64P!7=6bf#IL*Nbzj}b>Ry@qASrCyfuvCx|B$5TPbF+yG0dcSas3;jr$q1Ethb}Ts6y@A z%03`XXWLU1I5w79@0^%&#;W(>XQVhFyUM?gc4?#MuIehEbN-(Du%(hmL>#EPwN~-V z94C05D}G$QacU(*yTjuu&jR$iV|1@B55}g!7@66CG($^#YSld2f<&Bwo|pfX&fxwe#rZbV6M-}2jQHS9-8GuzQ~ zk<3}|Zw2UZ8w}CgAYrvpG6N2-W%9-b!c*4S0u?DBJFg>#KWH&E$6XC)prOXC6*@T!t|DI|$ijU+Rs1%rwr(rm{E6fYmx$ zHGYM6QO9+2Yj1&*Uf8O#m}x=z(UC51HMGqq=*Im#7F!{`#V*GAKn z>$XiBAl)TL30%N&zfIt7mD=E|_uZYPt(H4KqXtbl;LG8Nh+2!zOV%KPwitU(?fKF? zT*6@S2FLW+M?!YdeiH?;$fGJ0Q;aEd!+2C;le;&wO4s40mqs&m zqTTtN{H7N|xtmt3u^gw;XeyL7sL#f9zmkUCQxy~oe`@z zeQ2uw?$}7XX@duvMe0{^aVJelzESSSonPONrqsJv!R>UdJg}?+oe)3x;2f7tyqad~Mxrxt7f=b`g+16Mvd38H{S8+~_bcNTHo ztZOD1kT9#A>~B5qy6L_oswcFRJOskAPmk6W4w%1GR0=Es7Z84PJq5h=1|i_BKjz=d zj8SeG(#PVKRlmoQg)&OX+@@xhny+jDnG2;Y2}W^(e=XW@xC{8SiI<=U+3IYIcJwzXb7tOMjcXHb~q&T@R=G``~$q@^4 zR%a2n5BZ}e&aT(9hEiJk1)u$d{V*)BmThs1f3o07J`)X#j73dvd0$N7zwc+G&RvBllBO8ec90*qXGYE zH_DT98o1+}yPv+kScZAYbwLgGPt!gaP~J!{13F2w?2#yxL%+34+cNugi{5p%<&uhw z_t)(kq0DtZLjqkSPczpJnlm2Ik%9z%12szZSLfl{MgfqLxRTD@!BDd67!lv^ECLUH z`uYfFWa>Hh+mv|V^kX(gRCt=ZvK`8iP4qlhrF2RzyM9o68qN^lR;~$Vo!IJr;%*Ey|6w(e07N?2C)UiBR#oQwKA!hDAfxL5i9ORGt=J`7ghGz19@4 z+Tr1%Cj>z}G_v1!7-lQq*ya|C3xzpAYb936qCSUZ0F`@_Dg_S~s=mUP;lG^Z`6Oiz z7;qDi{gEnZI3def^u(uGZrgklNh8r&Vu$hob?`IvAS1Ad$3G3Rt)hvYyMX&Ko4D6? z%YP+JO};=hF}J&T+`FstJDL&JYz(gxLrXX~zjodk^Bhs@veW)<*|a?6U2MVG7i_q( zAJU~gE}JcIJ&uMC)Y>~ZL2a!YV#=&-(CdKk_PxXiWBMp64=u|zG{(cMG3&BSGIiWfQTbfQ>{4o}U9#lvJdKNp`1fJD$Lv03`D=H!M6}AG1{!gIO9sW} zks!2rK7Qt3-BN^kmm> zbWkJsM)pwHB#frMP?BV$4vZJdT1NRXC3~=Yv2v6)i*k;(fIH1wRX#$4ikkUJM+_TM z7g4Fy-m=_ku$T@!0W*;BntCqs`e$;X1TY|%2kUk!v+?!?VUE5;mo-2=8SFsk$UCvl)aF_GP(Am7-ssRt;G=rVKbS)@xri#q4tjK>CAP zc5!#-d0Oeq-TJI2gile~@ZhOoU^z;tZJf$SzimlW??2lX@NBu<`4%qfroP_Dzs!<9 z1V4VbPy%S$#g;L)G=Lquncyrn+T3tX`KE-)Uqwky%Z75frKvmnEx6R(xyswo6awLX z(g!y>CfG?%jwWXpyDw+d{@~3cJdg&e~6uGYJkx+ z7aTwHtRqz-ju^KHT{j8UbBwXB+o!{hRI%}*nd**GeiRe~DX6J5PKTJR(%f%I?=(n> zhpN3#O|YH`G5B@wx5)}9cH4dYq;1>hX-#YHa$@_=g`cld(>{7|n^vc_`4$)VqD{oS zX7c;|y(8u%CPx|KTYk!`K6geF6K9nh86x$|31Ck*`?|XToUhXn}g0vfZ)t~nwSXkk?CnA>~Y=x`t8I{X3GhA0+Cnpbt zUIF1a(#f}TlZa5Us$jF^jp@wZzl5amp1nPrZrlr93)ptxdLvUld(nsJNq#wVP{qAS zRNVA7sUt+i&8!5KlFZT8g2vi$A(7fRL)4oThR#pcatd^WjUlkaxY#KDxXq~qEB7!&8qLS8v3{xuq5WG3d}#}bX(GbR(-lh zuMG;Ej(E>hnMuTT`_$sCt{Xf~RfMj4V!lh!=K`)lSqsk!o~u_m+q2jR-Cz7}yd`j_=t&(K!(J@?0^dL6wiC4{~ZqRw;G_-i}wcvyl>65Sq>Js|A9%w?zjIXMZNtJ@%$*-3e?+d${r)laKD5XPbgWo1e1^81(-Yo_+Y z6#WpL1?F!1`Zej?Duh;j(7DmyE-Zu@1?trK%+-Gjg|Q3f0R}rCTJ-|tqfyJJ)=d}H zj#uq_c4Hm=dEXrA60Z%KAt>(Yy%{zEgK&qu3-<=X58H-nuce zZ)YoZ7k$H9n&ff$<;8=dc5`@vRVaO4>8D9@r0bI;T>R~Ir}q`tSIUd`-wdi*^i7p? zrq|cOD9SqTXjATa96}Vzv)1QtGQ{H;QJ^SZ*voB2qjN*KUvBh z_oiIDyyQqw6_ZWx^{x7&-&-AdM7O2x)aPOf^LULNt6Q`!MjWkVBxosR7r8)i`HQ{) zZQM*HyLiVCAV7B8X6sQ;j-{2F-dtML<+nQKgd)+|y5PPW=x6qnEUh$wpj|G!lC-(- zf_`nckVlFz#<+_tDdYZv+(Pv&s&uocUg;wiQVJ8XRg3(E37YzytGf#7ir7NGH}oo# z`VuhMNh=5xn|EpMbk>=YAS9;Dw_e?A<*Boud{^Z8fPou}Tb<;V>aAyaAIQjcW$xXS zm!I3^+~H^iVd&1=+ZrHTj}Ci!P|k2&1Dtt&tJ3Hv033%-5$m}XaiZMWPhpLWrmeZ{ z!02S;3)THRvOU+Gn5-?F_TknYf3-YBnIqJ2*~ZPfi*>o(y zF$iMv!uAeItI*r%*!(x?ay`D9M$$$WWM%E+iXPKYV2hhW_hR-5n{;^z8*gY>LO(!C z!VK!iFbVx{5(}#o0S;#jZFZ9omMqDOPE4!Nvl=g&jVPAsQcm~1w>G4v zBdGV-BQ0kxPxk?>4dB!jAwH>;Gr-_=1QduWwTkz<_1jP!OT+l(*!x?&cIhcMJJJ0T zy9bpcnLE*P_8isph?@Kc71E!Z;U;yTL+yf`7dD+SseTc*9LMMr=2RwcVC{TIxN>ns zCG$(eImvVF@JU1~OOmYk`WM@IA_g%(^-ubZl-Zq1b8hxXXj#w zn*3Cp&NZ%cDretN&V&c0fMg1%Z5cM^HIlj|zPLN`rd^#`k5xrm+pQ2eugr>^Yd(B; z%?H1{|KzU<*{uV>A^ENldjqwcA6j?T5_8*+@v_xu4CEV31yCSue(3H$zO%F;vB@d+ z?JYAp`I|ULroYXI!gL#-du~ijF2@VQvil^%u5)kgM&MnPjfH})^v&2>zq&qQnSiSX zS5v*vI3)+%HSs;vOs6>RDHYY3-mjc#*qjc9%rnn3-MV+)@c4KbAk9)YlHbdu0X$p2 z;Dz0k&`g#f3aG2 z%~H41@hecDW>BvaEC}2E-tx}B{QqFV83_SFZ}XzLuK`FH)jYFs%ekm>iSjq0Ep#ya z{zs75UoK`Lg7FWSUp{pl3@4p)y6PGp0O)hH$LWuRNTANSs}Y>a=V?53%9g~g6z>`F z_~#FE_)s%P)dYvPO5-@W^*y)@OVXlw^kftI@~;8l%O~^pHx2Z?f$uppHf-6<_akXL zr2h}r@$qPvQe`u6iKiPL_L>hAxhsh!yB>IZim_mO=Bv&wEp9BaAgn@hp;{K}04PkmtY}|Hmp%sRN2m^v#&8g5$1{?IHPL9}pmW3OwPK)6Hl+ zQPt6JB@Vp(zZ#tAl>lD*ZbG};uWO*cV`T(+=PyCp4gY%X z!ATKu0qh~9`<>%U(2Jn%ti|`@fUu^2zsmeEcmln*H{1Tiaao1Ei#O!{TH670owBTN z00$I$?99J@0uwl%MRl99d#eb)3GZDsqQc_*57O3A8qsy^FuR#!W)^w;AGX-`6 zjO`K5=a&wwntv_xG|_*0!pSLk@-@WG@~uV6>3?(SfRs=a1El1#YL0nBYzU!voOFm@ zl0R5({s=rF-gAv@qMJfi;p?^QWQQiiE>Y)YTw^XN07A&C^Uyp$tVCoa04C_XpZ=N- z9z}g8MEc<3_!lj~nf%!BiA4f&EwmmEhwoQ21az49SP=OBnL^g;mDd#4UzX#bJPC9H z0zn-ow6)3u`jq)kNF3Hgk&qrCZXZ&=yh8j87la+Wnd;9)3cLh_d?gSyzb*!pyf?&b z=&+QOWdOTSXY+Jm1iMH8_bnb;9Bu&HM*IE_`Yf^W?`MY5slz^^sS7+oaDDymUj6BS zupO~S&kntbD_|308N*G_%q~HaDL9iA?jBH~{_T{!xdar7-ZLq|mjoQ6qEnQIUW4Ts zu>W{Vi6f~o5I0hFN_n}%uHiDV8;w*$-SPqh$z0p@R!O$Qo;VRM#Dk{e4G;S*@TfCg zHxJQK`G@>BeIqhsbxPsud)k1oX9f>W9-0t%&?%JcH^VIt(uHn8NqWqbhm{CLVZel( zyRFaV!K0X7o`D}$H%UnCz!Sg;aD0wd*~&U13L6#`Yc`r(gt)~z%?Db7xOO@ zH30;IiO+g@QXf=yOwW5<{_7V9rYI?~QxXz{njn&a*=qUl*8VIY1HA=D?>w3kjcUQ(l^a3D4jzn=tamo*f*@Wn97$5lLJE`|Oe-vp+&=Ia$ z{GT88mo@*( z{k!v9XI6 z@b9DMUy}2N14x6lLsE+x}ls6fwu5Z*|Zn-V}{QOqUp1XB1(Q?iiz6rw?F&sYrF|ir7ZtrJ?Fva2;LR; z8x>z&eh?h}R8pgh?-mVNf2=NAYtADNtvT6gV>FDcC-K5cgh+}30 zPX9*N3|JuP*H#i5a>*Y7Nx1np>={We0qP_k5~6IRObTBZ{?We45>wK*yl%ezD|Pc* z7-DWmlKQNO@bD<}OaITJb4#_VR~Pr5c9WdxB=Kk*=bZbZ86?N@_uc+3LaIc^o>tZ6 zip*t_ImHyF??HbT@KeJ_R-d+YcRDzOo{`hzr$&5ZfNvA^$I)|>YD8Lco_6OzquW!Oh@{>=CfmnXL# zJHk>&$)x6boWX9eE+oxhAEjvt2UJ*rX85^~hijo3LO={e<{ zXSnU%WGM8o0V9$z{NUPe zx*N&!gOUqLK0nMtyB zceekouB3SsHJ zN+$fQeHt#!7Bw5tmzJcR#FxHUl8CM6JZ}G_)j;*sNbj37PdFf$OXmNG%l@w}dnC^( zItP#MbHnG#Pv6|Rh)LqUkyW?7FJZ$HO;?EK@p7%=mTTNlUK{z;YcQQ`&|p56`uvf6 zmw|Em^tEB%0+r(<zTJZ5Z<$XkdTfD&N+~3K>`u_O0V@b)JYfCRtD=dB@ zjUAOoI=W|7H@B14?MfvYa-}8A)(pCBx*Sz`E*Z4#D~Z64LwRl?%Q_3KoIS*N#vM8~ zj2n~T|0TO_E<#jU`|oT^UO;7so?XBAcisgaKeKWr*{pGTIA&$RXU`^rN2^gw%JE-ZN^F0YSXp9BDZ7tsWZi6!Y?tO z2De^!)T>W?_T(96ZJT1&TDuuKSI=N-@8=c2WWnlO2q2Y-GmIrl-o zCW#2=!Lq(nOL&Nmq%E55x;G48d3#aZqsOssy-X0mqQpGb+`Jh*6eke?BiWa0G_v5+ z)iwx5?#PR4NTBW)22Hi4v@g^F94zP^e9$!8bHnS%p9tV$K7mIAT3)v6N#@4a+3F^n zpG^Fj&=jbUMY%Li<-SzNd`lq}JYp1YImq>;zH{W>(+=keD=PWasJS^;t-3X?oO|5s z1f)a4QvW@b6HSc0FB6r!X0Rm&YC~coSi9IP0k^RrcNV#>=9!tlYvSLJpa9t{VoH!J zOU#7@0M?hruKh~OJKI6W2sQbIJ@1u<9=f6it$cLM0<^ZgQQIfC=nYcammg=65LFud znNdRLM9xpk(4JsVmCqUEnBbg_XA{qH4uTGy}-&62YqL8)yWngFr5&uphqtD}fmqABu=Yp2Y zWp8!fOOtzTSgKowpu!otCup}M(+I|oD7hE>W3tZNh$uNQhu(%Lkcvs>00qmfvDNQ` zMK-wQ+no=?eG-)kmZizK0#ZbG6*B- zic$NHbUqgK2r+*!6+!UpOGk)z;~v|;#=1;>%OPb6CysT=8Tj(=o#u#87+v_6;Rtl& zc2dfr?a8w2*~dt)9_@0LIaLyF?QVsf&vii7cUCdSVDiWO8kCw(6Zp@5LI%UVmfZ9z zA8L9H`(F#LEYI1o(|@Awa$H>GI@2ckM9^>N$Zuay6LUY8vo7JN!D!m0G0+KY1<-P!OLGA-A z-;&PWK(KL*d!eL=(>uFS*iBx8!`?&R1UBOcTnevEI7nBiPG}O05TYbisOwlz9_s=0AzUdW4I`Zy?dD zzGHw{9|FyjX$(r;P%J5BHuF2{rQ0v)@-U~kO0a#j-2ZHZbniubvW4r&QP7K=nzg7vYq7buaf{_z61dp$&RQ!!R&wf9wr)7T`DDS-4i8I1 zXMbuC*yxqN+6%KPgFT)7Ba&l{kexqbH5G{u*%!rE6wbB?BRv|)(lBOUasgG+JC*j5 zx?L2KqY7*@c5U)BT3TbDim`|49)mvZvQ$mi3EVVX8OC;$_$va>;-9QV!~!u)OMc5p zN((Xxd6R&5HN-9rxI%jvCgQXIOiQG(pWo~)t^}FzY)+ELGzwLtL<<36A@$Z9Q`CdT zeEjI%A+LcyVU-f2`5DQwX^{04(0Gz%V%m~!7WkA4WSktv#{kR8(t4M0N?e*7D(dpSStiEw364Px^tiVbr&9g>bo`g*{r^7#Ul9{F?>n8I z$*_>j4NWNH%On=$o25 zwopmcMNmlyIvz76zx-N%jAV|95Z*LAcYzDw*o1Rg&hPSc!Z*!6pFR^ntr)dHK9&mZ zN6qPIr~1R*DQ+EcZ)J)apkq-TaQ#Ljvp6jW3?2)WT%ybjHsQvM+*Y3imzT@;`(Hd47@0D)n!oDR`L}P=rO3!=Ld5-- zje36kqy$hFF|K=83(xXI=)ZHZq@%KMK=~*RBz|1_b}Vmd%6dQM>-r9W{@vdS6|wjZ zngQ$)aaW@?KpU?*U(S6wKE(Z=rPj-g9+wrt2_1({%_Ri-|hJe25LOHW?13MFaEXVJQ(_JR*3Lmf;S|z2I%j znM(ev+B&(>e2?N&rG4}~SR^?Xq=%o~FULwOt!pg5l<P@q>dai|zU5zjAGU%R)ZJDWTVTc0r$C?X{Dok$)8(NHDZKs+-v^`)}UK@ALWq5w6 z9w@7o0F6Hj7jflU01Q@H@}`#VGJaguxM)NtHxx7Pm+jUG2Hs3pY@e1*ixu<{v34_H z$7L6RW)O6BJ-9cqSgz}9w=a%P*+c@bCWH}5TXzVaop$MO3$&T(iT9bs4hknOPr9~>B9pq>hA z?1-re4l^9Z)2D0_{0F>WyEJ6ntsKJUK1gNSs&*WzG(Cdae|e%svGUQUz!lJ3nz%hW z^XiL9H@0#>e;~qUM(}=-ll0>7I6)Rk2t35pv)4orD+_gScMUojUR{ zwL0>=SU#Ka%-$kr{iSd+pw|xo5H8pRhkY#}B_pXg$3!C}vRj*DHltIg-%t3MbGG)& zEBodJgg~#ax}0^+D*QqVeEtsyQr7aU=T3sL*0sWY|1iq_`aOxFa{nc?^O6~K)gZA3 zk#2>8ErZTD5f$7P=I3^&@?t{ZzB;DH&$C?I*8u8=eq&gau;2QQTk~2zH#&Uc6GA`R_lRGa#Zd8mD%(9~Dr_#A*}3~}qVs`07}!Mwv=B#!O}h8W zj?)yP9WgTQ0LtpU#AfZ+aBOYnDDQ1~zr7J}T3=u5Avc5ChgQ|~TsJtj?l=O_)x4Lf zHdh3v2xLjxvT)JUJM68+*W&FAG@B?CDg4$;AMLormy#L8QQA_*#0RFS)TK`xrP|m8 zZD)0X5B+CJM`x)`H~<)M&=+4u)>FEnJ21VKP-*vT>{MO3RvwsTc9|i8y3Z|4X8U2} z$zA6V-8&u2Te3KwsZ1oJVPbH2YV_Sss+g!O$25`koY85}kYNxkoR1&+tfa0_g;t;M z?H;b(n|`Qw0X;kcwH~d=lJrrK7p&Vu3nLeazGCJ?uf=rMuRwIkTMabm@}AL?aqlBS zuPbu~kK0+1!4?Xd%g_mqn#dl(5^r??Z!P#iv;JcJ8Ab{cI70y~g$0%o+82@yIf6uB*f%`&dNlS8(y!%=kW;#@crGxK#505~+0KKhzC&xT{iw5w&D*r`Jg zI(FQtwq~zuLhzt7Y)XaJvJ*6Tx_4l0%bMj`Ug12itcMZ85Us(qQz3>0BB_%+$r069 z`E~$dt`>ikMe%_JCpBf4{e3Il)%h#KNQ!SAt&EhR1#~;IBpocq^ ztZnhpuI}z`t-LY%9BrduMycQ&5~a~Ln(+)n~E=xV{QsNaS5 zKSerlos$@&w;Kd8fUzJ$^KRs6*c%g{gB?C_w)5A07XLL8S3HIET9t3w3|+yfY&A{m zw%$*q*<|4qjbHfi1>EJ-az3WH#;m>-%H@upFw;9WX*XP?tVEl(PW81`q-PAxNs0jm z>Lwx4bk9XDNj&1If<}vn_LousOjT#q+_Js-33xI;bvM;QZp?3#S_f!9O{!Jn`DUX# zxR&+RZrMmIzn)kA-lHN3&3|))(95d@euFJeItwrSn#?digewO@@LL(cxg(hx+8$n1g@%RN5I`-x<3X-2|qk6@h4ihqBU6N-HSmoi>RvS#s7UuQyY zZeLnGf`qa|d4@+3+dTEE4GZ!EGrDxKapCRZl1omXmirdxX0ac(Rr8X?s|?f9ihTY* z%Dy}h>aG7DS&~o*MYa}h6qTK9X_ckyyGo2*Sw{9yR07=~zg~w$f=Z!9cZmGShh?({fj$CU2f?5C zS)t1V1Nv8INaQy!ah|v5cs#;28bZV3au%0ARVWs8+0wBc89Xot-5_2JsI!O$rg^Sj z@kdAV1iQ`MsR&cEwT~W3&-G=eoT7A6->H z?Ogo(Z3`%+CW|+ozOjA^ROu6WfLY1BdZS@O6AVbD!rKj5?{XLBbj@jeFzfvu}3U>n9vV%I!FlJ z__BEYK3_=336be4OY&j+im)j>iqkMk&puMb+N10PXpranp0wx1(CV&uPnIIU;GZd% z7kn6-If*e@usE$1o72v9Vjy$UoH>1jny$wA!3PS{x#6p=Lc*fOG34#Do}xWyvio_kj6 zfn&|}$DN3%{oxu{ChsWR&E167DwZ1;J1r8&h)(%?Rem)Xg)Z(W9j@4gFRbNxA{NB; zEO4mk2M~@_qCm@Tn6aK(yR_Jt<@4w6H3Ve#B|w5QbEn96(7zRmIaKB+T4wuovEn-7 ztx^YOgh-l);H#wGq<_e^&ezDT9pAnJ_!3a%?l4nX+WDnex*jA zqmPem2%FdipB~5+E0)>{;lc+od-QsT`H-A&qVxBKIl_tV&mpj`e$X&lwr%@#CrrA& ze4uQ7qmmb!_jsO#csR(9Bw$Y18EDfj$LZVQ{48i#7qE= zi~bW6r3O54wS;kpd|z04MN;X2QH5{A)OXSeJbmtM&Q@omdF}Z65$xEm<|eBCe2T}Y zf)v3tG0ktvFX|fEsp#8Bf_oB0De>{3uiOo$jt1&aXzeKi(${z3k9{!ydS#3V?&j{5 zF+QGeD^aVwxbevc-pxeuc;61NN?u+}f%JYgBN~N|8(|`kw!L2^_M|rB>xMJ7gl1u~ zo#S6G>m_gT4K4XU>AP3@-W#e9HZs3Hd#v@V9EP6;lqGLWq(96Qpp-KJgSeDlz5(bh z0I3d#{YJUVq)klqlY(!`I_z8ccFWw!dO!hCH(k{Vq@H`ixmKboLeTUh`eg|(jEr}_ z6|)v~_X62)*@4a8psX0G`+FA`ZY@Vl!xo{2{cjUPpI5#^#<;}1`sh0DZFm6F?r3(m z2|-ccl^pqgrD55`mVHh|YgBkk!`-N6mr0rR53X%)dkgHtEua>PU0(aZ71)O?3e$_H zPxd#dI&0o=#{=ZoFX2>h_Q&MC^mtbhoZ*4#m+$z<1!+e+`Qn4;wp$;@Ryn|X2R$g- zUhA!F6^1pE=g@_OL$VKYdhJ{dRt6lI^X;DYqurcJwM)&+_TD)AeJIfAf8=rdw-XD5 zt~aq2SIoI(d)ZdqEfD76pv=M8woqT10IYaFaK(?S_I(F>Zjl3mh4q8aEU+BssL(Ut zL}p?~3W}=jc6O60uE)OeCy5YkhYb8B?r!+(_iE|;x=z{|Um7vI?Hlgzi4lOn^c}}5 z7oSozrB?Weygixs(bqGp0avrz7idbA1<$#UcfZfdTg~^2p7)5WscKlk$43w+HUzxk zT|P~_!ZTcc^>v8BOcYK9m)%uO->7sEX3N}QFK;{6Pl?AsI$}J6=UbLVI=XYoc&32J ztw`u(ZR7c6x2C;(2{Kn1f<6ahd*}so*GP4Wy+s+W+D5tZfqZ{pCJ)+9T3m zSHG6(hoz+tO10BN1Q2px*0a*N4& zJ|eJ6UP3e0>TZym*R%-r&cB_x#w}bbe65)M)q%T4iv}N-hNJTYo;7Gkp47g3^|yBs zR}MeFdD0Pu!;X!R3A;(Mn50s}8qCw4FUSUZT(dnUz-XLO^~I5AhpNIvMqv zqHvlYs7l2%Cuxu*D{2$D2dVG@0pV+W`VP; zvk6^}`dUfz-uV?U-pnIwT7oxu;kJi%N`&%@Q`E7XTu<|j>r0vS7Uh`Jpq2Ke@DF(# zZ;cCBG-i@+qelAqI>;JM-ZN=8%`8Q63}WJ-^rF^RqA@q*SeF#{+c>eltqU*G6wH)X zJ+cF{IQA&X&B1t3v`4tX7(3`_>5LUTPouK_(p8;(VlXI|%EQiFE7*MTb!QlwkdEd_ zb2ww+;q4p7&Qe!^nU|`~@s*_V4#+mG9nlp+sJG9rZ8Dgu?n7SFNZvvdL^pC|{GDsrZ*P6r=#<~)D!VqJ@BnmpB~y)f&5>*PvAyTU{*|(H3*#MptlxH>dWAf$zNq}2 zOGfb-$4BNtohV*$3&mrQ`e%pWwqNJwg9uO9+f^HCC;9fF!}Z$+?zooD`twv%+rU3x z-Y$3QDYVwB$*x!0^l^DGR9IZIVu-6GkCp~*UJI{1%as$>$6LANR#ob2Sz|1MAHU!e zHz+AT##)ys{zF*%FdeTdttA;Xfs%zj?*a08BK7Uok`~ zDtlJr=5Ilyjshuy>nGc6?NW_`XUj@8P!3TlIJt|E!nn@kYk19j=yp;Jzp=uwV~}^E zfP$vNSQksI#EowqhWE0FjWgY_a}h#9h{w`vNs@V}1|25bM-SQ08st=(T5ohpp@0!utTZYpOupxZ7C7q}k55OXlu!b!8%!gUe;$UMYQg8TL}j zLpV*I3Z$aW&zsd2ny1sb_r^%6?Ub|ca{hXf<#ScZrImV);P{14P3ln-9a0UqG+$>a zO>hC0u)VErZk&28;Yc?S0a)e|SIz7&dysXCE?H8B*hEI(D?fW^Fq+8?f*-p?uA(;2 zaPfuD*?)741@kL~h!vAg;Q83I#K+BSWiKED z=sA)OImdZAE3H*?Is)ClOKnX|L=8joRiQj`RQ4yoH`!m7rO3x@Dh(TCzLUR)j3CHM z{ycV6_+gKR4+iR1JMY6EFWbT|pck`m75AB1lyWTc;$ZQ?Ly{f5a5HbHxQVPO;hb^( zH+>S60BI(q)Ho;oh#!iTPlCOPCWKe*W?@Nwh5tD7Ik`vtoqn;Md`|}~s&0z=zf+_l zMgX0~zBUBcQ>p%>P6$f*_?&Xfa7TP;$@_qTdF2g_>QEZ)bi}1!?t<_~U?`y670_H} zI!%RrtyM`?nm<1mVWIHT?=%*cR^{x6njCcQy$f3P_#$H zZB*jK37NJjKejuf4?ahsO5YXh>q1SeLBPG_gBeR&o;?DjxW34~;TqCI@p?omeA`_4 z(02Y*mUnZg)Z=T-Y%^WFSchmN)uvUJ^jm_cLT7&Og^iWmRE85}X~72a64{m&!zE(Z z;!JUYiHb1{{;QWtfUcbsZ|_5KjqjW3o&XtDd;ImU}Iz1VtYX1H1L+53`84SHY59RV$Kr+mRe1CxFDz zE{B-$kP|fb_y}v~F-ZB$<`ewBeBd;^6r>Zz)$-*FGU_CJ9bu5qpNunPwW;ti3sDbI zL3NJ)%-_3!*i>TJ7P8n+LyU^Y_`CwRQO!&|9;v+L&P;8wid@`YHGp2eMZYD}uWA2r zcYMplYRr|0m8rK{4iD+@P3`noB8``Nu74(s56u|B+>1xY;P6CqtIusb%Rc>@&0dwQ zw0mSo{X~l6E=r?3wY27q|H1E!#}}cb!IZJVevPPkX!BrsO`q_z!R3uGX8xMy7n>&* zc@axhW}caA*yWvI`s9)+;)Ndfq7#3Zrye>ddB-=A!tXxRPw-~~Gmmyp0U4{3J-dxr zej|ifW18bxztDG-(dU`s3-Q)54e0WDejx>O^mL-+j_HtMyhQ2Q{qT9~jpxeTE&~kG zRB((Xra(V4B*OuoQiR3Uxf?CirH4gx7bw?$zvI zL&U}YXJnFd=#I!v{rVbieN*1TOO@w56_!@@}DR?9QWs7<(+BMIv% z)K6~vP%^S~P+4dpL2%UbrNl+O+_El*4%7jGACBg3t*NMTyu;j2I zfwlv`g9@UdH|9#C=cyWmo?_UFc)uXmZ=ZHT@p}&P)dZ?&MYePL1JlTm<7T}aSw)D} zyMQsm!YObXbtQKV^*kWNX7Uc)Wv_RYyKdRo5mz%#-kP0CZ26Z@1$K#vQ~0;{%k#Fm zC5!G=)^9-&k~6R-_iVeSjrIwKgb%Nf0btSo8v3d}WM0Nr9!(onR=r+1Qhj^FOLCfT zBguVM!E&jZlOaJ2A_2ElMPpZvSygo3acg~WZOMySt0pRP%ddx^W@7VcQ1ta`GA@41 z1104&ekN;ly?C%!iJk%E{;U4)(^$nPA7{DL*Gq5vdA*y9=6O(NgR69kA9fApc-j?) zYcd>c_WC2qI8>Fh>m^(4gBMFV@%kmV3(MHRS=>^7s0dZ!J3-EhQ89M4Gmr~UcJWtS zmP140KZ#S%O%z$P{EgfD&#d#CQ_~>V)Vjq?K--Ue9vFw}0lssIt6#M)J?uFVt1!() z@m}zy{>l9A_3;lpV>?%wlpB6`4{ScfZ?wDxe%of;dD~Jf>Nfr6aG%lC`rTU(dW*%W z5Zym`3a)qmH7gf8sFat)RQuUZhN3CZ>BYS9tHTIQCy z?-pMrsg7|l$8>ov7@yTijlmKcI5XRpV59@6uEdw@EL#juSGc8h1bwT9&=Sj-1YRxw zPmT4wwt-#&iT!7WFXOd z`aPZh(0s?`S}E5Qc;u4P`(dh5C+Y9OOzA|%8zW|y_XaSR9LEZzj>6fyn>$STRRz0> z7OTshPUCqq;ENN|>Dt5Z*4s2VQJ(&Hj5&8ipw7cZH;l(Fk8X!j;0B$)>3~ zjXldp7pUioV4{(@`dz(mqb_fKSqFF)2^vbS&dmo@nyZ_|y`8#gki%-nhzIgkKReo2Zl66*qH7m^fuIDR^WOL+db~^dA(tinh^tt0QMEDGh zCq=uM{_ePUax_}lw14VC&F#6=Ah1QpZmxhqh3FMxitShYWT)~Cta`W6V^v!VNZsYC z^twd8wMidOrv+1IGkrncn(yjWtC82CoV~MT!EsSD+opl)3D}m&^pdxE=rQ_mc9wqS z)yFsVN(g?I1L5m07>BL@@Im15yv&Fliz~CA7M(FkzNt|uq3mZJ#D+mYKsU~^=qz$% zQ7cip!M1Wq$}%YmdV$);ztBi^YsIJTYOuL?zQUV!Si*1P(FauGc(*ZPd1#aY@Jn}y_9A!J0~=t@Hs!RXqC0< z@eYHz7Wvo-2P*tpMMFfeWG?;l$%rH3pPsQ+oFy&(4dQ@O|H91TlPMBNm+Y>%PY67od0P#C=S1J{7gijg!Vy z#@+`P9_N@2ubqzWR9tNEfRT|h-ECh;9A~NEQHGp#Zb8i2cI4b7&l|IG!pOIA!D5on zvd`CmF73-g{*`(NBN40c*dk@2Q{__{$$bs5F8B(StQ@^hW$Qq6<2%%M z=S@t%eGv4}{p+eJD`Ot9W;F;}QT_aJVJ>`MCi~N}BahNSkm9vvB-D;Yqfnh?JE<;2ftHTUv8dIMxipRPWu5oNEtp=x47<+TJy*VN za_T+MW_(N5xcAkjE3EsTs|w+3P=N+$Lc8KTR%C)2#TWY$D@SVd#yR5$h}%MvF%DB5vbuIfHSdM^)A z-C?xMs%-B*N1SC!$Tk@5lG@;u1hl404-$S!VvXg)Z-4?l$l%j*M8oIr8Dnl>h}MSWL}f{6O2 z%!id0CxN2HR3t&HB1Iu_K&?khGb!!;ag^uzh4v|fq!}JD01dB+tBLQI7q>=gZkJfv z&!syWXS*+DF`H2xf@$>7tQkmElb$*)^ZJ%}j!oHBEpGa3P_ysmas;t zQFq&{?y*U*Zxxf>@n|l+w${PhBq-<193{#v0#EYUE;YcVV!g!sa0)ng@&=!%Gt0u{ z^Kgc+ojca&@x55yHCdFQA9>GRyZY+g8n}M!pxs6hYR*LT-2k&4y*raZhIvCrip9dJ zG|vtA>IoD*)b>14UY32u9nHp;IOtXxt)FJx@32#4yxRknwwH30?nm5+UoG3!*iqgH zSJB^xtiH{x5?+-NKS#{g5HVXMxKs{m=XqZ)!OZ$Q8<+aLG2Ppt^=4UCh1T*_6K0S9 zFfU9Arj}W5b}?0A3(uF&PeBrcn3Pw>VS)yUP-QiFC7PpNF(=|JD(aFGN##P zoAdkR-fd-iyib2Ldr9=G&9Ehj2^!&oZ9RZ|gY)Gatq(jZaS_Jy5)6DkF#CGMuq ztiR2^UW1}NH|RKgU$uF`Aj9D-$cA%DoeXc!ikY2N9p7zhAgF5*Kx8w!=h`Xg%x9&( zTBRSgZob-Ma$m4~WlTgYJ_k|IY5LpQ%ypAW{cQDHp5#XJa+-qt@gi?ntrFQ_*KTcm zJ5I_0eKzA2XW3%z2eC6kJUV8mm_@H8?C>Q*R>Nm(kLY4wUeZCVw-XXy(Xexi_sLXA zvQ>&W03NDg>ZSY4E;$i{j`!BEs#z=H7)H)pEJ_U*W#6qz==*4@uc?qK!OBy>fYV{5G>b&dV;f<`#0}_sF>`no(k>AlR6$`a$dwYrc%>5H*zy9Qfy597X=zg~Y8yx-sCV(1)D<)5EpUVy?P{${5_D&Y#^BvQGzrV--9yhzCN)Ut zl}geM;}Wc)?vx4w@)PEiubf)VlzqsE#*kIFutNx%zvGHOm0ZWd!O+qk?6YB|*3jPB z)>)n!@jOxkKqDacvHK(5%zhpHSafgPYC(vp@0+|rF!Wu zz0ke=q>AuvTf6on1}X?X8(q(wEQVNo zgFS_9-*cAD^uqfNy0(lIKN?;@nxQwAJ*S?^bc(DKwMtiM+ z-Z9L_0J9A2;~TA@PSftD6Ch&>(!&9gmDp80m{X$AEAl z3Z!6gg4P$=dB0Kpdbh{jZ9SN>kIp!(s0XZKX=qCKCdnX7n9E*PRt!xa$WhU# zsxvXMH7v197cD=q_O4;D^<#KLiNN{`o+-n_=c(X&Nd_SJ@h4YY(~nc~FBm^bi6%%F zdt+_660p`+z8b3-1~tA#E!PpO0vJEqMU7eIriH{7h!d&>?z}O~-2yqTb~@Ut9h4I5 z!mO`|>>q!mA|hM2)?Kbv=AS4}gk^USzhOcjeoug1ZI(Bc@0*%ut^5W`?i=}_&RvUB z78Bd#5v9VK!?x=>N7H!X`qlzlmgUGBuiWFUP zy%yxva?3q;F}=fhGwa}!HD7ri{3D&{f%OJWO-cM#CTb_UBD_>33F)_7t4~^VTGoMI z;+fydYQ%)slhLNV(y6_Zaloz|e>z~8Gp*2`S6*KR7mT>9}~xO{xrx;*EMYWt8m(_%@(<#C^13qUwAtNkhg;reT&eIona}DtC2rW+(>c%w)l(ZA%VNL zQb%iBb?FCJ%gB<49M#)DoD*#x%oi-n)w_V(_2VuaTrC}2lHC`x!jm@IVGi(ZU-speojRRlYO6P%jmoF^|xF zs#)>tx>}18h-^0yhC(w@pbft5eyf3yBz~4D!@bFPJB}~$f{8hKDa6N}XnGFZ;lzPe zzd5zl-#Nm{-)Sj!s4KhSTG+V;F&+8NV}XhjjxgS*16B-6Vz%jVVj`It^QAhBUSyI4 zn;%qIWkp(GF1VkyWmtpBlhE?=WsOjDWGmC{7cs98bdFmPV8ujK7;=>CkD+p@94~d2 zA1hVpwxPE9jF7$f;RM^Skad%u8ier|4(#rn00ru)MyT9sGEH5|WcyVQ^;6|#im$C{78`^qP|ukvJ-g*eeM47R1jM{0QOJ{t z6K_HEy+K55N-hd_^NkB3 zJ(W>4TKFBuwjBjhL7Ru%;)veiIz&)b(l|4x%N;zhfMDo=9W`O}YKYZDH&|4c{&uce zU#V1JF820;+vLX?356xh3LpX$q&+X^*zkIRRhc0WiGLU`ow7T3;r!C)3q-?Tv$Z1z zLG=z(cDU1O5J>AsGaHJ^q7O^Ey}e$R)0W3aj?5rCMKF&*Td!|qT`l^oUFRZet6P%e z=7_%Y>L`>n>5r&CI=}ZxX4j)>z|`e=f*=^jLolk9kTu!v-w)pnm_GVQSkW89A+boC z#X6L=PmmTa()n63-pws8|E7jyZ??6R9!rdpAfsbe2yXZ+4|nXYD$-i?>}g_i+-eDZ z5|eBrMBWhtj2WC{irhP!tTG!IZ~zHp1EamS1wYd!Gb-@~3QYgZ8vZjipogL@g-U7V z69Q`G{;xMu>eZO{%9K)|rXfTKk>mJfzYjiT(<_zuUPb`p77dzOzS+#~@20=+;p}JM zuXb5pr0$yBebSsiG&VSSUy8L3HHsd#PhhUJ^e8ymDzKYj$t~`3pH;N!fZUnQr;Lew zN)?5dFO;P-ipSq8$=(K=WAHuGJ6TLsU^|Z%OB>5{6e;!*JYg5=+St{Y)sm!~l0?n! zzqiXjs;=uWkjCsu&)#zX3i4e$ne~p=1mE?d9(d>Do?3I}vs@q7ml|Y_8$7DG0w_3?8KRa&^@N3cxQ=rR{5$VXe*mZ1e0q-E%rugd;`I z%Hx*bM=e&gExZ{yeWri6bM8s{-C_ST5bMlReh6U)l%dapIH^V%RjUL&bsXl zKA--Ic-4mIdG5GlB%&~aETK=)n1Lh?AYE19+YbAXPVA6gggQqdt5^0jST94u* z%B*022$g*h8=UNpzRRwY;oVN`nVFWz)*p~p#$QZRhmYthXZl&(5$qH>DIz7?XbsDh%y#Z>;88cC0WG$>X(uT;ym#}$3RgnSr zO7))&xZ|5QmFDM;+TIn?2vb^rdcy20ZEAaHr0DFur6G}Gr_h%5ExH*@6x~A-jLxcY z{j*?G-b}p4+_1ivCaVhP1-&H6y`^UtC7u@5pk!*%iy;3cCjn?9hGzckx zxh^{Q>g3?GeT@(-4iBCTPYjY`ggJG?ZDKDT3jeI{OuKP3Pdj}hu; z2j_U_Oin!fY3kl-^UFMQ(CQX-iH^s7s%@2w&lKl!8i2rQ9Fx$8O5rm9rA;g7saEL zOP70@rQ;zUJ+itJ7neRK^LG4wI{JfzG|dVe{jO!g`)y%HWg#r`(Stu3Vk(+jr+@*! z&?(B2w-MOJ;1FgMgfQQ4tlB9xnqarlp*aI7QS8@!RZeaDMumZXQvvT~MQZ^qJ+7u@C;zk?hnFwF@RcESe{F<6eJL8RTx|Vrp8$m0 zM@nUu27kkV_A^p$MbASDlqvu@@y57ZV%Y}t0B--|*+#xT`Ueav%ty>HXDN*0h(S*GAy-w!S_D_e; zu^v#gw}q4xCbI=YOM%WpGO@$*wp5 zJo5pj=MD)(I_&ETXfHO~RB7s(?T#P3#uX^#zvO}$j_q~_ZsPJT&T4j_{C>c}59m#> zLs%P&$d9}(_C%5o*i0A^=1S;O%WU~U4&PfIlvpl;W)C<{e&6ukU$*zhP5i+BpI67O z5x6BkUgGIWV6tvq*q`u|43V-ZTj9&u*O(<%QEvdB0=8!?4iLh8sn~wFw`&EXTgjq0 z@7HsT&*IP*T=~;Z9QA>|LqhGjBez{TKq&HLLv9gP6i>^0@;nZApX<;5jB%WAkZ(aFuug9DQ~uqyP9ELfx!CRq~j+%{AGBq15u_5 zl`zUp-SuM$`}5x;a_L6zxy)UQnIY+oxf%1*!ilOuz(F#q)g-F3n#H6He<~5(de`Yx zC@Zs*F!t4KWh4sAb$0rMZI!dP;2(WAKMlZ-x9ep9Ej|i+vi_ht;_7!$X5UY689jGM zG2MX;3BI~ibLTT6Afg1$f{lE^5;W;_LLkN=5NXbVI!nhBGe`<>+>1xql4-~Sr~VH! z&_HRBSn*J1u}}j0SiDp$KS=;ZFwl-Zb(zbc{ZNyOhKy)HF43omFA3OiTXbWPVQ&Kw zC`6}34Pq=1nfQd~iou1S{{2V!=?5Z}Bfx|5vsklG9$58!*V<3^V?9&(rnc7zQ4?vkKjQY#M68O5ry80!aKYs#Xy)t0t(I9VeSE4(t$?*u{lJxkJqW8!{ z!wI;+-cs7VUyJj2X${`DH>Dwr|N(%%R_+rm%mFFx3X6?QcYDPfnjVZ>N#a%qFs zovdVb0r~xA%|8ig{2AL|nuO{Pc;Z>@Ol8LOmbAJqTX`Q7o9n z;h4Q|97(f^*;8(>X&T>1a4sRG*X%yP{mVq?m#wZ!%Qdyk5Knw+2B8c|dR z=q^ijQp{@}cQM1ylX6MykaLUdhBvgFf77SX#o?!T>L)xN0urun4yU{xrh&^je6bq* z>Ff4?ITP{mf|j?Y|BE(O4c(Qd?q>-lCJDr!gpU4f zp7(zNc|Fg_3*KRhzBu>eVaY#xv7hGUZ{9}ys|&PIrBfsNDwUk{8xG7r7WAC11p|`6 z7v$qh4;=p1s_WX%BlFWu|K+W6CIA#9?ltp~v*0n_#x4DxdH)Zz{P%RW5GcV0>6p+K zJE$@(OioV!8&v=OvH#|#{dDz!bT%*V&4xG z9if-uZ+>ma|9Xc3J`}p#IJ2jV8EAr;=3?#oS?KJ4-os5OHKG16SwJy|O7BQ$ktWYL{z!T9l2&BM57@ju$8pMCW0~Jk` zI#_I?+=aE!YH%sk3m1idjHzvkaWc2q=2ZokI>@j8kMChWEl7M>zTca@0|rE~@B0bX zUk}`0|Js5E1L2C>nZcKUosz|n2&P{E@UQ<)`7ld1m;}|f&c-WXiG;lRUq171R`?+e z@ca@y16GtBWCx+yUrJE?&Hq1DPC5csMpm#m&g>xAgO;{VxcHB)%zMf}Xu~X-sBN5R z{*Np2KLZlbLD?1pN42q0gb^mwm;SlZZ7&6qo2!E4uOJyAUHpFVAFs`alu=Mmd&`P= zPUWU}!cFwYcK`o*fwfSiAJ0t`*$z<59XdkcZ-D=6nD0_V$^E#nr)%{=I4<*B!jXSG z6BL!%_fH(aXB!8tg`L|bpNimc%x3}F6flIN{ywUhS55OPj5AdPLar3eI zT{4veiu}juy8f~Faf<>4Pzb}BR`D}bi9#V!p}&?_`%2P{h>U&Bw*T1H%2Fg+LndVN zP5~`!`F{)tWqxsh2XUZ<{fy$gWX{U}x+e8Ea9A$|i}SKVZL9xdut5A@%c%ZSGsPbZ z22iNiX1d80XkoK5B;NjIN6+7_nqo>Zg6WAvoI4m%Bk6~%znZwewbgzUD+RkQ&sYE? zgpRNr$oh3C`csTcd3(AD48&>PguO?0z+^W4=KAIz-vs59BB8E#3OvuirGk_#+5YiR z@_}jWY7T-Oj0RF%$FB#t{>_a2-2ndQcP^9)@Tj=H=ejzhGN$$ZOzMCB_J4a7;J^mP z(y??&h8N7n+Hc*z=2QJmAf)^WY&Lq*9XNVO7B}tHlV{GHZ3Yiqx_#?k zTk_Kd9PNC$Qi3ZlU9Eo%f%3ZpmwU3(j*4jyC82X+K4J~|rm%EKo9+K-!~Jh_1*Kn3 zcpo11Ai)1zQiEGY-f*cx{$aSUA)T!$;n9c(X3Y1J>tu0dd791u-2(63TZ&IUR#c=} zOV^(s@mSfK6&Ii6Bg06>_CYbR!(-zWM8>iVpX?*hZoXXUHqb<}YapJ;O8bgK^t3Gl z%S|;qW5r5ThsA@k^$e>avfSbdOM283?%zooVz?;rq|$n>Jy zx=Nzeo3@$h_csb6uh40Dn)F`xFIG-UxQt2O{(8MiXQG2G{B2`hS47`F+x3Y>SZfF0 zj`r2Ln_(x0^duflIfLG$@|8wh*eNQk$A5}_FAVs{fd1O|YgkObX6K@3&9c11s}7^u z&+(9-D%w9Uuz)`tH;l4Qu}J*B!s>@DUt}*?&j!XU({oS7gfuvjmG{zvs* z26*dc#%mQzpaOuc1WYL0vew)Dpyu}VviQ``d<#@=7>=!(Zbcrftm9C*h=oByR~OZ0 z$oTmvlN*}ha@#2)?NP#_7MDHYM*&658}Y8{xea>vxkNkn;z+B$ortrR3K^NBF9JajK`_)kUd5NI%k zH7(B#=)XED8c7{W3b<&RMGA|nYF>< zPK6KDXMWhC2N`*9-r$~9TIZPVO1-;!QJ!+dJ!DM5Sl@A!qr!o#dH&(O=m8ZXqcX$e z>Co8XGoh`|vn1XTvu)SMq#IfQfw*|9ni#Oi+926Tyc^533|VY_KD_IzpcUP&Y40#- zbB{0^t#q(A^x6+oK}8eG{(|G_w!gKy__(6?%+$)vLW$-((2Iv^0-h#Mig@^!9tN}% zN#Oof?S<|%fmVl3ah-b5a^CPp<~ooe?RiLe1!!K2tqr7M*7dn(!;j5w6rFr-H4u@T z0SJq~Kgfmm%rvA6x1IJY6A(CbL39hcptFUZ9s2TzAD>nV0L{B+aTcP?VR7^T zwfLeAu=vjLUc7UF^CVRwdHHDm?^1-+|27nVdUcbMvwtxv&I$s>FKjZ{nce7AqObVq zpKey9bVg6q=V9$$k)5TX8O0T_w0>SnmWZL15Ms z&?=S%zPxrdWGeH%t_8 z(Hw@#Zv!S+KWX>VD67462w%meGp|~0XU%&uaT)X$WqRi=P-7x*?DV3h?DWKMA7}wx z&aK+6n(ymPPe6UJ!Lus3;p+PuwonJ=5}3AjmBZPy=B0(e=b@7j!0^n}Is3f@u6R@< zRdLa9Atvd8`3=w|WZ4Yejnh~sEHJMV8n~ByW8cMD4@8x5RF`zhL))W64X%zl>zk`q z>qrhx+4c@@756tBl`|g}c$;BojMEccKqyKA4Hw3GHJ_|~C)Ym-K@UX33 zL#9OOl)j#D9AR>WT>ipK18-O4FjOsW!zbtJRN__sz=A@7yVz@`M5?+zmQZ(7$dTar z)p!Fxveae$WWZH{^sy;@dy;+HW&_o8(FC$w1-_$&!s-Pq7^|UgX2~lSLVb!IT?>TJ zdc;orn7sSz8A{vU*Xqvu2!rtgLEqhyidcX3Bfd%ldB)~)#{p?Vw;bp3GWFV$_eyo= zNaqvhcQ_1@YondTtMhzkwB;tzq)zz5+4~kH_MP?*2U2IY$Cz&zV;!7O{Hrn_3x1bNY=Z zpzr=@-+@M_3sOyC9W>0-c5|zskMTXWCTQO`z~N9v!6sUZSo@=N!) z(M`N&&y`tADAPKr-@6^&_%*!lOeo1%gtOF+UqQ?M!If2ahTAySF@CSVXU@ciNe|I)+EPM{isQB}YqWhh z$LmyPmWgp4AJTGsVQDk&ioH~KgAyMMITqu&dJddbkeJ!Cvq6*}QHD3b0BE6Z)(^{G=YT_EAm zu|1PamnGFHi08)g7jeOaoPO)F=k#)0G8JZh1N1y-5VWC#ZCV2z!G0&<#+T)!X%T?7e zbKE!U5w<&|dy&-NMc~_O9=Nk0iII38rm=_;#lspO3QBoMo?|A8yV289A`u6 zy~2+&>#7VYqFD5(@L+L8EIWo*M3rwoHEND5Ql`KQ) zXKe)>Gv)(ri*;G-S(2Lt?4xB~B_q&y?~HLKotcpga&_pEs|}TL5T1)PK=?Y&A_(Zx zgreu!1A9I0m=Q6p9fa-Fwpp=VlT`Md>Sx50f%*>zGjTQ{@)lbjWdfv^9v0vAo(x9e z$qXoukSc$>7=lr51tFe$dRxr$M-Ra}E&jW(i)_SU(~M2=VZgwF?DV7)Jnxdb?tI-_ z2=klN8R1kSpTQ4jJ(=Ki$15oHi@FX3`=6%b8GD}b*XZR(h(-y3*Fb3^Z2VQyFsRj_ zRJIuIp#j6>_+wR09nY$A>?R?H*`@oG^DBBEGzW;GsrzhMw~oO1bFh|dd%h^$r2f^C zkiZl*01s=KRuLJaT#aZgJN$3!)>SR4ysKt7#u_Ksn{|)NJ7M8kNhsVeSJ`6JK#w z11Gb*)@|Q}OHF=es`YmxgFaF2$taGE0-Cjza$0%LOV1Bz~WOjdS89r|;*K5UQXAf8e zRB{b>7&3XGFxwSvHVk2 gGegP*Ji+A`dM+a59?m7A@%7wQayJ8>@7K}kUc4Cv^6oQqguw$0hdxKGn zj(V#ZvqlyM_zY@hIzIJwbvhdlvd*mNTMFkZ^h3c`&YML|^Btoe>l!13tzV0Aa? zqDGUl+O5x0F3{xfo0wVm^`ViHI>mU8B`E>4?^tbpQr4J%l`nSg3bU>fX`3^Z03Ek? zs|wq2L~Cy4wB+hVhl~|URh!2vQNf$fniR(nPlkkToO9)6A{knl7s$^b`s0_NTt`_H z#_lVSUIhk?u41%9b%hPoxU8gsl zXJXG4AX zIVIRj%xB8$93LXR$gk;n7Ws_6ih8ZSK`bf7)GTft^XkO2&Wu2@TVcaMM@s78!nS>X za^~x*nUnIlDTDgb;e~p3?lp)I)AI{y8mg_);6UxSSJI-|A|pYXHoIl9IcRKRHRyEW z$!d6jXwRVqo=oFX{V&XeSAytCRBp~XTSmD~H5&UGxc1)k?KMMl$zgnbs+u{Aw0;GI z2Ard^lp6uaXgFV)cVGIhl9ss816q1iacoXw7F#B&7%oK*lesdWTM&QUXYP3~+HbjJ zOdKo)0-)cNf3B<%9fQQX@_hSO7xJQbP<`PnT!IacdkY~zFExD9X)#d;HIaM2E+O%AQ-F6$v?dH3S&X{) zFW}jj0r3O;dLIaK!;FVFdV~a9v;;rpo(F9Grbe#){h3j!@}rV+s!zJ}Hx)K7HKM&~ z8quskK%t^;{jD>6=#YIa^&EAgNy{6~((;i-t&@vNfi-ZQ60b|8D^*barfydAu|`cL z@|daTe9&fcVNz()`|^28VduJLMK6!WnFUVz1V~nYIw8&3`s18~0iL&14GW4(p0`DP zp7S#8B0et7s#{+bGXM}6z7N${^EK?nl%o` zH^Qt88>)EQ0c zOoBR`dKaI3Z!1|^YTGiwl7JG=Ag{>8qp+gEd->&XdECv=_~4qF0|ZmRy*_J{_fa-0 zQRTiqxvXxZ|40>N>7X;gwNqhBeIlvnxq|u`N1Xe2_XDv=F%F;YFM8(B*MN#wDgfb~ zys-+eFfLlnhwbWAcs-rBJK3%C>=CL6)drc>EpcM)S7UdRTyH|W(w!3`RK(Ua12uTg z40blf0=l}=n>cU)jn6pfh>yGMi2P0L2^(POs`XeZX|R5&A?)|vhB#wF*Cn=&ikCt=UwM~JD>CWtH%qy?)!CL%YEI?>$;wI>@j5|)d@e%R|~Xw z1!cbqPr=ewcPNL<-u|1GSA}fAan@Bq=tg&rX_!N$@Wm&>H1WyFMG=~jcQC6NNmDm)l%waEY?+!(bwpCh7 zl}FrIL*7J&?H^bICwn`g7lfX3#|Ho(n=1SgRxw&dbb^oLHOeb8kDd&<4e^1cUo)ht z%cWZ+t;3{-QMcsI_{gU=(kv)Sz0W^Z%(m$1Pzi9hd=1EB;=w1AqNR!C0MHFp?xwic zvg4j&<>KmUKeJ%=j^g0H?BZhtJ};{X2}uUFU-sygO5+|l^*>A%5&4? z>jS~-?nr&v?pc(c7Jl1>heJ_qGO?j8Df;R=WYo9q-au0}8*mfXZ~8w}p8mN_|LHMr zgOts)FOSU4WOlG+aXO2SvQtXcpa*SyHrqBz*52zl!dCpI12zG>Ni~r zK%n2A(P4LutNU8BRb)ReR zNk5F!Hu^Tf9+35cb|EciPaCRHUK_kjXu^70jIQ?(eY+EMdd8$A8t~0eI}-7$d{@EYbYk%$2)5elr*uDgE(@bkTNF~Q zNfOmou@EXrG_?LWiUj)Gt+xZ~_X=X>aZZky-Tg|h@?`fZd)E{rn;hRBT>M5>il{@t zUQ60*FFxT4wXj`33AhiWDlKqP%@+XH;#=ki{z&f66)0sWS_o{E@6s(qM6f{3j8{Pm zn?aSIh4I5FMOey`sI?8au$BFE%KyU!{h?@Ol&ZmqCl0BUTYsa{6sb4?;bTL$!mhq= zk=c1fP?(*+y!4$FRKZ!iiC>~gRlCl0jLTxammx2p(r^@7@nc|mlyM(vo(;G2TM_}J zVM&P8v&3#kr|4B(BS(NT`Vw(iuMzIzz)Oa7)s1<3vJ&@vM++OrQ4Zb_Bc?_+)aYuB zj}&STCzLIlb>RY+mj63s-fz$h?K=d1mV1r6^UMuh|DlAk-Gs$#szdCnCjeBGP}-ZP zj}eL3T2-t9A;*C^11)1=i26B6?oD@f6)eSvU#;SB`I4SF2H=UxjdB@8&`{)<_vhcF z6+6=GB}Z0jCE#yjETVEBM?R;8lj;avMN}R+R@;vO)HBgCoKE@zpwL0iYPD|}p;=b3 z8yVMMXmbpeu?0;;fx|JKx9M38^-vo}{v4Q4kNWN?hGSdWkV>Yn_}xC&6P%vR3mLxq zx~AKmvRCjZm_szkLY1e(|T+oI`;xO0y9~^Tp6Yv zxfO8DEHz06&sS|F{s-RPCK7ZL_DTIQRh>qrA>h#JE`Gl>rMR_5Md)PbpS3-lK6^id z`KMJMN@u}_bN)dL)Y1?@hRO@f??G?4y%ythJ0-0#MS&x-lpqSN;>E$M-IN%o!F|RRzbaf=0=drMscwAsU>oZDV#=W-4*Q+uyORBw>`u449 z5bAeAI41>{nxiX$aAOdDP9SxK8b2Q{*!FuQK`td8u$j;ddBc(WB^#0-uAazW9&XG( zf0vD2{#H2RRtL<;Yj}I_7^OqMs&cfdiqXisojThN`^gcpT2Fol$Tr+e7UMDom&fBw z4lJRZ*UnH*hs>Libk(NBRm63CvVQ=hm(4Izg~*S|=%uP4r@nQDGvH6lj7(fzaj*D2 zPT7^FGARtO-JQv^$LKpu)VAuvqGiO)byw`Y0QsSph8J}@IDzfu%M^(hcX?Gu)4NNQ zvUmAx0dhHE8z9d3nif@TDspGHxMmVIPLlhhKIZ+q+ zYEOyW15FNs%tAi{)PmIMSQ##wCgcJ3xJiWKxz7G^Bq&|Q^0pX5sSl^8OmEUY1RGID zyod;|+^~^g()0JDl8#ft9J+%i0rRh3W?4P{$!0W)A-*sUaL82=%Qjwu9(|q;MoIKm zmR7yvp*l+1WmEn3Hoe*HZLHd;+8UFFC1{wH#*<1nMrQTKo+CLn96dXZi~y<@Y;)BZ zqB1tWM`lE`*cb`vuCrDj?sZ5OjXo2h6~6%B}`BQtWl_C?xuX37vPAnj78svC(E z{TwClKR-Rmon@3XyBetdU_kxI-l5&C@TD_0&(wMUK)$?eN)& z4VkgYfdr-5;ToJn&PtKYvd>ZjOTI0{v#_WLv&e>~MBjc%zwAl8Njud0d=FDXvMNaV z8n~Gh)&UqE5Q0++}4;WrDi7t@<;@hBkxM?tna z^!r9sF!k6|>P{`_ z`TmV7Zr}X@(27#r?^;obUyek#siD%+rUmFgJNf17Q-CYX`VcbDmiD(8I<{i{YUviQ z1Ou0$JFUNlT?5TSyK|gm(S?N&zhpr`9QqlTMB!nP>!aI}mocxZ2Z_%~oZ*N!K%}m0 zB@qYAHUJHwAJHSjybHd8g~t1KR6MBERgD_LuJ&nGj22gYskmwjYZWS+)Vc1J1Ut$k zN!0+wn{tjaFsBfyTG0|zaReTnJykz4MO8>PoWFZV%NhK z)zi;Bu%9T2d(k+uyK9e$;r^Xpr9C6wX+4;^^hTMG~o!e^u50xWA-+g5eLQ^2-I^oSGSPc&IN{1} z{>SOMkCm5XK|EE*yUpoCNxmsHuikqDo=d<=U=IZ0dqCkcR$)O}>pOF0L~gO73q19w(b4=~@y_wd?|$Un%w zo{{*y3bJDn{a4L7`)`D_QuthTQ<;`eUiE)8!9Uk^ot;*AAYq`ZDqqTJGtPczJ;|Cd zLSH(0L);Z_FFprS*E{SZ%YQJ7j4gw>r#-SIX9V7VS|*WtPkcZN&{DAq+K@aaEB-te zr+D%Hhl~xYrA!s#@A(Gnm~yw5qXum7%apt*b~-qf*vbU%IRi*e!tOA{^q#)d5WTJ8 zMd1n+2Bj%aSJ`FvFqVT9z@>KU8=ZM;E$J0xj*TV2MJN(|xr`ssy`;F2=lkDtX(j1a z2fA%=0iu(1i=CZVYhN15@rt~MnaCO`m8jR?g%KD|6P5wHoTBRuOv~dpwV&Lwl3&6B zBefE`>}F%w#v>|2q)xh-Nbkvf4*%IqW~nu5`A&36dSSP`%ZG5utBz7p8^^H33qTe8 z=z%gg*Oo+X$>$_^Lqb}6URO8j|6)F=>&ROe=mS!iS1g)%tNIZlU)q<}lAe>pAr~A8 z^>Rd`KEW5$lSz)@??W2NH)W!bynnVPy>vhLZ2v{V61XuT!L0Ez5p^l9aMFgvBQ5Q4 z#89yXR6JRPA(Ku#>8|yU;QvXXrPAbyw!24Uio?@90qM$OAweEx!U%|#+V&3&Q}S;w zl5qE&^K>WaJ}sLz1G4HPQVVfT03p&F%8pG}G^;RH*mKG&n5-}vqHudP#kR-25wujh zlW7Q15h8b+)jbGn+>D+0M7{?Sxx0QgiWhBDD~0u|?xrSfRPH0plfEbvWUP)Nv;z0t zBVjC@G^v|9W_b^a-c(cI)hxgX3i64MexfEENJ5zE&7rlC8 zb&k#jlV*|r_fxWFqH)rS#V-|gonM{}rT=_+Q0Pw1!nVVpgEs=EPE|ja>HN9Mq=~Tg zJ87HWrAk;X>U4i5<{Pe;Be>D?iz;C3MIv%$Ue^%B4-1(K4nb1(bz2 z0no3OSHul53je~dxThOeJmH|67a6Ufe)YG}#TVHRvTt54PNTT|y-y5=9hAMN^y;wm zO6J<*_Hi?ZYo==*0t*2ZcH19wQolm%hPuHaOZBb)qvv@?vCI-^E$1F_%_$M0o)>oH zyedRUbg|Nbk5YnwXPLl#U7(=PuZrK*p90*5wKP2wlHWSg<_iJ$ftU6fQ>56p&F7V6 zpXyOH8n8rV#kaK@t@n{%O9C(gyUrb&BM3zm!MMw7s<*hFV*ca;n7=!Uf1}+=c%`d@ z-TrdZn}v`JLZ6!x(SF@48Q1-*g?If^>ZSc(T{0^-7;>5viR~hq0A7r~-q(Q!H>P@$ zm;*l7OJO{vO7V@2RugG4DA7n86y{{uDg9{o;KS@O;WU2A-ffdx6J7l$HV+2Z2au7SO5dI(GG(u%|Yv z4rNdRcN*~6Lqy10ClF&d{i1ZA>E$Qdc@DT>vX~b-HrKkkN>)f6n(?U^PX7-6hNe{C znadji7+W?fS&N0JO+4nM4p+fPv$GZw!9kuh~6+-Iw%nmI%4G6A=sDHG9D)yE} z=Y%4r$^l1m8{z(1lJ%a~70Bn5yW8K4?LnYlU7M@HUrWr;&I(xGvYRi(4Q}nR(@EGG|G#x( zKj06P$H$s{;%Am_kJNW^U-sS-pdy01H)xYt1`(gW=_%b@=DW~;Q)ksgr-UCT;&t3# zl$~?9lmuCQq)g3u^22k+`-gRI9%E$?%uRowM(Hrz8?uD|IW09AU#I3KTjaLjj48^$QX|ezTY8hKF z*42$xHn7-nAO1LCP1=6NB68Soi_peP=1p7T(Cmg#84BI2Ty|%6vQLq9Sj;De2??L-t?h5<;p3%( z;-2eQPU`@Iri}F5?!FeUk%HUj>^0I5E_w1K>;?b5mdgr910gx`5~F%wbS*JDj*#Ma z&pDpxW?_wtW8Xuo9ZjB!T&Cjouoq;?YtC*c9OSIAie#?}Xb9wAh zF)s+{Y2PgD=Az98JG5L-WUDUDj~M0kTWl=hQ1Qu;Sfmd^r7(1W~4EncG`^PyQBi{PMW`J)c>3-qBTR zwbceAO@L**|Mt`Fia8~|m}4H6^okMS9!)0At0xm`K_OfxNLyMLR^}T;+}bV(W#E&v zy*GAJ*u=_xocvJUzUfhtm}j=IaoMFz$Z}3pwL{->$ zB|i?mYu8JU6Y+j`1H!NU#BJt_LB2)IhF=Q({VLZWb?W=*!2*Mz{yWDT)SDo5E%k z6m;Nt`Y|C7Gh?Ab``nuCH`UAZJ5FWSl?PmtuediN&oAu_^t{Wl8_b7PE<~=>!LX@w zrt!u4(}%8>vx|JgvzWBx=f~o9bL|~tvKc2rXe*6-k#M9lNy7S_cj9H|`?nAVA19VP zriO?{WRIvGFT9hlMq1_jwAs_bziR$@Lh(MhyU(qSyj6ZbhNjB2!BBDl>b&dPev~|A z;8zp#b0&j(UI&+N^u`MBU-AU}*WTFD>|a3PdrZ0*AkS`BPuD_a7EYWLChj@;+vdvS z`}8cUoOJ(9f5Kz_mzNHkfSV|;@KdF9B`8ll0F)>uE5BU={a{yEhsPn8cw8nv>kdMa zbY-`(dJbQ-w67#5IsNfzf8(0|QqZb2!f;c$H&)_5UjW0Fexh(TAE603!go*bAm`Nr zivjDN>R8*rR|wzCI^5UY@Pr$^cKn~nR@UQq!@PpD(7(L$ziS76m`N?`y(5N&D5JDR zHwoVc2hcmV=u`){w&W&wR+`yXzNq5qtqq zos-E}nTmxheBxx4RV6%dAWnqP!_)w7CB5QqYTzu0{@*I)pVqei=L~rv2z=;?^vi0? zpzBdYUM&s?=JEmRbo^vCuhbopX*7+E^>Xzj!QOg&o`> zUFXB^_iv2wKZCJ?@??>Uhc*(Rm(P@Oso>`X3xBiD7g~X<>-g4`eZ_9w3cx+`eFu*_cu`3K$Mn*utvICebm@t87I z-D_?aFZKif@*VmrVEXw-+E()gl&Jg$_uu|&s)1Ywu$Dq&$9u|&pbyxZ_G#A-tU&+p z5kNaPjKNx_@}@s;^aZclJ8nh(*~0zZCkFL{Hb0ZP)Jwu@;Cl>$`+lHv`N0JK<}r7U z@)^5yC3W6uR9hJ611x1*nS3kp_ip8H#{M(%VWafvtH>nI zyO@E`X$kox@Drf!@86Su9~4X5eXt(1I-D-e@NZS}z~M3qw@lE8-7 z{RSv>E$R)IB6~*xLKI&9svkV>-{|oV*4B0&*u$>JRl(^h@T#Y@DJK8g-|B+i(=EZT zm(g%A8&gl^xIdTp|14D<0WgW!Wt+w6MgW?&gft8Mygl@9gzZb=D~M*+v>d()UNwE8 zJo^7U`X6so`ZKE5IS6KRPRZirzZS;{ia0*dD)M@zQ1~aPtNwj_L7`&q=qZK2G`dSw zcY{aQ>*tpm{f&Uz5-2XBuk5QjFcIsF{~x3YK}tX$`I^vnKtCG{hYkKDrv95{|NBM0 z=R|Q4W6FA$C6lQcN4dNq400L34QhVBmGR(E>c{?6LXId5UPoA zS`Yne(gYn=pa^X9x8nwgz)fi~b0z(mEc!oBrhuZ^`E;p+pTK0?1^&+~_&?wE7_cqK za0>6mQ5dowoVN`6Vd(k04=tOAie9a!R{!vuzdXLAl#<+kinjz!#&zno2B*K5$$Puw zw~tE4d+;Aojn|3V{kc06j04ko?kU$XF$oseJNyOX4{oFFc6!B)o;=-Kr(|M}&i*V% ze&DcRBjsg)G1-q9WI?v4&1ZiYyzE4q=aTf`r()j*e9|nIwUr_YbeTL@vQ%%2_KG`UnW%PE`&EO*;qMpqFB``$rPJFiTK(LJ2=G&LO65u4y-_LjMBCYq$ttK9 zzm~O2S`SKR4*t#-{e##3@5i73kXcM&R(*HE`Otx-y8-JXp5Ludx-tFZmp0w$YWqdB z;*U@3cjx-wN|})g_x^6+zfAPV90i_}Q&eJuZXQw6+v4veeeaanRQQfu%o$0mFzMG+ zFYkT$Ad$~K@lMmY)oD+`)$U{eunzy=ua$h+F9_5pyScT~ooQ=-Dq{cmjkadr#g9ua zmQT|eE}r^1mCOYc#d&N`3z0dssOt84m2uzu$=upDwiVi0we@ITGS zzdMsRQbAYG%%6>!QDtRRXw?#}y&2$AJIv=1fPXreo$|If{-4~!Ts#o-z6?*SlRXe~ zopLwR_i@m?5}(S$+P0;g@xCJ*UGn%3ae|?59nxot^#a-WN4JGr+{EagE(0npv#XJ0i`B&Y1xf z?{>qSJ?saM@Z)2fIFN>~my+Pv0@#8bRFjF{6ZUNwq>Fvws*Y8;#UAx*&sFv)=EZ3A zF?D9s7SoF~!7gs=D|H`pk{K3+l6e$sUFz4~u2;EaT|Cd~W&RH#dXOA|Mp9I1Gp{(& zA6RPl`7&bto%QjVQNKPM6Y)Zj>;79u5iWMD!L|DXX9rroeamdwy?U&Rzx75f*H~gveD#kengV23FZ)ZZeF%_U(QMb`_dFB3LdWPXs!CmP z@|aF)=5n8|agkJXRoNK|?k+-iI~opaIwp?ja!Qs)CSEPsUO`nQO27$?5pg2r$c0NK zW;s1oYXVx;qOinAnXoe`~-KB?Y=)=q}rD&fH>eq}%AE;~qEKzH>wYabFmf@7#*5E#&SC6tXui*433I z;m1R93)WL3LM^Q$&akd$q3>qSEsvG45eN{C%fIy9aH~a0^gfH#dErW zRstDR^CiVXuzVGA>OT+>U0?}nc5$z%tGOTQ{2)AyEkI-`M-xj%6&ekQ$YnI7RID*g zKhm@O8hXY8GcBc9p0IiH+~Id7F20QHPowP5(OqYG62(8q_?@o*uh##uvrJNKV@z3F zTJi;z$NaVK)pOtd{Y&J*(CGyi&e>aRjd!>MO?kTQgp6T$atdyAv`9KHbFkokgNxzC zqr!%DolY?G62?pw?5(t|-*RK!PHR*$7Qu(aVfH|+GC z;-+UDVWmlKk$=v~<{u-sznWdBGrt&I6_C}TP+Y-d!gQe$-qV!9Vg_LZ_kD&qFydjl z5*)$0=a$+C!P64W_otNts$HmGEl*#g`O#Sad-pm3xCljo?e2QY2~G@w8F_>!bAKO8 zY~1D(S>_rms<}TBmZmq%AMaI0^ct>E$9-!lWmyfTrK$O~oI#!?ScJu0_vbO*OJ0gI zoxP?rS_pi$Ewj9=>2+!+nJncUmMJK0bmbb1kZ+7x-rKexVQXDI?zHLI!&H^kL1LJS zf6T|;ap|*{81q3kldoTx#>ONIhwzBq&-fTjR}U>*p`}In@((V zpn17jxJ|1bWeK~Q#jx)q!n#cB`WN77dWvLa zU#Z zDwpLeNtme5FMJ~$x1L^yeYltEd`pr${&cog+bC&K!ln0-~iNrL^1`Aq}hL85F`l`|7|q6waL+g$6TH z@fmtfw^XZRs60ML;-}165Vf0uRpSr|%(rn>$({W6ZNB@Ac%{*0!kSGAZdlNAU9r~$ zH|0j?-Id!V#Y>X#$dEp1m~eg%TjAn1TB}OJgwGUH4>~g6O{urs$cci7=*%-)aee-vA5R(moeuY!AeImYFn6^_ide!e67P%Z~*Tz3Ne?lSE zrR3GqSCH2uXd*&fKQ`C}hUW76xIZPLZ)8~ZWsKdSs+*fRR3!ho%589burXynp4)$n z;hdSibdok6P3V^XAZa@)mM@Hw4(zc{OYBCpWyK6$DO)yG_7KO7B}_RuuAV{j)?H7|Au(BD$_NjkveCT7l3T0@SVEBb`p@{yyh{&fN$h z=*Q(H*A4+H=m)2y))Z9JbuYz9$Lfd}2F&=skqZ=>amX(s5v%Y1~#jX+f~u zZ12>8rDKi~%&Yab;{Mon3!?6Yubw*^J&EvZszz7!`^ zq!XFf5#;3-&P`kzBwDvETC66ZXbsr#$3{88rQpwN2-9WogWRW%1vCBfPX-kV49YmS z3{(LFgUSU4HFK~_gX2q;f=P6#E*gaw?=hUbY?}WQpXSxiEjr?c z7azzoG@wmq8*kWrafrB(dnF@E#nS0_ZzmI*0PiLCBJ8j2j?+$+m``caPsQVuL~dAu zjmmb-`%XL_D{RtyFFAPm{N%SX5L{it%nTXWYiQ@bjN?7XZ01wrIb2jZb;`u3?$Ze% zrGjt|rvOss2a#!lMpBV|bxrumD#yyeYuIo_tKny4|IcxCv<7Y?z!Gnl&-Hr_8FWNB zA+v~xfY65BT_4^(;obiB)?^LNp;DCdwULzq?H1>f<|wG*DT@Z0z*Jmd<$!<&CQ6)X z9q=0a@1^Jak=n-04m-PV7!IWg^@W?T9-KmqvBb{Qw|#E1c;_qdat?X1`F?58*=cLc zb$#LpaWquzdbJBPIbe7*xPG)cAM5wUsxx(#{#rhL1;Y(%ed;>Y5LoPT-}%KU z=LrH6{nX+kK8hW|s284z)#@Z^~M8k6G=pt3R!!1lgK?O7ea*V) z{(ZA4jrY7)Sis~3>aE7&nN3d>VdL1t^pVl6p=+nxU_tpZ7+Y(ulFX@IUX$1be&;}i z=^^XhQ}+GoUiv{U%Vp%%kW!Wbo?0vPP$jqIVt~1MP^lwWn`I+?@W=aES&xObh0j&TCzOR9c+bGPqeZAGManm z(3nfZUezj+yt-B!p>F;@$ZX$cz^Y5jI21Njr6F#F40K%cZZ;j;aouDmTU0mhxDLbi zR(B=+nsvygV~tKJp8M;d0xkh}#z33;4!3G$A4~S|)(FFE&+;f)2M2pSvjHuF*G8Jk zjZk{=)f!jrsbWwL^2UhNKYUy^%Zn+-I8+86;=D|%cJbJ% z$zo7amA|^#>l`StdrlJ5%G`hm%j|)!GjifEzpX=OlrWVjx5YaQFz%~GdIJfl3XZ{i z-`0!bizCG%0lN!}vl=MXvN%B<-C|uvdxWjK{eXiBzW9}6Z%LJ+Rv^JYszG8yl|ZUS zz83C|R;%pP5nrviqdn%=vRw#?*{gcBIViD%N)828L$x^UQrha+=R6eKCHF2n2u8`9 zxYBeWC5LgMw%Xl>Sf_mrFRlo>265R_F$sI}lf z(=d(NYR8n0GQ;*$wt|j2wib1p;ZJg_LNrsPVWoK98NrUgnfligEy3Hdb9)R6U0d6Q zJSmO?+2}oNbmL~I{Q9R~e=ENg@^J)Qt=qF#05>WRGb>Wa+47BrFUySiqa%~`pxz{@ zl59rw4k5UkEP7tE6pu`{VTfaG&^p`^;beW4s-aMpS7$;GwU&)dJ7_;(EnIRR%i&}F zMT=y7B-ocM-nP(yWo$P*_@Na7Z41@tPRZ}0Kwsng1=-ElnbcE)gYA}F|)Y#u4;P6QUqfpN%pX5=()>6|8QIn z1yL-6@F_z^@UO*EU$2e8fh9Xg{;*zy2>l@+6JA*BqtegboaFcwf=Vbl5@?IWq8$6o#mAw>Jl2< zwLu+ET}ln3QE?D|M1jBnRmH*AQr?q2lJ=9iZC8Si)5~9Q8J*pYe*P2-su_=r`6o4( z+!NE<@?0NI!_27C?%j{)Ek~q4zjg=uykU??@xu%C6-}@ABD%fa73)*io}VK3V*|Hi zTnxq1-{%GATt|D1G2l#oVa<2J73O$VoTR>9pKdmjA6$WwlfPi=qYce$RcbYB5~Ci_ z9JQ7m8x9@N2{L{McNF!xVC>rNxJAcgyd4RX~}tFLK=N^46%2=yy@_!ydn7-4aPU$tWo70bFhYfJQdXteIN=S&Kn z@MB&Wfp)}saFUQVLf3D72aci3V7@C24kc~1coBxd?=iWvep_^I! zUd|K&4kfj$-9dm2mtyxNWZANm6z|&wb_FzR?TrNB)P2M)8W zMQZv*sZ?tpSPG{NG?&*LK`~9%YLtE4b&Z%<9Bn9u+VwE+*4^e!QI$#i!uqChT>eE& zkxFqmN`WvrVWxO{)P&$iyhG4W@qE;@{x~JjlNoMI?hGeweob{}!kKvVC=5-k#Z>ki zFF-{;AUYdlq^mV$!VjbnEaGy#vCCx)d1 zjuh0;T4Z$G<{Ao-Q^sBss%I*~5`r2OW(XggPB);o6*?!>w%$K8oUt~VX}B{6?VCo_ zqB9E_1O%8*u9(N#r=2#Qn=bQ66Y{%e(Z+2ZHkexs^D1fB`0Q0Ixej$KU<{fO6`x90KjXP(eGf zMx%}nJ!e*XVIWi#B zoh(?N&#b2y4XX~=Ku$pCM`QL^>0L2H+uzPYtg3DLhD{Nqxrc1Hh42;G%SMajw5GvUNU1HRJt1#-p)Xe51+tBM7nC+;Jw=Wi+_*bi_l2HC zISlSl;4YG@!|kARb%~2{dBsoh>u94&Gps3qEDME!itad4q2O$)PisfhFKfNzM3w-y zm50A!Au==!Ci9OV6U^{4v;+QiVvE`#jYlWLiqF-OniIrN4SSCb;o4Nf38{6eOZCQy z8FwA7>L)u=8G>8ksSlVII^?MFh&(XRg}6iHrEKVviSvScaCkA#5!*SzVbvCWUIhK9 z-}|$d(@#%mLhR$bUB)Y;VKx5y99VL&nbwh^9Mt3MQ=nS|!HvjCX(UJWK?vq4{P4Sz z(>J>9>y&-+-ZG) ze>y=gsFfex7_!t@93H>*@K&!*8*qfv zp;xX=rfixFpB@urEMJX?ZqB5an;iZJTIplIvVi-$TAPx}z)6goC7NcUpE{k*SiTeD z2-=3i#lD^@6iDu%@^EniNW%@$*+Aj|Ybr$h;|QW#?!wWxf<9gwDZ~(iyIYCvzi>3( z&s}_LWVU`_>fyPM)aiidYyEwaOcJ~TtVl4@8*#U!FU?hN$6&Bj)H7Bs#IE!AwuL&E z{9s=@`p1QsgLwo;Wa-6#>};1+Ish*)qoV~QZYdA&0-XNTaNW#j{3=E?@F>CVYjcZN zWrT@Do6Q(Gu@OgjQQLPPw{uQ))YPbYV>XpXZV0=i*vX7uMDy0J|0-6JzU#Ci_2Cw2 zJ)Gfit03y4P9>7zj2Zgi*KPZcf*e9yKCc;E1;RdqZ5tB9SqmLol%~$&L`!S%OdLmJ>z{13sO${>1gYLc_ znx5$>#C~JVYt^)BGh2gb!_6DooYAUqS?6RYd8myyfKUCMheQg$QKiFbu`0E9NcOSW z`%?G_hU)Vo;-ISz{?2*a<#}FOA`j2bR7Zb^^(ZG9Etxu$=j;IaJWw_Lsho22?p z{_!-Y)>;?KR{fd>*C#iPZ_5lXq-%kbNEy>urPrBB;erl%5!UkO8b!=0Fnu2<+K7Qe zC*bh>hj}-k%Z9cl@rJ5bA78VcKEZz1w1c;Jxtx9YnD=Cq>tLOAoy)%HfK|9xUALke zn|25-ua1P_^v4g`>pSa+o+=J%eDnuGrC=y8Lbc#*6`XqtBgnwawQJ!+wDqMgCr`b? zKub&)tGfpV#$8XzpHb-KX^6YhKsr$^H9=5|vax38;>hnTu-A{B)2_5Bxi&`Skz|D) zO)4^U?xl2)kk{4MO{XVQt-0r>1lLFLA(wH#F+3Fotx`)fyhpFiKH(>hhXOIvR^qE_)w<2~@b&T=__eAeNpZ*m3d(O&7r&CqQPIz&#Jhsq#s)(NWvoQ? zA9*)k=~Qe>$LI`5mri+c658LFMN~Zo$lN9IBr1;*=sBWOy8Rut!A!zlwyZ9^m)td{ z*kX~*hX|epop0=>IZbr~P?5vX2Ms*ci$f$7-&K=$godJkvk=saPiVP@_KBQ959Tks zJQYg~7fzNygnrb->^_f7+R9l=MFRptz2obqdZ)z)0c{<|2pA*mSG`!P0c zC8Z448!!huud|JPa1<1wn#e)-4LL=`1+oB|*sA!j>~Sswp_&}3tVFNI~wTxunoHD{PvZ^J$r9i;ipc z(hi={s@t?=$E7SBG6()7`?IP>&?jxFD19EmO;JEb0TLTs{MN=8)kJ z?=2qXs!PWkne7el)$%#R<4zf`iQBxGka*}bEbp4|?7)({Nmh3eb*v0qpu%M6659>6 zA=X}KDdAg{#`PmI-}Yg+=N5&INmhYFlOPl2Z&Ffp32aLCn&V?kZjgYGmB}VQ$Z5n> z>uf;}?YDPB59>_THtW=no^CHgy?=%K;Gg;Y=}hL>F~%N&{2F+p32v+j0EwcCNkw?5 z@jbC?y0Q-SLEDHGA6U0wz5fS|p56AIKF^!s2;S=Wl!b!?J9uKD;AY>+hPbN=F=$a4 zm}`qv?cK`jDtM5E+A!bM*}Umk#;7Fpb#I%WJv<_6Qq_}JkJ>dw(T-j5N-qs;+kIHd zmCvx!Fb#$qE&p`Gzu8-%E1l@SxS*}U9G-iQgJPDxMc!xZpywZ` zd1?(@bu6wja_oKk%xl@gnK1nr7UhmS?6#Rl*uCS|W`Vyt<@>s;=i1>7wfE4^5mhzS zrBZu5OAoqBO+mXETmfCkpjh1dgh46VzYGEVg2+!m?R8+u68o;W$AUbP7;Wsp^3#*Hk~F1=kBQk(W%M!Vgw9Mj<I ziB7u(TYFSVabD03$F+W^rs%@~>R|;0e%z%(5Dk}kc*p3=FMzUeBZEyDBENl;oohdv z?{F$;{dOriXk$l@^{A=SDm{bg7AYyP`)mgvE@GUyMG^EgEBC zB7yqwyu0a2FzS$rKID2?IyY1eS>v10`n5-z0R!@Km#ORefeBuxGK`f^Lu}NDeIaJ$ zzxN-47AFX5v7>;1P3$o%Ro#YzCOfY8jn}tfIcsZhUgu>!;!4icSY=PZF{fL=Bq18b zSfgw5t8c|z?Bk<`Z1IKr`qZ4B#=#FAX0EUt>J4#{oiLP)3LTHC+w~<(N1vusi-vI) z=H}0qX;q(ZE_rzM3tVjKBKE*D7=vJCtLQnYHAzEcP|6ydp0|E8TLoUxKEH8(va$!Z zBkwey1vL=}JIca)_E#g{xky0=v>aqWqGD=LE0oP3#A$89EwR!N*$5-_8l{c3i0E@) z4L!)lq|@;@h5lOLDqJ(4qjdBD3RgLG_Ile=<(uX0MfNw-X*T*hk;i8X{im*9TzrA+ zlB6nJ8C70;KH*&%+>LE|@zq_(uwf^&7iz7QtBGA#oS#rkZ;mywSubz4=imOt5}4l z4|=Q(%KJb@`!LlNV_IWVqBoHAeWbG1mX9iH8gR{Gvy!(9ff9TW#J4#p=0ijEcFcAM z4ZEU@*s9_9;&T~6IU>n1XE*%8*26^XG|rD)-qHM?DuQ{ZaX-LxknZ;#O_6?+_5iWM@Zw!!bYBa<@37baX5 zJN#-&+#%%R=l;SRPrL@xTTb+r_T0eSye2rF*=#$Vd*bNPq?5EJ!RN#nerkJE2Y*1h z(v4ihr=9UE7*QtTr|?FrE;BBad_1^Ax|5^2`Ki>bacobeaivyexpC#37LqLdPIbXK zQ{dSF8{u;t!G!Ie5s`{7J>dxh)al-1^`XT#3U(ouI)k?&?31LN=LFBC%^);L_EFqE z69ca0j{$gYIj)6OXyq7s29b><{RXXoXTW6up~FfE{i%x=3g1^G21Dre^YY+Df|l@Y zmqBB#VS7%+WDO9d#uNeAHBD&UJrydA)9GvLaAQ#02M{n$#98#LXWlO1dH zWI@dRs{d7Euza4o;={d>CX}Lu4Dz|XzvDzZ4|1-pBnfUy8#}@hf0|J#|21BZ*=)5X z9{#4jgDlS>!aw*#y|IQIEOxI5K0B%?0ePtFbJ+%dX%Fxk;J!&APttADK;6F8rTPzl zt&y+BP0LfS24_E?Ta??Wi`=ulE7pFOQ1>G2D4WQtk49PzRY1+mFNfeeMNeu+`JG|r z%#G4#SF_yF2_3S#c>3720pdk6pGxmLv+7xg*2tv2YB*_s;LQv#mG4e-3sl9Z>o=Dj z*~~!tlh%Fq7YERy$}e^oosza zlp-Lw(o_U=Rgi82qy}^q6$DoZNLP^}Riw9oC^iIafRvD+6iFcT7D|*N0zxQ4=v4?c z0RjmSLf&ETz3;>BK9AS^OFthbznM96=G5;wv-H`aMrJV%H=KzzRf3I~!Zt?D3%Pw+ zBSXEr2*G<>_6)S#hS6%Gc5crpon}~+Pcxj5K`K2h@L_MLWx}>eM{R4OGtP!*URH6% zbM-`dUk@jFcIYSv$}>+t`&c4m2_2;JL~9+jJh-y1n@+`)n)JcU#YV(SxzCo@1uLXl z433n$x%ndeQIuCxnr8+U-{HAXHn%3fi(lY2UmARKsoT8Xs@_I^!Bca9bU9b6@&aCV zig-kDKDzi6e|H0Rw(zk;8X;mkc1Bd|s=%BGudak(TPZ@pzuR~r`H}Xjz{Ne)k)lQU z!{)6Q=>)?LjEuH(g0&T-m&sTSPh1S38&37s2nJcdNAp0-ZT4hd>ts*1Vt4GkZ+%XY z+{r&v$3N4#Yn7fiQjNc)D{Rnm19Xeyxajrcin%Y>L2T)>vDeqly!l(F(~~|RX{Eg0 z*Wl65T@9j0uoKr}4!e*NZJ;_-IRTzQcWrkyRXQ$6+ zpDlHYH<33P60tnv|2R^m6;=5?%t6x9nJ9mn(*o^8+(>d})3?Bj@xpDa(an2@|8+WS#F zV+~FfQB;Dhx1`SD%p#5hYv+h;4hXJRA_DLB{TlI-#jr70iurnKr?-fi_Rb66?(+X; zIV^J)8GN*_71TDTFHF-fng!Y0DKbobtpQs8SXr>$M79~SBoHTV7wA%yV&kSf;u5^! z3w2Y3+T4Pui8OtCc3B;Qm@fZRoZVFtm!sN7N!+--_VMW&e04ZHoq_E|??4G`uMD(V zewaBLaH;PcshoRUy;kN;$Z?-{R*RE;Bk%GnRW>6`U31-<%=M$7GZ)ngNp%W%;glnb z%&jAfXQdM&bV`!lHi>y47X-0~UOc2jqOsZnPCG zZ6Zzd-|Ljz?u-(miLK*LRo`7;m1)m16m}sj&V~Ac|!0(-rt;(UADK*6+7Mu#);3Fs@P3v^lfICUQAvzeOh*5*{P~AA6+T) zcD_fGw5mOBaX2IwlN>Nq>=_ebGYtaT>&!ZnPTgtC zjXm4NZNVuYU~Rwu&`IPUdOD+x{@c6uK1pSVl+g_zmuxsBV z(Qyv1U3?V(VxGAAu&>;TGPR{xb?iBcMiaUW^0IdU1gcDLFT3|kM6xE@^w!UDe=2pc zkq9L5l(QnMpLP68aU^#LqfKkQwn|rRGlJAkIzF^Zy~)9bc%A+;}>SigCYVdgqbz-~T1O`;=2Ipp|f7P2reEQy}=t&QJXdQ(}B2@iMH*bW=wJTX_`+P2+oHvPXDZbO;&3uyqAlB+@ z{5*l@2~GOj-#(>&_!TQNZ6bY947#x4SWfEvTHVw8LLa0;to)NQUuE=?6nKLsf^+J` zq@dst!M$eNR;`qs$+|Hn5Zt8)y|g@@FC3fj&%%_U+9+EbWGP_Tspq&zDXhbT4}F2N zso^`UULJOy^vJs_??L|qHik>V%OTRikC<@OE7Y8Ox;GHV%11%y;ltOMR_f zL95Mv<@C%r9vN*@Z~i)%k|~GUC3eSPl8HB|nw!wZ$-zUD&! z(9&PZFa8>3I~W738sn4C6$Li&ITMbp^57PC?u4+aV}9AQ-T-a`Y{w`2T|*>vsIu$zdgJ?EPZ?%w zR^?j4CPw}4jIOSku$s*gc(QDaBfp^5b@MP+sZnTbMJ+xDUTX?WH?f8!DkGBZhkRJl`^zzeoKFdu6hkZN@w>P$P*OGCI{ubA-)OnXnV2N>Mq&i&tEyB z9!v9%cl~nQ!#OeAf~Zx>^pfZ`rCs7r)EGw>%YMgpRZKc^g(H zz!0HV9URfbO4{s^6vi;8i>j(l%|(;?A{YX1;JaqYrKh z9jCN?s#f1b@@d|5XDR2g`Ls$U5+{A4Ky*|rgb}f?S!;!MDhptcs&e2~Izo+|IFQzo zeu&Zv6;(n00$v;-b+**%({lWvuwwnF@#(AmYcvT{fHP_!=^~)P(oPhSafju2=z5> zu*>a?zYRWVGgqKBki1m0u7e8VKC;7OY;ZdAY-{f+dOco}M_aLkC%V5wK|RIRdQZhV z?M9&Iyp#gOs*@GLqn-16+OQVx!b*Y`q|#}`VO#Ji=d@<&AcZ4}&D}q4Idgvzv~uBL@Ijb`i@V+j7USyVfjE_c2P6g)53^ahh(^aao<#f%2>l zl7)L|GSbo-yau(hS$`32DagaEOIJDpsZ8hj9_c@MR$|4f>Q)-RGJ5|gy3nz6PX8>) zoVaQCM_UVGR|Hv#12{kZ7mq!0)5SzgbwW6k>Rw$QjV^3#8ZT%U^VZ zESa>c(om7rlN@)V?IwU@{iINk2}I2i3_zAu7+rt4hI8QP3pK>^*f%#gmyB6{D6p0L zmdTCdZX)51nuJD~uqn>XoD4v&gP51kw`PJvWgreYS@ka6?%2W1bWS;1)%4R;QcXDa zEUONC4d0uHWZf88tDrpATgw1HCHZFbASH@>$XOfKC-mGDKu^&r9ljCL6r9|5i3A^OY1Fmidx1}k_y)us)cv~ z)}NEcKnlBrg70eMNAHdz6#KGP8}KC`@LB@mRk`zP-%4SiCF4HsQP~#~g#cnx1j=3Z zYrPPBZb<8e1MCdJjFZ8ce>ymwaX@o17QUg>3;mZKDcbd)I67W6VEE>@htlbUvqhsV zu0xr_hNr!d&F47U?2bRz-r!m>_8gh0t?Wz;gLqxv36vFcElQM9rIK@p@>g3{YKeZozUx9fzER4mV56-MRu&9 z{z&Umaoxcc(HrV~s);>Q5q~df-dakaeGRCSOJ;k`HX9Atwzr`yaDb7Dt3X298DNi* zc_3NPHIq%KsYyFHN#wV=%`J%5Bv;#`k0*5t!cES1xSD567|0MnrOMbg0lx$h%zMTl1yo=ovxdQ`O?Wlw|kvEHqVV66cr$qa~H16 zvir`0){r196kR!nY369sTTYlwGCn^f5rVvF3r|jPQjXw2y|$uDJLtd7jp1>a4l??< zlvBndkS<)+=`%Pf^GF;|R37=__{I1zNX2|rzP;DY_%;gk8O)9@*Oe?brW-FCu`iZb zDg|h^qSCAQD^C166kv7ZU0x!{x@a8BR#jBzVH58w=8uvQQ?lGw&tFLF*quny>SL>3On%7c%Qgzd|f> zz#ij;V$OlS(__iyi`RW~9Mg4%Ht37T11D?mURwkqR0;4q7jC#R4_={eOMA2;!==ZVP6Drm> z^X~Y!z%Eb|n4xgSyj|GJ*F)0$akcMucePH_YkXbta**uY6nHw^l!QvZ`nuYK61mZk zUWW8EePPt;B-&+GzrQo{jzzJH3->wrLWhJ80fXd-;Ik15WzHsh)-X-xm*665NYKs` zWFYSIEXo(;gv5)}_&L0Iz2zRH&pC#y+A8~wwBL9WqG|7Is#?~x;W4H#xopxNngt(( zfAp3LPmv5y0xwsniwq{X2xK%DDh&{9Hi1uK?ZsEF518CR@ zDBuV*Hrrd1B=}$d*YJh!37+KilULemHB2j7KcCG!+wElSdrJSEFr2KzTL_TB)G zQX3lVLA-``{o)nmO-Fr=V;5RbGQ>GGwB1HaE2E-W|O*V>sIPFq+-oXIH-))N8xd5x+z(XUH*3!oD{j3s(^>F~gPWKFX$r$WR zg}e5BxD?#y_I}r>mf;dYAGSW^JtXz2$c1tRB)__7mj8BTMwMMN125hn$R;0KT$LbZ z4o6l|p2LU3<_{2-0(J83PVn7d-+lFqYWwKm^p)MACK8nZ95~<*&S8pOA@DOy>A~rJ z4UE1rU2=Amf5+hZjklHa69+L9S`>_N1S|x5EiEB?B>8pryJ6gYDhHbC&2BqRPpunu08v(Rz{qjjA?Fk|{zb+`|=r4L9Djr5}InRI~z)ur18PNa&VDwheUP z7V|Xh(OfUXDzW64*2UyY5c3p(sy3e^BveZM~IMDBWP2OUJI+HBsLU}H;-?Gyo z8$BpNd1lYlFr1`r&Ne zJQ+0dvW&*9u1@~?j5p2)P<9H68~b`3yp9Z>v=eO4F}&UWE@okQxCv_|A;0J!*Klw0 z0kCI}?EL=d{plBykji^ynTwusT$TM$t|gBg%%TIaKi2Y|tzqJcKwt&ZyRSof*;58; zUNmZoh=eMvJWI}n=27N$9zGSI{y7{eBFsD#^L!%h$6y8s+tg-PtB#xIEt?VRC+|0F zBU=+}OPVcKWZv&LX`LOOK|bXf_^@X@20<$XD0(4N#8oCtr~r?7=uecb$(~DZ&WgsE zpiMw!SZ_2aSS3XD**fo9yOAMNobGhb_V9u5&yO;Bzdw0xnvP-(GG4&-_#s5v`jZcY(4#1+UH( zlr*YqvthbEXqaxxoCI6!vz~vEIXzw^H9IHk)1;i28AkI|s2w0MjXEc5V=qC}-e%a1 z1^9%kO9?6PxrE(mBQ{|33(zXiS+?}Hu2O4x^>+5J(V+Meb0krtFgx%w>VyC&i8ve_ zJ~g@C!z-H<@>SfT?Ac;=(7eU~4ZY`{jV~O-okP}{>P1_}^*rJ=a*aUq@t4oc9>1N* zDY%3>D+$sP?8giTebq6)-;IzObu+a#qRH4r$Uu3i>cf=-d;MWUs% zG(Ky7d>=Rgini*!Biu4%XfssIEIkJ}( z!Dm`V@GMfaOq*1o^In`K55-NKY*K@W&0ejaQzpYIWx}S~i0TH=kAaR!6#^mm5BA30+|l@0yN%*f)mkvLBDl>l znBYl292Zn9)C7Wlz(7i267_Y&5Rq&N250^ixPN10i56%~anXtx(+$r-0dyqEZ)Aq!#i0N&x)89$>g z@UN#VcDLD#<9Xi&fAc@ETB~ZCYHZX{fx|619YC9*eT+G&D!H=gl%6*L6+b z6lo2052v8JcfDO~uw7>V?o=PFq!q3q_$p~~H7qHH~`z=l;EulFH3yt8g1yn~Jo z;z@E#!o9S17jNgT`M#c9gDV!qY>Yv3(K>BoN=6GaO??wjWoq3nXlchO6qq^Op~H?@ z(gg=BmJDxB_K>UIjhzYZ0w4-h+~;DMAoVO#kMIsgPVmI`z~v5#o^2bZkQb4IlbX37 zx(2FhiP)A9LXdl_XjB7{61wej%&E099j16&pt!3!# zI^Ew@ltV2~y+W#?iMkIHUYffx;ND1rK!2rbK(NhbOa6;F-WA```j|BjTx^70x`mBG zdgf@A_<=ju@Wss*72hQFMB7b!+W8SYtEZQss>H)?0SYjB>B1V{iCS2+b%*>pP#49~ zJDdZLnyC@p(TLOr(F2+!&1@{c1)E9XX084LAb?!i^HgrSX0``nzjCUnFDCx`Ct>-N ztln2?tnQ;K{dcGXim!}4`0toxPO!BqtR%@m<|Ks*@1nkJKbObX!-?7n8tYCTjv%ZKZ(=xsqevm18e&iFvtDy-A)5VSa(CUjulq`d z7nkpNI{e&hUCLNBeTrkVH-u@CsRZ-Zmkr|5m9+@Ysn}1acPttmJhVfMUJSZwc))`I zDDA1EDSLpO&WisyH#=$|N2>JTk_Th?VV75Z2VDMs= zBLMfmzkGe0IX`{UCJT5tj}c)lcWg*3XJrraWs6DcJAb9ZUkt+Uo5eN?-ex|aBM2(u z=)3Lzy5yBc1x6Hj-38|9 zqg3`IQ}GdYl4e&7bT$1pQi=g?Z^iq0^6^eJ`Yf_z8TK$7gI)_P@yb)1`8HqvUS>?p z>d7iHgeB`k-(M;-OBo6x_>6dI-zeg#J(_H5ArN)>mr#@a=J?-+ zf!`gg=&Q&o3kiq}N4aa!9cO}WFgo)cDE!Q?$$lf=m}&S;RO5bbXnBYNmsQbam`H$$ zkfX>w+9AhaZ0W(mz)PSey(*e~)_&V$9Xa--T?!*6ykBrU+HH5ue<73~u#}UyFtE)& zw&M=t{~Fz`$~or}CstV=_g2;YrPwH18?;*xj6bl`r8PI|3Q}_j#($-fjlDxcgLT~K zhS_EcYxX(AT2J+yLTvm!JJq*WL1j7ywA^VnD?Kvajwv-xM#tEARu5K1uLD#ac$?!5 z)wpY?DAshS*S)P8RQ7HHB)&vBm4v%i=+wLzvj??V;k+2=5bKX;XvAOxD)S+G9zwS5 zVcT~0wZi$S_Ftr*J^A&g{CSBOk@M`I!mjUT7kr@*c9~P>*^;%u zMbPJO+biFeend~83f;}8U@n$YVd!I!81Gr-Fjh~eu8yyKQu&;0k&T1~j%h}JzCWZj zFhxj9Jv+nmZIypCAsxHh3yw)zOOoJ3fVX_Xo58P9?`0vHit5|cVvLThr4l6e5y#d>{O{S>O!mW4g zKm~qkJO9VXM>+=)$JY}Hm8X=goX6LlL#n1}D_2#*h+tw{huW#&Y`AyY9rR6$K@fT|PG4+Q`*w zyO!U#o3c#vM< zie?E%_#zf9HJO6*!Lw5iqlNeZL44KH&_Z>D)y?v09nHpb3oYWvz3tNvJ@h{74i&o2 zt~VClS{91KFtXzdNS~K`cDAwT^&z#0X#H&U3$`WNClMMRJ#SCLr{12lHR-3X6uwn* zaHB(xvhBd_SiJ3-eWB+Kcg*ER)r`e;jhzF*+)L|%el2I)sO1Ks26V4qm)2)*Pp#}c27SKg5)vqv*5^vv}kXug*M|368oVL55vG(oM!l<5qJ9a2S{FyH;aL@Lj8{<32ZiSD>Mva48)m>*3`}mVY zg4*G9Lei;^DuGErP(W%u@YElamj^NmnOld6dIq_9@SiBBXA zt^vRrr{R_dHfY59z`;^aI)n47+H!x>7z+W{(NGPx7l#{2X_8V%f)85^?i-8?28bgJ z0$aAXo`0e$8YiSX4sGA@5XqUlOZ@2nEub9P04GRxKQu@NDIO_GRnb-g-AH9`EcB%R z)|fsG@tP)kaC>o|&p>(JX5Bp+j-s}Da-TIdcoYSs?zDyTxX`Fr&X5AF&pYw@oz=CB z0bfH@@ltKasZql?YcV{2xN-J3`mEr(TsOGeEj0uyDb481^z|c?S&BG=aO{!fg1EGW zn2(-Bd1rx8EX?Ha57w*%)@;(3r<|Ar>a1KpjBn+1)c7Cd{Yp)Lr&*rCk~O?nn`|9? ze`5EsuohT>bmFx`;RxB_fkTsmPS~Yp!rA7Rk5L^v+hSThzXqOAUn!Fn9O#UV*2_4b zL0UZSJ)YKM1d}jW_xvw!$G5maS0$a6S zOFDfUew1J-7G@x&mhpnR9*5)eBXjHG-yj4LoT)~6d+kbO7bf5@Ko+W$9jxo`Xo_4n%mWk*4Oghe+yWr>5j9`zA-T1MT;^XTmE%5Tjx&D1LP~Cy&tnb3>omSaQn1%u;Z=!=v>beO%<7FO@2AkY3U)$ zOUkC#}`Rc_Fyi=2KS2oAPpv9Yx_<4%d4RNOYn*W=i9WQ)|$*5f+Ob%fLm z3-*7j8lD)jJt^Ys<==e6lSyd{JxIBuR-z9Lc4sPD)m2`b*)U6eQ_j|;^oitE=-H)( z+w%x}Bmvy4srYYQuvyO))nFyfnP0bjd@Gl4(xFuitR%a@)KwKUcqr~SiP$<=n}_E# z*HICvGZ``C=h~yi4^37mhNB9gX7u&dn837Gk1~u>i~={pPUG$gEo;7Ksl|$DT#@M!+SeLgkS)6~d=!hO~wJ2M0Z0C=ck+}0|)7X3sMRj)E-o8^@h~9F8AoBhYIm{CW;r3q@%;GjZpKJ7I!{IP;8E0WYl7F{U<;5NNwmsF+eYbwgwH7;Joa_Os%!~yqf-y894kL<& z5u+6HUdNVWs#_oXo zD&I7Wk|z5-jnSrIO*}i0<>k)~jdy>81@43r13qj$wZCYyLNwSOhHRPm)dJx1l-o~k zT}vyCP4iWw(#+hn>?1*XkpAzPeCI^?MS{;)mJ&H)%Fhup@#vgm!u08?QP_Cp0psFh zTUGjBX4>rt+tmL9Wyxd>+HD<-vfZ&iJQmX%amz!|RoHQITDn&>{7qn?NatuW zJ}vzkJWuktRVVu5UqAXE4guc+{I~;U;ZN_qK?X3;+^4ZykMe$$z%jO_W#Pg1IUj`S z0ntlo*%a%$!SQ9hY{=U~>G4t>?id$X1z_ zAi4xoF^!8bO%L==FT+`CrrTe=q8lx;G;1Wabs2y9ArL=no8kxmSiX{N+hpvZ*6TkF zzHf>8{Z-kp+4YbUZa3+V?o47iMY{00^qD`6`s*k6Z+$`S(PG2-fC1|FmdUg=iu z|DRv|dyJzKVBqw@WEv8@xWb_13H``t+rpTC{G7uGyzO;dsS+~;&W9-p9)$b9xBAyV zq22?|Ru5q4!WY4IU2nE>5(eTW>V`i018MMQz6Z;AbQP?c z%cC-21gx4z(CY%K-&gok-*}5(#yCY*ond z^VACcIKPuin;%)E*!c_S81UfT(|@#R;7)p-+b>pg=paP%Kx388KVc9FKx$e~Q>^7v zh?kyQ;-w#4uD_A`f<7R1?PTy7uy}^%4-WM2f0~R2YYr)VF6IU1*O6NO!7chLYlUiC z@BpE6hIFnZ!Y#8DvE>;R0_>a3P z!ON>ZeaNksz{H5czAL3Bzz^;hG}>yn{kQM@P^JI34LksrnWkUtU?CS+K}6`pFF(Cz z;B|2VTKmpVsMNHxqY`h5eEmmT{*kHr-?q#f4`}?NEx^MD+(pK_+q^$dYOri@6|63n zMsG%;p5!u){e$14>^60>&rGlFC|m1XUi9WWWFP3|Is>@bb;`Mnt$fQ0ji^32ORoovH?pd8&JJ3ATTk+16)tMuKkb9 zroSEt=#jW>(!Mv6FA2OT!|8_mk%jQL9dR54w*#UP&1VVj_VA;@KhyFDWCnklJOU;* z=$(_a1d2+)?b#1KlfMeVgzJD@PgODm(j_4SJIh@ne>~Tpet!Rx!0u3S4Lx`B9bg6L zwW(bHgw_u>b+aEe@g{&AH0Sb6{F5y^ih&8cdN9RFnVXgt=KMd>&6^72i(_S}BDfyG zzn}bp+4I*k1}p-uhr*G5-QU1Be(Mf?^YgdzU~4{@PrlrH?gS`~p>^wG{zT0GLOR|! zz|MCsF$}E0&T(>o@}~YP<@Rp|twP&0G{6FC#%5*z$r<|qTfi+2;nL;})ZOIgc;)}H z(5UpoxshlIQ>rxl=d>!r$nq+Ywge6E$1&G<9h zCMSjtpV}HH`EMt7`ZX{LPR(85Y&j3XZC4q1^-s*N?SMVRA<4R&3gAB9J?H*Uj@auJ zm{@AgM*s_h;C8Ciz4<5fy0U5a)h2fAG!h6UKeQ?aDfgfL`N!c+yDvFSMLrBL*{>-7 z)XW`Pw28S}{jVb8Jl7h^h#;R<&=epehyVI&;ZvoxRk0?cpSnG{q!`D`&B@V z(+3*A9NMH3n{mzoll!t&fsR?F{q5r_HuP|0{R5-)xMgF%)yo2->pA!wm%yOjuifLP zq+-0;e||$K3ON4Yl9Tti0Q<>)U{Fduf~G>P^hWA4G)3Ll7js6_{Hcw__XVrg$OE^K zbILL{9t~IMwHXE)Ia#J6%9g=(eoZvdx;g$UPpLWOrzXAz=iw~M9)siI-wpfebsVn+ z%Q(k7yIcvjZ5lLKMU@?!q|aJEh+%6aSqJJ~>3e4kVqQ{JOBO7F2u0=ep!Ij6l&EOL zd|bY@V3&pWt@ZH_bm7i3ii`~@(H&_`I%3wlL&@_tkft9wvRkFW{hJ`VD(-VnA`3)D zu#Vq&w1;TJuk(h82AB!+)I}-!z#+bYnNB5wGPkxw8OvZ{L$gGtzG|htqI+Tt8fE4= z5$nob1h!Em?)20AbmIe%?2pa68G%Az(s?jxMlzi_w9lh6L}I!#x1=R4*3Zn+XO>~x zllHlb*I6)h(3a{ww!)9kJfMF4(ClKk>vbS=YOWL=`B_^3$-}gZ7G+1}l#Xw#eDrWo zSX8XmDR=(`8B*^o>{sts>N&G%7)_EnQ_AJ{I|+KKFKKL)A% zsJ)8^5XJh~%WXe9h4ziB;M<%r9ZhSpz?}SLMjjH}6;o12GAKjg3-jp8IZr56tXNErbn5U8poB~X136HXpxaJa_-XE=3(_K%67|U* z{$@7UZpeu1}E0%xTlehM4tchd~Wu5J3taR8_THgd`mp7B{Tra6; zBW-g7A%{2s&d6+ZTw6ad2;5j3GHPGKNWsKXp zh0Hgs5a;+~Z5c*;T_^!V;z}~NFv}(pb1LSCO;Z#Xyi^16M)(a~KN z*%Hon_=wl}s~LD*#fp_{n`n!-CxcBiVwqJe<^*H(lXOR5aJ0csa*)?EAQdxay8%&^u+J3E@5= zfj!M0?W@GD8HK)Ut#knfd3T^&8T`4$y@mYB-$$n9b_Dkhxjl<;uTY;@ewAx*i1fgw zO3=^~#g{TBh`6xePp~bT_=;jAib4(7#U31xYI^ zO-3+-T!L42o-ZOY_V+*!md?L@&~#!-V%x0O_oti0fcJN=)LQs_p#{`jzxOl_=G!Sh zwDwWJV;!0EtjVpa#0~$mD*x|C25n|*<-ZdDyMXyd%RbZE1`*4WRz&}eBB9aQoQjMC zzMJw!)s&@j?HI0<<1mC7v)wmxyH8J{pB<7sB{&cqz2RMxCmkC6t=u=l%js@Nj+oYR zho6l4iITzP##yiFoJ!wlkhcq9M)tN(wM($3$|{pjY6^mGV^uy^_rcvymn6?gudi=N zB*h~NnSKOpg|#AtnLWhPgwvif7X_ZoXnlL{(Unw|$0CLZ(4lR?_q?JH`FkI$jG&|q zQEgeIT|JkY2c*(Of-46)8XBQr&bC7F^J|apua0nOE5@)VhxmW*`_*ijw6=+1Q7H)a z{7Hua^?K7w@uw%=m;-M_Uilyry3uBXeWq8n41HPsb}Hc3+Sl$mPbposhT@W$zQ?os z7%n9@Rlfrrkbqb$UqW%9=tCZ3E1z|8WbrS#qYV@Hv2b(u*Ejm9p0?q3aZwEdaSa9& zR+5`G2f*b3@oV5|;7RdMyGj*{)^9#nG9@Z&FZG*Ya;eLP0|LmTx&nGS257NPm)SDV z-^o^lqP46lCdfoGBnU&R!>>E2zFAs#f>P<(cqdnsGJ>O$U>YK3Xuq+HO#!V0>FYcm zdOqB~y$tCNhw}+~YD#`-3uCt;yroDSot`+#!X5vQ6@!_b;2z)6)RWKi^KYc}%k5o{ zwxC2WML8q~YPDbbY>|U^%6eI5Y!f$hFXTW#e|+Z^rSTM+frK8zYfXgjNm_kZ^6rgq z1wE9@!ufbv9&CnE79!HZeX;hs3gfkbTuxO0&mMkV2#z$=ak@lZJb6EHVD)aQcf}cZ zI2^tFeLU_dOiDpyCR^!DS}Skm zWUCy5hLDwfYaI-DgH|b~+L1A1JqwPkymj zP=JgU*tqAN6fhOJ>)en)!SSVX-vPP77{qUt#JCVM`i@DY_(rT>vn)|YD~273eB!=N zc3+?bip%z)dDPt(7gv@nd=<85WKw$N-UPJz5mwojPYRPqFSCvf*W#^3p<49mi&7f&ifh+3*l9%b zGDiIAiGqwI2?rbhK*Go>RP7?e+;Ym-W2VON7`k%M=)n`Wac6&zfHtGgUHmH)cRuxxmZeNE|aPT&7-cA;JaJ6`=x zN#fn?%}aPkFx1*7^XRDi5In@cea~Dj$3x){gaQh+%8#&v@`a zJk&tSDC0FeVn(cfUD*wA_`6;TgHq5Dqyn&ri)CKz)D0VGwi~MKfH7=Su#SHsCTG}E z$~xB;9`IM?9f+S;!MZc6ZeA_lTWUqXuc-;0>Fs%1&>OdaGjXF^=!4$8iH%v z`9+D}K4yEqKr#N_FxHN`N*vg?sZ8uDkMS1ys`ac>hE}!pEz=p_zY7q`C9C2Pv4e54 z;WUEg8frgA5gFi-1YZqt5|;q*F78>I!2ZWguX{V{eOc?$3jk26M7?@wtMl|Hiv5{Y z?{DTGm#qrcOp~I3h?wWaeX$j5z^2q;`F>_oUjpvbv%~bEOc&O-OQgCo zV*g7br#fVSDmdtMi>d-=l$1_>E^ngHi{|l^{-c8heG}vJ7e;#TX-j~2#MdbTTEf6D zlnfcQDbd{hIEZB!9E3Y5SC&&Xde8qTBDP{xH_B%C&0q?*cE+kZ^;xHF^QAGWY8F7z zeSNDW^=f&nBRR59B4Lj&bj?_+k1k+?TVubV|r+nF`-N7sSf%KF>ToG?}xr-OB~g2thZ>jCZX?aWsFW zN8&v{H6abe4eQ`t-Vn853<>&c=|ZyZ7$(DNKdafr>Sx`Y)^b2eidMkm&3GhRzXe1s za)ov%aMMe>PX4@M!@ANBtQ|Y1o!J-qD|c~V&cATMiTh8-`wfV|lf%79LC{RdEBFsohZ_I zzA7hgbmb3|i^TA}c6Xtb4qf@|S7S0G(%G%b!wZdPe~igV;nK$YbQF!fW{~#+-ITXx z#Pi0z@wp*>6uJ;QryP|{v?-cpEfF^Mhm@`1?KFh~I8a6}0^$fu@(_eUn?Z)U2$5;1 zAEAj~iFlVV^tgu6s^TJs?02tUERWdZH01v}uKua+tVNaWrlm7p4>#UC0Jc_6yj#=C zY@ZKym0U5qLY<)m98qA>D?RG6>2cfW2|6-AOXJ-j2)FYBxcazid@f`O_zJrnLdG@6 ztr5O+Vhard1lbve8{Q*`I!ugNwuSqetxvxaZCbm*iRy?b>AM?whMZdoeD>I5cq1!6 z9~#wTWZAb~mAJ0bp4lngZ$?q0ICIwZ$|~CUhykO(V^y9Ww|riHb`f1PCMD6A5fn82 z+-yN#Ib*{TpoV2)EdpFtFRDqOLF}~*-sJ;XJM7-8ycu>vL)$2en;Lf`sB=z<0Qf54 zOvUDn_xPxg7(1h;#1La$pp_3Ior{EGBO(eyTwMUvvx_y(TE)j3;{zUm_otsp^l)7$#R5^3t+=%diNXG9{b{Spd zHwf!QY}`aM!N5=JD0E8IPKtH!TcGVgLrh1Q(F@Nw!n#~?;6`|m%i0NG6z-M{0V*Jzxn>wJ* znWzA|Tf~~*0EusP1NkdL4baLS5&#Ug`b;D|(7s3P2?8-UW&^@h?U_v-_AOB{l5zsh zS*4afYD?TN4eYVLk-u#c&}evL*#c{-u&VB0`HPgzT`Mz+-XTQn22w)8`qXKJJt8Q= zxfJw651gVbJ*E#zD%&{RTUf=>XDIL^RrjWk0?;bvJ$Oy_CrEeS0OSS8g<|gc%iP+g z%BcXX=4z7{us&+!F7KOrhDlS(v6O`etXMSCkic0CVtoyXT{hl}hIlQ!6pFP_qjd)j zXmBy7mrWz;K7Zps#{w3_=wye2ym%8ux}tIr9W(Fav@*}nIuJMLW!U`od}gWuI%K1P zDKg&nh`{R&Su@qG`hS#tdpy(q`@d4@?m*p<%BjO$Dj`X7oN{+0DrtpTkrW~3Jlm+G z2%S()(}|ER#LTedup*m7&WD8<#ugi6$KPxB;rpo1@AK_jf7PS5z2C3vbzRr%d0p4@ zx?bAO<&_>oJRjuO4|~4|Fn31vNw%6gCWY^$$p8t5pXWkoXuCaTcjM4TP_OQT8-FhH z{ftXVSU?sC8hk(Db+<85+nzUy;pCZ$H5@_!Gv*(8~*396~}#65&Ov{}?Q z1YGSPgqyi*w~67>!z@1Wfh#be1mz%+DmcKVDT(T&VD%F8V6Nf&s?^rXp53fxnnEL; zihPsLsqebCRl}UaCz;uqMl;_NSAHNvD(go+{ghv=~6)9o;;dJHpWy8NUwyW}< zoC(a%ANn+7#&7o(SlZQvK6^(quYh|ybL0Qg9)%E5;^boj3*4^&k{b7dX+bu+KtAIY zbHKE}Jm1QI~Jw0BU0P_10J$_43MwKg0lo{=VxDp2p!^QqhGlNz9X;&ZCP za!BGdIH3jR`Tjl z2)~>}=?)5YGr~FF3Z1N}t&WB8&)ivSmZM4tDOMiUP}?znl+0wPqmCP0IRTJm)!FmX zc;k>-iQ``>j=7RTv62*{7vO#tto(;L;z2XV`?Aj}aum=PLwIYGnL4gQ7S@;WCbN`B zR6s#3`MpZ91EfMyX_$x@Te}z~&Bo*5Ncf#GYH}?|lIv2-XX2(FAJ9(qudc{%*`lkf z0YGaOWjY9QvQ6&UPOuqAI)B3 zZ3b;Pf+K-X=cx8%gc*ijuRQbY>%S?9u%{4D9gUMeS$DBe0hJFz)5YR}lOTUfYHOGA zUxxx-pe9K^cw&CH2sr0h1<}{>g)mrH_Q+(GuG*PB z4FGNx&&|ez8cFKZ2a&5_dHdGx^bl_wRiMzm?VD^9yvmi@976VgtiSe7!PKbyVu$qf z#mv%!4j4BX!t~u~4FKM65+fw53A>_g5~sYb=hL7k4Q(1qPb>wd<|uIIx8J2 zM-r07p-=i0cSEG9D2kc6*TwOv#}Dd4eIl1b;d)fz6sdj#52B|%BOK7J3q7$$p6%}t zY-~`*=QrbZq9IPcRsk*ZhwKyKTNEzgO+s8cdECN6#C4)>#i?SYNDYiXHh3b_Q@M4P zV^28b=jE@x=c0d@o&foH<{3XnIovsPd|@)5B@4VkRo|xk^DwkdC1F z16xBd39l=i|1)O=_>A!}fJj;b%RaPefuQ}actHk5r{av$%!ESqtgowQAgA~2x!F?E z7}ndg16;sS!S6eROc)xB2FR|v-Wv?)3fX<~HIb1p%unNyH%JeU0%k!9JEkfQlKU#_ zU2^9U(zcgn<0q{iPUtqID3j~^M4)n|1kOsG?wEIvnx45zPty(f?p=W)tzDCo*z{G( zP8etttPgqf5aT0Ck4hXSPm;)VRRZ_-8_pn&>e3B;rQYrH=AaXbQspZS2uftX(ph#< zrqq38rgBH4sPf}j1trTKvrAWsD-WOl%q6vO)=4dkavVwCv9u5y`lZ{YFyM6d*_juH zy`ZNj@bdF>LDLCn+Zk!P2!OpfMN=JINawxLC=t1EYCWduG>VQ)fmR0<(tF34HxRfu z>CtJ5O{2n4<)PPG2S6V5IATdq6I@ru?0nCC-yxnt43{*^$n}YbhzHwB2K%>#ln3KV zvRZJq;%fB0`QtSK<7<;BAO{aW)%&v!*H`Lr2}2D<=YYdSb2Vks(q}tT2r=b^JM83ZQ}A~ZhQM5=?-yS3BBY}4n)Gj1`h){OU9kpUGz zWdpD5f~s22+S^fV71sjyT>Or#te_ys_OZFv>GYjCryYHX!t{4}H38MOV{#dX z-0&uItBN$Om1)*#dRht}&5c|yn(8y>Oi!8ncD|6N)}oILQW6kzwQQXjJ6&Ra@T+0- zN5Jtdu+4JgEgN$d(WCsj{T;3vyM?qAL2oNQ)y65V#uu;o0GjELSqAvmJWSGi7%`+rqTW`&>_ceDn+EX6T9o$MqvS$)Y-pL130)=1^)7xheX;GS ziqBSgv`_bNbgR*D6Kx4DNXL6FzbwG}x1wB$^> zQ=pycy|mC&oAo-ld&?}cjF!C!%CA*?Eg3@w#`hY+vo4Lbh(_JrDJRGk&)dnmH8B9T zj&g^_!VyhSHaaA5BVQ98>g|LP9;#!3{GESk@Dgg)s%8P=MTQ_M4npeBZWV*6F_TJ&#BLWvvpZgxlDnhTg&k!(n@3<*=#hNc5!gz5Q=vaUgok3TKK3GnO=MD09Tve$E+&`HPTuQNr)%f zm}A-bp=BwlHeN+VqYv2~OrhfMaML1Tg@rAFEw?Km!g_nqn`-+>&HRz3g|f!stR)x^ ziJEKsF_kD}%eG3m(e!}nGGrsmv6?}jOdgnAGb-b+ckjtpojzC(oKO=wS)8`#HmC+Y zYo}L5Wl?W&aOL`F-=^t%`x{Z^ClAlvLKVmJF4mgaYU=jg>k~<+6}zMnRDQ>!Cf|D7 zxUHp6on?#zGG&6646!RZOY{43R@F~VFWEL5CY}zeq3M>HdlSiG_W5$go1e{&!$5Yt zJHXxX0t_%)3Qm+;BS!OMD9I0MDPL~aSA(30%7Y|u%D86P-NrsL*Jq)Gqb1CHS)n18 zgE(#<^kUY2+jV4rY5iXh6^Y6Z#;;S-a_2a?)(pACj;oBCJUbL0 zefjLpJ&~?0Sh+0gc%%lhwEbKNhTKh`^vpBe&<1mJF{fO(yT4DG?_kY+Dx^*G0ygbI z?=6#-_KF=at!FL^OU8L_PCFhiOtPDu{V+~5d)$dxv_>_(Wc(!9^4s~R1GjUNwPNFy zorAYwc+){YsssAL0 z^E=Gp=-d7g-0}SrLDk=%+35#NeUm%89`F+1z-52>djKj%h(Q6Ccc{K&pOh2ee^U2X zNHK4ujU?v?*g` zYob0_a=lm4)?bnJT`3P}ZJshu+Bv9uwD$X?=l`LlieSl+Hw3qUmc=h7#s3QF)ZsLE zo*MyYwgucHr!Kgp^poCQit;1+L6eEP&SiSGlpc|EVAKEcn%}L-LKYkki*_bQ0n%t_ za4HI1Qu5RCYSaM>o+x;rT`CWHy?Xby{G|Q=^@uxn0n=)6rQiyXbeGT1BIUmn!2$y; zLh#IOJVR;`#@WihBIzy%An7~;VNO|7rdNo(aPwCreNo!Zli54+mI&C`pEDhQwkjum z?Q=3fTC#6BBX6Z_7VnYezw%%k@L<;SUhj8BODqigGavo_^Sfk`aT`1^B^Y6R-UEQ7 z*Y$0`!s%UO3iPA0kehh`uw$GT?2i9Vd;Sk)F_xyXuN#urCIYQqMmi_|D@$&Z(k|1= zJ?bAXu^aU@LES{S^nYU;=srlqEa2z*2ql$r~Ck%h3EkW7`1{#{0b_F&{ zEh6pH(qECZmo|`eTX(lGW>vVi*ld^OFG$)#A4uA;#oPZgxQp53YK!(S0T3A=t$CkA z{69NlM zeEVWMFMuUm9%R;_fHPpl+}HcB`uo47x*~x|Z0I-N2!3PJJJz#b_-;fZFhTFmJkR*s zpkt6??y&GzoKK0=`B-%YjV+N92Ah7x-L7v0txcu#?hN;X1*@yO!+!-fy@>$}CXHW+ z!CA_b9x$Z7`4xNG1dyWH{;%ea;K4H~KbctlTPlsx<~8x9wI(A#(${UqB7a5F#nO&t z=7g8H<~IvNiTdMT>Q;FSB%N~E(DZQ&u~Y7^qUs8;LGV7$Evmi>AmVPKlt5;H*IXx|5Eny!HPKNQ%1BOgp_YU zZ-YN_!o5E4piJpd@y8qA?OcW}Xmbtq=IWgvIk>CqyZ`#`aSOWOKzT&Gl5FT!nch#` zu72NbM5AuR6L~Yk%@2FerfB@la-A0 zRlnb0ZF_3-{R@0+yN&5U8zzW&?Lu&=W@6{|Ro@MziCDN`^@iCV`k~d^TFMS9Xumf8 zAs$M$2P-=plxaDdo51TK`hJ{XAKxFGt>-w_x6}6oBwj26CU0CB6u-0Q0`zFlI zz)4C!&;0ho7No_B8-|?QT9|j8O^_j%n_8{z5|eNPqqoeLkE!E+)JOb7=oWEW`OM*9 z;`yMexZf|J<2O9xKeY4S`Enn)d2z#t_mUrkdJ&0IqZ^&@6ny~hO|0(l&seCx)u78U zhY1a{y6k8c-{2%rscoWmM3e`M~ez|?eu=sG4%EpfaUSCtNmwyb($b0 zdFkJZt3mtqxx2(vpI%&7ZS50Am+z2?^43oZTDog);`DJgc049>Vq87*hf+Br1+@OI z#%>M(&=$0`9r;EJBTlax+5EiB0_s(Dt&-6tK9KZsxsLAc#W0gHiaYpez0=^vqVE*? z+vCFmAw>r5X#buo;N89JwI6-^VeR#e>tB~yAiSy?7h;k3TW=;Qn=OV3($nE5e$i$C2=uD`6?*wfp{_{_N`Ti?!eIJ2|A$DnM_TPKrO#k!%VNaXg{&ycr%g!&`4 zfReL!!Sc~Jqd=*<;v99qU1jpw43kez`t=KwNh%)t4ZRaX90S>C@qlxj$MLQ2KGc}0 zoKEp$h2lu$ViL(rqvKhZsOhF!ujLOraCYAVUTc-tK}{RbC$uW4H~CxF1Qs1|?ZeXD z0fzqWDWvYYgoLzgd=B{v-b)8-6**?=ckHQAfPX;S8)aK4--DC`ZxaPi{yEg=YVDP^ z?%P-Y)~5gkjmVU)vs8QZ)o;I91ht_ZwZHvvGBjiRb0@P8$-}IpL2*P}ZZ05O$8dFTc&uV;joiZm1KT$B(QMI$*4>$hz8ZNtAYS|ia+`*+sKAatw!~_*<0Bzp+*hiI<~X2`L|0TW z)yo3|YK|DTFWnD)_tBs#`oXi7_P^eT>q%YoBe=dsI(gv9>KU;!uo>h~)3>HFZ+_Lr zMm2982(;xB?6NA_rjmj4y?lHI1B#;lVHdD!12B^JiHgAWk#wg}OX0{kruNg?!q5dz z3O`T11f%*8+D8`yTFA}gKS&y6T$b8upr^5`3$WFE+Uaj!AYxc)MBXq7@#^vzZnr#y ze9C+sr(m*EQa){fzoT2`8Gi;8+Imsfk0*oaajKk@n1MTFN!IVz)L}{v>IRt<gN8k%zDLaq)#MD{_{vhOrhXMXQIhTj2$V+lt^UlDDF5HP(dpnNx^-kcWy zOg>bUk;Zo_D`l9aEkb?L)xCA1Qxc=sx?#lscYpixT+^H@+m{wq)hV2sPV)Nk6sjMN zQQ8=h{2bxtY;a7p972m(6&LIYS_k-51+_6gCHm%JJ!{Wa8!a_kx=$g7_@mf+x3o74 zF>Xnr?w1K2A)vufx`FqipzRQD4IHM37_K9{(rl15f89YhC-)t%5p;QT8d;WzVkBmnd`?9TuVx!qk6PW7KCvuVJ0-oB8Z^mW6i6Z z9ZMXW>Ivbv2F^(G!e$~*Omb7_^cpY+a)(d+Am_AZ5zzhf7BjbN!RZ|9m4hrs)r{p& z-Ef=ARGeQnS3$`oA+@FD-&9U3FVVHwTzI4Sw-q|lz8hvH^Py)hG`PPeX`p|{xRh4z z+V!z>`sT9G?gTny#}<%I$FL8fxr~x8bl$RA6^dGMP#L;@dWt8U8c-QXAxi}F*-k)x zrJR|CU2+Q9F=}^9h56kH_NGqrEKy*q^4_mSDYZ#`MV@^j zfPms6&@mt1s8t zpu4B6-->)@_Bw1+myt{_!fUBz2*0z_w=S~1COb)Jl8!k)VpFNklHr1~^C0MlF$9~k zZj#omeoH}2)*pPa?bdr=J_ZQ54I`UVYrHZuKy~^HnA|vJ#+ZX&9s; zx%=`5{H&4$`VfJAy18edIDW~346D@(|9@h&0&zDx5`F9q;$B!(XABqWpXtRf%Zb>4IKJwLy@n zQ%l>+X8k{UY&0!+PL7+dr%%M2iLQikZ;+*?*;MFxe5^_>yl=?fv&PnZCee?jA;h@X z&?N}?S&d6ijBoUea7QE1&zd-`bno4n?#LxCh2p7{!IyA&b7Af?X5NZ$@rblAU2(ZP z4BLFUk8<(+%u+mAD;?CKwzz9XK&C$;Ecx-u#(d@KfxjH1#i1qsk&k1F+D~aEL`Gr@ z7x-I$6i>DtprE%lOE%UYc1EOQRj?we?ZD%+g$0-I;8GXBZe(zFAowSKGYFDPCs|T^ zy=u0X3ZfG$`g~IMKr)xnBr>+}tP85&9@5{R=oTpeauGUj7I*o9DV!CqWQowk6;!0N z*9J=)53+2G@tJuiUbr7FNt11)8;jUd-{QG7(ZOZ%QJHX8euLKO_}I2br)JFdx`mD- zxtITDsl8qTglALP7()&@tbX-y)_S&h?!l(WGC5|B{D$}oGRBc&TE$p#vfB$u2w;bN zO@6SYnn`fdZN5EPGu_&v6H9kaObc)Sv%PLrZOuaZ-jdX&lz3wU^VbyL9b>7H8I)5OAJ$a`Eb%|TegT-8@vm`zFRs7v#4?cD zkdC}{$4XE2tge3=l{7W{C97Io=G+pa-I5$O4qw!K#uARMa^-(CDkraJPCS?4#vMvu zW9R<7g*pb`c4qE+)l8h;GcC=>BAumY(cvSvg=rT9Oxj^^ahLuzD!I< z*AAe@3tcFnwo4bhbbo1Fd8Eyd;d0f^Ay`Th=#PqFjU(ksw)!bfxaw-f)1 zp#CRYy$mPKe}#rRLZlLt6Ex4m$I61P6b*kV1te!xQjDUDbvwb9Y>GxVO@|N(8ldIZ zIEr0}3JYd?P1PR4hHeQI^?WFjUG!wn?_gHWqrfWYo1-$u+UMStY%W}tNKX=3M&!?h zN?T$EKVo{ju6kAVg0YjNS!st&F22Ocd<2o@w89;B7C8{awq^bs4s#D>SeroAbFyca zSp)&Z0mgIkgh>Tpaw)~VZ?bDIH@2I{sIoMl>8Z!vX`u-m1NoenJ1R^we-EeneN3>+ zXkiro=^q&IkNM5r-JP>_N3-bh4q=$<>T7{N$U3Z8a|QUO%GJ{qXlc|lypA;M;yV{4 z-(VXiZGoLkw#6!H9b2P};WtOjS@O)q{^Qdx;Cs;fpz$*P+D*eu>o_`^rRFwxI!dw? zOy+e2)HmSt)Za=r-J$%Z*2ii5RCp)Kxy=Z&bf1JdYg_$%a&Y^^u_**!Uw`lxUb4PkC;oO* zr-XmZc%kvoqZs7oPpOg5>aQTqzVyg-whqDsc*5(0Y_J;fX6@}wwIa+6OO}c&_^2`a z;N$Zs#orf~FC1-FT=D0;h54_RoPNc0fvuRqGo!uE*4!-3&E2|vYogM)%b^7;@Ae_t zD-MTq)2-*oY$C#km1ey~|AEnmV^gSr;WxZ8whW8hKiEz!0)RGi@%)MI^MNtCM_4XY<8zc;PM_nSI+{;eMQy$~m}t)!?J+ zyjv57*y9WG4lVPHbsyH*QNcnBAI~yldCJW4V~I4QaiU3W%uLsY;=|`BJ`7S6`v(?Pu=*a|Ym>_jAQLPhey2@Sa74nM%RM6{Q)NBWakr!;kD+S}Hx-0gU z>&7JFgvdILqT;wyT-4>meMJSzu+FH+wHk3Tl5LD3;z7rj!)j@lv^ud5?S z-YQ5h$mW?2G^Yby_}k>C@wv&b+)m%~p-`4J4Y|`n)Pn*&YvA78SZNpSBXM)LdbC37 zB*_I8wQZFvTaB=_jbjqhU>0xaiMKByylVPb0yWS4F9^hC3}Ihi)s+hb6klJb14v&Fq3o&-R$J*`43 z{V3C{NOf5K4(-^U4-(S7?rlDyzSdnA{PWYXyjTU(v#%IFN%YC9AJ4viUhMU6khSw_ zgu1u~)@^?_8%%Xw27AI#y+*}2(<&LN;WiSZtL+m5WwsTF&q*f+9>YyJl7aL?>Q=4T zsMVE>4F^^jiz12>Lv5aneDX+vC8R^Iw8Nc@eU^7UExyIX;^yHi58M3fnEuCie)E^t z`$4rQGO{Q@TGjX9I=$En)uL+4?M2+xClJan&}V4`)f2BIlU>MxO>|Pm8F(v!wV_|u z#$10`*V%z-{;FuRSYU>~l{6tqEyW0NYPh^FOWd(0Y_@OT3qspWE52;{D{8UWT2Di`-MWgJkn<-BN}NzM2nGE2qBhaeyr*)v!PUSbpUTh^%7oT zevpC%&`RKyPrcnciItC5eL9gRn&Tq}tK3DzCssTnO*mLI`C<^R z9>s?Jmbb^>M#bp8Xi%|P%!b2HEVuzK=%9gvLaL37=dK>@iS+gsYWed=1?DoscoX&8 zJhVu-@rq#5P-C^grgv9y`tFL^WkTChR-wcXRpq8$!rU`S3{qDz+R@`k65U%nd0WGI zP4D$DlBohl%{HGfU!Sbi*xT2|bOLf*e+?GT7trR77>2QWg4tT~cN8l43-8JD&5DGN zMbk<_wG0fOcc#E}Gjy!0iH5XUR?FBTSA`K}D`7vBZd-SnK0C+RDEN15rQHdnr*C~!lJ-Oy)B z`eT(4V&@G#z0D$HhR5Ei6f)VkVlK+l1I0ON#gF3RF`rv~zo6|@W}vwvHtP&CUoL`S zcG6qOVbkrCpY00Af_TVsLHYD%84)#!rHtLn`s#vvoIS-^3K90Md9~hsdeInIWhv(g z(i^^1-92fXbT;SDG_4Em1XWe>Mssc!zCkvc_XQ&6`E?$67Nq6|vXH))4P=w$UY4PRF4Q zAsGM&2*X~Y+z0CYO75}zt<;xc-S}g`w+T=1gq3x9$LF*@NVpPi>!x|sI#TJqcYwyvzy(XOe zAnwG;IOKo|L})Kw>c~foH`ZaHE!bA*f(#C}JL;2YZBPw%kSRV)H(-Jb#>(zE@HCrs z$3m`p%lc0|Qu>if$x6#+w~`Tyq>O6!I@=dZXg;d$N~8&#eJ!-D(_~A0ghE@DoD)#W2(v&?o~I*|rnM6*XfmvMso2&q z@iax_)&r{0GJD?0Sb5LXXS>PRFUVF{{OO>YI7jO{$`eFOp@6B72X6K0G8xE&^Fw-O zzH%MNWhXTjuzY0rhLXABm#486+~TO1qblZJhB`x*4pwTqACRXo0;|nUY94D= z6wj;;0jKn~=jbC&2;N}PSle9GO6SC!4VYaEnVNBG_Nhs^o5|B$ECm*C2D`$by}gmY zDdyZvNLCrKBZ)kuvEb!tChKq|_p&~tHEt;3Z`BL9FT5@fv2HEpm>9V4+uV~{H7;P6 z*{fo&(WAyIU`3u^c1mu8i4$JP*Wg~wC8E`vzvTgMKa04-1@<%De5m9l4QH5 zCEce?&i#8}Hu^+(@9VkQPGWOQ;p{~bPcjU6Gmhuzs;`*>6dPaP{J%%DGQf!fq71@v z(<{Kp;MN5buT2bPzeC8o4+nBJF)QLTKl`FgF2qj^rYe-RR_T+Ki zFuzJ~cQ5^7cHQiZ-4?}4hKJi&&!|ATZv}j=72+Wx$%P|2Org6Wf@@3*0}g$s4l#$UB0MFWA7m0o+X#Ke1@?l zKBP%G&Q__2!f2iCFjB7d!B^y-;l=)wy5Ctc|3GO-&E4fG39$*XjoD)es%21d7Crsm z>1OPNkEoC0V$I)2xOl}XQ74v%7Fy};hK5t&P50XnAC2;|AePXsuB8^bR*>lF-5ur}23Ww>7^T?e8Si*d!PD&_>Ie&bb+4SOUJ2PRCMOW{qra<>sH zkSB7sb~~C(d+FXLs8`rFxq+(@eP<8R)UVpNvv_UYWz!VD_X0YNk2uk^hpjQb-W?@l z3~fNyV8oXa`Wa&Z<--d}lq9-nYV4wF%Dc|ix|$Go)QS?wypb^0LM#e;!pj&h`T8_v zBXl|2HWzCG4Kp{l*JkDY&XyvqN2NoVHHyS_v$i_K7myYMZXTA@|JGvNmYSL{iS zQ}x3Yv*vx)6$=ZVPWes;^M+0cCRE*1zmB;CA(vb!(~E4*RRULL2IUDP9SSGk&gS&V)*3BH)4Ii=Ie1UoXUGW<4=Bpv)FuBEn2uLi zSPmFPCNte%Ey~~&FfC4qh+t~I^}G>k99IR=JQaa}*kN2+^2mc#Sex^V!~xGs4mbd_ zTQfX|(sQ4TDBgF@?+UQhnpo3V?mTlrmK$Ds^@l~e9FV2Af9ID5szmsY=)P?}aiXBU zoV|^X7L(WU=zU>d4dj$XXiP)zfyn-ZLrgQ7G(mfmy-71pFE^?aM0#5HV?DVz974M=zXx-W@dqQ=Evt>SSyG(USGhTB=e(ZrGYd1be=Pe>BUN?nhEG}vC0AV%UMihQ_J2ExTq(0%#JL1 zGFmvmB$sa&hqj1ne74~sr!{2Ie#2#Z$5t`8XXc2Z)GWHVS=v$^(;$o+4l2@}=#q%q z*FY{_XfnWTDcDyuttn&HA%(cudwr6m)Twf3HaWCGGI>+Eh7^xR=Rd{-pQEp$Zf%op ztejG~&Lz}8h4-UMBO7jXzs@aW((Z-0^S8$hxyf5FTtgm<(;rr-?`7-1a2`#T7tbi5 zj77B%6~ny&km7b9yIK7FEdqd9riH?Xm^VAxV#wD{iPcYz!}602Ne=NQxpIOxis7tP z4{W~WAADOt20jA?rj4^UJ@g)umI6!L8NKIyq~{Y1iTF(@GhfK>3{*-WOMw?uJ@MgF`*XIi%fnlEP%&w(>!3_4}HSBn>%g z*1Ye}t6}xM>zZZ^MHdiKLr#9#-bO_2wRaJ7rg?2aqnuD4QqZP>yA5uyHb|wnwXL+J zCM(B7^bOUm;ASE6fp-hdWl#eIG(2~A@742WSA=5^d}7N3ADvV+;;{*}?ljW#HmUyy zdLs{&umzHB^1TQ_S8&K?vMa%qdtr*KE52WGkqZBGwXC$MyQkHBx}KfN?b;j0PK$r0h=hqg2eFgtOpjWO4g((G z9wwB-OynUa&WIHBzI;W>S3(^zfJ_83rfd-uKlimf=ngy8-#S2FUfdYu0$|E@XCpIP zz;|{n{)g)LaLe&Ol2s1jCvsk$5}Q75Z-M4(MW%Oij>}R=C%l|-!j^?3^ zyk401vL_njQ%^r*8Lp&^moS+l8>Fqnvu*EHk)UU=o=JU&MlR`Yk#l_DmMV!S~R() zot^?VV{-f;$d+M*Jfv&S$UUvV8P|yjP4`-es68HP{0w=x1hkw_KX)2sX21x?`WqP4 zE3?Nual2r2w2+W8xD-NqQ_M`pi#)B@I1>A4VlLa4wVCiKF3-bF_~_m}*~ZqucZL`Z zfRN7x6vFFSyy6PE3|;ZSWPZb!qnkmYX1aE^SyvYy!d<JWTZokj{?U{3P8zz4?BX-3#mw^QNhjiS`C>xf+3u?0gXe~^4{a|H4I z^h}f28f6`s@&TiYna{n0Rupnshn{=o{n<7R{8`_tN}g3G4e;@0;sbhbnDCeMnHTWt zSOsg(kzTVuz%Z23{^~biIze}JR-fOW+8-YyWbmfbQPLdXfp$20DsQq!EmM*CKc2+A z`Y4!1Rsl=p^tZRqkohf;I6+p!D=(h=3qkqv-7=`zK9d9T6T`*lCJTbaALwJ#yZl~^ z>yk-Rul!yNIr$PRV4@-gMf)O7g)}cCq~Y-|Aw7ekymRB1vv^kOE3$%5qFn!w`*5Tx@XHPRp9$xwPj(Q=qT{U4uo|r3{3a_`t?ToDBjG;1k*_5Y2kN!8vWI z-E3TiiH#9McX=9chJsb$RN0~E1}JJ;lzp@*a|bRX(@NOZT_r<~YEXbwv5}vb{j+0z|ua$YCs4(OURyKfCth zT#QHev{uTUbte{-Gt9~u-Xce5#GRK zVz#vdl&O8AYzqj}XUTIkLTk=G##e;=KB%J)0xI~VYxofCM_d{#XQBl%=O`R6=*~$o z(}B!nRt>-oO~6%|qeeEWCfofiD!M>SjTppH(sABD81E@CU79zuTlF6Rv&c5%umOGz?!3N_|H2GUh%iyMQ7u6< zN*hy~sNd8)70&HOpl2TQ^44VCZZj8=-D^+^kQ1lEy)Um#jD}>9Y0K44&LLq-EEtJe z5a>Iq(dV*_U!>jR2fS9cLwduVKC)GQ7{!8JbzWu0z)3GLihPZ{%fpJ9lzUZ`sLNoC zi(Q!Ddcs(ZRU)A#2I3d^(ecgmKo4F%h+mD~2LG9Z7BaQiSN3KF`Z+u{MO!;@=P% zg#=y4LQ}_zN%U?D@Z&wGdV=|yxpfEu3yY5dXV%cs7RFZ&55g_&KvJ|lD5n9sSHoKO zGlEbcsn^kh@L;s!Q>SW`fwvhCDS|2YT!n{?kT5x3jD)`Z?{k-0U}ig%Yw^wc&aFbD z&tL0p%ZgT8OOA~RZfoFP4)=EVELZL<%6|efQxl&g=iZeaup0crMZ*!aL9^b#GJZzy z0QXc)`R0XIe)W*8cQNNOkfeSU%{Fs=qDLq$z0XcX8ji^Lr*pb7rF$wSNx7xlRrfd_ z5YwYHFkhDE&)vwciI|C_axLW{*`m8uQbqU!kX2}JSO2{`#}h3GJH4we(q$XdCMJBR z&uYYMTSZ9-cp|$lXr?D*GQu`hT{|!D*vjw<9~*bmRt_ymeng!5Bl_feK+i-fv}H>- zRx;>gzC%3s{%C85qk7o(I1`aO3aw*wWscB7U*%~1>V_gjQfM_O5eFhBgn#GECzVsP21Op+j1E6tFqu-&l2eU^9k$i1eSP8Puu zsy43Hg{jje%vfn)Qe$b`uzmg~(iO99eRIvCL8HrOy)fmY;#mS)m{0laRzw?1{M)!q zZBdJfn|cMhI%G5P)dn*?)QqshtGi(UWI43o4Rm|&G4DD#O=wFz+WH1qI%46-y(&l7 zvyR9w=O*Dkq3ah`GpfJ%x}K~l@fwIE`9SZ$%G=i>Rx563Im=Oo1}WA5tq63#;Ujt* zBQI~1n=*3PF@P7E?un~d(3dH8s03J*Cj~O6wox_iew>0t!VDwBYTO3Pnx+b zng7YrQ|T^Zs@L*u6)x(~57&rWXbP&8B7d2C-&axt87fF)uqFx zjBB(2ZJ$$G7L48y6Z>!*B`n9o{g7k6^Ntqmq-{ud{eXy~nr^b^n4lM~8^b{doqv<5 z@m00UAzN(ff5~&%5eVC8Hx#3@-2$2eNrKG_b>5zc;^;4bdu;H_{vQDVA1MG3%;oW* zx-x1&$SZUubx2nLrD{0BFY)4au)j!pi`$u6)$G|^O7Bhv_F5$A z*Js~R4W7vB<-UDzU@sqlBb`!^n-xXqqyOS-sitrD!sCYOI*Hc;anF0pr~d|P>jEdt zy?GN%HgaR1sEDo@F)^0kH;kLfhI=0dcnePJJ%2Q8LWGa@+7gc^H`wDC>n9~v{bJQ! z?Cc4Xfcn|dZIo8@rHl&Na-MAr0W+sOO>%i{4xgSkg6Ww&yz;$d+$287{+aiqH{P3~ zDloxKv6Dk^SVgnK4zS@{Y`4k4Yv=!_r(9d;PtspAb#yztP!f;TOi|KovYBLT``poRg8D*zwb8r6vQ4e z{I$!dtyqN8h|_Xo0wGn*DVeL(jG6w+KX4nlcmTcfVP&jHWbHkWxv8>?e4XwfKRmo7 zpCJ|{Cd|LvDkkoll7pkJu5 zXqP6WXX6da_V!&Jan_2oLu_Wig@ZG*Q@XnGvO%3&sB>SLF;;Mx3}2cL?BRdq2DhIO zP>^t63+tmwNhAVsX;L*v>1k1CMXlM}IR&h!n2En_p0T8DZY?9oYoOzVSsVmne_d>! z!w(zQz{i$3(?e5874QI*N8xM67^-rf=4=Myj|g`NQ;8qWT9CpMRr zlC#{eHj1hxtit z;6baoXE}q^Ls%P08{BFEH?)cPGyr$i#O+HN_w&Ze(_@+E3!Fh zysc~3o5f|`2{}#-chkTxw}Oq$2Ep%cP4~rI=efas^y9Fy8vr@r#mhx$^anFs;`^KN zA0Md^`JtGulBP|AL=&6aYFXBIK)Ijdn(gAR?mjF$kgJ;ciq`&G@y-Xf(7XG}>Xhdi z3m%yx(LI9d!Wx6TDVI{UtsF#)*Y=cuLe2;S#gTs6^m3AM^rT&zQBhdNCeiv!4sGDP zSz#Q7H8D1J;rMPEyzhhFQ43&aDgg)PuNCaJF`u^5(-nmeHFDi0Px63TT%+Xznv*3g zuehLD;o50qE_wc&uZY&R`~SN|X6yj&v*1E(wKDrZ#w+HxQuX%$ADq$Hnt8a zy(uAgbMyCYpo?G`V47t-yt^n`#-G)g9`^#w6htB&-n_ta|b9o*WOrkW)%>oK@&pfI~2UkIwLXA**CNb2QInJ ze|ZX}^Lw+Aj2hUt?fVWvWlA>z@i2`PQ8SeI_#`!MkCH1cvdGh?!psK3k!!lYpQa5G zd`rv-Z%!pzI@*0TvPXl?v~B&VxfWS!*|yW~JhTFop5#(MEnkLP;4g`3@uI=a|G20< z3IZ)AE&m7YR2CUw;Dx7R8^G0JGXA=I<-a3#S=^q#{5GQ$RCnrF^G13MCzu~A8H(XH z_8FTNrrV7fdEs8pPiv=%|CHayh7APZ*YNS}eXH4`cSZ+Bj9y@YM%$xp;MoiOpDX%r z=cmr68cjGo45B7r5gA4cpLh}(T}KtpGSaJPS{Di5_qctZk~!BazsfS)-^YTKk4KST={sL!i4FYeKcBdtBRy zl(fygvFE>K`v0fOa&19%7~>qOPylj9>#whi`_A_GTaW*dq9SMu97?D=NHtmAVbCM%6HrN-Fqzl`yL*%*x0WQ zz#G4dVkLgNsK(v%i>f)%S~(MAOZH_Q03z7FuN@k}It)&U5hEy?x^JX-Goa+D;@i;>b)YUT9X1SV&$0+zmxeA{8 z7aL;fPJUiO;k(?y{!!ZM%3-HD;$ldUeW?2Vqyw8r6mP`gavBq=5y>087}NgGJx{!9 zuQP}0H!p8*9;Dt>-}3`>y7-k9u&jV=9~S6*{rwxV6KKgVReHHO9qM#2KerU3&B1uu zXV`rv7HnFGwOecq#jrj;VZ0%4SkS9<$A)5;RR#>$0Xh!}WsS%08Spb-oDi`L`FgOv}@+eCa(4b|Ch2F)>Htl-`~HDnZp z)jB^?md+a*Bx2~=9mV;r8HnDRPe8>}(KuDdmDi|GhU@aFiXL$rLA~rx=zdyLQ{oaxP~=n6jFQN& zXe7*eWhQP}GBqbN!VIpzm{*V|#w7+39cJHPSg3=sQjR^NW=?32{bXs=O+HS#9 zEzbn@fvd#QWLes_yQx)Fqc^FEbC87Xv;^0X^2JtoMKmteF4bYdQ_iE-s|bhFP%XOv z6x-L`QbFZ=-}X(DAviOV_W>WWHvQefu;ud`RVJ%~{^7y=ZNitZq; zu!tn;(R89Y5UnxeF2WrNjbPxe`Xh4`VGEukmX&(KPs}sMLjk!8>J6JWbZV5CdjkRe zO4M51+kA2ye+q5muJ9oN3*{a=GFn!6KLxiX&9idMJ`&5ZUu@yN@CPSz#+4yr6`6s1+ee6(T37h@ZQTyZ;zS?!cg{4weD7&XO~LA$ zRFtRdaO|g?eM4_Pwx%Pt7~z#VznmH(I;=EqjQ|O~H)*!nH?c9XWj^-(jIc}g8yNNz zwCn$}%Dy{a|Fy2aua-}z91Jo5((Bz6RQ0W_!QJwuuMyMRV_*S-n74jzCX5uV55uJ^ z{LRzJCr6B0BW-eF-8CWENbO~5l=pD6q7B>LIsJk4+`#bIJhEZiTPIcK5=+K}!%HLk zYtAdt)WJ42t<2GNg=g@R#2L?TpY$K4y9I5VfGgO7I#cD?f(MnPx`&c{|Fe$mkjy=! z)AHN`Fs5QV!}L3Nu_i3Se!=~i-T+GUPK3N6bm?9w)Nf;{7Pse~APfKSzW1{Ij9eico^@_SfC-jxF(o>F62%Mh|6{w5b0fdS#spP#p8!s7dJZkUn6z1@{34qA9k7q6Tz%%iR-!|tkuB8!1HCjdBgPff z#4DQnsnoiHf_o%JPGbm0&w>TJ+&Xd8k6233;->CFxG{kAcUm|lOLoQ*vM-Z;9YYQ(TN{cjCHuaPbts_{W8Vf7V(dG^*zRlkoX_`nbV|+r zz3<24{^R~<^oY6M*ZXz7_UrX}zT_dEw`r3J;b88|-bJUslWl)%BMoxv3nLR@*=C^i zL?pz^L3NH7VgJ$32G0|1FY>IC>G{f<7KM^pDdEoWxtxA+S3X_aQ?{jQCzaD45MO?|DZ-?= zNV)%9#*ERmi(=Y-*(?*R_h!UZCE@~kJ15=RRgmeM%ka!yI#>={5+{un&3SK)gB)s4 zDb;Ya7whbzZ5LwruM-2kYD-3)ovaiuz0Kp%@VEAuI$~K%c-KH1&Z$$ge#OQ|I8~iW zmXCJd}2u)wwPN&d%w6Denh;gDl?3 zaG?!Xy{XbMt|5?^=nOH~om1AY%n2+@4YE=EgF_W$8lU38&2Ru(jMb@CPV&l(G zM80bSiEY05pmVfxU{hZ&NbF3nbfRRDZyamLomnzm(|CiWJ3WbmqEC#+p`F}GM!d~_!@s@lYN-Ip5J*ZX=cY8m9AtPK!%n%O0RHoid|NPPyE zThET!5)KzaoFDKdy!xjBl}*^^rx_4AxuUI|(a@`zS(rHar^|NwA($lLuy>q4r%Cnxv!EJaVc5H2aQ%H6sKMvi2M6W;48R*c?0FGNBTX#F zKBMi|#1j;+A~E}9bvy}4Gb-pW4KC0Vo-*znuGtwa3ric-WX`}ER2d=~mtTw$mI=~% zpZ2C{!|ECL=gIxUh8iYo?nX>><}H79$XkBn zP}`vtBgU63CBbL!c~@^^^pk{X)4j7&hAu+;;LX{XY!Hxp)9q=NlD;9a`tJAHoryAje zpcY_=u-BRFoiemvAtC29&adg*lBB8_ZkM1ba~q@}Cg)C~X2Cr~P?(4Dp_5;#bX}7X zikrQ#oRESo?|$)$V4)a2h-c%*OQjtLIq6@0JKzbOMKKe-!}{&iVgEtJ zVtj*wsxUGTiyZ--z9xi-!djk)t`s_fK4cI7O9Q>k0G8g)I%cOG-LcY+cO$Cw+%0hR zljCpUPMBAy=ckzEPZii+nJ6DJ#p#Qtnr4T-1(k<^`C_{-veRW}3Iiduo=+r^$s14` z11I=1T~sX$%PM$i*2j8?_xo}z$SJUJ1HG{H_oDKz4gR0CZ`T0CJHrO_;%Z_%0~@?1 zSnbH#8-|gl9^(uGWc=tu1w7M3YHb)QUJYdJi=zYp0^0xQf zXKd6ZS6zQf*{HKN`a68P@4dsF>sJR7TYL|oUEFOH`|j2~;0i5t_JA_qU3fvgj+R-T z&RZ{z5t?Gk3IjCz4wnOQN;uZ+^7+&Lmb43;v>R|3!XeOIk337Xi>+iw4~3T^NqB16zC231=A>@REV=~ ze%)@ZPT#L@`y5c*X04PJv9vgp2y=J1P~fws9aS&JFrf3P+l-nMVi1|>utQt_Xk-5% zI8*XB*~$KYM|LRCi{Qp9%#>!pRMlb&T)NlRHgqC|?g>!=XLebC@G!?hTr^hTfG=?OCRiABWFS zBsw+7;jGY2!7;2a>8nZ?nx2E2&%CO25SL0XXYoBSrR@=rzFP`h*$)ug{%xrpzsvym|KL>U{g+*e9SLiKC_PpBGt?>vok*b zg$}O+I^1B$X_nQeN!`U&zGAToaRgM_+o@Ve-;T-}u4nU5|9Z-~D2w*AB`6DO%ikrA z`uCH@h^cy`XZyQxZ@QS7IY4h-Q32q=!bRQ(`s8IHkr^`agw80zzY?mJgKU7~Wn@t2 z?0+d4IHVUD{~|@Vwg3k&Y9m!hrpX~%B9)4!g0ir9TVZgZDtqXx5hz{)l@;g#FVOiG?fHmyF}VN#K|2x^u)B zUq%00j9*YtAj;1tA<=8P`fBz>w`|jnpyOWx_}%U-Zvb&f_U1kU@&sNN!H3g#$%22W z${kL^Z6a``eJcmBnYk3~5UGnI7Q6Va|5~e)h|GEpuJ*rsxKKq=(%>iHYlzsw&NEGS zZP=>9u0cFi#i)0?%K6@SS&9=W;q?bo7x_V1m_8cQzr(%#j&9!zL#GDdBPH@!Fryco z=X)GU2It+$5dvKs8$~h7>>R(BD@? z*$A-8=3?s(Jg?m~>8ad2ptoRCuxfD>f^4jg;$lV7S$S$UdiFr1yiG%MoqzETUiqHj z-;vP&kLJ#SBZ^T)wL@kNpuB1QRA`xN;1OR#i6(PhA|43k^Z7)Dy63lQw5M`OIanR4 zJycQL;iXgzIRP*BTTp^dPzS+J5MVyJ?mn#x3p>KDN0B^vqss5T^!>U0(v2O7^(8 zg4;Yz-P>uvAApU9$Q|qM-rEdSVidU_9Y~4_%Pg&aDuBycJ9Rb;n7T9BueAA2L4ZF+ zKwhQ&eWiNa4!G}88B%w;@ZLoQeHTIuf%6KY+!wP^dB5-T`Vj+AJT_Ct0{l?OIJizJ zO9k-EZN{JMLfD$E!Jtk$0U?6wx@Ydb5hlvbKlA9KmPh(Y(zK<3>06s zj~l)3jEJsNEb&14^x?q3huNxOfF7%`ZeVbHFU zppwPMWR@x)_NDi=&lYLzAYlzKoDH=Xd=Mg~%ZSV{&iCTr&!6}`LHvlQGx*>PY%F=g zx>Bb;#{nWUbTN%v|Na`lBspSN-edr^aRZ zGREIu1MqX78~D)2wkj}ybL8DTE3mWnV%I}$<^vS;aab-dfH+rujGo*_WT#P2b_434 zQ|_OvM5Gl_CMCc}Hf%hR3Y=rq))O$G<+r~-Mg%~vDk1diLdvjr8eQ%Y*~zK$@sBLM z>^Awiu#?AQlupnM*M;0C8ofDV9^yS6w~bA34^?Cxs7o{HyjR=O(}T~02GTs}FYd1p zeU+HVPDIY>h$FU1n(Ejnw#;r>p_A7z+Fr^gLOr2JR%c>dPy33@tHJhKLC>-ryf z>3Q3}?XRB)Bsy67JzGnQrg%}ozE|;N{aj2K7nFSRtcpSI?QG3c`3th#|ykB zid#`fE(pRwHW$Qur}HYZ*m+SSewMSAH*H{-Jg+hrchPXgVlZJAINpagGw=!|Z`hBV z&gM6O^G2k>b;B}%mka=zK*O#)B|=F)>Cu9d+j*K1%BHA+mAfkaTD>AJ z4NB_wy$VdWuYfnwrc`l*fil_RV_}B*wjOw1E<1Ew)p>ikd)R)em@%HJ|49lAAsLGJ^wl$=aRr(yWdx zFKjl%nCHrC_C|+!CEEA-D`D11)~KL2UzU;$-i~Leb&Tm|q%p=)h?&gBn%tzc!nyWL z)7Ed)HauJ=5Z@xjobNug(fUtEcTM1quGSMkf#TqW}=gh zcu=xa`P$o*GeOB-U^+F=`1Z8?kqpc{Z%0=}{}zp+0xUk0U=hV{a%4_%iV(SIeT z4K_St-BN1pY+o5r;P&U~@k%uvab!?3I;@=4t4wEhJO<*d!nyJTN$Y}KWkC8#a%JhIPH(3n2HOQBm|ErS2utux|K5*ij7LVdW1G@L*`-<$ zslyGu5}qt8kB+?=5F}4?Dj#Z6Fl~BwmTMV(dYn13X*wUn7Pb}~mDQe729S6;jj#XP zHryTtsO-FWFb;_@+pFJ=&#l{w=Yu;;8A4zXqW20cbsTqOe)9c0c;JfV?yRCvB zT-$E2NBlwlMEhlV&uWVUxK^XDpYgVpmz0Dn=M38mczBm(-w>6c$cK5|k-xHi5CD4- z`&Oo6#1IbpaJ(sXeL1Y1A|X+r714&&ENoE!QYM41d}utiqrT$5Jjy~e0Kt5}w1Bc7 z_tZe455FwXKy4Ybt^^5wUiq52=Ab~y#s^ipHWukT@OXWOxkfK2*}5@Uy<@aacHxoW zl;X+@#>7Bm-MzC7Ljc;${&~u}JpX_X`og^)JC<077A3rbm!1|z8q_-5iNvVd4s3i; z=jS0W_OhWS8ygT$HjV0k{0_5uz$eFCH0VeEx()@=7`*;9@pB{h1r{ArdIfr2Yewlz zmp&L5>4J)UfQ(bob$F>WCM8K-Wd2oCl^h5^Fh`oV--9le@*V}-R7#fOUvpk@H7c_@MJZD~?1&v%0 zd7cyN8kFjMio-uFEXu6AoVftFDQWK}_zCLIMEf3l-S2VjKLrv4OTw~2+R)Y-4 zp!sJYgYYt>@k7&PQz;=Yxjy&p!j8Daog*dw_Q57|h;2PWM`C-g0Xb8|^lFzy=dlOX4|>g(v~CT!76N02ZFSGcDBO4_RUG`lR6SR`h{*Yl zLK9c;eZ1#F(q_Cwr=gt~jaq)Pv5uqTKZuoX`-5>!9`rnk?i(&KT1P({nU7;)LE@O!+ z7%_l$6*@A_;!qnKewA~k;*)S@(pkeo+{%%(ROjr`ml@*tPCeisvf}|Xn$5|h4H)sE zG~hdyH*y?HS#p-jU<6=unwM67P{;D^Hn9Po{Tn*o+t6z=pFdK2lRdDg?u|pDDUOGu_W9$Qhj8M(B4SCkUo2d}qc8O}+RRPz z=%RX6M^Ph3$OF)mlRUNp;0A^xgOc%{H{kB2y?Hstlh)e={!w1Nqv3CIS0;L&e4YQ? zcP(RbRP?_-^gkUFC4i)0FmvU|?|3AHFAEcaMgyI<{)%Vd$=dfOW3xVt8KCo3n&ydF z3=WkHHPxpFc^c51JUagbo?MqYnAI}SbCLnOB>VMYQ)SWLGO{nrsj9(V#dxwdgBGe? z53o_R0m96hEv1Z+)9mp76Z_=hus@2i73Mt`&PK;0_PFng&E!}}eOw$Jt+bFpBrnV; zt)3NQPcLCtYL&PBxB5h-JGwl=*$Q27?KgMK^T3%BJ7y~5%m230=LzWOD$(q+a+vYt zg!i6i&4Y?R5+@=yd?^})R=?6XN6Cre(319K@qT9{xXKp_OrAd55Sfy*qEqOsTbOdV z@P~=T|CCAfah&_5_50@;|1-oUCI0)_8bk%g0zQ7>!~Waz_|O0R|7js29sa+R783aY zzz*jdOu|js?q65O(Vr4vV`g)Ul@W^k%+dl&Fqiq3x$D8+>iR*@@RMT}7A9tk;#c=G z__7K)TxZ^TFlpNTe1zJufq^DivFffYcbrtd@iqZ~>{ zD~5Ocmfd{jV~3U$n(_H=LYX>9r+LERZU!PhQqcbt-v3#=TlHI@knju9_?1djW&;LV!9slq%1j$9Ow*D|iW_up&l%7NGz-6Vo1@}AzBr*v_NxPi{OgY$Y{r{9Z5heN9%A3*C7Qm!-zik% zOj1pY?;gdd;@Z#T!Ta4;dZm=W4VJq~pMzn=+!c}9=FYI9i_ohInC6lNoAvsspcolY zW>Gm50btrRLQa-$Y0MfrjCAhgoZYmL-?HxQ!67q#w_Byxd??x!Af6Y6yiVAxc8@r$ z*5`yjrt6wfe9R?hvk#p->j13o%gUS+HRZQ!1vu6I+Vdi2%Mcht};-#HX)In$O`IH4{U80IAI+e zHO<(n<9jqNa~`bhQr)K!?R-^E_3*wUWO7$k^Vm}>x(|~tYra19`nHGW;kWmkRgaO4 zlZ{KgLO%LS8WLw2}0rx|?T;3f_kzH0;I_X@ER+|HK; zQXv-);_JpjQ#$VcmE&G%c`%@Ppq14lNL-f?j+N1eQv3^Z{- zqHFpuL?%5W{P)Sa- z9ce`n=hy`5-&fBE4v(<|+bX2@p?}-LJ4DB;^Jt|C+(bjtq2H5#v(z}ii@oc`@tCQ_ zn;`>tdXL&klr_KbF_)C#wkHg@vbZ2W&m5HH6Y$*o+a3Zq6wf3gVIrq1Wy-_|w7NQ- z>))tih%)}VXcomD72Lg1eK2p(5FLTF#AOz2a(gEt^qpGmr~;6gNXOTEy~Yoz%A@^W#!v1SGc>6Yb7mpY+?BHVBQFc0HYW@OZM(c6eq; z(O^2o%vk*@eT8yFiuwVsiN78POBe(y>}hT|jBVcScCN@A ziNUNcB158Pp{4!n<8>3TSY`}-=q(Lq>8gx?(FsP8xIB2!aQkF3#JTcKC`o6@1kO?_ zH!Q7p(Z>SYZLG4rQKvj#*Z!8J_~a!|`-*i5q)T^l3ZZmj(d+6fPUoP+jxF$%>Cn(0 zWLbWyv&Iy^JtewhUqa4yuQI=dUOm~^arws3O66HmNWc0fxG1fDH~IVS9gwPo8RD9< zhDreS!N~S_j^xGUniegL^$pwYGzxLsHsYdgAEwTcAk)6G{y?a~PBiFzee8zrm$>u^ zKSm>^Zu2taEk?~eh!B3+;_5Gwv!Wpb=CNKX|3Q}brzAMlobZhX7Xc00F4AQ~MOZ5x zYtCM2F7>uWZL8FA^^gDjo{T&!@0_{dY|E3q>%xFFFG|}W8w(G$- z-yyCLNyjYRycVyx;1(v8$@ZIN7=U(>QX=%D1n*BbZh08EW2}1jrIbs#0&|4QgFG|r zME=Wkb`)v(_)!Vo?0hqq#)UQSSH`_KXte1UUIi_Df))uJPqwG>GI)!iNUJ6JHq(N= z=juMVm|y#PMon`}zE_W4_}ZPGFXL$HU) ztiOM`u{c?jhcS1_X82>935HUA`rgLkA(WRCpO5FQoM5yU;k?L7w?puatrcf<|J3Xz zZlJl5)pKQ@OS;km?b>~%vO^M5IZbg!#NCp%QA>oR_iRu*CFADGU9t`X6L@s?fvQUl zFL4OVnm4C&>~ua{(P;^5l4HqOr04Rqg_K#+vI(!q^^z-(Qn8^>$9#D;YC`>or9 z!Qt`^ZEjSuUGKbO!ey9k>;=;34cyAm470jIGi%HAu|C2Ct6$Yx(?Ij1h=$}Wa{%$xJGd7YMq_!_M?ZE-xo>$#3w$AKkxh&YpAJenb}2?u?h zR4V3ZW6QW#qz@H6Zb^#1C#s=Ej)CKAQLMqqKAUHvY&bt(ic*vti|hA9)i11#)Uis~ z-|8*eC@U~LqZ$lxj`VGskl~}e48%GyDb486!1$cu8I$Orp4E?3mEFP5mD8^+KjptF z<+brNHTzJVDC{t>0Gsp3?{RI88&FQ{C-3ZXek@Ik6v>7PeBb1x*CKZ}#It`zTJ;rx0ghYiTN(6rT7!&AP2JSeWXef%)clLffQKtbE_-fY0@> z(YR~suLw@`zD>l^0D7pMr-5W!U$<#J&y6x()MzThK_a84%P>fXh-Ao$@adn}>>RkX z-#%A~ua#euBz|90>8EQ%%beIG;KTK_5z4)Lno*_TVuIDT$)q`r(OJ>SNsv$fu>SxG zvBZ>jBgn~-lvWkl1pa-|78Q((TV7`LKCFk8HVKuw%VNm$Z!-5dn{u}<2nR=#C(zwt z(o8V@@IlA8d~cM9`K;piO7!P^e0VHkk5ioy{e0b0nI=N{Pfl4p7**l(G#fz0>X4V6 z)$}twQOZAAPYLs|*febYlO$$}rGLKIT*WRkGJb6kmrT$=C_e>|)k|tTMzrmMkl6E3 zO}{3K`o>18g2PMq#*m%#{O(U#qWElKB)!1dJx=i@Qqe~4qEs@p_kA`A3cOLZPYMtL zcOAvE2emK*1zjh+rb@i2aXFKWRPBo$Y&`WRMT|&P@E9tJ5rlqAF_ECl(yVo2$o=Ig#o>1;vEGeZ1tT`A? zvp)unyeds47sV-;lYc8ScOn-Wb>M8@S3+7HoJVS?H(@GYn9FfOMk1NzBD7l4hv1?~xyqNC) zOPB7#Hn;Pt-;F;t88F>`urb+|Kj);iyw>;$9n2|>o1phm7EmMeoG%l#zLEfNbp%~0 zPLD;72JqkYw=aVvrFr!@k)m1d093 z3BXw*BQ34$!$!f&ukc&`c}O3h#c$cqvwlCfYZqSs*RKSVt1B$nLe|g&4E(d9+#7v- zgrszIk91f2v4+xS2CQQma2>Bw5@(dgb_IROgiLlk-Wj=G`?E6k3J?l;gwRP4Cd9 zCaY_WH$Io@)jy7UiO5p;94h6i@AJ{vV4P=9!yk~?yLtf$RP{X`4KZ?K8VAJ#5}^4L z%@>&a1uZR?n2O|qzOi0nDpM1rK1p9n#&tD&+jrodZQRfH@&k78E2I3%z2FAWnQ#nElQc1rOG zZXo0+PVJG{dejOSYND<+Ee0^h#*I#|zFe`=3VvN5OvAv^WtM&1zuoiB@dU1FFUML9)pK7$}WU!PwsC@Q+-tamjkVY1{-$US#fot0G z15=Vr@DtgX(?k0+mh_`-Yvp2`axB|o)yc+Y#)PU1D$hasAzH~lRi{5n`KWqaJ{PchC7h}c2}Xz z8N?KShhqmKe^2wWhzMzFXdMK+)0mQ{VE5~Xc7M=!v}C*v_WW2YkqmbR((fB=a)T80 zGNJ=oal{Natidd(GRCuZBt3cJEXaNHjT?%G0T4O^(Kb>v$kHuv#?ocEQp`#44(fm)vC7k*=g&kXkho~kdhbmNwHuJ2t!JTfOA+oxHkNeM>ifli zBuM}BH>wJN+TteoIsjhnHJtuJ;3u^CmwhJYj%JB@p8lfg$0ASwhwhECof)w(L%!Vg zf&cU5zyAT^-v@IJ_7Av(;+6hmMqh4NH%8^T?rjGS1sD{>T?AE>B1Mf^pH@BaM;HGA zkU0+4oVo(<1faN_t1p>^&pDcQhWCBYWEXMQVSBQ~Ns2h2*dN79a4ocPT=V(V_BdWB zY0hMs@-pa(h@DM62UA;wIA_c`wGlAa+N_y6zDhaY*u`P{*RNEW{35l_U2SL^ri$%i z2RA1MF)mXAm7Ri+e({Zp9@Z8?$7Si^(Q71e#Z%darKrS_7AC43{Ye1xvb3;d<}zqt z0~$D3e6-d|sknxZkRV#JrU%)YSza}b$y(sNf&T!t?;ab&M^-Y;R4S3=v?eU> zX{6m`UnoeXXZ<{4O{bZyloN~<`j#+yk{z5QHgRo_&_P*-3>k~{Wa{GJ3O{y{g|!T>5dix1!>q?ltzJmnalTKEwof?w3v~ z_O53jvz4|7FawT!+ODPp_|pL4G@r70FEH~M4r3H4>`OyF3OYxUK^-Cor2q7@n4%-8 zR*>va8lMAFI<{1A3U-F|j^?3OZh)&7Gz>6O^;Xm79vkTCw*%*&}3ZmtQ++rY- zC5P@L0|X)+e*LPP#`jwACo0o#1nk07Om9lwTa#=|UjMigDLs9H*}$p{XE!?X3y_VC zn7pVYiK6wyt%s;77!W6SJdCy=N%?^4)un~<73%rXJS? z=vC12HCpD$MFMxqW)W}d&SqfK!OsknR+5y`7bSp48~^SSXe2O9-q=ry1z#feJsTqL zz-`{`X@=WKRg%yZC7aL*-nfXq6A=V{vMiL4bR(jA8u(gdLxm{t-Q{KB-B1C)XV(NI zvC(qn_|(WEgYV1;l_h}`@f8PO?mFN-qGS}@NE>~Ey)#-f@ksilYaLb1&|^iBkdNV6 z8vT1+?9W0BEbi8j;%$4D5-%$0@8Z?#_!j4!<~!655RwIox#EP|4IyQ(B5UrD!i?0Q zlhq*ctmk&ANP8+S+r_Ik1wYm6FXVFrQdU=8M$#$sgHvYY0kAMGxqF&B#H>guFgTS< zR4MXCm(3uAUOKnnQF5h#76P^9130>()b?wJbd^G(OJ(LQ5oHbEnf-AJBpD4xdE(lN zw@&&hli?x*g7-8lZ9+||3Sit!V&u;-Wrm%pOdNZf`>Pkvf6oQq%ilj;J=q#i7u;oe z0mzcS9cp-Jf>Eo76XehJlHsWTSdR!5Yf^mdQ_W070WG`{K{jTi(wCLFX9;C7pf9}8 zVbq;Yushep3G8NKKEg4RVx;`KnLgbmq*O$Oq8>i1`LCUN-sYxRthVB^wF+ zm0$r%0lhlaVX?$%h<`jEB}M;?=o4+@HY9R+5`1%Sw5eq*Sr! zU6VsbURt5@so9tpXxiW)KFq~rX|en=iitj;B$~bik^%;?yo$6tK0ibXnFaxwYznW=%HRVTm-~wBb5@t)47_sdR1V5^ozTIP zLN)1gM4lwiIwXtawte`aN=%3Mbs9pk=K~K_{<@t$pG|ux9od-u7msHo_&c%*#^0p+ z7?5hB9y@lqxySv&Mg_Jk{c(bG5aDH4W z!ybwb1eUv9cqhEH3iP6DqQs|W6)5B6RpiLcHO`6_@}z*W!IyZ_KPr+aAXNl#CLTkTc@@hZ#}Rc=iwx{Y_w$C@GiMz<$ZryyUOCd zWL_!loFI_OJ!{8IiZ;apUa)U=>6^`DN*r&Tb5^7`K}}G3369+?7vTYU%C+UCws^1Y zFn;F%za)Ev!?FRt-O9_>(!C@+q&lBC_p_6$xd}{fnXcv@ag>hdEBtfaThZxI-^hm~ z$(C|^TDD7~od#xCGf}N`Q`p=SQr>^wj1l56^t3at*yzo4w_jKSb4To>j3#7c2v;*D zO=?>gz2X-T0n&;L%)4{SPU{{C2DL3+GW7j4xDGBWJ+K0>u;eYC01OXR%n&Xy=ingf*kza>pXr<^7l_RfK@q1Nj-;G|w zHn%G1w!e-e8_Tl^eLy=^cujJC=vj&R#xTFz);sHzw0^aHow{as^yjmZg0?MC{33?2 zTb?)L<~@t!S!ksNE^N(X4?fPu5F)G1ZE~0?W(qwd2^(KaW@b1x1_+%Co=m?*?}k`n z7L9xDd0v}I!QI4Q3HgzpYTiC!Lnmi_kBM7J*Vif|&j04|G%ErX&va+- zzapvGXkJ%PGn~w33)RHP!~THuuTWC6cFUj~y5k(?c%g;;33S>y6^nVI%kL1ilTJ9k zx4V6uUyoj} zR)}M!a~x;AM*O=nu5cZGAFm+_cFpVAeWRbDhqqT}|8iei(;iMrE1-Pae(Q?%{SF1% z;LxrUEVKRgPftkSxjSMy-@-$j zNji4zxgU6W@|5DGM3g^XZWig2ad_a>Fm##V>f=6zN_sWxvrsF#!VwkOw7wvxU6nL4 zj_-`>!j}JD5R*$xo#$N(XP$QJ3YnQyE5gRG?JK#&70w5Z|F^a_*P+S4o#gWKigwI zEIO&a9x>|HHO%+^mJGpZyn>I-c^P`63i&iYeUf6T#6xoB-PhIe5v0g_y_J!o1^eH# z7wrHnt}F<+ni3QM4RdC>gLayp4Pz6NA3PlIep;C@Qp9gXn984IiG9P_EF(H9HQ$sa za^A+32(OUFu$3{TH~AE>da!Bo!CLO%-&)1nvDMEM7%a^q zOIkNFdhmF^%o}(h;KyQkpH@Pg;WbMQcOFy!W-8Gy2}D4Aa8MGLFYO&1|4Hb_+sysNf zy}63Y+op+$TwZ$-Z*XM03}(_(G<3ZZqzfI^7f?v>N;Y{To*8v)DqDAT4-kqK;zCV* zysh#+Ug{x&rSLtaMJN0oi3Oj1(}eXiMwJrsnGyx*J)hnGW8E{XF=L_o5*TutJ>q39 zx?&wSTLYquVvbXo9d}DmOKJlRkCq-bMD_#+4~sP0W-*TntkrJ z${RVYQkN@a?k1WDioZiCwksTNdU$IDO?x&dfr+GCML-Vb(X%XcN@=!>F&K^}0<>?V zS)jI!cNS@gC@T5-tmac3Vphb5L8Wp*ucyel^%g*IQdiHc>Pqmw8>Vx_O<+k_Ye_HZExR<7nt7Y+-@!Qge#86;(ai6c`eb2RM?hJ?Ajrvi}aDGq@{YAZPa$! zbMeX0v&nsQ*w(qz{wC8A3Xz1F&$B#I&pI8#vqbJ^bwYX8v$aDs6{tfaGdbaUHQEA` zUL2@nB2ue2xplhr850xzmoUAe>$3_DUZw*Z?t}=d+O~Hvi}0+@a3rim-nfEnbG^PG zN13b8V+rW@Vug6FBA4IGlvXbQgwFoklLJ6LYfct%+fK~+z{)Q`DlKbK?q8JW)9}-( zdMGe9F&ytby?rL0&tRhSZ4y@WjIfbKgc@5_v3Oeiot-!wT|IOZy)HJ@F%0F~VKAQoRQGaGxD2gciNfk!BK zuWU;2PPepfUa4|(_@g|o*AwK`M+@*6k+6brY>r^j$sBa3fr_}yDBsyBLKFAJ^~M@J z_g`&_v`B|Xgtaa>-Ea_MO{GGxXqs~sW0$X`KR0rv*S&07ahSLAY*Ur1H%0_op%)Ij zusMo)4p)?bp_JdqoEo!K92}g?zqlHpTfMQBVst@h`T;C0-`cgP3d!FyyQ$c-(YDA% zGqZ|(ba|>P1R?3;*pmgOtM;{SV8l~5q}6>1xwA%U2c!|>39-YzZnmshTl9Ax@Y;LM zjT4=dYm{M_-BSqvJz^bc-~&aWU0~0Vpk=G@SkwkO$aIogi!V!2h^$F%n3E>V9oIP@ z${nKD$BHn%!8|uj^)Mv~ZUzxA5_8694b4dv^A_p$%6)=t4@FB1zvQwHAI-dB3&qSp zv)N+7IIxF#^|Qz;%t*9rOO;W*Tx;iWlI%jMcK=D7p@+hSmwg1E5eG`oIKpGM+SFHE z8UuP0YfT(+4C)rV>0dB(uR4-wy5;;o`C4gn$)=o^r)4^d3|qg`W635u{SLS@AI-WR za$NXhJG2I?dq9~XN3%f1X#>E?hffxq@)+rS3NDqs6)#M^M0E{gk(+A%=!n_qbiWkJ z>Dnv~R8sc71ogSiLUt@mnx~6Jv4+RGO;x#c#(_=e@^DR`c;JF=D%w9ZioL6P2x_ca zjxIvY6Z+O1=G^!mTAbs_X6`4TezP`%Pz63o5>5@4&K#aF}1W|Jr)lpKYp2KNI7;dGUsLt3zr3} zO$e*uDspgw>l$Tya+V8(Fg)8M9M*4vdACe7TM1;FRQ2PC(I%r4PNRJ1V^jQ15erE7 z)t>8SU1d&cCofJbL&O`0o8p<-*tPVT|B~8z*)WX7%M`soramX4$;1ZiM820*C}1x~ zb5W^LGi+n8sr>uijF9_C`&@bY!%Y#r$#WYH76yz+Nqs{(NzDyue8DVVq2fSR#t}YS z`v*%>$N{yn&3l)S>UxW$W3!pypU^O8Q-o9O+pP4?x&E`XW5r>LBz@6O=Zk)jlg<#EnFH=8)qR@x)? zB;q%g1kC#F*4N@|r^FT;vNiW71d9+S8#<$=RuoL-=#_0NlRRegI`+>en&Nq=l9Ppv zBxfgx5uTn1AG6yzNaZpiqn53JvPTKFC+W*_PENUmk4OLN<>w{&iyC<=tN7`|3Kff4 zN!BeF9<9yC>oX#y)L1ilq|1pOQ-IN$s;;V7fHk`E5>@NKUD%sPc2Fo~5aJFRNzZww z3LjI&rRi(mFRVGBe7qzW>L|&P@uxvU)}`CM{g5R#6=^}W1EnQNx4kG!wCyisu8+{p z=#{;^mnB1(Ec8X}6r6`tBkyeqY+%p9R|bb0;U>EH~J z6w1aRpV=X9ZYh@s7MxXR6Mv1o%`QY$`5cTeRa)B+04L0TWuWO!TM8ntjj7)#*~Gf! zg-ZQi$_1_h9J1Lgs~k^uva$0TDyXdx(;JhKd+MNY!j$md#3XqG(G!T36w_|X;Jpvm z;|c5T3$+V(O`v3B7Wvj_HYR+R`&yAMOBi7#wDZ1^&){CO(__b8_Dwfb>7Nlau!D$e z9^0Diq77H-GAtEbN%8UY=v%FR(h;OcJs`O{Hv_FrWAo4+cTCUqo^!*{zzrQg89#oP zSIeX6DZN^buoP(4w{7#Rx~w%KmIZ~%jb{gHLGjq0VW5@W_BKZx55=UX#&VuCa_Utu zovXgqk!@if;YGW;Law-J-&!8J{@!c25);Z(Il8?$9Jl&59!B(QQx7d_G5KcKBL%%b zd?{H|sE-H;f&u%r`Wc;VxrnjcG^`yyc1GFN&dy*nlCx2qQr5_OA!s;@Dcg`yS`#k4 z6cWt787a}LbyBQw4r<`>{$Y~2o8*c&GknzO2Cmls)2x7jie|jJ**ugh9l;QPeSJyf zFhYD}?oULnYM+nKa;!tA8S=Qw^zU6*=qQ6MWYp6D`}VG5zF|6U5s&BbZ8BPVuRU}F zhLJv_DN?MysL9OX0?I6Z#bIXm-hlb;#ixq6@q|l|&AJNmJaiX=DeVbN2udlpJ^Giw z;_2?C&rwZP=d#mMnW1(Nf&r}mqR+|;d{p388-g_iwzUo4L%(d#NABXCN`I-BqXQCaontJ9a9-Cx@_d>+$76tC%O6GT2S7s)wVIXSrb7 zfgTyuvR%VaLboC2y|zptbX-&2(j7Qu=POjkO+;wQ2t1n6MGU^m2+O-YA~I^iHKqlh z#*xm4Z`k*{W9>v9upt)US$wr9?5dsQ=BL7Zn+U8$*;)rypCQWP_-IryOL2YYd=~o( zw~*rTQS~Gbrr#5k1^`C6v`{oajR%lvNBs9Mg|GXplwNje8`?9yk+f(skty;prGFrW zvKAk=*pu&5y#20JQ6m~8-s2I|t0&yXdCbr}(_ae{2Uys8T^iI1G|2EzEsV6pRVX_4 zC&()OZdbN91!lDW)B&f2Xr87DBF>%Bqv`|Q}| z;?|@%8Vy&WLcM5J29W+p?x&Vb;p~HEmX}P-5LM9zb{YSyaZ1EUT-3GKHuhansqTG5 z40!GxgEb#=ZHJF>#>|9We&-vmW%SN>VBSR7CrVX1l#1){b zuJ^F%OvPzF%rVD!1iK7(8A+zLFSSgCi%LJ*ByC9S;Gh#dwPcNc(L!nBPq0coh$ludXgZ!zhO&ESR^zUepl`7p2JZ@6kI01Mb` z@{Bkh!N;$!o#?JI8rPI@CtRCv7LdYA%uFCPtU3)L1nnM}agP)c_)=Ymdte{CaQ|k)iyuBu?pZ^Hrp%udtkx| zXkw|r+FAQ4hGW1tmqu*$4uWJwFxQk1E_^#orthv%IFDg^W(?;PJ@O!*Qs^dXd40&r z%IKu;!1}Z8U=Vuo_2-P>q}w>gW8HU+XojQ*By zHOlci=51Lg-cZ_JY!-0n(?xIrk{vswLN-6N@?dJKQ5Qr zzcuJ!)^>ex^q3>B{RQUO%dNE_SHA`V;-1>J^pz|7skzBh+xDhe-%V%LFV*~yS|LDh zAgUj2J$hA=gx;Liy^Uz9Ag@*IA8=cSrVHBeL1MRbPHncxI;{7VY6CD(<@0e`MKYE+ zo}rLLhHd2NJVWw(GAt@#s^`6b3D{Kf(d1`}K&UV}C2sRazXc18~fXyry zus5qN1pa^J0P5Dp((0xnk#vP|7rG7mIJrU?a@;K9IcZZU-$y{ro+H89Syf4)ohMkd z;p?fb&MD|Prdd&9iXu*Q>~Cf)TR`6ZQ|qmG(e&ryw$aHtn6hZ<(uc1nbLz7>VvT@Q zMPO4P&L_j^elIbUPQ0eubNy*AxTodI&pNa(IU^`;zP@C8T)Qk3;18P)JyZ|pp5zF~ zQ2$Wo2pSWe&1%1pQ^lBOsKm2mQOYU+wI$=dd?l|@-bPEgpaEwG60nlXson04ElJWc z@TTJqHJfybxPGZIAg>a`T0SZU)UvdU%`(}aQL!#sCv~Hns%8}$hI_z+H=LOAAB4yd*;Kok#l$DwUxLd9*u9BMfpAS>& z;x+hF^FFQE@ayLi2;*@*3tF{{%i$bsj6mmGkGHJHdy3I)4%8+sb`tg8UKCtTa_il* zPNhiCibeX#x}2(#l08$4Pc7aXrfein{a>YBc|6qX8kdfoOKGztA)JyW(>a7Nh|X~$ zB#kBeUfHtCm>KGn3aL|(T}QGE#y+;0X|WVBW1TXXEEx>O7{)S;`%c~a`P@Iw{d~CB zAN==zUhnUD-sgF~-|zFhb-)X$I_^YmzoZgjqMBcT(q$PWB7i7hYTZgha90F(j2@D#1vzvd-=c)bpwdGWRm98s{0L3-R_S1={%meJxGTlf^1mR3 z=E?48kYhRQsF$I3BkX^So`22FBU=zE7vc26lJ7x8EC>z*LP{2jw+9?d-!09;suVD&^@HiwqH{FB3jCxRG>%l-y6y)$cY#U@%Ot|Bx` zqzFXX`H-l%(d1iCl`ejMLOCzUI1Dgo|HAfk*{I|CLH$%yU}<*pRcUujiBp~hRh1zH zAUqrcosRAX)8@|EX14@E9$v9EZbg$ zO$n$8B4G*(FZ$yT{b6Z7AY=t6O{c1*;W}ZY`C7&Dv z$(d7HTgHqQ{52Mmz>8r{^iCcj1YCtzTXT_Xt!+r*DFPH#zxt-=RVMe*(T%fbgUrsZ zL~IfRM?p>zpCZKh--AQDzu=xpS(M%?=~HwjtSvxK{n`~d4LJQB@i!r{8f@M^hOVZQ zBAz`0bRAph&-u*OAjf11rTAS)VZl8+_`Gs-ZLI1IdKz!(pnX1n^dAdrc zqMJ6kN<6Y@>WYaV9iypyrQ#yH5~C&=Y97lL^@9ZPK++?uF|+vm)1Pg3T|fiSjkFfv zP%5z*GCBA7R@pO(?Jq2qxyY)8;Hl{MIXi+t%6@=eT(R;w&}juzJN`=0)IVy}6~N0) zOFl=er>B?dSe4g%Xw8iR!e-dS1*0EBevq5+DfdXM* ztcT`U-sHiHP>To7scnr>FB1hmkjGc&}w;ZKaxH2+>G55yWY9;pa8+}0r^XYRl)GEwHfWTkAxO$Orypyfokg;3v7Um`(|6{9E_3C_q^!HEm3IK z>*ly*2>4nb(h+c_P+Ce)9}gdh9{Qw={t5B+rY)AN+TUT+z)Ra6wojvm{xLF-P_kY>`6Dz$(3acqdIetPW*4?C{AwRVu-l=BqoZVyuf9a~+_pTq{|^XT{U};zqkoT0(&eEuuw{MD z0_6cV`O~s*TQkCd9EDp-QIhh++3qaVlqb+;P{f_;Kg41z$QTg-0G#lt%5;ig5{1$Q#sn!SU6R4P^Vlo znj`b(CixGK81HJGGGU0pasIhAQlX>Qg$A|HBLO4N5uF0KPB79;3R-F|%QZ3$NN zhWU>6^F7|JXm#hLSE@%E7Usn~7U$*4+unjrO!^)%6YlkO%!@|VjwWi4W;&!e!PU_CjdM2Ty4fc`*+>-YVqDwFJJ~&H`48p*JC`7;>8v80mDGv<+@Bo|%1_|!JbeEQ;}Pry zcS&OJ1FroE!csE-1kp0<@fk~{b#X1A$|#0&_E{w7`?SLj!_;K&D^P*0y{ppa=$skhnSiTgW#daW#XoI zkq89e!?p6_i)tSucD^mvZE2-e&K?*UV@I9u`^&Onl4_qf9Y^u)E)*g)TWC7Lzpk{& zH8fkKmsmGmUc#sGg-)x&PH~5SX50t$Y~eKC`km-*=v*aWgE=l8CyeB5u8b*cc z@JfTBIU;VlQxkMg!~%LkaIW@d#=;0xXM=)J;B3q=pSgI$a%t780ZyyQIsnqynQz)_ zpzWRgyBw|4Pe~QE5Lg=D>hipM&I72Mx@)&4^f!FQOJ|L)*+}uO(1urSwQw9F_nXj2 zx}|i;?Vje6CilLCP+uUXfp)*xl=U`mFRAEPkc*wn)oqGg8qZ5ZIK5i>J6 zPhAz^0Sh=HKrc(cmXWy7gd6qrIT8~eEqUsQX?1% za;tP}Iu(*6IQ>qru`%#9G8N2Y+W-kI>07L!XX9|qE8PNc*BxK(3q9=+0pu85;QD13 z-LwTBSm%v+J}H{OYtj>+Yx-JT$XbokW3NA*85kT@$Q;f`Vm}rcVSWj2wgcGdDCHh7Rw#k^-cmQ%CRT40UGA1~> ze-PjlpLI+<4?-nUWDun@Xh(5lDHwP~!zWcWIVc<`;UU&~@xtg}o^)?@0AXJ3 zR9{jIx18OkAfJ6FJG=cY5%_6}){X7-ixgbSNfFFZ1bKPWjFVQu0^+pqDR5A`9QO5W z4Y>SX)@sxmLiQROJd=VC)^g-!9kgmIr>YgesfZ-BZ_!P^`;5QP;sW0yqOM$4Ho|<| zovKOgY`zN~Ck|LS_RHC=AzR-K%J?6=h5G8ulc21O=yCm?i$%w+t3gK5clq#ktmsEi ze%u+*fB6-aERfTh`8;XmaoRl6Y2_KFXnI}m{AoNFvmORuiSpxrGe)&cf@>} zLnQm3U%5R+_;;Jj-=F;7-pa9fHIms*lJ&%HI<`|7OV!Wc7h@4$HB~-l@xdfxm@H9@ z!DWMYgB`3G+nK{vP+}Ok+mIHrx|urvWrd-bdWkOzmuo4lS3sRNsZ^o&C0}4bd0MI` zX=~f*HC;r+4uhFq5A+NgZm=JjXWyJ?sk;_tx??i5;zKJj+Ey*40lyGc@8f#`cyEiN zMCEoC*C;ZC2!lBOGuvHEuz`eY$vW+jdgMU_d5oGTA zYEi+gu%rhDn{{afaY8pCAy|2n4yLC^Ze?XXq4qJB9R}b6004;Z$^Neb1Pt;$UkJ$W zQOxiA_~%ysSNUi3?NO)CwO2*;|gih)t zNn7m{v~$>8rJ___O{oa$<;k^t4yi)iQ7fN!VKjwng+9E=aEXTYSK3%s6n%YDLy>YO z_zW{us$LzdcczhOcn>!O@r5ge#zlde9s_Un*2;pe1F}Ef?;NpSzubq0JqZL;)mpU% z^3m2wSO~HuIRTRjt-|G+DdgJ~?-7?p73Qfby=VyBQ03n=&|d6}8B(dtd&CV2xy*>eOkYq#@?0?@TL!k)2(Bg&yGt%)6O*Y3<{>+!;r8te!#SahoP=gm+x8 zVp!JFOv-4J&osWU{OiwFLm5+Y!_Mr~#p=>2r%9P|q?7MMf|7AGiRpwXGU6P2+n?TXPdUx=ccWi zr6s~sAT)S9z2wW*mREXn9Bbh5)J5n^DbKl76$|dVVU?nx9jj;T?i_h@S6N?iv)=Tq z@eNUP^*>1BJjRON9P}z@iY~g>{1C>5o@v*if99dhYSf;7x@>Sk=!a$1n6+?(6G_U3QXbOnz``Z_%VYU)Zj?JzTTADauvhI zUWSmV*A;I?OtR>l;^QIZk%hdOCz|MWCU&y2$jIdJD^a|N+=dAcBqmEM28QXABgb_y zsq}F-C`Q%^EGe6zQ}JTlXD;*ILiV{9Wv6=v=LX)Gww3kTHCTh`a=TT(W3meZjbp>& z7rF6V?(+;w^Cv;-#<_~+n_aHSO2N$8uZ&OdM&K}ecoFv72o2*7$r3=cxfrM-+^qs zNmwoiOuo;N^GKjv`Q|q-AG<@4T4 z`c<3%+=58j$gP?A#TH*`_2h-2EfdNgRK}zGT0{m?4jt`4`OJa5eYH(!Q#qq^{MbEI zgmZ?xz0=kn>$J{AwD>zucy`JP!z-1`LU^s!jIk#UkRvCh@0v=AY+ifmiXsil^Q3Ph zlW|sA1)YV!P{6D~l)nBmCH5wU6-T}C6wf86X^l@PMe?Ym5v@GDDFfG;J4_lkV7Ow6 zBqPG+dcH>lTu=pGB!*v`wFH|*!x`RSNmq_Do|t z`A6Y2F}%W>s3NDtAp|>|R&g3vQbd+*(EOO_adjH7OIF4#y@QPpr2vS5=-OV>Ya5Ro8gu} zBdbGJ{$#!r+bogU%d*h{p}Vua`DA$+IaZb1hC)+Kd+LFPiq|loQz~zN#+Id3wqVx$ zyT08apR-N&y!ng)eKZb%ysm{4+H+57EKmC+#CZ{guv&VH43Z?si$sxoXvntl*6N8r zE+nU!+qO5!_ZS#ImS*hgvAZq1xV`e|>Rftw?`h;fD06@}8Tuz}&vBqq;p$>yWtAF< zauCp(=hvCyDUWq`<&kCXk^=1*o(nmG+ZGljs?N=%r-vn*`mZ(I=2(Wcx85`1?kW!q zI{25SQejsoGw;QbFL!bq9m1K*P5b2XI^zPnVRFg3L{3p!L$186pj2gtAER*s1>N}H zUiy1I>M%gGEP21yr}@V;$m zJ7|C>>y4WOdqnA)oCS*a9B(r*AP3r+`w~QhZh& zj1%&^$7@Be%?>ZcUphQf^Mpk^jXF$nJw7Xb(V*5py)7+IDqr7mM#wyN>eU5$W|=8Z zyyU6F?DTRa*~M$6h(3qyavZ6_0l&z2Rj^3>OVRu)RJ4Wdq0!F#((0&t`8~oajSa>! zt2=)QI7U5ITwOjOF#k?6sid@fFIN#{X(sS0g2y26`Sbg;v#7268Y5 z1n8dGKA`kCAXthmRvFeb4+?V+x!wT?bibh`9f}6T$Vf2_n2;0FZXHU8EmDZnM97>O zpHfgOKC1x~O_rED4;6qN3Cb1^8w4)M3=QNT5D#Ds@JIR%UA|+Ye;U?uP+0$eq8%`C z$bDb{I54=hsVOisfJrb~2n$m@J`zBMg=q+Yw5Xm!0-mNcA`drAcN}hLufL+xLt|ALJ)(Sz5 z2th=iMUD_gPSgyA3M3>)71k=m6!;GJSP%g~ARxeCARwSXVE=}F-$CAYFo*<>jEI6t z#Dqr7#>^r_LQ2Leh)zh(F0API9SK5yD*}N5{{=ve`D6-A@C`|Y3jGBPro1V&fqYb$ zAlTCX1?+chX^)-^eN1Gg-yeMW#IfBFoF=5i%I5zC1n^14if9lD=XW?bpQ4&Mvo(Tl zYzyTKxI~_&Omn%63+-gg?ovw$YuBx6xe$ zcg4tnoy#0mufzjk`LyrN!Gy{Kmrd5sh zXp>#em+l;jKOp}K*QgTh(I@WFMzv31P>X;mwplR|KSRma z|8=u0;kh|F5MBp^n)lH}w|tG9xkIT4)ytKs2vsHp-;0R|)g}o$A=+>Y8%cbBT(iTL zCIuU5v^baoa?nMk^_JEqYtqu7bor&_l7l6K4=H6{d6`j0fe|7L`_gQT>4fi*m1%DC z#U5E^GL9kTrYvDHC(b%3{mB8xdYx&s=a2p?`of_6IFS`xd7SwwS1d7QrAS-Eu1WN* zlJ;It4V)n*7e0ZEZ}m}FNG_PCi2r?FAOW_+A`;Bw!4`s0Piu6lzpS-U!#WG!JS>ML z(tiFm4^I->Xj(<2G!@k**%p~-*E0Y3WxDg4;2H{^$c0Ypk6Y7cQ0Vbl&$Z}I^1G0S z8{d$IW(g$yFVkdk$r;>$hAsTJ3o4V6Sf;H(ymo)o7*hD7N8avemd-(5UXTrh^6EO8 zhiupvu5n6^0NH-}pR1!YQ;EPEAv7`~*crE;FXSHke*un_&0$h_wd#|9T99!aV$Akq+5+-KCf!6JsE@vaIAoq4)5h-faqZ4_lO-ojID` zfz&X22h*b+WDkp8Pd!2#Gm_N%QI}Gml;*EXl3X^psl8kogYdJEYV%vw)<$pZgx1mx z-Afenx{Q>C7cox-EG>h?`RosJlKoeSc8j3n*u7XV*5d_t?+O zI*&H#8wQ-(}cI+d9UK0v!Crx-Md&&*&$oHB24Xiu+}zxbp0~btHGF+G6gd zuwX=nBHwvXTiUxrC2hy#sraPN2<>=$&T~@A9@gYGnkdq;gpxh#HF7iL=ta%YtL>56 zD-X0e8W<_9++j#O@B$`*%@r{yo=&w4L&2B=w zO7aN4Hr{>!sYI&>Fm4UX|Y5l9jrt1o!r|64ED|^VI z%uFu#QL@FVG9u5ddk4opl*Z*2J%`0PAqBhtv`?0WJw`;2Oib@K$u775RmQBvqvLXv z>178s(!wbgLeKeKJOJgcHWkowT%T(LEq&G#w>6c8(58hRufa)t+bf&Bp z&(D}tuRPbTwRaoJo4eZL#a9Rkl`1%?$Q{sEZW=j}a(h#dK}FqBsii25m$$iJ^Njp? z=VI_vM6&GDqXK4Vq_5glEjV;9FrtepYX)YSg*sW*MoZq}p3`i!t{R_4ug!6zR|HLE z3iq#0ALgmQW0XH%f3Ul2)u{heX|Wt}PkoClv#-c)t@V*lj5yH@wSR9qWOYa#Ka+N8 zDcPof4s4CNc6C^6qaSO6nrL5MSy9$$W1cWH|5LLW@awi+42>;K;bX+b&&25W553PD zzS{=HoR-e6cWjlG@|TXZ=;pJagGdSGk38(42)bitbiP`6I#6CzDeBXmG#FT8>mQ`w zZ#%7rOpB9aI2XLeLM$D+!ZR^G-ucVFfW8uVI`4svC^=uYy~F4FF9Sv2(F}nhI-^H! zlY`lWn{d0 zHE9aB>>Qu4u~qF(lKVp^R|ivj*#Q>U;TUir&!Z}H}fL|KIO zO#Uu%$K$Pr;&C(Rl(lbYOm%{W&2PeLch$NS^O7QC{-P5*Kto3UEA_6THeL=s>Q5Ba zo_t-Z5O`cldM3LJm@av4ne1}9&GzD&UL}Eyb>BEO>u2!cotE;Zv`z!~Qkjol6#+>F z>;BA{x_hTpYM55Wrk=ilQSsb^nqD2n#47_#Mu_Ci8aQ9=5tC)=-ZTCcWsk>cfgDz1hj2Or*TW0^)nM~XvZ$XIP&n@vpdwcEN zP2C$dHB|Q~T87G+l|G8Hp9G4Vo$ZH}KPF?zTPg2SjkKv<|Kzt`R8mh;M?dr}W>&fN zRxG>y5dFb7TD+=$F{Kn^&10F(oWHwb#zJjn7_oXa^J1c0WsJIt$M(2}g>$i~X?|CJ zQ(8;Mr3K0!<%awHyz~KwN%8f-dCU?}?dtB{w{bvwf`WuNS*C{F+!AKjIa#`|>1DMZ z83_zuj=M;dnxAeF+yUh?*oJ-bQPq`1a$C0Ou{PGw?qA7s8c>~87B_6sSXxgx6Bq`p z@D_o>kSfQlHzQk1Emx zlNW}LA%#9U2YOY|u4ZmhpJ*7Blvk9Mg{E>DMyg22uP3vQt?h6oq{uz$+Qi*b?u3v? z^8|#OapT=}iV7^VB4T^{JaKF`-{@FfX5x^r8?mxgQH`^fTNy_hcRPL{```Sg&P}B> zJBWMXJYXAu06oLiEgx~it5WFl@o^%wb1+olFHw_0lMHFsmq6}92EgIPQ^Goy>|D~# zVZZ)t;jrMF73RBWxWUJAws%nKBQM1FMY$Leor)>c_R3&2+LqpF4)fS>Tw^+b4ut-de(P0uFs>!LoB zC-#cOMz|uJyQ_cFV{x(31EH)B_5fvwFK`ygR`{ZNRfkmrE zVzHs;>@vKfyuJ7sl+a6}x}s?L2d#%_q2naN-9wfAg;oFN($-_v1};iUO7c*yK;9tV z60-(BZZztvEp0hH*UgU4AlQfz{z2?GKjI^Tv3r3EOhQGOby-4^L@dH>fKEJVg+HD7 zt>*Q-0>aqY;0L)Q)$O>Ye7tc$U(b=ib|wYy=3az0q>!ooW2^@QQ3(PO(gyxj<0#r^ z-?V}dUrTFMlTBJ6I12Ayz?mw)wN-PER(Wynnw$_=ZlQK31x?E=HDzO zp}XJ)R^%O=TU--5TB+dh%B*?5+OYP(^uc((>SszyR zz4UJ5{efe8+_XJ?Fma5197@C$Ub+5UW^`$uIjyQ*dg}V3Qu_-~uJHKK9^0Hh%&fJw z`32hw&6o0{ruq9*D{A0-FxYR{^_VrTsCxj6Ep$+%22Hg#UB;@4I5xDEJLNB+%*+s? zj2Gk z1zr^)p^)Z4OjiymQumRKBq(t9X|tNfk_-VMIj)?|pN5C(INy~Y@g^N^$c*v3rpxp$ zh2|^=9NSTmCaJ^v*c~FZ04x$~#*aDBi7f@);Es;Xx;3Dn%~ET6$YOY!;-I3Vlkic9O+yyWkf z;?d61FJ9qQOX7@ndN-kd@ZYi#IG6YNWVGVdcf_QZk2~LIukpbWj`)W{F}C4WSDVWf zxYKXeXB?dMIb(vKrbJg9oWhOclgu)AomhN3nN5r^Vs#(7_Vk+Zlz_Is0J@i=V7#3X zM)!LM6!h*?S;3$mBKmN}iKh=00__O{5p&z-mfmm?5K^e4H8l=um=@(j>Dy~f_p`&E zd}+x~Hw4O~o`}8i_a1B&6MYgO$-HqdKV3$ZfhXhR!3Dv*oSuFUe$W~PL06VSn@$ze z`;`lh=;)EpueM9!;7-}$19%e2ESQ?4U%L`-l36hI z&;}t??XVoe;zNP2ODK6r+&$g<9Xwc(l7%RpCh_L?J?jk_po`5ywp8VJ^Ky~1*=qK8 z2{I#eVBtGPmLzvg6B}k+U@Em#7^q4S&sr%DT-ZCUFmIm8w$~?kEd;7){`BjQx?r!6 z&LwglxkgH`avd^%K5}+!C20#?T5ncdZWFudcKqV2i})Qe1G7E92Iqg=#W^8n51{K% z;1m{5N`^=A{OMCSaqv57yY&RzKU{BND02+1MXg~8$Ti`j4T5?qM1t)}ReJT0Os)(L z1rzZ2VJ6>#X@nlvG=qum%%>b^?m5e7@mE*Hu}d_Ic#iC6VRnminRu*35$r%g95E*a zO=k}BAuDt&5+YYR2qtR`4#%mDi0y$PVAKV<=V&+Z0ux8>NFvhv;|cr_E_Z}c4I9O zR-58-J=_!57RtqC5*cpPCW?jWW6Ddw58Czf>;p_1%MY>(jrT=UXX$xXY8dwV=; zRxdur{<49KG|6C2Vfv5ew>I)7$k;9Pkrq203_5Un4abow9rW2lUb>v$M&JiVCLQ(~ z2Z;6c^{qAKA+%)uD*K@aMn-mbEk?FF=;*tPLOsy7@KSQ&!6r92?0$b<`KoePmf76k z^h7lN>CRbSVt3r=zSR1Bv*p%jEpBlC#r$8#{?D@t{jn3buVfiq<`B^{^#POqH|0%Kr2Vq4JZ-%}@Lr0K7GkzZab5~ zLT);pk;H5+JMrC>Ax)GrZ6cTYCP`#Te*s|MOGxv*gup-`pupcP*nce{FcKm%5fcas zvkj1Fe!@k)G*f(yBK2YE49@|{t{2r-@+8|hn4Ojh_b`|_LkumeF}{OK)%7El zyBkTMsbr$b)zP{Bwv`W>%o~FYtv&U)W7xzzc@<~$u$#mrD5PV_fGoBxJclDTjpB)- zJF+Ijz&xcmMwz~qGEiM6q0Bf2 zVT2j;%8~tALd;%og8->i=8WLc5BLiw{=u|c(pl{G{x^BeVJ*9`MtusBgi0chSiBFj zK4^CWzLr@08J<3qg-9a5c@2HovWLYeUHcz`P?WdK)>3ixS|0Et?#PnhnJGLsz z`0gs1mPlT7`;|WsO0x}2BLBfy52aFCN*RwEg&!lmmX2`)9c!db+`b^H&_DbOSW@1> zZY_|s?bfG!cKtM|In={-ik1FAAM%*E!+2n@o>}N?*ce4u9u$js=eBW+ZHvIxi8fZ7 zMaQ>+fw@luFTi-)>cn{QE_L0*ym~uaa34Nzf1^5B0+0p7P_B$UHn zfbjRjAn^^s{{y*0LVTx;fc@jr{(<0;h(Nzx8Zonwk`W3ai<5Ig!vKk}vP(cx0T`-r z;sT?fN?_4FDXWOdfnrc$;%%NQl)KxQVdQ{#IJ zFD5j2+IPWd+{B*pVW_~!a-KT_q;)5$D>A8fJ?TUqR6{S&)H&%S&=xw_4uYkSCb(P~ z^kCM6f6Wi;!JG!fCv32lfK6(`cF8DynN|8RYUll?Q}{?NxYG`MqK}RX|0Z-IyXXZU z1J=3sEef96W!-ct-~1hn;%i8y&tTENBI@RUnH9bRYyA7lrCoIY_^WSC+KSa?7j5Be z=!vPKi0$HWvtkEkZQ0?y!A{DkqVVsgAc~D&oVc1YGX7Ae!qq_!SN@m}XYjb6#7?Pa z_*Q5pmq?Hwnh?DFz(x0)?=XQhcW{!s%f3a_wdq%FM$9D4Ho9Tpl@UZ_nm+xTgT zh6A$PFHQkxkR%oy;o)1kCNw#tq}fOGBA(QLYnu4(N%?>3(!Iz+(_?K+UW%*jM^%x< zi5?D5n)uvgDdy}+hq1?iv8=(TkI9ic6rLxU8%^cuXN%v z6-qU4AyFV!Z%Prt08Y?@fDChC_%I^bNT6yX9P^thbfjhIe$0zpXtPDU6b+sVsP^S? zs!noz2$p-Cah_Lbfjt5!1+jEd$7wk5i26hNhAtQ#Sbbm+Eeh~-WiNIXkYM2Xe$IDLkGW{Q<)YW9hx zHcq-~>aSF`GjP<^#Vm;nsGI(YLz(e?FfiJ&>{oW8ZE)7wClnJ#kvkv>i6)zDNpC|qaKLcAFaZj{T_+68^;iW!mI$xv23!<+i0T_wTRfmn&U zJaZb3p?)x;_KlH7W><#8DXXXm^`Q;kYtG9w?T1lb6RQ&0Fb(Q=RL{fOr*B4oCOc5& z`{>KSWU+Uht1xOHFGP^SL{#J|D~X?>q0MhZk_2ZB@Xy(kJ6SW?Qr_ik5b>PNB-U|9 znaxC5M4qDeic8bVh-&cF!~-fTsduvd#o=N`>RY?bk8Kweip{j;7iJvvmRYYfg{srk zmq|-{B&&7gf05pjyz%Mbx`zQ`cW(xmCo= zU%G&Q>JSQ>WJ%6g7}33hnhW1wfJOSimK3bgO*{dX=*m2J%;}K3Dg}y3g&W! zDbr?7dI#gHT!dRGstm4(pXQEf-Kd#e5O>m5b5xE%Rm(nXLga_$kAwzURn*sEcl0)9 zcM2R{UriS*H1q}Z<)ew_)HXQaFbH&9a}~Kjy-B&z4id|%=x32uy)R-)+ZQ{bX>P7S zlswGPmKHMZWmm#LYY)nGAh0m|g&y-r-Y$@=>`0gTHtlRw{ke;2XR9IZ-=OC$#A+Og zn;Dc!I*iwty3pZcJTTcisC?_{Re~r)&+n8<#Mug@i9ex9bY$s=m&cQevLZx-3~hES z!fH?7_wHj7iH;DS)$J#ge%!^Y>o*-&8`Eh{bb$|=tL4|HwsRPp7@(7cq6lAHtJV~3 z);v*@HJYu~D(241Hj1(Y-e|p-2&LVBOxj53RVbD(8^dFzRqW z%(7klDwF7Rt4KTZ7eF-$6=w$_M;RG}_$dwj!3yZcHZ6e^W1#Oz)w z8U#A(8=Z+lJl4oPdm-JWmXd!y?%cT3Al7t(?)knf1S&TZ!-%t5y^~nzvqxCnQ$`~& zHlqExq4g>49HPDe;pJm8Y>S$vtvh9$=lbkX6M%rS(W0Yw zX*l$tuD|*1Ui_v`b14eh?Nn!AMPx!|gWaBtwv|kVvth#xTq13(NbZ@Lnk`!l=cVg(IL%+v^wVkn|<0mX&9`8A>MwP$+YI<&EZoM z^gL1`3M^Cpxnp%0eY2zA6>k0u@JaO@Q}9cyoKZ5Zf%`D~Q2=>*u6iZ!&^#E{4UM7F zjbtl`yHsDsw5gc8SGd5fIKBBJKMNgTA}SrvqHaGRu}eT^p4NOv2J*XGt!^iIcB&h# ztmXJSH-aN({&Ouuu}l6z{z~1?eGl}S4g^g$)Ou!9qIJdk(jk)`o^4uRCLCZceOz7b zDrF-&4)!{3!Y%r#qCZ3d!l)F`77Z@jS&^4gt zBb9sZnPOlyNnlCo`WK)wUa&=V^!XR?Ra^5?Yu+5_IvdWfpEY!B&BFVwv; z90V+xXz&javhnwXQG(cE?E_-Uf>EPIOn#bF^Q!s|t?u*o;GqRJ>5G{PAi3B{{1)p5xM8i>RS56I3GE@_ zT(>3s)qjpZ2n&B4f@3=2WREeuf$l*b z0g1%!sV+Of++p^h9FQbctMpTB%tk?` zuv5y#$s){|ww3!?XoXTXK+^A{YLXzqhESLPkiS>Y@Ppfh%ErC}n;JlgfmQVp54ImOp%7Tv z>|R>^sc(&{SL53??@$A`u7m)HrIyQI2Z+_70OwfEOipoy-J~9`D{f*hB!*aqZp#`D zUf2rNu-Qc4{pm^n{vgIciy6d+fF+mLmh5QA9w%MJBoM_OohbANof6UE^kmGiRRoc} zpT_?al>z7fOOO61rOEtAm8YZlOw`9Vg}4irGl-=Jc#tut$hy!*#BAEt((ZWspd^ffUZCD(KN_v5zB+F*#^SHT=kl3@5u$V>F zz@qO@VPO>LoUGc^{8;T-2npDNq4$iLI;Tq-5^)@JrH6UbY1XCs{N5%ORI&~t5O)Y0 z-g-jsXl;Gh#`n&`iV|A)t`x?c-SR2S#dPjglWJcacbnCU z(PmX*VR_+3fEk%!=+o?k@|6N}(rVsBc89))}@W+!nXL(5q{rUNpDN%8!*lLu&0nnoB;cmJ$ehgY{b&Z2^pGF0TWX4=*VV;bk#Ch zH86hA9l9~2zS@I&yDpltnZ&|qKt)<0(>2l#c|=F7Chjy-e|9SxH(d5OLjX1j$Ur(g z)phved9|BN^eHN5y(lwGef)kFK0Q!)CaYe~kO%x$b= zF5}>S-weTc9xxHSr8_yNy|@>x0*hbe%+=zsRqPqpNLR>g6g)bY9R-(I=kg~J(h(OsB6~BFLOKs%61@(=h?kWdPh-~}r8RtYzG!)gagw5<|o3*bD zKk!Sdw=}K228{Ma$Cg3Ay%I?;4wv~v$YMpge2bw~__o@nTH)4Y>S*ABKkKB3bp+Zc z>5$%THIvC&QW)W0>{erEhWiu@(NJBbYQ{^lE{N~^kHSq8cI`&_F9R^EqiARBESQ_brS9zX~dMlA^ zE0jPcu{V(iW{FovMzH%8Nn!98AiaXT1{aGsYmWtnmg)tLg``hCv%*k0-z*+{H>i&O zS%LxXts?8|<5M_<)u^?txZSQtEIP8J&8DoTn>`dTDKBeNMixqCs9g5W$B zhMOAdlLm9fMXNA30M;Wdqkf&R+bB;$M*xNbE8dlCWh0`oYXZd?!PaZJS*`e6ywh+f zJ6yhb6PGFDyv=MyvC`3~OgoG`g3rIJL!yD(8OaF@8dYo3G>{#u^heGF2Mhtf0UG4j zWB@qsA-HH(4w>0jexs6c=pij;NzadCSrI1e%L?b(?>A)c^$vVY`$ZF*Z4eGnIw^Vz zR&DV9&&lU{0o%S2 zP(cqyy@_`bSlCuMe0js1OB^E}n7;0%2Ixs~Yu4z-dkMS~sm4?mKj( z3AP$I2rJFA0aMj&OL*Y}*M#^AHOSlbMlBc5!kacVp$`Ov+cP!Wl*K;65UL;cp!TOY zG5vtH0!P^7&ETz&E>rS!5T`lY1>dZPdnG5u^SQ2ckMdZLX3J38c5>B*Afw_{!3+oe zkmBZ>^)kc>l*`B&4zYn=7!*hn&(6{Vo#-ZI>d3a=gdQpKwjIroE}*vyGwN+HZ`6cU zj!e`~f;;7GHICZiDy$OmFsSMmoXec~nAa3F9EiN7za2Fd`frtb@p0FX8cCNPL~Jra z2jpEZgoZdZljcTZx@>P);}H%MU^~%Rs1-w$a1qH$6&+vo|R@9d(N` zf9C{^mpPKSc3qghUqv_f^lvKO@JaAKWvHOx8girgPeEKUpm%U%GJ+70H9*rz55FYx%BvsMlx*qet(m-_}37d zzW~MBr1z44XpP?`+M=IgZSu!pr^*xbqTes*3x#Q#5&_14MA12)!Yw;b{}Fl2(3E`t ziUnA|hZZ|Uo}}0Qi;e#eTl_7$K=@aq#^p&m!>89u)#-PL)rDJ+B|GLN&GMaySkBeT z#}s+q={Ep4xNM<12sAJBR)c8^5)`-;y7T~(Z{fWVIG6%a(+{k=DepVs%T!(LpL&v@#r1D@rRAI0{TK7^(0>&EM-44O3+*4B|G%Dmvn$`y z@0yhQEnoTGRQ!*?;2XZCM*N1Wzc+J$!N0fL{@suR0w57FedE?n0SSl&4Fe1Jga;3d zf{Op0I4(f+7tr-!RKxEabTsyO_V)0h_ZI-p2+5s1_`)sb2l3|l#p`!w%|TFH!!7a` zpn#QJw$waZhwc^R2h-#0>o>gjMQn$((1{l=@SUf-mv=a*_KPs_;~?+Y58r|S`Y)i4 z0RAU_Gv5iQK%BtuM8*nRnXOG-f_w8X+@Uu|M%1TG3x(O*6EUn%E8GcV<@G!Ki2)HP z+Cr}YkCHZ3p%d@FtZHwj z3{)u;Q?Y$XJ7o3zvf{iF+fmPeBauI03q!w56h7j0&hRRQOy*=cag2K;46r$!q8?84 zJhnQ&4LyV>cRve7Hx{rLQD7pk6}P{Bewsq{4%iLM9?E4PhY*by^MUJgS~W4RZWMo$BU}E{=o`VX^It`h6FbvXTIY)5Pfs9{1 z1}~2zR|@P;Mrc5C3O>G|o@)?idjANTEz3vTg7&+;2QUxg`7A)mwLOz)v8*;RQNaD7 zaNhQVf&$G9bmksqrpD)U+JrbI--yt%QYYwb4A4bSJNHcMNAJ>ws8$c!k5ua(o5`}j zr($05h2qPz(o>B+nsyQbhl^dIv@!EPdHgC#Q1&0XLh1$5dp~pw3TcJV$ZDm&!mu6i zY9B>+ejCQlEr`+0?3{C5HO6JWlafL8l%3&662H8YO4IP1^tdj%|70v<=T$!$xUd1P z6CEYDM1UmY;w9JoBefhQ&LzDu5P7NZp9adb0JnS6yGxW5(`lksd2Q~>JW7@fX&I`x zP_Ou!D^Ja*!Ao-7C+TCUJ!tyxQN(`1tlbQ7*ix)%+_eE{7Er@C>Lrg;^0iq4AOwMNu% zYW*eC0SU22kmIn-y#%8vJsy-@M0yZpzC+NtTcpy%OiFpKgcc4`v05i0&nF|*fSw*7 zAi)>mMt`h}F>lx`Kc-wtSf!Xq26imm}`=5ZQk4!EKJQ)oJIH7(V6)QwrCd3}RxPfs^l z0z+ zgH?LqYbyH6>?`L?rOz=Uv3+eIt!0r{?V`e)-w_|U`VXWE29CK1w~-`;#*9}8B}SU2 zI<@QeQa-yLN^v!4@iFtA(m;m6EZ8ZxuI}`11@4eJe%SWZ8lfH(qwHJK}}=gB+d8(wcR-sxw96${Au9! z2GNt{I{S0rvEu6`ozar3RbfxvYsqzECf$}xFZo64id&`I3*0|S)l`RM$PYmp8vt_l z5-CpJ zg3Xv1(BfYPhn4BNyyL;(^9^FAGs$N$RyzU%HdQ|z+z~VLyYwf_qy!Zpk>av`{YtOi zQes~KIB73~^O7C8X$MvxXCta5Y;;20Rgd>0NKys6qq#69lYhoUJFVgfr#KxfJBS~E zT19M%2r<5;m^y}T4`P4*7>Rll@OV0%Jq={n$hNCt;#Xx@e6Uk??rLyb4Eh9Z>&zzkVEvDVs z{#CSEJH6T^g7<{JpdQWye?>|*%acn^qKiJ^IO*2^`;%<-I@U%YeA3m=Qu#q*M1}i+ z0UPI4k~3+5MFn-$OJx&^7KlYakTQH`0XVJdqhu}Ua&$CCC~7igwNmklCr(sXP$Ta0 zXM=Q!Fm5IaFeBZh@APz9EA`4B=~zuY#6Rdpe_V$zK)7SC(%~BRDdr`BXdkX+$wq{P z!r>m*gm_jrIhY5Ee~S^2B) zr}$`<(XZvmE1%@F15m9j_C^sk9!x8;Z(ri5%4}1_=`@Vwr;nEXT*Kq(-+SiAE(KSut0}F$4y!0L?Xg<*tQZk;T zS+`We6_xl1QOZM+H|$K;8|y`3(^05o^zPrEhI4C?qpMnpyr4WY^PM>k45!)!$l~jV zFs%yHIL6 zX|+R6(f+QnhsRjFO%^8Gqsi6_)*&>!1S&6?TnSU@NqvbyB88-Wdw?dM{I{rvgj~LD zj8k46T?6YKnpx!??U2SCknkcb;1cCsmNN=4X8!lx?>|e{AiJssL-!)veINq(=`FJn zbd-_%yr@M~1@V1}oL<$`7J1yyww#q-J3S!oB(_+0yh~mkXJZPKpFWOL@9zL1-*jKN z!$s7M077(z@90N^B35xUmRe4dwXH^yvh6BKyy@4`_>F6D?tdZ!k4bW~zLPs@0hp1T ze`Ww|K19Rs?GdOYU2T6h5yulC<(2I%XMT`=i~-tM1a3JS{1};bJ|oc`^+jRB#G-xY z{Vx!Bjr^Inw`r5>qx;h+l*}4eqqdn0VaXaZs0b<6wrl|I&fue|vw00Lg8NO&c2 zalqBj2;E{9XCwOdj3MM~Np@ITo%Q?U>`9gj%W(y48oAE8OB`U_<)5tJ>V1V1C@6Tq z2X`>k6bs{TSq@pKUcK4<kJ=1m#hB(1R~;8jWnGhC|K33T=}e=+s%@*hS6oIKI5yt;n#iiA4`)oEtd za?*FadPT_nV!RrUv-q5CS{b!(=#wb?Yn4%ck?t@_M>v@{ufa4uCt}`1@<(CVjd{GC zK;OT?h17M!u5l_1N6fi5-*|gwD&ge!o^dw@(YKT2Sguu zxeEm65nz^%k0^f?3d@wqbSvk85Ha^yBA>B64EqpZWId#dYRmitt9UmsR9y8ZY{O=E-a3@QbxvHRK$p*vzD5UbD~`}dS2<9s}a zUo!CsGpQV4e8h6f5v)X`8J^cjIr)7iLtm%_9Wyn;B6J21kqfIUCY@d7Vox5&M|g9U zbm&!{pEhef{he2eB?r~Fx7dlH*`1vIW8i?fTy)8G^^gwSaYcuygBV~xt&lDECTTH8 zF|SsK9Y!jh$1ZBomTu}D5%^%QI#RKW%GJQQ7?`Nx9}{BxK}DEfpk-g;2js+n13@sGoYpxa z64j8k&^qx2k<~u^<>{la<#*y=BCpcso@E-A@Ij%V&(fA-I=2|4AaD-(p}KHtuA1O z{Q=v=2PRG^N|R%v5UdaE}17 z(;U8%gw3xic_pP7P9B`>>)KGz;BD^nFBTLT9`f7jLMue48y5o}=fW*8e_xdrnTo0*U=cq>rs9Y1JtL*Tcu$7nPF6b1rQ zQ@^z8qFRL0n3_xxIVWgm96_qp=w8nfiXB&Q?hi&#bU!lqo5UsVdPq9sFsv{DFdZQ9 z%ubHw2Dw&oox!3TH{v>A@cdcZl=+w-2}iaFN^yx{Rnw#!LHfJOd5=qkq118Z_nEsR z=`WcoD#6+X>!*|C{6wm*MSPtYe?7wk(HUVIT*@%~;vF!w974?HjVo$PT7#vt0cU8} z8-VtiEV`&sTYXQ5brIBd>o8|=);R$wz#vpZzjy-#ux4SL`Im{~m=}tTSBipkXuLrs zaKmmC)E+koSX5V);u_Fy$5PZ3M(+o~HZv2vK5=sy>j6f0c*H1g+5w8)L|feZN8{zR zIf3|9_#u@rHoUt)3ULb_Lo!~kiT>eh@hcE96lv=PY4#!$q^;QCBsGJis|Rrz}L{8AfSQr&eWx{g*VFEzYJ` zVsy$GopOg06;-K00Qy9>%{rV#O)$@9F*_izOcxfuVm6&B@dwoCZI#>D#8|kMiI*+L zHL#)5WTHPQIE~)w%?h&>@|S-R;H$|DcpG>T+^aCNHSnXDQOxD1Bavs(9fUG6+ z8g)d4Ci+aVY{e(uRTN{HoV`~X!xbsK>vH1E@p0OvaZwsVaFniOkd2T)570(7cw@Xd zTtPv;F>@k;^AjiX4kmeJ;^D&*Sa-!!CT9#ngA6H#S!OJ0k(O6BA9;|*(pcxLIbB7? z8HSch@x%c06lwsAhEnrP;jtYQ-cVS+t-~209Fe%J-Cl9lP?|H(!OwYsof&pTMe1CE z&IFaKPKOZqgR2=%gFe$H>SN*4N}L7cR*dN!pc}I@yve7fy`XBGMb(-kd|T_Q4@oW&2P-)=mw6b;uax1Q<;(+=LA)L9i8AD z48uX7V#?#zTWUz8*V0{qLU_C1X>dhK6-{-TWLV^|BnsBiy9&1vhGF+r!1n;?!y_}Fd48DG|na*6c1(?BX@~GwmOtcq4?c!SL zKv$I+h;{K)6smH;RC#gC#j-sfxs8a#U5@UO+!r-+WtcJMQf86lhg8$FZ9v?z*BKf4 z^@>*tb2RC=H%@#-PI2_fau^D_7Ui}e>n!7LVcbSI1e6B*3b=$u!?aQJ zf+n)u%6JALoi!T6CHP`h%EE&fxo|>Mvd}%BNna>H#zUWKhh0Qiw=BNVR+o6GU{Kz3 zs9m+(LuGW_uz+}}?Ewrpq~bTL^D&DhRcIcw-dEB%m#zanqrVfJGV3rbwW+XcJltr{ z-6b_L-ec*!E#!dg>f=$1;!xnnR4!T?6e=vUQj8kB_m9!# z(lrx@SxH%Lss-h(;t=F^3a=5Bv_j|CGSpOFg}m-+IDV8Y_jIw{DWq-mgKfvt<&K(E zd5g1I_>5%rsX#g3qy548QHnl{`apTt;)D71jBx&{bN!@jy^>n)^7*g|T8n00x1h~U zn){N@(1q4n>VdlWY87`!)@-QF-%3Mcg}H(O4-mDfW2oIfVw6|hogXN$caW2QjJd(& z1|DUV2fTHGVE$7!?ec{T!=gt76KxN8!bfBxjjim<2x@N3YGhPh5mW0A7rh&SauvtW zmUbR~IQEAUjVr#J`@}%%7fYo=>YZ9F_F@%V*=#Iqg>oi!MV%nZ3Z&EutXa7Ak-EQR zGzz~HFb>Ly`7!dDGi>oS!Rsk*Rd|Mi+ewY|n@bm=c)H#RG(z>FU>r3a|qO z!y0_RT`xY9AtJsCf-pQ&%3L>3OJ1WpR4m#qAI$U8OLiP<<7kG%h&nCB?+m|Qw^rtl zytor8{}cbF~K9bz~KXPH*_wW)mu`alMkaO_*wI)&W3(0k>a z2fb7k{Q+Bp(`;As39s68%xMo=g~{%fFmH)i*F@^Lic%+BC4(R^=}*L`oeS)4H6L2p zTII|JwydyGeQF9>p894-(coY}x$3|?<#6NX7~8hk!0KLRBo%r_ za57>GtxP6DC1o)a98|!eTYl-Yj00&>t=t!I+ZHIXI<)mK5Wf88Ax?}1xx~SU4$~N@ zP(4oY%uwaqtOl1?PBr;KOL4VHk-mJzCPDO|HAAYeih6}=Tu^Dld>*iI5KHw_D>lq2 zZ&nvZt=$^6ZTikLN(Jkd(@3aStH8S*lU}9s&Dm1J0=c_Ymu(Fi12H+KQ&oIpv*pHbmZv75pU;)-#C&?(k zao zX=TShbaEJd<@9LrEw(Q%Zyiu}(4iq2!?dMJ0~+FNz9wo}6{Xx%26evZ;ZAVdeJ`Xxr=kNj7|gEq0t>k;Dpqr5DlN+J za{2l|#NDUrrb;EQWf@;q9iODms&67Cau-Ek<{_nsc6F4Xm@vr}{UuRs*5%fqpg3%W ztcpteCUU`C%4fUpFm^_iF&KA}=1INE&~nRDM6FY}wQ&xzgvHWgXK;NcSDfNgez7RM z^$Fb(YQu0M_Ngnk3e9l>*&@B_F2lSqV+}w=1&Kef^Mv4ueK$0nA-Nlz2Ohn?M?X0!~2-jm1E~|oU*BU)IqLmRh$0dsQElV zFk`32v<%Uh#(XHg>Whqx=QR!HSyIEnI0YuFsrH!aianQ3u(g5y6ej^zhbWgd$aRLPt@3$>o;JFC;t+QB;ICO=`<_X08dGRHK(&}1 z7?E)>%?>Pyfw9u@d5gmJmZ#PlNnrE2eIh7VC2LPUF)us8 zc#Rx$e;!U0W70n5ru+ROWhS_OlQ1FT<41GdeWP8W=lVeJT@C#r#eE0mh#{fXABpr6 z{v*^E_rz;aj|{r1ORzTt+dhh13DmE;8vTfmKTKaKXEwiWOnpz= zQ??(s5fJ!q@Je+@PwJKa{{YG=(znO;!!wQS{1UE@U+SCc{{Y*F7AoibB1(T_wCZ0P z^8LQhY{keQENlJ$0F-}s`bR=B;-{~M`3@s1$&m`(h$a?^0Vt-IYFZYX<$a);uh+zL zi(2XVN;p5h(0G4iv^8Y?Iz;h5t5X(EvBWNP2jNUGybFDx*}>y2glMNfD5~Z*srHDx zK%{l_fNb$!5#2Sb`@`yU0Hz+3w}wA#q5XdILeBA&KW|y8JMXXOIboTtS$azO9w+3~ zrf8j_3esARj+1Y+maHNb0`JmqmmD1<-8a9YQPt@i1;?dsDSvEs;o@!DVQcwH6nv7+ zo)r}7D^<@a&Fq++yF&o!9YA3|bFAD-+bn6vN|wMYiMz@s6kEf8IFL1_VpOqWGB*yk z{U>C3O=*UUfy}&ppn-ow`;~9-jds6XVzd$I62sV!{^$ODe<$P2dH8sSp%3B5!SDY7 z!+-E`JpTX=Gx6u*ZlnJIUqAVA4~HN26#h>K=00mM104Mltr)%3k$(^rk&tE2O`ZN64{{UKi z6a3khJ&$b9uWZ4uY{jo^?a2QCgq>etpXSg1+5ij#0RRF30{{R35U=#22raC~pLkaF zU$@VgiS2*pKlno)O#c9Fnh0z%{{U_2kNa-pM1s0AeVKUKj8 zXNz*}fCj(sRHMV@Se^?`Hf~eKcaIPoVdT`kPB5Ojk;_89mT)0If7-;~&7P1wTz4qF zuMM*cgN2U&0QT)!=ZPQ|Q!}yr=iPtxqF_`?qwAwWOm>W4&NPGuQR6xOpmvvM!1@Szx zy;kbEky3F!57+5Tf$0Q3KXaf>4^vV8mM4(8NYS=G(?`;))7nHFdvbH*!PyoLY2$4O zehkp%rt+Yh-~vIr`MJ^t#`LN@!&TxBNSy)&EFvTeD^Tnw+&`!sYwbe-Ie4CVKAY7* zsC0N5vm&9fH$jOS^}Ce}<~bitCjMnv?TpFd)3J1xSP|o?_}?J{bJ~WA5-a9NHlHc| zrnkz?3P1amccY^Yb{GlVH8jiU8PVF25()|Cm12CLj$M%Q-vYwV3+sHcXk$B;zOnpt zlT51PV}|lRpM7k@PA~z_o-EXKclk>kJ(l~8uD@!+<3)Xn9X2)%u*uSW_n7|xf9`&3 zD!YGlzW>AkBoP1u00II60{{X800000000015g{=UQ9)rKFmXV^fswKQ+5iXv0|5a) z5WhlHZ@|8^OAkaJ$#Xu2qWf10Bp);4iVTP@zckn@KTe zLcs>iW7zx!8VYOl`ul0tq$nflRdGzAgajpjBL2TVQ?|A3qiJ;T@*N7aHKUJ0jOER zE@-qZL-aRH4d8KO0V=PN?NRcJfr~6P5@ctPhOUrW6;{Tk2f`#tnnf}u?J;*H#MEqP zCJ{xUq7ifj6HGx*52$lq<#4=2Ex#=G;IwIHfu+Ya40x<5`-gYO9UNo zhs$UD6N3gdMuvDQoFnv3l8;U#&TrNh6Rpk6AAn-b;KZGqjHgZdf_g z3NMIv)v^;Uwhl9xp#Xa1Li^1vJW!zJcBNrbqvD)02er6$>?_S z9wS2|1QI7a`_80$mq>Kx2{86ci<7VnI$Ru{3yZ`#l6jF~Ifa?U;D^jXb=0DwfebIv>SDS`ozwHhZTnzA~ay(su<^f^1is z^gj0SZi#T=f%Db33z27V?Xm~QEI9RKO@{VvtIeaq0e)@)jv#t0{(ga{yCmF);_rcp z=4vNS=Yx^~IY8kA&9PXV!Nx+XKID{q*fnfR6km90BMqx~&sx409_7Q)<$JksOObHb z?nb55LOME^v_GYUkOwgc-djAJi&=F@;Fvs4yLT)#0Ab_ddUYiavg>(}A$ekeQI4Qh zsxrzz~s7< zf)eQBZjQ%xfev@mhx3lT#|%3k7jF>vxOuePuyeSb_7ZV#Jj} z3F+mwJo0W@J`IoX{9bm==HObrT89(jc}bychoI5>+y`Xk(jiBA5Y=`ivkoBsDV+wz zA?!U9BLw)^3LiGAPFVryNY|K#j&mjQd7C(ww2c_sjuws?+{>pin+7JYLA<@=2yw%o zn@=_dF>{bI1GMz%}nCoJ<3mMAx1EIh(_xyanR?p#eS*>5&%aAl*w z^Cmp34#XJ}i!L9^;29oX=dlNGyCVReILJru9t-1Vu2??v){&1ew=TU7>=^;g#OE#N z{qr|H(mlZVE%^TIPEO?>mutuO5T1Zwu`@pZ0PVm2pt}2C>9@o8FXQg`KezthAKmfW z_I=9sec$c3#XWibuzo)8jt|7Ii{h5?ab|trAKjOU_HB-@gYW*|9J{%EQdl|tN7rYY zKS<-#KOML9Hs8URv+>It8=D&+Tzx;C{xIT-I4#}fv#j?uN=IMh!l?>i9W-YIJx zxZf@nllxk4EN&f(zGmnQK`_^vpu7G`U>@#?DWC36OT>k*!+noFi zeiW~R=Mxe#C9iYC2*fn)ePp&E>zodrQAOkb`CIdb&PjCNwX{{YPA z7;E7_`Ay{Gi`EES(z|t#pKL!3f8cB5*ZwEd;l_GrjF|D8Gk2c98Sft$-ZsU>3U8c9 zk+u!}I>21|J>cZ)Iq{EKbAzKi8KfL$*y=g>Em<1DW8eT51Yt$4p0I$j4FtZpMA`-! zspY($0Ub@5SQUI@B=9Cxr*uG%rZ~BxG9L4UQRp)?cf8>Ur5~0U1!8Jz z>x_g*&C~t%#R*pWj$D)iP^P?K#!2WJdi!8hip28m!U{~8^O89yLgTx{v?$ESJYklK zJb3elk|J{+F~$hjFW)8tHu2Z`UB`N_fAhH#jHAsc$hr~%Rn&b=`}U|D1s4ARabj8*Y*xRz$s~ILR$NsW z`3iF@*VeEs^raOyqh9#BMZlYLTRmene>%c@SMiDv1hyWMZxSu8Q1(Y2fz7L`$PnX; zmtVa`1d|M2A*Az=OcP=DcZmd&q(me!&EVr=`iaC1#XG<6zCnO!?XK|H7?{&t;89=l z-#_jek^n7cT%~*h@GNRz)+UJ;(3p6bjHDGXYc8ICc#=t_K#B9ujN2~|kvgmtfpC;T zZ>#>~7T3u zrI6FHUvHKdf>B7mGQdXNVpGnAb_BCnOPqPt{@nB5J~jPGd&A2?Y0D|08Ga`;Ryn>(ZrG5@5T{wsU=yCoAbs&<1CCx5qtiOExt|r`{uy7pbluq(nqH zU^+5SCWpQ%5?JKGP;4lMS+_1JOt6nK{M+$v#=K)tkj#<=?h>DD;RYkWragDmo3k6xeAon0QB z`eNojP-03e_4vih@Dd*`@F1rN$UN%E+-BFHXhGhi63A5)svpj=rJ+Dl3%G>tFtJo% z@_6B`bndVT96%7HH4zExIOOG;0ptlL$n?BJRRG$N2&FlY-V*d$ECoahWxiSk*lzmJKwLLFVT*SyqDoUn~P?X5DFeBwyo|6P%iIO$wUl~G_4}24% zdr6X&;7&WMC5=I-!vr!mpb7b235W^#{{Vh*S=Yh7As{G*ykC7}j36S|7v2=E@zJ_- zi5_SI1e0^lhwlK09m6!doy?qKK)I)$?@+~EMPidSoPpHu)92?JodgT4Et0X-PO?DZ zgHsI(3pnPTl6`#f zVpk3*aTH7p4s+39LUiL2f$&7n`;0A@Ky`ox2N8mRy;5(+Od12{l7v^Iw+b0b+wYB9 z2S)z@?g=H2V{4LtGAeid`pAgbVitDSraKZv+`+%?`p5-3Vg z?BS~Myb1*w7yJ0YbDYwZE&YEva6u6$TpdtJLy_at>zBBLASk?Cs1F_C5wZ?}63c6* z;~BdUa;#GAV}fuV!~p0eV)-^@{E|r}6+}=*yqA=`u$UG`jbGYwT^dtv$9r`wR;@^u zq@ePwvjvB#kc*K35U*5+5@7;?CsHzhb$}pPPxrP@z`>+bxbMf~20$_bvO&U(B=w6i zx~#wwPD0-#-VQa00{{pJSp=@I;sVP=M&Xtt%+FYkQw$VY@<{IX!Fd9i0BSiwI`qJi zl5B)GDI50VBnDWC(FN#$OFNUy6+Duux*NHPS$!)85+)l59?G9NAd*65-}uFlD=6Q2 zILo(nIn!Ivapwpbh>`&VyuO@_B&2JmzPJQq)be=a5f07!;S>qNbeRGG3?6VL2;lMG z_gMpt1bM(DNSAoX1&M4)>6-vZhS)^|omL3QBO<&QvTMoSSF|Sj#DhX%g74{wrb!O( z1>-`>#fG9{OH=Eto@~WqP7QHpj`ARqFz8N1nx?8TB$Q-@W1kp^BOz26 z646^|rF@iSAAe$XE4Mc4(95`gS-5q-M9+=1$EblBH=9#Q! zTC$2@o|~r=kP#}LaJP~I1Pb+oj*LJftW-$=u-cWgrjmBnIdbUO7YO?aUEw@aEu2bP z82n?HiB8Tz0+SOQI>IYv=ohFy9x$sXg{&zO2?<3OW6+ZTN(9crq?A;wLh)*es7xbC z&@H)Isl#~#6r5Q6p0H|DAmO*~j{XLEgozAG7}q8-E?@_)L3mT=DACs@BxLR{EQfBk z1c4+6X;q;3OUP5W0CUF~Con?T)K4)HkpO}L{ARnzvoR^wDN-j=BOtWhQY{ag^vK7V zZ~V$OM+&?$L3DTRfXNEPC;s5n(1fV%<#Hh?mE)X<1|$VuLM;tcLbwwOH_I3^^AUh> zm0*rP?hpikA&(SY))y%HvNuAlj$Bq-S=+1yBC#R%hb4p>x{t5w(D976D9Rf- zF^yvK4XMe4U>3L|`{j@9(mIV#-y=@;U(X0MvLe!Vi*zc4ugF^mjOI$G%e-+}3neG_ zIEfXa?G8Jo`sEymA%|bxV{p-GP5}*Pgn2OvJQ|~;1?K7rh&+FDjD(D`qYpB8lf~q8 zT87?e(fPzgz=)w!pt^6UF>MXz5U8GA@0!Jo0VVHy^!?&wp&+d&44oB04Ku&rt_kyS z+5y*&@v*=3ua60ZFQwm8I!^9g(bDA>%V`9AR!`;7$gCJR0J7yxcOqH(H#U*gX$4| zH=GxR_ZBD1>)sQAgFq0>P)WVp89m3M0}%&jm?tPGr}Sn@gKIYu*>raMV?C@WArVku zp$>)QZQ|IY8hSr@CV_Y3CxB`#gMZ&Ffg>PEV-f=J(Wl=V5F(b9A8ZV@srel15*Vc| zj=B8gDj_MQXPN%iSTajc6^SC$1jikG@={Pqz`zBiZ(I+i2^to!{qGpiBYk23lr%AU zz(G05q$1{}tBj<;yA+I6NmMRtjDU&~VkyaW$4ENLO^*)TQ(82VU;g0)7*H3=9 zo5T>@;}Q}Q7Jg%@;~dBU-Y~5YK-#lF1mY@YX&lRcRq$3v{;3%pn^WGL02Ujl-cnYc z^kt2@JTV|6DOHLfZ6^V=gr^WB%}ji>-U3J)ZbG~`Cv;*^c6_jKGRZ`pt>1^NU=ZpF zoxL~Lc%&lgH^tRNN;y`5C0fWs>7?9k7KG+D2F$`H4>bQR1E=5m1f6oLx5@Q1-9m~Q303R-lH$^utqY-z6 z=rVXp+H7=NbU+D0Nd7~RXV>BFctsx$5CoPAJ3NS<(~JQ}oj%xwC{?r`oZ%|!3KecI zck_&fl_42I?3D*`!Rdh@6$8;C!yMdjOGHqub%$Q)Y6T9YOW-@iyFrwK!@y1=0@~Ws zq>nR@45JSr~?TS{{R?iM6BKQ^!i{< zL<>vW*x}dKGsQ9!@|e6l(3Wy!9sh(@*@^IYw3_?Kmo7s^Dp4* z6o-V@c*UoLp)3x1`(g!0gkT7B!ZJ@y)-)MP%A~0YvYi%Hx8$ z5O%+gc)~^{i3;hl5+T%KV5RS{K?EaaB(M#AFaT&byo}GhiXyv&o&pWHxCR;oihaoU z%K%)|y6k4eu_Vg|7M$C0WIoQEG_B3pBlQ;v5mA@>`&j-HQXOH?P)?qo2x;??gG&uH zQ8Y6%>y!bWXWL$VGr_qvDJ6i~@Og|kG~CuQXaxc2Wa8@th#@Cp2YboSlSUFiK|UL9 zK6w(Dv=m#nvkAtRxD^jl5yvK!3w62LFtE_hXu6vHBrfq zx55$vf-;a!;;gyAh7JhM&$?KH3UuExz{y!>uUz-Xc*STE7?f)!Cj?1?TU3HDG{tY} zlP$=UfI2ZVxGf^&!Ud~JeR0s`F{UP1ImFpzP~TW;AaAapjE`Dd=;P~?8DNw!_MnP6 zPKO?2r6@kn9lga-XsJxUY+$J?DAaS&`p9Q^3TE4c@iND*2FMh^J7#8Q0u?1!engGO zwi1T`#DD5QPx_IM)y8xT`zWT<3%iCgZ%$lJ*Z|NXDxnq^p=X4%MLLavrtkMN5i|#-WW}qYa5N z+Gwli6kNHb2~@KZ>xeL`kb-!i2j3OJOWWI1NVi)LgFzyF-#q zJW)jN3V~BP&;g>M1R)b+vl6uG2bbSby>Am3On{7R1w55^kSrqtU|l9HiE_aU0achc ztd7Po$Q26ABF~(N^!8VF=g+)+5Oedc>1N z;G2KVuCf%iL}?Mjz;+hl8D&8K@0&=A!1^HM8hEm(<#lV{ z4nbjpXbu~ZVF+OE89hTNJC&K05N3GAEQy{}wdu#ULPN#NfdERBNqj!o)}i1T`KkFU zBhdS$+2pg)ImeEi3P?uMnfJs7!3lLZvDb0|g?9wc1$vs%vUp36L}5*B_$U;*50GZ_ zKWIYBAuw?=-lmDrIWLV#fu@*;B%3`!KVjT&lF zkIN9mEKX5VmS!}oq8B4sWQmi2&?DF_oupZ=NO*x0w0o5Y=3xSnLI9z=bj(O%O$Pxl ziB#5Y`kbo6xL|nTS zph3k*8P&VtjJm5`Q3;K%0Qwkh2vR0iiU^4DwadUMNg~l`S6N>V!wEu*B{uPh>@^^i zzgAArH92&}i%}!WK3=R)F&RZ+S}q>3&eWmt9F2gA$1GqFERq$hPFVT~#Y7N&nfzmh zs?O*wyz%><0bLWer864@GO0(= zZzfWI8$^7A3VLD}q`!;AW9qQg?}2-9?0b8@eGPW&|;^=2;$<(vzVmB^{7eZoP0WSg=qZvzXMRu$!3{01pbHiiKS3m8ue}H@btQ!v6 z>6s%GIVHM`30>52l&Bu4mcL^UNl$3XkOWan67jq;0uyj!@sWf%jdSNGvVc)4z0<5% zBt1-H&ndi<#xamc2qC&toSo8Xa)xj1=N(`<;w_(jeK7ez!j?}s=EYcPp4#UpE<%?7 z02xh8A(+tm;Gii4*dxdX3OJ2-^9*6yUspI=rapJ$C}52wX;k3-A^`y)d{v!5;>5sB zXe8=EIJ1nfj)5ApLS}cqadd#BACDN$`X0=v`hhgIWU@dR#1e$c9<15oM8xtxIMPa% zJO|?i$#bdF{&P~|xz_O{>XQVH8A*MAtZJ_R04t5W5JP!2oQRVOHoy|~fMTG&mH>>RH+pG-g^Ra$_;M4_4JnXt3~oy-e^W|V~|zqgR@ z7#E)cWKTyHX5@*B4hexbf zSIZE>1qZHB?Opjd;~>s11!BgRa|B1ePdx9C#2}uB=rT?}hmI`!lOV%k>E|eT2zm6t zP@TO#GLj{<@q*Ie7sK-Afbe_b-m$@hAq1I>ZD8~uzO>8V7@gEu>_h$Sf>S~iJ<0i) z(Lz`T*v67oS))UM$iAUc1B66!$6Ey)9^^~4z=`O;Ztyso&`NSdXE?mH8LVFfGE0b<-wl0 z3IGtc631oZI4-5hTf0#_dC9Hn*<-eG6EEl=oE)3j6#V7ksFNMPIXFblOB6j6KBsu6 zUfRMLt;p?&7fRs~W9%mBB_Cdsk;5P~Bno)|F!Ezj#|l9idrnBDm~D`GUdlUhFvQu4 zZaI0#!gZFsagq`Q#aJ?w{*W4tmSeNV1@8fsUgUlG5UvfW%ff8wG8o9kB6M*iKKPXh z4@8ftGw4`I26#b)P8q~(t5L9cKzulA6f*!R@;EuPePDiaAegGlQ^-m=h{fXvNEr#? z9D&*}O7-JKvP_nXE36O+Pwj{v1qQLa0VmV`u}S0TumBRp$~Aoc_$Y)3*C*#8!XxkS zKnBReQp!`3K$M|7IGy5(A$3Kq=ZnbzAu5s_vtf8|L$+dU`dN{T84wN&X=ACvQat2j zqQAF=2%9Av?CPI)q>hP-A*oVq-K6q@R(L1Wl+e zQ0%mQGD^CV*hY6R1IXpw>VP2_U58U|thO$UX0aSFjyDqVh(bwv65DdxiM9P1ERMoD6FBuGxoIx-S>A&;&5EEk&+gDw2GSmbWwOP;GhANgM`uPw>1+XVArJAWp$jlLn>5kLS{&j+yPbS zL;we@ZwOR`LMqw`u0anDAp;~&n=!Ns_6}tBqh#<o*rYSO?4#=5WiMX>RQ!M*^Mw0r6rU+VB-d)EEYOcbVf6#-GIOz!#*r*a=*Y(R(Q>N1G6SL6{JPZi&!)e zae!D9p4KFoNf0cJ`oBDtN%q?l^~n}EGJ>#niiaYbj5ZXYLhMNp4ormR6STC}v~t!` zh!a=^4uvPnl7$XZkc-jG^%(&(Dl(HX#On%heP;wo3Q>%a%!ns9_!P-&l^osMB@*>9By_Q^PFBA($qiekg{90y=TPuC$^>II6F zA0fCsZLRlSt@S|f*45L(vkxwauX{Nwn1FFIem6Bqf zh}%*=FtLCeULIi&351MMrfVReMf&VXHt*9Mikr7@rXZwBP2YmV07${x%qsVA2dSPzh$6(!Nj!E-1a zYOi;!CfJg*F}cSsq%Ic-1uN%=!9YU$>^x+wtZ`U@A{g$NdzK^=kO2iKDpqa|3_sP? z0T~70Qa$iBaY>lKIKCY)L%(jkK9yi))WkYqA(fhA~3ne{JSWd8sXG?P2&r!NRy zQ^w}Vw{Xu{}Ok`c40#d~FG3kTDCKfAA12R3}9C0_e z5=Yi~!A?=KZP&GPg2qdYilp-G^=Az+1^}*H*$KopPo@$EcEE7D!Gqftr(7KfZQSEg z#Nn8&V$+L<$EUHE3?P^L`;1_K=+?3#*%Wz_vI)paw)=Zz4S58LV;+J=N=XrkOQaQ% z>K&0IbHfPkW!@yf1XhU1;iAdq$eH}oucL)VIhv< zE*9GL$V7B&G20$8NqGs0daQ6k5Q4Hs2qHxxj$oS2Vs@tKj_?{b<59z)^`gfi6a#|? z=@LRH<%(snqh^dmG7nvuVFC@Nj^~UOnimBNv)cps4Xa=P&*RvK#Q0x(->y^gpOC?KGM8`NVDpGLt;=ySZ$J}y< zkR3gUbP#-Y0zXcd0bM-x&%QGmq|7`S11$%m*Cv*VcsNBJTahNIP>C2)@-%VqV0ujWg83ytuCVet+CU!@p@*YCm|$8o`JYy`$H72oOljOFPRb1ftr{?8gWM z3Er;pV3P=FSB!#*V|G|!^Yn~LYAp#-KN~R1DiG8aO&C*R$Grv>cCYUj1#C4HKvg)!z67PA-)Cf$;?ZM2?_xp}H zrYs2yBUntLK*EnE@9l$hx`|tt_VU4t02FKcoD|rY(1$PU34}tDi|gUMPlY);{ESkS zP~6dy6aWesTKr%FI#PFS`(Yz0BpQBMA)t(|D1!Ylgrt!?e(^&iEXbBS@sA(^snqmi z%?yEb7*Lu?OL&-OP$Zd-{+I-kOi8={0Jz!HO#*#!T?QIH?nfhIWJni-DwvS(S^?V^ zB&|HqCN81>0J!=5)%#ap>3K^=c}n}M{Dar(uGA0aV>ofrc;Nv5>m zVZ0qYh{ww|A9Y0&ws^^!q!sLZRzl(w&BA!buuo#-~7qHfrMpAib@|LSQ5qgO%X#+bNqU zM9!V!h(69>(s>;j3<_+A4oE3RzwSl2LLWV2fXzmg3_h&N(yP3gVSM+3V#tEy`1;_` zn~Ok^`SIrzWT>DR*{FGX!$urD5OCfB2~OLY`9@D*DI2c+KA5CtB?EIG-)s`%jT?YZ z$jAVRZOq{cSgK-zV^fc#qf(y!xLEy>9>4BVMH)jU#0Z7w9wAs|89DULA=8K~#9aB! z6o^oX<9zz%^q0e!`>;C3sOR{}?0hAnkZ)-k#Nlp1l*5p)Pj`)|4l+2j0d&P0LR$U;7Avutnt=JbB+GA+0@13D_8fTUHSN_i1*8VNyc!{B_4 zFKlS$9KkJQB!ILCjs!sQfTXgYBij|#p)3$PG*@mEGtXiQ!Fn8&K{yz~PRJPX&y0#t zOg6%#t;iDZ@f^+u$Jc>ckL_TDQq54T1Bm(74W`u3TTaVV8DV6xadm>4Z?b7Cdqi;(qQ^wM@o&ryXvs1p2#CcNJmhu zyv}#F(sJW-^T$~%ZhdhMvECB|5&($nc>XtOjf=d6K{IUvH1h)chYSLsBh^p$jzBS%S3YxT-u@#7B zb*|!ZYF+`{KP;3E;GH(>-wEgeM}9iX7GZ2`Ke@;f+8J!XP}#O@pX-SN8c`{;0uq$| zgZRSd>m{HxN{4ZC#wrt1;|UxEv9Z+cx9DnMKF^F;giy_E!IAVaD5!$zCMY!Im&fP? z3&kVRaX?K3WKsb25-TuL%uXr%C4m{zAEhnT~=h@&HbmLQ4iIG`bV z#)X)BAK#qSuoyzGh%m>nP9gxP-sf1H4=55V0IH~?wlRncyNLpuLM33MD$4ng3?!Ql z=ZuvvATb4N3WvTtpR|HSw@WOo9pa!qfOTStNsd<+>tTZ_1)%6g*_n(|ha)2%_!VS{K_FxgtGpc$7BT4grIq1%1T{U+%z?pB~ks}C}4sL6Kv?bkm)Uzge~J^ ztbj&U8`tH{Q=?JmuSoXKd@?9F`!Pl0a7pfJzwU6l%c4lBgEIz;gAWvd%tO?v!rvv99t6X^{EhCKL=a5b>z>!Gu9;Dan$y zHBqnc=L^(MTdyh4{l-H&1cpo5M8Q8lmIg^)K&S#U%;oDyp))doGVsnS2|X}Y!o4t& z)khH#>LfcnAH4eLNW+wi?{?t7^t$4*Vh1r!ZdRY&=tw z%R(6}VVZ)*{O$v5&pr+={DOwu1-^ zwh@Fe;jC`>5CfYc3)b?~SQfUZNgQJI3KdumgedEbKt_qy0M`lOH;|yDGjH?rf^-W6 z?jL9GiHd4o8_M8CvO!4mh|;@j1u4OrNk87%I0W+EzHy6O^ryi!t*K@5TibaG*qYZ_gAowrH3^fdfbf ztn5HeHT1<230j)NjkbqJ=*R@oFM?BGnPws*c&R`vLqT~;Ix6vsHn%ZmS~EGadBRVL z%*?MldOmr(6j%ie@qm>ROH%&7Sk&Ut0uefs=`d}^aFaqDr~}+%ISjgu?tfzx12-WV z=3FNuj+g9I07SNtIQPZ83aLp@snG6+zA*8_s$-@RKj09c| z>Vajpo5+}yG{o;j%wmKmIEaZL5f-rOX+WS5-2@{gZe}p55KCb#fRlCvwU7qK!nsGJ zee(36{Kr|6WZXTHm{gGngGA99oZMc1B~8!vu~v9(LmYj6*nQuMMpX32+YGS;M9VlO z3n7^jdNgCos*uYo^mr%=#3Uf_qw9`D%2`%ISYnL^H!nC;pjO3o-a)uTtyTljVqrvc zJK}J)7dMvRp<>{?k{m*|F?)y;5(u6t#R!Kq`C$){gr$`l=XXEO7iObHl~5(ncrsgz z076Nm@;zfDMFCLxcrmz+AQCndyi86U-9OG6gqXlMKMd4VXnT2NK%|99lxyvTi3q8M z^u~!{)|kk6>KK#^UKG*##^3}%0(N;Ky>XDNAlSZMR{{_yx7B1_0HWS8A>f0p7^RKW zYt99u7(z~gxIEFkD5F$GN)e{YolIj=uxyl+1sOK;cysZXNE8(*gQFLNew89RqntR4 zV)dWKBRMsND}l94VE}&x2y_LKUgIBL64ZhcOfba5y_ms;WoQhB;vxnidBoA^m`<5! zO{~V(yhEu7)+Pi>kh9mEF%^}lt;_bptnxY&Fuc6Rsxb&5Q%?pkAV8ACY;WHn!kj3# zSV9mXeAY`GAwh8d_mqai3I?G+!;I8OL>AEVafZZHWh>XlFpyybncs@dhy>eFJ!D-p z#Fg^F+%oAUt>8$AVlqP&{o@+otC3UIOA&+sjUu*nnkkwE;FMe_bo2SdWTdPVHR>^w z5YR+)?*ULEldKuN210~jlr@qvFdpnF1nsNBcp|c&TFc<^?FyW@1458BtdA?~Zzk+D z7puhRiiWz4VKh<$g)jG!APLdm_u~TM8hv++!S#M|>5$txObdV<>{g;i`*P59MTE|5 z0eYG7fTBer#;^gQRMKK5d&-xwpE#6`ERL@XikL>kWe9Y17X}e!z>I*Xgr|OgyTJtn zmdXjl3nF5&uo+Sho=#H3IBf&~wrB4+cFq_OY3{_e7e>rH4y2!Q8Gw12pv69_J1m{< zvKFaY$@mcLFwb7G^1^_Xq_zMbI3NUwpzJ;l-LdV06n2S15pas(M7iq#V(ild0HGGC zwZ@h*cj6&p?lopM1lRx$;D?w#xUNu0A=uBW9=S@95gh5-#PKFfFwhNeJK~~tnBFzS zf{c)JjewUz#U6XeO|_ES=N2jj5}BXZ*CLgG3S5%UrnA}QSv~&%oZ==Sij;!~j8xDs z6C=0fjKyPNjgtc0unM&pKoY4A`BRFFRJG|i?5s~hMkK^&yr>}tjNnNHR8I~?eD@e& zM9LsYHXtTYIi)Jhnnb^FD%$S$`yas(*j z84##Rt_Q#SgsiY7M(~14f*0Oi&@+pFrz&bwUEqci%|sy?00LMyIL_H^W`_eg056Cf z=aK*=hA0^lA51{Y0#%RezzC}#T=O`$6%c|6jtjZRiNYj>!-Ym;#xn>|sULkz<68zC zB{AfQAUpNKfkF@x*ymqdgmYv7s7)dU15*>mNZ@FJW#H<;QhP9)Kq6U%meWJIftj3{ zB?5lf5R4cw6Rgn3gfJ5&72fh#1$bZvC&(%D$P9F=P(?6H;wg0#dx~J0p+#tDnmQ4Z zPy#w{qk^Ru8A+Y^c^KYMkr6gDX)Ru!xRKqVlC*1gsE2jl6?B5YQ|kd<4)Nw74_hz6ahZa`W& z#l}ED(-(l2R{&s`Ehu`xoJbb3Dhd4Y5@~t4$Us0giJR5{8&_x5#xivKj8GM&Z+sXS1TRZj3c(6vs%IM+dxPHIgAMjaCAJ!bM0y z%==au9RSiwMm16Crx7tEfe6`C_L#~^VgcbUnQ6A1MO4^lcHuohlBBkvQSx2WhMyEcCq`LM z28@7grvb5z>D(He;tEZdjRzKurBmRVL}pVKVIP!2+F@s1MlO{=XgqNb8^H>Ix$uhiw8M7a}E1sGBw4V!TZ3H0dQRS>m&|PqGLou5lFfH zU@8KohO#^%TMPh&!W}IAG1StCszDI=!iM#LK$r8DrHrg`gf!shdc*cVs!84iVs&43rx!}mv(cKKqLxCVo81uaA!%_S?OvJObq6YsVa(u^>5P*P#{c3 zk_IndUxCg9$ih7^1`*JRB}pX?(r_#&2!OtZA3XD%B*_$+?%Q!-DM$#8<(?;?IU~jE z7zO8Gb=>gb1)gt@^auO1k|3X&PZiVLtohs3^^ zN+7L?Nq z!MW3cnYQh;f&_WKCjl9lfS+r6<3^W(cW~3&4nhZMeIhZ+xB=gj@4^Zg0u!Z#!SdD> zALLMi_C$@7a?o_GXIKzlS`5XU4deeWP`Bnvq6yq50}84`u2+VPSw zV1$c4f8!LGxXb-wMiLnj&IFxJu$`~@$IJy?yE3?eiTA{nB(T<_Tfm%FlGaQ@1ekqK zt{CRY5l`Qo1`;<=;-(pe(E8-ms93l?awt+e7X0I=;cK&7aD!!}1brDIsfnmH>yc6s z6c7w{v~Y09?c|ED`rzs64 zY?yLrjHi=%P*f8zteJQa#iliZ0G`h-NdyFa`N%^-6_g;5^nHK2&Gw$p9NrV5L}lMM0@LOA!D>Z#MX8zkxZVMLvh`2xsV@yf6C?-XG(iyb6B@?-QS}e(@Ol zZ{8o~KX^Cle(;fFxPI`d<VtzsU%fAcvnjdHPkNEH2DF#1B?+gC` cN&C<9Z{BYEXYT=_uj2A)`9IyC^IyFG*}s literal 0 HcmV?d00001 From 08233aa1ac9af1ac777c4f10258951af9c381aeb Mon Sep 17 00:00:00 2001 From: Timothy Ellsworth Bowers Date: Mon, 9 Feb 2026 10:46:31 -0700 Subject: [PATCH 06/22] Update vendor dependencies (#138) * Update PhotonLib * Update YAGSL * Revert Phoenix libraries to non-replay versions -- YAGSL no longer depends on the replay versions of the Phoenix 5/6 libraries. * Update PhotonLib to 2026.2.2 --- ...eplay-5.36.0.json => Phoenix5-5.36.0.json} | 88 ++++--------------- ...c2026-latest.json => Phoenix6-26.1.1.json} | 76 +++------------- vendordeps/photonlib.json | 12 +-- ...l-2026.1.30.json => yagsl-2026.2.3.1.json} | 18 +--- 4 files changed, 42 insertions(+), 152 deletions(-) rename vendordeps/{Phoenix5-replay-5.36.0.json => Phoenix5-5.36.0.json} (68%) rename vendordeps/{Phoenix6-replay-frc2026-latest.json => Phoenix6-26.1.1.json} (87%) rename vendordeps/{yagsl-2026.1.30.json => yagsl-2026.2.3.1.json} (64%) diff --git a/vendordeps/Phoenix5-replay-5.36.0.json b/vendordeps/Phoenix5-5.36.0.json similarity index 68% rename from vendordeps/Phoenix5-replay-5.36.0.json rename to vendordeps/Phoenix5-5.36.0.json index 7fbfcf5..c60dd4c 100644 --- a/vendordeps/Phoenix5-replay-5.36.0.json +++ b/vendordeps/Phoenix5-5.36.0.json @@ -1,31 +1,31 @@ { - "fileName": "Phoenix5-replay-5.36.0.json", + "fileName": "Phoenix5-5.36.0.json", "name": "CTRE-Phoenix (v5)", "version": "5.36.0", "frcYear": "2026", - "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", "mavenUrls": [ "https://maven.ctr-electronics.com/release/" ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-replay-frc2026-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2026-latest.json", "requires": [ { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", - "offlineFileName": "Phoenix6-replay-frc2026-latest.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-replay-frc2026-latest.json" + "offlineFileName": "Phoenix6-frc2026-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json" } ], "conflictsWith": [ { - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "errorMessage": "Users must use the regular Phoenix 5 vendordep when using the regular Phoenix 6 vendordep.", - "offlineFileName": "Phoenix6-frc2026-latest.json" + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" }, { - "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", - "offlineFileName": "Phoenix5-frc2026-latest.json" + "offlineFileName": "Phoenix5-replay-frc2026-latest.json" } ], "javaDependencies": [ @@ -47,22 +47,11 @@ "version": "5.36.0", "isJar": false, "skipInvalidPlatforms": true, - "validPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.replay", - "artifactId": "cci-replay", - "version": "5.36.0", - "isJar": false, - "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", "linuxarm64", - "osxuniversal" + "linuxathena" ], "simMode": "hwsim" }, @@ -91,6 +80,9 @@ "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -104,6 +96,9 @@ "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -116,56 +111,11 @@ "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.replay", - "artifactId": "wpiapi-cpp-replay", - "version": "5.36.0", - "libName": "CTRE_Phoenix_WPIReplay", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", "linuxarm64", - "osxuniversal" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.replay", - "artifactId": "api-cpp-replay", - "version": "5.36.0", - "libName": "CTRE_PhoenixReplay", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.replay", - "artifactId": "cci-replay", - "version": "5.36.0", - "libName": "CTRE_PhoenixCCIReplay", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" + "linuxathena" ], "simMode": "hwsim" }, diff --git a/vendordeps/Phoenix6-replay-frc2026-latest.json b/vendordeps/Phoenix6-26.1.1.json similarity index 87% rename from vendordeps/Phoenix6-replay-frc2026-latest.json rename to vendordeps/Phoenix6-26.1.1.json index 75532e9..c0a1c19 100644 --- a/vendordeps/Phoenix6-replay-frc2026-latest.json +++ b/vendordeps/Phoenix6-26.1.1.json @@ -1,18 +1,18 @@ { - "fileName": "Phoenix6-replay-frc2026-latest.json", - "name": "CTRE-Phoenix (v6) Replay", + "fileName": "Phoenix6-26.1.1.json", + "name": "CTRE-Phoenix (v6)", "version": "26.1.1", "frcYear": "2026", - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ "https://maven.ctr-electronics.com/release/" ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-replay-frc2026-latest.json", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json", "conflictsWith": [ { - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", - "offlineFileName": "Phoenix6-frc2026-latest.json" + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" } ], "javaDependencies": [ @@ -29,39 +29,17 @@ "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, - "validPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "26.1.1", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "api-cpp-replay", - "version": "26.1.1", - "isJar": false, - "skipInvalidPlatforms": true, "validPlatforms": [ "windowsx86-64", "linuxx86-64", "linuxarm64", - "osxuniversal" + "linuxathena" ], "simMode": "hwsim" }, { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "tools-replay", + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", "version": "26.1.1", "isJar": false, "skipInvalidPlatforms": true, @@ -69,7 +47,7 @@ "windowsx86-64", "linuxx86-64", "linuxarm64", - "osxuniversal" + "linuxathena" ], "simMode": "hwsim" }, @@ -252,6 +230,9 @@ "sharedLibrary": true, "skipInvalidPlatforms": true, "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", "linuxathena" ], "simMode": "hwsim" @@ -264,40 +245,11 @@ "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "wpiapi-cpp-replay", - "version": "26.1.1", - "libName": "CTRE_Phoenix6_WPIReplay", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", "linuxx86-64", "linuxarm64", - "osxuniversal" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.replay", - "artifactId": "tools-replay", - "version": "26.1.1", - "libName": "CTRE_PhoenixTools_Replay", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" + "linuxathena" ], "simMode": "hwsim" }, diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index b0ac8fb..6279e58 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,7 +1,7 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2026.1.1", + "version": "v2026.2.2", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2026", "mavenUrls": [ @@ -13,7 +13,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.1.1", + "version": "v2026.2.2", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -28,7 +28,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2026.1.1", + "version": "v2026.2.2", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -43,7 +43,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.1.1", + "version": "v2026.2.2", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -60,12 +60,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2026.1.1" + "version": "v2026.2.2" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2026.1.1" + "version": "v2026.2.2" } ] } diff --git a/vendordeps/yagsl-2026.1.30.json b/vendordeps/yagsl-2026.2.3.1.json similarity index 64% rename from vendordeps/yagsl-2026.1.30.json rename to vendordeps/yagsl-2026.2.3.1.json index aaee5a3..b783dcd 100644 --- a/vendordeps/yagsl-2026.1.30.json +++ b/vendordeps/yagsl-2026.2.3.1.json @@ -1,7 +1,7 @@ { - "fileName": "yagsl-2026.1.30.json", + "fileName": "yagsl-2026.2.3.1.json", "name": "YAGSL", - "version": "2026.1.30", + "version": "2026.2.3.1", "frcYear": "2026", "uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400", "mavenUrls": [ @@ -13,7 +13,7 @@ { "groupId": "swervelib", "artifactId": "YAGSL-java", - "version": "2026.1.30" + "version": "2026.2.3.1" }, { "groupId": "org.dyn4j", @@ -34,18 +34,6 @@ "offlineFileName": "REVLib.json", "onlineUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json" }, - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Phoenix6 Replay is required!", - "offlineFileName": "Phoenix6-replay-26.1.0.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-replay-frc2026-latest.json" - }, - { - "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", - "errorMessage": "Phoenix5 Replay Compatibility is required!", - "offlineFileName": "Phoenix5-replay-5.36.0.json", - "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-replay-frc2026-latest.json" - }, { "uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0", "errorMessage": "ThriftyLib is required!", From 35964c54aecb37c8140bf7c97d79a742c30ccbb7 Mon Sep 17 00:00:00 2001 From: Timothy Ellsworth Bowers Date: Mon, 9 Feb 2026 10:52:05 -0700 Subject: [PATCH 07/22] Add a "RBSI-standard" AdvantageScope layout (#131) * Add a "RBSI-standard" AdvantageScope layout -- Primarily for tournament troubleshooting by CSA's. * Revert drivebase power port assignments -- No changes to be pushed to teams in case they already updated these in their templated code. --- AdvantageScope RBSI Standard.json | 541 +++++++++++++++++++++++++ src/main/java/frc/robot/Constants.java | 16 +- 2 files changed, 549 insertions(+), 8 deletions(-) create mode 100644 AdvantageScope RBSI Standard.json diff --git a/AdvantageScope RBSI Standard.json b/AdvantageScope RBSI Standard.json new file mode 100644 index 0000000..67dc05a --- /dev/null +++ b/AdvantageScope RBSI Standard.json @@ -0,0 +1,541 @@ +{ + "hubs": [ + { + "x": 71, + "y": 33, + "width": 1315, + "height": 776, + "state": { + "sidebar": { + "width": 300, + "expanded": [ + "/RealOutputs", + "/RealOutputs/LoopSpike/Drive", + "/RealOutputs/Drive/OdomThread", + "/RealOutputs/CAN/DriveTrain", + "/RealOutputs/CAN/Module0", + "/RealOutputs/LoopSpike", + "/AdvantageKit", + "/RealOutputs/Loop/Drive", + "/RealOutputs/Loop/Mech", + "/RealOutputs/Odometry/Yaw", + "/RealOutputs/Vision/Camera0", + "/RealOutputs/Vision/Camera0/TagPoses", + "/RealOutputs/Vision/Summary/TagPoses", + "/RealOutputs/Vision/Camera1/RobotPosesAccepted", + "/RealOutputs/Vision/Camera0/RobotPosesAccepted", + "/RealOutputs/Power", + "/RealOutputs/Power/Subsystems", + "/NetworkInputs/SmartDashboard", + "/RealOutputs/Loop", + "/RealOutputs/Loop/Virtual" + ] + }, + "tabs": { + "selected": 7, + "tabs": [ + { + "type": 0, + "title": "", + "controller": null, + "controllerUUID": "27w43phb8fm0oyp20p0wxms1a35yrw0i", + "renderer": "", + "controlsHeight": 0 + }, + { + "type": 2, + "title": "2D Field - Odometry", + "controller": { + "sources": [ + { + "type": "robot", + "logKey": "/RealOutputs/Odometry/Robot", + "logType": "Pose2d", + "visible": true, + "options": { + "bumpers": "" + } + } + ], + "field": "FRC:2026 Field", + "orientation": 0, + "size": "large" + }, + "controllerUUID": "ibthfkqod1n0vovjoxhcg2d9954wcpe4", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 2, + "title": "2D Field - Vision", + "controller": { + "sources": [ + { + "type": "robot", + "logKey": "/RealOutputs/Odometry/Robot", + "logType": "Pose2d", + "visible": false, + "options": { + "bumpers": "" + } + }, + { + "type": "arrow", + "logKey": "/RealOutputs/Vision/Summary/TagPoses", + "logType": "Pose3d[]", + "visible": true, + "options": { + "position": "center" + } + }, + { + "type": "ghost", + "logKey": "/RealOutputs/Vision/Camera0/RobotPosesAccepted", + "logType": "Pose3d[]", + "visible": true, + "options": { + "color": "#00ff00" + } + }, + { + "type": "ghost", + "logKey": "/RealOutputs/Vision/Camera1/RobotPosesAccepted", + "logType": "Pose3d[]", + "visible": true, + "options": { + "color": "#ffff00" + } + } + ], + "field": "FRC:2026 Field", + "orientation": 0, + "size": "large" + }, + "controllerUUID": "u9myuirzag5qydjp9nozn8qxpfqofuuq", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 9, + "title": "Swerve", + "controller": { + "sources": [ + { + "type": "states", + "logKey": "/RealOutputs/SwerveStates/Measured", + "logType": "SwerveModuleState[]", + "visible": true, + "options": { + "color": "#ff0000", + "arrangement": "0,1,2,3" + } + }, + { + "type": "states", + "logKey": "/RealOutputs/SwerveStates/SetpointsOptimized", + "logType": "SwerveModuleState[]", + "visible": true, + "options": { + "color": "#00ffff", + "arrangement": "0,1,2,3" + } + }, + { + "type": "rotation", + "logKey": "/RealOutputs/Odometry/Robot/rotation", + "logType": "Rotation2d", + "visible": true, + "options": {} + }, + { + "type": "chassisSpeeds", + "logKey": "/RealOutputs/SwerveChassisSpeeds/Measured", + "logType": "ChassisSpeeds", + "visible": true, + "options": { + "color": "#ff0000" + } + } + ], + "maxSpeed": 5, + "sizeX": 0.65, + "sizeY": 0.65, + "orientation": 1 + }, + "controllerUUID": "zo4ukgbiguacvfe9e2iui2ytosl7gutn", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "Power", + "controller": { + "leftSources": [ + { + "type": "stepped", + "logKey": "/PowerDistribution/Voltage", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + } + ], + "rightSources": [ + { + "type": "stepped", + "logKey": "/PowerDistribution/TotalCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Power/Subsystems/DriveCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Power/Subsystems/SteerCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#e48b32", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Power/Subsystems/FlywheelCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#c0b487", + "size": "normal" + } + } + ], + "discreteSources": [ + { + "type": "stripes", + "logKey": "/RealOutputs/Power/BrownoutImminent", + "logType": "Boolean", + "visible": true, + "options": { + "color": "#af2437" + } + } + ], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "9vyygyem9we0y5917klbu25cz9hruszx", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "CAN Health", + "controller": { + "leftSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/CAN//Utilization", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/Utilization", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + } + ], + "rightSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/RxErrorCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#af2437", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/TxErrorCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN//RxErrorCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#e48b32", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/TxFullCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#c0b487", + "size": "normal" + } + } + ], + "discreteSources": [], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "f15s8kcvuqce63dlc7cf4yunt6c0372w", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "Loop Time - Robot", + "controller": { + "leftSources": [], + "rightSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/FullCycleMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/GCTimeMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/LogPeriodicMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/UserCodeMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#af2437", + "size": "normal" + } + } + ], + "discreteSources": [], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "yktsi99006yw1sq2h8mihr8kiy9h5xk9", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "Loop Time - Subsystems", + "controller": { + "leftSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Mech/Drive_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Mech/Flywheel_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/Accelerometer_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#af2437", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/RBSICANHealth_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/RBSIPowerMonitor_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#e48b32", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/Vision_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#c0b487", + "size": "normal" + } + } + ], + "rightSources": [], + "discreteSources": [], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "no6ewy1a2lc06qvs7einn5i430wwub9n", + "renderer": null, + "controlsHeight": 195 + }, + { + "type": 3, + "title": "3D Field", + "controller": { + "sources": [ + { + "type": "robot", + "logKey": "/RealOutputs/Vision/Summary/TagPoses", + "logType": "Pose3d[]", + "visible": true, + "options": { + "model": "Crab Bot" + } + }, + { + "type": "robot", + "logKey": "/RealOutputs/Odometry/Robot", + "logType": "Pose2d", + "visible": true, + "options": { + "model": "2026 KitBot" + } + } + ], + "game": "FRC:2026 Field" + }, + "controllerUUID": "x1j1ypjwdchzmk115shjrh4ml6w4osq9", + "renderer": { + "cameraIndex": -1, + "orbitFov": 50, + "cameraPosition": [ + 1.4695761589768238e-15, + 5.999999999999999, + -12 + ], + "cameraTarget": [ + 0, + 0.5, + 0 + ] + }, + "controlsHeight": 200 + } + ] + } + } + } + ], + "satellites": [], + "version": "26.0.0" +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 26f2525..3b31b77 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -180,30 +180,30 @@ public static class RobotDevices { // Front Left public static final RobotDeviceId FL_DRIVE = - new RobotDeviceId(SwerveConstants.kFLDriveMotorId, SwerveConstants.kFLDriveCanbus, 16); + new RobotDeviceId(SwerveConstants.kFLDriveMotorId, SwerveConstants.kFLDriveCanbus, 18); public static final RobotDeviceId FL_ROTATION = - new RobotDeviceId(SwerveConstants.kFLSteerMotorId, SwerveConstants.kFLSteerCanbus, 17); + new RobotDeviceId(SwerveConstants.kFLSteerMotorId, SwerveConstants.kFLSteerCanbus, 19); public static final RobotDeviceId FL_CANCODER = new RobotDeviceId(SwerveConstants.kFLEncoderId, SwerveConstants.kFLEncoderCanbus, null); // Front Right public static final RobotDeviceId FR_DRIVE = - new RobotDeviceId(SwerveConstants.kFRDriveMotorId, SwerveConstants.kFRDriveCanbus, 13); + new RobotDeviceId(SwerveConstants.kFRDriveMotorId, SwerveConstants.kFRDriveCanbus, 17); public static final RobotDeviceId FR_ROTATION = - new RobotDeviceId(SwerveConstants.kFRSteerMotorId, SwerveConstants.kFRSteerCanbus, 12); + new RobotDeviceId(SwerveConstants.kFRSteerMotorId, SwerveConstants.kFRSteerCanbus, 16); public static final RobotDeviceId FR_CANCODER = new RobotDeviceId(SwerveConstants.kFREncoderId, SwerveConstants.kFREncoderCanbus, null); // Back Left public static final RobotDeviceId BL_DRIVE = - new RobotDeviceId(SwerveConstants.kBLDriveMotorId, SwerveConstants.kBLDriveCanbus, 2); + new RobotDeviceId(SwerveConstants.kBLDriveMotorId, SwerveConstants.kBLDriveCanbus, 1); public static final RobotDeviceId BL_ROTATION = - new RobotDeviceId(SwerveConstants.kBLSteerMotorId, SwerveConstants.kBLSteerCanbus, 3); + new RobotDeviceId(SwerveConstants.kBLSteerMotorId, SwerveConstants.kBLSteerCanbus, 0); public static final RobotDeviceId BL_CANCODER = new RobotDeviceId(SwerveConstants.kBLEncoderId, SwerveConstants.kBLEncoderCanbus, null); // Back Right public static final RobotDeviceId BR_DRIVE = - new RobotDeviceId(SwerveConstants.kBRDriveMotorId, SwerveConstants.kBRSteerCanbus, 7); + new RobotDeviceId(SwerveConstants.kBRDriveMotorId, SwerveConstants.kBRSteerCanbus, 2); public static final RobotDeviceId BR_ROTATION = - new RobotDeviceId(SwerveConstants.kBRSteerMotorId, SwerveConstants.kBRSteerCanbus, 6); + new RobotDeviceId(SwerveConstants.kBRSteerMotorId, SwerveConstants.kBRSteerCanbus, 3); public static final RobotDeviceId BR_CANCODER = new RobotDeviceId(SwerveConstants.kBREncoderId, SwerveConstants.kBREncoderCanbus, null); // Pigeon From 13962fd189cbe17cb6a7deb0f1ddeeafe5659cff Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 26 Jan 2026 04:11:49 +0000 Subject: [PATCH 08/22] Bump com.diffplug.spotless from 8.1.0 to 8.2.0 (#121) Bumps com.diffplug.spotless from 8.1.0 to 8.2.0. --- updated-dependencies: - dependency-name: com.diffplug.spotless dependency-version: 8.2.0 dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 4df38fa..152cc20 100644 --- a/build.gradle +++ b/build.gradle @@ -2,7 +2,7 @@ plugins { id "java" id "edu.wpi.first.GradleRIO" version "2026.2.1" id "com.peterabeles.gversion" version "1.10.3" - id "com.diffplug.spotless" version "8.1.0" + id "com.diffplug.spotless" version "8.2.0" id "io.freefair.lombok" version "9.2.0" id "com.google.protobuf" version "0.9.6" } From e313e27155746a205856ad1f5f30c22a27eff50a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 31 Jan 2026 02:09:08 +0000 Subject: [PATCH 09/22] Bump com.diffplug.spotless from 8.2.0 to 8.2.1 (#129) Bumps com.diffplug.spotless from 8.2.0 to 8.2.1. --- updated-dependencies: - dependency-name: com.diffplug.spotless dependency-version: 8.2.1 dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 152cc20..8334e36 100644 --- a/build.gradle +++ b/build.gradle @@ -2,7 +2,7 @@ plugins { id "java" id "edu.wpi.first.GradleRIO" version "2026.2.1" id "com.peterabeles.gversion" version "1.10.3" - id "com.diffplug.spotless" version "8.2.0" + id "com.diffplug.spotless" version "8.2.1" id "io.freefair.lombok" version "9.2.0" id "com.google.protobuf" version "0.9.6" } From 2b8c50e2979b173ebe7c316b05731ff8d03044b4 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Mon, 9 Feb 2026 16:33:50 -0700 Subject: [PATCH 10/22] Call the pose estimator "TimedPose" --- .../frc/robot/subsystems/drive/Drive.java | 4 +- .../frc/robot/subsystems/vision/Vision.java | 44 +++++++++---------- .../util/{RBSIPose.java => TimedPose.java} | 2 +- 3 files changed, 25 insertions(+), 25 deletions(-) rename src/main/java/frc/robot/util/{RBSIPose.java => TimedPose.java} (89%) diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 041a0e6..71b9e37 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -51,8 +51,8 @@ import frc.robot.util.LocalADStarAK; import frc.robot.util.RBSIEnum.Mode; import frc.robot.util.RBSIParsing; -import frc.robot.util.RBSIPose; import frc.robot.util.RBSISubsystem; +import frc.robot.util.TimedPose; import java.util.Optional; import java.util.OptionalDouble; import java.util.concurrent.locks.Lock; @@ -743,7 +743,7 @@ public void zeroHeading() { } /** Adds a vision measurement safely into the PoseEstimator. */ - public void addVisionMeasurement(RBSIPose rbsiPose) { + public void addVisionMeasurement(TimedPose rbsiPose) { odometryLock.lock(); try { m_PoseEstimator.addVisionMeasurement( diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index c7849e3..86c1055 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -32,7 +32,7 @@ import frc.robot.FieldConstants; import frc.robot.subsystems.drive.Drive; import frc.robot.subsystems.vision.VisionIO.PoseObservationType; -import frc.robot.util.RBSIPose; +import frc.robot.util.TimedPose; import frc.robot.util.VirtualSubsystem; import java.util.ArrayDeque; import java.util.ArrayList; @@ -48,7 +48,7 @@ public class Vision extends VirtualSubsystem { /** Vision Consumer definition */ @FunctionalInterface public interface PoseMeasurementConsumer { - void accept(RBSIPose measurement); + void accept(TimedPose measurement); } private final PoseMeasurementConsumer consumer; @@ -65,7 +65,7 @@ public interface PoseMeasurementConsumer { private volatile double lastPoseResetTimestamp = Double.NEGATIVE_INFINITY; // Smoothing buffer (recent fused estimates) - private final ArrayDeque fusedBuffer = new ArrayDeque<>(); + private final ArrayDeque fusedBuffer = new ArrayDeque<>(); private final double smoothWindowSec = 0.25; private final int smoothMaxSize = 12; @@ -127,7 +127,7 @@ public void rbsiPeriodic() { } // Pick the one best accepted estimate per camera for this loop - final ArrayList perCamAccepted = new ArrayList<>(io.length); + final ArrayList perCamAccepted = new ArrayList<>(io.length); // Loop over cameras for (int cam = 0; cam < io.length; cam++) { @@ -136,7 +136,7 @@ public void rbsiPeriodic() { int seen = 0; int accepted = 0; int rejected = 0; - RBSIPose best = null; + TimedPose best = null; double bestTrustScale = Double.NaN; int bestTrustedCount = 0; int bestTagCount = 0; @@ -162,7 +162,7 @@ public void rbsiPeriodic() { continue; } - RBSIPose est = built.estimate; + TimedPose est = built.estimate; if (best == null || isBetter(est, best)) { best = est; bestTrustScale = built.trustScale; @@ -197,12 +197,12 @@ public void rbsiPeriodic() { if (!Double.isFinite(tF)) return; // Time-align camera estimates to tF using odometry buffer, then inverse-variance fuse - RBSIPose fused = fuseAtTime(perCamAccepted, tF); + TimedPose fused = fuseAtTime(perCamAccepted, tF); if (fused == null) return; // Smooth by fusing recent fused estimates (also aligned to tF) pushFused(fused); - RBSIPose smoothed = smoothAtTime(tF); + TimedPose smoothed = smoothAtTime(tF); if (smoothed == null) return; // Inject the pose -- commented out for now... @@ -317,11 +317,11 @@ private GateResult passesHardGatesAndYawGate(int cam, VisionIO.PoseObservation o } private static final class BuiltEstimate { - final RBSIPose estimate; + final TimedPose estimate; final double trustScale; final int trustedCount; - BuiltEstimate(RBSIPose estimate, double trustScale, int trustedCount) { + BuiltEstimate(TimedPose estimate, double trustScale, int trustedCount) { this.estimate = estimate; this.trustScale = trustScale; this.trustedCount = trustedCount; @@ -369,7 +369,7 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { Logger.recordOutput("Vision/Camera" + cam + "/InjectedFracTrusted", fracTrusted); return new BuiltEstimate( - new RBSIPose( + new TimedPose( obs.pose().toPose2d(), obs.timestamp(), VecBuilder.fill(linearStdDev, linearStdDev, angularStdDev)), @@ -377,7 +377,7 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { trustedCount); } - private boolean isBetter(RBSIPose a, RBSIPose b) { + private boolean isBetter(TimedPose a, TimedPose b) { // Lower trace of stddev vector (x+y+theta) is better double ta = a.stdDevs().get(0, 0) + a.stdDevs().get(1, 0) + a.stdDevs().get(2, 0); double tb = b.stdDevs().get(0, 0) + b.stdDevs().get(1, 0) + b.stdDevs().get(2, 0); @@ -385,12 +385,12 @@ private boolean isBetter(RBSIPose a, RBSIPose b) { } /** Time alignment & fusion ********************************************** */ - private RBSIPose fuseAtTime(ArrayList estimates, double tF) { - final ArrayList aligned = new ArrayList<>(estimates.size()); + private TimedPose fuseAtTime(ArrayList estimates, double tF) { + final ArrayList aligned = new ArrayList<>(estimates.size()); for (var e : estimates) { Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tF); if (alignedPose == null) return null; - aligned.add(new RBSIPose(alignedPose, tF, e.stdDevs())); + aligned.add(new TimedPose(alignedPose, tF, e.stdDevs())); } return inverseVarianceFuse(aligned, tF); } @@ -410,7 +410,7 @@ private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tF) { return visionPoseAtTs.transformBy(ts_T_tf); } - private RBSIPose inverseVarianceFuse(ArrayList alignedAtTF, double tF) { + private TimedPose inverseVarianceFuse(ArrayList alignedAtTF, double tF) { if (alignedAtTF == null || alignedAtTF.isEmpty()) return null; if (alignedAtTF.size() == 1) return alignedAtTF.get(0); @@ -419,7 +419,7 @@ private RBSIPose inverseVarianceFuse(ArrayList alignedAtTF, double tF) double sumCos = 0.0, sumSin = 0.0; for (int i = 0; i < alignedAtTF.size(); i++) { - final RBSIPose e = alignedAtTF.get(i); + final TimedPose e = alignedAtTF.get(i); final Pose2d p = e.pose(); final Matrix s = e.stdDevs(); @@ -469,11 +469,11 @@ private RBSIPose inverseVarianceFuse(ArrayList alignedAtTF, double tF) final Matrix fusedStdDevs = VecBuilder.fill(Math.sqrt(1.0 / sumWx), Math.sqrt(1.0 / sumWy), Math.sqrt(1.0 / sumWth)); - return new RBSIPose(fusedPose, tF, fusedStdDevs); + return new TimedPose(fusedPose, tF, fusedStdDevs); } /** Smoothing buffer ***************************************************** */ - private void pushFused(RBSIPose fused) { + private void pushFused(TimedPose fused) { fusedBuffer.addLast(fused); while (fusedBuffer.size() > smoothMaxSize) { @@ -488,15 +488,15 @@ private void pushFused(RBSIPose fused) { } } - private RBSIPose smoothAtTime(double tF) { + private TimedPose smoothAtTime(double tF) { if (fusedBuffer.isEmpty()) return null; if (fusedBuffer.size() == 1) return fusedBuffer.peekLast(); - final ArrayList aligned = new ArrayList<>(fusedBuffer.size()); + final ArrayList aligned = new ArrayList<>(fusedBuffer.size()); for (var e : fusedBuffer) { Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tF); if (alignedPose == null) continue; - aligned.add(new RBSIPose(alignedPose, tF, e.stdDevs())); + aligned.add(new TimedPose(alignedPose, tF, e.stdDevs())); } if (aligned.isEmpty()) return fusedBuffer.peekLast(); diff --git a/src/main/java/frc/robot/util/RBSIPose.java b/src/main/java/frc/robot/util/TimedPose.java similarity index 89% rename from src/main/java/frc/robot/util/RBSIPose.java rename to src/main/java/frc/robot/util/TimedPose.java index 4a4df2f..440cd31 100644 --- a/src/main/java/frc/robot/util/RBSIPose.java +++ b/src/main/java/frc/robot/util/TimedPose.java @@ -18,4 +18,4 @@ import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; -public record RBSIPose(Pose2d pose, double timestampSeconds, Matrix stdDevs) {} +public record TimedPose(Pose2d pose, double timestampSeconds, Matrix stdDevs) {} From 3bf64b5b63d0e47979c647107add4bdc0267cccf Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Tue, 10 Feb 2026 18:07:07 -0700 Subject: [PATCH 11/22] Move the odometry queue draining into a VirtualSubsystem --- src/main/java/frc/robot/RobotContainer.java | 14 +- .../accelerometer/Accelerometer.java | 6 + .../frc/robot/subsystems/drive/Drive.java | 226 +++++-------- .../robot/subsystems/drive/DriveOdometry.java | 297 ++++++++++++++++++ .../java/frc/robot/subsystems/imu/Imu.java | 7 + .../frc/robot/subsystems/vision/Vision.java | 21 +- .../java/frc/robot/util/VirtualSubsystem.java | 22 ++ 7 files changed, 438 insertions(+), 155 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/drive/DriveOdometry.java diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 521e09d..8e4fdd9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -47,6 +47,7 @@ import frc.robot.commands.DriveCommands; import frc.robot.subsystems.accelerometer.Accelerometer; import frc.robot.subsystems.drive.Drive; +import frc.robot.subsystems.drive.DriveOdometry; import frc.robot.subsystems.drive.SwerveConstants; import frc.robot.subsystems.flywheel_example.Flywheel; import frc.robot.subsystems.flywheel_example.FlywheelIO; @@ -107,6 +108,9 @@ public class RobotContainer { private final Imu m_imu; private final Vision m_vision; + @SuppressWarnings("unused") + private final DriveOdometry m_driveOdometry; + @SuppressWarnings("unused") private final Accelerometer m_accel; @@ -156,10 +160,12 @@ public RobotContainer() { m_imu = new Imu(SwerveConstants.kImu.factory.get()); m_drivebase = new Drive(m_imu); - m_flywheel = new Flywheel(new FlywheelIOSim()); // new Flywheel(new FlywheelIOTalonFX()); + m_driveOdometry = + new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); // see note m_vision = new Vision( m_drivebase, m_drivebase::addVisionMeasurement, buildVisionIOsReal(m_drivebase)); + m_flywheel = new Flywheel(new FlywheelIOSim()); // new Flywheel(new FlywheelIOTalonFX()); m_accel = new Accelerometer(m_imu); sweep = null; break; @@ -169,6 +175,9 @@ public RobotContainer() { m_imu = new Imu(new ImuIOSim()); m_drivebase = new Drive(m_imu); + m_driveOdometry = + new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); // see note + m_flywheel = new Flywheel(new FlywheelIOSim()); // ---------------- Vision IOs (robot code) ---------------- @@ -208,6 +217,9 @@ public RobotContainer() { RBSICANBusRegistry.initSim(CANBuses.RIO, CANBuses.DRIVE); m_imu = new Imu(new ImuIOSim() {}); m_drivebase = new Drive(m_imu); + m_driveOdometry = + new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); // see note + m_flywheel = new Flywheel(new FlywheelIO() {}); m_vision = new Vision(m_drivebase, m_drivebase::addVisionMeasurement, buildVisionIOsReplay()); diff --git a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java index fcb7dd6..0b5ff65 100644 --- a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java +++ b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java @@ -55,6 +55,12 @@ public Accelerometer(Imu imu) { this.rio = new RioAccelIORoboRIO(200.0); // 200 Hz is a good start } + // Priority value for this virtual subsystem + @Override + protected int getPeriodPriority() { + return +10; + } + @Override public void rbsiPeriodic() { final boolean doProfile = (++profileCount >= PROFILE_EVERY_N); diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 71b9e37..fda4cde 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -253,156 +253,20 @@ public Drive(Imu imu) { /** Periodic function that is called each robot cycle by the command scheduler */ @Override public void rbsiPeriodic() { - odometryLock.lock(); - try { - // Ensure IMU inputs are fresh for this cycle - final var imuInputs = imu.getInputs(); - - // Stop modules & log empty setpoint states if disabled - if (DriverStation.isDisabled()) { - for (var module : modules) { - module.stop(); - } - Logger.recordOutput("SwerveStates/Setpoints", new SwerveModuleState[] {}); - Logger.recordOutput("SwerveStates/SetpointsOptimized", new SwerveModuleState[] {}); - } - - // Drain per-module odometry queues for this cycle - for (var module : modules) { - module.periodic(); - } - - // -------- REAL ODOMETRY REPLAY (canonical timestamps from module[0]) -------- - if (Constants.getMode() != Mode.SIM) { - final double[] ts = modules[0].getOdometryTimestamps(); - final int n = (ts == null) ? 0 : ts.length; - - // Cache per-module histories ONCE (avoid repeated getters in the loop) - final SwerveModulePosition[][] modHist = new SwerveModulePosition[4][]; - for (int m = 0; m < 4; m++) { - modHist[m] = modules[m].getOdometryPositions(); - } - - // Determine yaw queue availability - final boolean hasYawQueue = - imuInputs.connected - && imuInputs.odometryYawTimestamps != null - && imuInputs.odometryYawPositionsRad != null - && imuInputs.odometryYawTimestamps.length - == imuInputs.odometryYawPositionsRad.length - && imuInputs.odometryYawTimestamps.length > 0; - - final double[] yawTs = hasYawQueue ? imuInputs.odometryYawTimestamps : null; - final double[] yawPos = hasYawQueue ? imuInputs.odometryYawPositionsRad : null; - - // If we have no module samples, still keep yaw buffers “alive” for gating callers - if (n == 0) { - final double now = Timer.getFPGATimestamp(); - yawBuffer.addSample(now, imuInputs.yawPositionRad); - yawRateBuffer.addSample(now, imuInputs.yawRateRadPerSec); - - gyroDisconnectedAlert.set(!imuInputs.connected); - return; - } - - // Decide whether yaw queue is index-aligned with module[0] timestamps. - // We only trust index alignment if BOTH: - // - yaw has at least n samples - // - yawTs[i] ~= ts[i] for i in range (tight epsilon) - boolean yawIndexAligned = false; - if (hasYawQueue && yawTs.length >= n) { - yawIndexAligned = true; - final double eps = 1e-3; // 1 ms - for (int i = 0; i < n; i++) { - if (Math.abs(yawTs[i] - ts[i]) > eps) { - yawIndexAligned = false; - break; - } - } - } - - // If yaw is NOT index-aligned but we have a yaw queue, build yaw/yawRate buffers ONCE. - if (hasYawQueue && !yawIndexAligned) { - for (int k = 0; k < yawTs.length; k++) { - yawBuffer.addSample(yawTs[k], yawPos[k]); - if (k > 0) { - final double dt = yawTs[k] - yawTs[k - 1]; - if (dt > 1e-6) { - yawRateBuffer.addSample(yawTs[k], (yawPos[k] - yawPos[k - 1]) / dt); - } - } - } - } - - // If NO yaw queue, add a single “now” sample once (don’t do this per replay sample) - if (!hasYawQueue) { - final double now = Timer.getFPGATimestamp(); - yawBuffer.addSample(now, imuInputs.yawPositionRad); - yawRateBuffer.addSample(now, imuInputs.yawRateRadPerSec); - } - - // Replay each odometry sample - for (int i = 0; i < n; i++) { - final double t = ts[i]; - - // Build module positions at this sample index (clamp defensively) - for (int m = 0; m < 4; m++) { - final SwerveModulePosition[] hist = modHist[m]; - if (hist == null || hist.length == 0) { - odomPositions[m] = modules[m].getPosition(); - } else if (i < hist.length) { - odomPositions[m] = hist[i]; - } else { - odomPositions[m] = hist[hist.length - 1]; - } - } - - // Determine yaw at this timestamp - double yawRad = imuInputs.yawPositionRad; // fallback - - if (hasYawQueue) { - if (yawIndexAligned) { - yawRad = yawPos[i]; - - // Keep yaw/yawRate buffers updated in odometry timebase (good for yaw-gate) - yawBuffer.addSample(t, yawRad); - if (i > 0) { - final double dt = yawTs[i] - yawTs[i - 1]; - if (dt > 1e-6) { - yawRateBuffer.addSample(t, (yawPos[i] - yawPos[i - 1]) / dt); - } - } - } else { - // yawBuffer was pre-filled above; interpolate here - yawRad = yawBuffer.getSample(t).orElse(imuInputs.yawPositionRad); - } - } - - // Feed estimator at this historical timestamp - m_PoseEstimator.updateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); - - // Maintain pose history in SAME timebase as estimator - poseBuffer.addSample(t, m_PoseEstimator.getEstimatedPosition()); - } - - Logger.recordOutput("Drive/Pose", m_PoseEstimator.getEstimatedPosition()); - gyroDisconnectedAlert.set(!imuInputs.connected); - return; - - } else { + // NO odometryLock needed unless you touch poseEstimator directly here. + // Keep this focused on control / setpoints / characterization. - // SIMULATION: Keep sim pose buffer time-aligned, too - double now = Timer.getFPGATimestamp(); - poseBuffer.addSample(now, simPhysics.getPose()); - yawBuffer.addSample(now, simPhysics.getYaw().getRadians()); - yawRateBuffer.addSample(now, simPhysics.getOmegaRadPerSec()); - - Logger.recordOutput("Drive/Pose", simPhysics.getPose()); - gyroDisconnectedAlert.set(false); - } - } finally { - odometryLock.unlock(); + if (DriverStation.isDisabled()) { + for (var module : modules) module.stop(); + Logger.recordOutput("SwerveStates/Setpoints", new SwerveModuleState[] {}); + Logger.recordOutput("SwerveStates/SetpointsOptimized", new SwerveModuleState[] {}); } + + // If you need module refresh for control, you can either: + // A) leave it in DriveOdometry (recommended) and here just use cached inputs, OR + // B) keep a lightweight "module.controlPeriodic()" that doesn't drain queues. + // + // For now: do nothing here re: odometry. } /** @@ -559,6 +423,9 @@ public Command sysIdDynamic(SysIdRoutine.Direction direction) { } /** Getter Functions ***************************************************** */ + public Module[] getModules() { + return modules; + } /** Returns the module states (turn angles and drive velocities) for all of the modules. */ @AutoLogOutput(key = "SwerveStates/Measured") @@ -862,4 +729,67 @@ private edu.wpi.first.math.Matrix getSimulatedVisionStdDevs() { stdDevs.set(2, 0, Math.toRadians(2)); // rotation standard deviation (radians) return stdDevs; } + + // --- Helpers used by DriveOdometry (package-private) --- + + Pose2d poseEstimatorGetPose() { + return m_PoseEstimator.getEstimatedPosition(); + } + + void poseEstimatorUpdateWithTime(double t, Rotation2d yaw, SwerveModulePosition[] positions) { + m_PoseEstimator.updateWithTime(t, yaw, positions); + } + + void poseBufferAddSample(double t, Pose2d pose) { + poseBuffer.addSample(t, pose); + } + + // Yaw buffer helpers (assuming you already have yawBuffer + yawRateBuffer) + double yawBufferSampleOr(double t, double fallbackYawRad) { + return yawBuffer.getSample(t).orElse(fallbackYawRad); + } + + void yawBuffersAddSample(double t, double yawRad, double yawRateRadPerSec) { + yawBuffer.addSample(t, yawRad); + yawRateBuffer.addSample(t, yawRateRadPerSec); + } + + void yawBuffersFillFromQueue(double[] yawTs, double[] yawPosRad) { + for (int k = 0; k < yawTs.length; k++) { + yawBuffer.addSample(yawTs[k], yawPosRad[k]); + if (k > 0) { + double dt = yawTs[k] - yawTs[k - 1]; + if (dt > 1e-6) { + yawRateBuffer.addSample(yawTs[k], (yawPosRad[k] - yawPosRad[k - 1]) / dt); + } + } + } + } + + void yawBuffersAddSampleIndexAligned(double t, double[] yawTs, double[] yawPos, int i) { + yawBuffer.addSample(t, yawPos[i]); + if (i > 0) { + double dt = yawTs[i] - yawTs[i - 1]; + if (dt > 1e-6) { + yawRateBuffer.addSample(t, (yawPos[i] - yawPos[i - 1]) / dt); + } + } + } + + void setGyroDisconnectedAlert(boolean disconnected) { + gyroDisconnectedAlert.set(disconnected); + } + + // Drive.java + public Pose2d getSimPose() { + return simPhysics.getPose(); + } + + public double getSimYawRad() { + return simPhysics.getYaw().getRadians(); + } + + public double getSimYawRateRadPerSec() { + return simPhysics.getOmegaRadPerSec(); + } } diff --git a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java new file mode 100644 index 0000000..494e0ab --- /dev/null +++ b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java @@ -0,0 +1,297 @@ +package frc.robot.subsystems.drive; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.SwerveModulePosition; +import edu.wpi.first.wpilibj.Timer; +import frc.robot.Constants; +import frc.robot.subsystems.imu.Imu; +import frc.robot.util.RBSIEnum.Mode; +import frc.robot.util.VirtualSubsystem; +import org.littletonrobotics.junction.Logger; + +public final class DriveOdometry extends VirtualSubsystem { + private final Drive drive; + private final Imu imu; + private final Module[] modules; + + // Scratch (no per-loop allocations) + private final SwerveModulePosition[] odomPositions = new SwerveModulePosition[4]; + + public DriveOdometry(Drive drive, Imu imu, Module[] modules) { + this.drive = drive; + this.imu = imu; + this.modules = modules; + } + + // Priority value for this virtual subsystem + @Override + protected int getPeriodPriority() { + return -20; + } + + @Override + public void rbsiPeriodic() { + Drive.odometryLock.lock(); + try { + final var imuInputs = imu.getInputs(); + + // Drain per-module odometry queues ONCE per loop (this also refreshes motor signals) + for (var module : modules) { + module.periodic(); // if you later split, this becomes module.updateInputs() + } + + if (Constants.getMode() == Mode.SIM) { + final double now = Timer.getFPGATimestamp(); + drive.poseBufferAddSample(now, drive.getSimPose()); + drive.yawBuffersAddSample(now, drive.getSimYawRad(), drive.getSimYawRateRadPerSec()); + Logger.recordOutput("Drive/Pose", drive.getSimPose()); + return; + } + + // Canonical timestamp queue from module[0] + final double[] ts = modules[0].getOdometryTimestamps(); + final int n = (ts == null) ? 0 : ts.length; + + // Always keep yaw buffers “alive” even if no samples + if (n == 0) { + final double now = Timer.getFPGATimestamp(); + drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); + drive.setGyroDisconnectedAlert(!imuInputs.connected); + return; + } + + // Cache module histories once + final SwerveModulePosition[][] modHist = new SwerveModulePosition[4][]; + for (int m = 0; m < 4; m++) { + modHist[m] = modules[m].getOdometryPositions(); + } + + // Yaw queue availability + final boolean hasYawQueue = + imuInputs.connected + && imuInputs.odometryYawTimestamps != null + && imuInputs.odometryYawPositionsRad != null + && imuInputs.odometryYawTimestamps.length == imuInputs.odometryYawPositionsRad.length + && imuInputs.odometryYawTimestamps.length > 0; + + final double[] yawTs = hasYawQueue ? imuInputs.odometryYawTimestamps : null; + final double[] yawPos = hasYawQueue ? imuInputs.odometryYawPositionsRad : null; + + // Determine index alignment (cheap + deterministic) + boolean yawIndexAligned = false; + if (hasYawQueue && yawTs.length >= n) { + yawIndexAligned = true; + final double eps = 1e-3; // 1ms + for (int i = 0; i < n; i++) { + if (Math.abs(yawTs[i] - ts[i]) > eps) { + yawIndexAligned = false; + break; + } + } + } + + // If yaw not aligned, pre-fill yaw buffers once and interpolate later + if (hasYawQueue && !yawIndexAligned) { + drive.yawBuffersFillFromQueue(yawTs, yawPos); + } else if (!hasYawQueue) { + // Single “now” sample once (not per replay) + final double now = Timer.getFPGATimestamp(); + drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); + } + + // Replay + for (int i = 0; i < n; i++) { + final double t = ts[i]; + + // Build module positions at sample i (clamp defensively) + for (int m = 0; m < 4; m++) { + final SwerveModulePosition[] hist = modHist[m]; + if (hist == null || hist.length == 0) { + odomPositions[m] = modules[m].getPosition(); + } else if (i < hist.length) { + odomPositions[m] = hist[i]; + } else { + odomPositions[m] = hist[hist.length - 1]; + } + } + + double yawRad = imuInputs.yawPositionRad; + if (hasYawQueue) { + if (yawIndexAligned) { + yawRad = yawPos[i]; + // Keep yaw buffers aligned to replay timeline (good for yaw-rate gate) + drive.yawBuffersAddSampleIndexAligned(t, yawTs, yawPos, i); + } else { + yawRad = drive.yawBufferSampleOr(t, imuInputs.yawPositionRad); + } + } + + drive.poseEstimatorUpdateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); + drive.poseBufferAddSample(t, drive.poseEstimatorGetPose()); + } + + Logger.recordOutput("Drive/Pose", drive.poseEstimatorGetPose()); + drive.setGyroDisconnectedAlert(!imuInputs.connected); + + } finally { + Drive.odometryLock.unlock(); + } + } + + // /************************************************************************* */ + // /** Periodic function that is called each robot cycle by the command scheduler */ + // @Override + // public void rbsiPeriodic() { + // odometryLock.lock(); + // try { + // // Ensure IMU inputs are fresh for this cycle + // final var imuInputs = imu.getInputs(); + + // // Stop modules & log empty setpoint states if disabled + // if (DriverStation.isDisabled()) { + // for (var module : modules) { + // module.stop(); + // } + // Logger.recordOutput("SwerveStates/Setpoints", new SwerveModuleState[] {}); + // Logger.recordOutput("SwerveStates/SetpointsOptimized", new SwerveModuleState[] {}); + // } + + // // Drain per-module odometry queues for this cycle + // for (var module : modules) { + // module.periodic(); + // } + + // // -------- REAL ODOMETRY REPLAY (canonical timestamps from module[0]) -------- + // if (Constants.getMode() != Mode.SIM) { + // final double[] ts = modules[0].getOdometryTimestamps(); + // final int n = (ts == null) ? 0 : ts.length; + + // // Cache per-module histories ONCE (avoid repeated getters in the loop) + // final SwerveModulePosition[][] modHist = new SwerveModulePosition[4][]; + // for (int m = 0; m < 4; m++) { + // modHist[m] = modules[m].getOdometryPositions(); + // } + + // // Determine yaw queue availability + // final boolean hasYawQueue = + // imuInputs.connected + // && imuInputs.odometryYawTimestamps != null + // && imuInputs.odometryYawPositionsRad != null + // && imuInputs.odometryYawTimestamps.length + // == imuInputs.odometryYawPositionsRad.length + // && imuInputs.odometryYawTimestamps.length > 0; + + // final double[] yawTs = hasYawQueue ? imuInputs.odometryYawTimestamps : null; + // final double[] yawPos = hasYawQueue ? imuInputs.odometryYawPositionsRad : null; + + // // If we have no module samples, still keep yaw buffers “alive” for gating callers + // if (n == 0) { + // final double now = Timer.getFPGATimestamp(); + // yawBuffer.addSample(now, imuInputs.yawPositionRad); + // yawRateBuffer.addSample(now, imuInputs.yawRateRadPerSec); + + // gyroDisconnectedAlert.set(!imuInputs.connected); + // return; + // } + + // // Decide whether yaw queue is index-aligned with module[0] timestamps. + // // We only trust index alignment if BOTH: + // // - yaw has at least n samples + // // - yawTs[i] ~= ts[i] for i in range (tight epsilon) + // boolean yawIndexAligned = false; + // if (hasYawQueue && yawTs.length >= n) { + // yawIndexAligned = true; + // final double eps = 1e-3; // 1 ms + // for (int i = 0; i < n; i++) { + // if (Math.abs(yawTs[i] - ts[i]) > eps) { + // yawIndexAligned = false; + // break; + // } + // } + // } + + // // If yaw is NOT index-aligned but we have a yaw queue, build yaw/yawRate buffers ONCE. + // if (hasYawQueue && !yawIndexAligned) { + // for (int k = 0; k < yawTs.length; k++) { + // yawBuffer.addSample(yawTs[k], yawPos[k]); + // if (k > 0) { + // final double dt = yawTs[k] - yawTs[k - 1]; + // if (dt > 1e-6) { + // yawRateBuffer.addSample(yawTs[k], (yawPos[k] - yawPos[k - 1]) / dt); + // } + // } + // } + // } + + // // If NO yaw queue, add a single “now” sample once (don’t do this per replay sample) + // if (!hasYawQueue) { + // final double now = Timer.getFPGATimestamp(); + // yawBuffer.addSample(now, imuInputs.yawPositionRad); + // yawRateBuffer.addSample(now, imuInputs.yawRateRadPerSec); + // } + + // // Replay each odometry sample + // for (int i = 0; i < n; i++) { + // final double t = ts[i]; + + // // Build module positions at this sample index (clamp defensively) + // for (int m = 0; m < 4; m++) { + // final SwerveModulePosition[] hist = modHist[m]; + // if (hist == null || hist.length == 0) { + // odomPositions[m] = modules[m].getPosition(); + // } else if (i < hist.length) { + // odomPositions[m] = hist[i]; + // } else { + // odomPositions[m] = hist[hist.length - 1]; + // } + // } + + // // Determine yaw at this timestamp + // double yawRad = imuInputs.yawPositionRad; // fallback + + // if (hasYawQueue) { + // if (yawIndexAligned) { + // yawRad = yawPos[i]; + + // // Keep yaw/yawRate buffers updated in odometry timebase (good for yaw-gate) + // yawBuffer.addSample(t, yawRad); + // if (i > 0) { + // final double dt = yawTs[i] - yawTs[i - 1]; + // if (dt > 1e-6) { + // yawRateBuffer.addSample(t, (yawPos[i] - yawPos[i - 1]) / dt); + // } + // } + // } else { + // // yawBuffer was pre-filled above; interpolate here + // yawRad = yawBuffer.getSample(t).orElse(imuInputs.yawPositionRad); + // } + // } + + // // Feed estimator at this historical timestamp + // m_PoseEstimator.updateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); + + // // Maintain pose history in SAME timebase as estimator + // poseBuffer.addSample(t, m_PoseEstimator.getEstimatedPosition()); + // } + + // Logger.recordOutput("Drive/Pose", m_PoseEstimator.getEstimatedPosition()); + // gyroDisconnectedAlert.set(!imuInputs.connected); + // return; + + // } else { + + // // SIMULATION: Keep sim pose buffer time-aligned, too + // double now = Timer.getFPGATimestamp(); + // poseBuffer.addSample(now, simPhysics.getPose()); + // yawBuffer.addSample(now, simPhysics.getYaw().getRadians()); + // yawRateBuffer.addSample(now, simPhysics.getOmegaRadPerSec()); + + // Logger.recordOutput("Drive/Pose", simPhysics.getPose()); + // gyroDisconnectedAlert.set(false); + // } + // } finally { + // odometryLock.unlock(); + // } + // } + +} diff --git a/src/main/java/frc/robot/subsystems/imu/Imu.java b/src/main/java/frc/robot/subsystems/imu/Imu.java index f5f6315..c0a1ba6 100644 --- a/src/main/java/frc/robot/subsystems/imu/Imu.java +++ b/src/main/java/frc/robot/subsystems/imu/Imu.java @@ -36,7 +36,14 @@ public Imu(ImuIO io) { this.io = io; } + // Priority value for this virtual subsystem + @Override + protected int getPeriodPriority() { + return -30; + } + // Periodic function to read inputs + @Override public void rbsiPeriodic() { io.updateInputs(inputs); } diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 86c1055..0928d65 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -28,7 +28,7 @@ import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; -import frc.robot.Constants; +import frc.robot.Constants.Cameras; import frc.robot.FieldConstants; import frc.robot.subsystems.drive.Drive; import frc.robot.subsystems.vision.VisionIO.PoseObservationType; @@ -45,20 +45,23 @@ public class Vision extends VirtualSubsystem { + // Declare the Vision IO + private final VisionIO[] io; + private final VisionIOInputsAutoLogged[] inputs; + /** Vision Consumer definition */ @FunctionalInterface public interface PoseMeasurementConsumer { void accept(TimedPose measurement); } + // Declare pose consumer, drivebase, and epoch reset private final PoseMeasurementConsumer consumer; private final Drive drive; private long lastSeenPoseResetEpoch = -1; - private final VisionIO[] io; - private final VisionIOInputsAutoLogged[] inputs; - - private final Constants.Cameras.CameraConfig[] camConfigs = Constants.Cameras.ALL; + // Declare the camera configurations + private final Cameras.CameraConfig[] camConfigs = Cameras.ALL; // Per-camera monotonic and pose reset gates private final double[] lastAcceptedTsPerCam; @@ -106,6 +109,12 @@ public Vision(Drive drive, PoseMeasurementConsumer consumer, VisionIO... io) { } } + // Priority value for this virtual subsystem + @Override + protected int getPeriodPriority() { + return -10; + } + /** Periodic Function */ @Override public void rbsiPeriodic() { @@ -205,7 +214,7 @@ public void rbsiPeriodic() { TimedPose smoothed = smoothAtTime(tF); if (smoothed == null) return; - // Inject the pose -- commented out for now... + // Inject the pose consumer.accept(smoothed); Logger.recordOutput("Vision/FusedPose", fused.pose()); diff --git a/src/main/java/frc/robot/util/VirtualSubsystem.java b/src/main/java/frc/robot/util/VirtualSubsystem.java index 2996aa3..4b1c57e 100644 --- a/src/main/java/frc/robot/util/VirtualSubsystem.java +++ b/src/main/java/frc/robot/util/VirtualSubsystem.java @@ -10,6 +10,7 @@ package frc.robot.util; import java.util.ArrayList; +import java.util.Comparator; import java.util.List; import org.littletonrobotics.junction.Logger; @@ -18,14 +19,35 @@ */ public abstract class VirtualSubsystem { private static final List subsystems = new ArrayList<>(); + private static boolean needsSort = false; + private final String name = getClass().getSimpleName(); // Load all defined virtual subsystems into a list public VirtualSubsystem() { subsystems.add(this); + needsSort = true; // a new subsystem changed ordering + } + + /** + * Override to control ordering. Lower runs earlier. + * + *

Example: IMU inputs -30, Drive odometry -20, Vision -10, Coordinator 0. + */ + protected int getPeriodPriority() { + return 0; } public static void periodicAll() { + // Sort once (and again only if new subsystems are constructed) + if (needsSort) { + subsystems.sort( + Comparator.comparingInt(VirtualSubsystem::getPeriodPriority) + // deterministic tie-break to avoid “random” order when priorities match + .thenComparingInt(System::identityHashCode)); + needsSort = false; + } + // Call each virtual subsystem during robotPeriodic() for (VirtualSubsystem subsystem : subsystems) { subsystem.periodic(); From 592314512ded7009357c65a194c79ab51f1d28ac Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Fri, 13 Feb 2026 14:53:30 -0700 Subject: [PATCH 12/22] Update AprilTag definitions --- src/main/deploy/apriltags/2024-crescendo.json | 296 +++++++++ .../apriltags/2025-reefscape-andymark.json | 404 ++++++++++++ ...ficial.json => 2025-reefscape-welded.json} | 0 src/main/deploy/apriltags/2026-none.json | 7 - .../apriltags/2026-rebuilt-andymark.json | 584 ++++++++++++++++++ ...official.json => 2026-rebuilt-welded.json} | 0 src/main/deploy/apriltags/none-andymark.json | 7 + src/main/deploy/apriltags/none-welded.json | 7 + src/main/java/frc/robot/FieldConstants.java | 21 +- src/main/java/frc/robot/RobotContainer.java | 3 +- 10 files changed, 1314 insertions(+), 15 deletions(-) create mode 100644 src/main/deploy/apriltags/2024-crescendo.json create mode 100644 src/main/deploy/apriltags/2025-reefscape-andymark.json rename src/main/deploy/apriltags/{2025-official.json => 2025-reefscape-welded.json} (100%) delete mode 100644 src/main/deploy/apriltags/2026-none.json create mode 100644 src/main/deploy/apriltags/2026-rebuilt-andymark.json rename src/main/deploy/apriltags/{2026-official.json => 2026-rebuilt-welded.json} (100%) create mode 100644 src/main/deploy/apriltags/none-andymark.json create mode 100644 src/main/deploy/apriltags/none-welded.json diff --git a/src/main/deploy/apriltags/2024-crescendo.json b/src/main/deploy/apriltags/2024-crescendo.json new file mode 100644 index 0000000..8cb837a --- /dev/null +++ b/src/main/deploy/apriltags/2024-crescendo.json @@ -0,0 +1,296 @@ +{ + "tags": [ + { + "ID": 1, + "pose": { + "translation": { + "x": 15.079471999999997, + "y": 0.24587199999999998, + "z": 1.355852 + }, + "rotation": { + "quaternion": { + "W": 0.5000000000000001, + "X": 0.0, + "Y": 0.0, + "Z": 0.8660254037844386 + } + } + } + }, + { + "ID": 2, + "pose": { + "translation": { + "x": 16.185134, + "y": 0.883666, + "z": 1.355852 + }, + "rotation": { + "quaternion": { + "W": 0.5000000000000001, + "X": 0.0, + "Y": 0.0, + "Z": 0.8660254037844386 + } + } + } + }, + { + "ID": 3, + "pose": { + "translation": { + "x": 16.579342, + "y": 4.982717999999999, + "z": 1.4511020000000001 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 4, + "pose": { + "translation": { + "x": 16.579342, + "y": 5.547867999999999, + "z": 1.4511020000000001 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 5, + "pose": { + "translation": { + "x": 14.700757999999999, + "y": 8.2042, + "z": 1.355852 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 6, + "pose": { + "translation": { + "x": 1.8415, + "y": 8.2042, + "z": 1.355852 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 7, + "pose": { + "translation": { + "x": -0.038099999999999995, + "y": 5.547867999999999, + "z": 1.4511020000000001 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 8, + "pose": { + "translation": { + "x": -0.038099999999999995, + "y": 4.982717999999999, + "z": 1.4511020000000001 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 9, + "pose": { + "translation": { + "x": 0.356108, + "y": 0.883666, + "z": 1.355852 + }, + "rotation": { + "quaternion": { + "W": 0.8660254037844387, + "X": 0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 10, + "pose": { + "translation": { + "x": 1.4615159999999998, + "y": 0.24587199999999998, + "z": 1.355852 + }, + "rotation": { + "quaternion": { + "W": 0.8660254037844387, + "X": 0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 11, + "pose": { + "translation": { + "x": 11.904726, + "y": 3.7132259999999997, + "z": 1.3208 + }, + "rotation": { + "quaternion": { + "W": -0.8660254037844387, + "X": -0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 12, + "pose": { + "translation": { + "x": 11.904726, + "y": 4.49834, + "z": 1.3208 + }, + "rotation": { + "quaternion": { + "W": 0.8660254037844387, + "X": 0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 13, + "pose": { + "translation": { + "x": 11.220196, + "y": 4.105148, + "z": 1.3208 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 14, + "pose": { + "translation": { + "x": 5.320792, + "y": 4.105148, + "z": 1.3208 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 15, + "pose": { + "translation": { + "x": 4.641342, + "y": 4.49834, + "z": 1.3208 + }, + "rotation": { + "quaternion": { + "W": 0.5000000000000001, + "X": 0.0, + "Y": 0.0, + "Z": 0.8660254037844386 + } + } + } + }, + { + "ID": 16, + "pose": { + "translation": { + "x": 4.641342, + "y": 3.7132259999999997, + "z": 1.3208 + }, + "rotation": { + "quaternion": { + "W": -0.4999999999999998, + "X": -0.0, + "Y": 0.0, + "Z": 0.8660254037844387 + } + } + } + } + ], + "field": { + "length": 16.541, + "width": 8.211 + } +} diff --git a/src/main/deploy/apriltags/2025-reefscape-andymark.json b/src/main/deploy/apriltags/2025-reefscape-andymark.json new file mode 100644 index 0000000..60b60e5 --- /dev/null +++ b/src/main/deploy/apriltags/2025-reefscape-andymark.json @@ -0,0 +1,404 @@ +{ + "tags": [ + { + "ID": 1, + "pose": { + "translation": { + "x": 16.687292, + "y": 0.628142, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": 0.4539904997395468, + "X": 0.0, + "Y": 0.0, + "Z": 0.8910065241883678 + } + } + } + }, + { + "ID": 2, + "pose": { + "translation": { + "x": 16.687292, + "y": 7.414259999999999, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": -0.45399049973954675, + "X": -0.0, + "Y": 0.0, + "Z": 0.8910065241883679 + } + } + } + }, + { + "ID": 3, + "pose": { + "translation": { + "x": 11.49096, + "y": 8.031733999999998, + "z": 1.30175 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 4, + "pose": { + "translation": { + "x": 9.276079999999999, + "y": 6.132575999999999, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 0.9659258262890683, + "X": 0.0, + "Y": 0.25881904510252074, + "Z": 0.0 + } + } + } + }, + { + "ID": 5, + "pose": { + "translation": { + "x": 9.276079999999999, + "y": 1.9098259999999998, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 0.9659258262890683, + "X": 0.0, + "Y": 0.25881904510252074, + "Z": 0.0 + } + } + } + }, + { + "ID": 6, + "pose": { + "translation": { + "x": 13.474446, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.8660254037844387, + "X": -0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 7, + "pose": { + "translation": { + "x": 13.890498, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 8, + "pose": { + "translation": { + "x": 13.474446, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.8660254037844387, + "X": 0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 9, + "pose": { + "translation": { + "x": 12.643358, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.5000000000000001, + "X": 0.0, + "Y": 0.0, + "Z": 0.8660254037844386 + } + } + } + }, + { + "ID": 10, + "pose": { + "translation": { + "x": 12.227305999999999, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 11, + "pose": { + "translation": { + "x": 12.643358, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.4999999999999998, + "X": -0.0, + "Y": 0.0, + "Z": 0.8660254037844387 + } + } + } + }, + { + "ID": 12, + "pose": { + "translation": { + "x": 0.8613139999999999, + "y": 0.628142, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": 0.8910065241883679, + "X": 0.0, + "Y": 0.0, + "Z": 0.45399049973954675 + } + } + } + }, + { + "ID": 13, + "pose": { + "translation": { + "x": 0.8613139999999999, + "y": 7.414259999999999, + "z": 1.4859 + }, + "rotation": { + "quaternion": { + "W": -0.8910065241883678, + "X": -0.0, + "Y": 0.0, + "Z": 0.45399049973954686 + } + } + } + }, + { + "ID": 14, + "pose": { + "translation": { + "x": 8.272272, + "y": 6.132575999999999, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 5.914589856893349e-17, + "X": -0.25881904510252074, + "Y": 1.5848095757158825e-17, + "Z": 0.9659258262890683 + } + } + } + }, + { + "ID": 15, + "pose": { + "translation": { + "x": 8.272272, + "y": 1.9098259999999998, + "z": 1.8679160000000001 + }, + "rotation": { + "quaternion": { + "W": 5.914589856893349e-17, + "X": -0.25881904510252074, + "Y": 1.5848095757158825e-17, + "Z": 0.9659258262890683 + } + } + } + }, + { + "ID": 16, + "pose": { + "translation": { + "x": 6.057646, + "y": 0.010667999999999999, + "z": 1.30175 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 17, + "pose": { + "translation": { + "x": 4.073905999999999, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.4999999999999998, + "X": -0.0, + "Y": 0.0, + "Z": 0.8660254037844387 + } + } + } + }, + { + "ID": 18, + "pose": { + "translation": { + "x": 3.6576, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 19, + "pose": { + "translation": { + "x": 4.073905999999999, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.5000000000000001, + "X": 0.0, + "Y": 0.0, + "Z": 0.8660254037844386 + } + } + } + }, + { + "ID": 20, + "pose": { + "translation": { + "x": 4.904739999999999, + "y": 4.740402, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 0.8660254037844387, + "X": 0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + }, + { + "ID": 21, + "pose": { + "translation": { + "x": 5.321046, + "y": 4.0208200000000005, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 22, + "pose": { + "translation": { + "x": 4.904739999999999, + "y": 3.3012379999999997, + "z": 0.308102 + }, + "rotation": { + "quaternion": { + "W": -0.8660254037844387, + "X": -0.0, + "Y": 0.0, + "Z": 0.49999999999999994 + } + } + } + } + ], + "field": { + "length": 17.548, + "width": 8.042 + } +} diff --git a/src/main/deploy/apriltags/2025-official.json b/src/main/deploy/apriltags/2025-reefscape-welded.json similarity index 100% rename from src/main/deploy/apriltags/2025-official.json rename to src/main/deploy/apriltags/2025-reefscape-welded.json diff --git a/src/main/deploy/apriltags/2026-none.json b/src/main/deploy/apriltags/2026-none.json deleted file mode 100644 index 4763fda..0000000 --- a/src/main/deploy/apriltags/2026-none.json +++ /dev/null @@ -1,7 +0,0 @@ -{ - "tags": [], - "field": { - "length": 16.4592, - "width": 8.2296 - } -} diff --git a/src/main/deploy/apriltags/2026-rebuilt-andymark.json b/src/main/deploy/apriltags/2026-rebuilt-andymark.json new file mode 100644 index 0000000..ecc0390 --- /dev/null +++ b/src/main/deploy/apriltags/2026-rebuilt-andymark.json @@ -0,0 +1,584 @@ +{ + "tags": [ + { + "ID": 1, + "pose": { + "translation": { + "x": 11.863959, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 2, + "pose": { + "translation": { + "x": 11.9013986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 3, + "pose": { + "translation": { + "x": 11.2978438, + "y": 4.3769534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 4, + "pose": { + "translation": { + "x": 11.2978438, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 5, + "pose": { + "translation": { + "x": 11.9013986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 6, + "pose": { + "translation": { + "x": 11.863959, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 7, + "pose": { + "translation": { + "x": 11.9388636, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 8, + "pose": { + "translation": { + "x": 12.2569986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 9, + "pose": { + "translation": { + "x": 12.5051566, + "y": 3.6657534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 10, + "pose": { + "translation": { + "x": 12.5051566, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 11, + "pose": { + "translation": { + "x": 12.2569986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 12, + "pose": { + "translation": { + "x": 11.9388636, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 13, + "pose": { + "translation": { + "x": 16.499332, + "y": 7.391907999999999, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 14, + "pose": { + "translation": { + "x": 16.499332, + "y": 6.960107999999999, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 15, + "pose": { + "translation": { + "x": 16.4989764, + "y": 4.3124882, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 16, + "pose": { + "translation": { + "x": 16.4989764, + "y": 3.8806881999999994, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 17, + "pose": { + "translation": { + "x": 4.6490636, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 18, + "pose": { + "translation": { + "x": 4.6115986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 19, + "pose": { + "translation": { + "x": 5.2151534, + "y": 3.6657534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 20, + "pose": { + "translation": { + "x": 5.2151534, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 21, + "pose": { + "translation": { + "x": 4.6115986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 22, + "pose": { + "translation": { + "x": 4.6490636, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 23, + "pose": { + "translation": { + "x": 4.574159, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 24, + "pose": { + "translation": { + "x": 4.2559986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 25, + "pose": { + "translation": { + "x": 4.007866, + "y": 4.3769534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 26, + "pose": { + "translation": { + "x": 4.007866, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 27, + "pose": { + "translation": { + "x": 4.2559986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 28, + "pose": { + "translation": { + "x": 4.574159, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 29, + "pose": { + "translation": { + "x": 0.0136906, + "y": 0.6507734, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 30, + "pose": { + "translation": { + "x": 0.0136906, + "y": 1.0825734, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 31, + "pose": { + "translation": { + "x": 0.0140462, + "y": 3.7301932, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 32, + "pose": { + "translation": { + "x": 0.0140462, + "y": 4.1619931999999995, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + } + ], + "field": { + "length": 16.518, + "width": 8.043 + } +} diff --git a/src/main/deploy/apriltags/2026-official.json b/src/main/deploy/apriltags/2026-rebuilt-welded.json similarity index 100% rename from src/main/deploy/apriltags/2026-official.json rename to src/main/deploy/apriltags/2026-rebuilt-welded.json diff --git a/src/main/deploy/apriltags/none-andymark.json b/src/main/deploy/apriltags/none-andymark.json new file mode 100644 index 0000000..318fdac --- /dev/null +++ b/src/main/deploy/apriltags/none-andymark.json @@ -0,0 +1,7 @@ +{ + "tags": [], + "field": { + "length": 16.518, + "width": 8.043 + } +} diff --git a/src/main/deploy/apriltags/none-welded.json b/src/main/deploy/apriltags/none-welded.json new file mode 100644 index 0000000..6333798 --- /dev/null +++ b/src/main/deploy/apriltags/none-welded.json @@ -0,0 +1,7 @@ +{ + "tags": [], + "field": { + "length": 16.541, + "width": 8.069 + } +} diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 729b45f..34c356d 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -36,25 +36,32 @@ */ public class FieldConstants { + /** Specify which type of field your robot is using */ + private static final AprilTagLayoutType fieldType = AprilTagLayoutType.REBUILT_WELDED; + /** AprilTag Field Layout ************************************************ */ public static final double aprilTagWidth = Inches.of(6.50).in(Meters); public static final String aprilTagFamily = "36h11"; - public static final double fieldLength = AprilTagLayoutType.OFFICIAL.getLayout().getFieldLength(); - public static final double fieldWidth = AprilTagLayoutType.OFFICIAL.getLayout().getFieldWidth(); + public static final double fieldLength = fieldType.getLayout().getFieldLength(); + public static final double fieldWidth = fieldType.getLayout().getFieldWidth(); - public static final int aprilTagCount = AprilTagLayoutType.OFFICIAL.getLayout().getTags().size(); - public static final AprilTagLayoutType defaultAprilTagType = AprilTagLayoutType.OFFICIAL; + public static final int aprilTagCount = fieldType.getLayout().getTags().size(); + public static final AprilTagLayoutType defaultAprilTagType = fieldType; public static final AprilTagFieldLayout aprilTagLayout = AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField); @Getter public enum AprilTagLayoutType { - OFFICIAL("2026-official"), - NONE("2026-none"), - REEFSCAPE("2025-official"); + REBUILT_WELDED("2026-rebuilt-welded"), + REBUILT_ANDYMARK("2026-rebuilt-welded"), + REEFSCAPE_WELDED("2025-reefscape-welded"), + REEFSCAPE_ANDYMARK("2025-reefscape-andymark"), + CRESCENDO("2024-crescendo"), + NONE_WELDED("none-welded"), + NONE_ANDYMARK("none-andymark"); AprilTagLayoutType(String name) { try { diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 8e4fdd9..5b74cf6 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -469,7 +469,8 @@ public void getAutonomousCommandChoreo() { /** Updates the alerts. */ public void updateAlerts() { // AprilTag layout alert - boolean aprilTagAlertActive = Constants.getAprilTagLayoutType() != AprilTagLayoutType.OFFICIAL; + boolean aprilTagAlertActive = + Constants.getAprilTagLayoutType() != AprilTagLayoutType.REBUILT_WELDED; aprilTagLayoutAlert.set(aprilTagAlertActive); if (aprilTagAlertActive) { aprilTagLayoutAlert.setText( From 1c0875fd57e8dc5cad6f70dfff2ab88862108dec Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Fri, 13 Feb 2026 14:55:03 -0700 Subject: [PATCH 13/22] Clean up Subsystem defs --- .../java/frc/robot/subsystems/drive/ModuleIOTalonFX.java | 2 +- src/main/java/frc/robot/util/RBSISubsystem.java | 4 ++-- src/main/java/frc/robot/util/VirtualSubsystem.java | 5 +++++ 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java index df569b4..c7015bf 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java @@ -305,7 +305,7 @@ public void updateInputs(ModuleIOInputs inputs) { final int driveCount = drivePositionQueue.size(); final int turnCount = turnPositionQueue.size(); - // Only consume the common prefix — guarantees alignment + // Only consume the common prefix -- guarantees alignment final int sampleCount = Math.min(tsCount, Math.min(driveCount, turnCount)); if (sampleCount <= 0) { diff --git a/src/main/java/frc/robot/util/RBSISubsystem.java b/src/main/java/frc/robot/util/RBSISubsystem.java index 3aa3b8b..cb13520 100644 --- a/src/main/java/frc/robot/util/RBSISubsystem.java +++ b/src/main/java/frc/robot/util/RBSISubsystem.java @@ -38,8 +38,8 @@ public abstract class RBSISubsystem extends SubsystemBase { public final void periodic() { long start = System.nanoTime(); rbsiPeriodic(); - long end = System.nanoTime(); - Logger.recordOutput("Loop/Mech/" + name + "_ms", (end - start) / 1e6); + // Log the timing for this subsystem + Logger.recordOutput("Loop/Mech/" + name + "_ms", (System.nanoTime() - start) / 1e6); } /** Subclasses must implement this instead of periodic(). */ diff --git a/src/main/java/frc/robot/util/VirtualSubsystem.java b/src/main/java/frc/robot/util/VirtualSubsystem.java index 4b1c57e..36ece7b 100644 --- a/src/main/java/frc/robot/util/VirtualSubsystem.java +++ b/src/main/java/frc/robot/util/VirtualSubsystem.java @@ -38,6 +38,10 @@ protected int getPeriodPriority() { return 0; } + /** + * Run the periodic functions of each subsystem in the order determined by the getPeriodPriority() + * of each. + */ public static void periodicAll() { // Sort once (and again only if new subsystems are constructed) if (needsSort) { @@ -68,6 +72,7 @@ public static void periodicAll() { public final void periodic() { long start = System.nanoTime(); rbsiPeriodic(); + // Log the timing for this subsystem Logger.recordOutput("Loop/Virtual/" + name + "_ms", (System.nanoTime() - start) / 1e6); } From 5569b2b367daedc4bcd9c36b9ff1063db13f93e0 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Fri, 13 Feb 2026 17:29:27 -0700 Subject: [PATCH 14/22] Clean up the IMU code a little --- doc/RBSI-PoseBuffer.md | 131 ++++++++++++++++++ doc/RBSI-Vision.md | 2 +- src/main/java/frc/robot/Constants.java | 2 + .../robot/subsystems/drive/DriveOdometry.java | 17 +++ .../java/frc/robot/subsystems/imu/Imu.java | 53 +++++-- .../java/frc/robot/subsystems/imu/ImuIO.java | 26 ++-- .../frc/robot/subsystems/imu/ImuIONavX.java | 56 +++++--- .../robot/subsystems/imu/ImuIOPigeon2.java | 50 ++++--- 8 files changed, 270 insertions(+), 67 deletions(-) create mode 100644 doc/RBSI-PoseBuffer.md diff --git a/doc/RBSI-PoseBuffer.md b/doc/RBSI-PoseBuffer.md new file mode 100644 index 0000000..efbb828 --- /dev/null +++ b/doc/RBSI-PoseBuffer.md @@ -0,0 +1,131 @@ +# Az-RBSI Pose Buffering + +This page contains documentation for the Odometry and Vision Pose Buffering +system included in Az-RBSI. It is more for reference than instructing teams in +how to do something. + +-------- + +### Background for Need + +In previous versions of the Az-RBSI (or the base [AdvantageKit templates]( +https://docs.advantagekit.org/getting-started/template-projects)), there is a +temporal disconnect between the "now" state of the drivetrain odometry (wheel +encoders + gyro) and the "delayed" state of vision measurements (by exposure +time, pipeline processing, and network transport). Essentially, **the +different sensors on the robot do not all report data at the same time**. This +delay can be 30–120 ms -- which is huge when your robot can move a foot in that +time. Attempting to correct the "now" odometric pose with a "delayed" vision +estimate introduces systematic error than can cause jitter in the pose estimate +and incorrect downstream computed values. + + +### What is Pose Buffering + +A pose buffer lets you store a time history of your robot’s estimated pose so +that when a delayed vision measurement arrives, you can rewind the state +estimator to the exact timestamp the image was captured, inject the correction, +and then replay forward to the present. In essence, pose buffers enable **time +alignment between subsystems**. Since the Az-RBSI assumes input from multiple +cameras and combining that with the IMU yaw queues and high-frequency module +odometry, everything must agree on a common timebase. Introducing a pose +buffer allows us to query, "What did odometry think the robot pose was at time +`t`?" and compute the transform between two timestamps. This is the key to +making atency-aware fusion mathematically valid. + +Pose buffers dramatically improve **stability and predictability** as well. +They can prevent feedback oscillations caused by injecting corrections at +inconsistent times and enable smoothing, gating, and replay-based estimators. +These are incredibly important for accurate autonomous paths, reliable +auto-aim, and multi-camera fusion. + + +### Implementation as Virtual Subsystems + +The Az-RBSI pose buffer implementation is based on the principle that **Drive +owns the authoritative pose history** via a `poseBuffer` keyed by FPGA +timestamp, and we make sure that buffer is populated using the *same timebase* +as the estimator. Rather than updating the estimator only “once per loop,” +**all high-rate odometry samples** collected since the last loop are replayed +and inserted into the buffer. + +We have a series of three Virtual Subsystems that work together to compute the +estimated position of the robot each loop (20 ms), polled in this order: +* Imu +* DriveOdometry +* Vision + +The IMU is treated separately from the rest of the drive odometry because we +use its values in the Accelerometer virtual subsystem to compute the +accelerations the robot undergoes. Its `inputs` snapshot is refreshed before +odometry replay runs so that during odometry replay, we prefer using the IMU’s +**odometry yaw queue** when it exists and is aligned to the drivetrain odometry +timestamps. If now, we fall back to interpolating yaw from `yawBuffer` (or +"now" yaw if we have no queue). This allows for stable yaw-rate gating +(single-camera measurements discarded if the robot is spinning too quickly) +because `yawRateBuffer` is updated in the same timebase as the odometry replay. +When vision asks, "what is the max yaw rate over `[ts-lookback, ts]`," it is +querying a consistent history instead of a mix of current-time samples. + +The `DriveOdometry` virtual subsystem drains the PhoenixOdometryThread queues +to get a canonical timestamp array upon which is built the +`SwerveModulePosition` snapshots for each sample index. The YAW from the IMU +is computed for that same sample time, then the module positions and YAW are +added to the pose estimator using the `.updateWithTime()` function for each +timestamp in the queue. At the same time, we add the sample to the pose buffer +so that later consumers (vision alignment, gating, smoothing) can ask, "What +did the robot think at time `t`?" Practically, it runs early in the loop, +drains module odometry queues, performs the `updateWithTime(...)` replay, and +keeps the `poseBuffer`, `yawBuffer`, and `yawRateBuffer` coherent. + +Vision measurements get included *after* odometry has advanced and buffered +poses for the relevant timestamps. Vision reads all camera observations, +applies various gates, chooses one best observation per camera, then fuses them +by picking a fusion time `tF` (newest accepted timestamp), and **time-aligning +each camera estimate from its `ts` to `tF` using Drive’s pose buffer**. The +smoothed/fused result is then injected through the `addVisionMeasurement()` +consumer in `Drive` at the correct timestamp. The key is: we never try to +"correct the present" with delayed vision; we correct the past, and the +estimator/pose buffer machinery carries that correction forward coherently. + +To guarantee the right computation order, we implemented a simple +**priority/ordering mechanism for VirtualSubsystems** rather than relying on +construction order. Conceptually: `Imu` runs first (refresh sensor snapshot and +yaw queue), then `DriveOdometry` runs (drain odometry queues, replay estimator, +update buffers), then `Vision` runs (query pose history, fuse, inject +measurements), and finally anything downstream (targeting, coordinators, etc.). +With explicit ordering, vision always sees a pose buffer that is current +through the latest replayed timestamps, and its time alignment transform uses +consistent odometry states. + + +### Relationship Between Pose Buffering and Hardware Control Subsystems + +The `DriveOdometry` virtual subsystem exists to **isolate the heavy, +timing-sensitive replay logic** from the rest of `Drive` "control" behavior. +This separation allows `Drive`’s main subsystem to focus on setpoints/commands, +while `DriveOdometry` guarantees that by the time anything else runs, odometry +state and buffers are already up to date for the current cycle. + +The pose buffering system sits cleanly between **raw hardware sampling** and +**high-level control**, acting as a time-synchronized "memory layer" for the +robot’s physical motion. At the bottom, hardware devices are sampled at high +frequency with timestamps measurements in FPGA time and compensation for CAN +latency. Those timestamped samples are drained and replayed inside +`DriveOdometry`, which feeds the `SwerveDrivePoseEstimator` object. This means +the estimator is not tied to the 20 ms main loop -- it advances according to +the *actual sensor sample times*. The result is a pose estimate that reflects +real drivetrain physics at the rate the hardware can provide, not just the +scheduler tick rate. + +On the control side, everything -- heading controllers, auto-alignment, vision +fusion, targeting -- consumes pose data that is both temporally accurate and +historically queryable. Controllers still run at the 20 ms loop cycle, but +they operate on a pose that was built from high-rate, latency-compensated +measurements. When vision injects corrections, it does so at the correct +historical timestamp, and the estimator propagates that correction forward +consistently. The net effect is tighter autonomous path tracking, more stable +aiming, and reduced oscillation under aggressive maneuvers -- because control +decisions are based on a pose model that more faithfully represents the real +robot’s motion and sensor timing rather than a simplified "latest value only" +approximation. diff --git a/doc/RBSI-Vision.md b/doc/RBSI-Vision.md index 4327098..1889285 100644 --- a/doc/RBSI-Vision.md +++ b/doc/RBSI-Vision.md @@ -72,7 +72,7 @@ using a measuring tape to compare the reported vision-derived distance from each camera to one or more AprilTags with reality. -#### Using PhotonVision for vision simulation +#### Using PhotonVision for Vision Simulation This is an advanced topic, and is therefore in the Restricted Section. (More information about vision simulation to come in a future release.) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 23a3dc3..df22b2c 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -106,6 +106,8 @@ public static void disableHAL() { public static final boolean tuningMode = false; + public static final double G_TO_MPS2 = 9.80665; // Gravitational acceleration in m/s/s + /************************************************************************* */ /** Physical Constants for Robot Operation ******************************* */ public static final class RobotConstants { diff --git a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java index 494e0ab..f26a07c 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java @@ -1,3 +1,20 @@ +// Copyright (c) 2024-2026 Az-FIRST +// http://github.com/AZ-First +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// version 3 as published by the Free Software Foundation or +// available in the root directory of this project. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + package frc.robot.subsystems.drive; import edu.wpi.first.math.geometry.Rotation2d; diff --git a/src/main/java/frc/robot/subsystems/imu/Imu.java b/src/main/java/frc/robot/subsystems/imu/Imu.java index c0a1ba6..854f718 100644 --- a/src/main/java/frc/robot/subsystems/imu/Imu.java +++ b/src/main/java/frc/robot/subsystems/imu/Imu.java @@ -22,58 +22,95 @@ import frc.robot.util.VirtualSubsystem; public class Imu extends VirtualSubsystem { + + // Declare the io and inputs private final ImuIO io; private final ImuIO.ImuIOInputs inputs = new ImuIO.ImuIOInputs(); - // Optional per-cycle cached objects (avoid repeated allocations) + // Per-cycle cached objects (to avoid repeated allocations) private long cacheStampNs = -1L; private Rotation2d cachedYaw = Rotation2d.kZero; private Translation3d cachedAccel = Translation3d.kZero; private Translation3d cachedJerk = Translation3d.kZero; - // Constructor + /** Constructor */ public Imu(ImuIO io) { this.io = io; } - // Priority value for this virtual subsystem + /** + * Priority value for this virtual subsystem + * + *

See `frc.robot.util.VirtualSubsystem` for a description of the suggested values for various + * virtual subsystems. + */ @Override protected int getPeriodPriority() { return -30; } - // Periodic function to read inputs - @Override + /** Periodic function to read inputs */ public void rbsiPeriodic() { io.updateInputs(inputs); } - /** Hot-path access: primitive-only snapshot */ + /** + * Get the inputs objects + * + *

Hot-path access: primitive-only snapshot + * + * @return The inputs objects + */ public ImuIO.ImuIOInputs getInputs() { return inputs; } - /** Readable boundary: Rotation2d (alloc/cached per timestamp) */ + /** + * Get the current YAW + * + *

This function updates the caches if needed. + * + * @return The current YAW as a Rotation2d object + */ public Rotation2d getYaw() { refreshCachesIfNeeded(); return cachedYaw; } - /** Readable boundary: Translation3d accel (alloc/cached per timestamp) */ + /** + * Get the current linear acceleration + * + *

This function updates the caches as needed. + * + * @return The current linear acceleration as a Translation3d object + */ public Translation3d getLinearAccel() { refreshCachesIfNeeded(); return cachedAccel; } + /** + * Get the current jerk + * + *

This function updates the caches ad needed. + * + * @return The current jerk as a Translation3d object + */ public Translation3d getJerk() { refreshCachesIfNeeded(); return cachedJerk; } + /** + * Zero the YAW to this input value + * + * @param yaw Input YAW + */ public void zeroYaw(Rotation2d yaw) { io.zeroYawRad(yaw.getRadians()); } + /** Refresh the caches from the inputs, if needed */ private void refreshCachesIfNeeded() { final long stamp = inputs.timestampNs; if (stamp == cacheStampNs) return; diff --git a/src/main/java/frc/robot/subsystems/imu/ImuIO.java b/src/main/java/frc/robot/subsystems/imu/ImuIO.java index bf350c4..8ee521e 100644 --- a/src/main/java/frc/robot/subsystems/imu/ImuIO.java +++ b/src/main/java/frc/robot/subsystems/imu/ImuIO.java @@ -24,9 +24,6 @@ /** * Single IMU interface exposing all relevant state: orientation, rates, linear accel, jerk, and * odometry samples. - * - *

Primitive-only core: NO WPILib geometry objects, NO Units objects. Conversions happen at the - * boundary in the Imu subsystem (wrapper methods). */ public interface ImuIO extends RBSIIO { @@ -34,28 +31,21 @@ public interface ImuIO extends RBSIIO { class ImuIOInputs { public boolean connected = false; - /** FPGA-local timestamp when inputs were captured (ns) */ + // FPGA-local timestamp when inputs were captured (ns) public long timestampNs = 0L; - - /** Yaw angle (robot frame) in radians */ + // Yaw angle (robot frame) in radians public double yawPositionRad = 0.0; - - /** Yaw angular rate in radians/sec */ + // Yaw angular rate in radians/sec public double yawRateRadPerSec = 0.0; - - /** Linear acceleration in robot frame (m/s^2) */ + // Linear acceleration in robot frame (m/s^2) public Translation3d linearAccel = Translation3d.kZero; - - /** Linear jerk in robot frame (m/s^3) */ + // Linear jerk in robot frame (m/s^3) public Translation3d linearJerk = Translation3d.kZero; - - /** Time spent in the IO update call (seconds) */ + // Time spent in the IO update call (seconds) public double latencySeconds = 0.0; - - /** Optional odometry samples (timestamps in seconds) */ + // Odometry samples (timestamps in seconds) public double[] odometryYawTimestamps = new double[] {}; - - /** Optional odometry samples (yaw positions in radians) */ + // Odometry samples (yaw positions in radians) public double[] odometryYawPositionsRad = new double[] {}; } diff --git a/src/main/java/frc/robot/subsystems/imu/ImuIONavX.java b/src/main/java/frc/robot/subsystems/imu/ImuIONavX.java index 18fa3c2..97d4710 100644 --- a/src/main/java/frc/robot/subsystems/imu/ImuIONavX.java +++ b/src/main/java/frc/robot/subsystems/imu/ImuIONavX.java @@ -20,8 +20,10 @@ import com.studica.frc.AHRS; import com.studica.frc.AHRS.NavXComType; import edu.wpi.first.math.geometry.Translation3d; +import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; +import frc.robot.Constants; import frc.robot.subsystems.drive.PhoenixOdometryThread; import frc.robot.subsystems.drive.SwerveConstants; import java.util.Iterator; @@ -29,23 +31,23 @@ /** IMU IO for NavX. Primitive-only: yaw/rate in radians, accel in m/s^2, jerk in m/s^3. */ public class ImuIONavX implements ImuIO { - private static final double DEG_TO_RAD = Math.PI / 180.0; - private static final double G_TO_MPS2 = 9.80665; + // Define the NavX Hardware private final AHRS navx; - // Phoenix odometry queues (boxed Doubles, but we drain without streams) + // Queues private final Queue yawPositionDegQueue; private final Queue yawTimestampQueue; - // Previous accel (m/s^2) for jerk + // Previous accel for jerk calculation (m/s/s) private Translation3d prevAcc = Translation3d.kZero; private long prevTimestampNs = 0L; - // Reusable buffers for queue drain + // Reusable buffers for queue-drain (to avoid using streams) private double[] odomTsBuf = new double[8]; private double[] odomYawRadBuf = new double[8]; + /** Constructor */ public ImuIONavX() { // Initialize NavX over SPI navx = new AHRS(NavXComType.kMXP_SPI, (byte) SwerveConstants.kOdometryFrequency); @@ -63,10 +65,14 @@ public ImuIONavX() { yawPositionDegQueue = PhoenixOdometryThread.getInstance().registerSignal(navx::getYaw); } + /** Update the Inputs */ @Override public void updateInputs(ImuIOInputs inputs) { final long start = System.nanoTime(); + // Load the nanosecond timestamp + inputs.timestampNs = start; + inputs.connected = navx.isConnected(); // Your original sign convention: @@ -76,21 +82,17 @@ public void updateInputs(ImuIOInputs inputs) { // NavX: // - getAngle() is degrees (continuous) // - getRawGyroZ() is deg/sec - final double yawDeg = -navx.getAngle(); - final double yawRateDegPerSec = -navx.getRawGyroZ(); - - inputs.yawPositionRad = yawDeg * DEG_TO_RAD; - inputs.yawRateRadPerSec = yawRateDegPerSec * DEG_TO_RAD; + inputs.yawPositionRad = Units.degreesToRadians(-navx.getAngle()); + inputs.yawRateRadPerSec = Units.degreesToRadians(-navx.getRawGyroZ()); - // World linear accel (NavX returns "g" typically). Convert to m/s^2. + // World linear accel (NavX returns "g" typically); convert to m/s/s inputs.linearAccel = new Translation3d( - navx.getWorldLinearAccelX(), - navx.getWorldLinearAccelY(), - navx.getWorldLinearAccelZ()) - .times(G_TO_MPS2); + navx.getWorldLinearAccelX() * Constants.G_TO_MPS2, + navx.getWorldLinearAccelY() * Constants.G_TO_MPS2, + navx.getWorldLinearAccelZ() * Constants.G_TO_MPS2); - // Jerk + // Jerk computed as (delta accel) / dt if (prevTimestampNs != 0L) { final double dt = (start - prevTimestampNs) * 1e-9; if (dt > 1e-6) { @@ -98,14 +100,14 @@ public void updateInputs(ImuIOInputs inputs) { } } + // Load "previous values" for the next loop prevTimestampNs = start; prevAcc = inputs.linearAccel; - inputs.timestampNs = start; - - // Odometry history + // Drain odometry queues to primitive arrays (timestamps == doubles; yaws == degrees) final int n = drainOdomQueues(); if (n > 0) { + // If there's anything to drain... final double[] tsOut = new double[n]; final double[] yawOut = new double[n]; System.arraycopy(odomTsBuf, 0, tsOut, 0, n); @@ -113,10 +115,12 @@ public void updateInputs(ImuIOInputs inputs) { inputs.odometryYawTimestamps = tsOut; inputs.odometryYawPositionsRad = yawOut; } else { + // ...otherwise return empty arrays inputs.odometryYawTimestamps = new double[] {}; inputs.odometryYawPositionsRad = new double[] {}; } + // Compute how long this took in seconds final long end = System.nanoTime(); inputs.latencySeconds = (end - start) * 1e-9; } @@ -128,7 +132,7 @@ public void updateInputs(ImuIOInputs inputs) { */ @Override public void zeroYawRad(double yawRad) { - navx.setAngleAdjustment(yawRad / DEG_TO_RAD); + navx.setAngleAdjustment(Units.radiansToDegrees(yawRad)); navx.zeroYaw(); // Reset jerk history so you don't spike on the next frame @@ -136,6 +140,11 @@ public void zeroYawRad(double yawRad) { prevAcc = Translation3d.kZero; } + /** + * Drain the Odometry Queues into a Buffer + * + *

Private function that does the heavy lifting of draining the queues + */ private int drainOdomQueues() { final int nTs = yawTimestampQueue.size(); final int nYaw = yawPositionDegQueue.size(); @@ -157,7 +166,7 @@ private int drainOdomQueues() { // queue provides degrees (navx::getYaw). Apply your sign convention (-d) then rad. final double yawDeg = -itY.next(); - odomYawRadBuf[i] = yawDeg * DEG_TO_RAD; + odomYawRadBuf[i] = Units.degreesToRadians(yawDeg); i++; } @@ -167,6 +176,11 @@ private int drainOdomQueues() { return i; } + /** + * Check that buffer is big enough for this queue + * + *

Private function that ensures odometry buffer capacity + */ private void ensureOdomCapacity(int n) { if (odomTsBuf.length >= n) return; int newCap = odomTsBuf.length; diff --git a/src/main/java/frc/robot/subsystems/imu/ImuIOPigeon2.java b/src/main/java/frc/robot/subsystems/imu/ImuIOPigeon2.java index 0db40ef..a1f708b 100644 --- a/src/main/java/frc/robot/subsystems/imu/ImuIOPigeon2.java +++ b/src/main/java/frc/robot/subsystems/imu/ImuIOPigeon2.java @@ -27,6 +27,7 @@ import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.LinearAcceleration; +import frc.robot.Constants; import frc.robot.subsystems.drive.PhoenixOdometryThread; import frc.robot.subsystems.drive.SwerveConstants; import frc.robot.util.RBSICANBusRegistry; @@ -36,10 +37,7 @@ /** IMU IO for CTRE Pigeon2 */ public class ImuIOPigeon2 implements ImuIO { - // Constants - private static final double G_TO_MPS2 = 9.80665; - - // Define the Pigeon2 + // Define the Pigeon2 Hardware private final Pigeon2 pigeon = new Pigeon2( SwerveConstants.kPigeonId, RBSICANBusRegistry.getBus(SwerveConstants.kCANbusName)); @@ -55,15 +53,15 @@ public class ImuIOPigeon2 implements ImuIO { private final Queue odomTimestamps; private final Queue odomYawsDeg; - // Previous accel for jerk (m/s^2) + // Previous accel for jerk calculation (m/s/s) private Translation3d prevAcc = Translation3d.kZero; private long prevTimestampNs = 0L; - // Reusable buffers for queue-drain (avoid streams) + // Reusable buffers for queue-drain (to avoid using streams) private double[] odomTsBuf = new double[8]; private double[] odomYawRadBuf = new double[8]; - // Constructor + /** Constructor */ public ImuIOPigeon2() { pigeon.getConfigurator().apply(new Pigeon2Configuration()); pigeon.getConfigurator().setYaw(0.0); @@ -86,38 +84,40 @@ public ImuIOPigeon2() { public void updateInputs(ImuIOInputs inputs) { final long start = System.nanoTime(); + // Load the nanosecond timestamp + inputs.timestampNs = start; + StatusCode code = BaseStatusSignal.refreshAll(yawSignal, yawRateSignal, accelX, accelY, accelZ); inputs.connected = code.isOK(); // Yaw / rate: Phoenix returns degrees and deg/s here; convert to radians - final double yawDeg = yawSignal.getValueAsDouble(); - final double yawRateDegPerSec = yawRateSignal.getValueAsDouble(); + inputs.yawPositionRad = Units.degreesToRadians(yawSignal.getValueAsDouble()); + inputs.yawRateRadPerSec = Units.degreesToRadians(yawRateSignal.getValueAsDouble()); - inputs.yawPositionRad = Units.degreesToRadians(yawDeg); - inputs.yawRateRadPerSec = Units.degreesToRadians(yawRateDegPerSec); - - // Accel: Phoenix returns "g" for these signals (common for Pigeon2). Convert to m/s^2 + // Accel: Phoenix returns "g" for these signals; convert to m/s/s inputs.linearAccel = new Translation3d( - accelX.getValueAsDouble(), accelY.getValueAsDouble(), accelZ.getValueAsDouble()) - .times(G_TO_MPS2); + accelX.getValueAsDouble() * Constants.G_TO_MPS2, + accelY.getValueAsDouble() * Constants.G_TO_MPS2, + accelZ.getValueAsDouble() * Constants.G_TO_MPS2); - // Jerk from delta accel / dt + // Jerk computed as (delta accel) / dt if (prevTimestampNs != 0L) { final double dt = (start - prevTimestampNs) * 1e-9; + // Only compute if `dt` is larger than 1 ms. if (dt > 1e-6) { inputs.linearJerk = inputs.linearAccel.minus(prevAcc).div(dt); } } + // Load "previous values" for the next loop prevTimestampNs = start; prevAcc = inputs.linearAccel; - inputs.timestampNs = start; - - // Drain odometry queues to primitive arrays (timestamps are already doubles; yaws are degrees) + // Drain odometry queues to primitive arrays (timestamps == doubles; yaws == degrees) final int n = drainOdometryQueuesIntoBuffers(); if (n > 0) { + // If there's anything to drain... final double[] tsOut = new double[n]; final double[] yawOut = new double[n]; System.arraycopy(odomTsBuf, 0, tsOut, 0, n); @@ -125,10 +125,12 @@ public void updateInputs(ImuIOInputs inputs) { inputs.odometryYawTimestamps = tsOut; inputs.odometryYawPositionsRad = yawOut; } else { + // ...otherwise return empty arrays inputs.odometryYawTimestamps = new double[] {}; inputs.odometryYawPositionsRad = new double[] {}; } + // Compute how long this took in seconds final long end = System.nanoTime(); inputs.latencySeconds = (end - start) * 1e-9; } @@ -143,6 +145,11 @@ public void zeroYawRad(double yawRad) { pigeon.setYaw(Units.radiansToDegrees(yawRad)); } + /** + * Drain the Odometry Queues into a Buffer + * + *

Private function that does the heavy lifting of draining the queues + */ private int drainOdometryQueuesIntoBuffers() { final int nTs = odomTimestamps.size(); final int nYaw = odomYawsDeg.size(); @@ -171,6 +178,11 @@ private int drainOdometryQueuesIntoBuffers() { return i; } + /** + * Check that buffer is big enough for this queue + * + *

Private function that ensures odometry buffer capacity + */ private void ensureOdomCapacity(int n) { if (odomTsBuf.length >= n) return; int newCap = odomTsBuf.length; From 5fa0ae4bc22def50ee606d07e798b5003abb37c3 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Sat, 14 Feb 2026 12:47:55 -0700 Subject: [PATCH 15/22] Clean up Drive and DriveOdometry code --- src/main/java/frc/robot/Constants.java | 12 +- .../frc/robot/subsystems/drive/Drive.java | 248 ++++++++---------- .../robot/subsystems/drive/DriveOdometry.java | 186 ++----------- 3 files changed, 131 insertions(+), 315 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index df22b2c..7e3af17 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -74,7 +74,7 @@ public final class Constants { private static SwerveType swerveType = SwerveType.PHOENIX6; // PHOENIX6, YAGSL private static CTREPro phoenixPro = CTREPro.UNLICENSED; // LICENSED, UNLICENSED private static AutoType autoType = AutoType.MANUAL; // MANUAL, PATHPLANNER, CHOREO - private static VisionType visionType = VisionType.PHOTON; // PHOTON, LIMELIGHT, NONE + private static VisionType visionType = VisionType.NONE; // PHOTON, LIMELIGHT, NONE /** Enumerate the robot types (name your robots here) */ public static enum RobotType { @@ -313,19 +313,15 @@ public static final class DrivebaseConstants { public static final double kNominalFFVolts = 2.0; // Volts // Default TalonFX Gains (Replaces what's in Phoenix X's Tuner Constants) - // NOTE: Default values from 6328's 2025 Public Code - // - // IMPORTANT:: These values are valid only for CTRE LICENSED operation!! - // Adjust these downward until your modules behave correctly - public static final double kDriveP = 40.0; + public static final double kDriveP = 4.0; public static final double kDriveD = 0.03; public static final double kDriveV = 0.83; public static final double kDriveA = 0.0; public static final double kDriveS = 2.00; public static final double kDriveT = SwerveConstants.kDriveGearRatio / DCMotor.getKrakenX60Foc(1).KtNMPerAmp; - public static final double kSteerP = 400.0; - public static final double kSteerD = 20.0; + public static final double kSteerP = 4.0; + public static final double kSteerD = 0.02; public static final double kSteerS = 2.0; // Odometry-related constants diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index fda4cde..8ebda99 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -32,8 +32,6 @@ import edu.wpi.first.math.kinematics.SwerveDriveKinematics; import edu.wpi.first.math.kinematics.SwerveModulePosition; import edu.wpi.first.math.kinematics.SwerveModuleState; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N3; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; @@ -73,7 +71,7 @@ public class Drive extends RBSISubsystem { private final Module[] modules = new Module[4]; // FL, FR, BL, BR private final SysIdRoutine sysId; - // Buffers for necessary things + // Pose Buffer Declarations private final ConcurrentTimeInterpolatableBuffer poseBuffer = ConcurrentTimeInterpolatableBuffer.createBuffer(DrivebaseConstants.kHistorySize); private final ConcurrentTimeInterpolatableBuffer yawBuffer = @@ -95,12 +93,6 @@ public class Drive extends RBSISubsystem { new SwerveModulePosition(), new SwerveModulePosition() }; - private final SwerveModulePosition[] odomPositions = { - new SwerveModulePosition(), - new SwerveModulePosition(), - new SwerveModulePosition(), - new SwerveModulePosition() - }; private SwerveDrivePoseEstimator m_PoseEstimator = new SwerveDrivePoseEstimator(kinematics, Rotation2d.kZero, lastModulePositions, Pose2d.kZero); @@ -250,23 +242,17 @@ public Drive(Imu imu) { } /************************************************************************* */ - /** Periodic function that is called each robot cycle by the command scheduler */ + /** Periodic function that is called each cycle by the command scheduler */ @Override public void rbsiPeriodic() { - // NO odometryLock needed unless you touch poseEstimator directly here. - // Keep this focused on control / setpoints / characterization. + // The only function of the drive periodic() is to stop the modules if the DriverStation is + // diabled. if (DriverStation.isDisabled()) { for (var module : modules) module.stop(); Logger.recordOutput("SwerveStates/Setpoints", new SwerveModuleState[] {}); Logger.recordOutput("SwerveStates/SetpointsOptimized", new SwerveModuleState[] {}); } - - // If you need module refresh for control, you can either: - // A) leave it in DriveOdometry (recommended) and here just use cached inputs, OR - // B) keep a lightweight "module.controlPeriodic()" that doesn't drain queues. - // - // For now: do nothing here re: odometry. } /** @@ -285,7 +271,7 @@ public void simulationPeriodic() { modules[i].simulationPeriodic(); } - // Get module states from modules + // Get module states from modules (ok to allocate; can be cached later if desired) final SwerveModuleState[] moduleStates = new SwerveModuleState[modules.length]; for (int i = 0; i < modules.length; i++) { moduleStates[i] = modules[i].getState(); @@ -305,31 +291,14 @@ public void simulationPeriodic() { imu.simulationSetOmegaRadPerSec(omegaRadPerSec); imu.simulationSetLinearAccelMps2(ax, ay, 0.0); - // Feed PoseEstimator with authoritative yaw and module positions - final SwerveModulePosition[] modulePositions = new SwerveModulePosition[modules.length]; - for (int i = 0; i < modules.length; i++) { - modulePositions[i] = modules[i].getPosition(); - } - m_PoseEstimator.resetPosition( - Rotation2d.fromRadians(yawRad), modulePositions, simPhysics.getPose()); - - // If simulated vision available, inject vision measurement - if (simulatedVisionAvailable) { - final Pose2d visionPose = getSimulatedVisionPose(); - final double visionTimestamp = Timer.getFPGATimestamp(); - final var visionStdDevs = getSimulatedVisionStdDevs(); - m_PoseEstimator.addVisionMeasurement(visionPose, visionTimestamp, visionStdDevs); - } - - poseBuffer.addSample(Timer.getFPGATimestamp(), simPhysics.getPose()); - - // Logging + // Logging ONLY for physics (NOT estimator) Logger.recordOutput("Sim/Pose", simPhysics.getPose()); Logger.recordOutput("Sim/YawRad", yawRad); - Logger.recordOutput("Sim/OmegaRadPerSec", simPhysics.getOmegaRadPerSec()); + Logger.recordOutput("Sim/OmegaRadPerSec", omegaRadPerSec); Logger.recordOutput("Sim/LinearAccelXY_mps2", new double[] {ax, ay}); } + /************************************************************************* */ /** Drive Base Action Functions ****************************************** */ /** @@ -387,7 +356,11 @@ public void runVelocity(ChassisSpeeds speeds) { Logger.recordOutput("SwerveStates/SetpointsOptimized", setpointStates); } - /** Runs the drive in a straight line with the specified drive output. */ + /** + * Runs the drive in a straight line with the specified drive output + * + * @param output Specified drive output for characterization + */ public void runCharacterization(double output) { for (int i = 0; i < 4; i++) { modules[i].runCharacterization(output); @@ -408,6 +381,7 @@ public ProfiledPIDController getAngleController() { return angleController; } + /************************************************************************* */ /** SysId Characterization Routines ************************************** */ /** Returns a command to run a quasistatic test in the specified direction. */ @@ -422,7 +396,10 @@ public Command sysIdDynamic(SysIdRoutine.Direction direction) { return run(() -> runCharacterization(0.0)).withTimeout(1.0).andThen(sysId.dynamic(direction)); } + /************************************************************************* */ /** Getter Functions ***************************************************** */ + + /** Returns the module array */ public Module[] getModules() { return modules; } @@ -462,7 +439,7 @@ public Pose2d getPose() { return m_PoseEstimator.getEstimatedPosition(); } - /** Returns the current odometry rotation. */ + /** Returns the current odometry YAW. */ @AutoLogOutput(key = "Odometry/Yaw") public Rotation2d getHeading() { if (Constants.getMode() == Mode.SIM) { @@ -584,9 +561,14 @@ public double getFFCharacterizationVelocity() { return output; } + /************************************************************************* */ /* Setter Functions ****************************************************** */ - /** Resets the current odometry pose. */ + /** + * Resets the current odometry pose + * + * @param pose The specified pose to which to reset the poseEsitmator + */ public void resetPose(Pose2d pose) { m_PoseEstimator.resetPosition(getHeading(), getModulePositions(), pose); markPoseReset(Timer.getFPGATimestamp()); @@ -602,19 +584,23 @@ public void zeroHeadingForAlliance() { markPoseReset(Timer.getFPGATimestamp()); } - /** Zeros the heading */ + /** Zeros the gyro regardless of the alliance */ public void zeroHeading() { imu.zeroYaw(Rotation2d.kZero); resetHeadingController(); markPoseReset(Timer.getFPGATimestamp()); } - /** Adds a vision measurement safely into the PoseEstimator. */ - public void addVisionMeasurement(TimedPose rbsiPose) { + /** + * Adds a vision measurement safely into the PoseEstimator + * + * @param timedPose The pose @ timestamp to add to the pose estimator + */ + public void addVisionMeasurement(TimedPose timedPose) { odometryLock.lock(); try { m_PoseEstimator.addVisionMeasurement( - rbsiPose.pose(), rbsiPose.timestampSeconds(), rbsiPose.stdDevs()); + timedPose.pose(), timedPose.timestampSeconds(), timedPose.stdDevs()); } finally { odometryLock.unlock(); } @@ -632,128 +618,42 @@ private void markPoseReset(double fpgaNow) { Logger.recordOutput("Drive/PoseResetTimestamp", lastPoseResetTimestamp); } - /** UTILITY FUNCTION SECTION ********************************************* */ - - /** CHOREO SECTION (Ignore if AutoType == PATHPLANNER) ******************* */ - - /** Choreo: Reset odometry */ - public Command resetOdometry(Pose2d orElseGet) { - // TODO Auto-generated method stub - throw new UnsupportedOperationException("Unimplemented method 'resetOdometry'"); - } - - /** Swerve request to apply during field-centric path following */ - @SuppressWarnings("unused") - private final SwerveRequest.ApplyFieldSpeeds m_pathApplyFieldSpeeds = - new SwerveRequest.ApplyFieldSpeeds(); - - // Choreo Controller Values - private final PIDController m_pathXController = new PIDController(10, 0, 0); - private final PIDController m_pathYController = new PIDController(10, 0, 0); - private final PIDController m_pathThetaController = new PIDController(7, 0, 0); - + /************************************************************************* */ /** - * Follows the given field-centric path sample with PID for Choreo + * DriveOdometry Helpers (package-private) * - * @param pose Current pose of the robot - * @param sample Sample along the path to follow - */ - public void choreoController(Pose2d pose, SwerveSample sample) { - m_pathThetaController.enableContinuousInput(-Math.PI, Math.PI); - - var targetSpeeds = sample.getChassisSpeeds(); - targetSpeeds.vxMetersPerSecond += m_pathXController.calculate(pose.getX(), sample.x); - targetSpeeds.vyMetersPerSecond += m_pathYController.calculate(pose.getY(), sample.y); - targetSpeeds.omegaRadiansPerSecond += - m_pathThetaController.calculate(pose.getRotation().getRadians(), sample.heading); - - // setControl( - // m_pathApplyFieldSpeeds - // .withSpeeds(targetSpeeds) - // .withWheelForceFeedforwardsX(sample.moduleForcesX()) - // .withWheelForceFeedforwardsY(sample.moduleForcesY())); - } - - public void followTrajectory(SwerveSample sample) { - // Get the current pose of the robot - Pose2d pose = getPose(); - - // Generate the next speeds for the robot - ChassisSpeeds speeds = - new ChassisSpeeds( - sample.vx + m_pathXController.calculate(pose.getX(), sample.x), - sample.vy + m_pathXController.calculate(pose.getX(), sample.y), - sample.omega - + m_pathXController.calculate(pose.getRotation().getRadians(), sample.heading)); - - // Apply the generated speeds - runVelocity(speeds); - } - - /** SIMULATION VISION FUNCTIONS ****************************************** */ - - // Vision measurement enabled in simulation - private boolean simulatedVisionAvailable = true; - - // Maximum simulated noise in meters/radians - private static final double SIM_VISION_POS_NOISE_M = 0.02; // +/- 2cm - private static final double SIM_VISION_YAW_NOISE_RAD = Math.toRadians(2); // +/- 2 degrees - - /** - * Returns a simulated Pose2d for vision in field coordinates. Adds a small random jitter to - * simulate measurement error. + *

The pose estimator and pose buffers are owned by Drive, but DriveOdometry needs access to + * them in order to update and process the odometry. These functions are the appropriate + * pass-throughs to allow this functionality. */ - private Pose2d getSimulatedVisionPose() { - Pose2d truePose = simPhysics.getPose(); // authoritative pose - - // Add small random noise - double dx = (Math.random() * 2 - 1) * SIM_VISION_POS_NOISE_M; - double dy = (Math.random() * 2 - 1) * SIM_VISION_POS_NOISE_M; - double dTheta = (Math.random() * 2 - 1) * SIM_VISION_YAW_NOISE_RAD; - - return new Pose2d( - truePose.getX() + dx, - truePose.getY() + dy, - truePose.getRotation().plus(new Rotation2d(dTheta))); - } - - /** - * Returns the standard deviations for the simulated vision measurement. These values are used by - * the PoseEstimator to weight vision updates. - */ - private edu.wpi.first.math.Matrix getSimulatedVisionStdDevs() { - edu.wpi.first.math.Matrix stdDevs = - new edu.wpi.first.math.Matrix<>(N3.instance, N1.instance); - stdDevs.set(0, 0, 0.02); // X standard deviation (meters) - stdDevs.set(1, 0, 0.02); // Y standard deviation (meters) - stdDevs.set(2, 0, Math.toRadians(2)); // rotation standard deviation (radians) - return stdDevs; - } - - // --- Helpers used by DriveOdometry (package-private) --- + /** Get the pose estimator current pose */ Pose2d poseEstimatorGetPose() { return m_PoseEstimator.getEstimatedPosition(); } + /** Update the pose estimator at a timestamp */ void poseEstimatorUpdateWithTime(double t, Rotation2d yaw, SwerveModulePosition[] positions) { m_PoseEstimator.updateWithTime(t, yaw, positions); } + /** Add a sample to the pose buffer */ void poseBufferAddSample(double t, Pose2d pose) { poseBuffer.addSample(t, pose); } - // Yaw buffer helpers (assuming you already have yawBuffer + yawRateBuffer) + /** Yaw buffer helper */ double yawBufferSampleOr(double t, double fallbackYawRad) { return yawBuffer.getSample(t).orElse(fallbackYawRad); } + /** Yaw buffer helper */ void yawBuffersAddSample(double t, double yawRad, double yawRateRadPerSec) { yawBuffer.addSample(t, yawRad); yawRateBuffer.addSample(t, yawRateRadPerSec); } + /** Yaw buffer helper */ void yawBuffersFillFromQueue(double[] yawTs, double[] yawPosRad) { for (int k = 0; k < yawTs.length; k++) { yawBuffer.addSample(yawTs[k], yawPosRad[k]); @@ -766,6 +666,7 @@ void yawBuffersFillFromQueue(double[] yawTs, double[] yawPosRad) { } } + /** Yaw buffer helper */ void yawBuffersAddSampleIndexAligned(double t, double[] yawTs, double[] yawPos, int i) { yawBuffer.addSample(t, yawPos[i]); if (i > 0) { @@ -776,11 +677,13 @@ void yawBuffersAddSampleIndexAligned(double t, double[] yawTs, double[] yawPos, } } + /** Set the gyroDisconnectedAlert */ void setGyroDisconnectedAlert(boolean disconnected) { gyroDisconnectedAlert.set(disconnected); } - // Drive.java + /************************************************************************* */ + /** Simulation Getter Functions (from simPhysics) */ public Pose2d getSimPose() { return simPhysics.getPose(); } @@ -792,4 +695,61 @@ public double getSimYawRad() { public double getSimYawRateRadPerSec() { return simPhysics.getOmegaRadPerSec(); } + + /************************************************************************* */ + /** CHOREO SECTION (Ignore if AutoType == PATHPLANNER) ******************* */ + + /** Choreo: Reset odometry */ + public Command resetOdometry(Pose2d orElseGet) { + // TODO Auto-generated method stub + throw new UnsupportedOperationException("Unimplemented method 'resetOdometry'"); + } + + /** Swerve request to apply during field-centric path following */ + @SuppressWarnings("unused") + private final SwerveRequest.ApplyFieldSpeeds m_pathApplyFieldSpeeds = + new SwerveRequest.ApplyFieldSpeeds(); + + // Choreo Controller Values + private final PIDController m_pathXController = new PIDController(10, 0, 0); + private final PIDController m_pathYController = new PIDController(10, 0, 0); + private final PIDController m_pathThetaController = new PIDController(7, 0, 0); + + /** + * Follows the given field-centric path sample with PID for Choreo + * + * @param pose Current pose of the robot + * @param sample Sample along the path to follow + */ + public void choreoController(Pose2d pose, SwerveSample sample) { + m_pathThetaController.enableContinuousInput(-Math.PI, Math.PI); + + var targetSpeeds = sample.getChassisSpeeds(); + targetSpeeds.vxMetersPerSecond += m_pathXController.calculate(pose.getX(), sample.x); + targetSpeeds.vyMetersPerSecond += m_pathYController.calculate(pose.getY(), sample.y); + targetSpeeds.omegaRadiansPerSecond += + m_pathThetaController.calculate(pose.getRotation().getRadians(), sample.heading); + + // setControl( + // m_pathApplyFieldSpeeds + // .withSpeeds(targetSpeeds) + // .withWheelForceFeedforwardsX(sample.moduleForcesX()) + // .withWheelForceFeedforwardsY(sample.moduleForcesY())); + } + + public void followTrajectory(SwerveSample sample) { + // Get the current pose of the robot + Pose2d pose = getPose(); + + // Generate the next speeds for the robot + ChassisSpeeds speeds = + new ChassisSpeeds( + sample.vx + m_pathXController.calculate(pose.getX(), sample.x), + sample.vy + m_pathXController.calculate(pose.getX(), sample.y), + sample.omega + + m_pathXController.calculate(pose.getRotation().getRadians(), sample.heading)); + + // Apply the generated speeds + runVelocity(speeds); + } } diff --git a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java index f26a07c..9925064 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java @@ -27,37 +27,48 @@ import org.littletonrobotics.junction.Logger; public final class DriveOdometry extends VirtualSubsystem { + + // Declare the io and inputs private final Drive drive; private final Imu imu; private final Module[] modules; - // Scratch (no per-loop allocations) + // Per-cycle cached objects (to avoid repeated allocations) private final SwerveModulePosition[] odomPositions = new SwerveModulePosition[4]; + /** Constructor */ public DriveOdometry(Drive drive, Imu imu, Module[] modules) { this.drive = drive; this.imu = imu; this.modules = modules; } - // Priority value for this virtual subsystem + /** + * Priority value for this virtual subsystem + * + *

See `frc.robot.util.VirtualSubsystem` for a description of the suggested values for various + * virtual subsystems. + */ @Override protected int getPeriodPriority() { return -20; } + /** Periodic function to read inputs */ @Override public void rbsiPeriodic() { Drive.odometryLock.lock(); try { + // Ensure IMU inputs are fresh for this cycle final var imuInputs = imu.getInputs(); // Drain per-module odometry queues ONCE per loop (this also refreshes motor signals) for (var module : modules) { - module.periodic(); // if you later split, this becomes module.updateInputs() + module.periodic(); } if (Constants.getMode() == Mode.SIM) { + // SIMULATION: Keep sim pose buffer time-aligned, too final double now = Timer.getFPGATimestamp(); drive.poseBufferAddSample(now, drive.getSimPose()); drive.yawBuffersAddSample(now, drive.getSimYawRad(), drive.getSimYawRateRadPerSec()); @@ -83,7 +94,7 @@ public void rbsiPeriodic() { modHist[m] = modules[m].getOdometryPositions(); } - // Yaw queue availability + // Determine YAW queue availability (everything exists and lines up) final boolean hasYawQueue = imuInputs.connected && imuInputs.odometryYawTimestamps != null @@ -95,6 +106,9 @@ public void rbsiPeriodic() { final double[] yawPos = hasYawQueue ? imuInputs.odometryYawPositionsRad : null; // Determine index alignment (cheap + deterministic) + // We only trust index alignment if BOTH: + // - yaw has at least n samples + // - yawTs[i] ~= ts[i] for i in range (tight epsilon) boolean yawIndexAligned = false; if (hasYawQueue && yawTs.length >= n) { yawIndexAligned = true; @@ -116,7 +130,7 @@ public void rbsiPeriodic() { drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); } - // Replay + // Replay each odometry sample for (int i = 0; i < n; i++) { final double t = ts[i]; @@ -132,18 +146,21 @@ public void rbsiPeriodic() { } } + // Determine yaw at this timestamp double yawRad = imuInputs.yawPositionRad; if (hasYawQueue) { if (yawIndexAligned) { yawRad = yawPos[i]; - // Keep yaw buffers aligned to replay timeline (good for yaw-rate gate) + // Keep yaw buffers aligned to replay timeline drive.yawBuffersAddSampleIndexAligned(t, yawTs, yawPos, i); } else { yawRad = drive.yawBufferSampleOr(t, imuInputs.yawPositionRad); } } + // Feed estimator at this historical timestamp drive.poseEstimatorUpdateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); + // Maintain pose history in SAME timebase as estimator drive.poseBufferAddSample(t, drive.poseEstimatorGetPose()); } @@ -154,161 +171,4 @@ public void rbsiPeriodic() { Drive.odometryLock.unlock(); } } - - // /************************************************************************* */ - // /** Periodic function that is called each robot cycle by the command scheduler */ - // @Override - // public void rbsiPeriodic() { - // odometryLock.lock(); - // try { - // // Ensure IMU inputs are fresh for this cycle - // final var imuInputs = imu.getInputs(); - - // // Stop modules & log empty setpoint states if disabled - // if (DriverStation.isDisabled()) { - // for (var module : modules) { - // module.stop(); - // } - // Logger.recordOutput("SwerveStates/Setpoints", new SwerveModuleState[] {}); - // Logger.recordOutput("SwerveStates/SetpointsOptimized", new SwerveModuleState[] {}); - // } - - // // Drain per-module odometry queues for this cycle - // for (var module : modules) { - // module.periodic(); - // } - - // // -------- REAL ODOMETRY REPLAY (canonical timestamps from module[0]) -------- - // if (Constants.getMode() != Mode.SIM) { - // final double[] ts = modules[0].getOdometryTimestamps(); - // final int n = (ts == null) ? 0 : ts.length; - - // // Cache per-module histories ONCE (avoid repeated getters in the loop) - // final SwerveModulePosition[][] modHist = new SwerveModulePosition[4][]; - // for (int m = 0; m < 4; m++) { - // modHist[m] = modules[m].getOdometryPositions(); - // } - - // // Determine yaw queue availability - // final boolean hasYawQueue = - // imuInputs.connected - // && imuInputs.odometryYawTimestamps != null - // && imuInputs.odometryYawPositionsRad != null - // && imuInputs.odometryYawTimestamps.length - // == imuInputs.odometryYawPositionsRad.length - // && imuInputs.odometryYawTimestamps.length > 0; - - // final double[] yawTs = hasYawQueue ? imuInputs.odometryYawTimestamps : null; - // final double[] yawPos = hasYawQueue ? imuInputs.odometryYawPositionsRad : null; - - // // If we have no module samples, still keep yaw buffers “alive” for gating callers - // if (n == 0) { - // final double now = Timer.getFPGATimestamp(); - // yawBuffer.addSample(now, imuInputs.yawPositionRad); - // yawRateBuffer.addSample(now, imuInputs.yawRateRadPerSec); - - // gyroDisconnectedAlert.set(!imuInputs.connected); - // return; - // } - - // // Decide whether yaw queue is index-aligned with module[0] timestamps. - // // We only trust index alignment if BOTH: - // // - yaw has at least n samples - // // - yawTs[i] ~= ts[i] for i in range (tight epsilon) - // boolean yawIndexAligned = false; - // if (hasYawQueue && yawTs.length >= n) { - // yawIndexAligned = true; - // final double eps = 1e-3; // 1 ms - // for (int i = 0; i < n; i++) { - // if (Math.abs(yawTs[i] - ts[i]) > eps) { - // yawIndexAligned = false; - // break; - // } - // } - // } - - // // If yaw is NOT index-aligned but we have a yaw queue, build yaw/yawRate buffers ONCE. - // if (hasYawQueue && !yawIndexAligned) { - // for (int k = 0; k < yawTs.length; k++) { - // yawBuffer.addSample(yawTs[k], yawPos[k]); - // if (k > 0) { - // final double dt = yawTs[k] - yawTs[k - 1]; - // if (dt > 1e-6) { - // yawRateBuffer.addSample(yawTs[k], (yawPos[k] - yawPos[k - 1]) / dt); - // } - // } - // } - // } - - // // If NO yaw queue, add a single “now” sample once (don’t do this per replay sample) - // if (!hasYawQueue) { - // final double now = Timer.getFPGATimestamp(); - // yawBuffer.addSample(now, imuInputs.yawPositionRad); - // yawRateBuffer.addSample(now, imuInputs.yawRateRadPerSec); - // } - - // // Replay each odometry sample - // for (int i = 0; i < n; i++) { - // final double t = ts[i]; - - // // Build module positions at this sample index (clamp defensively) - // for (int m = 0; m < 4; m++) { - // final SwerveModulePosition[] hist = modHist[m]; - // if (hist == null || hist.length == 0) { - // odomPositions[m] = modules[m].getPosition(); - // } else if (i < hist.length) { - // odomPositions[m] = hist[i]; - // } else { - // odomPositions[m] = hist[hist.length - 1]; - // } - // } - - // // Determine yaw at this timestamp - // double yawRad = imuInputs.yawPositionRad; // fallback - - // if (hasYawQueue) { - // if (yawIndexAligned) { - // yawRad = yawPos[i]; - - // // Keep yaw/yawRate buffers updated in odometry timebase (good for yaw-gate) - // yawBuffer.addSample(t, yawRad); - // if (i > 0) { - // final double dt = yawTs[i] - yawTs[i - 1]; - // if (dt > 1e-6) { - // yawRateBuffer.addSample(t, (yawPos[i] - yawPos[i - 1]) / dt); - // } - // } - // } else { - // // yawBuffer was pre-filled above; interpolate here - // yawRad = yawBuffer.getSample(t).orElse(imuInputs.yawPositionRad); - // } - // } - - // // Feed estimator at this historical timestamp - // m_PoseEstimator.updateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); - - // // Maintain pose history in SAME timebase as estimator - // poseBuffer.addSample(t, m_PoseEstimator.getEstimatedPosition()); - // } - - // Logger.recordOutput("Drive/Pose", m_PoseEstimator.getEstimatedPosition()); - // gyroDisconnectedAlert.set(!imuInputs.connected); - // return; - - // } else { - - // // SIMULATION: Keep sim pose buffer time-aligned, too - // double now = Timer.getFPGATimestamp(); - // poseBuffer.addSample(now, simPhysics.getPose()); - // yawBuffer.addSample(now, simPhysics.getYaw().getRadians()); - // yawRateBuffer.addSample(now, simPhysics.getOmegaRadPerSec()); - - // Logger.recordOutput("Drive/Pose", simPhysics.getPose()); - // gyroDisconnectedAlert.set(false); - // } - // } finally { - // odometryLock.unlock(); - // } - // } - } From 01d0cc2c5a16b72fc96f65a5558445175c68fb0b Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Sat, 14 Feb 2026 14:15:24 -0700 Subject: [PATCH 16/22] Commenting the Vision.java file --- .../frc/robot/subsystems/vision/Vision.java | 134 ++++++++++++++---- 1 file changed, 104 insertions(+), 30 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 0928d65..271904b 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -109,7 +109,12 @@ public Vision(Drive drive, PoseMeasurementConsumer consumer, VisionIO... io) { } } - // Priority value for this virtual subsystem + /** + * Priority value for this virtual subsystem + * + *

See `frc.robot.util.VirtualSubsystem` for a description of the suggested values for various + * virtual subsystems. + */ @Override protected int getPeriodPriority() { return -10; @@ -171,6 +176,7 @@ public void rbsiPeriodic() { continue; } + // If this estimate is better than the existing "best", update this -> best TimedPose est = built.estimate; if (best == null || isBetter(est, best)) { best = est; @@ -180,6 +186,7 @@ public void rbsiPeriodic() { } } + // Add an accepted measurement, and update if (best != null) { accepted++; lastAcceptedTsPerCam[cam] = best.timestampSeconds(); @@ -193,39 +200,46 @@ public void rbsiPeriodic() { Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTagCount", bestTagCount); } + // Log everything from this camera Logger.recordOutput("Vision/Camera" + cam + "/ObsSeen", seen); Logger.recordOutput("Vision/Camera" + cam + "/ObsAccepted", accepted); Logger.recordOutput("Vision/Camera" + cam + "/ObsRejected", rejected); } + // If no "accepted" pose measurements from this loop, return now if (perCamAccepted.isEmpty()) return; - // Fusion time is the newest timestamp among accepted per-camera samples - double tF = + // Fusion time is the newest timestamp among accepted per-camera samples; return if NaN + double tFusion = perCamAccepted.stream().mapToDouble(e -> e.timestampSeconds()).max().orElse(Double.NaN); - if (!Double.isFinite(tF)) return; + if (!Double.isFinite(tFusion)) return; - // Time-align camera estimates to tF using odometry buffer, then inverse-variance fuse - TimedPose fused = fuseAtTime(perCamAccepted, tF); + // Time-align camera estimates to tFusion using odometry buffer, then inverse-variance fuse; + // return if null + TimedPose fused = fuseAtTime(perCamAccepted, tFusion); if (fused == null) return; - // Smooth by fusing recent fused estimates (also aligned to tF) + // Smooth by fusing recent fused estimates (also aligned to tFusion); return if null + // NOTE: THIS IS WHERE THE PROBLEM LIES, I THINK. THE FUSED POSE IS OKAY, BUT THE SMOOTHED POSE + // IS NOT!!! pushFused(fused); - TimedPose smoothed = smoothAtTime(tF); + TimedPose smoothed = smoothAtTime(tFusion); if (smoothed == null) return; // Inject the pose consumer.accept(smoothed); + // Log the fused and smoothed poses along with tFusion Logger.recordOutput("Vision/FusedPose", fused.pose()); Logger.recordOutput("Vision/SmoothedPose", smoothed.pose()); - Logger.recordOutput("Vision/FusedTimestamp", tF); + Logger.recordOutput("Vision/FusedTimestamp", tFusion); } + /************************************************************************* */ /** Runtime configuration hooks ****************************************** */ /** - * Call when you reset odometry (e.g. auto start, manual reset, etc). + * Call when odometry is reset (e.g. auto start, manual reset, etc). * * @param fpgaNowSeconds Timestamp for the pose gate reset */ @@ -245,7 +259,7 @@ public void setTrustedTags(Set tags) { } /** - * Set whether to requite trusted tags + * Set whether to require trusted tags * * @param require Boolean */ @@ -277,7 +291,10 @@ public void setSingleTagYawGate(boolean enabled, double lookbackSec, double limi yawGateLimitRadPerSec = limitRadPerSec; } + /************************************************************************* */ /** Gating + Scoring ***************************************************** */ + + /** GateResult Class */ private static final class GateResult { final boolean accepted; final String reason; @@ -288,6 +305,12 @@ private static final class GateResult { } } + /** + * Gating Function -- checks all sorts of things! + * + * @param cam Camera index + * @param obs PoseObservation + */ private GateResult passesHardGatesAndYawGate(int cam, VisionIO.PoseObservation obs) { final double ts = obs.timestamp(); @@ -325,6 +348,7 @@ private GateResult passesHardGatesAndYawGate(int cam, VisionIO.PoseObservation o return new GateResult(true, ""); } + /** Built Estimate Class */ private static final class BuiltEstimate { final TimedPose estimate; final double trustScale; @@ -337,12 +361,19 @@ private static final class BuiltEstimate { } } + /** + * Build a pose esitmate + * + * @param cam Camera Index + * @param obs PoseObservation + */ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { - // Base uncertainty grows with distance^2 / tagCount (your 2486-style) + // Base uncertainty grows with distance^2 / tagCount final double tagCount = Math.max(1, obs.tagCount()); final double avgDist = Math.max(0.0, obs.averageTagDistance()); final double distFactor = (avgDist * avgDist) / tagCount; + // Camera uncertainty factor final double camFactor = (cam < camConfigs.length) ? camConfigs[cam].stdDevFactor() : 1.0; double linearStdDev = linearStdDevBaseline * camFactor * distFactor; @@ -361,13 +392,14 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { if (kTrusted.contains(id)) trustedCount++; } + // If no trusted tags, return null if (requireTrustedTag && trustedCount == 0) { return null; } + // Build the trust scale final int usedCount = obs.usedTagIds().size(); final double fracTrusted = (usedCount == 0) ? 0.0 : ((double) trustedCount / usedCount); - final double trustScale = untrustedTagStdDevScale + fracTrusted * (trustedTagStdDevScale - untrustedTagStdDevScale); @@ -386,6 +418,12 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { trustedCount); } + /** + * Evaluate whether a is better than b + * + * @param a Base pose + * @param b Competitor pose + */ private boolean isBetter(TimedPose a, TimedPose b) { // Lower trace of stddev vector (x+y+theta) is better double ta = a.stdDevs().get(0, 0) + a.stdDevs().get(1, 0) + a.stdDevs().get(2, 0); @@ -393,40 +431,67 @@ private boolean isBetter(TimedPose a, TimedPose b) { return ta < tb; } + /************************************************************************* */ /** Time alignment & fusion ********************************************** */ - private TimedPose fuseAtTime(ArrayList estimates, double tF) { + + /** + * Fuse poses at a specified timestamp + * + * @param estimates Array of TimedPose esitmates + * @param tFusion The timestamp at which to fuse the measurements + */ + private TimedPose fuseAtTime(ArrayList estimates, double tFusion) { final ArrayList aligned = new ArrayList<>(estimates.size()); for (var e : estimates) { - Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tF); + Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tFusion); if (alignedPose == null) return null; - aligned.add(new TimedPose(alignedPose, tF, e.stdDevs())); + aligned.add(new TimedPose(alignedPose, tFusion, e.stdDevs())); } - return inverseVarianceFuse(aligned, tF); + return inverseVarianceFuse(aligned, tFusion); } - private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tF) { + /** + * Align a pose to where it would have been at the fusion time + * + *

Gets the odometric poses at ts and tFusion from the drivebase PoseEstimator, computes the + * transform between them, and applies that to the vision pose. + * + * @param visionPoseAtTs The pose at ts + * @param ts Timestamp of the pose + * @param tFusion Fusion timestamp + * @return Transformed Pose2d + */ + private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tFusion) { Optional odomAtTsOpt = drive.getPoseAtTime(ts); - Optional odomAtTFOpt = drive.getPoseAtTime(tF); + Optional odomAtTFOpt = drive.getPoseAtTime(tFusion); + // If empty, return null if (odomAtTsOpt.isEmpty() || odomAtTFOpt.isEmpty()) return null; - Pose2d odomAtTs = odomAtTsOpt.get(); - Pose2d odomAtTF = odomAtTFOpt.get(); - // Transform that takes odomAtTs -> odomAtTF - Transform2d ts_T_tf = odomAtTF.minus(odomAtTs); + Transform2d ts_T_tf = odomAtTFOpt.get().minus(odomAtTsOpt.get()); // Apply same motion to vision pose to bring it forward return visionPoseAtTs.transformBy(ts_T_tf); } - private TimedPose inverseVarianceFuse(ArrayList alignedAtTF, double tF) { + /** + * Fuse a list of poses using inverse variable weighting + * + * @param alignedAtTF List of aligned poses + * @param tFusion Fusion timestamp + * @return Fuesed TimedPose object + */ + private TimedPose inverseVarianceFuse(ArrayList alignedAtTF, double tFusion) { + // If size of alignedAtTF is 0 or 1, return null or the only value if (alignedAtTF == null || alignedAtTF.isEmpty()) return null; if (alignedAtTF.size() == 1) return alignedAtTF.get(0); + // Define summing values double sumWx = 0.0, sumWy = 0.0, sumWth = 0.0; double sumX = 0.0, sumY = 0.0; double sumCos = 0.0, sumSin = 0.0; + // Loop over poses in the list for (int i = 0; i < alignedAtTF.size(); i++) { final TimedPose e = alignedAtTF.get(i); final Pose2d p = e.pose(); @@ -462,9 +527,10 @@ private TimedPose inverseVarianceFuse(ArrayList alignedAtTF, double t sumSin += rot.getSin() * wth; } - // If everything got skipped, fail closed. + // If everything got skipped; return null if (sumWx <= 0.0 || sumWy <= 0.0 || sumWth <= 0.0) return null; + // Construct the fused translation final Translation2d fusedTranslation = new Translation2d(sumX / sumWx, sumY / sumWy); // Rotation2d(cos, sin) will normalize internally; if both are ~0, fall back to zero. @@ -473,15 +539,23 @@ private TimedPose inverseVarianceFuse(ArrayList alignedAtTF, double t ? Rotation2d.kZero : new Rotation2d(sumCos, sumSin); + // The fused pose is the combination of translation and rotation final Pose2d fusedPose = new Pose2d(fusedTranslation, fusedRotation); + // Fused standard deviations final Matrix fusedStdDevs = VecBuilder.fill(Math.sqrt(1.0 / sumWx), Math.sqrt(1.0 / sumWy), Math.sqrt(1.0 / sumWth)); - return new TimedPose(fusedPose, tF, fusedStdDevs); + // Construct and return the TimedPose objects + return new TimedPose(fusedPose, tFusion, fusedStdDevs); } + /************************************************************************* */ /** Smoothing buffer ***************************************************** */ + + /** THIS LIKELY HAS PROBLEMS */ + + /** Push the fused pose */ private void pushFused(TimedPose fused) { fusedBuffer.addLast(fused); @@ -497,18 +571,18 @@ private void pushFused(TimedPose fused) { } } - private TimedPose smoothAtTime(double tF) { + private TimedPose smoothAtTime(double tFusion) { if (fusedBuffer.isEmpty()) return null; if (fusedBuffer.size() == 1) return fusedBuffer.peekLast(); final ArrayList aligned = new ArrayList<>(fusedBuffer.size()); for (var e : fusedBuffer) { - Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tF); + Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tFusion); if (alignedPose == null) continue; - aligned.add(new TimedPose(alignedPose, tF, e.stdDevs())); + aligned.add(new TimedPose(alignedPose, tFusion, e.stdDevs())); } if (aligned.isEmpty()) return fusedBuffer.peekLast(); - return inverseVarianceFuse(aligned, tF); + return inverseVarianceFuse(aligned, tFusion); } } From f6a938e526e4ad84c784f581f690a8d416a52631 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Mon, 16 Feb 2026 10:01:06 -0700 Subject: [PATCH 17/22] PoseBuffer: Correctly align timestamps and poses MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit That plot (purple exploding to tens of thousands of feet) is exactly what you see when the time-alignment math is applying the odometry delta in the wrong reference frame. The fused pose stays sane because it’s only aligning aw camera estimates (which are usually already close to odom), but the smoother repeatedly re-aligns already-fused field poses across a sliding window — and a small frame mistake turns into a huge “ping-pong” once you do it over and over. --- doc/RBSI-PoseBuffer.md | 19 + src/main/java/frc/robot/Constants.java | 9 +- src/main/java/frc/robot/Robot.java | 3 +- src/main/java/frc/robot/RobotContainer.java | 21 +- .../accelerometer/Accelerometer.java | 4 +- .../frc/robot/subsystems/drive/Drive.java | 73 +++- .../robot/subsystems/drive/DriveOdometry.java | 69 ++- .../robot/subsystems/drive/ModuleIOSim.java | 4 +- .../frc/robot/subsystems/imu/ImuIOSim.java | 4 +- .../frc/robot/subsystems/vision/Vision.java | 401 +++++++++++++----- .../frc/robot/subsystems/vision/VisionIO.java | 9 +- .../subsystems/vision/VisionIOLimelight.java | 81 ++-- .../vision/VisionIOPhotonVision.java | 16 +- src/main/java/frc/robot/util/Alert.java | 3 +- .../ConcurrentTimeInterpolatableBuffer.java | 59 ++- src/main/java/frc/robot/util/TimeUtil.java | 32 ++ 16 files changed, 619 insertions(+), 188 deletions(-) create mode 100644 src/main/java/frc/robot/util/TimeUtil.java diff --git a/doc/RBSI-PoseBuffer.md b/doc/RBSI-PoseBuffer.md index efbb828..60823c4 100644 --- a/doc/RBSI-PoseBuffer.md +++ b/doc/RBSI-PoseBuffer.md @@ -129,3 +129,22 @@ aiming, and reduced oscillation under aggressive maneuvers -- because control decisions are based on a pose model that more faithfully represents the real robot’s motion and sensor timing rather than a simplified "latest value only" approximation. + + +### Behavior when the Robot is Disabled + +In normal operation (robot enabled), vision measurements are incorporated using standard Kalman fusion via addVisionMeasurement(). This is a probabilistic update: the estimator weighs the vision measurement against the predicted state based on covariance, producing a smooth, statistically optimal correction. Small errors are gently nudged toward vision; large discrepancies are handled proportionally according to the reported measurement uncertainty. This is the correct and intended behavior for a moving robot. + +When the robot is disabled, however, the estimator is no longer operating in a dynamic system. Wheel odometry is effectively static, process noise collapses, and repeated vision corrections can cause pathological estimator behavior (particularly in translation). Instead of performing another Kalman update in this regime, the system switches to a controlled pose blending strategy. Each accepted vision pose is blended toward the current estimate using a fixed interpolation factor (e.g., 10–20%), and the estimator is explicitly reset to that blended pose. This produces a gradual convergence toward the vision solution without allowing covariance collapse or runaway corrections. + +The result is a stable and intuitive pre-match behavior: while disabled, the robot will slowly “walk” its pose estimate toward the vision solution if needed, but it will not snap violently or diverge numerically. Once enabled, the system seamlessly returns to proper Kalman fusion, where vision and odometry interact in a fully dynamic and statistically grounded manner. + +### Design Rationale – Split Enabled/Disabled Vision Handling + +The core reason for separating enabled and disabled behavior is that the Kalman filter assumes a **dynamic system model**. When the robot is enabled, the drivetrain is actively moving and the estimator continuously predicts forward using wheel odometry and gyro inputs. Vision measurements then act as bounded corrections against that prediction. In this regime, Kalman fusion is mathematically appropriate: process noise and measurement noise are balanced, covariance evolves realistically, and corrections remain stable. + +When the robot is disabled, however, the system is no longer dynamic. Wheel distances stop changing, gyro rate is near zero, and process noise effectively collapses. If vision continues injecting measurements into the estimator with timestamps that are slightly offset from the estimator’s internal state, the filter can enter a degenerate regime. Because translational covariance may shrink aggressively while no true motion exists, even small inconsistencies between time-aligned vision and odometry can produce disproportionately large corrections. This is why translation can numerically “explode” while rotation often remains stable—rotation is typically better constrained by the gyro and wraps naturally, while translation depends more directly on integrated wheel deltas and covariance scaling. + +The disabled blending pattern avoids this pathological case by temporarily stepping outside strict Kalman fusion. Instead of applying repeated measurement updates against a near-zero process model, we treat vision as a slowly converging reference and explicitly blend the current estimate toward it. This maintains numerical stability, prevents covariance collapse artifacts, and still allows the pose to settle accurately before a match begins. + +Once the robot transitions back to enabled, the estimator resumes normal probabilistic fusion with a healthy process model. The split-mode approach therefore preserves mathematical correctness while the robot is moving, and guarantees numerical stability while it is stationary. diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 7e3af17..59647ab 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -30,6 +30,7 @@ import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.util.Units; import edu.wpi.first.units.measure.Mass; import edu.wpi.first.wpilibj.PowerDistribution; import edu.wpi.first.wpilibj.RobotBase; @@ -324,8 +325,14 @@ public static final class DrivebaseConstants { public static final double kSteerD = 0.02; public static final double kSteerS = 2.0; - // Odometry-related constants + // Odometry-related constants ================================== public static final double kHistorySize = 1.5; // seconds + // How aggressively to pull pose toward vision while DISABLED. + // 0.10 = gentle, 0.25 = fairly quick, 1.0 = full snap. + public static final double kDisabledVisionBlendAlpha = 0.15; + // Optional: ignore obviously insane measurements while disabled. + public static final double kDisabledVisionMaxJumpM = 2.0; // meters + public static final double kDisabledVisionMaxJumpRad = Units.degreesToRadians(20.0); } /************************************************************************* */ diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index b9668ae..92196f6 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -25,6 +25,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; import frc.robot.Constants.PowerConstants; +import frc.robot.util.TimeUtil; import frc.robot.util.VirtualSubsystem; import org.littletonrobotics.junction.LogFileUtil; import org.littletonrobotics.junction.LoggedPowerDistribution; @@ -192,7 +193,7 @@ public void autonomousInit() { CommandScheduler.getInstance().cancelAll(); m_robotContainer.getDrivebase().setMotorBrake(true); m_robotContainer.getDrivebase().resetHeadingController(); - m_robotContainer.getVision().resetPoseGate(Timer.getFPGATimestamp()); + m_robotContainer.getVision().resetPoseGate(TimeUtil.now()); // TODO: Make sure Gyro inits here with whatever is in the path planning thingie switch (Constants.getAutoType()) { diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 5b74cf6..e80e242 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -222,7 +222,9 @@ public RobotContainer() { m_flywheel = new Flywheel(new FlywheelIO() {}); m_vision = - new Vision(m_drivebase, m_drivebase::addVisionMeasurement, buildVisionIOsReplay()); + new Vision( + m_drivebase, m_drivebase::addVisionMeasurement, buildVisionIOsReplay(m_drivebase)); + m_accel = new Accelerometer(m_imu); sweep = null; break; @@ -563,8 +565,21 @@ private VisionIO[] buildVisionIOsSim(Drive drive) { } // Vision Factories (REPLAY) - private VisionIO[] buildVisionIOsReplay() { - return new VisionIO[] {}; // simplest: Vision does nothing during replay + private VisionIO[] buildVisionIOsReplay(Drive drive) { + var cams = Constants.Cameras.ALL; + + VisionIO[] ios = new VisionIO[cams.length]; + for (int i = 0; i < cams.length; i++) { + ios[i] = + new VisionIO() { + @Override + public void updateInputs(VisionIOInputs inputs) { + // Intentionally empty. + // Logger.processInputs("Vision/Camera" + i, inputs) will populate these from the log. + } + }; + } + return ios; } /** diff --git a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java index 0b5ff65..205edd4 100644 --- a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java +++ b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java @@ -14,10 +14,10 @@ package frc.robot.subsystems.accelerometer; import edu.wpi.first.math.geometry.Translation3d; -import edu.wpi.first.wpilibj.Timer; import frc.robot.Constants; import frc.robot.Constants.RobotConstants; import frc.robot.subsystems.imu.Imu; +import frc.robot.util.TimeUtil; import frc.robot.util.VirtualSubsystem; import org.littletonrobotics.junction.Logger; @@ -95,7 +95,7 @@ public void rbsiPeriodic() { final double[] ts = imuInputs.odometryYawTimestamps; if (ts.length > 0) { - Logger.recordOutput("IMU/OdometryLatencySec", Timer.getFPGATimestamp() - ts[ts.length - 1]); + Logger.recordOutput("IMU/OdometryLatencySec", TimeUtil.now() - ts[ts.length - 1]); } } } diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 8ebda99..3098132 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -37,7 +37,6 @@ import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.Constants; @@ -50,6 +49,7 @@ import frc.robot.util.RBSIEnum.Mode; import frc.robot.util.RBSIParsing; import frc.robot.util.RBSISubsystem; +import frc.robot.util.TimeUtil; import frc.robot.util.TimedPose; import java.util.Optional; import java.util.OptionalDouble; @@ -264,6 +264,10 @@ public void rbsiPeriodic() { */ @Override public void simulationPeriodic() { + + // IMPORTANT: do not run sim physics during REPLAY + if (Constants.getMode() != Mode.SIM) return; + final double dt = Constants.loopPeriodSecs; // Advance module wheel physics @@ -477,6 +481,14 @@ public Optional getPoseAtTime(double timestampSeconds) { return poseBuffer.getSample(timestampSeconds); } + public double getPoseBufferOldestTime() { + return poseBuffer.getOldestTimestamp().getAsDouble(); + } + + public double getPoseBufferNewestTime() { + return poseBuffer.getNewestTimestamp().getAsDouble(); + } + /** * Max abs yaw rate over [t0, t1] using buffered yaw-rate history * @@ -571,7 +583,7 @@ public double getFFCharacterizationVelocity() { */ public void resetPose(Pose2d pose) { m_PoseEstimator.resetPosition(getHeading(), getModulePositions(), pose); - markPoseReset(Timer.getFPGATimestamp()); + markPoseReset(TimeUtil.now()); } /** Zeros the gyro based on alliance color */ @@ -581,28 +593,69 @@ public void zeroHeadingForAlliance() { ? Rotation2d.kZero : Rotation2d.k180deg); resetHeadingController(); - markPoseReset(Timer.getFPGATimestamp()); + markPoseReset(TimeUtil.now()); } /** Zeros the gyro regardless of the alliance */ public void zeroHeading() { imu.zeroYaw(Rotation2d.kZero); resetHeadingController(); - markPoseReset(Timer.getFPGATimestamp()); + markPoseReset(TimeUtil.now()); } /** * Adds a vision measurement safely into the PoseEstimator * - * @param timedPose The pose @ timestamp to add to the pose estimator + * @param measurement The pose @ timestamp to add to the pose estimator */ - public void addVisionMeasurement(TimedPose timedPose) { - odometryLock.lock(); + // Called by Vision via consumer.accept(TimedPose) + public void addVisionMeasurement(TimedPose meas) { + Drive.odometryLock.lock(); try { - m_PoseEstimator.addVisionMeasurement( - timedPose.pose(), timedPose.timestampSeconds(), timedPose.stdDevs()); + // Always use measurement timestamp when fusing (enabled path) + final double t = meas.timestampSeconds(); + + if (!DriverStation.isDisabled()) { + // ENABLED: normal soft fusion + m_PoseEstimator.addVisionMeasurement(meas.pose(), t, meas.stdDevs()); + return; + } + + // DISABLED: blend toward vision, then reset estimator to blended pose + final Pose2d current = m_PoseEstimator.getEstimatedPosition(); + final Pose2d vision = meas.pose(); + + // Optional sanity gate while disabled (prevents one bad frame from wrecking you) + final double dTrans = current.getTranslation().getDistance(vision.getTranslation()); + final double dRot = Math.abs(current.getRotation().minus(vision.getRotation()).getRadians()); + if (dTrans > DrivebaseConstants.kDisabledVisionMaxJumpM + || dRot > DrivebaseConstants.kDisabledVisionMaxJumpRad) { + Logger.recordOutput("Vision/DisabledReject", true); + Logger.recordOutput("Vision/DisabledReject_dTransM", dTrans); + Logger.recordOutput("Vision/DisabledReject_dRotRad", dRot); + return; + } + Logger.recordOutput("Vision/DisabledReject", false); + + // Controlled “soft snap” + final Pose2d blended = + current.interpolate(vision, DrivebaseConstants.kDisabledVisionBlendAlpha); + + // Reset estimator to blended pose (heading/modules are "now", but robot can't move while + // disabled) + m_PoseEstimator.resetPosition(getHeading(), getModulePositions(), blended); + + // Mark reset so Vision gates old samples, etc. + markPoseReset(TimeUtil.now()); + + // Keep pose buffer in sync immediately (helps timeAlignPose calls) + poseBufferAddSample(TimeUtil.now(), blended); + + Logger.recordOutput( + "Vision/DisabledBlendAlpha", DrivebaseConstants.kDisabledVisionBlendAlpha); + Logger.recordOutput("Vision/DisabledBlendedPose", blended); } finally { - odometryLock.unlock(); + Drive.odometryLock.unlock(); } } diff --git a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java index 9925064..900bd15 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java @@ -19,10 +19,11 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.SwerveModulePosition; -import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.DriverStation; import frc.robot.Constants; import frc.robot.subsystems.imu.Imu; import frc.robot.util.RBSIEnum.Mode; +import frc.robot.util.TimeUtil; import frc.robot.util.VirtualSubsystem; import org.littletonrobotics.junction.Logger; @@ -59,31 +60,55 @@ protected int getPeriodPriority() { public void rbsiPeriodic() { Drive.odometryLock.lock(); try { - // Ensure IMU inputs are fresh for this cycle final var imuInputs = imu.getInputs(); - // Drain per-module odometry queues ONCE per loop (this also refreshes motor signals) + // Drain per-module odometry queues ONCE per loop (refresh signals). for (var module : modules) { module.periodic(); } - if (Constants.getMode() == Mode.SIM) { - // SIMULATION: Keep sim pose buffer time-aligned, too - final double now = Timer.getFPGATimestamp(); + final boolean isReplayActive = Logger.hasReplaySource(); + + // Pure SIM (not replaying a log): use sim pose/yaw + if (Constants.getMode() == Mode.SIM && !isReplayActive) { + final double now = TimeUtil.now(); drive.poseBufferAddSample(now, drive.getSimPose()); drive.yawBuffersAddSample(now, drive.getSimYawRad(), drive.getSimYawRateRadPerSec()); Logger.recordOutput("Drive/Pose", drive.getSimPose()); return; } + // DISABLED (REAL or REPLAY): minimal ticking — keep buffers alive, do NOT integrate module + // deltas. + // Exception: if you *want* replay odometry integration while disabled, remove the + // DriverStation + // guard and keep the original replay loop. + if (DriverStation.isDisabled() && !isReplayActive) { + final double now = TimeUtil.now(); + + // keep yaw buffers alive + if (imuInputs.connected) { + drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); + } + + // keep pose buffer alive with the *current estimator pose* (which can be blended by + // disabled vision) + drive.poseBufferAddSample(now, drive.poseEstimatorGetPose()); + Logger.recordOutput("Drive/Pose", drive.poseEstimatorGetPose()); + drive.setGyroDisconnectedAlert(!imuInputs.connected); + return; + } + // Canonical timestamp queue from module[0] final double[] ts = modules[0].getOdometryTimestamps(); final int n = (ts == null) ? 0 : ts.length; // Always keep yaw buffers “alive” even if no samples if (n == 0) { - final double now = Timer.getFPGATimestamp(); - drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); + if (Constants.getMode() != Mode.REPLAY) { + final double now = TimeUtil.now(); + drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); + } drive.setGyroDisconnectedAlert(!imuInputs.connected); return; } @@ -126,7 +151,7 @@ public void rbsiPeriodic() { drive.yawBuffersFillFromQueue(yawTs, yawPos); } else if (!hasYawQueue) { // Single “now” sample once (not per replay) - final double now = Timer.getFPGATimestamp(); + final double now = TimeUtil.now(); drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); } @@ -158,6 +183,32 @@ public void rbsiPeriodic() { } } + // Debugging + Logger.recordOutput("Odometry/Debug/timestamp", t); + Logger.recordOutput("Odometry/Debug/now", TimeUtil.now()); + if (i > 0) { + Logger.recordOutput("Odometry/Debug/timeNowDiff", t - ts[i - 1]); + } + + Logger.recordOutput("Odometry/Debug/replay_t", t); + Logger.recordOutput("Odometry/Debug/replay_yawRad", yawRad); + + double[] lastDist = new double[4]; + boolean firstSample = true; + for (int m = 0; m < 4; m++) { + SwerveModulePosition pos = odomPositions[m]; + double dist = pos.distanceMeters; + + Logger.recordOutput("Odometry/Debug/mod" + m + "_distanceMeters", dist); + Logger.recordOutput("Odometry/Debug/mod" + m + "_angleRad", pos.angle.getRadians()); + if (!firstSample) { + double delta = dist - lastDist[m]; + Logger.recordOutput("Odometry/Debug/mod" + m + "_deltaMeters", delta); + } + + lastDist[m] = dist; + } + firstSample = false; // Feed estimator at this historical timestamp drive.poseEstimatorUpdateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); // Maintain pose history in SAME timebase as estimator diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java index 8fb64fe..ec87f59 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java @@ -15,9 +15,9 @@ import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.simulation.DCMotorSim; import frc.robot.Constants; +import frc.robot.util.TimeUtil; /** * Physics sim implementation of module IO. The sim models are configured using a set of module @@ -116,7 +116,7 @@ public void updateInputs(ModuleIOInputs inputs) { inputs.turnCurrentAmps = Math.abs(turnSim.getCurrentDrawAmps()); // Odometry (single sample per loop is fine) - inputs.odometryTimestamps = new double[] {Timer.getFPGATimestamp()}; + inputs.odometryTimestamps = new double[] {TimeUtil.now()}; inputs.odometryDrivePositionsRad = new double[] {mechanismPositionRad}; inputs.odometryTurnPositions = new Rotation2d[] {inputs.turnPosition}; } diff --git a/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java b/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java index a28212c..102b60e 100644 --- a/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java +++ b/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java @@ -19,7 +19,7 @@ import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.Timer; +import frc.robot.util.TimeUtil; import org.littletonrobotics.junction.Logger; /** Simulated IMU for full robot simulation & replay logging */ @@ -73,7 +73,7 @@ public void updateInputs(ImuIOInputs inputs) { inputs.linearJerk = Translation3d.kZero; // Maintain odometry history - pushOdomSample(Timer.getFPGATimestamp(), yawRad); + pushOdomSample(TimeUtil.now(), yawRad); // Export odometry arrays (copy out in chronological order) final int n = odomSize; diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 271904b..0753b67 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -88,6 +88,13 @@ public interface PoseMeasurementConsumer { // Variance minimum for fusing poses to prevent divide-by-zero explosions private static final double kMinVariance = 1e-12; + // Fields + private Pose2d lastFusedPose = new Pose2d(); + private Pose2d lastSmoothedPose = new Pose2d(); + private double lastFusedTs = Double.NaN; + private boolean lastFusedValid = false; + private boolean lastSmoothedValid = false; + /** Constructor */ public Vision(Drive drive, PoseMeasurementConsumer consumer, VisionIO... io) { this.drive = drive; @@ -124,115 +131,182 @@ protected int getPeriodPriority() { @Override public void rbsiPeriodic() { - // Pose reset logic and logging - long epoch = drive.getPoseResetEpoch(); - if (epoch != lastSeenPoseResetEpoch) { - lastSeenPoseResetEpoch = epoch; - resetPoseGate(drive.getLastPoseResetTimestamp()); - Logger.recordOutput("Vision/PoseGateResetFromDrive", true); - } else { - Logger.recordOutput("Vision/PoseGateResetFromDrive", false); - } + boolean hasAcceptedThisLoop = false; + boolean hasFusedThisLoop = false; + boolean hasSmoothedThisLoop = false; + + // Default debug outputs (so keys exist even if we return early) + double dbgAlignDt = Double.NaN; + double dbgDeltaTranslation = Double.NaN; + double dbgDeltaRotation = Double.NaN; + boolean dbgAlignFinite = false; + + try { + + lastAlignDbg.reset(); + // ---------------------------------------------------------------------- + // 1) Pose reset gate (clears smoothing state, resets per-cam monotonic gates) + // ---------------------------------------------------------------------- + long epoch = drive.getPoseResetEpoch(); + if (epoch != lastSeenPoseResetEpoch) { + lastSeenPoseResetEpoch = epoch; + resetPoseGate(drive.getLastPoseResetTimestamp()); + Logger.recordOutput("Vision/PoseGateResetFromDrive", true); + } else { + Logger.recordOutput("Vision/PoseGateResetFromDrive", false); + } - // Update & log camera inputs - for (int i = 0; i < io.length; i++) { - io[i].updateInputs(inputs[i]); - Logger.processInputs("Vision/Camera" + i, inputs[i]); - } + // ---------------------------------------------------------------------- + // 2) Read camera inputs (REAL/SIM/REPLAY all go through IO inputs) + // ---------------------------------------------------------------------- + for (int i = 0; i < io.length; i++) { + io[i].updateInputs(inputs[i]); + Logger.processInputs("Vision/Camera" + i, inputs[i]); + } - // Pick the one best accepted estimate per camera for this loop - final ArrayList perCamAccepted = new ArrayList<>(io.length); + // Optional always-on “health” debug + Logger.recordOutput("Vision/Debug/ioLength", io.length); + int totalObs = 0; + for (int i = 0; i < io.length; i++) { + totalObs += (inputs[i].poseObservations != null) ? inputs[i].poseObservations.length : 0; + } + Logger.recordOutput("Vision/Debug/totalObsThisLoop", totalObs); - // Loop over cameras - for (int cam = 0; cam < io.length; cam++) { + // ---------------------------------------------------------------------- + // 3) Choose best observation per camera for THIS loop + // ---------------------------------------------------------------------- + final ArrayList perCamAccepted = new ArrayList<>(io.length); - // Instantiate variables for this camera - int seen = 0; - int accepted = 0; - int rejected = 0; - TimedPose best = null; - double bestTrustScale = Double.NaN; - int bestTrustedCount = 0; - int bestTagCount = 0; + for (int cam = 0; cam < io.length; cam++) { - // Loop over observations for this camera this loop - for (var obs : inputs[cam].poseObservations) { + int seen = 0; + int accepted = 0; + int rejected = 0; - // Increment - seen++; + TimedPose best = null; + double bestTrustScale = Double.NaN; + int bestTrustedCount = 0; + int bestTagCount = 0; - // Check the gating criteria; move on if bad - GateResult gate = passesHardGatesAndYawGate(cam, obs); - Logger.recordOutput("Vision/Camera" + cam + "/GateFail", gate.reason); - if (!gate.accepted) { - rejected++; + final var obsArr = inputs[cam].poseObservations; + if (obsArr == null) { + Logger.recordOutput("Vision/Camera" + cam + "/ObsSeen", 0); + Logger.recordOutput("Vision/Camera" + cam + "/ObsAccepted", 0); + Logger.recordOutput("Vision/Camera" + cam + "/ObsRejected", 0); continue; } - // Build a pose estimate; move on if bad - BuiltEstimate built = buildEstimate(cam, obs); - if (built == null) { - rejected++; - continue; + for (var obs : obsArr) { + seen++; + + GateResult gate = passesHardGatesAndYawGate(cam, obs); + Logger.recordOutput("Vision/Camera" + cam + "/GateFail", gate.reason); + if (!gate.accepted) { + rejected++; + continue; + } + + BuiltEstimate built = buildEstimate(cam, obs); + if (built == null) { + rejected++; + continue; + } + + // Prefer “best” by your scoring function + if (best == null || isBetter(built.estimate, best)) { + best = built.estimate; + bestTrustScale = built.trustScale; + bestTrustedCount = built.trustedCount; + bestTagCount = obs.tagCount(); + } } - // If this estimate is better than the existing "best", update this -> best - TimedPose est = built.estimate; - if (best == null || isBetter(est, best)) { - best = est; - bestTrustScale = built.trustScale; - bestTrustedCount = built.trustedCount; - bestTagCount = obs.tagCount(); + if (best != null) { + accepted++; + lastAcceptedTsPerCam[cam] = best.timestampSeconds(); + perCamAccepted.add(best); + + Logger.recordOutput("Vision/Camera" + cam + "/InjectedPose2d", best.pose()); + Logger.recordOutput( + "Vision/Camera" + cam + "/InjectedTimestamp", best.timestampSeconds()); + Logger.recordOutput( + "Vision/Camera" + cam + "/InjectedStdDevs", stdDevsToArray(best.stdDevs())); + Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTrustScale", bestTrustScale); + Logger.recordOutput( + "Vision/Camera" + cam + "/LastAcceptedTrustedCount", bestTrustedCount); + Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTagCount", bestTagCount); } - } - // Add an accepted measurement, and update - if (best != null) { - accepted++; - lastAcceptedTsPerCam[cam] = best.timestampSeconds(); - perCamAccepted.add(best); - - Logger.recordOutput("Vision/Camera" + cam + "/InjectedPose2d", best.pose()); - Logger.recordOutput("Vision/Camera" + cam + "/InjectedTimestamp", best.timestampSeconds()); - Logger.recordOutput("Vision/Camera" + cam + "/InjectedStdDevs", best.stdDevs()); - Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTrustScale", bestTrustScale); - Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTrustedCount", bestTrustedCount); - Logger.recordOutput("Vision/Camera" + cam + "/LastAcceptedTagCount", bestTagCount); + Logger.recordOutput("Vision/Camera" + cam + "/ObsSeen", seen); + Logger.recordOutput("Vision/Camera" + cam + "/ObsAccepted", accepted); + Logger.recordOutput("Vision/Camera" + cam + "/ObsRejected", rejected); } - // Log everything from this camera - Logger.recordOutput("Vision/Camera" + cam + "/ObsSeen", seen); - Logger.recordOutput("Vision/Camera" + cam + "/ObsAccepted", accepted); - Logger.recordOutput("Vision/Camera" + cam + "/ObsRejected", rejected); - } + Logger.recordOutput("Vision/Debug/perCamAcceptedSize", perCamAccepted.size()); - // If no "accepted" pose measurements from this loop, return now - if (perCamAccepted.isEmpty()) return; - - // Fusion time is the newest timestamp among accepted per-camera samples; return if NaN - double tFusion = - perCamAccepted.stream().mapToDouble(e -> e.timestampSeconds()).max().orElse(Double.NaN); - if (!Double.isFinite(tFusion)) return; - - // Time-align camera estimates to tFusion using odometry buffer, then inverse-variance fuse; - // return if null - TimedPose fused = fuseAtTime(perCamAccepted, tFusion); - if (fused == null) return; - - // Smooth by fusing recent fused estimates (also aligned to tFusion); return if null - // NOTE: THIS IS WHERE THE PROBLEM LIES, I THINK. THE FUSED POSE IS OKAY, BUT THE SMOOTHED POSE - // IS NOT!!! - pushFused(fused); - TimedPose smoothed = smoothAtTime(tFusion); - if (smoothed == null) return; - - // Inject the pose - consumer.accept(smoothed); - - // Log the fused and smoothed poses along with tFusion - Logger.recordOutput("Vision/FusedPose", fused.pose()); - Logger.recordOutput("Vision/SmoothedPose", smoothed.pose()); - Logger.recordOutput("Vision/FusedTimestamp", tFusion); + if (perCamAccepted.isEmpty()) { + // No new vision accepted this loop; we still log cached outputs below (in finally). + return; + } + hasAcceptedThisLoop = true; + + // ---------------------------------------------------------------------- + // 4) Fuse all accepted cams at the newest timestamp among them + // ---------------------------------------------------------------------- + final double tFusion = + perCamAccepted.stream().mapToDouble(e -> e.timestampSeconds()).max().orElse(Double.NaN); + if (!Double.isFinite(tFusion)) return; + + final TimedPose fused = fuseAtTime(perCamAccepted, tFusion); + if (fused == null) return; + hasFusedThisLoop = true; + + // ---------------------------------------------------------------------- + // 5) Smooth by fusing recent fused estimates aligned to tFusion + // ---------------------------------------------------------------------- + pushFused(fused); + final TimedPose smoothed = smoothAtTime(tFusion); + if (smoothed == null) return; + hasSmoothedThisLoop = true; + + // ---------------------------------------------------------------------- + // 6) Update caches (ONLY HERE) + inject to drive + // ---------------------------------------------------------------------- + lastFusedPose = fused.pose(); + lastSmoothedPose = smoothed.pose(); + lastFusedTs = tFusion; + lastFusedValid = true; + lastSmoothedValid = true; + + consumer.accept(smoothed); + + // If you want, you can feed debug values from inside timeAlignPose(...) via fields, + // but leaving the plumbing as-is since you’re already logging inside helpers. + + } finally { + + // ---------------------------------------------------------------------- + // 7) “Ultra-clean” logging: one place, every loop, replay-safe + // ---------------------------------------------------------------------- + + // Always-present “outputs” + Logger.recordOutput("Vision/FusedPose", lastFusedPose); + Logger.recordOutput("Vision/SmoothedPose", lastSmoothedPose); + Logger.recordOutput("Vision/FusedTimestamp", lastFusedTs); + Logger.recordOutput("Vision/HasFused", lastFusedValid); + Logger.recordOutput("Vision/HasSmoothed", lastSmoothedValid); + + // Per-loop flags (never stale) + Logger.recordOutput("Vision/HasAcceptedThisLoop", hasAcceptedThisLoop); + Logger.recordOutput("Vision/HasFusedThisLoop", hasFusedThisLoop); + Logger.recordOutput("Vision/HasSmoothedThisLoop", hasSmoothedThisLoop); + + // Debug keys (exist even if not touched) + Logger.recordOutput("Vision/Debug/alignDt", lastAlignDbg.alignDt); + Logger.recordOutput("Vision/Debug/deltaTranslation", lastAlignDbg.deltaTranslation); + Logger.recordOutput("Vision/Debug/deltaRotation", lastAlignDbg.deltaRotation); + Logger.recordOutput("Vision/Debug/alignFinite", lastAlignDbg.alignFinite); + } } /************************************************************************* */ @@ -387,9 +461,11 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { // Trusted tag blending final Set kTrusted = trustedTags.get(); + final int[] usedIds = (obs.usedTagIds() != null) ? obs.usedTagIds() : new int[0]; + int trustedCount = 0; - for (int id : obs.usedTagIds()) { - if (kTrusted.contains(id)) trustedCount++; + for (int i = 0; i < usedIds.length; i++) { + if (kTrusted.contains(usedIds[i])) trustedCount++; } // If no trusted tags, return null @@ -398,7 +474,7 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { } // Build the trust scale - final int usedCount = obs.usedTagIds().size(); + final int usedCount = usedIds.length; final double fracTrusted = (usedCount == 0) ? 0.0 : ((double) trustedCount / usedCount); final double trustScale = untrustedTagStdDevScale + fracTrusted * (trustedTagStdDevScale - untrustedTagStdDevScale); @@ -406,9 +482,17 @@ private BuiltEstimate buildEstimate(int cam, VisionIO.PoseObservation obs) { linearStdDev *= trustScale; angularStdDev *= trustScale; + linearStdDev = Math.max(linearStdDev, linearStdDevBaseline); + angularStdDev = Math.max(angularStdDev, angularStdDevBaseline); + // Output logs for tuning Logger.recordOutput("Vision/Camera" + cam + "/InjectedFracTrusted", fracTrusted); + Logger.recordOutput("Vision/Camera" + cam + "/Dbg_linearStdDev", linearStdDev); + Logger.recordOutput("Vision/Camera" + cam + "/Dbg_angularStdDev", angularStdDev); + Logger.recordOutput("Vision/Camera" + cam + "/Dbg_avgDist", avgDist); + Logger.recordOutput("Vision/Camera" + cam + "/Dbg_tagCount", obs.tagCount()); + return new BuiltEstimate( new TimedPose( obs.pose().toPose2d(), @@ -431,6 +515,34 @@ private boolean isBetter(TimedPose a, TimedPose b) { return ta < tb; } + /************************************************************************* */ + /** Debug snapshot for the most-recent successful alignment this loop. */ + private static final class AlignDebug { + double alignDt = Double.NaN; + double deltaTranslation = Double.NaN; + double deltaRotation = Double.NaN; + boolean alignFinite = false; + + void reset() { + alignDt = Double.NaN; + deltaTranslation = Double.NaN; + deltaRotation = Double.NaN; + alignFinite = false; + } + + void set(double dt, Transform2d tf) { + alignDt = dt; + deltaTranslation = tf.getTranslation().getNorm(); + deltaRotation = tf.getRotation().getRadians(); + alignFinite = + Double.isFinite(alignDt) + && Double.isFinite(deltaTranslation) + && Double.isFinite(deltaRotation); + } + } + + private final AlignDebug lastAlignDbg = new AlignDebug(); + /************************************************************************* */ /** Time alignment & fusion ********************************************** */ @@ -443,7 +555,7 @@ private boolean isBetter(TimedPose a, TimedPose b) { private TimedPose fuseAtTime(ArrayList estimates, double tFusion) { final ArrayList aligned = new ArrayList<>(estimates.size()); for (var e : estimates) { - Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tFusion); + Pose2d alignedPose = timeAlignPoseFieldDelta(e.pose(), e.timestampSeconds(), tFusion); if (alignedPose == null) return null; aligned.add(new TimedPose(alignedPose, tFusion, e.stdDevs())); } @@ -454,7 +566,9 @@ private TimedPose fuseAtTime(ArrayList estimates, double tFusion) { * Align a pose to where it would have been at the fusion time * *

Gets the odometric poses at ts and tFusion from the drivebase PoseEstimator, computes the - * transform between them, and applies that to the vision pose. + * transform between them, and applies that to the vision pose. The correction is applied by + * finding the field-frame deltas for both translation and rotation, then returning a new Pose2d + * object that consists of the vision pose adjusted by the field-frame deltas. * * @param visionPoseAtTs The pose at ts * @param ts Timestamp of the pose @@ -462,18 +576,98 @@ private TimedPose fuseAtTime(ArrayList estimates, double tFusion) { * @return Transformed Pose2d */ private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tFusion) { + + Logger.recordOutput("Vision/Debug/ts", ts); + Logger.recordOutput("Vision/Debug/tFusion", tFusion); + Logger.recordOutput("Vision/Debug/alignDtMs", (tFusion - ts) * 1000.0); + + double dt = tFusion - ts; + Optional odomAtTsOpt = drive.getPoseAtTime(ts); Optional odomAtTFOpt = drive.getPoseAtTime(tFusion); // If empty, return null if (odomAtTsOpt.isEmpty() || odomAtTFOpt.isEmpty()) return null; - // Transform that takes odomAtTs -> odomAtTF + // Transform that takes odomAtTs -> odomAtTF (in odomAtTs frame) Transform2d ts_T_tf = odomAtTFOpt.get().minus(odomAtTsOpt.get()); - // Apply same motion to vision pose to bring it forward + double dtrans = ts_T_tf.getTranslation().getNorm(); + double drot = ts_T_tf.getRotation().getRadians(); + + boolean finite = + Double.isFinite(dt) + && Double.isFinite(dtrans) + && Double.isFinite(drot) + && Double.isFinite(odomAtTsOpt.get().getX()) + && Double.isFinite(odomAtTFOpt.get().getX()); + + // Even more debugging logging + Logger.recordOutput("Vision/Debug/alignDt", dt); + Logger.recordOutput("Vision/Debug/deltaTranslation", dtrans); + Logger.recordOutput("Vision/Debug/deltaRotation", drot); + Logger.recordOutput("Vision/Debug/alignFinite", finite); + Logger.recordOutput("Vision/Debug/odomAtTs", odomAtTsOpt.get()); + Logger.recordOutput("Vision/Debug/odomAtTF", odomAtTFOpt.get()); + + if (!finite) { + Logger.recordOutput("Vision/Debug/odomAtTs", odomAtTsOpt.get()); + Logger.recordOutput("Vision/Debug/odomAtTF", odomAtTFOpt.get()); + return null; + } + + // Debugging Logging + Logger.recordOutput("Vision/Debug/deltaTranslation", ts_T_tf.getTranslation().getNorm()); + Logger.recordOutput("Vision/Debug/deltaRotation", ts_T_tf.getRotation().getRadians()); + + // Apply the same SE(2) transform to the vision pose return visionPoseAtTs.transformBy(ts_T_tf); } + /** + * Align a pose to where it would have been at the fusion time + * + *

* + * + *

We compute: - dTrans = odomTF.translation - odomTs.translation (field frame) - dTheta = + * odomTF.rotation - odomTs.rotation (field frame / global heading delta) + * + *

Then apply those deltas directly to the vision pose at ts to estimate vision at tFusion. + * + *

Gets the odometric poses at ts and tFusion from the drivebase PoseEstimator, computes the + * transform between them, and applies that to the vision pose. The correction is applied by + * finding the field-frame deltas for both translation and rotation, then returning a new Pose2d + * object that consists of the vision pose adjusted by the field-frame deltas. + * + * @param visionPoseAtTs The pose at ts + * @param ts Timestamp of the pose + * @param tFusion Fusion timestamp + * @return Transformed Pose2d + */ + private Pose2d timeAlignPoseFieldDelta(Pose2d visionPoseAtTs, double ts, double tFusion) { + Optional odomAtTsOpt = drive.getPoseAtTime(ts); + Optional odomAtTFOpt = drive.getPoseAtTime(tFusion); + if (odomAtTsOpt.isEmpty() || odomAtTFOpt.isEmpty()) return null; + + final Pose2d odomAtTs = odomAtTsOpt.get(); + final Pose2d odomAtTF = odomAtTFOpt.get(); + + // FIELD-FRAME translation delta + final Translation2d dTrans = odomAtTF.getTranslation().minus(odomAtTs.getTranslation()); + + // Heading delta (Rotation2d handles wrapping) + final Rotation2d dTheta = odomAtTF.getRotation().minus(odomAtTs.getRotation()); + + // Update debug ONCE per loop (first successful alignment wins) + if (!lastAlignDbg.alignFinite) { + // For debug parity with the other version, package deltas as a Transform2d + lastAlignDbg.set(tFusion - ts, new Transform2d(dTrans, dTheta)); + } + + // Apply field-frame deltas to the vision pose + return new Pose2d( + visionPoseAtTs.getTranslation().plus(dTrans), visionPoseAtTs.getRotation().plus(dTheta)); + } + /** * Fuse a list of poses using inverse variable weighting * @@ -577,12 +771,19 @@ private TimedPose smoothAtTime(double tFusion) { final ArrayList aligned = new ArrayList<>(fusedBuffer.size()); for (var e : fusedBuffer) { - Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tFusion); + Pose2d alignedPose = timeAlignPoseFieldDelta(e.pose(), e.timestampSeconds(), tFusion); if (alignedPose == null) continue; aligned.add(new TimedPose(alignedPose, tFusion, e.stdDevs())); + // Debugging Logging + Logger.recordOutput("Vision/Debug/deltaTime", tFusion - e.timestampSeconds()); } if (aligned.isEmpty()) return fusedBuffer.peekLast(); return inverseVarianceFuse(aligned, tFusion); } + + /** UTILITY FUNCTIONS **************************************************** */ + private static double[] stdDevsToArray(Matrix s) { + return new double[] {s.get(0, 0), s.get(1, 0), s.get(2, 0)}; + } } diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIO.java b/src/main/java/frc/robot/subsystems/vision/VisionIO.java index 7bc61ed..dc249ec 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIO.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIO.java @@ -11,7 +11,6 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; -import java.util.Set; import org.littletonrobotics.junction.AutoLog; public interface VisionIO { @@ -41,8 +40,12 @@ record PoseObservation( int tagCount, double averageTagDistance, PoseObservationType type, - Set usedTagIds // immutable per observation - ) {} + int[] usedTagIds) { + // Compact constructor to coalesce null to empty + public PoseObservation { + usedTagIds = (usedTagIds == null) ? new int[0] : usedTagIds; + } + } enum PoseObservationType { MEGATAG_1, diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java index 07c83c7..a4c5d13 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java @@ -18,6 +18,7 @@ import edu.wpi.first.networktables.DoubleSubscriber; import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.wpilibj.RobotController; +import java.util.Arrays; import java.util.HashSet; import java.util.LinkedList; import java.util.List; @@ -55,57 +56,80 @@ public VisionIOLimelight(String name, Supplier rotationSupplier) { @Override public void updateInputs(VisionIOInputs inputs) { - // Update connection status based on whether an update has been seen in the last 250ms + // Update connection status inputs.connected = ((RobotController.getFPGATime() - latencySubscriber.getLastChange()) / 1000) < 250; - // Update target observation + // Target observation (simple tx/ty) inputs.latestTargetObservation = new TargetObservation( Rotation2d.fromDegrees(txSubscriber.get()), Rotation2d.fromDegrees(tySubscriber.get())); - // Update orientation for MegaTag 2 + // Push robot orientation for MegaTag 2 orientationPublisher.accept( new double[] {rotationSupplier.get().getDegrees(), 0.0, 0.0, 0.0, 0.0, 0.0}); - NetworkTableInstance.getDefault() - .flush(); // Increases network traffic but recommended by Limelight + NetworkTableInstance.getDefault().flush(); + + // Union of tag IDs seen this loop (for logging/UI only) + Set unionTagIds = new HashSet<>(); - // Read new pose observations from NetworkTables - Set tagIds = new HashSet<>(); List poseObservations = new LinkedList<>(); + + /* -------------------- MegaTag 1 -------------------- */ for (var rawSample : megatag1Subscriber.readQueue()) { if (rawSample.value.length == 0) continue; - for (int i = 11; i < rawSample.value.length; i += 7) { - tagIds.add((int) rawSample.value[i]); + + int tagCount = (int) rawSample.value[7]; + + // Build used tag array for THIS observation only + int[] used = new int[tagCount]; + int u = 0; + + for (int i = 11; i < rawSample.value.length && u < tagCount; i += 7) { + int id = (int) rawSample.value[i]; + used[u++] = id; + unionTagIds.add(id); } + poseObservations.add( new PoseObservation( - // Timestamp, based on server timestamp of publish and latency + // Timestamp (LL server time minus latency) rawSample.timestamp * 1.0e-6 - rawSample.value[6] * 1.0e-3, - // 3D pose estimate + // Pose parsePose(rawSample.value), - // Ambiguity, using only the first tag because ambiguity isn't applicable for multitag + // Ambiguity (first tag only) rawSample.value.length >= 18 ? rawSample.value[17] : 0.0, // Tag count - (int) rawSample.value[7], + tagCount, - // Average tag distance + // Avg distance rawSample.value[9], - // Observation type + // Type PoseObservationType.MEGATAG_1, - // Visible Tag IDs - tagIds)); + // Used tag IDs + used)); } + + /* -------------------- MegaTag 2 -------------------- */ for (var rawSample : megatag2Subscriber.readQueue()) { if (rawSample.value.length == 0) continue; - for (int i = 11; i < rawSample.value.length; i += 7) { - tagIds.add((int) rawSample.value[i]); + + int tagCount = (int) rawSample.value[7]; + + int[] used = new int[tagCount]; + int u = 0; + + for (int i = 11; i < rawSample.value.length && u < tagCount; i += 7) { + int id = (int) rawSample.value[i]; + used[u++] = id; + unionTagIds.add(id); } + poseObservations.add( new PoseObservation( // Timestamp, based on server timestamp of publish and latency @@ -125,23 +149,20 @@ public void updateInputs(VisionIOInputs inputs) { // Observation type PoseObservationType.MEGATAG_2, - - // Visible Tag IDs - tagIds)); + used)); } - // Save pose observations to inputs object - inputs.poseObservations = new PoseObservation[poseObservations.size()]; - for (int i = 0; i < poseObservations.size(); i++) { - inputs.poseObservations[i] = poseObservations.get(i); - } + /* -------------------- Save to inputs -------------------- */ - // Save tag IDs to inputs objects - inputs.tagIds = new int[tagIds.size()]; + inputs.poseObservations = poseObservations.toArray(new PoseObservation[0]); + + inputs.tagIds = new int[unionTagIds.size()]; int i = 0; - for (int id : tagIds) { + for (int id : unionTagIds) { inputs.tagIds[i++] = id; } + + Arrays.sort(inputs.tagIds); // optional but recommended } /** Parses the 3D pose from a Limelight botpose array. */ diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java index 14a2867..b328385 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java @@ -15,6 +15,7 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform3d; import java.util.ArrayList; +import java.util.Arrays; import java.util.HashSet; import java.util.Set; import org.photonvision.PhotonCamera; @@ -77,10 +78,12 @@ public void updateInputs(VisionIOInputs inputs) { double avgTagDistance = result.targets.isEmpty() ? 0.0 : (totalTagDistance / result.targets.size()); - Set used = new HashSet<>(); + // Build used tag list (loggable + replayable) + int[] used = new int[multitag.fiducialIDsUsed.size()]; + int u = 0; for (int id : multitag.fiducialIDsUsed) { - used.add(id); - unionTagIds.add(id); + used[u++] = id; + unionTagIds.add(id); // keep your union set for tagIds UI/log } poseObservations.add( @@ -91,7 +94,7 @@ public void updateInputs(VisionIOInputs inputs) { multitag.fiducialIDsUsed.size(), avgTagDistance, PoseObservationType.PHOTONVISION, - Set.copyOf(used))); + used)); } else if (!result.targets.isEmpty()) { var target = result.targets.get(0); @@ -117,7 +120,7 @@ public void updateInputs(VisionIOInputs inputs) { 1, cameraToTarget.getTranslation().getNorm(), PoseObservationType.PHOTONVISION, - Set.of(target.fiducialId))); + new int[] {target.fiducialId})); } } @@ -131,5 +134,8 @@ public void updateInputs(VisionIOInputs inputs) { inputs.tagIds = new int[unionTagIds.size()]; int i = 0; for (int id : unionTagIds) inputs.tagIds[i++] = id; + + // Sort the AprilTag IDs for ease of use by dashboards, etc. + Arrays.sort(inputs.tagIds); } } diff --git a/src/main/java/frc/robot/util/Alert.java b/src/main/java/frc/robot/util/Alert.java index 5f20d34..202012d 100644 --- a/src/main/java/frc/robot/util/Alert.java +++ b/src/main/java/frc/robot/util/Alert.java @@ -12,7 +12,6 @@ import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import java.util.ArrayList; import java.util.Comparator; @@ -66,7 +65,7 @@ public Alert(String group, String text, AlertType type) { */ public void set(boolean active) { if (active && !this.active) { - activeStartTime = Timer.getFPGATimestamp(); + activeStartTime = TimeUtil.now(); switch (type) { case ERROR: DriverStation.reportError(text, false); diff --git a/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java b/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java index df46efd..3db0b25 100644 --- a/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java +++ b/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java @@ -24,8 +24,10 @@ import edu.wpi.first.math.interpolation.Interpolator; import java.util.Map.Entry; import java.util.Optional; +import java.util.OptionalDouble; import java.util.concurrent.ConcurrentNavigableMap; import java.util.concurrent.ConcurrentSkipListMap; +import org.littletonrobotics.junction.Logger; /** * A concurrent version of WPIlib's TimeInterpolatableBuffer class to avoid the need for explicit @@ -88,6 +90,9 @@ public static ConcurrentTimeInterpolatableBuffer createDoubleBuffer( * @param sample The sample object. */ public void addSample(double timeSeconds, T sample) { + Logger.recordOutput("Odometry/Debug/lastPoseBufferAddTs", timeSeconds); + Logger.recordOutput("Odometry/Debug/nowTs", TimeUtil.now()); + m_pastSnapshots.put(timeSeconds, sample); cleanUp(timeSeconds); } @@ -126,26 +131,32 @@ public Optional getSample(double timeSeconds) { var bottomBound = m_pastSnapshots.floorEntry(timeSeconds); var topBound = m_pastSnapshots.ceilingEntry(timeSeconds); - // Return null if neither sample exists, and the opposite bound if the other is - // null - if (topBound == null && bottomBound == null) { - return Optional.empty(); - } else if (topBound == null) { + if (topBound == null && bottomBound == null) return Optional.empty(); + if (topBound == null) return Optional.of(bottomBound.getValue()); + if (bottomBound == null) return Optional.of(topBound.getValue()); + + // NEW: if they are the same sample, no interpolation possible/needed + if (topBound.getKey().doubleValue() == bottomBound.getKey().doubleValue()) { return Optional.of(bottomBound.getValue()); - } else if (bottomBound == null) { - return Optional.of(topBound.getValue()); - } else { - // Otherwise, interpolate. Because T is between [0, 1], we want the ratio of - // (the difference - // between the current time and bottom bound) and (the difference between top - // and bottom - // bounds). - return Optional.of( - m_interpolatingFunc.interpolate( - bottomBound.getValue(), - topBound.getValue(), - (timeSeconds - bottomBound.getKey()) / (topBound.getKey() - bottomBound.getKey()))); } + + double t0 = bottomBound.getKey(); + double t1 = topBound.getKey(); + double denom = t1 - t0; + + // (optional but good) + if (Math.abs(denom) < 1e-9) return Optional.of(bottomBound.getValue()); + + double ratio = (timeSeconds - t0) / denom; + ratio = MathUtil.clamp(ratio, 0.0, 1.0); + + Logger.recordOutput("Odometry/Debug/bottomKey", t0); + Logger.recordOutput("Odometry/Debug/topKey", t1); + Logger.recordOutput("Odometry/Debug/denom", denom); + Logger.recordOutput("Odometry/Debug/snaphotSize", m_pastSnapshots.size()); + + return Optional.of( + m_interpolatingFunc.interpolate(bottomBound.getValue(), topBound.getValue(), ratio)); } public Entry getLatest() { @@ -161,4 +172,16 @@ public Entry getLatest() { public ConcurrentNavigableMap getInternalBuffer() { return m_pastSnapshots; } + + /** Return the oldest timestamp in the buffer */ + public OptionalDouble getOldestTimestamp() { + if (m_pastSnapshots.isEmpty()) return OptionalDouble.empty(); + return OptionalDouble.of(m_pastSnapshots.firstKey()); + } + + /** Return the newest timestamp in the buffer */ + public OptionalDouble getNewestTimestamp() { + if (m_pastSnapshots.isEmpty()) return OptionalDouble.empty(); + return OptionalDouble.of(m_pastSnapshots.lastKey()); + } } diff --git a/src/main/java/frc/robot/util/TimeUtil.java b/src/main/java/frc/robot/util/TimeUtil.java new file mode 100644 index 0000000..3b8e7aa --- /dev/null +++ b/src/main/java/frc/robot/util/TimeUtil.java @@ -0,0 +1,32 @@ +// Copyright (c) 2024-2026 Az-FIRST +// http://github.com/AZ-First +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// version 3 as published by the Free Software Foundation or +// available in the root directory of this project. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. + +package frc.robot.util; + +import org.littletonrobotics.junction.Logger; + +public final class TimeUtil { + private TimeUtil() {} + + /** Always seconds, regardless of real/sim/replay timebase quirks. */ + public static double now() { + double t = Logger.getTimestamp(); + + // Empirical: in some environments, Logger timestamp is microseconds. + // If it looks like µs, convert to seconds. + if (t > 1.0e6) { + t *= 1.0e-6; + } + return t; + } +} From 03cbadfd15b693ef151204a19fcfb2b88e9372b6 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Mon, 16 Feb 2026 15:02:22 -0700 Subject: [PATCH 18/22] =?UTF-8?q?=F0=9F=98=AE=E2=80=8D=F0=9F=92=A8=20Got?= =?UTF-8?q?=20it?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Got the pose buffering cleaned up and working. Next step is to clean the code so that it's easy to read and clean up any extraneous additions. --- src/main/java/frc/robot/Constants.java | 10 + .../frc/robot/subsystems/drive/Drive.java | 229 +++++++++++++++--- .../robot/subsystems/drive/DriveOdometry.java | 106 ++++++-- .../frc/robot/subsystems/vision/Vision.java | 6 + 4 files changed, 301 insertions(+), 50 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 59647ab..bf2a175 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -333,6 +333,16 @@ public static final class DrivebaseConstants { // Optional: ignore obviously insane measurements while disabled. public static final double kDisabledVisionMaxJumpM = 2.0; // meters public static final double kDisabledVisionMaxJumpRad = Units.degreesToRadians(20.0); + public static final double kDisabledVisionStale = 0.75; // seconds + + // Coast window config + public static final double kDisabledCoastSeconds = 5.0; + + // "Stationary" detection config (tune) + public static final double kStationaryMaxWheelDeltaM = 0.002; // 2mm per loop + public static final double kStationaryMaxYawRateRadPerSec = 0.05; // ~3 deg/s + public static final int kStationaryLoopsToEndCoast = 10; // ~0.20s @ 20ms + public static final double kDisabledVisionIgnoreAfterDisableSec = 0.25; // 250ms } /************************************************************************* */ diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 3098132..1eb5411 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -104,6 +104,15 @@ public class Drive extends RBSISubsystem { private volatile long poseResetEpoch = 0; // monotonic counter private volatile double lastPoseResetTimestamp = Double.NEGATIVE_INFINITY; + // Pose Regimes (ENABLED, DISABLED_COAST, DISABLE_STATIONARY) + private boolean lastEnabled = false; + private double disabledCoastUntilTs = Double.NEGATIVE_INFINITY; + private double disabledCoastStartTs = Double.NEGATIVE_INFINITY; + + private final double[] lastWheelDistM = new double[4]; + private boolean haveLastWheelDist = false; + private int stationaryLoops = 0; + /** Constructor */ public Drive(Imu imu) { this.imu = imu; @@ -385,6 +394,83 @@ public ProfiledPIDController getAngleController() { return angleController; } + // Drive.java + public void updateDisabledCoastState( + boolean enabledNow, + boolean disabledNow, + double now, + double yawRateRadPerSec, + SwerveModulePosition[] odomPositions) { + + // Detect ENABLED -> DISABLED edge + if (lastEnabled && !enabledNow) { + disabledCoastStartTs = now; + disabledCoastUntilTs = now + DrivebaseConstants.kDisabledCoastSeconds; + + stationaryLoops = 0; + haveLastWheelDist = false; // reset delta baseline on transition + } + lastEnabled = enabledNow; + + // If not disabled, no coast. + if (!disabledNow) { + stationaryLoops = 0; + haveLastWheelDist = false; + return; + } + + // If coast already expired, nothing to do. + if (!(now < disabledCoastUntilTs)) { + return; + } + + // Need odometry positions to detect motion + if (odomPositions == null || odomPositions.length < 4) { + return; + } + + // Compute max wheel delta this loop + double maxDelta = 0.0; + if (haveLastWheelDist) { + for (int i = 0; i < 4; i++) { + double dist = odomPositions[i].distanceMeters; + double d = Math.abs(dist - lastWheelDistM[i]); + if (d > maxDelta) maxDelta = d; + } + } + + // Update baseline for next loop + for (int i = 0; i < 4; i++) { + lastWheelDistM[i] = odomPositions[i].distanceMeters; + } + haveLastWheelDist = true; + + // Stationary test (must have baseline) + if (haveLastWheelDist + && maxDelta <= DrivebaseConstants.kStationaryMaxWheelDeltaM + && Math.abs(yawRateRadPerSec) <= DrivebaseConstants.kStationaryMaxYawRateRadPerSec) { + stationaryLoops++; + } else { + stationaryLoops = 0; + } + + // Optional: don’t end coast “instantly” right after disable edge + final double minCoastTime = 0.25; // seconds + final boolean pastMin = (now - disabledCoastStartTs) >= minCoastTime; + + // End coast early if stationary long enough + if (pastMin && stationaryLoops >= DrivebaseConstants.kStationaryLoopsToEndCoast) { + disabledCoastUntilTs = now; // expires immediately + } + + // Debug logs (optional) + Logger.recordOutput("Odometry/Coast/active", isDisabledCoast(now)); + Logger.recordOutput("Odometry/Coast/untilTs", disabledCoastUntilTs); + Logger.recordOutput("Odometry/Coast/stationaryLoops", stationaryLoops); + Logger.recordOutput("Odometry/Coast/maxWheelDeltaM", maxDelta); + Logger.recordOutput("Odometry/Coast/yawRateRadPerSec", yawRateRadPerSec); + } + /************************************************************************* */ /** SysId Characterization Routines ************************************** */ @@ -420,7 +506,7 @@ private SwerveModuleState[] getModuleStates() { /** Returns the module positions (turn angles and drive positions) for all of the modules. */ @AutoLogOutput(key = "SwerveStates/Positions") - private SwerveModulePosition[] getModulePositions() { + SwerveModulePosition[] getModulePositions() { SwerveModulePosition[] states = new SwerveModulePosition[4]; for (int i = 0; i < 4; i++) { states[i] = modules[i].getPosition(); @@ -435,9 +521,9 @@ public ChassisSpeeds getChassisSpeeds() { } /** Returns the current odometry pose. */ - @AutoLogOutput(key = "Odometry/Robot") public Pose2d getPose() { - if (Constants.getMode() == Mode.SIM) { + boolean isReplay = Logger.hasReplaySource(); + if (Constants.getMode() == Mode.SIM && !isReplay) { return simPhysics.getPose(); } return m_PoseEstimator.getEstimatedPosition(); @@ -555,6 +641,19 @@ public static Translation2d[] getModuleTranslations() { }; } + // Drive.java + public boolean isDisabledCoast() { + return isDisabledCoast(TimeUtil.now()); + } + + public boolean isDisabledCoast(double now) { + return DriverStation.isDisabled() && (now < disabledCoastUntilTs); + } + + public double getDisabledCoastStartTs() { + return disabledCoastStartTs; + } + /** Returns the position of each module in radians. */ public double[] getWheelRadiusCharacterizationPositions() { double[] values = new double[4]; @@ -609,51 +708,125 @@ public void zeroHeading() { * @param measurement The pose @ timestamp to add to the pose estimator */ // Called by Vision via consumer.accept(TimedPose) + // Drive.java fields + private boolean disabledVisionInitialized = false; + + private Pose2d lastDisabledVisionPose = new Pose2d(); + private double lastDisabledVisionTs = Double.NaN; + public void addVisionMeasurement(TimedPose meas) { Drive.odometryLock.lock(); try { // Always use measurement timestamp when fusing (enabled path) final double t = meas.timestampSeconds(); + final Pose2d vision = meas.pose(); + // ENABLED: normal fusion if (!DriverStation.isDisabled()) { - // ENABLED: normal soft fusion - m_PoseEstimator.addVisionMeasurement(meas.pose(), t, meas.stdDevs()); + disabledVisionInitialized = false; + lastDisabledVisionTs = Double.NaN; + m_PoseEstimator.addVisionMeasurement(vision, t, meas.stdDevs()); return; } - // DISABLED: blend toward vision, then reset estimator to blended pose + // DISABLED: + final boolean coast = isDisabledCoast(t); // your overload (timebase-consistent) + + // Optional: ignore vision briefly right after ENABLE->DISABLE (prevents “phase mismatch” at + // disable edge) + if (coast) { + final double coastAge = t - getDisabledCoastStartTs(); + Logger.recordOutput("Vision/Dbg/disabledCoastAge", coastAge); + + if (coastAge >= 0.0 && coastAge < DrivebaseConstants.kDisabledVisionIgnoreAfterDisableSec) { + Logger.recordOutput("Vision/Dbg/disabledIgnoreEarlyCoast", true); + return; + } + } + Logger.recordOutput("Vision/Dbg/disabledIgnoreEarlyCoast", false); + + // If we're coasting, we *avoid* init snap and we lean gentler than stationary. + // (still use the same gating so one bad frame doesn't wreck you) + final double alpha = + coast + ? Math.min(DrivebaseConstants.kDisabledVisionBlendAlpha, 0.05) // gentle during coast + : DrivebaseConstants.kDisabledVisionBlendAlpha; + + // "Current" for blending target (estimator pose) final Pose2d current = m_PoseEstimator.getEstimatedPosition(); - final Pose2d vision = meas.pose(); - // Optional sanity gate while disabled (prevents one bad frame from wrecking you) - final double dTrans = current.getTranslation().getDistance(vision.getTranslation()); - final double dRot = Math.abs(current.getRotation().minus(vision.getRotation()).getRadians()); - if (dTrans > DrivebaseConstants.kDisabledVisionMaxJumpM - || dRot > DrivebaseConstants.kDisabledVisionMaxJumpRad) { + // Debug + Logger.recordOutput("Vision/Dbg/disabledCoast", coast); + Logger.recordOutput("Vision/Dbg/disabledVisionInitialized", disabledVisionInitialized); + Logger.recordOutput("Vision/Dbg/disabledVisionTs", t); + Logger.recordOutput( + "Vision/Dbg/disabledVisionAge", + Double.isFinite(lastDisabledVisionTs) ? (t - lastDisabledVisionTs) : Double.NaN); + + // Stale logic (looser = LONGER timeout) + final boolean stale = + Double.isFinite(lastDisabledVisionTs) + && (t - lastDisabledVisionTs) > DrivebaseConstants.kDisabledVisionStale; + Logger.recordOutput("Vision/Dbg/visionStale", stale); + + // If we're in coast, we intentionally *don't* init-snap. + // We also reset initialization so that once coast ends, the first good stationary frame + // snaps. + if (coast) { + disabledVisionInitialized = false; + } + + // If not initialized AND not coasting: snap hard to vision once + if (!disabledVisionInitialized && !coast) { + disabledVisionInitialized = true; + lastDisabledVisionPose = vision; + lastDisabledVisionTs = t; + + m_PoseEstimator.resetPosition(getHeading(), getModulePositions(), vision); + markPoseReset(t); + poseBufferAddSample(t, vision); + + Logger.recordOutput("Vision/DisabledInitSnap", true); + Logger.recordOutput("Vision/DisabledReject", false); + Logger.recordOutput("Vision/DisabledBlendAlphaUsed", alpha); + return; + } + Logger.recordOutput("Vision/DisabledInitSnap", false); + + // Gate vs last accepted disabled vision pose (not estimator) + final Pose2d gateRef = + Double.isFinite(lastDisabledVisionTs) ? lastDisabledVisionPose : vision; + + final double dTrans = gateRef.getTranslation().getDistance(vision.getTranslation()); + final double dRot = Math.abs(gateRef.getRotation().minus(vision.getRotation()).getRadians()); + + Logger.recordOutput("Vision/Dbg/dTransFromLastVision", dTrans); + Logger.recordOutput("Vision/Dbg/dRotFromLastVision", dRot); + + // Reject only if NOT stale + if (!stale + && (dTrans > DrivebaseConstants.kDisabledVisionMaxJumpM + || dRot > DrivebaseConstants.kDisabledVisionMaxJumpRad)) { Logger.recordOutput("Vision/DisabledReject", true); - Logger.recordOutput("Vision/DisabledReject_dTransM", dTrans); - Logger.recordOutput("Vision/DisabledReject_dRotRad", dRot); + Logger.recordOutput("Vision/DisabledBlendAlphaUsed", alpha); return; } Logger.recordOutput("Vision/DisabledReject", false); - // Controlled “soft snap” - final Pose2d blended = - current.interpolate(vision, DrivebaseConstants.kDisabledVisionBlendAlpha); - - // Reset estimator to blended pose (heading/modules are "now", but robot can't move while - // disabled) - m_PoseEstimator.resetPosition(getHeading(), getModulePositions(), blended); + // Accept this vision frame as the new reference + lastDisabledVisionPose = vision; + lastDisabledVisionTs = t; - // Mark reset so Vision gates old samples, etc. - markPoseReset(TimeUtil.now()); + // Blend toward vision + final Pose2d blended = current.interpolate(vision, alpha); - // Keep pose buffer in sync immediately (helps timeAlignPose calls) - poseBufferAddSample(TimeUtil.now(), blended); + m_PoseEstimator.resetPosition(getHeading(), getModulePositions(), blended); + markPoseReset(t); + poseBufferAddSample(t, blended); - Logger.recordOutput( - "Vision/DisabledBlendAlpha", DrivebaseConstants.kDisabledVisionBlendAlpha); Logger.recordOutput("Vision/DisabledBlendedPose", blended); + Logger.recordOutput("Vision/DisabledBlendAlphaUsed", alpha); + } finally { Drive.odometryLock.unlock(); } @@ -681,7 +854,7 @@ private void markPoseReset(double fpgaNow) { */ /** Get the pose estimator current pose */ - Pose2d poseEstimatorGetPose() { + public Pose2d poseEstimatorGetPose() { return m_PoseEstimator.getEstimatedPosition(); } diff --git a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java index 900bd15..1d50d9c 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java @@ -17,6 +17,7 @@ package frc.robot.subsystems.drive; +import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.SwerveModulePosition; import edu.wpi.first.wpilibj.DriverStation; @@ -34,6 +35,8 @@ public final class DriveOdometry extends VirtualSubsystem { private final Imu imu; private final Module[] modules; + private long writeNumber = 0L; + // Per-cycle cached objects (to avoid repeated allocations) private final SwerveModulePosition[] odomPositions = new SwerveModulePosition[4]; @@ -58,6 +61,8 @@ protected int getPeriodPriority() { /** Periodic function to read inputs */ @Override public void rbsiPeriodic() { + Logger.recordOutput("Odometry/Debug/alive", true); + Drive.odometryLock.lock(); try { final var imuInputs = imu.getInputs(); @@ -68,21 +73,34 @@ public void rbsiPeriodic() { } final boolean isReplayActive = Logger.hasReplaySource(); + Logger.recordOutput("Odometry/Debug/isDisabled", DriverStation.isDisabled()); + Logger.recordOutput("Odometry/Debug/isReplayActive", isReplayActive); + // ---------------------------------------------------------------------- // Pure SIM (not replaying a log): use sim pose/yaw + // ---------------------------------------------------------------------- if (Constants.getMode() == Mode.SIM && !isReplayActive) { final double now = TimeUtil.now(); + + // Keep buffers alive drive.poseBufferAddSample(now, drive.getSimPose()); drive.yawBuffersAddSample(now, drive.getSimYawRad(), drive.getSimYawRateRadPerSec()); - Logger.recordOutput("Drive/Pose", drive.getSimPose()); + + // Coast state uses "now" + current module positions + drive.updateDisabledCoastState( + DriverStation.isEnabled(), + DriverStation.isDisabled(), + now, + drive.getSimYawRateRadPerSec(), + drive.getModulePositions()); + return; } - // DISABLED (REAL or REPLAY): minimal ticking — keep buffers alive, do NOT integrate module - // deltas. - // Exception: if you *want* replay odometry integration while disabled, remove the - // DriverStation - // guard and keep the original replay loop. + // ---------------------------------------------------------------------- + // DISABLED (REAL only): minimal ticking — keep buffers alive, do NOT integrate module deltas. + // (If you want replay integration while disabled, this branch is already !isReplayActive.) + // ---------------------------------------------------------------------- if (DriverStation.isDisabled() && !isReplayActive) { final double now = TimeUtil.now(); @@ -91,15 +109,24 @@ public void rbsiPeriodic() { drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); } - // keep pose buffer alive with the *current estimator pose* (which can be blended by - // disabled vision) + // Coast state from "now" + current module positions + drive.updateDisabledCoastState( + DriverStation.isEnabled(), + DriverStation.isDisabled(), + now, + imuInputs.yawRateRadPerSec, + drive.getModulePositions()); + + // keep pose buffer alive with the *current estimator pose* drive.poseBufferAddSample(now, drive.poseEstimatorGetPose()); Logger.recordOutput("Drive/Pose", drive.poseEstimatorGetPose()); drive.setGyroDisconnectedAlert(!imuInputs.connected); return; } + // ---------------------------------------------------------------------- // Canonical timestamp queue from module[0] + // ---------------------------------------------------------------------- final double[] ts = modules[0].getOdometryTimestamps(); final int n = (ts == null) ? 0 : ts.length; @@ -108,6 +135,14 @@ public void rbsiPeriodic() { if (Constants.getMode() != Mode.REPLAY) { final double now = TimeUtil.now(); drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); + + // Coast state update (no per-sample positions available; use current) + drive.updateDisabledCoastState( + DriverStation.isEnabled(), + DriverStation.isDisabled(), + now, + imuInputs.yawRateRadPerSec, + drive.getModulePositions()); } drive.setGyroDisconnectedAlert(!imuInputs.connected); return; @@ -119,7 +154,9 @@ public void rbsiPeriodic() { modHist[m] = modules[m].getOdometryPositions(); } + // ---------------------------------------------------------------------- // Determine YAW queue availability (everything exists and lines up) + // ---------------------------------------------------------------------- final boolean hasYawQueue = imuInputs.connected && imuInputs.odometryYawTimestamps != null @@ -130,10 +167,7 @@ public void rbsiPeriodic() { final double[] yawTs = hasYawQueue ? imuInputs.odometryYawTimestamps : null; final double[] yawPos = hasYawQueue ? imuInputs.odometryYawPositionsRad : null; - // Determine index alignment (cheap + deterministic) - // We only trust index alignment if BOTH: - // - yaw has at least n samples - // - yawTs[i] ~= ts[i] for i in range (tight epsilon) + // Determine index alignment boolean yawIndexAligned = false; if (hasYawQueue && yawTs.length >= n) { yawIndexAligned = true; @@ -150,12 +184,16 @@ public void rbsiPeriodic() { if (hasYawQueue && !yawIndexAligned) { drive.yawBuffersFillFromQueue(yawTs, yawPos); } else if (!hasYawQueue) { - // Single “now” sample once (not per replay) final double now = TimeUtil.now(); drive.yawBuffersAddSample(now, imuInputs.yawPositionRad, imuInputs.yawRateRadPerSec); } + // ---------------------------------------------------------------------- // Replay each odometry sample + // ---------------------------------------------------------------------- + final double[] lastDist = new double[4]; + boolean haveLastDist = false; + for (int i = 0; i < n; i++) { final double t = ts[i]; @@ -176,41 +214,51 @@ public void rbsiPeriodic() { if (hasYawQueue) { if (yawIndexAligned) { yawRad = yawPos[i]; - // Keep yaw buffers aligned to replay timeline drive.yawBuffersAddSampleIndexAligned(t, yawTs, yawPos, i); } else { yawRad = drive.yawBufferSampleOr(t, imuInputs.yawPositionRad); } } + // Coast state update IN REPLAY TIMEBASE + // Yaw rate: if you have a buffered rate, use it; otherwise imuInputs.yawRateRadPerSec is + // ok. + drive.updateDisabledCoastState( + DriverStation.isEnabled(), + DriverStation.isDisabled(), + t, + imuInputs.yawRateRadPerSec, + odomPositions); + // Debugging Logger.recordOutput("Odometry/Debug/timestamp", t); Logger.recordOutput("Odometry/Debug/now", TimeUtil.now()); if (i > 0) { Logger.recordOutput("Odometry/Debug/timeNowDiff", t - ts[i - 1]); } - Logger.recordOutput("Odometry/Debug/replay_t", t); Logger.recordOutput("Odometry/Debug/replay_yawRad", yawRad); - double[] lastDist = new double[4]; - boolean firstSample = true; + // Module distance deltas (valid within batch) for (int m = 0; m < 4; m++) { - SwerveModulePosition pos = odomPositions[m]; - double dist = pos.distanceMeters; + final SwerveModulePosition pos = odomPositions[m]; + final double dist = pos.distanceMeters; Logger.recordOutput("Odometry/Debug/mod" + m + "_distanceMeters", dist); Logger.recordOutput("Odometry/Debug/mod" + m + "_angleRad", pos.angle.getRadians()); - if (!firstSample) { - double delta = dist - lastDist[m]; + + if (haveLastDist) { + final double delta = dist - lastDist[m]; Logger.recordOutput("Odometry/Debug/mod" + m + "_deltaMeters", delta); } lastDist[m] = dist; } - firstSample = false; + haveLastDist = true; + // Feed estimator at this historical timestamp drive.poseEstimatorUpdateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); + // Maintain pose history in SAME timebase as estimator drive.poseBufferAddSample(t, drive.poseEstimatorGetPose()); } @@ -219,6 +267,20 @@ public void rbsiPeriodic() { drive.setGyroDisconnectedAlert(!imuInputs.connected); } finally { + final Pose2d pose = drive.poseEstimatorGetPose(); + final double x = pose.getX(); + final double y = pose.getY(); + final double th = pose.getRotation().getRadians(); + + Logger.recordOutput("OdometryReplay/Debug/wroteRobotPose", ++writeNumber); + Logger.recordOutput("OdometryReplay/Debug/xFinite", Double.isFinite(x)); + Logger.recordOutput("OdometryReplay/Debug/yFinite", Double.isFinite(y)); + Logger.recordOutput("OdometryReplay/Debug/thFinite", Double.isFinite(th)); + + Logger.recordOutput("OdometryReplay/RobotX", x); + Logger.recordOutput("OdometryReplay/RobotY", y); + Logger.recordOutput("OdometryReplay/RobotThetaRad", th); + Drive.odometryLock.unlock(); } } diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 0753b67..ea4930f 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -278,8 +278,14 @@ public void rbsiPeriodic() { lastFusedValid = true; lastSmoothedValid = true; + Logger.recordOutput("OdometryReplay/PreInjectRobotX", drive.poseEstimatorGetPose().getX()); + Logger.recordOutput("OdometryReplay/PreInjectRobotY", drive.poseEstimatorGetPose().getY()); + consumer.accept(smoothed); + Logger.recordOutput("OdometryReplay/PostInjectRobotX", drive.poseEstimatorGetPose().getX()); + Logger.recordOutput("OdometryReplay/PostInjectRobotY", drive.poseEstimatorGetPose().getY()); + // If you want, you can feed debug values from inside timeAlignPose(...) via fields, // but leaving the plumbing as-is since you’re already logging inside helpers. From 1b4006d371f5ab1ee84c9cadf0ead0fda664c5b4 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Tue, 17 Feb 2026 09:45:46 -0700 Subject: [PATCH 19/22] Clean up diff versus `main` --- src/main/java/frc/robot/Constants.java | 49 +++--- src/main/java/frc/robot/Robot.java | 13 -- src/main/java/frc/robot/RobotContainer.java | 5 - .../accelerometer/Accelerometer.java | 11 +- .../frc/robot/subsystems/drive/ModuleIO.java | 1 - .../subsystems/drive/ModuleIOTalonFX.java | 11 +- .../frc/robot/subsystems/vision/VisionIO.java | 12 +- .../subsystems/vision/VisionIOLimelight.java | 30 ++-- .../vision/VisionIOPhotonVision.java | 12 +- src/main/java/frc/robot/util/GeomUtil.java | 165 ++++++++++++++++++ .../frc/robot/util/RBSICANBusRegistry.java | 3 +- 11 files changed, 234 insertions(+), 78 deletions(-) create mode 100644 src/main/java/frc/robot/util/GeomUtil.java diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index bf2a175..b7218f4 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -75,7 +75,7 @@ public final class Constants { private static SwerveType swerveType = SwerveType.PHOENIX6; // PHOENIX6, YAGSL private static CTREPro phoenixPro = CTREPro.UNLICENSED; // LICENSED, UNLICENSED private static AutoType autoType = AutoType.MANUAL; // MANUAL, PATHPLANNER, CHOREO - private static VisionType visionType = VisionType.NONE; // PHOTON, LIMELIGHT, NONE + private static VisionType visionType = VisionType.NONE; // PHOTON, LIMELIGHT, NONE /** Enumerate the robot types (name your robots here) */ public static enum RobotType { @@ -314,15 +314,19 @@ public static final class DrivebaseConstants { public static final double kNominalFFVolts = 2.0; // Volts // Default TalonFX Gains (Replaces what's in Phoenix X's Tuner Constants) - public static final double kDriveP = 4.0; + // NOTE: Default values from 6328's 2025 Public Code + // + // IMPORTANT:: These values are valid only for CTRE LICENSED operation!! + // Adjust these downward until your modules behave correctly + public static final double kDriveP = 40.0; public static final double kDriveD = 0.03; public static final double kDriveV = 0.83; public static final double kDriveA = 0.0; public static final double kDriveS = 2.00; public static final double kDriveT = SwerveConstants.kDriveGearRatio / DCMotor.getKrakenX60Foc(1).KtNMPerAmp; - public static final double kSteerP = 4.0; - public static final double kSteerD = 0.02; + public static final double kSteerP = 400.0; + public static final double kSteerD = 20.0; public static final double kSteerS = 2.0; // Odometry-related constants ================================== @@ -482,7 +486,7 @@ public record CameraConfig( // Example Cameras are mounted in the back corners, 18" up from the floor, facing sideways public static final CameraConfig[] ALL = { new CameraConfig( - "Photon_BW7", + "camera_0", new Transform3d( Inches.of(-13.0), Inches.of(13.0), @@ -498,24 +502,23 @@ public record CameraConfig( setLatencyStdDevMs(5); } }), - // - // new CameraConfig( - // "camera_1", - // new Transform3d( - // Inches.of(-13.0), - // Inches.of(-13.0), - // Inches.of(12.0), - // new Rotation3d(0.0, 0.0, -Math.PI / 2)), - // 1.0, - // new SimCameraProperties() { - // { - // setCalibration(1280, 800, Rotation2d.fromDegrees(120)); - // setCalibError(0.25, 0.08); - // setFPS(30); - // setAvgLatencyMs(20); - // setLatencyStdDevMs(5); - // } - // }), + new CameraConfig( + "camera_1", + new Transform3d( + Inches.of(-13.0), + Inches.of(-13.0), + Inches.of(12.0), + new Rotation3d(0.0, 0.0, -Math.PI / 2)), + 1.0, + new SimCameraProperties() { + { + setCalibration(1280, 800, Rotation2d.fromDegrees(120)); + setCalibError(0.25, 0.08); + setFPS(30); + setAvgLatencyMs(20); + setLatencyStdDevMs(5); + } + }), // ... And more, if needed }; diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 92196f6..c3db830 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -19,7 +19,6 @@ import com.revrobotics.util.StatusLogger; import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.Threads; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; @@ -49,7 +48,6 @@ public class Robot extends LoggedRobot { private Command m_autoCommandPathPlanner; private RobotContainer m_robotContainer; private Timer m_disabledTimer; - private static boolean isBlueAlliance = false; // Define simulation fields here private VisionSystemSim visionSim; @@ -139,8 +137,6 @@ public Robot() { @Override public void robotPeriodic() { - isBlueAlliance = DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Blue; - final long t0 = System.nanoTime(); if (isReal()) { @@ -323,13 +319,4 @@ public void simulationPeriodic() { // Update sim each sim tick visionSim.update(m_robotContainer.getDrivebase().getPose()); } - - // Helper method to simplify checking if the robot is blue or red alliance - public static boolean isBlue() { - return isBlueAlliance; - } - - public static boolean isRed() { - return !isBlue(); - } } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e80e242..28eae15 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -82,9 +82,6 @@ /** This is the location for defining robot hardware, commands, and controller button bindings. */ public class RobotContainer { - private static final boolean USE_MAPLESIM = true; - public static final boolean MAPLESIM = USE_MAPLESIM && Robot.isSimulation(); - /** Define the Driver and, optionally, the Operator/Co-Driver Controllers */ // Replace with ``CommandPS4Controller`` or ``CommandJoystick`` if needed final CommandXboxController driverController = new CommandXboxController(0); // Main Driver @@ -139,8 +136,6 @@ public class RobotContainer { // Alerts private final Alert aprilTagLayoutAlert = new Alert("", AlertType.INFO); - public static RobotContainer instance; - /** * Constructor for the Robot Container. This container holds subsystems, opertator interface * devices, and commands. diff --git a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java index 205edd4..2fb0361 100644 --- a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java +++ b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java @@ -30,9 +30,6 @@ */ public class Accelerometer extends VirtualSubsystem { - // Gravitational acceleration - private static final double G_TO_MPS2 = 9.80665; - // Define hardware interfaces private final RioAccelIO rio; private final RioAccelIO.Inputs rioInputs = new RioAccelIO.Inputs(); @@ -71,8 +68,12 @@ public void rbsiPeriodic() { rio.updateInputs(rioInputs); // Compute RIO accelerations and jerks - rawRio = new Translation3d(rioInputs.xG, rioInputs.yG, rioInputs.zG); - rioAcc = rawRio.rotateBy(RobotConstants.kRioOrientation).times(G_TO_MPS2); + rawRio = + new Translation3d( + rioInputs.xG * Constants.G_TO_MPS2, + rioInputs.yG * Constants.G_TO_MPS2, + rioInputs.zG * Constants.G_TO_MPS2); + rioAcc = rawRio.rotateBy(RobotConstants.kRioOrientation); // Acceleration from previous loop prevRioAcc = rioAcc; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIO.java b/src/main/java/frc/robot/subsystems/drive/ModuleIO.java index 8e9c113..1005577 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIO.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIO.java @@ -13,7 +13,6 @@ import org.littletonrobotics.junction.AutoLog; public interface ModuleIO { - @AutoLog public static class ModuleIOInputs { public boolean driveConnected = false; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java index c7015bf..4359b38 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java @@ -265,14 +265,14 @@ public ModuleIOTalonFX(int module) { @Override public void updateInputs(ModuleIOInputs inputs) { - // -------------------- Refresh Phoenix signals -------------------- + // Refresh Phoenix signals var driveStatus = BaseStatusSignal.refreshAll(drivePosition, driveVelocity, driveAppliedVolts, driveCurrent); var turnStatus = BaseStatusSignal.refreshAll(turnPosition, turnVelocity, turnAppliedVolts, turnCurrent); var encStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition); - // Log refresh failures explicitly (debug gold) + // Log *which* groups are failing and what the code is if (!driveStatus.isOK()) { Logger.recordOutput("CAN/Module" + module + "/DriveRefreshStatus", driveStatus.toString()); } @@ -283,24 +283,25 @@ public void updateInputs(ModuleIOInputs inputs) { Logger.recordOutput("CAN/Module" + module + "/EncRefreshStatus", encStatus.toString()); } - // -------------------- Connectivity flags -------------------- + // Connectivity flags inputs.driveConnected = driveConnectedDebounce.calculate(driveStatus.isOK()); inputs.turnConnected = turnConnectedDebounce.calculate(turnStatus.isOK()); inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(encStatus.isOK()); - // -------------------- Instantaneous state -------------------- + // Update drive inputs inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()); inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()); inputs.driveAppliedVolts = driveAppliedVolts.getValueAsDouble(); inputs.driveCurrentAmps = driveCurrent.getValueAsDouble(); + // Update turn inputs inputs.turnAbsolutePosition = Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble()); inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble()); inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()); inputs.turnAppliedVolts = turnAppliedVolts.getValueAsDouble(); inputs.turnCurrentAmps = turnCurrent.getValueAsDouble(); - // -------------------- Odometry queue drain -------------------- + // Odometry queue drain final int tsCount = timestampQueue.size(); final int driveCount = drivePositionQueue.size(); final int turnCount = turnPositionQueue.size(); diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIO.java b/src/main/java/frc/robot/subsystems/vision/VisionIO.java index dc249ec..4f11bf9 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIO.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIO.java @@ -18,14 +18,14 @@ public interface VisionIO { class VisionIOInputs { public boolean connected = false; - /** Latest "camera to target" observation (optional) */ + // Latest "camera to target" observation (optional) public TargetObservation latestTargetObservation = new TargetObservation(Rotation2d.kZero, Rotation2d.kZero); - /** Pose observations generated by the camera pipeline (each has its own timestamp) */ + // Pose observations generated by the camera pipeline (each has its own timestamp) public PoseObservation[] poseObservations = new PoseObservation[0]; - /** Union of tag IDs seen this loop (for logging/UI only) */ + // Union of tag IDs seen this loop public int[] tagIds = new int[0]; } @@ -34,9 +34,9 @@ record TargetObservation(Rotation2d tx, Rotation2d ty) {} /** Represents a robot pose sample used for pose estimation. */ record PoseObservation( - double timestamp, // camera capture time (seconds, same timebase as FPGA) - Pose3d pose, // field->robot pose - double ambiguity, // single-tag ambiguity if available + double timestamp, + Pose3d pose, + double ambiguity, int tagCount, double averageTagDistance, PoseObservationType type, diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java index a4c5d13..c9bbc0d 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java @@ -56,26 +56,25 @@ public VisionIOLimelight(String name, Supplier rotationSupplier) { @Override public void updateInputs(VisionIOInputs inputs) { - // Update connection status + // Update connection status based on whether an update has been seen in the last 250ms inputs.connected = ((RobotController.getFPGATime() - latencySubscriber.getLastChange()) / 1000) < 250; - // Target observation (simple tx/ty) + // Update target observation inputs.latestTargetObservation = new TargetObservation( Rotation2d.fromDegrees(txSubscriber.get()), Rotation2d.fromDegrees(tySubscriber.get())); - // Push robot orientation for MegaTag 2 + // Update orientation for MegaTag 2 orientationPublisher.accept( new double[] {rotationSupplier.get().getDegrees(), 0.0, 0.0, 0.0, 0.0, 0.0}); - NetworkTableInstance.getDefault().flush(); + NetworkTableInstance.getDefault() + .flush(); // Increases network traffic but recommended by Limelight - // Union of tag IDs seen this loop (for logging/UI only) + // Read new pose observations from NetworkTables Set unionTagIds = new HashSet<>(); - List poseObservations = new LinkedList<>(); - /* -------------------- MegaTag 1 -------------------- */ for (var rawSample : megatag1Subscriber.readQueue()) { if (rawSample.value.length == 0) continue; @@ -93,29 +92,28 @@ public void updateInputs(VisionIOInputs inputs) { poseObservations.add( new PoseObservation( - // Timestamp (LL server time minus latency) + // Timestamp, based on server timestamp of publish and latency rawSample.timestamp * 1.0e-6 - rawSample.value[6] * 1.0e-3, - // Pose + // 3D pose estimate parsePose(rawSample.value), - // Ambiguity (first tag only) + // Ambiguity, using only the first tag because ambiguity isn't applicable for multitag rawSample.value.length >= 18 ? rawSample.value[17] : 0.0, // Tag count tagCount, - // Avg distance + // Average tag distance rawSample.value[9], - // Type + // Observation type PoseObservationType.MEGATAG_1, // Used tag IDs used)); } - /* -------------------- MegaTag 2 -------------------- */ for (var rawSample : megatag2Subscriber.readQueue()) { if (rawSample.value.length == 0) continue; @@ -152,8 +150,7 @@ public void updateInputs(VisionIOInputs inputs) { used)); } - /* -------------------- Save to inputs -------------------- */ - + // Save pose observations to inputs object inputs.poseObservations = poseObservations.toArray(new PoseObservation[0]); inputs.tagIds = new int[unionTagIds.size()]; @@ -162,7 +159,8 @@ public void updateInputs(VisionIOInputs inputs) { inputs.tagIds[i++] = id; } - Arrays.sort(inputs.tagIds); // optional but recommended + // Sort list by TagID for clarity + Arrays.sort(inputs.tagIds); } /** Parses the 3D pose from a Limelight botpose array. */ diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java index b328385..4dac1e0 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOPhotonVision.java @@ -20,7 +20,7 @@ import java.util.Set; import org.photonvision.PhotonCamera; -/** IO implementation for real PhotonVision hardware (pose already solved by PV). */ +/** IO implementation for real PhotonVision hardware. */ public class VisionIOPhotonVision implements VisionIO { protected final PhotonCamera camera; protected final Transform3d robotToCamera; @@ -63,9 +63,11 @@ public void updateInputs(VisionIOInputs inputs) { bestPitch = Rotation2d.fromDegrees(result.getBestTarget().getPitch()); } - if (result.multitagResult.isPresent()) { + // Add pose observation + if (result.multitagResult.isPresent()) { // Multitag result var multitag = result.multitagResult.get(); + // Calculate robot pose Transform3d fieldToCamera = multitag.estimatedPose.best; Transform3d fieldToRobot = fieldToCamera.plus(robotToCamera.inverse()); Pose3d robotPose = new Pose3d(fieldToRobot.getTranslation(), fieldToRobot.getRotation()); @@ -86,6 +88,7 @@ public void updateInputs(VisionIOInputs inputs) { unionTagIds.add(id); // keep your union set for tagIds UI/log } + // Add observation poseObservations.add( new PoseObservation( ts, @@ -96,9 +99,10 @@ public void updateInputs(VisionIOInputs inputs) { PoseObservationType.PHOTONVISION, used)); - } else if (!result.targets.isEmpty()) { + } else if (!result.targets.isEmpty()) { // Single tag result var target = result.targets.get(0); + // Calculate robot pose var tagPose = aprilTagLayout.getTagPose(target.fiducialId); if (tagPose.isEmpty()) continue; @@ -124,6 +128,7 @@ public void updateInputs(VisionIOInputs inputs) { } } + // Save pose observations to inputs object inputs.latestTargetObservation = (newestTargetTs > Double.NEGATIVE_INFINITY) ? new TargetObservation(bestYaw, bestPitch) @@ -131,6 +136,7 @@ public void updateInputs(VisionIOInputs inputs) { inputs.poseObservations = poseObservations.toArray(new PoseObservation[0]); + // Save tag IDs to inputs objects inputs.tagIds = new int[unionTagIds.size()]; int i = 0; for (int id : unionTagIds) inputs.tagIds[i++] = id; diff --git a/src/main/java/frc/robot/util/GeomUtil.java b/src/main/java/frc/robot/util/GeomUtil.java new file mode 100644 index 0000000..f77c8b2 --- /dev/null +++ b/src/main/java/frc/robot/util/GeomUtil.java @@ -0,0 +1,165 @@ +// Copyright (c) 2024-2026 Az-FIRST +// http://github.com/AZ-First +// Copyright (c) 2021-2026 Littleton Robotics +// http://github.com/Mechanical-Advantage +// +// Use of this source code is governed by a BSD +// license that can be found in the AdvantageKit-License.md file +// at the root directory of this project. + +package frc.robot.util; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Pose3d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.geometry.Transform3d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.geometry.Twist2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; + +/** Geometry utilities for working with translations, rotations, transforms, and poses. */ +public class GeomUtil { + /** + * Creates a pure translating transform + * + * @param translation The translation to create the transform with + * @return The resulting transform + */ + public static Transform2d toTransform2d(Translation2d translation) { + return new Transform2d(translation, Rotation2d.kZero); + } + + /** + * Creates a pure translating transform + * + * @param x The x coordinate of the translation + * @param y The y coordinate of the translation + * @return The resulting transform + */ + public static Transform2d toTransform2d(double x, double y) { + return new Transform2d(x, y, Rotation2d.kZero); + } + + /** + * Creates a pure rotating transform + * + * @param rotation The rotation to create the transform with + * @return The resulting transform + */ + public static Transform2d toTransform2d(Rotation2d rotation) { + return new Transform2d(Translation2d.kZero, rotation); + } + + /** + * Converts a Pose2d to a Transform2d to be used in a kinematic chain + * + * @param pose The pose that will represent the transform + * @return The resulting transform + */ + public static Transform2d toTransform2d(Pose2d pose) { + return new Transform2d(pose.getTranslation(), pose.getRotation()); + } + + public static Pose2d inverse(Pose2d pose) { + Rotation2d rotationInverse = pose.getRotation().unaryMinus(); + return new Pose2d( + pose.getTranslation().unaryMinus().rotateBy(rotationInverse), rotationInverse); + } + + /** + * Converts a Transform2d to a Pose2d to be used as a position or as the start of a kinematic + * chain + * + * @param transform The transform that will represent the pose + * @return The resulting pose + */ + public static Pose2d toPose2d(Transform2d transform) { + return new Pose2d(transform.getTranslation(), transform.getRotation()); + } + + /** + * Creates a pure translated pose + * + * @param translation The translation to create the pose with + * @return The resulting pose + */ + public static Pose2d toPose2d(Translation2d translation) { + return new Pose2d(translation, Rotation2d.kZero); + } + + /** + * Creates a pure rotated pose + * + * @param rotation The rotation to create the pose with + * @return The resulting pose + */ + public static Pose2d toPose2d(Rotation2d rotation) { + return new Pose2d(Translation2d.kZero, rotation); + } + + /** + * Multiplies a twist by a scaling factor + * + * @param twist The twist to multiply + * @param factor The scaling factor for the twist components + * @return The new twist + */ + public static Twist2d multiply(Twist2d twist, double factor) { + return new Twist2d(twist.dx * factor, twist.dy * factor, twist.dtheta * factor); + } + + /** + * Converts a Pose3d to a Transform3d to be used in a kinematic chain + * + * @param pose The pose that will represent the transform + * @return The resulting transform + */ + public static Transform3d toTransform3d(Pose3d pose) { + return new Transform3d(pose.getTranslation(), pose.getRotation()); + } + + /** + * Converts a Transform3d to a Pose3d to be used as a position or as the start of a kinematic + * chain + * + * @param transform The transform that will represent the pose + * @return The resulting pose + */ + public static Pose3d toPose3d(Transform3d transform) { + return new Pose3d(transform.getTranslation(), transform.getRotation()); + } + + /** + * Converts a ChassisSpeeds to a Twist2d by extracting two dimensions (Y and Z). chain + * + * @param speeds The original translation + * @return The resulting translation + */ + public static Twist2d toTwist2d(ChassisSpeeds speeds) { + return new Twist2d( + speeds.vxMetersPerSecond, speeds.vyMetersPerSecond, speeds.omegaRadiansPerSecond); + } + + /** + * Creates a new pose from an existing one using a different translation value. + * + * @param pose The original pose + * @param translation The new translation to use + * @return The new pose with the new translation and original rotation + */ + public static Pose2d withTranslation(Pose2d pose, Translation2d translation) { + return new Pose2d(translation, pose.getRotation()); + } + + /** + * Creates a new pose from an existing one using a different rotation value. + * + * @param pose The original pose + * @param rotation The new rotation to use + * @return The new pose with the original translation and new rotation + */ + public static Pose2d withRotation(Pose2d pose, Rotation2d rotation) { + return new Pose2d(pose.getTranslation(), rotation); + } +} diff --git a/src/main/java/frc/robot/util/RBSICANBusRegistry.java b/src/main/java/frc/robot/util/RBSICANBusRegistry.java index b0707fc..ea3ef08 100644 --- a/src/main/java/frc/robot/util/RBSICANBusRegistry.java +++ b/src/main/java/frc/robot/util/RBSICANBusRegistry.java @@ -15,6 +15,7 @@ import com.ctre.phoenix6.CANBus; import java.util.Map; +import java.util.Set; import java.util.concurrent.ConcurrentHashMap; /** Centralized CAN bus singleton registry + SIM/REAL indirection. */ @@ -64,7 +65,7 @@ private static void checkInit() { if (!initialized) throw new IllegalStateException("RBSICANBusRegistry not initialized."); } - private static void throwUnknown(String name, java.util.Set known) { + private static void throwUnknown(String name, Set known) { throw new IllegalArgumentException("Unknown CAN bus '" + name + "'. Known: " + known); } From 8b3dafad170292e532ab92b443e045de1b0c0024 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Tue, 17 Feb 2026 14:25:48 -0700 Subject: [PATCH 20/22] Cleaning and making things line up. --- src/main/java/frc/robot/Constants.java | 8 + src/main/java/frc/robot/Robot.java | 29 +- src/main/java/frc/robot/RobotContainer.java | 26 +- .../frc/robot/subsystems/drive/Drive.java | 95 +- .../robot/subsystems/drive/DriveOdometry.java | 19 +- .../subsystems/drive/ModuleIOBlended.java | 74 +- .../robot/subsystems/drive/ModuleIOSpark.java | 58 +- .../drive/ModuleIOSparkCANcoder.java | 71 +- .../subsystems/drive/ModuleIOTalonFX.java | 8 +- .../subsystems/drive/ModuleIOTalonFXS.java | 939 ++++++++++-------- .../frc/robot/subsystems/vision/Vision.java | 81 +- .../ConcurrentTimeInterpolatableBuffer.java | 15 +- .../frc/robot/util/RBSICANBusRegistry.java | 39 +- .../java/frc/robot/util/RBSICANHealth.java | 10 + src/main/java/frc/robot/util/TimeUtil.java | 1 + 15 files changed, 806 insertions(+), 667 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index b7218f4..1b55642 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -47,6 +47,7 @@ import frc.robot.util.RBSIEnum.VisionType; import frc.robot.util.RobotDeviceId; import java.util.Set; +import org.littletonrobotics.junction.Logger; import org.photonvision.simulation.SimCameraProperties; import swervelib.math.Matter; @@ -502,6 +503,7 @@ public record CameraConfig( setLatencyStdDevMs(5); } }), + // new CameraConfig( "camera_1", new Transform3d( @@ -554,6 +556,12 @@ public static Mode getMode() { }; } + /** Return whether this is pure simulation */ + public static boolean isPureSim() { + boolean isReplay = Logger.hasReplaySource(); + return getMode() == Mode.SIM && !isReplay; + } + /** Get the current swerve drive type */ public static SwerveType getSwerveType() { return swerveType; diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index c3db830..5a1e15a 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -119,24 +119,8 @@ public Robot() { } // /** This function is called periodically during all modes. */ - // @Override - // public void robotPeriodic() { - - // // Run all virtual subsystems each time through the loop - // VirtualSubsystem.periodicAll(); - - // // Runs the Scheduler. This is responsible for polling buttons, adding - // // newly-scheduled commands, running already-scheduled commands, removing - // // finished or interrupted commands, and running subsystem periodic() methods. - // // This must be called from the robot's periodic block in order for anything in - // // the Command-based framework to work. - // CommandScheduler.getInstance().run(); - // } - - /** TESTING VERSION OF ROBOTPERIODIC FOR OVERRUN SOURCES */ @Override public void robotPeriodic() { - final long t0 = System.nanoTime(); if (isReal()) { @@ -145,20 +129,27 @@ public void robotPeriodic() { } final long t1 = System.nanoTime(); + // Run all virtual subsystems each time through the loop VirtualSubsystem.periodicAll(); final long t2 = System.nanoTime(); + // Runs the Scheduler. This is responsible for polling buttons, adding + // newly-scheduled commands, running already-scheduled commands, removing + // finished or interrupted commands, and running subsystem periodic() methods. + // This must be called from the robot's periodic block in order for anything in + // the Command-based framework to work. CommandScheduler.getInstance().run(); final long t3 = System.nanoTime(); - Threads.setCurrentThreadPriority(false, 10); + if (isReal()) { + // Return thread to normal priority + Threads.setCurrentThreadPriority(false, 10); + } final long t4 = System.nanoTime(); Logger.recordOutput("Loop/RobotPeriodic_ms", (t4 - t0) / 1e6); - Logger.recordOutput("Loop/ThreadBoost_ms", (t1 - t0) / 1e6); Logger.recordOutput("Loop/Virtual_ms", (t2 - t1) / 1e6); Logger.recordOutput("Loop/Scheduler_ms", (t3 - t2) / 1e6); - Logger.recordOutput("Loop/ThreadRestore_ms", (t4 - t3) / 1e6); } /** This function is called once when the robot is disabled. */ diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 28eae15..dfd7d65 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -155,8 +155,7 @@ public RobotContainer() { m_imu = new Imu(SwerveConstants.kImu.factory.get()); m_drivebase = new Drive(m_imu); - m_driveOdometry = - new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); // see note + m_driveOdometry = new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); m_vision = new Vision( m_drivebase, m_drivebase::addVisionMeasurement, buildVisionIOsReal(m_drivebase)); @@ -170,30 +169,22 @@ public RobotContainer() { m_imu = new Imu(new ImuIOSim()); m_drivebase = new Drive(m_imu); - m_driveOdometry = - new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); // see note - - m_flywheel = new Flywheel(new FlywheelIOSim()); - - // ---------------- Vision IOs (robot code) ---------------- - var cams = Cameras.ALL; + m_driveOdometry = new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); m_vision = new Vision( m_drivebase, m_drivebase::addVisionMeasurement, buildVisionIOsSim(m_drivebase)); + m_flywheel = new Flywheel(new FlywheelIOSim()); m_accel = new Accelerometer(m_imu); - // ---------------- CameraSweepEvaluator (sim-only analysis) ---------------- + // CameraSweepEvaluator (sim-only analysis) VisionSystemSim visionSim = new VisionSystemSim("CameraSweepWorld"); visionSim.addAprilTags(FieldConstants.aprilTagLayout); - + var cams = Cameras.ALL; PhotonCameraSim[] simCams = new PhotonCameraSim[cams.length]; - for (int i = 0; i < cams.length; i++) { var cfg = cams[i]; - PhotonCamera photonCam = new PhotonCamera(cfg.name()); PhotonCameraSim camSim = new PhotonCameraSim(photonCam, cfg.simProps()); - visionSim.addCamera(camSim, cfg.robotToCamera()); simCams[i] = camSim; } @@ -212,21 +203,18 @@ public RobotContainer() { RBSICANBusRegistry.initSim(CANBuses.RIO, CANBuses.DRIVE); m_imu = new Imu(new ImuIOSim() {}); m_drivebase = new Drive(m_imu); - m_driveOdometry = - new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); // see note - - m_flywheel = new Flywheel(new FlywheelIO() {}); + m_driveOdometry = new DriveOdometry(m_drivebase, m_imu, m_drivebase.getModules()); m_vision = new Vision( m_drivebase, m_drivebase::addVisionMeasurement, buildVisionIOsReplay(m_drivebase)); + m_flywheel = new Flywheel(new FlywheelIO() {}); m_accel = new Accelerometer(m_imu); sweep = null; break; } // Init all CAN busses specified in the `Constants.CANBuses` class - RBSICANBusRegistry.initReal(Constants.CANBuses.ALL); canHealth = Arrays.stream(Constants.CANBuses.ALL).map(RBSICANHealth::new).toList(); // In addition to the initial battery capacity from the Dashbaord, ``RBSIPowerMonitor`` takes diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 1eb5411..604d876 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -1,11 +1,19 @@ // Copyright (c) 2024-2026 Az-FIRST // http://github.com/AZ-First -// Copyright (c) 2021-2026 Littleton Robotics -// http://github.com/Mechanical-Advantage // -// Use of this source code is governed by a BSD -// license that can be found in the AdvantageKit-License.md file -// at the root directory of this project. +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// version 3 as published by the Free Software Foundation or +// available in the root directory of this project. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. package frc.robot.subsystems.drive; @@ -86,13 +94,8 @@ public class Drive extends RBSISubsystem { // Declare odometry and pose-related variables static final Lock odometryLock = new ReentrantLock(); private SwerveDriveKinematics kinematics = new SwerveDriveKinematics(getModuleTranslations()); - private SwerveModulePosition[] lastModulePositions = // For delta tracking - new SwerveModulePosition[] { - new SwerveModulePosition(), - new SwerveModulePosition(), - new SwerveModulePosition(), - new SwerveModulePosition() - }; + private SwerveModulePosition[] lastModulePositions = + new SwerveModulePosition[4]; // For delta tracking private SwerveDrivePoseEstimator m_PoseEstimator = new SwerveDrivePoseEstimator(kinematics, Rotation2d.kZero, lastModulePositions, Pose2d.kZero); @@ -108,11 +111,15 @@ public class Drive extends RBSISubsystem { private boolean lastEnabled = false; private double disabledCoastUntilTs = Double.NEGATIVE_INFINITY; private double disabledCoastStartTs = Double.NEGATIVE_INFINITY; - private final double[] lastWheelDistM = new double[4]; private boolean haveLastWheelDist = false; private int stationaryLoops = 0; + // Related to vision injection of pose + private boolean disabledVisionInitialized = false; + private Pose2d lastDisabledVisionPose = new Pose2d(); + private double lastDisabledVisionTs = Double.NaN; + /** Constructor */ public Drive(Imu imu) { this.imu = imu; @@ -389,12 +396,20 @@ public void resetHeadingController() { angleController.reset(getHeading().getRadians()); } - /** Getter function for the angle controller */ - public ProfiledPIDController getAngleController() { - return angleController; - } - - // Drive.java + /** + * Update the Disabled Coast State + * + *

The purpose of this function is to determine the coasting state of the robot on the ENABLE + * -> DISABLE edge. While the robot coasts to a stop, the wheel odometry will continue to + * integrate with usual vision input. Once the robot stops moving (within tolerance), the vision + * injection to the Pose will take over. + * + * @param enabledNow Are we enabled now? + * @param disabledNow Are we disabled now? + * @param now When is now? + * @param yawRateRadPerSec Current drivebase rotation rate + * @param odomPositions List of module odometry positions + */ public void updateDisabledCoastState( boolean enabledNow, boolean disabledNow, @@ -402,6 +417,10 @@ public void updateDisabledCoastState( double yawRateRadPerSec, SwerveModulePosition[] odomPositions) { + // Don’t end coast “instantly” right after disable edge + final double minCoastTime = 0.25; // seconds -- maybe put into Constants??? + final boolean pastMin = (now - disabledCoastStartTs) >= minCoastTime; + // Detect ENABLED -> DISABLED edge if (lastEnabled && !enabledNow) { disabledCoastStartTs = now; @@ -454,10 +473,6 @@ public void updateDisabledCoastState( stationaryLoops = 0; } - // Optional: don’t end coast “instantly” right after disable edge - final double minCoastTime = 0.25; // seconds - final boolean pastMin = (now - disabledCoastStartTs) >= minCoastTime; - // End coast early if stationary long enough if (pastMin && stationaryLoops >= DrivebaseConstants.kStationaryLoopsToEndCoast) { disabledCoastUntilTs = now; // expires immediately @@ -494,6 +509,11 @@ public Module[] getModules() { return modules; } + /** Return the prodiledPID angle controller */ + public ProfiledPIDController getAngleController() { + return angleController; + } + /** Returns the module states (turn angles and drive velocities) for all of the modules. */ @AutoLogOutput(key = "SwerveStates/Measured") private SwerveModuleState[] getModuleStates() { @@ -520,10 +540,14 @@ public ChassisSpeeds getChassisSpeeds() { return kinematics.toChassisSpeeds(getModuleStates()); } - /** Returns the current odometry pose. */ + /** + * Returns the current odometry pose. + * + *

If the code is running as pure simulation (i.e., not REPLAY of a log), return the simulated + * physics pose. Otherwise, return the pose from the pose estimator. + */ public Pose2d getPose() { - boolean isReplay = Logger.hasReplaySource(); - if (Constants.getMode() == Mode.SIM && !isReplay) { + if (Constants.isPureSim()) { return simPhysics.getPose(); } return m_PoseEstimator.getEstimatedPosition(); @@ -532,7 +556,7 @@ public Pose2d getPose() { /** Returns the current odometry YAW. */ @AutoLogOutput(key = "Odometry/Yaw") public Rotation2d getHeading() { - if (Constants.getMode() == Mode.SIM) { + if (Constants.isPureSim()) { return simPhysics.getYaw(); } return imu.getYaw(); @@ -567,10 +591,12 @@ public Optional getPoseAtTime(double timestampSeconds) { return poseBuffer.getSample(timestampSeconds); } + /** Returns the oldest timetamp in the current pose buffer */ public double getPoseBufferOldestTime() { return poseBuffer.getOldestTimestamp().getAsDouble(); } + /** Returns the newest timetamp in the current pose buffer */ public double getPoseBufferNewestTime() { return poseBuffer.getNewestTimestamp().getAsDouble(); } @@ -641,15 +667,17 @@ public static Translation2d[] getModuleTranslations() { }; } - // Drive.java + /** Returns whether the robot is currently in the DISABLED_COAST state */ public boolean isDisabledCoast() { return isDisabledCoast(TimeUtil.now()); } + /** Returns whether the robot was in the DISABLED_COAST state at time `now` */ public boolean isDisabledCoast(double now) { return DriverStation.isDisabled() && (now < disabledCoastUntilTs); } + /** Returns the disabledCoastStartTs variable */ public double getDisabledCoastStartTs() { return disabledCoastStartTs; } @@ -708,12 +736,6 @@ public void zeroHeading() { * @param measurement The pose @ timestamp to add to the pose estimator */ // Called by Vision via consumer.accept(TimedPose) - // Drive.java fields - private boolean disabledVisionInitialized = false; - - private Pose2d lastDisabledVisionPose = new Pose2d(); - private double lastDisabledVisionTs = Double.NaN; - public void addVisionMeasurement(TimedPose meas) { Drive.odometryLock.lock(); try { @@ -853,11 +875,6 @@ private void markPoseReset(double fpgaNow) { * pass-throughs to allow this functionality. */ - /** Get the pose estimator current pose */ - public Pose2d poseEstimatorGetPose() { - return m_PoseEstimator.getEstimatedPosition(); - } - /** Update the pose estimator at a timestamp */ void poseEstimatorUpdateWithTime(double t, Rotation2d yaw, SwerveModulePosition[] positions) { m_PoseEstimator.updateWithTime(t, yaw, positions); diff --git a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java index 1d50d9c..aff93c2 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java @@ -40,6 +40,9 @@ public final class DriveOdometry extends VirtualSubsystem { // Per-cycle cached objects (to avoid repeated allocations) private final SwerveModulePosition[] odomPositions = new SwerveModulePosition[4]; + // Checking whether this is a REPLAY + private boolean isReplayActive = Logger.hasReplaySource(); + /** Constructor */ public DriveOdometry(Drive drive, Imu imu, Module[] modules) { this.drive = drive; @@ -72,14 +75,10 @@ public void rbsiPeriodic() { module.periodic(); } - final boolean isReplayActive = Logger.hasReplaySource(); - Logger.recordOutput("Odometry/Debug/isDisabled", DriverStation.isDisabled()); - Logger.recordOutput("Odometry/Debug/isReplayActive", isReplayActive); - // ---------------------------------------------------------------------- // Pure SIM (not replaying a log): use sim pose/yaw // ---------------------------------------------------------------------- - if (Constants.getMode() == Mode.SIM && !isReplayActive) { + if (Constants.isPureSim()) { final double now = TimeUtil.now(); // Keep buffers alive @@ -118,8 +117,8 @@ public void rbsiPeriodic() { drive.getModulePositions()); // keep pose buffer alive with the *current estimator pose* - drive.poseBufferAddSample(now, drive.poseEstimatorGetPose()); - Logger.recordOutput("Drive/Pose", drive.poseEstimatorGetPose()); + drive.poseBufferAddSample(now, drive.getPose()); + Logger.recordOutput("Drive/Pose", drive.getPose()); drive.setGyroDisconnectedAlert(!imuInputs.connected); return; } @@ -260,14 +259,14 @@ public void rbsiPeriodic() { drive.poseEstimatorUpdateWithTime(t, Rotation2d.fromRadians(yawRad), odomPositions); // Maintain pose history in SAME timebase as estimator - drive.poseBufferAddSample(t, drive.poseEstimatorGetPose()); + drive.poseBufferAddSample(t, drive.getPose()); } - Logger.recordOutput("Drive/Pose", drive.poseEstimatorGetPose()); + Logger.recordOutput("Drive/Pose", drive.getPose()); drive.setGyroDisconnectedAlert(!imuInputs.connected); } finally { - final Pose2d pose = drive.poseEstimatorGetPose(); + final Pose2d pose = drive.getPose(); final double x = pose.getX(); final double y = pose.getY(); final double th = pose.getRotation().getRadians(); diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java index 01d0ffc..9ae8105 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java @@ -56,6 +56,7 @@ import frc.robot.util.PhoenixUtil; import frc.robot.util.RBSICANBusRegistry; import frc.robot.util.SparkUtil; +import java.util.Arrays; import java.util.Queue; import org.littletonrobotics.junction.Logger; @@ -73,6 +74,9 @@ public class ModuleIOBlended implements ModuleIO { TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> constants; + // This module number (for logging) + private final int module; + // Hardware Objects private final TalonFX driveTalon; private final SparkBase turnSpark; @@ -134,6 +138,8 @@ public class ModuleIOBlended implements ModuleIO { * added in appropriately. */ public ModuleIOBlended(int module) { + // Record the module number for logging purposes + this.module = module; constants = switch (module) { @@ -312,21 +318,28 @@ public ModuleIOBlended(int module) { @Override public void updateInputs(ModuleIOInputs inputs) { - // Refresh all signals + // Refresh signals var driveStatus = BaseStatusSignal.refreshAll(drivePosition, driveVelocity, driveAppliedVolts, driveCurrent); - var turnEncoderStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition); + var encStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition); + + if (!driveStatus.isOK()) { + Logger.recordOutput("CAN/Module" + module + "/DriveRefreshStatus", driveStatus.toString()); + } + if (!encStatus.isOK()) { + Logger.recordOutput("CAN/Module" + module + "/EncRefreshStatus", encStatus.toString()); + } - // Update drive inputs + // Drive inputs inputs.driveConnected = driveConnectedDebounce.calculate(driveStatus.isOK()); inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()); inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()); inputs.driveAppliedVolts = driveAppliedVolts.getValueAsDouble(); inputs.driveCurrentAmps = driveCurrent.getValueAsDouble(); - // Update turn inputs + // Turn inputs (Spark for turn motor, CANcoder for absolute) SparkUtil.sparkStickyFault = false; - inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(turnEncoderStatus.isOK()); + inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(encStatus.isOK()); inputs.turnAbsolutePosition = Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble()); inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble()); inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()); @@ -334,20 +347,43 @@ public void updateInputs(ModuleIOInputs inputs) { turnSpark, turnSpark::getOutputCurrent, (value) -> inputs.turnCurrentAmps = value); inputs.turnConnected = turnConnectedDebounce.calculate(!SparkUtil.sparkStickyFault); - // Update odometry inputs - inputs.odometryTimestamps = - timestampQueue.stream().mapToDouble((Double value) -> value).toArray(); - inputs.odometryDrivePositionsRad = - drivePositionQueue.stream() - .mapToDouble((Double value) -> Units.rotationsToRadians(value)) - .toArray(); - inputs.odometryTurnPositions = - turnPositionQueue.stream() - .map((Double value) -> Rotation2d.fromRotations(value)) - .toArray(Rotation2d[]::new); - timestampQueue.clear(); - drivePositionQueue.clear(); - turnPositionQueue.clear(); + // Odometry queue drain (common prefix only) + final int tsCount = timestampQueue.size(); + final int driveCount = drivePositionQueue.size(); + final int turnCount = turnPositionQueue.size(); + final int sampleCount = Math.min(tsCount, Math.min(driveCount, turnCount)); + + if (sampleCount <= 0) { + inputs.odometryTimestamps = new double[0]; + inputs.odometryDrivePositionsRad = new double[0]; + inputs.odometryTurnPositions = new Rotation2d[0]; + return; + } + + final double[] outTs = new double[sampleCount]; + final double[] outDriveRad = new double[sampleCount]; + final Rotation2d[] outTurn = new Rotation2d[sampleCount]; + + for (int i = 0; i < sampleCount; i++) { + final Double t = timestampQueue.poll(); + final Double driveRot = drivePositionQueue.poll(); + final Double turnRot = turnPositionQueue.poll(); + + if (t == null || driveRot == null || turnRot == null) { + inputs.odometryTimestamps = Arrays.copyOf(outTs, i); + inputs.odometryDrivePositionsRad = Arrays.copyOf(outDriveRad, i); + inputs.odometryTurnPositions = Arrays.copyOf(outTurn, i); + return; + } + + outTs[i] = t.doubleValue(); + outDriveRad[i] = Units.rotationsToRadians(driveRot.doubleValue()); + outTurn[i] = Rotation2d.fromRotations(turnRot.doubleValue()); + } + + inputs.odometryTimestamps = outTs; + inputs.odometryDrivePositionsRad = outDriveRad; + inputs.odometryTurnPositions = outTurn; } /** diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java index 1c92c68..c79d5ee 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java @@ -32,6 +32,7 @@ import frc.robot.Constants; import frc.robot.Constants.DrivebaseConstants; import frc.robot.util.SparkUtil; +import java.util.Arrays; import java.util.Queue; import java.util.function.DoubleSupplier; import org.littletonrobotics.junction.Logger; @@ -214,7 +215,7 @@ public ModuleIOSpark(int module) { @Override public void updateInputs(ModuleIOInputs inputs) { - // Update drive inputs + // Drive inputs SparkUtil.sparkStickyFault = false; SparkUtil.ifOk( driveSpark, driveEncoder::getPosition, (value) -> inputs.drivePositionRad = value); @@ -228,7 +229,7 @@ public void updateInputs(ModuleIOInputs inputs) { driveSpark, driveSpark::getOutputCurrent, (value) -> inputs.driveCurrentAmps = value); inputs.driveConnected = driveConnectedDebounce.calculate(!SparkUtil.sparkStickyFault); - // Update turn inputs + // Turn inputs SparkUtil.sparkStickyFault = false; SparkUtil.ifOk( turnSpark, @@ -244,18 +245,47 @@ public void updateInputs(ModuleIOInputs inputs) { turnSpark, turnSpark::getOutputCurrent, (value) -> inputs.turnCurrentAmps = value); inputs.turnConnected = turnConnectedDebounce.calculate(!SparkUtil.sparkStickyFault); - // Update odometry inputs - inputs.odometryTimestamps = - timestampQueue.stream().mapToDouble((Double value) -> value).toArray(); - inputs.odometryDrivePositionsRad = - drivePositionQueue.stream().mapToDouble((Double value) -> value).toArray(); - inputs.odometryTurnPositions = - turnPositionQueue.stream() - .map((Double value) -> new Rotation2d(value).minus(zeroRotation)) - .toArray(Rotation2d[]::new); - timestampQueue.clear(); - drivePositionQueue.clear(); - turnPositionQueue.clear(); + // If you don’t have an absolute encoder on this variant, keep these consistent: + inputs.turnEncoderConnected = true; // or a real debounce if you have one + inputs.turnAbsolutePosition = inputs.turnPosition; + + // Odometry queue drain (common prefix only) + final int tsCount = timestampQueue.size(); + final int driveCount = drivePositionQueue.size(); + final int turnCount = turnPositionQueue.size(); + final int sampleCount = Math.min(tsCount, Math.min(driveCount, turnCount)); + + if (sampleCount <= 0) { + inputs.odometryTimestamps = new double[0]; + inputs.odometryDrivePositionsRad = new double[0]; + inputs.odometryTurnPositions = new Rotation2d[0]; + return; + } + + final double[] outTs = new double[sampleCount]; + final double[] outDriveRad = new double[sampleCount]; + final Rotation2d[] outTurn = new Rotation2d[sampleCount]; + + for (int i = 0; i < sampleCount; i++) { + final Double t = timestampQueue.poll(); + final Double drivePosRad = drivePositionQueue.poll(); // already rad in your existing code + final Double turnPosRad = turnPositionQueue.poll(); // rad in your existing code + + if (t == null || drivePosRad == null || turnPosRad == null) { + inputs.odometryTimestamps = Arrays.copyOf(outTs, i); + inputs.odometryDrivePositionsRad = Arrays.copyOf(outDriveRad, i); + inputs.odometryTurnPositions = Arrays.copyOf(outTurn, i); + return; + } + + outTs[i] = t.doubleValue(); + outDriveRad[i] = drivePosRad.doubleValue(); + outTurn[i] = new Rotation2d(turnPosRad.doubleValue()).minus(zeroRotation); + } + + inputs.odometryTimestamps = outTs; + inputs.odometryDrivePositionsRad = outDriveRad; + inputs.odometryTurnPositions = outTurn; } /** diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java index 587f8ec..7c10683 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java @@ -38,6 +38,7 @@ import frc.robot.Constants.DrivebaseConstants; import frc.robot.util.RBSICANBusRegistry; import frc.robot.util.SparkUtil; +import java.util.Arrays; import java.util.Queue; import java.util.function.DoubleSupplier; import org.littletonrobotics.junction.Logger; @@ -47,6 +48,10 @@ * and duty cycle absolute encoder. */ public class ModuleIOSparkCANcoder implements ModuleIO { + + // This module number (for logging) + private final int module; + private final Rotation2d zeroRotation; // Hardware objects @@ -87,6 +92,9 @@ public class ModuleIOSparkCANcoder implements ModuleIO { * Spark I/O w/ CANcoders */ public ModuleIOSparkCANcoder(int module) { + // Record the module number for logging purposes + this.module = module; + zeroRotation = switch (module) { case 0 -> new Rotation2d(SwerveConstants.kFLEncoderOffset); @@ -237,11 +245,13 @@ public ModuleIOSparkCANcoder(int module) { @Override public void updateInputs(ModuleIOInputs inputs) { + // Refresh CANcoder absolute + var encStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition); + if (!encStatus.isOK()) { + Logger.recordOutput("CAN/Module" + module + "/EncRefreshStatus", encStatus.toString()); + } - // Refresh all signals - var turnEncoderStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition); - - // Update drive inputs + // Drive inputs (Spark) SparkUtil.sparkStickyFault = false; SparkUtil.ifOk( driveSpark, driveEncoder::getPosition, (value) -> inputs.drivePositionRad = value); @@ -255,9 +265,9 @@ public void updateInputs(ModuleIOInputs inputs) { driveSpark, driveSpark::getOutputCurrent, (value) -> inputs.driveCurrentAmps = value); inputs.driveConnected = driveConnectedDebounce.calculate(!SparkUtil.sparkStickyFault); - // Update turn inputs + // Turn inputs (CANcoder abs + Spark velocity/applied/current) SparkUtil.sparkStickyFault = false; - inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(turnEncoderStatus.isOK()); + inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(encStatus.isOK()); inputs.turnAbsolutePosition = Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble()); inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble()); inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()); @@ -269,18 +279,43 @@ public void updateInputs(ModuleIOInputs inputs) { turnSpark, turnSpark::getOutputCurrent, (value) -> inputs.turnCurrentAmps = value); inputs.turnConnected = turnConnectedDebounce.calculate(!SparkUtil.sparkStickyFault); - // Update odometry inputs - inputs.odometryTimestamps = - timestampQueue.stream().mapToDouble((Double value) -> value).toArray(); - inputs.odometryDrivePositionsRad = - drivePositionQueue.stream().mapToDouble((Double value) -> value).toArray(); - inputs.odometryTurnPositions = - turnPositionQueue.stream() - .map((Double value) -> new Rotation2d(value).minus(zeroRotation)) - .toArray(Rotation2d[]::new); - timestampQueue.clear(); - drivePositionQueue.clear(); - turnPositionQueue.clear(); + // Odometry queue drain (common prefix only) + final int tsCount = timestampQueue.size(); + final int driveCount = drivePositionQueue.size(); + final int turnCount = turnPositionQueue.size(); + final int sampleCount = Math.min(tsCount, Math.min(driveCount, turnCount)); + + if (sampleCount <= 0) { + inputs.odometryTimestamps = new double[0]; + inputs.odometryDrivePositionsRad = new double[0]; + inputs.odometryTurnPositions = new Rotation2d[0]; + return; + } + + final double[] outTs = new double[sampleCount]; + final double[] outDriveRad = new double[sampleCount]; + final Rotation2d[] outTurn = new Rotation2d[sampleCount]; + + for (int i = 0; i < sampleCount; i++) { + final Double t = timestampQueue.poll(); + final Double drivePosRad = drivePositionQueue.poll(); // already rad in your existing code + final Double turnPosRad = turnPositionQueue.poll(); // rad, then minus zeroRotation below + + if (t == null || drivePosRad == null || turnPosRad == null) { + inputs.odometryTimestamps = Arrays.copyOf(outTs, i); + inputs.odometryDrivePositionsRad = Arrays.copyOf(outDriveRad, i); + inputs.odometryTurnPositions = Arrays.copyOf(outTurn, i); + return; + } + + outTs[i] = t.doubleValue(); + outDriveRad[i] = drivePosRad.doubleValue(); + outTurn[i] = new Rotation2d(turnPosRad.doubleValue()).minus(zeroRotation); + } + + inputs.odometryTimestamps = outTs; + inputs.odometryDrivePositionsRad = outDriveRad; + inputs.odometryTurnPositions = outTurn; } /** diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java index 4359b38..ccf9c27 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java @@ -363,7 +363,7 @@ public void setDriveOpenLoop(double output) { // Log output and battery Logger.recordOutput("Swerve/Drive/OpenLoopOutput", scaledOutput); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); + Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); } /** @@ -384,7 +384,7 @@ public void setTurnOpenLoop(double output) { // Log output and battery Logger.recordOutput("Swerve/Turn/OpenLoopOutput", scaledOutput); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); + Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); } /** @@ -427,7 +427,7 @@ public void setDriveVelocity(double velocityRadPerSec) { Logger.recordOutput("Swerve/Drive/VelocityRotPerSec", velocityRotPerSec); Logger.recordOutput("Swerve/Drive/AccelerationRotPerSec2", accelerationRotPerSec2); Logger.recordOutput("Swerve/Drive/FeedForwardVolts", scaledFFVolts); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); + Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); Logger.recordOutput("Swerve/Drive/ClosedLoopMode", m_DriveMotorClosedLoopOutput); } @@ -455,7 +455,7 @@ public void setTurnPosition(Rotation2d rotation) { }); Logger.recordOutput("Swerve/Turn/TargetRotations", rotation.getRotations()); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); + Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); } @Override diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java index f3cc029..6226ed2 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFXS.java @@ -7,438 +7,507 @@ // license that can be found in the LICENSE file // at the root directory of this project. -package frc.robot.subsystems.drive; - -import static edu.wpi.first.units.Units.RotationsPerSecond; - -import com.ctre.phoenix6.BaseStatusSignal; -import com.ctre.phoenix6.CANBus; -import com.ctre.phoenix6.StatusSignal; -import com.ctre.phoenix6.configs.CANdiConfiguration; -import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; -import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; -import com.ctre.phoenix6.configs.Slot0Configs; -import com.ctre.phoenix6.configs.TalonFXSConfiguration; -import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; -import com.ctre.phoenix6.controls.PositionVoltage; -import com.ctre.phoenix6.controls.TorqueCurrentFOC; -import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; -import com.ctre.phoenix6.controls.VelocityVoltage; -import com.ctre.phoenix6.controls.VoltageOut; -import com.ctre.phoenix6.hardware.CANdi; -import com.ctre.phoenix6.hardware.ParentDevice; -import com.ctre.phoenix6.hardware.TalonFXS; -import com.ctre.phoenix6.signals.BrushedMotorWiringValue; -import com.ctre.phoenix6.signals.ExternalFeedbackSensorSourceValue; -import com.ctre.phoenix6.signals.InvertedValue; -import com.ctre.phoenix6.signals.MotorArrangementValue; -import com.ctre.phoenix6.signals.NeutralModeValue; -import com.ctre.phoenix6.signals.StaticFeedforwardSignValue; -import com.ctre.phoenix6.swerve.SwerveModuleConstants; -import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType; -import edu.wpi.first.math.filter.Debouncer; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.units.measure.Angle; -import edu.wpi.first.units.measure.AngularVelocity; -import edu.wpi.first.units.measure.Current; -import edu.wpi.first.units.measure.Voltage; -import edu.wpi.first.wpilibj.RobotController; -import frc.robot.Constants; -import frc.robot.Constants.DrivebaseConstants; -import frc.robot.util.PhoenixUtil; -import frc.robot.util.RBSICANBusRegistry; -import java.util.Queue; -import org.littletonrobotics.junction.Logger; - -/** - * Module IO implementation for Talon FXS drive motor controller, Talon FXS turn motor controller, - * and CANdi (PWM 1). Configured using a set of module constants from Phoenix. - * - *

Device configuration and other behaviors not exposed by TunerConstants can be customized here. - */ -public class ModuleIOTalonFXS implements ModuleIO { - // Hardware objects - private final TalonFXS driveTalon; - private final TalonFXS turnTalon; - private final CANdi candi; - private final ClosedLoopOutputType m_DriveMotorClosedLoopOutput = - switch (Constants.getPhoenixPro()) { - case LICENSED -> ClosedLoopOutputType.TorqueCurrentFOC; - case UNLICENSED -> ClosedLoopOutputType.Voltage; - }; - private final ClosedLoopOutputType m_SteerMotorClosedLoopOutput = - switch (Constants.getPhoenixPro()) { - case LICENSED -> ClosedLoopOutputType.TorqueCurrentFOC; - case UNLICENSED -> ClosedLoopOutputType.Voltage; - }; - - // Voltage control requests - private final VoltageOut voltageRequest = new VoltageOut(0); - private final PositionVoltage positionVoltageRequest = new PositionVoltage(0.0); - private final VelocityVoltage velocityVoltageRequest = new VelocityVoltage(0.0); - - // Torque-current control requests - private final TorqueCurrentFOC torqueCurrentRequest = new TorqueCurrentFOC(0); - private final PositionTorqueCurrentFOC positionTorqueCurrentRequest = - new PositionTorqueCurrentFOC(0.0); - private final VelocityTorqueCurrentFOC velocityTorqueCurrentRequest = - new VelocityTorqueCurrentFOC(0.0); - - // Timestamp inputs from Phoenix thread - private final Queue timestampQueue; - - // Inputs from drive motor - private final StatusSignal drivePosition; - private final StatusSignal drivePositionOdom; - private final Queue drivePositionQueue; - private final StatusSignal driveVelocity; - private final StatusSignal driveAppliedVolts; - private final StatusSignal driveCurrent; - - // Inputs from turn motor - private final StatusSignal turnAbsolutePosition; - private final StatusSignal turnPosition; - private final StatusSignal turnPositionOdom; - private final Queue turnPositionQueue; - private final StatusSignal turnVelocity; - private final StatusSignal turnAppliedVolts; - private final StatusSignal turnCurrent; - - // Connection debouncers - private final Debouncer driveConnectedDebounce = - new Debouncer(0.5, Debouncer.DebounceType.kFalling); - private final Debouncer turnConnectedDebounce = - new Debouncer(0.5, Debouncer.DebounceType.kFalling); - private final Debouncer turnEncoderConnectedDebounce = - new Debouncer(0.5, Debouncer.DebounceType.kFalling); - - // Config - private final TalonFXSConfiguration driveConfig = new TalonFXSConfiguration(); - private final TalonFXSConfiguration turnConfig = new TalonFXSConfiguration(); - - // Values used for calculating feedforward from kS, kV, and kA - private double lastVelocityRotPerSec = 0.0; - private long lastTimestampNano = System.nanoTime(); - - /* - * TalonFXS I/O - */ - public ModuleIOTalonFXS( - SwerveModuleConstants - constants) { - CANBus canBus = RBSICANBusRegistry.getBus(SwerveConstants.kCANbusName); - driveTalon = new TalonFXS(constants.DriveMotorId, canBus); - turnTalon = new TalonFXS(constants.SteerMotorId, canBus); - candi = new CANdi(constants.EncoderId, canBus); - - // Configure drive motor - driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - driveConfig.Slot0 = - new Slot0Configs() - .withKP(DrivebaseConstants.kDriveP) - .withKI(0.0) - .withKD(DrivebaseConstants.kDriveD) - .withKS(DrivebaseConstants.kDriveS) - .withKV(DrivebaseConstants.kDriveV) - .withKA(DrivebaseConstants.kDriveA); - driveConfig.Commutation.MotorArrangement = - switch (constants.DriveMotorType) { - case TalonFXS_NEO_JST -> MotorArrangementValue.NEO_JST; - case TalonFXS_VORTEX_JST -> MotorArrangementValue.VORTEX_JST; - default -> MotorArrangementValue.Disabled; - }; - driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - driveConfig.Slot0 = constants.DriveMotorGains; - driveConfig.ExternalFeedback.SensorToMechanismRatio = constants.DriveMotorGearRatio; - driveConfig.CurrentLimits.StatorCurrentLimit = DrivebaseConstants.kSlipCurrent; - driveConfig.CurrentLimits.StatorCurrentLimitEnable = true; - // Build the OpenLoopRampsConfigs and ClosedLoopRampsConfigs for current smoothing - OpenLoopRampsConfigs openRamps = new OpenLoopRampsConfigs(); - openRamps.DutyCycleOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; - openRamps.VoltageOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; - openRamps.TorqueOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; - ClosedLoopRampsConfigs closedRamps = new ClosedLoopRampsConfigs(); - closedRamps.DutyCycleClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; - closedRamps.VoltageClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; - closedRamps.TorqueClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; - // Apply the open- and closed-loop ramp configuration for current smoothing - driveConfig.withClosedLoopRamps(closedRamps).withOpenLoopRamps(openRamps); - // Set motor inversions - driveConfig.MotorOutput.Inverted = - constants.DriveMotorInverted - ? InvertedValue.Clockwise_Positive - : InvertedValue.CounterClockwise_Positive; - // Apply everything to the motor controllers - PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); - PhoenixUtil.tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); - - // Configure turn motor - turnConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - turnConfig.Slot0 = - new Slot0Configs() - .withKP(DrivebaseConstants.kSteerP) - .withKI(0.0) - .withKD(DrivebaseConstants.kSteerD) - .withKS(DrivebaseConstants.kSteerS) - .withKV(0.0) - .withKA(0.0) - .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); - turnConfig.Commutation.MotorArrangement = - switch (constants.SteerMotorType) { - case TalonFXS_Minion_JST -> MotorArrangementValue.Minion_JST; - case TalonFXS_NEO_JST -> MotorArrangementValue.NEO_JST; - case TalonFXS_VORTEX_JST -> MotorArrangementValue.VORTEX_JST; - case TalonFXS_NEO550_JST -> MotorArrangementValue.NEO550_JST; - case TalonFXS_Brushed_AB, TalonFXS_Brushed_AC, TalonFXS_Brushed_BC -> - MotorArrangementValue.Brushed_DC; - default -> MotorArrangementValue.Disabled; - }; - turnConfig.Commutation.BrushedMotorWiring = - switch (constants.SteerMotorType) { - case TalonFXS_Brushed_AC -> BrushedMotorWiringValue.Leads_A_and_C; - case TalonFXS_Brushed_BC -> BrushedMotorWiringValue.Leads_B_and_C; - default -> BrushedMotorWiringValue.Leads_A_and_B; - }; - turnConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - turnConfig.Slot0 = constants.SteerMotorGains; - turnConfig.ExternalFeedback.FeedbackRemoteSensorID = constants.EncoderId; - turnConfig.ExternalFeedback.ExternalFeedbackSensorSource = - switch (constants.FeedbackSource) { - case RemoteCANdiPWM1 -> ExternalFeedbackSensorSourceValue.RemoteCANdiPWM1; - case FusedCANdiPWM1 -> ExternalFeedbackSensorSourceValue.FusedCANdiPWM1; - case SyncCANdiPWM1 -> ExternalFeedbackSensorSourceValue.SyncCANdiPWM1; - default -> - throw new RuntimeException( - "You have selected a turn feedback source that is not supported by the default implementation of ModuleIOTalonFXS (CANdi PWM 1). Please check the AdvantageKit documentation for more information on alternative configurations: https://docs.advantagekit.org/getting-started/template-projects/talonfx-swerve-template#custom-module-implementations"); - }; - turnConfig.ExternalFeedback.RotorToSensorRatio = constants.SteerMotorGearRatio; - turnConfig.MotionMagic.MotionMagicCruiseVelocity = 100.0 / constants.SteerMotorGearRatio; - turnConfig.MotionMagic.MotionMagicAcceleration = - turnConfig.MotionMagic.MotionMagicCruiseVelocity / 0.100; - turnConfig.MotionMagic.MotionMagicExpo_kV = 0.12 * constants.SteerMotorGearRatio; - turnConfig.MotionMagic.MotionMagicExpo_kA = 0.1; - turnConfig.ClosedLoopGeneral.ContinuousWrap = true; - turnConfig.MotorOutput.Inverted = - constants.SteerMotorInverted - ? InvertedValue.Clockwise_Positive - : InvertedValue.CounterClockwise_Positive; - PhoenixUtil.tryUntilOk(5, () -> turnTalon.getConfigurator().apply(turnConfig, 0.25)); - - // Configure CANdi - CANdiConfiguration candiConfig = constants.EncoderInitialConfigs; - candiConfig.PWM1.AbsoluteSensorOffset = constants.EncoderOffset; - candiConfig.PWM1.SensorDirection = constants.EncoderInverted; - candi.getConfigurator().apply(candiConfig); - - // Create timestamp queue - timestampQueue = PhoenixOdometryThread.getInstance().makeTimestampQueue(); - - // Create drive status signals - drivePosition = driveTalon.getPosition(); - drivePositionOdom = drivePosition.clone(); // NEW - drivePositionQueue = PhoenixOdometryThread.getInstance().registerSignal(drivePositionOdom); - - driveVelocity = driveTalon.getVelocity(); - driveAppliedVolts = driveTalon.getMotorVoltage(); - driveCurrent = driveTalon.getStatorCurrent(); - - // Create turn status signals - turnPosition = turnTalon.getPosition(); - turnPositionOdom = turnPosition.clone(); // NEW - turnPositionQueue = PhoenixOdometryThread.getInstance().registerSignal(turnPositionOdom); - - turnAbsolutePosition = candi.getPWM1Position(); - turnVelocity = turnTalon.getVelocity(); - turnAppliedVolts = turnTalon.getMotorVoltage(); - turnCurrent = turnTalon.getStatorCurrent(); - - // Configure periodic frames (IMPORTANT: apply odometry rate to the *odom clones*) - BaseStatusSignal.setUpdateFrequencyForAll( - SwerveConstants.kOdometryFrequency, drivePositionOdom, turnPositionOdom); - BaseStatusSignal.setUpdateFrequencyForAll( - 50.0, - drivePosition, - turnPosition, - driveVelocity, - driveAppliedVolts, - driveCurrent, - turnAbsolutePosition, - turnVelocity, - turnAppliedVolts, - turnCurrent); - - ParentDevice.optimizeBusUtilizationForAll(driveTalon, turnTalon); - } - - @Override - public void updateInputs(ModuleIOInputs inputs) { - // Refresh all signals - var driveStatus = - BaseStatusSignal.refreshAll(drivePosition, driveVelocity, driveAppliedVolts, driveCurrent); - var turnStatus = - BaseStatusSignal.refreshAll(turnPosition, turnVelocity, turnAppliedVolts, turnCurrent); - var turnEncoderStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition); - - // Update drive inputs - inputs.driveConnected = driveConnectedDebounce.calculate(driveStatus.isOK()); - inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()); - inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()); - inputs.driveAppliedVolts = driveAppliedVolts.getValueAsDouble(); - inputs.driveCurrentAmps = driveCurrent.getValueAsDouble(); - - // Update turn inputs - inputs.turnConnected = turnConnectedDebounce.calculate(turnStatus.isOK()); - inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(turnEncoderStatus.isOK()); - inputs.turnAbsolutePosition = Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble()); - inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble()); - inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()); - inputs.turnAppliedVolts = turnAppliedVolts.getValueAsDouble(); - inputs.turnCurrentAmps = turnCurrent.getValueAsDouble(); - - // Update odometry inputs - inputs.odometryTimestamps = - timestampQueue.stream().mapToDouble((Double value) -> value).toArray(); - inputs.odometryDrivePositionsRad = - drivePositionQueue.stream() - .mapToDouble((Double value) -> Units.rotationsToRadians(value)) - .toArray(); - inputs.odometryTurnPositions = - turnPositionQueue.stream() - .map((Double value) -> Rotation2d.fromRotations(value)) - .toArray(Rotation2d[]::new); - timestampQueue.clear(); - drivePositionQueue.clear(); - turnPositionQueue.clear(); - } - - /** - * Set the drive motor to an open-loop voltage, scaled to battery voltage - * - * @param output Specified open-loop voltage requested - */ - @Override - public void setDriveOpenLoop(double output) { - // Scale by actual battery voltage to keep full output consistent - double busVoltage = RobotController.getBatteryVoltage(); - double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; - - driveTalon.setControl( - switch (m_DriveMotorClosedLoopOutput) { - case Voltage -> voltageRequest.withOutput(scaledOutput); - case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); - }); - - // Log output and battery - Logger.recordOutput("Swerve/Drive/OpenLoopOutput", scaledOutput); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); - } - - /** - * Set the turn motor to an open-loop voltage, scaled to battery voltage - * - * @param output Specified open-loop voltage requested - */ - @Override - public void setTurnOpenLoop(double output) { - double busVoltage = RobotController.getBatteryVoltage(); - double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; - - turnTalon.setControl( - switch (m_SteerMotorClosedLoopOutput) { - case Voltage -> voltageRequest.withOutput(scaledOutput); - case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); - }); - - Logger.recordOutput("Swerve/Turn/OpenLoopOutput", scaledOutput); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); - } - - /** - * Set the velocity of the module - * - * @param velocityRadPerSec Requested module drive velocity in radians per second - */ - @Override - public void setDriveVelocity(double velocityRadPerSec) { - double velocityRotPerSec = Units.radiansToRotations(velocityRadPerSec); - double busVoltage = RobotController.getBatteryVoltage(); - - // Compute the Feedforward voltage for CTRE UNLICENSED operation ***** - // Compute acceleration - long currentTimeNano = System.nanoTime(); - double deltaTimeSec = (currentTimeNano - lastTimestampNano) * 1e-9; - double accelerationRotPerSec2 = - deltaTimeSec > 0 ? (velocityRotPerSec - lastVelocityRotPerSec) / deltaTimeSec : 0.0; - // Update last values for next loop - lastVelocityRotPerSec = velocityRotPerSec; - lastTimestampNano = currentTimeNano; - // Compute feedforward voltage: kS + kV*v + kA*a - double nominalFFVolts = - Math.signum(velocityRotPerSec) * DrivebaseConstants.kDriveS - + DrivebaseConstants.kDriveV * velocityRotPerSec - + DrivebaseConstants.kDriveA * accelerationRotPerSec2; - double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; - - // Set the drive motor control based on CTRE LICENSED status - driveTalon.setControl( - switch (m_DriveMotorClosedLoopOutput) { - case Voltage -> - velocityVoltageRequest.withVelocity(velocityRotPerSec).withFeedForward(scaledFFVolts); - case TorqueCurrentFOC -> - velocityTorqueCurrentRequest.withVelocity(RotationsPerSecond.of(velocityRotPerSec)); - }); - - // AdvantageKit logging - Logger.recordOutput("Swerve/Drive/VelocityRadPerSec", velocityRadPerSec); - Logger.recordOutput("Swerve/Drive/VelocityRotPerSec", velocityRotPerSec); - Logger.recordOutput("Swerve/Drive/AccelerationRotPerSec2", accelerationRotPerSec2); - Logger.recordOutput("Swerve/Drive/FeedForwardVolts", scaledFFVolts); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); - Logger.recordOutput("Swerve/Drive/ClosedLoopMode", m_DriveMotorClosedLoopOutput); - } - - /** - * Set the turn position of the module - * - * @param rotation Requested module Rotation2d position - */ - @Override - public void setTurnPosition(Rotation2d rotation) { - double busVoltage = RobotController.getBatteryVoltage(); - - // Scale feedforward voltage by battery voltage - double nominalFFVolts = - DrivebaseConstants.kNominalFFVolts; // replace with your feedforward calculation if needed - double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; - - turnTalon.setControl( - switch (m_SteerMotorClosedLoopOutput) { - case Voltage -> - positionVoltageRequest - .withPosition(rotation.getRotations()) - .withFeedForward(scaledFFVolts); - case TorqueCurrentFOC -> - positionTorqueCurrentRequest.withPosition(rotation.getRotations()); - }); - - Logger.recordOutput("Swerve/Turn/TargetRotations", rotation.getRotations()); - Logger.recordOutput("Robot/BatteryVoltage", busVoltage); - } - - @Override - public void setDrivePID(double kP, double kI, double kD) { - driveConfig.Slot0.kP = kP; - driveConfig.Slot0.kI = kI; - driveConfig.Slot0.kD = kD; - PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); - } - - @Override - public void setTurnPID(double kP, double kI, double kD) { - turnConfig.Slot0.kP = kP; - turnConfig.Slot0.kI = kI; - turnConfig.Slot0.kD = kD; - PhoenixUtil.tryUntilOk(5, () -> turnTalon.getConfigurator().apply(turnConfig, 0.25)); - } -} +// IMPORTANT: UNCOMMENT THIS MODULE IF YOU ARE USING FXS instead of FX +// COMMENT OUT the FX module + +// package frc.robot.subsystems.drive; + +// import static edu.wpi.first.units.Units.RotationsPerSecond; + +// import com.ctre.phoenix6.BaseStatusSignal; +// import com.ctre.phoenix6.CANBus; +// import com.ctre.phoenix6.StatusSignal; +// import com.ctre.phoenix6.configs.CANdiConfiguration; +// import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +// import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; +// import com.ctre.phoenix6.configs.Slot0Configs; +// import com.ctre.phoenix6.configs.TalonFXConfiguration; +// import com.ctre.phoenix6.configs.TalonFXSConfiguration; +// import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; +// import com.ctre.phoenix6.controls.PositionVoltage; +// import com.ctre.phoenix6.controls.TorqueCurrentFOC; +// import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; +// import com.ctre.phoenix6.controls.VelocityVoltage; +// import com.ctre.phoenix6.controls.VoltageOut; +// import com.ctre.phoenix6.hardware.CANdi; +// import com.ctre.phoenix6.hardware.ParentDevice; +// import com.ctre.phoenix6.hardware.TalonFXS; +// import com.ctre.phoenix6.signals.BrushedMotorWiringValue; +// import com.ctre.phoenix6.signals.ExternalFeedbackSensorSourceValue; +// import com.ctre.phoenix6.signals.InvertedValue; +// import com.ctre.phoenix6.signals.MotorArrangementValue; +// import com.ctre.phoenix6.signals.NeutralModeValue; +// import com.ctre.phoenix6.signals.StaticFeedforwardSignValue; +// import com.ctre.phoenix6.swerve.SwerveModuleConstants; +// import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType; +// import edu.wpi.first.math.filter.Debouncer; +// import edu.wpi.first.math.geometry.Rotation2d; +// import edu.wpi.first.math.util.Units; +// import edu.wpi.first.units.measure.Angle; +// import edu.wpi.first.units.measure.AngularVelocity; +// import edu.wpi.first.units.measure.Current; +// import edu.wpi.first.units.measure.Voltage; +// import edu.wpi.first.wpilibj.RobotController; +// import frc.robot.Constants; +// import frc.robot.Constants.DrivebaseConstants; +// import frc.robot.generated.TunerConstants; +// import frc.robot.util.PhoenixUtil; +// import frc.robot.util.RBSICANBusRegistry; +// import java.util.Arrays; +// import java.util.Queue; +// import org.littletonrobotics.junction.Logger; + +// /** +// * Module IO implementation for Talon FXS drive motor controller, Talon FXS turn motor +// controller, +// * and CANdi (PWM 1). Configured using a set of module constants from Phoenix. +// * +// *

Device configuration and other behaviors not exposed by TunerConstants can be customized +// here. +// */ +// public class ModuleIOTalonFXS implements ModuleIO { +// private final SwerveModuleConstants< +// TalonFXConfiguration, TalonFXConfiguration, CANdiConfiguration> +// constants; + +// // This module number (for logging) +// private final int module; + +// // Hardware objects +// private final TalonFXS driveTalon; +// private final TalonFXS turnTalon; +// private final CANdi candi; +// private final ClosedLoopOutputType m_DriveMotorClosedLoopOutput = +// switch (Constants.getPhoenixPro()) { +// case LICENSED -> ClosedLoopOutputType.TorqueCurrentFOC; +// case UNLICENSED -> ClosedLoopOutputType.Voltage; +// }; +// private final ClosedLoopOutputType m_SteerMotorClosedLoopOutput = +// switch (Constants.getPhoenixPro()) { +// case LICENSED -> ClosedLoopOutputType.TorqueCurrentFOC; +// case UNLICENSED -> ClosedLoopOutputType.Voltage; +// }; + +// // Voltage control requests +// private final VoltageOut voltageRequest = new VoltageOut(0); +// private final PositionVoltage positionVoltageRequest = new PositionVoltage(0.0); +// private final VelocityVoltage velocityVoltageRequest = new VelocityVoltage(0.0); + +// // Torque-current control requests +// private final TorqueCurrentFOC torqueCurrentRequest = new TorqueCurrentFOC(0); +// private final PositionTorqueCurrentFOC positionTorqueCurrentRequest = +// new PositionTorqueCurrentFOC(0.0); +// private final VelocityTorqueCurrentFOC velocityTorqueCurrentRequest = +// new VelocityTorqueCurrentFOC(0.0); + +// // Timestamp inputs from Phoenix thread +// private final Queue timestampQueue; + +// // Inputs from drive motor +// private final StatusSignal drivePosition; +// private final StatusSignal drivePositionOdom; +// private final Queue drivePositionQueue; +// private final StatusSignal driveVelocity; +// private final StatusSignal driveAppliedVolts; +// private final StatusSignal driveCurrent; + +// // Inputs from turn motor +// private final StatusSignal turnAbsolutePosition; +// private final StatusSignal turnPosition; +// private final StatusSignal turnPositionOdom; +// private final Queue turnPositionQueue; +// private final StatusSignal turnVelocity; +// private final StatusSignal turnAppliedVolts; +// private final StatusSignal turnCurrent; + +// // Connection debouncers +// private final Debouncer driveConnectedDebounce = +// new Debouncer(0.5, Debouncer.DebounceType.kFalling); +// private final Debouncer turnConnectedDebounce = +// new Debouncer(0.5, Debouncer.DebounceType.kFalling); +// private final Debouncer turnEncoderConnectedDebounce = +// new Debouncer(0.5, Debouncer.DebounceType.kFalling); + +// // Config +// private final TalonFXSConfiguration driveConfig = new TalonFXSConfiguration(); +// private final TalonFXSConfiguration turnConfig = new TalonFXSConfiguration(); + +// // Values used for calculating feedforward from kS, kV, and kA +// private double lastVelocityRotPerSec = 0.0; +// private long lastTimestampNano = System.nanoTime(); + +// /* +// * TalonFXS I/O +// */ +// public ModuleIOTalonFXS(int module) { +// // Record the module number for logging purposes +// this.module = module; + +// constants = +// switch (module) { +// case 0 -> TunerConstants.FrontLeft; +// case 1 -> TunerConstants.FrontRight; +// case 2 -> TunerConstants.BackLeft; +// case 3 -> TunerConstants.BackRight; +// default -> throw new IllegalArgumentException("Invalid module index"); +// }; + +// CANBus canBus = RBSICANBusRegistry.getBus(SwerveConstants.kCANbusName); +// driveTalon = new TalonFXS(constants.DriveMotorId, canBus); +// turnTalon = new TalonFXS(constants.SteerMotorId, canBus); +// candi = new CANdi(constants.EncoderId, canBus); + +// // Configure drive motor +// driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; +// driveConfig.Slot0 = +// new Slot0Configs() +// .withKP(DrivebaseConstants.kDriveP) +// .withKI(0.0) +// .withKD(DrivebaseConstants.kDriveD) +// .withKS(DrivebaseConstants.kDriveS) +// .withKV(DrivebaseConstants.kDriveV) +// .withKA(DrivebaseConstants.kDriveA); +// driveConfig.Commutation.MotorArrangement = +// switch (constants.DriveMotorType) { +// case TalonFXS_NEO_JST -> MotorArrangementValue.NEO_JST; +// case TalonFXS_VORTEX_JST -> MotorArrangementValue.VORTEX_JST; +// default -> MotorArrangementValue.Disabled; +// }; +// driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; +// driveConfig.Slot0 = constants.DriveMotorGains; +// driveConfig.ExternalFeedback.SensorToMechanismRatio = constants.DriveMotorGearRatio; +// driveConfig.CurrentLimits.StatorCurrentLimit = DrivebaseConstants.kSlipCurrent; +// driveConfig.CurrentLimits.StatorCurrentLimitEnable = true; +// // Build the OpenLoopRampsConfigs and ClosedLoopRampsConfigs for current smoothing +// OpenLoopRampsConfigs openRamps = new OpenLoopRampsConfigs(); +// openRamps.DutyCycleOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; +// openRamps.VoltageOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; +// openRamps.TorqueOpenLoopRampPeriod = DrivebaseConstants.kDriveOpenLoopRampPeriod; +// ClosedLoopRampsConfigs closedRamps = new ClosedLoopRampsConfigs(); +// closedRamps.DutyCycleClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; +// closedRamps.VoltageClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; +// closedRamps.TorqueClosedLoopRampPeriod = DrivebaseConstants.kDriveClosedLoopRampPeriod; +// // Apply the open- and closed-loop ramp configuration for current smoothing +// driveConfig.withClosedLoopRamps(closedRamps).withOpenLoopRamps(openRamps); +// // Set motor inversions +// driveConfig.MotorOutput.Inverted = +// constants.DriveMotorInverted +// ? InvertedValue.Clockwise_Positive +// : InvertedValue.CounterClockwise_Positive; +// // Apply everything to the motor controllers +// PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); +// PhoenixUtil.tryUntilOk(5, () -> driveTalon.setPosition(0.0, 0.25)); + +// // Configure turn motor +// turnConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; +// turnConfig.Slot0 = +// new Slot0Configs() +// .withKP(DrivebaseConstants.kSteerP) +// .withKI(0.0) +// .withKD(DrivebaseConstants.kSteerD) +// .withKS(DrivebaseConstants.kSteerS) +// .withKV(0.0) +// .withKA(0.0) +// .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); +// turnConfig.Commutation.MotorArrangement = +// switch (constants.SteerMotorType) { +// case TalonFXS_Minion_JST -> MotorArrangementValue.Minion_JST; +// case TalonFXS_NEO_JST -> MotorArrangementValue.NEO_JST; +// case TalonFXS_VORTEX_JST -> MotorArrangementValue.VORTEX_JST; +// case TalonFXS_NEO550_JST -> MotorArrangementValue.NEO550_JST; +// case TalonFXS_Brushed_AB, TalonFXS_Brushed_AC, TalonFXS_Brushed_BC -> +// MotorArrangementValue.Brushed_DC; +// default -> MotorArrangementValue.Disabled; +// }; +// turnConfig.Commutation.BrushedMotorWiring = +// switch (constants.SteerMotorType) { +// case TalonFXS_Brushed_AC -> BrushedMotorWiringValue.Leads_A_and_C; +// case TalonFXS_Brushed_BC -> BrushedMotorWiringValue.Leads_B_and_C; +// default -> BrushedMotorWiringValue.Leads_A_and_B; +// }; +// turnConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; +// turnConfig.Slot0 = constants.SteerMotorGains; +// turnConfig.ExternalFeedback.FeedbackRemoteSensorID = constants.EncoderId; +// turnConfig.ExternalFeedback.ExternalFeedbackSensorSource = +// switch (constants.FeedbackSource) { +// case RemoteCANdiPWM1 -> ExternalFeedbackSensorSourceValue.RemoteCANdiPWM1; +// case FusedCANdiPWM1 -> ExternalFeedbackSensorSourceValue.FusedCANdiPWM1; +// case SyncCANdiPWM1 -> ExternalFeedbackSensorSourceValue.SyncCANdiPWM1; +// default -> +// throw new RuntimeException( +// "You have selected a turn feedback source that is not supported by the default +// implementation of ModuleIOTalonFXS (CANdi PWM 1). Please check the AdvantageKit documentation for +// more information on alternative configurations: +// https://docs.advantagekit.org/getting-started/template-projects/talonfx-swerve-template#custom-module-implementations"); +// }; +// turnConfig.ExternalFeedback.RotorToSensorRatio = constants.SteerMotorGearRatio; +// turnConfig.MotionMagic.MotionMagicCruiseVelocity = 100.0 / constants.SteerMotorGearRatio; +// turnConfig.MotionMagic.MotionMagicAcceleration = +// turnConfig.MotionMagic.MotionMagicCruiseVelocity / 0.100; +// turnConfig.MotionMagic.MotionMagicExpo_kV = 0.12 * constants.SteerMotorGearRatio; +// turnConfig.MotionMagic.MotionMagicExpo_kA = 0.1; +// turnConfig.ClosedLoopGeneral.ContinuousWrap = true; +// turnConfig.MotorOutput.Inverted = +// constants.SteerMotorInverted +// ? InvertedValue.Clockwise_Positive +// : InvertedValue.CounterClockwise_Positive; +// PhoenixUtil.tryUntilOk(5, () -> turnTalon.getConfigurator().apply(turnConfig, 0.25)); + +// // Configure CANdi +// CANdiConfiguration candiConfig = constants.EncoderInitialConfigs; +// candiConfig.PWM1.AbsoluteSensorOffset = constants.EncoderOffset; +// candiConfig.PWM1.SensorDirection = constants.EncoderInverted; +// candi.getConfigurator().apply(candiConfig); + +// // Create timestamp queue +// timestampQueue = PhoenixOdometryThread.getInstance().makeTimestampQueue(); + +// // Create drive status signals +// drivePosition = driveTalon.getPosition(); +// drivePositionOdom = drivePosition.clone(); // NEW +// drivePositionQueue = PhoenixOdometryThread.getInstance().registerSignal(drivePositionOdom); + +// driveVelocity = driveTalon.getVelocity(); +// driveAppliedVolts = driveTalon.getMotorVoltage(); +// driveCurrent = driveTalon.getStatorCurrent(); + +// // Create turn status signals +// turnPosition = turnTalon.getPosition(); +// turnPositionOdom = turnPosition.clone(); // NEW +// turnPositionQueue = PhoenixOdometryThread.getInstance().registerSignal(turnPositionOdom); + +// turnAbsolutePosition = candi.getPWM1Position(); +// turnVelocity = turnTalon.getVelocity(); +// turnAppliedVolts = turnTalon.getMotorVoltage(); +// turnCurrent = turnTalon.getStatorCurrent(); + +// // Configure periodic frames (IMPORTANT: apply odometry rate to the *odom clones*) +// BaseStatusSignal.setUpdateFrequencyForAll( +// SwerveConstants.kOdometryFrequency, drivePositionOdom, turnPositionOdom); +// BaseStatusSignal.setUpdateFrequencyForAll( +// 50.0, +// drivePosition, +// turnPosition, +// driveVelocity, +// driveAppliedVolts, +// driveCurrent, +// turnAbsolutePosition, +// turnVelocity, +// turnAppliedVolts, +// turnCurrent); + +// ParentDevice.optimizeBusUtilizationForAll(driveTalon, turnTalon); +// } + +// @Override +// public void updateInputs(ModuleIOInputs inputs) { +// // Refresh Phoenix signals +// var driveStatus = +// BaseStatusSignal.refreshAll(drivePosition, driveVelocity, driveAppliedVolts, +// driveCurrent); +// var turnStatus = +// BaseStatusSignal.refreshAll(turnPosition, turnVelocity, turnAppliedVolts, turnCurrent); +// var encStatus = BaseStatusSignal.refreshAll(turnAbsolutePosition); + +// // Optional: status logging +// if (!driveStatus.isOK()) { +// Logger.recordOutput("CAN/Module" + module + "/DriveRefreshStatus", driveStatus.toString()); +// } +// if (!turnStatus.isOK()) { +// Logger.recordOutput("CAN/Module" + module + "/TurnRefreshStatus", turnStatus.toString()); +// } +// if (!encStatus.isOK()) { +// Logger.recordOutput("CAN/Module" + module + "/EncRefreshStatus", encStatus.toString()); +// } + +// // Connectivity flags +// inputs.driveConnected = driveConnectedDebounce.calculate(driveStatus.isOK()); +// inputs.turnConnected = turnConnectedDebounce.calculate(turnStatus.isOK()); +// inputs.turnEncoderConnected = turnEncoderConnectedDebounce.calculate(encStatus.isOK()); + +// // Drive inputs +// inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()); +// inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()); +// inputs.driveAppliedVolts = driveAppliedVolts.getValueAsDouble(); +// inputs.driveCurrentAmps = driveCurrent.getValueAsDouble(); + +// // Turn inputs +// inputs.turnAbsolutePosition = +// Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble()); +// inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble()); +// inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()); +// inputs.turnAppliedVolts = turnAppliedVolts.getValueAsDouble(); +// inputs.turnCurrentAmps = turnCurrent.getValueAsDouble(); + +// // Odometry queue drain (common prefix only) +// final int tsCount = timestampQueue.size(); +// final int driveCount = drivePositionQueue.size(); +// final int turnCount = turnPositionQueue.size(); +// final int sampleCount = Math.min(tsCount, Math.min(driveCount, turnCount)); + +// if (sampleCount <= 0) { +// inputs.odometryTimestamps = new double[0]; +// inputs.odometryDrivePositionsRad = new double[0]; +// inputs.odometryTurnPositions = new Rotation2d[0]; +// return; +// } + +// final double[] outTs = new double[sampleCount]; +// final double[] outDriveRad = new double[sampleCount]; +// final Rotation2d[] outTurn = new Rotation2d[sampleCount]; + +// for (int i = 0; i < sampleCount; i++) { +// final Double t = timestampQueue.poll(); +// final Double driveRot = drivePositionQueue.poll(); +// final Double turnRot = turnPositionQueue.poll(); + +// if (t == null || driveRot == null || turnRot == null) { +// inputs.odometryTimestamps = Arrays.copyOf(outTs, i); +// inputs.odometryDrivePositionsRad = Arrays.copyOf(outDriveRad, i); +// inputs.odometryTurnPositions = Arrays.copyOf(outTurn, i); +// return; +// } + +// outTs[i] = t.doubleValue(); +// outDriveRad[i] = Units.rotationsToRadians(driveRot.doubleValue()); +// outTurn[i] = Rotation2d.fromRotations(turnRot.doubleValue()); +// } + +// inputs.odometryTimestamps = outTs; +// inputs.odometryDrivePositionsRad = outDriveRad; +// inputs.odometryTurnPositions = outTurn; +// } + +// /** Module Action Functions ********************************************** */ +// /** +// * Set the drive motor to an open-loop voltage, scaled to battery voltage +// * +// * @param output Specified open-loop voltage requested +// */ +// @Override +// public void setDriveOpenLoop(double output) { +// // Scale by actual battery voltage to keep full output consistent +// double busVoltage = RobotController.getBatteryVoltage(); +// double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + +// driveTalon.setControl( +// switch (m_DriveMotorClosedLoopOutput) { +// case Voltage -> voltageRequest.withOutput(scaledOutput); +// case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); +// }); + +// // Log output and battery +// Logger.recordOutput("Swerve/Drive/OpenLoopOutput", scaledOutput); +// Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); +// } + +// /** +// * Set the turn motor to an open-loop voltage, scaled to battery voltage +// * +// * @param output Specified open-loop voltage requested +// */ +// @Override +// public void setTurnOpenLoop(double output) { +// double busVoltage = RobotController.getBatteryVoltage(); +// double scaledOutput = output * DrivebaseConstants.kOptimalVoltage / busVoltage; + +// turnTalon.setControl( +// switch (m_SteerMotorClosedLoopOutput) { +// case Voltage -> voltageRequest.withOutput(scaledOutput); +// case TorqueCurrentFOC -> torqueCurrentRequest.withOutput(scaledOutput); +// }); + +// // Log output and battery +// Logger.recordOutput("Swerve/Turn/OpenLoopOutput", scaledOutput); +// Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); +// } + +// /** +// * Set the velocity of the module +// * +// * @param velocityRadPerSec Requested module drive velocity in radians per second +// */ +// @Override +// public void setDriveVelocity(double velocityRadPerSec) { +// double velocityRotPerSec = Units.radiansToRotations(velocityRadPerSec); +// double busVoltage = RobotController.getBatteryVoltage(); + +// // Compute the Feedforward voltage for CTRE UNLICENSED operation ***** +// // Compute acceleration +// long currentTimeNano = System.nanoTime(); +// double deltaTimeSec = (currentTimeNano - lastTimestampNano) * 1e-9; +// double accelerationRotPerSec2 = +// deltaTimeSec > 0 ? (velocityRotPerSec - lastVelocityRotPerSec) / deltaTimeSec : 0.0; +// // Update last values for next loop +// lastVelocityRotPerSec = velocityRotPerSec; +// lastTimestampNano = currentTimeNano; +// // Compute feedforward voltage: kS + kV*v + kA*a +// double nominalFFVolts = +// Math.signum(velocityRotPerSec) * DrivebaseConstants.kDriveS +// + DrivebaseConstants.kDriveV * velocityRotPerSec +// + DrivebaseConstants.kDriveA * accelerationRotPerSec2; +// double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + +// // Set the drive motor control based on CTRE LICENSED status +// driveTalon.setControl( +// switch (m_DriveMotorClosedLoopOutput) { +// case Voltage -> +// +// velocityVoltageRequest.withVelocity(velocityRotPerSec).withFeedForward(scaledFFVolts); +// case TorqueCurrentFOC -> +// +// velocityTorqueCurrentRequest.withVelocity(RotationsPerSecond.of(velocityRotPerSec)); +// }); + +// // AdvantageKit logging +// Logger.recordOutput("Swerve/Drive/VelocityRadPerSec", velocityRadPerSec); +// Logger.recordOutput("Swerve/Drive/VelocityRotPerSec", velocityRotPerSec); +// Logger.recordOutput("Swerve/Drive/AccelerationRotPerSec2", accelerationRotPerSec2); +// Logger.recordOutput("Swerve/Drive/FeedForwardVolts", scaledFFVolts); +// Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); +// Logger.recordOutput("Swerve/Drive/ClosedLoopMode", m_DriveMotorClosedLoopOutput); +// } + +// /** +// * Set the turn position of the module +// * +// * @param rotation Requested module Rotation2d position +// */ +// @Override +// public void setTurnPosition(Rotation2d rotation) { +// double busVoltage = RobotController.getBatteryVoltage(); + +// // Scale feedforward voltage by battery voltage +// double nominalFFVolts = DrivebaseConstants.kNominalFFVolts; +// double scaledFFVolts = nominalFFVolts * DrivebaseConstants.kOptimalVoltage / busVoltage; + +// turnTalon.setControl( +// switch (m_SteerMotorClosedLoopOutput) { +// case Voltage -> +// positionVoltageRequest +// .withPosition(rotation.getRotations()) +// .withFeedForward(scaledFFVolts); +// case TorqueCurrentFOC -> +// positionTorqueCurrentRequest.withPosition(rotation.getRotations()); +// }); + +// Logger.recordOutput("Swerve/Turn/TargetRotations", rotation.getRotations()); +// Logger.recordOutput("Swerve/BatteryVoltage", busVoltage); +// } + +// @Override +// public void setDrivePID(double kP, double kI, double kD) { +// driveConfig.Slot0.kP = kP; +// driveConfig.Slot0.kI = kI; +// driveConfig.Slot0.kD = kD; +// PhoenixUtil.tryUntilOk(5, () -> driveTalon.getConfigurator().apply(driveConfig, 0.25)); +// } + +// @Override +// public void setTurnPID(double kP, double kI, double kD) { +// turnConfig.Slot0.kP = kP; +// turnConfig.Slot0.kI = kI; +// turnConfig.Slot0.kD = kD; +// PhoenixUtil.tryUntilOk(5, () -> turnTalon.getConfigurator().apply(turnConfig, 0.25)); +// } +// } diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index ea4930f..48e3bba 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -135,12 +135,6 @@ public void rbsiPeriodic() { boolean hasFusedThisLoop = false; boolean hasSmoothedThisLoop = false; - // Default debug outputs (so keys exist even if we return early) - double dbgAlignDt = Double.NaN; - double dbgDeltaTranslation = Double.NaN; - double dbgDeltaRotation = Double.NaN; - boolean dbgAlignFinite = false; - try { lastAlignDbg.reset(); @@ -278,13 +272,13 @@ public void rbsiPeriodic() { lastFusedValid = true; lastSmoothedValid = true; - Logger.recordOutput("OdometryReplay/PreInjectRobotX", drive.poseEstimatorGetPose().getX()); - Logger.recordOutput("OdometryReplay/PreInjectRobotY", drive.poseEstimatorGetPose().getY()); + Logger.recordOutput("OdometryReplay/PreInjectRobotX", drive.getPose().getX()); + Logger.recordOutput("OdometryReplay/PreInjectRobotY", drive.getPose().getY()); consumer.accept(smoothed); - Logger.recordOutput("OdometryReplay/PostInjectRobotX", drive.poseEstimatorGetPose().getX()); - Logger.recordOutput("OdometryReplay/PostInjectRobotY", drive.poseEstimatorGetPose().getY()); + Logger.recordOutput("OdometryReplay/PostInjectRobotX", drive.getPose().getX()); + Logger.recordOutput("OdometryReplay/PostInjectRobotY", drive.getPose().getY()); // If you want, you can feed debug values from inside timeAlignPose(...) via fields, // but leaving the plumbing as-is since you’re already logging inside helpers. @@ -561,74 +555,13 @@ void set(double dt, Transform2d tf) { private TimedPose fuseAtTime(ArrayList estimates, double tFusion) { final ArrayList aligned = new ArrayList<>(estimates.size()); for (var e : estimates) { - Pose2d alignedPose = timeAlignPoseFieldDelta(e.pose(), e.timestampSeconds(), tFusion); + Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tFusion); if (alignedPose == null) return null; aligned.add(new TimedPose(alignedPose, tFusion, e.stdDevs())); } return inverseVarianceFuse(aligned, tFusion); } - /** - * Align a pose to where it would have been at the fusion time - * - *

Gets the odometric poses at ts and tFusion from the drivebase PoseEstimator, computes the - * transform between them, and applies that to the vision pose. The correction is applied by - * finding the field-frame deltas for both translation and rotation, then returning a new Pose2d - * object that consists of the vision pose adjusted by the field-frame deltas. - * - * @param visionPoseAtTs The pose at ts - * @param ts Timestamp of the pose - * @param tFusion Fusion timestamp - * @return Transformed Pose2d - */ - private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tFusion) { - - Logger.recordOutput("Vision/Debug/ts", ts); - Logger.recordOutput("Vision/Debug/tFusion", tFusion); - Logger.recordOutput("Vision/Debug/alignDtMs", (tFusion - ts) * 1000.0); - - double dt = tFusion - ts; - - Optional odomAtTsOpt = drive.getPoseAtTime(ts); - Optional odomAtTFOpt = drive.getPoseAtTime(tFusion); - // If empty, return null - if (odomAtTsOpt.isEmpty() || odomAtTFOpt.isEmpty()) return null; - - // Transform that takes odomAtTs -> odomAtTF (in odomAtTs frame) - Transform2d ts_T_tf = odomAtTFOpt.get().minus(odomAtTsOpt.get()); - - double dtrans = ts_T_tf.getTranslation().getNorm(); - double drot = ts_T_tf.getRotation().getRadians(); - - boolean finite = - Double.isFinite(dt) - && Double.isFinite(dtrans) - && Double.isFinite(drot) - && Double.isFinite(odomAtTsOpt.get().getX()) - && Double.isFinite(odomAtTFOpt.get().getX()); - - // Even more debugging logging - Logger.recordOutput("Vision/Debug/alignDt", dt); - Logger.recordOutput("Vision/Debug/deltaTranslation", dtrans); - Logger.recordOutput("Vision/Debug/deltaRotation", drot); - Logger.recordOutput("Vision/Debug/alignFinite", finite); - Logger.recordOutput("Vision/Debug/odomAtTs", odomAtTsOpt.get()); - Logger.recordOutput("Vision/Debug/odomAtTF", odomAtTFOpt.get()); - - if (!finite) { - Logger.recordOutput("Vision/Debug/odomAtTs", odomAtTsOpt.get()); - Logger.recordOutput("Vision/Debug/odomAtTF", odomAtTFOpt.get()); - return null; - } - - // Debugging Logging - Logger.recordOutput("Vision/Debug/deltaTranslation", ts_T_tf.getTranslation().getNorm()); - Logger.recordOutput("Vision/Debug/deltaRotation", ts_T_tf.getRotation().getRadians()); - - // Apply the same SE(2) transform to the vision pose - return visionPoseAtTs.transformBy(ts_T_tf); - } - /** * Align a pose to where it would have been at the fusion time * @@ -649,7 +582,7 @@ private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tFusion) { * @param tFusion Fusion timestamp * @return Transformed Pose2d */ - private Pose2d timeAlignPoseFieldDelta(Pose2d visionPoseAtTs, double ts, double tFusion) { + private Pose2d timeAlignPose(Pose2d visionPoseAtTs, double ts, double tFusion) { Optional odomAtTsOpt = drive.getPoseAtTime(ts); Optional odomAtTFOpt = drive.getPoseAtTime(tFusion); if (odomAtTsOpt.isEmpty() || odomAtTFOpt.isEmpty()) return null; @@ -777,7 +710,7 @@ private TimedPose smoothAtTime(double tFusion) { final ArrayList aligned = new ArrayList<>(fusedBuffer.size()); for (var e : fusedBuffer) { - Pose2d alignedPose = timeAlignPoseFieldDelta(e.pose(), e.timestampSeconds(), tFusion); + Pose2d alignedPose = timeAlignPose(e.pose(), e.timestampSeconds(), tFusion); if (alignedPose == null) continue; aligned.add(new TimedPose(alignedPose, tFusion, e.stdDevs())); // Debugging Logging diff --git a/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java b/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java index 3db0b25..a2e55e6 100644 --- a/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java +++ b/src/main/java/frc/robot/util/ConcurrentTimeInterpolatableBuffer.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Az-FIRST +// Copyright (c) 2026 Az-FIRST // http://github.com/AZ-First // Copyright (c) 2024 FRC 254 // https://github.com/team254 @@ -27,7 +27,6 @@ import java.util.OptionalDouble; import java.util.concurrent.ConcurrentNavigableMap; import java.util.concurrent.ConcurrentSkipListMap; -import org.littletonrobotics.junction.Logger; /** * A concurrent version of WPIlib's TimeInterpolatableBuffer class to avoid the need for explicit @@ -90,9 +89,6 @@ public static ConcurrentTimeInterpolatableBuffer createDoubleBuffer( * @param sample The sample object. */ public void addSample(double timeSeconds, T sample) { - Logger.recordOutput("Odometry/Debug/lastPoseBufferAddTs", timeSeconds); - Logger.recordOutput("Odometry/Debug/nowTs", TimeUtil.now()); - m_pastSnapshots.put(timeSeconds, sample); cleanUp(timeSeconds); } @@ -135,7 +131,7 @@ public Optional getSample(double timeSeconds) { if (topBound == null) return Optional.of(bottomBound.getValue()); if (bottomBound == null) return Optional.of(topBound.getValue()); - // NEW: if they are the same sample, no interpolation possible/needed + // If they are the same sample, no interpolation possible/needed if (topBound.getKey().doubleValue() == bottomBound.getKey().doubleValue()) { return Optional.of(bottomBound.getValue()); } @@ -144,17 +140,12 @@ public Optional getSample(double timeSeconds) { double t1 = topBound.getKey(); double denom = t1 - t0; - // (optional but good) + // If the samples are so close together as to be indistinguishable, they are the same if (Math.abs(denom) < 1e-9) return Optional.of(bottomBound.getValue()); double ratio = (timeSeconds - t0) / denom; ratio = MathUtil.clamp(ratio, 0.0, 1.0); - Logger.recordOutput("Odometry/Debug/bottomKey", t0); - Logger.recordOutput("Odometry/Debug/topKey", t1); - Logger.recordOutput("Odometry/Debug/denom", denom); - Logger.recordOutput("Odometry/Debug/snaphotSize", m_pastSnapshots.size()); - return Optional.of( m_interpolatingFunc.interpolate(bottomBound.getValue(), topBound.getValue(), ratio)); } diff --git a/src/main/java/frc/robot/util/RBSICANBusRegistry.java b/src/main/java/frc/robot/util/RBSICANBusRegistry.java index ea3ef08..4619ec7 100644 --- a/src/main/java/frc/robot/util/RBSICANBusRegistry.java +++ b/src/main/java/frc/robot/util/RBSICANBusRegistry.java @@ -18,13 +18,18 @@ import java.util.Set; import java.util.concurrent.ConcurrentHashMap; -/** Centralized CAN bus singleton registry + SIM/REAL indirection. */ +/** Centralized CAN bus singleton registry */ public final class RBSICANBusRegistry { private static final Map realBuses = new ConcurrentHashMap<>(); private static final Map likeBuses = new ConcurrentHashMap<>(); private static volatile boolean initialized = false; private static volatile boolean sim = false; + /** + * Initialize the REAL CANBusses + * + * @param busNames The list of bus names to initialize + */ public static void initReal(String... busNames) { sim = false; for (String name : busNames) { @@ -34,6 +39,11 @@ public static void initReal(String... busNames) { initialized = true; } + /** + * Initialize the SIM CANBusses + * + * @param busNames The list of bus names to initialize + */ public static void initSim(String... busNames) { sim = true; for (String name : busNames) { @@ -42,7 +52,12 @@ public static void initSim(String... busNames) { initialized = true; } - /** For Phoenix device constructors (REAL/REPLAY only). */ + /** + * Get the CANBus for Phoenix device constructors + * + * @param name Name of the CAN bus to get + * @return CANBus object corresponding to the name + */ public static CANBus getBus(String name) { checkInit(); if (sim) { @@ -53,7 +68,12 @@ public static CANBus getBus(String name) { return bus; } - /** For health logging (REAL or SIM). */ + /** + * Get a CANBus-like object for health logging + * + * @param name Name of the bus to health log + * @return CANBusLike object + */ public static CANBusLike getLike(String name) { checkInit(); CANBusLike bus = likeBuses.get(name); @@ -61,52 +81,63 @@ public static CANBusLike getLike(String name) { return bus; } + /** Check that the Registry is initialized */ private static void checkInit() { if (!initialized) throw new IllegalStateException("RBSICANBusRegistry not initialized."); } + /** Throw exception if the CAN bus name is not in the Registry */ private static void throwUnknown(String name, Set known) { throw new IllegalArgumentException("Unknown CAN bus '" + name + "'. Known: " + known); } - // ---- nested types ---- + /** Nested types for Registry Function *********************************** */ + /** CANBusLike interface */ public interface CANBusLike { String getName(); CANBus.CANBusStatus getStatus(); } + /** Real CAN Bus Adapter */ static final class RealCANBusAdapter implements CANBusLike { private final CANBus bus; + /** Constructor */ RealCANBusAdapter(CANBus bus) { this.bus = bus; } + /** Get the name of this CANBus instance */ @Override public String getName() { return bus.getName(); } + /** Get the status of this CANBus instance */ @Override public CANBus.CANBusStatus getStatus() { return bus.getStatus(); } } + /** Simulated CAN Bus Stub */ static final class SimCANBusStub implements CANBusLike { private final String name; + /** Constructor */ SimCANBusStub(String name) { this.name = name; } + /** Get the name of this simulated CANBus */ @Override public String getName() { return name; } + /** Get the status of this simulated CANBus */ @Override public CANBus.CANBusStatus getStatus() { return new CANBus.CANBusStatus(); diff --git a/src/main/java/frc/robot/util/RBSICANHealth.java b/src/main/java/frc/robot/util/RBSICANHealth.java index df7a185..8959020 100644 --- a/src/main/java/frc/robot/util/RBSICANHealth.java +++ b/src/main/java/frc/robot/util/RBSICANHealth.java @@ -15,17 +15,27 @@ import org.littletonrobotics.junction.Logger; +/** + * Virtual subsystem to monitor CAN health + * + *

Instantiate one of these subsystems for each CAN bus on the robot in the RobotContainer. + */ public class RBSICANHealth extends VirtualSubsystem { private long loops = 0; private final RBSICANBusRegistry.CANBusLike bus; + /** Constructur */ public RBSICANHealth(String busName) { bus = RBSICANBusRegistry.getLike(busName); } + /** Periodic function */ @Override protected void rbsiPeriodic() { + // Only log CAN health every 5 loops if ((loops++ % 5) != 0) return; + + // Get status and log var status = bus.getStatus(); Logger.recordOutput("CAN/" + bus.getName() + "/Utilization", status.BusUtilization); Logger.recordOutput("CAN/" + bus.getName() + "/TxFullCount", status.TxFullCount); diff --git a/src/main/java/frc/robot/util/TimeUtil.java b/src/main/java/frc/robot/util/TimeUtil.java index 3b8e7aa..62f3cb3 100644 --- a/src/main/java/frc/robot/util/TimeUtil.java +++ b/src/main/java/frc/robot/util/TimeUtil.java @@ -15,6 +15,7 @@ import org.littletonrobotics.junction.Logger; +/** Time utility that works for REAL, SIM, and REPLAY */ public final class TimeUtil { private TimeUtil() {} From 621ae9b73320e0d7ba90456f39957212c41a8b88 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Tue, 17 Feb 2026 18:03:59 -0700 Subject: [PATCH 21/22] Cleaning up the pose buffering more Next step: clean up the logging to remove extraneous debug statements. --- .../frc/robot/subsystems/drive/Drive.java | 81 ++++++++++--------- .../frc/robot/subsystems/vision/Vision.java | 65 +++++---------- 2 files changed, 67 insertions(+), 79 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 604d876..c6e36a5 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -92,10 +92,17 @@ public class Drive extends RBSISubsystem { new Alert("Disconnected gyro, using kinematics as fallback.", AlertType.kError); // Declare odometry and pose-related variables + // This one is package-private; used in DriveOdometry, PhoenixOdometryThread, and + // SparkOdometryThread static final Lock odometryLock = new ReentrantLock(); private SwerveDriveKinematics kinematics = new SwerveDriveKinematics(getModuleTranslations()); - private SwerveModulePosition[] lastModulePositions = - new SwerveModulePosition[4]; // For delta tracking + private SwerveModulePosition[] lastModulePositions = // For delta tracking + new SwerveModulePosition[] { + new SwerveModulePosition(), + new SwerveModulePosition(), + new SwerveModulePosition(), + new SwerveModulePosition() + }; private SwerveDrivePoseEstimator m_PoseEstimator = new SwerveDrivePoseEstimator(kinematics, Rotation2d.kZero, lastModulePositions, Pose2d.kZero); @@ -421,7 +428,7 @@ public void updateDisabledCoastState( final double minCoastTime = 0.25; // seconds -- maybe put into Constants??? final boolean pastMin = (now - disabledCoastStartTs) >= minCoastTime; - // Detect ENABLED -> DISABLED edge + // Detect ENABLED -> DISABLED edge -- set `disabledCoastUntilTs` when COAST-phase ends if (lastEnabled && !enabledNow) { disabledCoastStartTs = now; disabledCoastUntilTs = now + DrivebaseConstants.kDisabledCoastSeconds; @@ -672,9 +679,9 @@ public boolean isDisabledCoast() { return isDisabledCoast(TimeUtil.now()); } - /** Returns whether the robot was in the DISABLED_COAST state at time `now` */ - public boolean isDisabledCoast(double now) { - return DriverStation.isDisabled() && (now < disabledCoastUntilTs); + /** Returns whether the robot was in the DISABLED_COAST state at time `timestamp` */ + public boolean isDisabledCoast(double timestamp) { + return DriverStation.isDisabled() && (timestamp < disabledCoastUntilTs); } /** Returns the disabledCoastStartTs variable */ @@ -737,7 +744,7 @@ public void zeroHeading() { */ // Called by Vision via consumer.accept(TimedPose) public void addVisionMeasurement(TimedPose meas) { - Drive.odometryLock.lock(); + odometryLock.lock(); try { // Always use measurement timestamp when fusing (enabled path) final double t = meas.timestampSeconds(); @@ -751,49 +758,48 @@ public void addVisionMeasurement(TimedPose meas) { return; } - // DISABLED: - final boolean coast = isDisabledCoast(t); // your overload (timebase-consistent) + // DISABLED -- check if within "coast phase" + final boolean coast = isDisabledCoast(t); - // Optional: ignore vision briefly right after ENABLE->DISABLE (prevents “phase mismatch” at - // disable edge) + // If coasting, if (coast) { final double coastAge = t - getDisabledCoastStartTs(); - Logger.recordOutput("Vision/Dbg/disabledCoastAge", coastAge); + Logger.recordOutput("Vision/Debug/disabledCoastAge", coastAge); + // Ignore vision briefly right after ENABLE->DISABLE (prevents “phase mismatch” at disable + // edge) if (coastAge >= 0.0 && coastAge < DrivebaseConstants.kDisabledVisionIgnoreAfterDisableSec) { - Logger.recordOutput("Vision/Dbg/disabledIgnoreEarlyCoast", true); + Logger.recordOutput("Vision/Debug/disabledIgnoreEarlyCoast", true); return; } } - Logger.recordOutput("Vision/Dbg/disabledIgnoreEarlyCoast", false); + Logger.recordOutput("Vision/Debug/disabledIgnoreEarlyCoast", false); - // If we're coasting, we *avoid* init snap and we lean gentler than stationary. - // (still use the same gating so one bad frame doesn't wreck you) + // If we're coasting, avoid snapping Pose to Vision; lean gentler than stationary. final double alpha = coast - ? Math.min(DrivebaseConstants.kDisabledVisionBlendAlpha, 0.05) // gentle during coast + ? Math.min(DrivebaseConstants.kDisabledVisionBlendAlpha, 0.05) : DrivebaseConstants.kDisabledVisionBlendAlpha; // "Current" for blending target (estimator pose) final Pose2d current = m_PoseEstimator.getEstimatedPosition(); // Debug - Logger.recordOutput("Vision/Dbg/disabledCoast", coast); - Logger.recordOutput("Vision/Dbg/disabledVisionInitialized", disabledVisionInitialized); - Logger.recordOutput("Vision/Dbg/disabledVisionTs", t); + Logger.recordOutput("Vision/Debug/disabledCoast", coast); + Logger.recordOutput("Vision/Debug/disabledVisionInitialized", disabledVisionInitialized); + Logger.recordOutput("Vision/Debug/disabledVisionTs", t); Logger.recordOutput( - "Vision/Dbg/disabledVisionAge", + "Vision/Debug/disabledVisionAge", Double.isFinite(lastDisabledVisionTs) ? (t - lastDisabledVisionTs) : Double.NaN); - // Stale logic (looser = LONGER timeout) + // Check if the last while-disabled vision timestamp is stale (too old) final boolean stale = Double.isFinite(lastDisabledVisionTs) && (t - lastDisabledVisionTs) > DrivebaseConstants.kDisabledVisionStale; - Logger.recordOutput("Vision/Dbg/visionStale", stale); + Logger.recordOutput("Vision/Debug/visionStale", stale); - // If we're in coast, we intentionally *don't* init-snap. - // We also reset initialization so that once coast ends, the first good stationary frame - // snaps. + // If coasting, intentionally DO NOT snap; reset initialization so that once coast ends, the + // first good stationary frame snaps. if (coast) { disabledVisionInitialized = false; } @@ -815,20 +821,22 @@ public void addVisionMeasurement(TimedPose meas) { } Logger.recordOutput("Vision/DisabledInitSnap", false); - // Gate vs last accepted disabled vision pose (not estimator) + // Check that there is not a huge jump from the last accepted disabled vision pose final Pose2d gateRef = Double.isFinite(lastDisabledVisionTs) ? lastDisabledVisionPose : vision; - final double dTrans = gateRef.getTranslation().getDistance(vision.getTranslation()); - final double dRot = Math.abs(gateRef.getRotation().minus(vision.getRotation()).getRadians()); + final double deltaTranslation = gateRef.getTranslation().getDistance(vision.getTranslation()); + final double deltaRotation = + Math.abs(gateRef.getRotation().minus(vision.getRotation()).getRadians()); - Logger.recordOutput("Vision/Dbg/dTransFromLastVision", dTrans); - Logger.recordOutput("Vision/Dbg/dRotFromLastVision", dRot); + Logger.recordOutput("Vision/Debug/dTransFromLastVision", deltaTranslation); + Logger.recordOutput("Vision/Debug/dRotFromLastVision", deltaRotation); - // Reject only if NOT stale + // Reject large jumps only if vision measurement is not stale (large delta-T can mean large + // change in position) if (!stale - && (dTrans > DrivebaseConstants.kDisabledVisionMaxJumpM - || dRot > DrivebaseConstants.kDisabledVisionMaxJumpRad)) { + && (deltaTranslation > DrivebaseConstants.kDisabledVisionMaxJumpM + || deltaRotation > DrivebaseConstants.kDisabledVisionMaxJumpRad)) { Logger.recordOutput("Vision/DisabledReject", true); Logger.recordOutput("Vision/DisabledBlendAlphaUsed", alpha); return; @@ -839,9 +847,10 @@ public void addVisionMeasurement(TimedPose meas) { lastDisabledVisionPose = vision; lastDisabledVisionTs = t; - // Blend toward vision + // Blend toward vision -- gentle correction final Pose2d blended = current.interpolate(vision, alpha); + // Push values to pose estimator and pose buffer m_PoseEstimator.resetPosition(getHeading(), getModulePositions(), blended); markPoseReset(t); poseBufferAddSample(t, blended); @@ -850,7 +859,7 @@ public void addVisionMeasurement(TimedPose meas) { Logger.recordOutput("Vision/DisabledBlendAlphaUsed", alpha); } finally { - Drive.odometryLock.unlock(); + odometryLock.unlock(); } } diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 48e3bba..fda7b4b 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -88,7 +88,7 @@ public interface PoseMeasurementConsumer { // Variance minimum for fusing poses to prevent divide-by-zero explosions private static final double kMinVariance = 1e-12; - // Fields + // Last smoothed and fused poses -- used for debugging private Pose2d lastFusedPose = new Pose2d(); private Pose2d lastSmoothedPose = new Pose2d(); private double lastFusedTs = Double.NaN; @@ -109,7 +109,7 @@ public Vision(Drive drive, PoseMeasurementConsumer consumer, VisionIO... io) { this.lastAcceptedTsPerCam = new double[io.length]; Arrays.fill(lastAcceptedTsPerCam, Double.NEGATIVE_INFINITY); - // Log robot->camera transforms if available + // Log robot->camera transforms int n = Math.min(camConfigs.length, io.length); for (int i = 0; i < n; i++) { Logger.recordOutput("Vision/RobotToCamera" + i, camConfigs[i].robotToCamera()); @@ -131,6 +131,7 @@ protected int getPeriodPriority() { @Override public void rbsiPeriodic() { + // Debugging values boolean hasAcceptedThisLoop = false; boolean hasFusedThisLoop = false; boolean hasSmoothedThisLoop = false; @@ -138,9 +139,7 @@ public void rbsiPeriodic() { try { lastAlignDbg.reset(); - // ---------------------------------------------------------------------- - // 1) Pose reset gate (clears smoothing state, resets per-cam monotonic gates) - // ---------------------------------------------------------------------- + // Pose reset gate (clears smoothing state, resets per-cam monotonic gates) long epoch = drive.getPoseResetEpoch(); if (epoch != lastSeenPoseResetEpoch) { lastSeenPoseResetEpoch = epoch; @@ -150,15 +149,13 @@ public void rbsiPeriodic() { Logger.recordOutput("Vision/PoseGateResetFromDrive", false); } - // ---------------------------------------------------------------------- - // 2) Read camera inputs (REAL/SIM/REPLAY all go through IO inputs) - // ---------------------------------------------------------------------- + // Read camera inputs for (int i = 0; i < io.length; i++) { io[i].updateInputs(inputs[i]); Logger.processInputs("Vision/Camera" + i, inputs[i]); } - // Optional always-on “health” debug + // Always-on “health” debug -- may consider removing this Logger.recordOutput("Vision/Debug/ioLength", io.length); int totalObs = 0; for (int i = 0; i < io.length; i++) { @@ -166,13 +163,12 @@ public void rbsiPeriodic() { } Logger.recordOutput("Vision/Debug/totalObsThisLoop", totalObs); - // ---------------------------------------------------------------------- - // 3) Choose best observation per camera for THIS loop - // ---------------------------------------------------------------------- + // Choose best observation per camera for THIS loop final ArrayList perCamAccepted = new ArrayList<>(io.length); for (int cam = 0; cam < io.length; cam++) { + // Count the number of seen, accepted, and rejected poses estimates int seen = 0; int accepted = 0; int rejected = 0; @@ -184,16 +180,18 @@ public void rbsiPeriodic() { final var obsArr = inputs[cam].poseObservations; if (obsArr == null) { + // Log zeros and move along if we ain't seen nuthin' Logger.recordOutput("Vision/Camera" + cam + "/ObsSeen", 0); Logger.recordOutput("Vision/Camera" + cam + "/ObsAccepted", 0); Logger.recordOutput("Vision/Camera" + cam + "/ObsRejected", 0); continue; } + // Loop over pose observations; move along if gating or pose-construction fail for (var obs : obsArr) { seen++; - GateResult gate = passesHardGatesAndYawGate(cam, obs); + GateResult gate = passesScrutiny(cam, obs); Logger.recordOutput("Vision/Camera" + cam + "/GateFail", gate.reason); if (!gate.accepted) { rejected++; @@ -206,7 +204,7 @@ public void rbsiPeriodic() { continue; } - // Prefer “best” by your scoring function + // Compare this estimate to current "best" -- score current estimate using `isBetter()` if (best == null || isBetter(built.estimate, best)) { best = built.estimate; bestTrustScale = built.trustScale; @@ -215,11 +213,13 @@ public void rbsiPeriodic() { } } + // Accept the "best" pose, if extant if (best != null) { accepted++; lastAcceptedTsPerCam[cam] = best.timestampSeconds(); perCamAccepted.add(best); + // Log everything about the accepted pose Logger.recordOutput("Vision/Camera" + cam + "/InjectedPose2d", best.pose()); Logger.recordOutput( "Vision/Camera" + cam + "/InjectedTimestamp", best.timestampSeconds()); @@ -244,9 +244,8 @@ public void rbsiPeriodic() { } hasAcceptedThisLoop = true; - // ---------------------------------------------------------------------- - // 4) Fuse all accepted cams at the newest timestamp among them - // ---------------------------------------------------------------------- + // ===== + // Fuse all accepted cams at the newest timestamp among them final double tFusion = perCamAccepted.stream().mapToDouble(e -> e.timestampSeconds()).max().orElse(Double.NaN); if (!Double.isFinite(tFusion)) return; @@ -255,39 +254,25 @@ public void rbsiPeriodic() { if (fused == null) return; hasFusedThisLoop = true; - // ---------------------------------------------------------------------- - // 5) Smooth by fusing recent fused estimates aligned to tFusion - // ---------------------------------------------------------------------- + // ===== + // Smooth by fusing recent fused estimates aligned to tFusion pushFused(fused); final TimedPose smoothed = smoothAtTime(tFusion); if (smoothed == null) return; hasSmoothedThisLoop = true; - // ---------------------------------------------------------------------- - // 6) Update caches (ONLY HERE) + inject to drive - // ---------------------------------------------------------------------- + // Update caches & inject to drive lastFusedPose = fused.pose(); lastSmoothedPose = smoothed.pose(); lastFusedTs = tFusion; lastFusedValid = true; lastSmoothedValid = true; - Logger.recordOutput("OdometryReplay/PreInjectRobotX", drive.getPose().getX()); - Logger.recordOutput("OdometryReplay/PreInjectRobotY", drive.getPose().getY()); - consumer.accept(smoothed); - Logger.recordOutput("OdometryReplay/PostInjectRobotX", drive.getPose().getX()); - Logger.recordOutput("OdometryReplay/PostInjectRobotY", drive.getPose().getY()); - - // If you want, you can feed debug values from inside timeAlignPose(...) via fields, - // but leaving the plumbing as-is since you’re already logging inside helpers. - } finally { - // ---------------------------------------------------------------------- - // 7) “Ultra-clean” logging: one place, every loop, replay-safe - // ---------------------------------------------------------------------- + // Log everything on our way out of this function // Always-present “outputs” Logger.recordOutput("Vision/FusedPose", lastFusedPose); @@ -300,12 +285,6 @@ public void rbsiPeriodic() { Logger.recordOutput("Vision/HasAcceptedThisLoop", hasAcceptedThisLoop); Logger.recordOutput("Vision/HasFusedThisLoop", hasFusedThisLoop); Logger.recordOutput("Vision/HasSmoothedThisLoop", hasSmoothedThisLoop); - - // Debug keys (exist even if not touched) - Logger.recordOutput("Vision/Debug/alignDt", lastAlignDbg.alignDt); - Logger.recordOutput("Vision/Debug/deltaTranslation", lastAlignDbg.deltaTranslation); - Logger.recordOutput("Vision/Debug/deltaRotation", lastAlignDbg.deltaRotation); - Logger.recordOutput("Vision/Debug/alignFinite", lastAlignDbg.alignFinite); } } @@ -385,7 +364,7 @@ private static final class GateResult { * @param cam Camera index * @param obs PoseObservation */ - private GateResult passesHardGatesAndYawGate(int cam, VisionIO.PoseObservation obs) { + private GateResult passesScrutiny(int cam, VisionIO.PoseObservation obs) { final double ts = obs.timestamp(); // Monotonic per-camera time @@ -411,7 +390,7 @@ private GateResult passesHardGatesAndYawGate(int cam, VisionIO.PoseObservation o if (p.getY() < 0.0 || p.getY() > FieldConstants.aprilTagLayout.getFieldWidth()) return new GateResult(false, "out of bounds field Y"); - // Optional yaw gate: only meaningful for single-tag + // Yaw gate; only meaningful for single-tag if (enableSingleTagYawGate && obs.tagCount() == 1) { OptionalDouble maxYaw = drive.getMaxAbsYawRateRadPerSec(ts - yawGateLookbackSec, ts); if (maxYaw.isPresent() && maxYaw.getAsDouble() > yawGateLimitRadPerSec) { From fac0fba49cd8a35b658c7cada1f428c62d688090 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Thu, 19 Feb 2026 18:24:42 -0700 Subject: [PATCH 22/22] Clean logging --- src/main/java/frc/robot/Constants.java | 42 +++++++++---------- src/main/java/frc/robot/Robot.java | 6 +-- .../accelerometer/Accelerometer.java | 2 +- .../robot/subsystems/drive/DriveOdometry.java | 21 +--------- .../frc/robot/subsystems/imu/ImuIOSim.java | 2 +- .../java/frc/robot/util/RBSISubsystem.java | 2 +- .../java/frc/robot/util/VirtualSubsystem.java | 3 +- 7 files changed, 31 insertions(+), 47 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 1b55642..1f552a6 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -74,9 +74,9 @@ public final class Constants { // under strict caveat emptor -- and submit any error and bugfixes // via GitHub issues. private static SwerveType swerveType = SwerveType.PHOENIX6; // PHOENIX6, YAGSL - private static CTREPro phoenixPro = CTREPro.UNLICENSED; // LICENSED, UNLICENSED + private static CTREPro phoenixPro = CTREPro.LICENSED; // LICENSED, UNLICENSED private static AutoType autoType = AutoType.MANUAL; // MANUAL, PATHPLANNER, CHOREO - private static VisionType visionType = VisionType.NONE; // PHOTON, LIMELIGHT, NONE + private static VisionType visionType = VisionType.PHOTON; // PHOTON, LIMELIGHT, NONE /** Enumerate the robot types (name your robots here) */ public static enum RobotType { @@ -168,7 +168,7 @@ public static final class PowerConstants { /************************************************************************* */ /** List of Robot CAN Busses ********************************************* */ public static final class CANBuses { - public static final String RIO = ""; + public static final String RIO = "rio"; public static final String DRIVE = "DriveTrain"; public static final String[] ALL = {RIO, DRIVE}; @@ -487,7 +487,7 @@ public record CameraConfig( // Example Cameras are mounted in the back corners, 18" up from the floor, facing sideways public static final CameraConfig[] ALL = { new CameraConfig( - "camera_0", + "Photon_BW7", new Transform3d( Inches.of(-13.0), Inches.of(13.0), @@ -504,23 +504,23 @@ public record CameraConfig( } }), // - new CameraConfig( - "camera_1", - new Transform3d( - Inches.of(-13.0), - Inches.of(-13.0), - Inches.of(12.0), - new Rotation3d(0.0, 0.0, -Math.PI / 2)), - 1.0, - new SimCameraProperties() { - { - setCalibration(1280, 800, Rotation2d.fromDegrees(120)); - setCalibError(0.25, 0.08); - setFPS(30); - setAvgLatencyMs(20); - setLatencyStdDevMs(5); - } - }), + // new CameraConfig( + // "camera_1", + // new Transform3d( + // Inches.of(-13.0), + // Inches.of(-13.0), + // Inches.of(12.0), + // new Rotation3d(0.0, 0.0, -Math.PI / 2)), + // 1.0, + // new SimCameraProperties() { + // { + // setCalibration(1280, 800, Rotation2d.fromDegrees(120)); + // setCalibError(0.25, 0.08); + // setFPS(30); + // setAvgLatencyMs(20); + // setLatencyStdDevMs(5); + // } + // }), // ... And more, if needed }; diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 5a1e15a..0dbae5e 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -147,9 +147,9 @@ public void robotPeriodic() { } final long t4 = System.nanoTime(); - Logger.recordOutput("Loop/RobotPeriodic_ms", (t4 - t0) / 1e6); - Logger.recordOutput("Loop/Virtual_ms", (t2 - t1) / 1e6); - Logger.recordOutput("Loop/Scheduler_ms", (t3 - t2) / 1e6); + Logger.recordOutput("LogPeriodic/CodeLoop/RobotPeriodicMS", (t4 - t0) / 1e6); + Logger.recordOutput("LogPeriodic/CodeLoop/VirtualMS", (t2 - t1) / 1e6); + Logger.recordOutput("LogPeriodic/CodeLoop/SchedulerMS", (t3 - t2) / 1e6); } /** This function is called once when the robot is disabled. */ diff --git a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java index 2fb0361..e6ebe08 100644 --- a/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java +++ b/src/main/java/frc/robot/subsystems/accelerometer/Accelerometer.java @@ -96,7 +96,7 @@ public void rbsiPeriodic() { final double[] ts = imuInputs.odometryYawTimestamps; if (ts.length > 0) { - Logger.recordOutput("IMU/OdometryLatencySec", TimeUtil.now() - ts[ts.length - 1]); + Logger.recordOutput("Odometry/IMULatencySec", TimeUtil.now() - ts[ts.length - 1]); } } } diff --git a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java index aff93c2..7dc4925 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveOdometry.java @@ -17,7 +17,6 @@ package frc.robot.subsystems.drive; -import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.SwerveModulePosition; import edu.wpi.first.wpilibj.DriverStation; @@ -35,8 +34,6 @@ public final class DriveOdometry extends VirtualSubsystem { private final Imu imu; private final Module[] modules; - private long writeNumber = 0L; - // Per-cycle cached objects (to avoid repeated allocations) private final SwerveModulePosition[] odomPositions = new SwerveModulePosition[4]; @@ -64,7 +61,6 @@ protected int getPeriodPriority() { /** Periodic function to read inputs */ @Override public void rbsiPeriodic() { - Logger.recordOutput("Odometry/Debug/alive", true); Drive.odometryLock.lock(); try { @@ -118,7 +114,6 @@ public void rbsiPeriodic() { // keep pose buffer alive with the *current estimator pose* drive.poseBufferAddSample(now, drive.getPose()); - Logger.recordOutput("Drive/Pose", drive.getPose()); drive.setGyroDisconnectedAlert(!imuInputs.connected); return; } @@ -262,23 +257,11 @@ public void rbsiPeriodic() { drive.poseBufferAddSample(t, drive.getPose()); } - Logger.recordOutput("Drive/Pose", drive.getPose()); drive.setGyroDisconnectedAlert(!imuInputs.connected); } finally { - final Pose2d pose = drive.getPose(); - final double x = pose.getX(); - final double y = pose.getY(); - final double th = pose.getRotation().getRadians(); - - Logger.recordOutput("OdometryReplay/Debug/wroteRobotPose", ++writeNumber); - Logger.recordOutput("OdometryReplay/Debug/xFinite", Double.isFinite(x)); - Logger.recordOutput("OdometryReplay/Debug/yFinite", Double.isFinite(y)); - Logger.recordOutput("OdometryReplay/Debug/thFinite", Double.isFinite(th)); - - Logger.recordOutput("OdometryReplay/RobotX", x); - Logger.recordOutput("OdometryReplay/RobotY", y); - Logger.recordOutput("OdometryReplay/RobotThetaRad", th); + + Logger.recordOutput("Odometry/Robot", drive.getPose()); Drive.odometryLock.unlock(); } diff --git a/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java b/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java index 102b60e..1bf04a7 100644 --- a/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java +++ b/src/main/java/frc/robot/subsystems/imu/ImuIOSim.java @@ -94,7 +94,7 @@ public void updateInputs(ImuIOInputs inputs) { inputs.odometryYawTimestamps = tsOut; inputs.odometryYawPositionsRad = yawOut; - // Optional: SIM logging (primitive-friendly) + // SIM logging Logger.recordOutput("IMU/YawRad", yawRad); Logger.recordOutput("IMU/YawDeg", Units.radiansToDegrees(yawRad)); Logger.recordOutput("IMU/YawRateDps", Units.radiansToDegrees(yawRateRadPerSec)); diff --git a/src/main/java/frc/robot/util/RBSISubsystem.java b/src/main/java/frc/robot/util/RBSISubsystem.java index cb13520..b90752f 100644 --- a/src/main/java/frc/robot/util/RBSISubsystem.java +++ b/src/main/java/frc/robot/util/RBSISubsystem.java @@ -39,7 +39,7 @@ public final void periodic() { long start = System.nanoTime(); rbsiPeriodic(); // Log the timing for this subsystem - Logger.recordOutput("Loop/Mech/" + name + "_ms", (System.nanoTime() - start) / 1e6); + Logger.recordOutput("LogPeriodic/Subsystem/" + name + "MS", (System.nanoTime() - start) / 1e6); } /** Subclasses must implement this instead of periodic(). */ diff --git a/src/main/java/frc/robot/util/VirtualSubsystem.java b/src/main/java/frc/robot/util/VirtualSubsystem.java index 36ece7b..bb99b7e 100644 --- a/src/main/java/frc/robot/util/VirtualSubsystem.java +++ b/src/main/java/frc/robot/util/VirtualSubsystem.java @@ -73,7 +73,8 @@ public final void periodic() { long start = System.nanoTime(); rbsiPeriodic(); // Log the timing for this subsystem - Logger.recordOutput("Loop/Virtual/" + name + "_ms", (System.nanoTime() - start) / 1e6); + Logger.recordOutput( + "LogPeriodic/VirtualSubsystem/" + name + "MS", (System.nanoTime() - start) / 1e6); } /** Subclasses must implement this instead of periodic(). */

m$k`eXw@Hvk0$(<)mKM)74PbY zg1*2uEMdk0g8}B|#Ia;9$nn}H5+(f61Z1ov6X-*ybhQ6Z9N&Zbn&|hvs4mBIix!&x z^bClzQphJ}NGs}Y*TAzLzDj=i)P!=PVGZsI1CYWDRFGnxnWl)XLoKojfL%vc7(U45 zO#M89`7gHxOSal#?XRNzSNGy~JTqw@tez)86Z?vDDp3!g$^F5D;z*}AEx#|EzY6YA z`%@3Wpl62k)zIfHr{!_oVKAH1myHUKbxw1-x69mW)~bJwx;!9#BG9m09rlwls&Bx? zMR$-V)_5)2MADnv;p;=*z+GaziMZSHpwt6}wgf-$iiB=eXkI9eplZX5x6qLlWnS~? zBip8B2Mx$;B?}rtZe1q9V$NRPZmxpVlnjMr#XPX_An!rQM2O zF0*X}aA#|4YYR?V#Z-#GGkHD4d8dZfwIAqib`iJp4?#Ro2Ar6G!?vDY&fO7m)|h#o z_GOTdwrn(ARrH4K^pH()WQ6^v%f5%s@4crL7aIgbT1vh0VZ#qpCf(OPfrOeKpRS%7 zuRS7>ByheUK_72EJnH^cOYXw0mz6AO^Xjjz9sxd}zzsmhJmA8zoJ#m5+R2#%>WS-f-RimR(1y?AGX?Jf{qiYd+`s!?}nLfFIJ9&Cwe% zg2d#hXL!`V+ z#B7d4V{HY0ec*TQAb#tEx5zIcvvvFKVCg$~_QD#4wgU#j*L-Ij+NklW9u3IoyxDn_ z^byhd{Z=N@mwqo?xWXqOWPC(rk9G)6Ak`nV#DnnM!!Z0A3?jocrlbBG?VfmneTKz0&g%^pf&oi zJqDogv9v&1exI7cTH<+9r7H{;uifND!EX-oK%f)6&-uT|y|`D#IK&Gcq)nBkf? zZEW&pYqNPu5B^B&G<(n;ly_x<)tzh0d|-_Gp!&br3EKiUcN zAL&_ggALv8?!&(`&j51OB8X!egsU-Byl|4=wI8$bDy6)S^5&d$6(Rbq`tYQ*#-!WS zLhx?qD7d4ym{d)}zyUKR!Yw$Wy^?OfO27E-nP@3cQ-A2tb!Vr@=f1tGZ8k9}QGO2A zm>6D#LicMB;{>*1f$ksm@ftZiPm4Bq&Jzaf#<=k=!w0QY84a>NDQPqgWl8hGHjp`_ z4x<6RayHakFP_U;S}p8mIVexMZ?jWfYH9lb7mv6J^~>PwZT$~zdyQw+yV*Bu85Ra5 zZ`QN?=l#zvt(gZZ`wXU0P0c@E>My`o;qp@X6b)8n`E(ip@?vksF6g;kFjXb;B(d?xQSKja$SB-gWZx4Vizv zlJ?5(?;6;jmz}OD(j}HOhtSDo_-)9!xz4?vuiU+`EUvT)q1tBU-3=o+o^f$4R=+X$ z?CZ1qOj@qR@@6Z7mv>ViZjec#VI%G^x9#O^(7n+;p`B63DEZ62+^3WZw`554d2J;d ziI8-y2x{Q9$nLL`?Gdk0*Qyzn1%3UhzHids_7HwsLmZU4G$?Q?RW$yr_l1O!|BdC_!ZsYRr^?QRO-8upoy?E zbB%ZcAuGHmgrq_EChzGMy|d9Dw?0^i*1S&d`KzWsK%ptPhpQ7(D69yxRVf=#k?^lJ zocTo{UbBDJ)@OpNpn^$Mc^)dex`hy>{*+hvgW39sX2#*`>$lWzIGF+27iHDrtW$Om zi4*I@RA=zV{;VrHIeFC8R*Y0spdCJxxjc1^8Om|;B$gO!!-ZA5tP4MVLRRF(SDLQ^ zal$cJ`Yld?_tAPnluN%Gbiz!Zq*Y9pNu<3*e)lnKA>EFO{)C!u)lIr>P|gE3>=7dwBh9kxq(KL$YU9qjRz%=VLZKL1U&6`Q*2P$tX*bdwB={>=Q#xApTK% z9CIGYA#;|^^463H5p${s%P4DEu1>Byq$`F8{xEHNul(1;H3eX;nBqynrjZJZF&q8q zj2rNg7SAy{Qen`NhFb4&K&Yzv8)aF%jkP}Xyj4Fn_N9f;w#gC}ws9z|xLfO>-+h}Z zyvS}u?NQTr)o8AFf>0HHRzzN!QzVxZY+nnty%OF6Mz>4MKJhDt^yq~mS`$kSQ-dKS zz&mzvala;*&1F%0(BVY)6*WZB@|P+H`OKJ)14-J^HQ6Vp5!J%Z(q#qM2D-WRR&BIw z5wm%+nfM)aRy18`&wgpLgAd!-Os&$wO;T^v8#NrTRneBhe>708WTUG(r=RWr=5d$oM0Puxi;Xj>%O?mj!T4fGkNud|G_Q6 z4wY_o$ZfDMKwMboX9uzDPT=-7=T4g4M}n!89ho{Hok>Gf@JeN19I&qrI@oWDMT?@8^Sl{@;Y zUy1=n0{mrA==2J(;TklXc29Z72?I7vO8i<$2gp$obyH-AiLI8oIgB&f!oP#QA|uag zbo>1ySJdyR2=Yor$Q&?m$!;N4zedk2zY7R}`49qp=GL9TTiS0V^837e>W3y7D4#}X z?b&Ms`q2-&U)gs*`OFHKzIvwox~aN*=yFP5UqAJ-3WPRlZ%od>W0}KmUn$(EA>@|- z?LBfTH9*ye`|!a8#fC}v=_x6flv|)Y9a(*w9 zyMIG)fYVNWaQ2{%Td|3^iFA*6yh#288*-(vINn+DND+AYmOd1@Est%hFCS^~s~EbO zp>%_Bj;>=o_ijgDuAY{%w(jEW%uzf$gKc>FpBN7<1YSAaSWRo-^5add+&)^LSwkRS z0Us4KdrzdfZ-pUW_yeJ&9hE+bLZ;do8!6rmPBl@L-HoN>yz{=|6N!m0+pvx24Ia~_ z@YKz;)fO^BRKRp$wZXQ{n@jl$Xwj+h?-bB#9;%DEuQgVzVCrMg;~q{q$7&!o%=JgdrjVp4YV1_F}8iLQyZ4F&Bc zhF9y;!SjDoDY2mWV10nvRrX4!j$Zbg$mSQs9l~Wv+x@#*oyI>A)4syCI5n@Y z2wJ!S^~kVtVM$v3=0_G<>#My<$z~_#$N`jStJm$vGH&OxmE%Y5Fv&@?dYDZ|Z(FT! z{Cf*_?(JU`adAHMnp)2G-3l#V1`Fuo^wun}Bek|O%Zf3?u~TB~Uc(+F=I^Ja!nAD+ zc;^ML)}|6`zcQ9mtf6#J+bvD!^*!}Eu*Q$ycY~pMb9oP)?w0Mu=VK;olmim~-UmQw zH&afJv#v*A5$!Gif{bsd`yDRhTm5=ts$WJQ+0O~PuT4*CTdnEoP)B02XRzvPMeEgt z%05HZn-c^0xR{)!ov~rUPK4BU!e*SC1@*10ef)lPl53nyDQUt)v|3u`_1Is;A7OuO zeT%gVc}3a+iiCri=QF zk{mJ6f@psg+sAFc97jl(6>AjkY2^kU+TYsF+OD(J_LfCdK~7iuz0W6ZGBN+N*#95v z051Y&KEM89oScQuoyK3c=e~yqHZ}daWGJyO;>hbZ{j>H9kX3oiata zAhPTmCVtH|weEE=SI60iJ?O|Hk>TJ(g)JYbPAJJzU0D|@xyusP1 z3`gRKAy29LS#Hb{`U(9B0bScd#-5RhY5dT496tS}@;zLbcE#E+=1JmWIh@ZG1onUh zN|jlCFyuMi5S2akcrXw z2XX%V-Cd;C@z~@RR20uTX0VzaYEPD!qQmi6Gy4#Zbj!!>maAHN06qY6TDj+%=gW#3Vm6rNavYWSNEh{r z6R%LNvx=`?041e}FI4M2m~M{bOrTkoy{YA*J-1?(+-ya8Y0h3H z;K8nccW?P=^4k!ISI&A@d})?+O?2tF%!;zF+&dj^*fbi#lxU)@pJu$=arrVsDB0|J z5@P@=(C6=ky7+93#dby;VzAH;Pj>xRsMzCFCEB)hZ%c!mtbpfa&C_wiLO{D?xABjc z<&abRz~_ze8UI|BhOOQ^c$5$$Mg6qrKb?(BO@T8m-^Xw)dQ}>swo_~VqGGvEwl-3) z^;tpAY-znO1=OB$Ak>N%EtYGBeY~_#a6>}BM0Hf%A+Rm@L=UT)MPG=FxY9Nz_y*K8_ zZsvo?46oHXSPQjDD`<=pk}0H9XbJXwIq`X|*lX&;i@4gH6W0t!GGO0NXL+{zQ|O@Y zGmJ?DBR(OiN`wB*WRKX|7lra;j;pMBD&u6adN=`B6VMBWJnm}rU9t7fQ7k{n*qsHq z0abE3REUw8>~2@W#&#w?TtGiKp0nTfgu|I&knxTSdTze;)2F$bO5@C|Y$BEFRsgTx zA?&)U-H^Uuqr9DTFJ!80I&K&54i`#X|L^6|4trs9Z`H?fi{I#v6qIWd06v;Z*4YU- zup9!}L4^4t!=D{fobky_81DfF+Z)TWH*w$)pF^7Mbd+ZW)=;KB2I4Q%1Tghxx4i>o zPq1$@T1B8J>2gTVc?3m3Joc*N`ukqG$5V`)@R9_H}56a>!gP^$>Npa4jDO45N4V{xJ<*#l;hNS#H zjm=|<>->=!h}sPcsox48i_Y;=u7^dvrQ#Dwe8*e+O++>dOqE_l# zUPJIQp4cXi*Mp6}*Wcw5hoGt3XaPaq=4S<%yarYSmK+x<-N~W@ldrA$Q3nrwYArKO z#DIv8#(3Z!R2!_NEbwLYiJ<3m4O;NWn zxA95$ZP=~^bRx4!ak5Dk(Nu|k)1uAt>LV2;l|=%E%zO1hrD`g3n$Na7(wh64=*KB9 zxBxs-CL0@$7ep9zWF(&EgUToM*#CqAy*%w=mSsGNyhimpU<*cWBO8Tz_2kJ$T#I)SZV)6T=6WRz#G$tb9bn=OX~c-d z46(zgT0-dJpN-(kno@IyY_DL+sVjmjiz_JVX-q4WtWWehCFS<3#-Mx;)5+?rN3^%F zd$(liZru^TV=9m7i2~MV)IrgIa$yEna0qqaxi`m7Z?j6j&?;y`mzd>$hF5;i(_f~Z z+0;MB^; z))-{i@!MciuP@gnqh|wH=;o(_N#=}VS6*>8^HhXZE$QgOMsm*f8yI?14msi=oyQqi zD%QsjpZV*`9D;Gc|F<0Lt9jx;24Z2MXrUYc`qdlL?H zQm`zXX|d#7i-PCwlUAw`2)&^);t=%~z&A&eMHFGroYDK`4&I<$$^t+c? zH}mE!zPc)(H{Or>9RI&ZePvm2NI**H>VWrV5PDSL>R;X6vdnioNGz$#?--*M*LM|9OoSC=mDcq-XzRR-lZPE`1e#)1?O6dcJ3 zLQNdiM9rw<(aWm1s~S?2D4&*_ccvj$A1uD^aLUi>%e{ruWp@KLb98O<;G}XX1;9N= z5Of-M(bvo@X_~IKn^VZf}9`BR9A1JG5hn1 zJl(++l1g)MnrI?H3@x#eun#g9_HvdYV6y@`AMw+3$tVXL-L4$fH|5>F$fhfCOce%8 zvq~IDPl<1>+3Ic&_E`UaLC?E+!V|pD#MIn zCcu>ifP4Ut#*@*??5GXSHA2b*!WXY_v!71U0VIpYe1WtwR#cb{MR3!y92uSD*ZGe4 zrH7V8ynm}muk--OjRE zf|afguHTQ3gsxNnbmK1{5rgykJ!gSrx^YL@Ml{=+zbgA*e7$!x+X4SJoCKv}b=b32 z)QnNo4vN;+){07~T2<7DJyNqRrE0_;wW>zc-lAI67Q|jfjo6zQZ|?hd-t(UGp6B=c zpFh4Q=Oo|jbIruD`$&0y%P~^>1wq=~i;Etg>BzPyxDS{WYQ9k#b%(_}L56L>=%UL$ z;VxgPutaDlUSFq6%E@d2A!n;p{iz{_b}Z+sLP25cBOTVBYJGX*f93*{(-H2y^DTby$!p6ld81XSGweaHQ(QXedb$HWpLuuD{g!AftAa& zT;Y69ukcENZYq8~>td8}6JKoJ8m=jbt~iqLA1GnVt$J*eAgN$-sCtI~R&Ayiv6~kj zI`LeyXv}3ywaT?bV<<;kgStwkoJvW_R8Wb}AD3`pNGX(GbgCM+|J3C<4u+F@6PZ`? zBe7RF7*lGhQSd+&eVA`~6a{*N41A{YC%KRS277QERkXS|ti`G$0J%hz@(LhzdUkw6 zMrN!b9w{p8w9LdqewZZD+|&l#y>{pl-`YLfxv?tt<7~t9X4PtAUyn8=z-J`~^48ae zj4-4V@^PTNT==tH{^Cpl=q}PsEQi2+d%BW5<@=N{hkoOtoSl6kh)KWuP76MC+1J`F zCeSTQ@kkFf*fTgcx4gfBvKatIi2RJgjzY2muAeMdZY4l;L_nELx{aN){0x59)?jg$ zW{mIIvQ0~N`EcM91@v^VWjA>CLWfr9i%7#$q?f~;7MlBaHE_Aa6zY(gn0zqs%xvZR zU-Z$c)CS12{t&8(x)xV$0~Exn$2Mn399_{sqb3xB8?~zsS_vivGah zB9Hu2^VI?+N(qkAsKo?ug0S)#hrz%AD)K57w=oJeCuGW&Dy8s;*|{BD;sJ$NkM9o| zQG=$zYLvdC^a}=@AOs;ge5JRQMNW5dP^d!Kdb!{We0z4oBoz%%X|&4(`k85%BC-o{ zwI$H^6xhQW-)k)OtF(S)>4Dev7%nBxeD7F=`12C$VxlSLx2=tKL3aXohA3xp3u8|w zyEfJKsZc{4$8*Og4PDAmLNha@aSBz)8Gft7#(B}ikwAXdGri~w(a`e!uu(O2x~Jjo z%I@@e>bNJ$iN4imJa9YhO6`$v?$7^%0(^NbRbcLOYyQfsQ3Y6GO`q`rTUG)j2m|C*jFFA_3Uq4y3R;fPS4v9PSnyCJWk zGHS#eRq!b<%}&voD7kih9lI8zN@L+YhVZJo#r%O3lGi;6Z(MR)ID*k}mKG{KD8o z#U{(29-v!a-iM6{AeLuCZXzNU_ zr_PV9ru)X_6DyUo-5t#bYVt}sV5|?f`nj9^?gTF9o>MUDbV586A#yag;qq&_$86@1 zqlqbXEm%wX&dx&nPp9rKkH7gC{o^)8?N(l9Os+~zVQtK5oDQn)2q9jjsN%De{Y!87 zYfY1a>kDwH{l)q^M?Xu7UFLqjFY#hKxYY;QdwJhur7G|AqpUGu6h3SB@@Em&z?6={lVeyGvVV6dl5#jd>)b3t zrq8dN*JF6FmHu2oH4xdWD|H}Wp_2wDG}ASkTjPF)j_r0oGAE}Jo%3^CA7Q*0g*w?z0dUZEGI>O-Gl>yUkdbul(x(s0WE!V$xfpv=f=#{gc)*=Y?c^;x z{h&s1ScAKn`0l+*MRKkXbvyH3PwF-2LjA(}`Va0Pr)$s^?bxqLV$0v2O>&QN@0p@- zI}hhE`0uTXnJy5WrgD9YQQDsX-$$J^(+{`?BHQ-jDA9Pv?0XD`MXMz$Yke8NpA?B7 zdI;Xs?rbwoY~@kY?1(JzQH5~XrCZCng9rc2=+VWMmv4k_BTEiSXD2qc0yjflh@?OD z^b-zYKr$_0FiP0$q@8U}4v@vC92(?)SNs})nZD-Txo0hT*$$NWo=g^~D!{?O4Z_R+ zv)bpV?*(iAyj#$0PH|phyaMp8J{RcHHk5c+^78jCO;k^JPrGN&^(Uz-^QQBkQLOZE zY9-|yWyt(>C$r@7ys4euoWA_XU;Aboiptw`-lvaNCcr11+AG%pIZ?x)lZm-0(Q`ORM3VkI1PN(#= zOV&nLr8|c-u#1}VSKy#tsLs272W7VNItxe&kA?E^u?M{~9{PH|*J8 z4RiImW+pYeDog)oO1r4VX zIvzL2i62S7!P&$@X#VfxU9`bm2Od=4X7p{5D;cC{K>*=T8|ra z9hCegG}U&93!|XSwH9TI)Bm|4RUgy)RAx;y@D$nSLNweT#S-cWiC=K9h((Ucb-aq^ zE;7uo|Kz3dwWeO{%h7MB&C~063kb{1TRyDYaJs&eB-$wL)`9U?U3TM{sVE%UdURZ- z5bQ)+7JRnZKzv@0A``QsEEV)06#jhhnJn;K;a0c~DuANUr2;KRCZhar`KzADJRI<^ zA>UTI8?&p{zs3f5g(`H~2ybBsGi%T`SSw3aEhKv4P>;%)vGI5q zgc`NyQ=r6}W6MplA%N2c*=>-WSx7A!Wtyev7m~Ojy>$cMScp)zHc%{xAr@E_Q%nL9 zs=6+tZ0F*oMA+RSJog)2c#(98_44DGh`X(CL<`#}8DDrvszvy13r2is?;gIfeTV$W z4+UX?35Tz69O<-Qz@;s-dwuH>Y@?XmnQu!dAkj=7h%lF6edSF`Fi<^Qjh-jl zcGPD{m)^P}A7tKPa5vHi!;Hdsfe%CC^H2Z&ro&Q{ipq-(ihX&;?FhbToQG>;uY`^* z(rU~1Xm);IY7w*RvBOG4g*gsAJZ0ja^A6lQFnVc6&*QxtN8jAH&5*X{CW6sn)FAA$1}8~1eb z`zjWUul1yY3<}uM=pEiV!R(TxNKesYhN0n#0#)I)Bq_+)0`GhuAP?T;V}$()%f1+j z4SIf-PZP9k8kA4`G916xZ zmZ4+0RD`hFSN|$!0F?L_nL4kcuc2LHu@We(j-!R=L?4Wfdt` zDaD2UkyxOdt-pPp!?hhi-y^>Oli0z1E;Ls@=mXQo#3C1$jJDw{&9})#9gJNOx3OG zfBCV_4vJ0uN}e=}y=e!ctsSFa%QdNE%Kd4?pGdJ&oVebpW<UH&4i zpQ5dEw!3DkMkr{pt(57uz`OW*>E_!v4@!E9^=M&##iV)26QZh+@qv=1t2pR!GroE` zx^}E)=B%qnJkaE*n`e<{`-m6iFg(mnycfJjXxKda2j&`LUw#9_^AV@^p2=}tW%RmY zc=u~Gar}+~O4jR3^42)oshUa8#UxYx^~W7%DT2bwR;g~ywomaAvSsl>ClAWdE&+nS z49aNp^9|TP=*Ys)K3Hh2oPTsV`}z&C=VQ4=KUlwU2i_Ck-+=2@q~k8o>(FxwoRsaW zI~M{U@}J$^mKU?UIr0B?0T43+FNJtK1s^U7T%`4?ee|?SNF|sr+vl6_e?Pb}YP9ja z!ZbhjHJe9o=QDR{^Etvvg2bC1zRdC@cGp}=wOU-G?`|z=e5o%UI^gzy@C5#kOwiKwY z9Y_(2`and@l@}OK;?OQwFXbI4Q6%g|DoF1=b5I`kcREyiohf_&TM)(NAB#iKWBv?! zI|0i;LqU}jkiG=hJleVxxMlP66g4i-drFmG#KchgeCp=;^Tm+hFCC$K67~9@xn3mU z%w)v$uTftymOoRD+p?CX&!EtCo}0Utj_eTVcJ;PMv*37b#me@!dnT646B2XONcz3= zd_#ExkEh!}a~w(8)w4pa=!3S%CESajXWVrdm&J_=vsXvAc05qe&vlys>9>AL`P3f( z>*?2ih|AGKKTe|ZHgY1VI9LGg=Ah{Z7`_)!4cND;fFBM&fz037FKy(=4bcFM+@4jo zLZ=h0-*wkjvw)+WC>KJ%rO4}wkTCf|Ja6GC0Yn8#xo9IQGkOo zZ%}l;=7)Y>dsTz|9(%=UmHBL7l(vB4>fExp6E|UyLp#g72Jmh4xhRO#*ksp7aYk&ml9EzK9;PuvCpGy~ zK9-2vp>Rn&4Crapkrvk1cL?&d-1&XyFW9VmdGY7Y+REfg18s?PE2Wi3XA8U2}OecY{@Sk#x zVe-vE0%urczs}4J2&E`l1)Llj*n6jzIJEu+a&M3cVUoO}k(1l*x0!Py=ilI;Nx4YW z+L+iVgoPi4=cohj#{M{4xo8)xq8o1~SIe?=@q~C~s%JId%nbbD}0+X zaQ*KWBKaDa2hz?UZQM&OmEnAndnn{!|8my|o^hl+#D2SMa-srcqm!KDh*Lwj}<@{9oBrh-?Q0V9hg^7y9T zunSMFs-}5scMwDiUz~$|eN4Q|9z^rbCIRMgFzgreA+RQ5EQF3+sT3C|n%Fw+Yb0{$ zNb46@JGc=ExL@i(^!+VdwPDJ?2CfqIxdLEA6+tY_KN{F zM?g``ZX%89P(S08@?Ur_QPX#PYQ|c(T>eug#NA*Ot(pXgDIxpvP(AjaG=`4K&zcK$ za8n)$Qt2FgVg3trkIA9vxHaplIKNePbH$n4%HCOO7f@-1aUcN|%1Vs~$eq@Y=|HFohVA1IG?CF#MKZZZ;p{JnTHAT?t@px|cC1 zt;Zb%+cEuHBtV~IPNjyg7H)dtfy)oTz6V)lDf&v13&7x+y2R6gU^prSPLco++m{Df zm&5>;Ypj-B(m3baxkDrK-Y52#kQdGs=z<6t49-*vpjmT`^Sxy`&|f-?%MqF z!+ON(G&2X7C}cRO>}YAaZKlzWGpwmWyOjs;hO?*ue>@pD^ILo(J2F+)uUu<=CMR5# zzUC;kr)_?E3*ayZ!XZB~=Y6+zQf&mj(-hOdjJK}`{d4ZO8er>E<}oZK^^@YkD5m>m ziWG$KSX>-1Hhc?ee+xZeF1EI&9nRMV{V~l6QNMY>{nL#;pWwnyf>yPa_63!9-)7$CQtZxMUiuR{J#wdc$I>_JyY}hcdCf=;+hMlm zLx5OXSTFfyf|oW6;PdB(u^tRfI|Egpv9%fsvbn<(5K6fhgbyME^d23R?g@@4co$1& zD4@)e9%AdR7Kk&TY{qCFX5s!Gvln97LQrg@0@wJ77U6dV#`XKE0 z?ei)u*_G5JJR-CCNvz_IB1j~lZDEDgeg6F?8AYC-A7imhC*Nj+c3 z*5C1(YkCMhzXji(Ji`c=(rHFwgoykHWnU%Yl*iTs&nEXI9awv5!^Z1>ottx zu0M|m!=(HW_gXoBeGH>~SvbbKe_>tIImY2$-_4F;t~-H6ku?RiEzY&2kWX>Ngss)H z@8buldQMVw{RKUGn1TFH6YX27N`6MSicEx<_gVKEjcXasw{rrCFl~K8{{mKJ`|CTF`JqFtoGRYj9AS~Iig9oAj>QQ|5M~@3jvZ80L zTqp3#qRdUusNVJd<+_KCzWsf|HXsmzS$?mcAWj4%#S+ zoF|4b(GAms-<9aSdvDD@0rv6GuRys5k!pp(2SLAf0vL$o!k__I&;+&bW zFX(#oM56J{(2hyh4q3JNVkqCbe6Yy<)-rb989=6LD&Kn7jlk;ANXA#ePuf9s%m9iL zK?ikF$Ei;3Qpw?p2hp|bs#^T-2Dz3XAYE_YLI1h|qTa0g5JGi<5oIW;0T7>66z-%6NoSWiR|ZMS&SxrH=PH)n~{_1?^uZf`yV&pfYNT^(&& zOb<7|I`{UOa0biUuhRI29M?zQ*ieq`C%yJFnHT;|R8ojc;qRV8^S^~6-8xKAUzo}R zRTpI3Qnh4bfQoOD>a4(`1q1t%X*}R}xb;*falX21_kW`2sLenZDj@OJ_bDf*r&3$A zryr@tQ<(?2BqJzMyDJT)768{|m8;Gt^kF8>UxhVXSwfdpj?ubXGqj1=R-Y@01{DxJ z#pjxSa51Pq-Ibz=D*HZGrKirTYF3VaUY8+bf1)~@qO&2U)=BT+F&j{fqW3mn`jtZ? z(1v1z@$IwIZaP9dl;1H@c7GG`Vv-iBQ=V@1%|PX%>I6_pKKA;$2{r-$PSoZ~mv}4q zuYo6mI63w)U`Y^~Gnh$!Cxr`f8qaQ8yS`-1EZ?zgV4sRy)+wLM)f&B96(ES{d{piS zEdT)yL;iBKj(kd-kyIZ1ux#^g2sdOtd%3#wr{=JfM%^H&gcACVSD8Hge=VW5)iZG4iV%(jf8lSqVF4_cS?&HV(&DWdA72VHI~?kdvyAQJ@<#H=HaaVY~Cm?CWwMclxn&z@N-1d z_uz=Q!ehUWzmEzelrbxTV7dfdkz@+ri$mUlQ22<>oz*xKG;5A9d#iBqQgo7YppPsKt-9kk`cg>5 zbsve&faY^yZesjt#*cFDBUPR%f+utkUhIF=7StUjw(#m4Ikqt2?)F57G}Iz~YHCS} z1O%8DmZCk?hZE5@MT!S0^l@2^>xNCshj>$yT}O-5p;5_vRvpaYP+C=@(-h52g7owL zA=b4ilS%0TfA8%vPDoER@zDuYFnnOo*}sFAULCXC*CI@hL?}u0HSOfN)J5u(R_&bx zPd;*=Hgxkrnp(@IUj?lj6bv-9eBYST&Dzj%Fo;-ytkuhqz-#FP7kCqiziN^o$o(&Y zKJ3*T$;c-;OqSz%WOz)nNbj-(b11$!d=f)h(o-rv-~gm`D*J93=>?wj@s3J-^?<$Q z0s%a-+uO)^{!ug0UIcdYao^<8_TjL+j8g?=p7)TNvtde%4lr!NAw%v?M7~-nBU`W( z&jVv}1}3X&=Tjb2xF-B_S6xqz>lr&2C2G)}#fm<`oOaWQLrd_{Gufg=YeCw#w!b25 zco<+i{Tj6$WUI6Qf!bOZYt@@p4|o!3|4tomdwI_`A^9ve#zp5ibMTlz~T7 zF7lPFOPkF;RGfzl*&O?e>1Tz23A*EBfDW+#8dadaiddX8l6C(8J7N?-4shx*=Rdp^ zL$}h~JZY|sd|hO2e_bxUDYZXsX^@MjVRGx6D=+mLyI`n#h0$zDvi$4_>+KZ%1;95z z&ZevT^+=>%@!ICJP83&%Zlh6#^=#ckCwJARzHS!0P#np08I|w9%GgjQ>bJ(;&@o!m z?bn_9w9UOtbSMfIX|8zRVvJf0zNUGT<+sqM=TeqyPh=m^c205b7TaFIBD=8F?%#J$ zPmTNqms8z2WeETWKM^IXyi$-1z4255?O`sf%2@mQAPm67>p|sJ#TfEvoG)wl|CD?8x=TolO z>dP`}{qB4TGhiBNAO}20?O9@(0$!j>*IBIiBb&YvnV1go6U3w+A&ozKG?@W8^wnkH zx)CLx@Md2yVL*5zn7I(rXkk`k0a&P~e(aDHINZLXC$dkS3@1~x9IT3pTs91Jw2C{v z88y(^RQ1f0p?RcXt0{Y=p7+(l1wGWbWg2TPW3?%Ll;$@timjfFQu@6o=Kp|abvggA zf}3;81JIx8>Di?t|9pC4K|FP;fDAAo!0~x|V*_|nmYpDA)_hP7GtcD60=j(5Hn-~7 z@P6=)gNb>pvEAm?Z=I*;l4pfY0eNnSLd~SXp)rLQ0tZN%fG6L}82dTj4I;xTA5|_U z!Bf3OBLk8W_-HY^ps^cJ=<UX5w(Z#~q^CG&!p1juy{za2yiFZniK_Kzj?;0uk5{dIwGc+;GZqR=@#=i0KJ&ofo?%^k~MeU zPNVUAe_T7Pxt#jJ(?EF4{%#rW!M4F=P+)m zQ@jCxVVLIqtPTh}G)X2C7=+t}WFR=)=BTk@1m2RU9t=dOlvLWUcD30TTuHqeaq%D9 z{)T--v&JfW0gcr71$x&1=f(RZLqg#aMJzQ3wUq>q!!StELrm@xsq`%;yMW1%8CBvG z2KZKSIr0RK_cV8N9#aso;D(xFbw#Oq+-tZ8reBMKnJYa?qh zKRwa(L?S_7*oJrmkmhU-si?}R5$)-B7riL{8^6eY@ji(998XE*yjtzYe(^&E_harz zPRyD5?0FebIrws7WyU@$*yNQ+GERQ25xE)bcwH|_OsIA>^mdIk~A=&G$XcPlN7BO-`G(L|&Aw!f`@9_nZ!#$_C*>NsxPi)<}PMlGQy%3*V8>ZJx|M>ZF!Vzxo2pza#%B+JLPL; z{7%Oj`MZku+YD0+EDYF+ZcY4&a(8Low@{hzTH-6+S@>Gm#k;-3Izgh_yII$Vx5MJ{ zmk;CeFATX4lZ@^5vN;nV{pKXfw$+wtEB2Jej$ylwF7XEm z)r(f_Ympa6Fw5a$r}e}EfeUv2^T)Z!2_1EX9Eji9PiK-@fJ$YLS;^>XG%=w%c)jxM z#(Wb&@5NHQQ~Q&aFW$y}Y22CdGOR5zn%%A6r_+|2pO{b81f1W4h?W-rE!y9{Fqku_ zqIbiPc#_5Z)CeJAFL)yeH5O0`xS-u;LTQjFE{9V1WGA3&ET)Zxxu z;EXYkCom#mUzRJI+2{9r6W?-qAFDY=R2GE={ZsY9-Q}A_Vaty^m>3#xx9f~hGBpnb z2I+z><4}V*c9jPuOeT8hf+m^;aguYh39w*fiAIT#IX`YP>(E0e-Ck0arVlT!ehtda z1A!Ngg=8IuDe-30!qSiaJ*K?mOflyAg>f^>8O7?AeB8~M*%F&y@!xJ83p}aDcv70Z zygVsJETFDM>9bqR9O1q0NCo#qo|u)9f3E>xI<>goaK1D))X@xhdAMo|{3${f_AkY+ zHY%UFRL1Ga4hL5izv%m&+qdFEO5{;%XvOSSfSFfOej6iQH1Lxps6bAB97yx&w+i5u zeNES$wvSlJZqY%AwUG{>%3uwD{gdMj7}d;I9tSAC2N1&q*yVwueD0s&O$z{uf$);!IR@$R6RY7Oe}$`LaB- zT#xNWAKWuAIcNal`n&bnv|2*%Z<4y=B(DEej~awGw2WsH4Ds1v=4g?HbTC81C@bN+ zo4En!+(GQBF0JhrR>^;yLSRae`=}j_>R9Tcn)6mm&`b zw*W4ZDaYC#P*(a{{BLRb`a>F`b@24^-C;k=9zA?<(Qs?LWQv&4@^F&VV(6ZXmV4D} zro=pR;%lC&FwOqiq@&0N=FcCVYc?pPO6C9T}hs7wRO|n%eK+Z zAPcIoM75B-aLibj{g)FtC@&OkNQG$~VzQ|k_?YuzF$+Kgr0glSK+&ezbL0#oIHN4S3R7n$H(A3HK0Q=xAN2_niuLT|ZVSL{Bg7EQ1j*h^y`N z*|L!?McmV1w>j@$%;F}=q`@;KsDNpAk1H%^|98C&oT*%e6ck^a^}H1{)>to%IxhyD z<$R!61^Xy0g;z5kOrTH6L#ev2Lg_Cn?l!t@{fF+SeefT;U!Svp)ICoI%iDy#Cc%A?co1gsuE1)^|*3y(CZo3XF~3MX6k@ z8R#IYqKTuJplV`=Y>N@}3y9Wo8wYV*?dEXHqzTZICPSbnzC75VTssVB-BuT_g8(#C zE&N3P)G!%HiS6C9lA5nO7&gq3_*`b2C(PM42y04mna&H~wQ*b}bMR>5JU#*Ni{@6& zHH<)*LkS1#dBfI^r6-ocWYA9Az5blj@|K#jAaY- zS-hk}4+}c77h+pjVu4Aob#<+zH_f&^=xwNpQ-1Vs{XGFCUmQJJ+w~(c=TLGW-;uTL zGGw2VJJ1L0d`cr~8(-Zy=%oi%iCFltv-WGTb$7=(s9VSMY%j0uG(;6O2n(0#lkC>K zcsBROV5K?axHZM~NDEV0I!A1tBeWbhZzF?GB7?^-Htbb|oeVpEAMtu0ng)KM&p5D1 zc_J(+jyWtKEDL-5mTnqcVl};Zsk7PmU|D+4qv-{+ogi@U6w6+TN*+obLOCoJ0Fvw$wFs2Xg~VFR3!Y;RR_K z!14aE8A=w>qKo$K#O`*D`;@v=2TF0lY1C`=Nbal3GuMW5!O-4!|EX|jk)Ll^lFx#u zB}AM!`aYTZiBNct)xrAPut` zL^$^B%w2F_S^H0Px+eb*kSHN4HU95Ff==7&#H@e>BtmoduZbLzfQ0qMj_Wz)@Q2WL zZY~7fz9zQL8rMq|`;>A`pM6moRANPP70Y~ztN^W&y8^5hj6C&vbcN?dAUmR;`v?-u zmx^U<39=lZbiK;nF7Ws_moFyW`01So_ovC@4_^mU`@9*~4=jfZg>OvrqhA2-edoEO zwoh$Van!o^B=v&wJ+F`Xnz^p{hor-r8j~O2DrcLI+f3y?0~u(_SK5f&o&RH| z3WgJ5#Krq|dguyD-2lA-q3;9cfKA(ZxbbAN)a4G0480W46r{*WpQ!r|MY%1#@E4+4 z^6jg3KKkG2#*0v1x;aG}UT*Qd1}GEPM{W*IZx||_Or-RDj+=vpJHv{?i8jgv)%(WK zDGg?zcrC1{oO+y!keuDy(A>W0asxW?m3~gux{Z%V`tMsmcX9yh!P0Ij7bK+0w6Q2DB*3}QeNy!-yXy#YAmnTQsb6{`pH{8$fqppg^$P>X{uUHBH) zIQMohl7NcN47?6Vm5`Gk(dMuCswB}uS%tv119H#+Kt_nT;;)bb_Zu&qTbTgIFZPO# zr9=ZV4M3i(YIKzR8L6-g>rVC#kQ(Sc`qwoP8r&nGAM*fXaNcI&G6XCAgzL!Ip_mX@l&u=Tc? zi!cTWHJfkhKV`QZuyRj$qAQoD+FoV7nqE`xW_kw!Vo8)JZ1^LihUvpR&|D_4#ofeE z4_$uP7}RdOUdf+-vV_zdxTB|S$w>Fx-T0lXF2*layBptbL*Kd3$|LWjvd&DwZ=38F zTAtvFc>V*Udmvd`qAajBd@U{} zHjs`=hTKjaMK-G1zLzOUhn}q1pE60v>iOU_j9`gP;t@-Bfr+cD>)bVR?bE2jQ5bXN zbW{_AC-KPgh!LUOVA=9*=kKY@aZm6Px?%G$YHN466BRyDxZ6b6-qQ9?9CbxOb$yz_ zs;NIp9Y#KK^I%9BfX{b6s%_vKeNRen(`ZL4_azb^ zz8gA&<`vO57pE`dPt8SmcJgr;vMu$cQJ9ISbx!Jqdr0adHq$NDxI+*>-qpEe@9wyD zz3XTE-D5uJK#$VE^0F!rMU_4L6t;OC_=#DL#sSZ)m=JYbp{MR(UBBIzx`cZU6*kxM zJ*BMBneE)cjY^^%4v}P*WF7+wp*=HOLxPa{z)#F|x8B;ThkqAKfmBw+YYtXF% zYmV!a^sSFy`uu!Bq!M3H&R%CmVVLS%71av2r<)B_1{$_qEHx_T6j(hnd@q|MsB|?;SmT# z*~_eQZL*cRF5;L=mccZ|8%R(x{&Z>pZAC7@xWlMO{kPJ^A+c*-%WpkTalBx*3biga z?!PqUc{;hW9Bm1wzM1}w`9xs*=o!x_DJ_7zSjU_T5n>Q)a`&wkxGz?{;Gv$Ttv0|p6J+ugn!04)i~~@Ex_W(E5W*vraft1 z{43SeGnCBo#JS0(<3QhIo%EPAPx32j#l#xtZiA(C`6Km~yDGLU^Nt;p0nN6<0)&B& zX?VZo+4XQ=IOTyE@@2Ex8sm=0j+~W)dg(FsInAnpU(Q@i_&Io_67%C>iN@RJ3d8;* zEv1T<2K(g8!q^CT-{}54`htAD9y1k}+qGBH163zA0o|GfxHmIP$h5JJc8{sZCzng+ zuEB@hO7mJP>d-{i$gm=N|GhNA-rkL4k@f6`d}X2Gu2Rt~uii>sz#x8Ts%7zefK(a2 zHsHXhxvwsT%a{L+ZDNansO`^IYf_U0a%D7>lD<1IqCo(%p6XY~fkW@`8<4mIz2S)@ zz$!N>L^#8J-p1`YcXfFj#Wgv%W22J09f6OHw_AlNyVr1H;_dza{V_!i_R|u11NU*6 z$Tun;6NgY=N~#Pr?C#isI$LRPG~o+e?Bt1pvqR>XGbdp!*MBd?XY#sU&qU`*g4En) zms3Ea@`ShD_!maPPsf*N5kJtQCf?6H`wK91iaWV;Y<4#MUY?1)M}HR?Df&62eml&3c)@ zbWO|s__>J1<;nEj6XRug;^p@yxAnu<6-@)4-KM?Q!VC8a53ARlr(Xvz2cI;nZYtM( zxasqsUZF><2a5lfULn4B3(s;%y+SUuy=m?weWH->DAbkotx=9%7gQJt_)8&z=hq#U z4Dak(t~Jr0RtGQE%b-K4q3j^pn=zRKlXSMWe5)K^G46?kkxI^~gGr7+itMHq%GQ0K97UVMXp``UAgius(pN+&ehO!QMm$X z$qYTCW=os#9O%@V4Ep4q*_fiO&MC+>sKd?JkPt|6~u(SWrTv)3kYW|VV` zTykK9ZJ9?2|3`WGUm^QqsMTj&UEGSH{LtC~W9i_HewaU3ngBiA6tjQ-C3#>N=)fx31^Nkosav*&3!k>pe9M!(Yy<~G(=2FUhQOk}W#UJUH2%5ydK2ks2qRbg#6A+a|?^nUP9KthG1RNY&xf zA6u-G?^@2nRP(ue65sZX{9ksTwmlnLUP`sGlc$HfNi!*67j2)}-L6?otLP8ZS@JVX zt!}v&x2A0eE@Os4WOOj2Gdig39*zgDWEJJnPzMaNIWaKKj+QV0TWVIEv*lh6zl&l8 zhoF>_JMPX%I5j~4qLubtZ8sqdzSs>Nd7Wa^>IC9w!b2h-Y-jG&sJ(QPXZt!acAgvi zJwSS%1KeBO<2|k}yP(IwiUjCzyZg{4eBEfE=r=$Z{D3NTws`&Y;S7mU%8eC>gaBWG zQ!@#0kT?vrW#4*IvVj5RtN<&h8yIwn6NOpo{y=~<^cvkS`nC4!{8jmcpt6S)()650 zL?#5??;F_<41iVZ?;7it_zEkO>+hyWu%JO<5w0tYj*N7AC3NfAM?O~0 z3*uXy;I7dc{quBk){fs7YLFx44XP%Tdr~Lugbr=SqhhkNL)TE zKQOMV1`_NFCn7<3-`~7P&K#`I(+E zz|r9IUDJ0Ce-w(eLi%`)t5KETJzsS}Ky^P=kC1FKPfxlvWQ;G= z<8m{P{@Vj+CAG_Ulon8HhKN>!9Yg`WN>SOj zZ$MlwBgB?PnFS0=F@y@8TMB*H!Z&I?J?MEQU&WQ!DfN;mCr(qVZ&puzlbCJAP&z#5 z{+8C`S^wWxKU9u78xX{5gzzcMpJ~K4$Y*EL3v}d8UqjnNO_Q{BFE)ubc#kPN$1|Ee zHPd}T(3$^%(r%UY{b1k^(lhqgIaTlkc4}^OF>E&*G}(M@dFX}HR;XcRo+T+lbC;KY znPET@5IfmjbQd)=$iQpZMX>4+(aLNE>9!nKBR@7r;+Tg8EKj7~G%xdGh6{Xg8H}k+ zsrlGn)ra5VpRn0Ew#{90K`aI=m+>lcbjn$~m(SR6m6#-w|FBS=edciTVDR)@k{hqCk(10qlBT>~v|oUqtt$V&IaCrSG$?vaI#bzBSw#9vmYA$71`V(w$iO zA}3Z%X>qKRuaw^9fgp3x&v@qsyYV2@U=eTN6wPb;QjVbiKRE(i zd6OLEKRE(BUY;snU$cyI(d`E;`r$G*BFZ2&f5SNW4+6T33<4AkrO4-^dZc1%Dfx}Z zpNfCNhW$nap>-(3-XV{NHV=29K{86*u{{>~@{PTtMY)mL_(%b$5cKP{10jaTK|&6q zW4SfoX(-f8p;g&)eSM=_{WX;9PRkzuq7)Nau4c)g1KYcX>FRnV(an+J8NPG_)C_FU zZo2GwV=M%(vb?`i3;0%IJ@hF1BlO2I-@C!lZd#eoKnaie>*XY)F<92j7ymIE?lc%; z8uKHd>4Qd}Wr-2j&Y-1JaL?e>lnS*d%CLa!{T*x1$lk_uZ zO^ZRgtPDzQZsP9m9!?P!c@g)Y?-;Qd9j@(SMiWT9DPmJ zz@WMp`Pf2v=~(<_K5=&?iy1pf9eFNXRe!ukVe;MU^8g#ux8nu~BEVckpsasx&5P6} zbC-DgvOK{O1?RAO7a~u&lw18X{uW^7pe+cjpW5k{nw6_^O*hc1D$-~)FgZI=&mKYb z`u(h?EI%gRC3#oo7d^67REjHjI5f;?b5e7CEOML6-MD_LiLcuL7##DuKgQSRIlV$Y z-^^g97={MU7YXB~znD795zLZqtr<;9;l!Nlt%S#hbs?e8iuyL@j{ZTF z(E=N5iNOrG4&1GJLF?0WE%d4j>Hz$rpN&ge!0z7dL{1|+y&VC{1K%EftdYn}DmJao z+;u(?B{m?xn6&rcYODCMp7TSoq`M4(9a_hQ%)dGc6$K3HY-nwTM*$vI|7z@icO+zG zM_kXmgY_UBm3~oK`4`4jVr6YQ8I@ok3L1m0yhFS+`zL-L*8VRLU;-Pp+yhhefC_-+ zR&nUklIVB%_Yla5dmAg|+=j;thZQaS-$F9`CE%GM%^S~JlxZ`?45EU0`^Obmd8bGv zCFiEnCYQ~{Dd;T>$Z2R7dvTJ?oIwZZ;5tpbw$~C+Z+c|wZG7x9)cQMBvMP|&!uFcx zYbg2T|3le(1vU9c@4iW>iWEWVRisxb(n1%Jjv~Da2#E9^2n1;=y$jN-^xi@T0i}j6 zz1Pr5D1pG?cV^B$`#<|?U%WH#)tigVcfM;q>sg7T zmCA-urOS`%PWLM5TIv(XmSwc1wCl2MEntY8=SI-KfH>kiYqIk^8t$|9j?pTl)X)i! zXy8l9D6od;)l4ymEuf5ws@m&O{_=Hv?I6}IaGmk}HVj(Rr6)PfUS38K%1VJB?Y3D; zq7V{?Ban7KZ$w=Z5N$GUKZ=E8Cxq(Ehnu1pUGm2G%ALJN&;3)Q{5r}t%D7|?oSZFt zpJod9$~#1DQ35uDy9r(ec2NoVSVjgK`}1u?`c?Cpr{jnYGiWs1&i-rdRRi49+S+)T zzq6L94qWirUFUYvdT1gN*yggVhT4iIo?Ve-cS?C5y>%*GI4kGB$Apvk70`=`O%KjU zomb<+d0iqrI$n?SF`I9ce6E+n_AuRKUmxd@HtADr^sBjF9C^#$U5&OdK{o}IEyTF} z|HA>#y!dZep!)Qq(6#wZEmL*o<=Q7aRwDX`FcrBthwn?GCISeqPQ@PB&mo>{c1oG@ z2`VggnaVV&3zr3(;smb#tl8X?Dz>j&E9HRVy*a%WZF{;4nT86#EjrSyF!_>#g1$5mX0&;TTS4M}uGYy%4V)vyeP=IQ zBOIyuiz?!V7zwGA*~81;J1COdk<>KetGtT-1}BF!6huUB>Y7fGqk6(gBfQnoUpmm| zy#cTEHjyl+eya#;=sICEGcDHE)(}V|+Y@P+ zbnz#*MCg(1s;JPnOnWXvrsnx%8y!u|UJ0aBvv_bX!={Yl=*M6R#yZufU*-0`uWv<$ zjpk ze51czzv8rgdUP{#tsr^kKRs`6> z*snXvM77s%c1aQ>7+}xN){X*?Uu0)CJ6(^oIpGkE@fiKW{Zrp^v<;<#M@>00rdOWA z{8PfW>mu2-%Rd|*FnG~97z4Uqeiz-Gn!?0FAE>=LgVj+|Rb}fi`a7R8XM`W8g@yfm z3a}>d-?|};J$`I~^z9VlK3FhXts=}mc|ni zS~$h24AOgD9^c|x%#J-KSRf${e;x4JEPJf$u=eot9o}UH1#E%wVN^_W?_gJ5T%WF7 z-h(kZpQ5aFxt*P_o4MChYuZx`6Qw`#V%3*86EhDcUqYJ>7s!0rs%rD6dDmvrnT}0% z-&no!oBa5}Q*&dlM3D4m{^oJVn;iP-$%Z+h+I5`NXq(s3>o-qotTu05`9IbhlhP7F zDq}1BO|(X8eX84$!TiuqR-(4&0>NP1gSQH=EOX)zMoH}2caPb}#I z;%o_NOa3@jO1?fI1GKXlHP|j-1Qu>i)c)DH#kR1Gra<)o+?AD;iS_;rYKYSP$Dl$q z6ZAOggKP5_=V}NMV9qZgROy`OBqL(qdmlKsj~8ImMddvWEQbfWZas2<@qZVUeb{qv z{Nul_miy4jy~pYI?{t8#kP#v>+BOPyJ_k&jTQ9dvstR}hQxj7;uT^Sy$&T8A@=6>5 zzCT5Pz1z*@m_UK``~GiQI3^{;j}!iEFXn}7!Lc~Ji0a6e6w@z|^9Ygw;YOMA&;5FS zzkgXzxv&`(eBN35q^eO_?PjRMC+=eOzT!!%cd@sy=kVikwT`Ms(%~kp;~Gd86~^1L zs`7`0p6Pf#Jm!kN$6{!KfdwYLpET7<%sWaPTN_sLusDlXW;(|6fQ80c28K^vq=x*L zT*nUuX%D1zDQ}ahzdT9T_d;~RX=jr?bIYDaOOPAJ>e;AW<>uBk4yoyKY%0}*-pLic z98)UyUiQ1|abk2BB3RIp23_)ZFhMT?i{Py#9AxgJ;|#x}oYb?$5#Y2s*Tt$blh@JW z@@oPaC2@bCb<#B(ugs{`*n+^vf1}XOQxKQk!_MwO(51PR%)(Zth9Sl##`Exm1gOOe zm_Akt<~yXqQ`!`zzoi5cLFv@aWgoDCx{V#>m1UBsD zjfuwZjUlq*(wH^Ni$Ff?pf0D_{>8mpKskokj~PX*6GpRtn-X|3Gq7y_CDdr;edlXn z`~&N8B8zb%qf;Zn3XA3)r8F15aWz}=s>v^N{J%^WJ3ps2Uix7>)gW**^Xh609Sb+k9TMOl=HDv|%v z4-ZH0(L>Aky8i7aE-J=Hn>`I4eK^lmQ{%g|mjX=u$L&veiRVSkIWE-=?a*@pg$&4@o~%tHrqsC@g$`{x zY#mm#LM_eDv#gnW6!tF?IgtgBz-fK@1Kzv5O;@)1MS9Ax4O?$E_kilOFn!YS-bvub z(ElG10G3n#g@LGGfVK5c3_mo2_aj=^F*W5jl@c;OS>U8F(e1ofpL69}Y(?#CHXfxl zP3(Aukn$RMwsbO)Y8xnwZ#M4??K3kfBzo=r=mVPsGR%Yb2-|TXKkX2N*sGM}A?}}) za5n89b_1@L9z}=CU>}ht>k5n~UmaYAY`^3aa((pKFa9G-pVp~+IqzpJvjcb35!7sL z#;Dcd6{e~a8UdZI2j5@8h1kivbLTs+i^jY2Wq!<#r&P*B1-1@ashD?QzP1}PGr)y) zyqCc5w+B8Juw~^@36_;=)*+kMA3MWk_-j<>?Q4m3riI`kDq6EBt);2aeA`=&I*m4u zxpw1GqzcBd`42lJQP6{YWUaP<$2p-w!(mV}*>ACaJ-)r8;`8amx%IF63Mn?peEN-I zUdDm@!gs|TQ=sC%zL zK~@7@z_`Azh?D8{uiKRC@93xx;;hi2f7f5a%mN;bvV1uG|5yO)8*J-8&f{%&+BfeE zoof8&(s`u}`LFZ~I68QR`|~dU9u5qFb~+h!eKaGYq|pp6ys@6_PerffLQ5VLDC8CDN`5htSnKL|NXQ4> zZEHUmsK3wHX0EfC8_xn7gkGY95TKoBM7c9=^;u^IQWgHj-|9f)#V~4nJ;5LE9$-VJ zOR(jgV(V!6E6U{SEnp8X-{^_`*#$s>sL5#e5ELeXFOFXAH%B_*gk|EC7vRbB(Go=( z!41|s?Sq4Jw_!>3k`4217b^i5sK4$cGDqG&k=}8C!LF}y)lxT)AC$fwM3}9fHG}MM zyDpnOfWM8V!M)FN+Qjk53VY?d5TNhiM-9#an%I^6fB+95*&I#wu43oJHa+08`q+6--yCH7WG)DI)O(^-bC*m12*qH(dE-T`z*E+_euxO{ldp96`4R~VShLs+E%G}L z(W1sVl~{!vjlN=}A0N(>wdL3$fyz=|4zH$3wsc&#O3C=lnlc`}NC!m0JTtPUtG$1( z5A`4FG1N~;BBI&Q3a&~=XFy+6D z>80|%k7&K|-ja%f)62tw2Q2*_q4v${DLG7t`>A_Cf;p)-`=Exo{_X2sKGOArAv>@4 z2T@kF^L$V`5c<>gOu`v2ep#i=&TA-5@28P{b9}h(Zf+t?nMVE1S5?zIg@Qe;Hld1A z``W(pt(ZGKEbSQ6D0HH9UxQDYbiKgJXnblExg)Gw_0D|J=WegH3@Unuk+bu)v)A48 z996r)tkwr1dR}taE3=D2>n_xje>P>lkpCEU1)@ALJqr6oLNnuMns2cWfgD{LO=JO= z$tn(B+HdFqJ~L#2>TICX@H4ER_rIAs!hV?%{FAZ!Ng$>JCi?s7X$k>lCKK3)w5rN) z)85fG)(%@ZtA{6`zO{ukQtR=FiB*HRcb^IS_$2D8oiAJYdgZRDfj{R7<-~ zpyQEOf)IaejELLsBqykR;m22VTrZ!JgmJv$9{`sy+Z9i}(80f~Ie$-B_v54K^d&?T z+cJcWrsUP-4Qj1`76GI@4&{3=mSr15w{g16JT7Yy?~h;lc-tpk)0=mKgclCZzWf7U zaQ2@8ejojsbA@JR5y%VG9tY2@;EP= zPes2+IQ>jn&;$PS^KKo)4&C08bXs+)Zd3x)4Zss6&&=x)HOv>jNCUx(Ql_Pzj4Vc= zW&p{b9k0fa&>c}ZqHDmedFwx*f16R~qqT_hs)en#Z1bgm8xssm>j(7vo<+R*4zL0$ z+;=xTa8t7CL0J=I2YHjnm zWdr>3Jj^(U$H+oD>h6qx-WkOWYFzu?_x@v6J&c6Vi8{-)wv5PZqYh{qlPAV2{7Or`q}wrjrIjV;v*_jJrRWsR1UzNH=fu$q<28I< znlft($^+_HCE9GR*1^qecDogY<;mBJW1349K*JDmJ7Dw|WsD*nVnd7^wtUfXhg}6q zfeu>_8s@v_ggv>esuJbv^55P~8$0uvUBG9adM`u05n-}8)x1&)^qa#RITOTh*g|AG zvtXn^+c8Ff9ZvtBc|?T3O}iESPK5o0EPWl&eoZSw@+p>uFXh3(3I+2cTKk1;QqIfn zP@=JySTEUkvt|z6$wgO$_^OP*wq@YU8x-De=$olgTh-g%P&GL)js(zk4Ve2ON{pAB zh)}v9B^-F3Bg<$tq4hxv`$cQ|S_x{ovT)@-rp#+@^>mIB;v1B9&3)Omy>2(_O3`ha zGoNj8czO#rM-6XsA%%Q*Zoto-j$WQh{yuX^ab*b4r|54c$+`ahZ&ib*Qok}d@`N!a zfkSgo&71=cFy4`)qD3(^*Xm^}Q{6`(EjD~^BT?TC2op%j9v$M5+XLjJ;tXkA3Yprq zv|p1mM9BW(F>Q7xQ5o)MO;YXD@Ts#Z<0QC4G@5}5^G6L}eOWS4$!Wsr@2TY0DuJBN zhDMnZ(&IxDIHX{0|H~ex=-a;58#SYQjG=AMDn%ok@=nc_d42r#^nS|GtRL zAVN6Okz@)4N3Mc^IhNMy*RzJ1g_do96;nLl7`C*guOG%##uc}1H*Tg*1XW1yMoZPT z@-l@pMl?-Bxn7f-^rJLJXO8u}eQD9=zw(?9%}2uRw+_T*c#ts>mpd|mi*fFk#1>BTN5ldn?jz@Q92Kj@J!*3*%_bRuq#c&3n1+dO{RzcVsqKN zm+>)S$5v819wGe32!P#YWKx#ep+&}Dcqz1)oI8#BqLJAA8RTSTrE<>|N%#~;pf;oZ z`Apu6UoxJt-qNEpXcq%IVzRk-iS$+ZyJ&FwJG-U^+@;$FrpRrr_JD1HTek(-ON;}T z|JlzagVz0m3$KYxgW@ofxZ?-O=>BHNs+y} z=9=NtIi-0c=)+mrVwu6%ABe@`5tjFF$tTfD-o~@Vy=7=PUNO~c|5#*gXc#Ua43Xoj zI=#7h8x*u{!*Co{MJ6sP%u`arbz5x>o=tuH%c1;-u^qDNqQuTsyqOCQNV5rY*=hm^ zu7eZ?X@!|>88S8Yx^C-8Cd8{Gd{4uCc1D9Vz!oz&7-GX$TR?F@K{8D2QUho@ZS$BG zL1eKjI=0P%sVI{_`g5j&Vo1$j07VvrpCr_DzWF!HNWuJ(&u6N+c)-g;&`Uv&PapSI zHT+$IPEGo_-Zd!Q(b;S5*wevJSC4)*2M94zEp&9DL0A2mEPpO(GQ$NppQRY(P~GJW}h!+$+%Vy+@T zvQ2z{okUr-e?>4CymO)Vkf>dHb29C1!eXx9pHv}JL!Kq!O7b9+%5k4>0zefWeWbp( zKz91fc?oKT8alk|({^NjMle%Zq(It{GB{s4P@pJ!%H7W&9Dy^Cwv_!?=Bx0J<`N0c zz7qV{*0s@cPl@lmrlFZ6xnn=48K~k1PbPo$vjDS?vxyM;*JN_$Wy1})Tl8a?f0P66 zmX><1a_{G4lf=Y?8Lm0a`Kc)g)2KcJLKh%Njoy&+2nisqS6y-zxEP{6LnI1_n=e-x z>x3_r@CsKxX~~r+PH`?|pDMhxBbscjz^Vx{8M;ifG@V#E>L;!xwvdYyzqtT zQqtz{8mC;ftn5uM!r&5xi(&9v)=j@QJNvR`Wo?~LOlJ91r*xq9QDi{$t+ti2-M$Ji zzxiS%w8pXi0b#0NTJ31YW9QJrS?gwqt4?xSjB1hRXrUiZdmnHImj^+CF(O>q0@!O6 z`1EZah$OP`)_^rJ>`Lk7*lsF|QuU*|fsIQ3(zvwqH6Mqu<4p#VxhZHb z4<<~fy47Q&Ts}{pP+~ILZ}d+0_xi!iZ(4kxKNioXMT0$nfrtl#gjxu~;5Xp{IgJFfbmjQX-YQ`L!s*;(3JMa$ts$v@pIN^|`` zneHFw@xNlEBypk#0Q_E|+IcpH06V(OZ>&r>oja@|$AHeNd{Q|&hp9Rhcz0hL;MX#HH67}Tq&?|@UIeZ))z=Dl`rlV)|;YYp!-(6;WC#w zYik7&Ie|MYneasAd!Mbx0#wn_=lqRS=0si6;5Ur;(r)MQ)9IWtr7xAX`jl@IgbX(5i*V*wk@ z1t>k`xLB+G#!dW3Wn<5jqD>p*W`*}bz}pf3CV~9sERu}ZcH7|aWTvx6Pz8cAf=s_= z`e7XOeq7rosp;SXOKW%0HXYioCwbDIAY8M0tA>)-)R=pEdWIX0QR=!mmJaiE>!2T( ziEbD!y>d5iF4VxufmT|kX4@WP{DTlq^Q{}JRp7?m8owm>RAlIA3jStX(qa{6gLGg$ zg|$QK4BU@gHFFe^vs2r42_q)MxJ1wEe@7}aVhl#%r^Jmxj5IP{9o6rm3(rj-xQu%O4}&fi zicDr>-aY4`({Gze#MKUCTk|2S2ww$1VW0xgI%vWot3UoN>gU+zz`>OkYspp|%2Q1V z&0y`f9xVtXol0x?I9>xR9Ehk z9iU3!`a#au7=sH@Gx7dTBOTHqKV9{5IvMYGCNVd5TNOC-T$$fiKs_FvPXf>d^i{>t=ilj5)~af z70SgojL4aNA*$g436k1mu`RU|(>a}bu2*~S=r^49R_ygNOlE>6bhKn>rU_EehSuXd zcYl5XK%fX<&6@DAz5w#<5cFEui$Qv2E8+Mtl`K-yL~tsFz~6Fv?>;;}w>n zH(^T;<)G01b?3RNv&&Ma3gvh)xgBvHP_dp7twufPpg$K9Kc3i(XC~0)m0{zi+tA~5 zq~wB@EdH3|NP(<(@@O`bHK#v-`%T1KDMEAR)kDhT#q^ zNN?%vm^=@<=OGN#ym!8C)5i)aapU*DcPmD9L#$FEfiQmi>oKYUqx0Y4Ew~|v!^=!$ zl9j^0m~;d9gMVxtPn))IZOiC;mi*Y(ND>m?a%*1rhjY$TDLIAxt5ur9eSVsS`KP9( zoLSv3E_!ek`Ho#mcj5jM2gcJhjhP}!DERXvoOj+#n*EXW?+!b}C;L{=AE+$q?HcO) zhxXW5VA*-_lpo`R!utuWfC*3;3nXEpHJ=p`CYR=Tkf#IhE8&}yEvAa{sw>n|A9PFJ zX_PE6C;SKQw!HADuB$0yFgf_GCUN{My9}1)2&kLu=<6R>6E^UhUgL`uI%VK0#QlhW z+{$WkaG4KyHAmWyoBYw72c;W4^0hN3RK{@$NIjq?Gk8)%YA&T~t|V++Z^RHe;4N>{5sy)S#{ey9bpR!NF zLp-~Mm(RkvC_K4Bh~~7lpd2v_KLcS|!OZ~0o^YPG)ozH7pCw@1y=9=mp;ndx>DV@% zMw+=EtO6Yz_m5IKv3BW7`Ew121;08aCW{q9IlE#5g9FMR)D2$1^g;MbcdIC>Gwz08 z85MAU#TUQ0)%~e=G9I2b4(Vq+*ro5p=S@r)7<618SDJ(ceE8joQeBMm{scq7vW+5F`CTEN@?YS5fSj>;eB z>wj-%3%=VKz*eEE$lGzfk(g_Oz~dq3*I+liuMU78@_7c_>?A&st>qeqk<*g4WK=oV zUCzgsj-~ZPX@6)*%>@EZBJ!C2qid24Z%LB7|*6UdhHu zL3?y4oo&;6WxuYcr(E>k*BOT=?7ug!de#cneAj{%#>1w(ujD-!WgAz8lH)ez?6zxA zK`(>^r3t8oNOq*HZDljC}w(QqB;%aN6byFx?+OAn^ zqq%jkIdTRx(4sN%oH!;gvvN$uV+7#Bt03G+823&73iTKM%5)G2NtQj(iAHbbgfnty z`mB9BOzUpVC$TvmvP|)&y+WLVpNHsQq=M-;V}%)S!L~a@2a2TIkmKQqbAz9@=|AXv zaO&F5Tgsi5Mc4pUZc*+AG0GpW`fcdrKg$rR^tX(n$!-_JTbZ_oS!!I;5i{smFedya zV;gdXu9Dfnl5P7|Z$BOFDs*B3{dRTgKm9wAD`(huwUceLEgjVSU6X9ikF=22&C}5Q zCw|U0u48A)rs9qlF|489!$+~b^&fz2PT(Tjwot{C-aZn?9R7E6^@cNF)`WDAsda(? zlZ*sI&(p0(5cuXs7BQg$3WE#S6|u;V$v^iWAaBHl`($;3Ak7$2bcqORDKRWOv2qWU zoQFl8fXgblB$lDBet$-V+zb^?`HaI0<5K(voddW#KCgwVg9xxvr?H+LmW}K|SWr&$ zwoigww*dU?e9il=^5RJh_}nLIe6`~<3=!O41ymqS9+WQ(nBXygyKuqNfnd8LIJ%ZQ zY4E=3IrOBkzn2OAS0O6b%G(V>nSiq{`Knfm>Yi|B_ma;kXI*% z@3Xs!Je&xOeoyJatW@2ABC9L;VDKzQr}L}A)3sSI1N?mcaPp8t9O#;yMOJ4&5TNsz zdTk*E(l9Z_4;uvF6sv!=sN$Um?W}c=M**b3+RO2qV3{s)VIGUx5=-n+p_J2D(AXD7 zO)V-Skix`_E3hn@zIQK6Zj>CK`RDF8LxwMWyRpj2nRs46m*BE0y=K1HDHO`&PgHoh zaE-{n2NpEbZ2FT=V5~u*9tM$0-FdlfHEy~q)$1n~={+Chl)z*JPkM4l=M*s|FoeNS zP-i}`CFl)~9Wj8gG`n_>h&l7%F`BDSl>h`viuxL(3*`@Z&-@bh`OhP0D?C7HTGNA> z&ti6~uaNP^{0XTPCbERYd42*U67z&d4JJPUb6CX=i z{$bV>4~8w+`o_12w*^Y^0LL12TD=_Bpqibkxu<~*;wt3>n|1F#q2q(p3a*mA#^S%A zKihziV6cvlD)3Av7)`!R%9CEvbWk0dG=4HyCaQZMuWo6Zg&e%Sw15_;@NO>PWGh0Z zR(;y~mS*S+P#3Jbzn4V+9;9%g;E4Wsn9WBTa=jA|&J85?yhmh^Jq#Cn8oYhmUAzE` z|`aodOOEguYqf?-#!vB z``*YY%=+X0AI1PLQE&;Xo=r`FUIpFg&s}!CP5j>Y=!ErwaUEjHl@Hw>v5&G7>Rt4& zt=0TeJ6S>LPR^AMfxs#NC+$Ok1^UVr`p!l9f>!F?1uI8%AJOaDIoa2^l0OhK4TCaL ztP!nq%KdmSMjeJSg<3JEf%pSG5gaoSjj`hQ<;akSZz zW!6|xRQ-hs1pu=*#nan&>Q#;3DOcanOT|1v41{wMe5HD-_(5u55Ir=nCiWg`5;Mp1 z4c;b$OKnq3?ynfCi9U-x*&a1b z3}6-WiEB{B_b<=OJMSwf5~DZftk})8SHwv0k)hKL9SfCe`H)*JfH5`;v#|NZ_Pz+m zapyw~sobl5;Ze#WbUeKrQCTfc-4+{=H_y8&dW6VUH7hL+&)!g17S0T}8ecB2U+d{@ zR1PGa&kC05JkNaf?_SgV`4V+@eH3^ZWkhGNZrBlD{|crCi~rFP;)6qAnk-7@jED#7 z?8~3$12sWEeuKrn#>YCGa#{g$?0Hnccb_d z%|{U4Y`!ICU5a)#?3e+3NF}htnPeM2Wv}zkwr|%MoN-F<7zcb>b{pjD)eu{Ja$;|$ zHwGte8UqLdiWrSMEhDAu0s7TL4$wb6=>!?BcEld|4(5 zx90#y*xY55(_n)R=HU}_OPHDFpyT6iVQ2wUo1smf8nI9XX5!3n zDf{{av!BUMvqe!@^}4g08L>uz!8VKh_Z7$%L}2^2NgWH%JcP1Y7YDG?4H7_~M}t>@ z?SxsCMH+iecZWZ(Rens2_@bx{mo|uz3CIJnkfMdD-RVlxY4B#wrtPAl*G~L}^{DNr zmBN6wK#`TN)S{$iYKu(rnj>EZ7!@uZO7;2QGJsjQan?aSg3Q*JqR}Kn|44XdV^b2i ze0iDiwq0<&{oTDR5)n=cZe5igDg4H7z_h~Q?P->-ueE$9iZsf7S7~MHB5BE3L^;FX zpS5R9CVCl^GQti}2c# z{}Uj?WMOYcp9J0#FHe_WnFgLzK8cY%vA)2RvWx?A2x30qgfQ}^1gm4W^xJBDW}qDl zY*(4ff#xR{OXutV=g{ENC|2%@vw)M98MVrIh)=jE8}O7YtreAR5YsvMWh!{x3}7pp zvC37r8XNzefH|y=n?WrGURmg(2= z;gd7zXu@@g3{}U;O~K=3)VXbvn-H!&>*{Hh32ou6I=ksMq5s^_ zUwv8@jxGtmr+DziJgmwK9%CSJz>OTEc|Vqx=&2Y~BcYv|nOP7F;q2hz2?Qi2=*|_e z8AfGFl=Q3_uUUA$%QBx4HkJNm{tjODLX8quacK-seuLK zQ&K5dFuS#edjgJwVOMKIuHrTi#6X~QLdcb`1yNJj#3v|1%>lqi_S!JiIDbD%(lxv# zw{SGhBp9&GlxD43xHkvZvfMlDdS`7tVRVp*F_y3)8=Ngm3*0B5*827U4d%L1ki}nk z{7%JgER+I?klYwoiMhyD=CqmIhk=df*S03Jfs zG3L#5j`j{y+(4+AZpvdE*bK6)u>u+UvSK?^IXqZwf>ARi{Kj)T9P5jLeTY{x`=AXT zJ0!Rf`mAD0Fa^1_r~feNkmPpwj6^5sQ&f3M$C4--X~jWINVbIDE9roCD-4da_!TJE ztwtL(P5t1ItDHbWL?gq~x2lA$wX`roZ}f*#?9rn!CiwQPs!Myi!LKr$2YXQjp^4S% zENNSgwC-!ViovJ=vR;wTGtPcx%0M0Cx@mo3gEz%j=03vSzwuRk$O1hvg<~@=L&1>U zfbW2p33;Enm&rMw84}EJm$U_Y`oChf;srILzYtG*DAzeP;MRZx{N?3{%n-9*d-_tx zu09wsj}sqo&ClsXr-Qj;%gao@k+6zZ5Etb^-A#@*)wKu{pE1{wrGq>kzUPLaE2ih` zGoF@HBL8xGD4T1?_HKQ9(e|qjKh_XgUnc16kX?1vQVR8W65Dkia;P$m_kC&d7N-g( z{U}>dF39u1(P7R3{cd=xuKO_qql5DpV`KG$6}vnGP|*@90R`xCk+>W^bdVpl)GZOx3%0v8x|g5~umKbB!4$ zY37LO)bO_DiVO5PBH5~m4WG+;qM9IMToq2H57| za157F#UUM-)$@bFgOnVyQ~&m+D{mqjM;8B-Y;M!$Yv7I|6Zg{nYCJ*b$&%j@-(k~w zbQOt)FYIrO494z$5%l;S=&aLwY_7ScxcNnz)^+u%N zlDE(vjK5@D6uhf*+?H|IxDO0Yh`FGSJ(A4NVFJuN@?aMsOA}u)svv%~8SwqZaK>&N ze$27zGGNJakydTVAb5*byT!N0sVU}=sdf8i+fgF3QN;*5w|N?Hr0Zmm={vl;?b;|@ z7La+=bgjH2L$L)dBtDBC0*dEq{dwek%z2hteIhR3Bd6#=!&9|AnnlWRMl0uQXLOfs z!w^mi*xzA0=n20Py(1Yus`5{9-;sF?8Ty+iWA9_$a#W^+imN9Id}q$GuJmB*iGU)2 zgo8=C;gRV~-J2rmK@ym_o9}TKK?DJ#5AzmSD9_BaWA&ToII_S7Z&-c_3nKwf1tEq+ z$L$CGXVfYLOjP0gS&YWyK z{6U!`ec-)rl$oewnldyd*1BoG=<)`7x_>W->6^DKoDth|c=zlaBxy1-HcONZ#-1o= zA&9|}U7|~vpwGp&8TB`dFC~LUR^HTR(hzF+qQ3dk3-o`IJu&OQDQvfYyyo5}WO~6$ z%YE0B>04VdAuv}!TJ~Z{4YT1fVBEiYe~$h3xp0V&I<9^+EvBbD3BLmt*Z*z}cv`uq zXOFFW!?J91>SG2kMcS+}-)aOuL;FwEFF+4!JTdt#k-OwuXs!u^kk=2xXBbdNe|mVn zg}FbkVqz9~9df&ocN8K0``!I|YM}nfi1{zrPfgh&%loSz3?U|iRGE+n)!%pY`66^i z|GWC%X_+K<@m3utM5avf$L0Uq?az>gY{fM&Y3h^4`T^6i9$`g4@N?F`d&$3;RNrL< zb<+|?6&SDZ*JvyZ7v&FrmxJ@(ofPW0PbQ=mJw?{I+jsBXzUn%+f*AN(7%_y#4wkH@iS{Oqpi0>2m zlD#OVUlA2eV!egR#skn$zHD4)w&i2o*CZ5gnCc#glKIJR7ELcfOX&nSQ2#4LIsLG@ zvz1F0F3d&5UgSyE%HCeBTJzL@(PgiRF&AekuHLTMF{pNaor2{rLlje1Wyk8IinPJ@ z#Mof&;A*!|HG6=OqoF$aJ6qSc$!$%P%a(j@RHdPq)|>n?%OhS&^MJj-;vQj#-#e`n zui}@Iw{^}UYRYEgMSI>7AJvcyWKGHQ1B3uz`Z;D}PffihJV3n7LB_%6TKAPZ5clZM zhn-~W#?l^q7y|Yk-eW}9k1@E0rzuy+aWcWz-kB)UVSD4BTiD^`05fR`%iZ4gq2KKg zY;PukwvIXRip>nrAVSS)^b+O7L3FfxT|rQa-k;pEF(c7eE(=L=daTDwe*;KuKb2A^B_>z{fe zKd0oXS}pvf37^~C*(!aVvJZQsnIrYk_t^=VQlh>?rm826r#Q;JsSG(w z!`tWBZzd@Et^OsH#=`gQ_1cT1ZG?{~jPlHC?x?OI#=)5`D=BHK;hZEWcV3~t0X?p! zrT{`n@E@ZdS-dN6ltLQadG55jSQq~LH8f@KA&O&`%ha$8$&XUY=ZlHd$|B^HKSFVa-->JDs=p4 zq1@CUD9g!SpuHsckVl{2o|Jg?X=y}!9AE~ZD~56-G55|kXE>?IFfmxj05SZdZ;19r zOZ~mi7cVnjO*%p+lB>v$BVHJ(h<#1!NzGmCn2Wdi;hmE=r@iCh`3`z4{T3hQVpI0^ zwGA6H6TpA2yEg_lNJpFH=wS?F!LHkIpLabeOtp~=RuCU+;3um%WO+pwf$&+Yswt>u ze7xiH3WN7Az<9S!)7wRwf(y-eFue2J42)iwDHQsXP3Dp*qoLN3PYG%=*SizZo13!* z;%CWltt^SQZLpbAQ*mkt;n)ET%Lp5cDaMJ+T2*Byv7lbU_+o0R z?{0hhP0o2!V7q*0uIMhsRRl(|@5|wY5qaP9gExKtuCIkB@BjFxN!;yRq`Ucgb=%9rDc5MrXzX^rZOjqhc$(<+35t=?C;kKF9$!O588fbHFXC8!{mPFtU`|2HY%2~$t%mnm+>feZ~CyNdaRoKB2S$KSAo;{pom@MqK_s z+=NxC+1GFWn+;5}sQcf~pKnk6P=Qe6z%|$t-V^o|MxjELu2sV1s{wk`Jwmx{`Fmxn zJeHM7i!G^yAW)M1>!hi?0Deo2W@0X`W1@^4dw|O?Hz25hp_#vPb~jf5>HFY`W14n1 zC9?=Oyeef~dwsQRKwCj#RVS+inOM;=Icz7-8KgNl_dZ1pmWo1TDRxiFNEFjoPsW!4 zUq^cURYeurJT-ccbBV`H8=2wiKdn&|oCV3zB1a<%Rp>@ed`+M6FElTay5Y z1gxV@G3F8suF83wiknX6qCWZ&hftVRZ5-^f2_R96G@#h1?TC@R?G^vArTs7>#K9PZ ztKx3}3mfGMGJo|B@KX(h1pFSu@t887-3vj-x=M2{liNACyYrRF#|*k{r^93|n-jth z5|kr!?z3i?b9+J_PcbC*ONtW&Q9%B+R|K~)O!b3ADM?eTzqyzar~r}y$GCQy;1hLU z2X&!|o^y?$@CIvQ$jRwbhW0;3KVVZc;#E(X={l#HiRW zLApAC@9pze+PKe*@&ZquBG*3ARX$s-DeSI+JdaO(hyvyO_2}ii1m7Wk(0S0=DfT&N zKd;=F;KRK$*%0v%mD8&jr-MtQnc>XP!_uF9&!=>93|dx*N8#(@!XK1oj(w!{>!n)r zF|Y1;(_&w^zG{6#%g^mgJls1O0N-AZCJd*_8d9aV5uLQ4LeY-s;bRe`fM@7z+~g#P{I5%$w|f=tXG zh@+pXIXeRTO6`Jpy=D^3(owGUFjAc{<j&3gOvR^KWP=& zaw%P8TAz-&E+Lh??{eQ(!jV)?^Mcr>jgIKAl?0u3Yg#{j!$jW)K4Rs~`^aLCqW_1m z^Nfb8f7kyMy(fa`BoRazHF}Q_Jw#^^Bt-N&7)D6+8oi4eM33I0_ZcKSy6B8v(Zd*_+f5j_%ws#y{SC3o#_{;ZOKA% z82;RYn6QWBS=u+nP$`zrPeOYh+#KoB$zS*wt6?9`(Ui!an?9Zp2B7A1emIunRUz7Y z4Y_`grS8Y}dFJ%CjaKZNR_%|tbSW7r8B+V>2e(J7i@h+x7^R44d)(DMf;$hYUGDBG zwx-teI;^xlc|20PKU|O^;u1|N`?O2cMvT+_-c;T7Sx zkCj|N{*0{M9HSLm@PFp>&un8+yOm}$*FGz@jOYN>^skUH|K#5lg%bFRBqF?0&npilIT3B;%Dzv4fe>(2qx#Fw42&audhi= zS=$g|0V8^DWJL!a&L~YHtN=*BZ=%0IZ6;anP%$onP4;N;Dj{8xllZ>B>lCw`jibwh zn>J`+dDS+Km=LowcY9>}xpSoujEN?U(fR&8D1%|BhY` z&N4sW?s$&2a7Eo$`TQ2F60*awM6^eCh;oyG252Q zEIQ5A1hd{iW7hdwBam%;_rq=ziz2$+QEQA+cJ;tEcI19rozBRu<;`^hF05+spTjMNBZCwdjVA z<<$JEbcU&7PVP~x+v?P-8;d={6V3|Y?O4hl%b*kH`EnQ1O zrr7H8aoGb-4J2P4T4K3*BiI9t&u;tu;E4UUt>Y*+<3pDcS5WXRGmJARV>*{cPI*-p~6No!Ya5i(t3T<=v}Hb8{9Q}g;)V@Uy$;;C!Q# z$Lc|P&xD^U=I@-3)l+ELMho+LkVq%9?C$88U9N(HfR8e1!^q`$$}+7%Bz(M?_vMtU z*-_~znO;F=gyW8tEOvF74It-BB!`dE^eFNSBMq}xr-XwZ^eW&n)7@ji`$4+%+n}B7 zeqZsvm;wGbT027YSlMxlVgc~!T@T@s#m7=-L)uDJr-`?NcFLXG>W0aQa(dF(5o2SC znP=~4a^jefqyx3p^^ZC;DC!;%P?>lr-2pZ8o-T~XM8;V~=m&Cq-+8ObYo{#u0AT(! zar)*h1z?$H{I&kq@F1>~HLa{6{IJsI8_KBhR7PGHbs+H}+AE7f0K&7BW!L6=5c~x# z{H|H>9qL8yri&mY{6`9>v}cfXvPoqpg%1b7map8_a! zEv{kJh#q%CR<2Y3E349dN(U;piVFKeVJf0MrHu$VuYzWEOs1Og#at!Ffn8g9=89@j zL&ro!>fCoD4jN32$Gd8cf5(g9jgefDuS4CNgds)m-gaKYTk&-7hx8WUzk6<5W%y@- zO(xn_6F=WM;T~XU%|_n<{qtPrjNfi-4Ecqr|MWCCEzK>~QqCr49I8+o;x6p&OZ;Aa zc_jR8fTEDH7brRA1D181Wr$&xf#x4$zrMQmC;-4!53m{2ImBG9?BJY9i!!Ni7xA0f zv?cd`abh69#lr{)wN$#^ujm{?&pPAd*)q6^%klvFo6BtmTPt^n*!ULv|2(BFrK5x3 z6D30gb19KoEjnf`yc&770?!p&`kkJk`gs!p38 zZmeEqGCsa+zJd5Ke>;lpnv{=`CX)9Cu3m8@6-T-%64>qG8 z^0eN*=JY7x&>1h6=T-+k+*k~*o=qlpM$95|!5{h9M9PO_%u`I9Aq%F8tx{^KEB<_s z&rBcGkI-s-OPwHf)K%A~&NYR6bR_v_EJY;28VW9b$UWtO{N$i+NDeAqLVSY($(KiW zF^!1VDaz{pL*P_r(nk3?K;XQ0U!lr@_@Fb}gw28w2G=0+?4UQA^l{7&BRAi)Y zd^unHJB&WXpl*W?=o(j_a5REl2&34$yc$T|&?>IQ8B=Z__)^y04sW5YuH8|D|72%` z;7+V6dnLJ!yPHb5Qj-&hOG1z{LA?*9nCcgY74a2799e-7*U&Qe=8@^BJ>q+bwmCYX zNlmiwj{zx*YeQCO%%-Pmcegu5{acym2vX?0SF1R!x?3rs9HsQ3JRvX1AAfLqTS&N>Jx0A>pya-29Qn^UJ)Q?uTE5HT#l0d&9cc~ z{MTc)%hb!_W`!;i8E{sM|Cd@@`d&>i<#|SZJUt7G>Ur}=dSfRoZ_^4wq>oKZF)Qj@ zRx7_XP%|KO4Y8$K1~fFMyj>m?@|c6!!6cs`Yg|=l1sD!rLCyK6A{9>Eno;%nVf6K$&d3+ColJvw3b9FI0;Xx4DFhWj3H9I3+p4S>t<7~ia7I))8Sk8Tq{hFh)4HH zCU#ab_EuoZ$3tv79L0xyZX})nKvf`R%`6CcwTGuXM!YMuH|ADZJMwS7zGQyNnq~-p zWodUF{F7*Li_o5h_2PI~b+>I1{9|%T*k47zhbDwU9EZwpFmDosm=5o4xN?DwK=WXEd@2S2wBeO86T5vo?T-p&rLCgw?h=~h z`{9Fxa&OdIxt|ioa%%`$+{10%K-&z6H*Or7<3d#Fo6Q%?W#CQ;nSWlq9G5kgK`;)X z0U?2kct@zOfrup71=F-z1{I*3ii=bL8AcVEpU?D?6!xw4H83OOwLv17P{z#Sk3t$s z?5NX37I%c0K7mlU7iRQB}g>AqW4(Z*9H zh(w_Q!5;F%st$H5fE45pu#qggdd}CH6^S4Y?W5ESI&}j1%t*O~p+p*1TDG1BOTE4tu ztQ@p_tBP5NB{{DWD6cE0p!-?NA!_`?t2ga#0WQ!&Dm33@MvD0>me=)V{mn19>K?F( z$^Vl?%WcwJ12yB;qG>8{=Wd_22>)PF(ct`D)85cnY!fI?uaOw#vFSu1qUVHhl+!e< zqpnQ<3f>XgFbBZm3R%X`WUd7uM8#TkL0-iNZ@c*1uan;>I^`-AXrgiV@2LNF(xwXw z56hR7_zin<`md+w#PXgaVBpJY7E&q`pZd3&p_%!5l9)eN6J?XtZ<7k_9pY-E07nwp zL*xv@0VKb-e-Ki>8rx@OUmaeIZ?U@hv%T(F>Lb_o3=&(Io$+oZB^iwsrD|?iJDk~( zLDUlre$X))OIfvB516lj`o7|K9iRxCqondZG?`f9cOx!M?+=%BsK=-ezcNL;nF3Y> zdBKDO1{Msd8N?Db$dNG(BAY6Dz_{R1gcW8c&A9F3FiCiben9R_ zg!fOmnuAe0Is3?Q<2~&bkUHNm2?TO4T5V~SgUNV$!N~f@vlI83HDRGk;RGB6Fa*bjY@R`Z&iih*987RbID(AnO?r5cU+|c8=+G) zUibRoX6NKlEa#8?{{)?N>o!hFt_2mlkpK+l3XK3q%5(^6gSmI7;oE{o{cu7E49EaA zGn6|@Eoc*aK?7a z#P?*MRs42h<1VO02kmMn)Aia~hWaIQ#d0oXRhtv_bNQ|ALek(yY;Ols#*5P!|;G)krrPILv@PM&wqLVGp}0L+80jnP*S^w=0a* z8peE?G=^~-4lDYU>qe%Lbg+_rw|{d*|8Ic4V!zDOM9+-F0r8bB3zojmw~f)hsyXYO{82$AM)<&e(fRyyv$$PaN21$dpuKgR zdo#>!DJwg)hfmC7$X7Gd^@ZU-oMew)S{UUUN1FHfzQ5E-maKn>WD25%`~idzd>rxZ zWJw)PyFw{;#7V$@cXt=J^+!+@Gu?8@!IMId_X*kkCn$aD+rK(V9{!Rgv>;Hd)q>sd z z@~cR$s==g1WU>RX7XFQk{_gOwCoZUt$CR(984UtB_(23}_eJ=K87MD^acLO^^3B001AYY|Wh4e-_{+ZHCG zAHx;u>v}RA5mqKbSx&yhMUPbQzu~cU{fd?s|s{HF$fC` zp2707=t!#0IZ*3Ir=f_PW5Dzi%UYHawcUEAhsUq8k}2dRGaPzbSz6ugx~&)~TVNNX z-DVX0;&HMk^J#B23_!r=o;Gc6W>W+}cJPx~+Cy8-(01ugInUz|`O$65_ezv&K%0DC zYsnYssBRB=RU<{b`R9*)_0*`7Us`55^rp)`R%@xP5hp5%x|d38)F0#kt{`{= z&JvU{TfD#ZQk5~t*T!C1zV0j&;i#6QW7;(nrt&#~+xC=80)dh|=6mS+ zc2i`3Z=tO*qd8Xv36tj@LufQ(4dV2p^hoGNcTLFYV62?ZM@vD|sb0I3YJ|$KbWDoT z`b}<&8vB%KkrlLmaZf)fzPQ6{vmREDQA3#N!i)D5WMJv%0>xt0 zOI;%FqA5XhMdp6WlaKOLSC-xo4i7cKh!$R$meL<7cp8i8HnlFnGMm$5kKFK&&`qTa ze>rLc2x7l$fx^zGDtRXDHiL`*q9Sq(Zak$}iq; zPF|qu-@Z4QzJD|(`dYw9C@hbVV4ZArVHKCF4|SVR;wk*2hRXHFui|oeHZV85s!u#b zw&EO@3Zy@432?d^PNh!ah+;0N#Pv0plSqEIQ5&3G_(D1J?W5>;7N5++H)R z8suN}Fa|U6kBc^30~J$f{5~y;ek&NXD!=G^%i+grA+$9B61>(`&kat7*8KYC+-^%v z1+r|(QIW45$~w(ZLFa{cyGDv%9d7p+xGYi8=K9X0({Ma^Y@@l|hN{u($8AkSnc>@S znw=9R6T2bMt@v#dxLoeT9K0vrBxoF34QAz8^Tp=&HJ5dn zooYEDd=MIy7?yiRTQe&c@fp@R|4a-^w~Dym&eQL4){XN|{oI89Ru}ajv~*XQ_HD8= zys>EY(f51m*9tWuLE$aaRDa+8^ssmX#>U+j2T2g$srEi** zg=&{6lF`wPR>sWHKRt;`GF zn)syo6KSjcT3qHiHiU7!g>vvKf^|o_=?ZAFR=)bY7;$b>Q(4m^hcDC#>V9v0TbNFL zntl`tW#BqL3LQ07fJqnS=c%12_la{)pb%bHvLYxZmk%)aQ2~(0iMN4k3U$$dY-)zl zQahVrEvV(K4U;=zdAk=!_(0C&$XM-G_6ymMffQGOIrpzPV;Jjm$F0rtth>ud>mMRp z!&Xt1ed2@zfDhH2%*fU*&Sm!+fwYyR&o6@=jOP4vh~QIp4N62ZOJa>oOq;ePt3v$R z?LhHF&and}@Z}b@V>e+3-Cr@n19@tfll)j&2G7CnF5#)X%dD-lJn|Cs%=;YjI8F~h z5HOX1&Ay#0MatAv*6-}2>)EaZ&=W~$Lz}rqn!7mb70A zvfIkj{EPqjAA8sU^UJ2cn}ag0JFDn1YqhYCZaDEFwuM~Oc0s@{Sr89zP`dMLtkaRk zr)&Npc2kex=Ka&oy)MHKk3Vlb-eim}IOdzya^}Z28^=e8qXX7spvH%NNRlt!(m)TO7mZH(;KG4e*dZ3{}~ogw(#iIo%I3t_TkMuG?nfc+}jsAbvdx$8$@>p!qZIj^SAEuXj+{y|%U|qXV8~bGY~mda{?~Ppu#4;pMlMTKe|$* z6{r|!yEd!i_`fZW6e)Pk+9r%RzXL;~WCQLZ{(A^iV27Nmyjs`M@u5yA^SV;cFL^uL zlVvTcSlkEsen}=!VMOF+yl*N4?yJn1hEz;G-UPW$L=eiz_D$h_c}SQUU`v3W%z(NQ_mRj*L-s1V}>Fi@1XN z!JA-|t8y=G&OKHd0H3Toe;fs3mE0IFGp(<5pq#=8e~sRP0wCzNNQ-dLFvwHEf0!{L zHdvk6)ZBi5efI0%BjV(uylQ>`nF0RkjegF%Y4$>df*y#<8;@Y|k3yV+gtW(I9v|h0 z%LmxfS!vf58`rg-R{5?(WiLnL1?kd8ww-UIU>{!92E0^~L>oYw$dt6W!ED&o#Qju1 zr`wXX1d3ly;?GD?pkv-0V24S9zv!$a)d~O*nNtRuHyaPWV{~q2?;N?WF;45_t9Ro_ z;*Wc6c(2=;K`)a_sME%QxaW@~daTAT?Qs(c?z!o5-YggAi^RgRYNB6S=5nP zXh4W_Ip0a1k<`Ij8+RIP( zJLe@Iy19@B>*`TzK(>`fVk>ToO&$w&wA4Pne|@bUu%q&`m~6uDXRWi$!yZo=O~+kE zq6MjUo@(vM1`?$LgM~W~%k(30w#DS^Xkr24FwtbuJ$n@o@sUNh5V!(i=*dw{6a^jr z6a0}OS&<*u&{Lc)K)fFS)N3ld6&L?EKw%LVe%#K9z5a9cjpjf`Fy|8IOG3+i$7Arzyq;o7cI6wCU(7 zY03=osAw!QKt^>xD|2N0p0+0l1lq{9kGR}Ue9o9A1DiMDqMl7Jl zV;_>nSws&55|0}LkA0uhVlCHBAv*=)mPg4~i&H)|{V_yFkssq#1{g#d&03?B9~#d8 ztj;dtxm^J&TZnqLpB`54PNXy*^s$6MgD1eN4Q z$pzkk9DC<+^L`rY)&5r?U;eNotfFapQ?zi&%k1f=Rt-|-a1s7UtQ zc$kiP6IJ#MiZyH zm5I2?Hh&DtGP|~EWwsS-3zD(1s=7bD#!edCK{N{XUyjeWeS77^Gn+e8<9BF!p2$Ax zPc`w}7YG^n5XWH$-siH8^&eM><*UooM&8K+)ZD9yjL+ht zTAGNSvGS|g=K4rWH`f8_XWUwWVgZ>MgO+gAk(uU1E@C4Bc0RuZY{Krsr)@3Ic=aq; z-)zbL-X>S~Uiz0=$nnK2xCJ{)Pj3;Oq+MTew|^=A$q*;(Q0tk21-I4S_;4fM=Y}M5 z6|A!&u>l%V)YgY(PDm|Ju@56Va2!;eEBoB zi#E@ZeOB7&dE%eIri*;O%KBU%N~Q#@QU564otBEeM-W`vpu;ngB#efz&1+{<+f-BW zSQ!!QI%%wDGUCHW7pY=j$aQO+nE8`H^iVJEJsp)37e_fWn z-V5~a9V-T=HBwHGFQF9B#fz+^ib}_Mqj{Gd8`qVKYM)E&O7C#*B`IAbXUEN(qg%>= zC)uVH`R>D`Vo6`Pbi*OvDZb$EE~DoAwLiM?)4S)@ktnr}wN2EKYp zxo$C&lr*eY1O0C;=Cr}*i`bP$6}K5A{5C$wx{EF(mgTR+#uqX}GuNZ`L$*r?1PZ?5 zc>jOGDF2f(QK>-e!J2~$qU@Hr!VO!2H)rG_6qcI44+pG&h13GYS43oT$&L#Wp@;;) z?xBu!?zd-^#koDFCC>$^|9t-*3I`^D+CFhc`}Um5iw%{<05r^0>fd@X>r}{uhiAxl zHB#aJJOEX=Sf1Jip^OhnGY}E}X`J$HBi>ZrrfXqQ*!Smk&+ff&TIt@~OzVN;1W+E+ zHITq#d3Bt*Q<@uZy0P3$YXA&b(c84{UB3?qwj~a7#3OPdMoiNBd=9Obs<{a*>>M3y z4v6E_@dk-+=bFeT{on%(?fgt%oC-eSKIMFpcLdA?H%1a(N*l#0k;>%aCkhLT-D9(o z7x`NAZRUOz5y~qASp|lI!Z;NX*5Yg3LZb57KB+t`-ro2&QeL`*V3nRS3fF!-D-foL z6`escjbERZl{Ma-WIG-wYRA0%_763Ar=*=}XT9iYpeA9UbQB>T;Xm|jBJ1^kC;{W@ zpuFCo?su>Wk?Qs4mR?B zO&LCxBV&;n-&=#+>c6Fqm4TWyc}ToL>^~~r1K7bv)I}dYFp95{ma{=7sL6b0aaXk@ zjMkfY?NONNJ@nGS?^H8<;dx1HvD>p(+ihmIaqvpFC|oRDc;H28OF7(!h|~NJJ3<0N zeU5c0Z>X$TV2z2ld(388P;}a5r}kU7A%l z)*J=1{o&F&68W>Kbd#Zt9arGY+C~pIgkz(d#*r5K_X2il_I4=k5rkJTb;mak!U}2U z8x%0QmvzpkQ>VUh4LwoX%@#?gf6bG=c^Sp6y?xI^iI-(D`X}+gBNU547}nga=vuTc zP4g*wztt*xfL55$k}$^h@{gUC0nWw5_Cj)<94U%;sPi8f8-aQ;nag?R6l&Q}4)S3B_WeT2%$F-Be7BO`=c)?_D1 zo$9P1uG)0U9b3v8{%P4>A?S8X>&ePidDTI>TNXgkeYz(9T5>l0G?)?8Tkpx5u>WWf zm^(&P%km`Vf>AKMkZ*Xdda2}@Mef7tb^su}jTyy%{@fm^7xc#br+#cvGx7HYOwFr^ zucVMqx;#{|$Mf3Cr58-A*(wgwkCk#H)m9gy{0fpg2j*Ko4m7WZU>KTBCGj?)4pzR< zo1yf&&PTX6B&Sb4@gEgKff*onEh6bQ{w!Z4*ejVEI7&w`H||$1AG^Iso-4O7KX0Nho3r$egX-E5!#cBe}w*)yhl8P|YXg9cg&C{RfTT%?w3~(jQAK3vN^-<}`I>;xSoU-s|9K ze2%IoRh*b-nqE}Qy5K9kJUGonxf%_44)RJwJETyWD=n?f#Ac28zRL7KNQhrNigqiY z-yKd@mbeIgf1=Jj1U@!yZ8nnjejbz*i?%!)lR6-CpX%7m)}kuGTHM_4>Z^jD=5I~V|zUm1eX-KK%KjWuQk$b&-&sNh$a?R`@A`QkOl zCgzh3l>5C%6z+5oalS+qO&iXNT4Ym}Gy6>Z{gY>J`sMe}(Cq7#8{eEfTV@wi7Kh>% znb{#*!`KWu#S@EIz4xj4F~igwxTY0sUZ7daO|B%rwjI4Z5}k-v>c%Q-hr))t9MhjV zvL-S<&9K@&^%~7kI_AUe@(;&E9U#jFejD}E_Lals#REOl^>}-i$SXf6719@4;ZJTmlh;lDMX|7B17kHIA5(M74vW#RdvdF$Q*c45V| z{W9Y%^TVlE8+S--mmJUHX+{SPdMF?Wb%#8-%~;`p1iVh!J-^9feI|Pmf88<-TU+#l z>fTT~!_|*|RASxzjun~DzRJ<+oD~P2(M3Xt#ZA3EU5=No=A8L%FRXL8+K(7-KOU{h zT`BcW-_4}_DZ`lM#J|qF+Y`HWJgN*>y$i#Za@Kmic1APHT~78o-?ey8s}&C8W*-Z~ zo8Q_uMn|3resD*YH-D{yoZ_Wgrx%zTmP~GbwFH*&@E~?7VOVcMyH=u0~D-erb z;O%U|{g~0*QP@Hc5fCCHA}6|Wl*3?qGnO!YGPa29n;va!RKVAqIXc2!eOyoKO=Sct zuAFuf+|K&uaww^+_u%Gwi6>w?C2+5~^Wge!OUC!;=tatiddHEe;+@@rX5e3`!pbGx znI&yV{*T}_U4z#g>+o-0he7av@;d%U z?P|-Bo(}HxNrr-ihL7#P0nC1Zt?x}J5PDzf8x)na%CjQG>M`NFL*JtShQt^RCQ8vA zVo#ASE1poV(%{0Ee=1w>bkJIVOzJ0lMGC+lIT0y}tO(o&>)Vfd-6g;Sy-H~jE}$P% zPa^)e=zFr-IT4ADPuulNTA$`7$%}IDcfqzA-Sjm#GeKAoZyzq1ScJmagNmQj57p(n zJhJxmEjc>jH$fCA48KZ1vp?8%(B4Laibv)ND@`f`Y0~7?8;Km=rFpzv4NcJ^OAXtL z5Ge!x72!Nzwyt0^ma(_^yzqTy6vecW`fr7}a{Cw}RWR3cd66riIy@j%Yik+m!vX}@ zg;o=kYX+M1#^)D%G>USXynTb21yuo)p;N^Z*Sg*&Hxy$FLarcB(X?96}co8e=tlnljW*hw(Y7s1S!27)Uc}( zaR+a@&zqD&o;5@rMyQj_A}AY@K(k8UY*F7Ut|AE&UrXzK3|Y^ezIHt&yz1VG0_EO^ z%bSG{*4gbW^Oz|FY4xXl zu?K<1Myv2I0bkS<$XdE2r>NwK8-Vfz!y-k`$6}@){`e*3*e2lOU+058Z>zt+2Hxa- ztL0$clf2qSmm*&Unh#i4R&!13Z@#&j)1-emK5mibWMZ~)l(;axl*)>|N$ME_%zmS3 zRhWcUU$`kaZ!fkNN>2^9LL#N!4y2Mfcnl+}Us?C+U3%6e1Q#K@Er-WUu z2wM1deKJu}AbS0ktR0(&il0+?+3cE;R6YLL8png4KePaMwJAsI11ihYFsKRe$#C{_ zDLHCdN2ytGk*Bhrz`zI%=pcTK~NYq+fv8#Uw>c%m$`xsSB9h`dbf`T;ah- zM@v@<{yDTC2SMv!$`r2THQ zg9JGzbBLl_$eFFKai8I7RiOVk9Wvi{d(k1hy#G?DE1@uPqe-npeta_79vverc<=FTt>(&+|ZlpJi5Uqax{} zQ&VH{D%4SnaDfrj?H(!iv~4~K8s!wZ^87?m1mM(9C+k7Sb|`Xg&>B@=*b0N|ucq^s zXN$XPoG8xs$)xipkPcAlz}$mVNPgetBi1p;sq*92peK_Dns6E$MGIhBS{gM#%6Qe( zyzS}o_zzb$B$ll6LjidSD00&JTQB>}m;op6+|e=f6}cwG4p7JuUB+P4P2keb5xLuM z>$z3l$@q8$t}e8p1x#9Qk80|8?3*KXnu7i&_h9;8%Pw4YYKwpf&gEeVd3yH?t)=YM zzHz@{Q|$g?Cnwl}JQe7I=Mv#xj6*Yu?O6y4C6E9S51s(hn);y(x*_AcFsUq&ofW$j zNv+j}2a5pyV`D?Af6$x$KrImJ*@ho^7%1ovip^TDaWkc)NMU9t+x z1ffU9X}SO|VPon1pRb{EUb{v>HV9-td((o5(f(N$k(>i%+L9o~go>*MpTQr=BvcEI(RXSA%yNA!GUF zlSIs%Inrz4x7XRf@-{#B--DS?*218r@Aeeicju*x~fu$GLK}yDAyX}AVE78>t_b@n2t{QdY zeEX-ek3JQ>&w10%>SKBo%DQD?y0dJ9Kvnwp4o4mY4hMFy)+`9Iw%x7v#WXl)X*f3=s+j86iD|>Qgmg6n^1i-uw-5XK)t!7LH z`u~`T9bSXB!;5?uak%dJ;eVTn+Z)btZl3L5YXEH6=6>hvNB2cjxg>p`h{>}LvSb%i zR@o)d0YGu#mU6EpvsrjJfF?eGxE1c-OI6ZkgvB65(&W4lrV+c@ZL79tl&&qY=Z()<11{@oLf(P-<)+X zM~Nla>+4T+>ry=OKolaot!Ws_hEas6(qdT@dN6U4We(nFXaH>)3UODpr2$o+GIjOk zEt5MGF)=eWF%V%c?KcXip+GzxQu1yF7?F|=&M_%Q(%u{nV&Y%RSQ^3rYCw_)RMO?I zNp}-iu8P2k=FBx(8agaGlsRzi&K&~>-B5p(KgHZK%f{226P(}|^^cZ?**24Pl)i%Q z%K0sDI#@m+esq+DRJJOtv8Mf5^J8BlX%3ghat-&YF7_X{SyR7eBFf#NE%grwi4S9$ za3x5p(Y@>xbYdZ@UB?7dKXDdle%}fHpYA)q$$Mv?B{Sel7VmvRGF8&xcwNrUQ>~+U zVI&P@;KtvTZ?ZposdipBbZRnm!%Z%JcyN5-xZS$v>-oCxS>!JU;cdeSy_ckIRuqGR zTK85}A--sz%;+?#le=8WQ$X9)`gosTo@nLoNNZfra-i3jwL&4L+Pv+Pn@9VCDH;sDchYO+i#m~!?Pf4}zj zkp2+*Ud3JCevTRxm(9f2zIV`GdJ&w{cqbo(x<*4DOWFDV2-GjWx?*(r+0Vs_*Z<=& ziISoEO!5q~ah z`-*hR27xfOqK?{HQJ)Gnz}I`ee1T=7qsA=}35Xj?xgH48xM6fn=u9-IAUrXDfE$QU`BZ{P_K zD143=MYT)~cy7Ti&smSBwz1A!CEw$XC(C>f;ZZKiW8&~37D7eT`5kli&qpKsca$$F z)YT2URv=}*4gbw)?D_SU`@{SMq>16>OHA3LUJ9Pw<>1S6hXPK2(=bP9xf_S`;n64{o-fc?S zlqN`cO{thfg*Lf5B_IooH}@M3&RuOr!>fruC{#m!@8|dc1t3UlI)O1O%e{vdkUhGbAZET$#uF!YXa=6N% z=#o@=Qk7E)bzocn6GZJMvM-Y`k$gGpTA|=*J3mlUgfd5J3;glGull8fG(#jRRGZT+ zX6eWTTNIZq?EDWSnULE+dXMuna17wpU*K@uJJbW$p~9tLnv%r&a$zjmx0l#9HOB{x z)QGJQ+ax?F+IFFGJSJPQ!U{M}EYme3V21>kz$v^Dd?OMaK1-AGHqgZ@p}*(W_!wo` zx@a-gkv6wLTQz1M+n;rL97O@UeL=txT<8q<8A-;Hs=w=@#57&)& zaa;iB7P!Wy^^icqv|dvQ z5V0{A20p=4L}22CIKFZ>q}-jDUQ2H-95fy9y>faq-Rk#lX<-WLxA$`nhJ=ktZqbI` z8aW&uOIq^f-aU1$^xjG%EhoR2>FySi6rr4bMEU+Q9e$7)Lvp2eEUbN8qO>F<*7_c> zD7TSn4I;yJ&Y)5Awd_lKorD%UV?q-Z=S`9P&0JZyj+pHPb^cd!Q^UJk#F9JXEbMhG zl#1xS8=}3x(PZK~&A2q~V{sA6tnA*Hrle|uYui!NICnyuY3ou9f|v6uLzzV>-rGu{Bux zQT=l=U0QrB>ezihZqtAG*JAgTBv)h{;pwNRo1cSFQ=}a&E5i>ZombC|I8v{zC7Ah> zv|+|m+|Uit?a_`AF`2y8qFNT_K$Qw@z8hrxm1}H(jU=`yu(?F(8iW73bIj;P-@;A- z^#pR^wpfq&0`Ebq`MIT1K_%b0U{(NVn6e^74h_R@dVbhE%6c?~r~*Fu;(9Ny3V zJP{vs)9qo0@=;ygWu0Vs6ieNhjk2N#?@s?z7OV5ONm~)qM|NON_`REzG*<`k1HGexgGyZR~!jx;@z)?!bcZ1Jc}=zRA1{+{PK-`_v?xzE`@_jYz&*ZY1YTnll;XMWo**P(weUns~+24B8gRO9mE ztO<%S9-31(AU31*6h}=$|GSy}AWjGnd=50@I6TiJC0v*He=SCC@DFdrel4GCgn~qt zGu^_xrIJ5>@Um6JOprfvNV^huXS0M`opvvq;Vo(qV=?b*}s#@ z+05x=pD~JKBzeCcU{jSKQPAV1#EjJn-}UK4n`d*-ZN@#O2*1uwt_SxHwV~wzY3gTVLhs@;E5ir$ zlk-h%ET1>2Nj~?gG}5FPoaAc%<^ts_A^&DVaywJq?__7ZQ{3opf}Rp|7+_rRP_+$d zZpgXHEh9O8mM5BY@f%w}C28SDaPWBc0?gqVortjEqU{jxT^J zpN|r+j)vSex(x<1e@*PrL_B`NXF2AR7K*ANR~mC!>SCH)0I0bLMzus`dH} z=A8QZ zGpxMAy%qM;#OXCoM)ho7)Kc7U4!vu*({(PIzA=$c6AHdZZw%rOFC5!*Z^44KFFtx6 zQy)4sVoO9P&C@q>WibRnSB2EEe9v>n3)(&#(@Oqd>)x|Ia_=VRC**Hpf3bqT#1%Hm z_jaZkh{ssdKB>eg@oxmX|l|46bcs&Blbdowg^iCf6!B4Bp zYdiXE#<=j08EU!8mwha{rW=ZZfT^2;OBfAnePS^A$xFAkx2e?XDo?PN0G&p!8YqV~ z%Xlpy|4K%?pn!)YdK=`3nvsZh7^XZefxQn@w<{g~LD~{aV($$VqNRO*V|TN){c0|- zW$}R}zKkHLKkKHJ!l$CX-tk|SGjU4!eO`_%0vdjO^j@*&O##gCNzYp!*O8)A>ULfo zQ4#jUIurh@2X{9!MOeX%v8I$yb7|&juR3$jIh^VW|Ox=t1RIRI5wx3*8Ysr6yi#^W1sa<~(uvU7%spR=<=3TBCVe<;dpWQ3L5d8?$)*vBb(T?~uD^|;PoWYDw#K5TXLDboR_!6oLFb(;OHeEm8 zXbK4@!N@C$i4s|{#YL7;2Q2^c(Genx>>>2>);qmKv&nG8MwDe>*Q5lroiC84h;g(8 zguAwB{<`dl*eMGiYC7&6jKVpq)(%`Wzpi)Kw*QEc1hu76&?4Q_y+T#qnR^0GfA4}0 ze1FiU-X2SPmAm^>{TcT zX{)y?=I(!ZbE!WFwLfhinMVpYDEjR*^hDQQCC8vxfLe6%?{$$-mpvW-kxS?IAC)7xv2T!i1o{bMP-&= zOF5lkR${Rzp6F|bG+~t(-xwC>a2M%cvZW8+)kS6~ofI0`vPs~dC)@nlPOE)nW;8Vz z<6eBec=mcscIV78AP2U*+IdGFoV-{pwrBz9D7$k^u>A)Wb~36M`|!`reW{tp;3c6?Z?+ z7aDc?PCdH*YaK&75<&0l`B6(s5~x&D`Q5?SVUf$}2T`&Ku+#5^hb~IV0&q}I#9a>JvW{OxdJf;t82mt zqgKN_%;WqI`ORe6@|N%5u7Y?5YzOXTE=mMAwE_iNo}<)8v@EWL=4M=fa!dW|N|$r> z9iJI9nGZ~=cny;NMF;dJwB!c;D$3fuXjl7v+gsD{S*o*u-L3OspUX2(wCn@8D*BQI1b;)T>(k-4a8}?Mo^@lyGtPdMWml+u-LtXj zS=ejMe)Q?^_l82Lpi+2D(DFF$(D+#@)E>WTDz_rwstx`i zMgrHz$F%2;CA^Le+OCHV4Tl=F&|I1vVz6HH-AGP`K81@jq5J{C8~0h0jp;&9$$Wn^ z4$oq&OLJ*(1z8g_=6&{mH!j7@y*}QP7lQPN0PSGHb^p}N%@(INv#h&;2`hzy+||Ao z-v9FeMcbzS^^-{^5gu^JVUQg`mG@yyZLXiI@BnHi%I^EmhAzdxg>M0x??Pru z7Z?DH@3jXX)7bK!CGD5o>m_Iz4YE9CztX^w<%r&g06qRwaWW<9<45yJavEi-Yxc4O z&wu&fHa}5YF1HD6CORPcb4SvkG%d?;5~(-KnjhapfBuR!A{ppEY+vFunMf`z%+Q$c z0E~d2()HCsg^<>^B&M&rFtYv*);i6Ax<7?0U1{N9YQ!f=ddYShFXKgKe(!Pf`a@1Y zY&#^R`dpG1wZB*8a!N%}%K@e5@P-bpRO|nIicYR~meW^2sEtdtzXt}`-@gT7AMKO} z+E%$q^%9fJiILTc{gq|NqPr_e8DFkQ>`$^K_JIBnX>WI=jPTZnsci4j-#4B|b>BV= z1!KM&0OUohxuhgmgs1)sI~IGZAx!BZ`(P0AwFwc9IoZ{ zQq73Tb*$n~&mml1YI3-yD=RI#)cr?y@cd2rr%hTElcXde zm>zkj6VYd7XVKI%zMDQAc#W?6d^cdYx4R^`I>u(!gD*1Vk3-!Z%k{)HoMvvyf?eGOZM#Q`F{AZyN)ZvUCb53D#m<+W>M z07|mk%rJ3|f6|!#%f5jN<-nZq(f%9b345*^uFATQ+Q%~6%G5ssVYJulaz#|7$FD|| z@;9aeIa29h%?1}@<-}osm=A?}oFYaf-ttNyvt<;>-YF(AnneGDI{~Dvw-DWiYcUq{5RQSkFfvbGlcy;o`%4yY^f>Ev&+ti z=39>!ff&G=%?!}zpZQu-7=u}=nCCv)~UEpyhX}i8cZpYC9=;P+h0cpW=8AKr988N5B7^erZP~+$AIXE*8ScDzv_2Xt7)={ku*WikS}t z#(T9$$ci#C5Naq7Mlr|=?RP`|`V6IKRBDxg{+i8kE4fQmQtLEHhnIHa37Y`l9W=Ft z>8@LOmpG;7Th2)7o_Tff)TkZ9p$=4LCi^VhLI>U^m~Cq_=dTX){%U@h8hh`6X-L_; zC~cf|C5IJ_00yFv-@^q=Bzn9OndvylEXEeQg!%J29gVX$htdvHcFJXm9-<{l7TtC6 zfiKbCA=UN14(BOZ*SzH&x!B$%<)(s_M-Zd3dAFB_Zxq}z%%8FV-O7_e&qPH z8J9#ja5$Ds`e{?wps90U{mH>!g0p-^Flpr`6a~ zkHZhqx3r#2Z-*g+JI3ts(!3u5BQU|By!;n1Fg+;#b-cQy$Ddg^$xD;Q?mt5?P zZjjjxAa}NrLQx(ofG4wc)b1Uiic)HSIYKBJg3KhFB&zsL(CYlTHQke0dW8~U&Za(P zhX(w>2YBhY3U=>x6ZLvXaI3mYu%?yQ}m-)fV4Dj%4_n>7!^^&?33( zs=Iw_(vUS&!O*&w;y$7$nvF1eVe`H&f22HARLHI=bD4q6Ni@47&uPQtZ!YoH(SCHV zlM#c@{dsGSECbiIF%YGO*I_#b^!h=jJI(RheKTh$aa^o-W~Y{?OK#roGlP1ZOhIl% z53!sPJDnNY8M*?;33G;$XD;;6e8xJEgZHdm7MX}mLXS=NA%aJ`{Y|M-&Vp-6PaM}J z*TO7bbE6%?P)SWt?Lq4{!xeGt;r{t|HX#b8$3y-$LAI{8f;F}+g})iYTYDQCv^0!9 z`OQL9hs0mDuI17mf4hCS<(Z;(Q5&A~NxA9TE{2fU(n8wP$|6Jng={{3=w=_7>8;oZ zNLk1e7|&R?0sBJ&SMfsEcPiH-l*gq#&2T7(lhV8p^7BI(XrXT*Z)dJTcWhJH=h))- z&da`@A4$Idkci&BMFW5SgI_^Yg=ABNAe-}v-#0YH3qDgOV-yaTj zk;V<3Ed@dF6~~ppI6MXWK4wANFv+FK)?@&fljfDI0b37TT$oRN;W%4(GpR9dv>O;? zQnzqqJbXu&teyCcob|;`yMZ1D=6IrC(_W zp4W^qwp}JZI`gP#CUB-=;pFG`0Yt34m zu(OceK)IWQOP=6Mlbzx*(SjiGDhUNeU!QzejQZV1JcQn{M$% z1xXpXo3Mk+`Wg!&#k{YV=b?Vm1_Yp3>Mp=hYvTYCWj}Dr39SdPj+OvD%aZ`kYRQ{r zI?xOc5~yjkyu!(-T*de#+OjES@JdIvS7CD!Z~Wb5)-b`Iz;} z+31}9o0lTMXcIKto0@$(^hEpkO=C@c0`o+k9j>_b zxYJQcp#)au2&kn!5MP)rg{T@J_C7!?!&(hLq~AVeTJ&n`j|NM#iu@tIZ3IbSi8Uqq z8yQJMo*fSF=_H&7z!lfFc&!76sZb_WA_FQ`JLo5mi77N$P^qnQ(fa3%VyzEWJ~C!? z6`83;0@$hU^$_hegCkF{j$|yVq=Hlb{zN=9k#t4dUA@b(XvZi5)yPQ-Shv`3JyjAS z;+?Zt8yY;QGMMTm{r3CI?e@<@*2>k)WjJahrzwYG{0mTOT|MF)6=Lpr%d)o6fWd>* zHglQuK4qx530s9jrM!W(m`I646~mzTm-RY+C0LgTAE|q5HMeTG+ITG85^07|%}O<* z_!?hbv?U@6>3!nN0`x`<>FM>DnGX{Z5^?n(0 z4Yp;fck=HdMnA-R$v(lZ8sp-1i?(Nq19pt(vnvvQONG)*)O|16bSp)_jN|!cl=vWa z@WC@741Es{H3#p9G-oDt2 z-0VjmQMB8(Um<(dJToMU90ezs(N?C^*d&5DD0yK4pRCpR;r z;TNGu6qa{rEjP8(9Ba0PGr(k@$uUupJc=!nOZzhim*o z$qpZ{O@vz`F;jj&40_S#-(juq;c+G5Hn`tptD9BuF3}91b%0ITueFM39TfI^$d;0% z=VeqUA2hy_H*&P`-^f%+y-c%1NWESNwO7AnJegkf-fH96$O z1Uz+}jbfPoI>vAzND+C)nyTXjukvz&U)jO@9G&qOs`Ji9S2&>W?aEpFdogLNuf)1B?{Qv|;ipq2nClCXoj!cyfq}WkjF!>I?^romI z)NLtp!@Kl{dIn~R70n0zfU)nQ?-WM}>PL)h0O8?L3?lJ8Qj0+46++oiEy_(^IP<4* zfx69=!Du}IoWXi#W5gtcO&)0b0l|b^jHbVKL36J8R;sKki)t~;EddpGr|U`sQ;=sv zhQcHEU)^nInYbzyrWhROalfyu%NL6~S)XhOz>?2vqx>sy*M`ZpShzjYa}#nwn8K1n z*6z}3?Lb@tHsiQ*&u&Y)u0Ie`y<8+$P~S+0X&Fu) zv4+usF?XcRvgi#8WV=GtgY2md!lKm_U#-`6+M29>wL8ZIHDGisfjS!CjeV1idgcTnDSnw;baFf`s@ZLv75{eQ zdvtAv{Kw)7isLU5_) zK!Eltj_9HT{I?m-q8NR>>iaiXTUg*e=6YMjM;bF!PoUkg)H zadwakQoaw_W>(KGHp3TAqCMkVEA*OJ2+2Qd$u~X-JkG+b=GStML4n`Rxw6cTr1&V+ ze-qR}p#q-JDPniiLnRK|w{1DSiI%*9rP*Lkns1b`a3TNw@8?7HQ&be1%Gxs9?%0vc z{fVZbhBllWR>aC1pUoS*C_3-;eJ`@~G{iKbtrBje z-0Lf=ANL(UG;Pyvy|`Kw-74XsYa!YZ#B^9^odRl^rb29?orbPt$gjcQiO8PQv0C>< zIrMXlt@Y$@a&4Dw#qm(({2*W@TOEa{V18f=mb&i&x^` zhoAKoJF48-Dv5Qs)5*|S7?o(M zIjOQM-nJMun5j`#Q?SyZHje#al&F_Dxw0T=abfD@!8@iIQU2sD|G-&Cr}(NfFy|=N zm_yI%IjPvBM5x!yHZ^vFQ7jmhe=QQDKOlLRB4bS%Dit=RG(W4qZc#s3!PsGM^5D&n z!QzyRo+2-;(Ta1HA)T-h9`(`!D#j?aBu8QTCcV;o$~~np=A7A+)bxPI0|_;63%VS1 zzVhGU?eSw0If^-J@U2*vX{<~b2+OZlCk|cbkG{iO^8Epr2-N%jpltngT_D$C#+!f6 zsw+s)dBMAk|HO5wS(lx3j}I^&|H{_~7j`b#@?_TE45y7a5gH)$|OhjX;?ZGpeDf8sRo(+xW z*eUzJHa5pj0pJaZDsD}M*bLm=<-Pb~4-U|(Rb!ULUy#cbro6XJ)8QnWf2Xx3)> zu#bmUz*`6YqY)0sP|xj7hc|*#v)#`8rBq3!537vln<)o)v8GUt zm4hb@auE4$vM`3EI9FY~8qlQNibam=$eXq2%XvA^&$$2>JW;_aoI z%vn880de?o!G1B9gVR9w;bcd+-gZT$WjUd-k?oK82TyU|ert5HQqx$y!(!#Gk5ZXg zh?!yAsZ~ZWAd=?86GfGTw0R`suGiUg++-@-nIKnBwtQd@K#8b~`sY2%r`b%t#0jL9 zUAw%^K&^@JHlSlN+4yD(m+`|08@VkqgcG6e!H3s z3`vg`E==rw5ZYdW$dgrA*&H4W2x%kj_Y+pWWg$zK!gC4xVX_#8eMAbu3iz{B9O6R5 ztV}kr^z<7p#%r;*bL}9_X6VoZl3gdswsf>)HK$woj~y?fa5CpOn1c@9plEvA`~%qx z+ZZ-vDSN#x3<$#T+6`5O<=6>+cb$?ITeo4l&w|d$RQzHd1Li^3lvQXe?C-UAjzAn1 z)#VRWs3)5v9JVMA*~10nMm$ssu5}hXn#x7C>$4j!qwff=Wea4Si7Df1^30yhuR6#K zta%ignIHGS>2hq+jV{){A)Ms2v%{wjBsPc~P7~Hv8>4M3Ss@nR`2J+5u?8u#ISZ_% z+6>j=63>QycrfLxRBXihd+H?hzzZ9o;4Hw&$%Nf2pfEJ_{C$O4$4nW!mC9eu7MCw9t&50gK-C$vR9m zxO6rPhizB1c`Teagj1(FmlLcJmlYY<|Do2FDSHNXqaFK8D_Xgig8bL?ux+geM}Xsb z9Jnoh{xqi2^R+|qKH~QZI5G3aPJnM(Be>q`usXTht^fA5;3HJ#@2ly zoFN7lHIf+~o5cEEt(4I>^Jk2C3y5bIE!@M|u(spI^9J^$)}Yd+M zSH<5)-jh4rBj$5)vhIWH1K2%@W51>SY`T+HK&qqMYF2NT`pnwOWzlRS$X9LB#v z2QHM>kXenCk&&~Q9M-PKeCLmbfxfwct&|xXT$1aJaSD0i^@p&WAVtY%RSaJ~G9Xb1 zd!Dl&WOCvkz49>m4>vepW-8aRyil8rOU6Gh4&RrIaT;C{veuP}QcW@C&RiQN8O{E_ zJSnl14$^xRvFcLZljJWTZ5kf;XkO4_-J1E-+uMjSV_+HA}miqARJA27gv2j6&~RYx1-Y|t^};L`y597b4bP53{k`{H2X-6UTow?Wp3lK@`VeJ0uH1X)LUL}(Sl2LgNCiiEf)l4vd0Bo zd9&-H(|e{>K}OvAk0M&G*6xi9(#dA9yBTju4fLv28a3$Eym%d^mQ*mGIM-1wrU1LQ zot3dEv8wF2R*|EZ&58xoJ!9p@+;3|N?}j^gjS)9f836T{vgB-{e*Qf?b`yMj`~23= z1V)05zseSV|1n?m^e;6Ml9_5RF-Vfr4`x{iBuT<``ayfmx*j{gE@Q04nyPN|om^98 za!u}7%dljb-j6J2n|+|s-;6Odi2LZl$VBAu z3(bfCG?-rB82U6Lt>!&UbxnkhjZtbe-$w`M`Wq>4yS02=n-Gwd=sH?V zs0g+tIbEp35%lKAR6iRPJwAo6%lq4|7ZORap-(dHGrk}c=uJGDzzYfbyUx?gtm+FWA{aomLEPVX5xt#G1 z4?COXRf-&Awn#HZ;jEX~!i4psQ1-fZ;K5g{$-=olQW^N^zv2Tcao9|~^C(Y4Vle97 zePg7(xhE;b^Iw;l;uh}+>8R)SmV|g})~P5(4KhTIK|5+n6rrf)X$=Zu_19qBc6WJ$ zfL);Iee8{5I}nO=Wnp7>0Ms8!Haq_`e3277(>|DeowVH!u+C`V?+)nwkr@#Jf`!(9 z%WbxI8kjv~i5Zsj$;qL+Qe&UG=e&ev3GfIiue2{aeZ7fv!bnMuYZxt17n= zK2K<`POwZPykJEs3TH3?wKo`-%B9j^X7u{5LUxFBOp+W&c`oB1zsHngLSp2w+$}vU zMkvlJAA7T(V6PlUgs(4z7dGuVp+2I9 zau-@&y}2V&xM9cmfUn|x19DppJXz@@5(h?h=?)6l`!Uu-V-jtQSMm896p&FC98Juy zI@i~u=$&GANXd`y@@qEtS1J}%h?}&xt}^J2DB=?7T{9ym6$65orbEzSDhQKMRR&W` z!F12((VTp3eu}4f5N4vd8#UGD^j!fqFQV;ps4kNtOt}j)Dp5GkLgC?+( z&;D|?o|FqsUfl9>p`lMbclF)o8*ABxQ;kl$U*Q{tF73_-H`)?f53?+u0~`!+sf(-Q zH=Fs`GM~1fy2+4e7%@`9?({A*=EFT!S$b8y%iI1vB zItU?;{ANMearV*1Zx*aJu5BY%?C}++`+Clvj&b%xIY9Wrl>z(DCsUdOYm8n&+pjjm{+HI;Q`}8s3K}3=KtO30#h>k*Fz2h&}eHHHBseZTD>tFWNxU@QuduG)Z31!9KTPkme6#k-vG~m3>zi9s$z~mVQ+g@dOx3;N z58@gVWC#8cKmC!U`Km7>nqgq8KHH&5KPx4KPxg+qX`|}%C2~MHBuc02y}MDwm%m5E zN(KQHo@sCs$qrhK>maD%L&?lLH%69CF4+-T1z)l7uB8WjqwgO=VT#j&*7NsXfJb#x zMy1VzIR<_kN(zU22;yYTB}S#!QCvRVvvNG=#Jj+L;Xz`t!zxmjUCM<3@G@ zErv{c_;jbbm%k#+E)Y48Ttnt#=Tq!Tb}ZT5!t#if1IJV(RC(x z`r~kVskimEG>B?y=0(NTgmJX-ue>kf?B6M|ulJ=hN&#>FHB?)>nrQwyqz=@O#=mZy zG(L%;Ig_Cku)A$Xi+jE8ct=&~c>Z}0=Wi^$^nvSnJ+G@FvO=-Ddt^p`#v4VY+IiZfW8USz z2uG*47t1hvwQdfk+_|r8rv%6ch{Lvz=UM-CdPPx;!e;PA9x4Y*d(B%hT@&BlNX{3#me0nHflFU*-+B}bhjG-B0 zuFM=+ z61h){K<7q=&mao`oJ{nz7!YbxxQF#l_6uUWI8uvxCVX@wkM@ON4L{koA@>Nnn)M&R zXsoqm=0mj16d~xbZ~hY)qp?-2C%-7!Zn~wJb#u8f-q3cnJ)L^w>;g*zsDTO1+727; zves?+&d~ltf+h3f_yr@H&52l`vu2BYn{-dZnRu&OKJMQ17_m|p%d8`PaZgBVho3b0 z!dR|#p&3ZNH`EDW&`B*7U1!(c7s<)-3YrtTYQ;Nk`EJu)zqlABDUvAf`8pU^MHY3> z3X<)49`-UaP7%GQD!FGVC|rROmRRL%TgwB>gc@LTaxGBHWqeBMUOL0l{VzAXvjrT~ z)54V-tTJsV0=BuFpPjj7`$ zcjyik|J`h73Se)FvbTT*H+E(cgSv}YmAgk_sr7SYUZ4GyplmJ&ucXUdNL+~Cb(W>SC5ddg|?j|Z(>I90l` zrHt~sgjDulH_A5)NLH_;xcV-q_(&iZJvJ9($>%dgLs#L$^vkK$U+ejkLQwKgu%PB7 zkBW^0+v&5RSZ~c4nzY(HtY~zgZZcz_Z{w&Rk0Tq0m=M&>{DQ`keNBaYvpvK=`NxO` zUk*=qFNb~19giis3Qpv8EV)qfop7?&`OX%Ds`-HO-{56Nmlv6}+d{&7@$@2JdotH0 z?0-$9*zhXb%Qo6x>taQMilr`P6QxJ2c-0Cao?$(8Q+JwSL)CQdhh47RfOT_5OeY<) z-^MN5_$g_u2!59^`^5e4*@s8|v=Tezr&S?)P}HL!9dMO)Q>j%cad72&W7krtv(ZhI z)3_0mzkIQZEx$9~8K{g5_erNjTp3u6kcHb_C>+#3f;4t}cwQ^$q`C+gZu6 zln&;bIGfBgIBT*8F37H^TvlHneYQaSTO-)Z3~55cdSIDnJy=lS?x;9nL0fM(dTI`g zW?lVG9=~&gVS3b;+U5G5L#!PRIP~^A*^XHl)vDy4t#D*&U-CAj?LqkdM<^YRNR_R+ z(EaBHOH|DaQ%)<8l#;bTYm=tyq%|5(A6p!P|ml0+>K3a=3H_|^`!qO?h% z*sC``wp3~h2-pVy?A`80+PR{NWiq0*1KoMuz)kl~$by&!TWq{UQfpu4%vb$C#xcZ7 zsZLqK8WW`~OZ9uVa(+@?- za4VR8V(BAV0IF}^awA7EK?|i5V<LI; zI&xt)QkD8lA!j32?c0O(;QrrVwOP^f3NFkXV%zrZj#a#l!HrRB`g8Akbe*#Q2qZrw z3!UPwiH|@g>{U4)v9v5qRQT(}&b-Zh^JAG)iAP$$Ay9AJy6-{x?6S9!Ib5>X;h`E! z#?k28J9+PBh*%E?J`*&|wh1Q2-+Y?hnhyMvuY?RIx%O3MatRO`D_?|_<4YqS z_$3oHAiX?w&2(hnbjl&fd{(e_5Y~`olU+VbAbdBmeOYuPvu7+Ul}hJR#(W6>mrGQ1 zY(n0Fy^~LFAs>_U!D3-Rz@e#^>O_Q+$es#v@@IV`%e@!RzqoIHWdGtu$i_FhSE!{Y zghT2a7RSm8Y z!%s8d(=~{$*F7K258^)Z%BhF>)K{gC{kgOXX0E!Vq1QvQ8S!tdWk?4LlY3IoVNe}! zcjM0b>_a%o>`VCW9T5w;Fz+a%*{JqLpzLklEu(Ur;0pG{O>}PaJcA9qbY)YbZ%-L@4O(G-d+3b@VhZxbywYSlq z*sYF@N|Lzs)MV(8H5I%b#TVh%;>YgtUuwF8!_g~5%&)?Cax}ghve=n=Qs$o(o-v>w zHWB2brZv2pEW}OVrKV@&&+&1k?ftsGd)8$@UWaD87&1BNXDeVLaADso7T$6y3`uwJ zg>UDrXuU8n_xf0oix|grTLnL&qj+4a=}%S%CfUhUQ8$WaWw{02vou`*6o3=6q!5M- zXfMq|$IM$t)NY+00AqkW)RY(bkGwA*H>@XnXv(bF?0^2zZC^KJG#$a7>x#h4&;vw? zbf;e^k&(3h5dL98^!(2JDoziXL1g2|7Ru{y6owaK^<)_ z^2V42y}-UObzIB}Jkc`l5qN4y%gxL{VT_wbDh-qRW4{rvi31!0$(i`cdMW1j7G;vJ z0D#*_g?3b#0x~dNbV81xf+bR?_(Ts9^5@y8U$W@8G(MI)RtYK3=5wG$s)8Yxdzbp6 zKTDX1TEDZB3$#m~QwWtY1g-H|P;zh`K>dEr5VRQ#)(I-b{xlesSj1b@9u3I&mTN(x+z{k$J6)DD>rQ}74QAst+4_AJ`dVpHPPaWO909g5bwVq)udbGMT!oWA;3k}LJQ zt-lI;rE|qQ^N}p2S5#=Zb|xX&Z(|tY6fS-u@ZTecL>5-#iz!wA2YvvyB0IMvJmv9)xW$*`QE#kRkZaKEdd<22`L=O{@@WE?>b%GBr%-~)Nu;O@ zUMdzO0E;>rIF0L05pu_S$RF)R-kFDeY!;ydp~EX}9J`;7hxK%?<(VxU{8S($N1o?f z5AC;kCKV2HwN78IVN4mS@qSv)xztnA^Fq8oV!8uMVQkEv(K}3crb0)waBB0yvSikz=hp-;9eq25WhB; zZ2XW2Ud*}Bqd$GODsMNzV2alvxnIpS^Xm?af7-d%m2MWsS727z{A|C@a(r!nA@4tD z*V)2El!1V;X#*Whu9JSjxI;$`3b0f+54MG?1<6pl>aECq_d-ymvy-PfMkSwi;SSsg<@bHI}r8&~( z1Mhwiw|6VkD?AK|K5iVi<_}A-%#|;z2+w)bNutIv(zIA4qxW?la1=(+gK0GF^VBNa}sy<98JHr zk1j8V4Xm4lMQ`kntW+!EC|bW0%M^vDJlFRTuk?+wwp4V?GXUrYe)R{Je%BFx#npSpv7V8?jb;j(()~h0PmQMJS^gic-ZHG| zKW_itXe1Q@sR1e>(jB9vBn9bi5a}E_1VIJqu2BNgU6LYQqr02YBS-!ByN~O7aNSS# zWRJebKKtyw^Zh!{^Q9x%iR}~u6E$w%G6(Jsfn@$EinSW*7JRLJTeY-X>Ubz{W0W$} zgiq=reY^K%dq6%w(*;@Z)4qg#-W(tQgh$7s*NVc+u2INwzD1g0_rqzT(?vDDsnqV? zR5Aw2dP#p&|CT~f;SV6^b`!r4Yt~GcW=w>K2~oS)NDqr=k`)Ko%w5>89FuW@hDH$B zFXm~m%-EL0DY3@kshv%o>%ZusVzz}O_h#(b_ea73QqUT`p#l&t3teOvt=PF!YOz5myEyGkwby!7|^YZ zD=H-8l=0imD+{}-?c&x6(Ki^`(R`23J8>dWVER*;1Qg@+PtajUg5 zntUpa-=1=Ahyrp%Y^Q>ApMl>RlQ(7N9{MS<{KzOQc`En5iOT6yc+$tD3+h{q(pL^J z(cIz-z;7FGPrBVYK(f!CipShQ{k691_G>npr@P6n)YQ*k7$HBWC3o>Z3Pw4q)l{2- zC}7%ZhNbxBA}N1{c($!e$xN_F;b!l+a;t27^bc%in$j53}d9rUc@Ah@GbE z2J!(kJCMx%LJV)WW`0QiMOZ(XvUE;=PU@RCPf8)qu`5ad zq4ZGgo{{qDjHIL_rWG!_TWi$8nCzKf^|g~in8_ew=v?0c9Jk*`Q_OFcb|}OZqUny( zte;9r_N|TFyn@tR6SSGDC>PPp7I$xGc43`USY5RLStG7;!T%7xOcrhbIUt;6_+JO! z#vg+m(maRfdGLCmhL}-=cAq{*i)VtNTF~@ahivP>nB?Fhz3t2>ep?U(E)$NKp$L+C z4+w>(0(g69H?GXOVy95zoz5^qx7Ydfu3lBf1CX|HishLx9BW|tKbm(6k9#$@(P~DN z%ah)IlRPO;vyZOYu3A0TzEa8u_2B}3O5SY7PoM>ZPchr2Ce9e=(c zvU;S!=iuWZn`vp2{sA z1@4C1W3&nl*3EIat}`K$s7{E4hP=3k(zjQmTS*i42#U;HmhIQ>fF-`8QbX`X5hfiX z)YUqQkGWP(#3n=!Pf(lQ zxrYh3&S%Ek5^>RyCb|a=J{3GORVI2Q2~SZixf1slMgvHgs4%jq%VL;^c=~(qKfkEn zVMfR5ZDH@2r>U-!;X;l=!SHjkCKtFA;!=@oCyC8FkWT0R4P?q%n?^0Y$39$$zdgfr z_s@Z$K2Fd;-`k7t z?X=d&X~gWN1;|;V^@A@R`4*l#T(zpBru zMi0@RH|SyY{JQrps*TyBw5IFXsU}4Z zS5HeJUNVa6^_=6$eCruHwz^dOr)som`oUw0FA2L>F!u8~;yqCsb~GxPK0Q;CXN$hFmcXJ3w^=jkJW* zv`~vsN`8WDLjNhuUs!@#4zhry*Yw#OQt$qXAb^7@QarwRFR@m>u=kJPcf2A@?U-nO z!|vh|-2u|8&-&nNpu-D{1>)sO0=^Y^x*JoikNmvc<1fD9Ex`@)S98;2a5{1iXR_6o z9bDD>@V*uZtN=#yo$DoKC1V>NDVz_y7nt_!SDZ)_v|k$GiEwv0BdL8w5BJz zWWT=`{P(fF>y!1S2n>G8Fi!82E}4_rLG^TMu~XXnTKxum<35D(T@>H~`CW(&k(nb>DoP?<<24o8VQ;3FSt+D(3V zzQHR#J=7sy=!hlE(1uua>B(HO&dx6Ewy~Kyb-*`QwZX7QXI(C!j;2rB!+}aqEU+J% z{1GeE$z8d20o?mBd@uIu1Jm<0m_tL=LCg!dME~;FkNTosW||gHHeC2C4a9Y|_W{{j zIAUp(XWi4egwkw^a_pBOv!=XwX`aP-N*0xcvSKtzXp6@73-(6*?8pN^O1PCPq^6_C zuwmbQ1w%#6zWwl+UYlvS5tykfn?Z&VqGEZdiBKbitQ9D1@cyPWD8L$6WI#L|?A3^} zFc(ILCT@u&B4tQH4r2t+INOx&8|=LAfxw>E?{+niVh=!bvXTIS~FIr@>!7PqM#B`7lJdV0d& zQ^7XLi{zFG7O+#TXAQMhAEE^GN4_82;u)*_N&f;#Co%pGtRgqJ zfuVoT?G+kbUdbkn~BHqB3$%l7+RZgQpa0Tr(O^e zIV(PqS|1kcqms03RjgX{vsN6k-5XM>U958{!_4kAjl)tL`qnPD+-^r)m&<)rTl0;S7pYaIf;5w z;3I4v6mLB*P2>fehiNTnHMddIEoFOlQ%}|vn7qf-z$2yZ{v7+YN2H&hDK#~(%V_0y zmr?lPA1~ASMo%s3XAFM+7GOtc1;tUuKxIte?ZS$LF~`YLMq49KUh=#=+I0qRzUj$Q z_%VTUcen>E%sk`S`A-2BVx)c+w5s3!6p<+~nnf~;2c-g}jB9Q46oDRPPnUGZ24D6M`?% zunMNQBhzy!J2I?cADP~aY!cz<;0vh#IlXwc5SYOZ+@VowlV^*H1Uu0O)@yzO2toi0 z*#aF)huOM4G}Jw*r)H7a8(Uiew^wq0LoDZjpF7o_igw1GlmQ9u!>F1g<0F5RdPcJ_ zBDofsD;2b;)}NfQ_C zR|r3^hT3A5*O<`q20_5yFiYqpeM2ze$+=IJQ>wespOl_6Uar->wse*pd%RczYO!lQ z%72G@Z~ds;?Pto3_pUdhNz@npGVIs3yzqzPFJmG^MvPkS&ITvE+i#bwly^&At>opA zY!^Cb9*d5iPx=i<#^m?X?32qR=mVN`{OmxXml|*q)UNPGgsoGyyUggT2|bqG?~SsE z{LgP+=mrhVxX&T`?>Lfg8Z&u446RM5yp0uKP`#7vK4glDd%{ z?tjn9utK-DsHdrSfC29)t`;^n`47FkO427L9najFsha6_@=~^&T~oVkGHu#+YIiKe z+yBkpQh^8j&wnVuLRGVzkf>1frs863S{-y~@ECR1k67c7&Ee_lTZz595Lw62NI42$qL2zH!_3ldU+b?(6@8^~M9# zTXlVBL+C5}H2EnK=^u(%*fEfTz|J6~cg1^W$b$acdhKVQ;mE;?fVG2J%*>#H-z17? zUUsG*FWpi6k?VoE^)`V1a~@*zI+Pg1&sjb-WG_C8hv?LHUG#`bkAmQL55u2)%3b)1O*S(_gaSNEl)E@X z2X6h)>;(@to?&fA&T6QlMH|$z~9FNpo2$BY-Y#KiW%DTg~^v7 z728Rlv=S%!*T{p(=^Budfn#dQQu?{H*$bF<<@mtEw@vW(8_!C+v!Vu)xv#^N}~M~(S(!gb>$B)k>|Cb z=lf)*T^KKc+k{QUr&;O1lzd{~W^B)CcyDx=r@F`QXOMHoPRnoZYMdX;HAr>T0AmN) z@noh>9xIblyNi1KDS3{o4KL~GzLspp-`x!&+t>`A!(DBJ9j3Ct`vSpJ1N*BMpG7x? zYSKuU)3($WEHWpQ!~3YvN%G%OPu&?Fdt~ zMx#vG>dzuwqWL-?g4bBrVDWx}7f{KICbLtzG0g5g{a^?`r#prPW=kX`E4TTO20r0% z%m}d?=h<2KnXs)7mHZBc#<~6J`W=v4l;_QA5(s>b@lNN~{1oz}qhChUe^)V-toleS zk5btOqHw(S&*x-Z!vqEKI0I{Hy?(3U?4$U@^5E_w=_Yk55$kh zQ0BUxow~%!DpzQo`>SPOQ5M0Qu82y7>4>fmO1jVa|E89^KNsiRZTX3mybQW7UEQY) zUk%SouKnt;_1%5MV6UQwZLl4~JkR)=&(jbQK~7e}{9-|Eg37OQG+VrC5XUii7}R`ym(-((@rk1Klf2(P; zi!DnhcKGR%Ih7tI=GDNSI!Ikxj(vmC|E)Y(uutapLvRA5>a!+8`%etf2tT6`Vt|>B zBu-t{^~>IAj)h4zoOxh=deRh95An%Q4H{uG+#BfmjWX2cSG;}M{qO>|{N%-QrH}C+ zZ`kyHeh2xzZ?HKy)8{X~{YNhDgLa$ta;iDZTFFQ!6&PJ>xOQ9l-~Xr*hws-vC;ykV zjTV1I=OfUY!A1 zF;cMEvF(0<19yN?FNyoU*ZV&t9FAvA)H=A3Qi7d4OANpEzGu%0j3;^V)#bma*W@5q7 zt$k7&A+ckodpXudROy<;2>K;V4BV3;BWV)oRC)7$af;*tVu)q50xVR6Z8@J~y#3sb zfri+?1H*Zr*ChXj=omF5y)P5Nj$?_-ZD0!ws9($y3iT1Q+tu|k#{8%KPRitE0RZj))$(>|j1cFjM0jBBdqA>Efd^Cp4Ob-;B} zmOkH}WT&~n+$bg_04jWwM0cY~nOK7Q$02FiJ^$B_=nu#KM7WJ)Oh07UZC)@)#^Xc5 z+Ru#IULy-fdNh4gr)_8Q#mu+9q0_u|)=PpcaXRwKkS7$glicqvM*_vCUan2Y31zyJr5E?bvcj)Wdl( z?BBTl@`s-nxuv0w=Kn4 z-PG8E1;qDid#8*gj{R2DNgfV$nmP5D&;Ct-(zEU(3+p~CCP>){{R=#wWPv3;>?*0d z=!8c5-o=m4wBH=ow=fIeEvy`2KML^hpSc$8l04eoryz+OKyMm^JH|C}Ujkyc{AB&tXU2C|t zw&HA-06Vp(lwTJdpL$2`2?iv>7GB3n%EIWY859O?{o_I>C>1NKM-O@PL#-Kq=K?#`_fYJtnF?iIyfD} z97E;4h^C3@{rD-;`L4fQp#!pV7hWM^Q};25+>FCbpuFb7)?EO1d>EW8AZyj<#;w5&1=4f2O|nd!)LJrrxVz>d3O!Besdq=Lcm_>3bOrd#RLr%?9|NefWOkKkN+yx+L6mf z^=+`r_4juqb~cOca*nLR#5XjRLY)jL8;0nonZ&@fThw==BxIncivU?mI$wErZ^miS zfl1)YQA+ZtfdT#w8+IAwvk}JN@?9}gvJQF?FlP)2l(IYe$w@Kt+e2aC2x2#>XpFAn zdKJu~SmjWEX?yu;#NP;9N<3d`e`YbDVf^xJ934zfWE=<|zL9_1guUw;qm_drQ^O;t zBOruO`v9n$5&!8|CTEU7)RoqD_>MyA?OG}%Qjvg=1d)auXJ z-cV|rCgf07>ujMBvdOGEBe_lfpfNz+N9Ctqhid!-w+x!XK4bMrj-2i)6Q-{}LI3EA z`baw1L2wM=!Q{RED0t;j{nV{2{ZZmSx>MK`$K z+l*3Rz(5Fw4Ca7sJ6aNPPkUauiVlj$$Mg9)9cE=glB9yHfh_%uvdH`pM^GE((yBB) z^D9DjX0PVB`ErgmV(i`*F3=2NziTX2Z`b0~7CyaE9nRE`a1uKD&juBiE<8;B}*)&0?xl+U^1b9-eihJ>W%Cg=m z_Tm$8rB=OCjoHdPz|Jbq#tg=;a;yl`Z>(u7lWdqKsWiN8-nKwTEj%#4lU-MD-)*q0 zu&v+*gk4y{V}aa}etYH{O=d~?B0@z3DOYF%22Mw!C;oLmRJ-)#*-odRW73GDOBO#+ zIHL>l*e8$;{1+M$Jz8os{~$EN(~sNQss0bygbgE1z*4a$-GY|mH(mzg+z{n65oaf% z{td@d0QJm=FK{KVr8Ax1R{W_Z0zEna7is{9_#mf{y<4(*JWnh zyTN39nrpHvO(R%{?THp25R-Qcb(8Op%@zF+*(Of%k~l3?P!$*ew)O@y2Fwf2 zMap^REBM%1mX$x{#UpMVqh~jmaPAnrtS2PuOK&sq8vTI!_PJIzy)T#$T9cE5Hb#T! z)`*xdXo=t%Cb?@7^h1yV`-mz4TrGXGE5c`Q>}^zFDt(SUn5D04gVh~Roi-=HivOXJ z80|;)ZIJs0-rP`8_~xHgkzgof%_m)0BhYS^b*q0#0?I^TlI;8;8uziP&N%5!JbTvb zdhr)rcM!Up(b{>j)_dm_RHS?MC5m_d1>T;33RSI1;d#mVG68L~BwVj2M$3PdyxhPr ze~jpC9E5ZZZ)5MGUTO97hUNn0|45$jnaW)C-iHX)4&Bq=?<(y5CE!w_Bp@7~H+#s% zG@A479rX7RTY3}u*ZN`dzSJ(wUe`E4qS?JnM={`5$0;gRNc3e?*6Gm7xZi^YfhZ#7 z^xRjW-3Kwy@>>?D15S0AB5;NM^n0-d!mUV6;#b82S28Kc~nc-doxxD zRd@W)qn6=f?&ASSAL$*iW0xzA)UkNUV)*cF*nc7l(b&AYTIPRLN&G~OVbW_qwKi?h zTiM6y>AlC>AG(En%V$ybEx(@ig8sY;I1e};zql+Aj7!JFJH(NE2o6$hXu9ZEE0}mZ zb4Dl6-CT*P=Hsg|AIk+HtIwlqmSsKU!n2l73ub;y~WcyhlU$04@4+y(Qc5H4x6{aOnd>jTcWWu2`aK#nu<&3xz~^ZyA;K_~JWX5;J|{zN}7 z3UvQJX}mq|#Y5Aon;9R}Z{?Ye_EV>Glp1doT8)y^_inadF_L__PB$)KIHHxgN%Jls z_-9UT%&S2MD4g38w5KfT(NDVTV6{?|!Fi<%$N`dW{O*z^20i@km9iTwC}qlU3g`SV zp4AFqQy$)ZuwQ&GC$z|q9m>m){bmWr11!b@|Lv6f?3TA`G zNc=7zZOV)93Mbj?xvK;%D>9#sCcV{Gzwe5}*9_4$?69c+dn4jxM8LqnC15|f8v@$I zn-qWL5C+(-eDQ;vcP-_gyn8C+JD`Ys{`(!fg_UP`be=xYAIpX$4`;q7MxRTT7}p@= znnf8JS>H8<#lQT#v+G^0*IZ6Z@_GyMG$F@_l=#rxf>D5+F2qFM&ya{RSPh@Gs|Jxr z5K9{_5pR{TTd}2zs_i!B0@et>eB>P!klPO=?IrhglMin{iTl+Akl`b-u2O{d*$1DD z|BW%Rfu}7Bazwx}WF*z4>Nk}n;r^wrVm&dw*KT0# zuT6i@y;ISZw$ZnPOsvQap1p*KdwurzkT1yBX9px z6msSjk>n*iEJWFDUqi~cXO6cwihgf4gd8!(ET#uE+}@CTG5<7M?)DPOz7-Y4na`Lh zmfj<1M>N#`^6-+s-uxZy&3y3wliIGfMZR35k}b_GIUV&brVB~7!guWDd8(NQPKJr+ z_V>~E@gKHmcPaJaN1<0w8rfItOg>X#9k8!*c5Hr?xOC6d-^Vdk-z8i60xcrI;87ob za!$s!zBnQBcKI(qZe!{by-vDG%$0jwlHckfd!k?C$)LL3Dgir$sd3tigrO9(GL9c4 zN$7oLg9c(UAjI3j79PU7uK$RHBPb*H?^s8ag~{I2i-vpF^Vpts>5SOcX{yu=k< zJ+xh^h_M}t{D~>%=<*IdzPyU~Au+r4uuJ}12lREEhRbM*t>}||=qs*CYL(h&9+}U% z1b^r27QleT(N42*%+Vm?61Zho^?E6yf~qtTLGAE9ALAQXX?7F3g%;y^YJT*+?-_H%*)E zV8TvHI**Wj`KwH3F6 zx~A;98q3})luVyX^W``8a+0Y0H^wYk?H3o;i| zltb9@v(xf~>}`EZb`>GKIcwp(&bvj0-FL!3Fg$h?QcQ0Ms5;Z1!oWFoJErY;z_5~g z%n1RJl6Q#CFs*=^P7{Fp*jNE*>;y*~mA&F46?>q6Z7k+(Z@PW;<5Do#87ON>ezRXv zF_z_%pA?One$&hjgzr+NvNjNQY6R_ajiA20yXX~l1?`O|Zv7h*0hv*ODrrC`JlR55 z(O`g!&+ZG`9zt=HH`y6O$?d;3q7yO~Y6gLhRlTnT6+S4%Z|H#a_0{f0b2UZ+fS)18 z*Pd0Qj>!`_py-Jy6Ms|QWod)|@8U+2$J>$RMdcCF~aBr^jd%5HDeYyMmL zx|wK`kLY5F`P>Kfv&}VsNvDs)TI$&U+Q)<}O(CAeeqVOuG@rq$fh17cfMmoF;##2>@m(xaNU%_03=vGpnk zG($ntUrhZ0gsK@A9kg{VO^(JpO8onV6iCYlb8?hLaQ3L=<6R}EItW>H5OTv9u`vv{ zwpR2P*?CAS_)lcXAV-TVYY2%~-g^VQh!n_QiA`kJ?Xw$rBXJ9y3>kUhFiLBdG1icY z&?9cxs_b95V0YG9QJat#(E(WwEVV&Wb~G8QJ>AAl7P2sh<7$;p?KTbRPpbVxwdy4Ez)%g#4^Gx^k}S-<`{jG4|pn*2T&2GT;zdS;L~ zN5A!zZ-A$bI0|(o4$z;UMGKaAOdu37(bS0>o#%Z}Mv-bnr^m^$$;JG6k5H@QT-%XE zpsnvhYQ=F>+y^g=Z~rsN1YO0FC(Mw%_m>TBQfpXdG8#}*dk>EfVTOF6{C!?*^Xb>ejiWp&Ft2x7O zJoEos_AEXV&{(NMd$wn;PQ3qzM#-vBaY|}%Nu>5cpqlYL?9IEko7T_>9kl{G*?Tr z0j@1iQ|5(b|KW)QRLc#L^uuQhi+UgL4F9hRUBENecMWOUN}kvZ*sx(DJ117l-`9_} z$EqD1V&$mifC90Vg*=0$>emZ@lUO7qXlX2-v0#ya)Au$y-6cSl-|#!X%i>^UxyT%F zgTsVLt^v3=!S^y9+rgdSI9p6E{7^tok6yJkyJ2t_WiJ5sY|PntJp zwOd4KwTzXn%0de?&~mH{C;ZoZT-m4H1UuNgc`B-t6){wU^+~?oHR_$tP+?XhJPRaomgg zkvsPcz`ub5nnm07c*U_U7dWjzlp+OA^VfRv(--*U$ak=J{3D`ljzR~f?td9%)R^v} zjv6NWVgu%VfgLZbxdsSO+5XE}bvQxmQYg(AiPntxDddWLD(|Nw-wQ|KSmm^gtCKQ| z;QD$w42*$%8PpZ`%xFWZ*IHkHv*z2adWHq~jpJUC6ipkR8JQ6Ee3L}eD0P$O{AZz| zxsq~Skx}tp|4|oNGeb^mWk3({aM%E@qn7yvS6Z)aA(Zt46KP3`m)O}utq>Oo!-ZD= zt;tydC3!m%XX$)_4T4)XZPUL(U7+_T>jCsmj1Wt-|63++y`li?c$~L7=tGyyM_#)LD!Xp>?Q42(ft*7%tZQDlOKDxUrcUzmkrr6=hKiZvQPT1ts za*24Lt?h?Gj7)+{pDOv=v}ppsXK239r)A4_c-m(Him8T6aR1V{gfQ9tIz(rg9@}V& zmz5LmKx!#NDi!+s)TO27jamD8`Q`0lnImN0Xr?J&%SfZSzsh8HtvljX z9=pmrXoit!izp6?>hqP(iYZ%3xFD89o|_O#w^24m2g*`Ls!~}BoQzLxg&Z{HIQ))D zZPN@2Y31u5Fg5;#^+$NA2+$9q`oS+F@*2=~kliIc!-PgltY?UTIiBBNuGWA}_Z#2R zIF_h&8|AVlX6_{{Y{~HhFRQFU9Ve@}l>oD62hzygYTmTnRT(hEkB3)swGEYycj$ZduF2q-Tyh|ITwEU**M&hwUt$UXApyA z7=f}=Lc}@r6?B|Zj%IR1(VINuhLogCMBuyoN}H<#_AknqRE?EQH)cs)PYB0jOQo(};7p~<+llb9f^ zMl6l*im6w6XD9N+QX;k9#lX3`2C(b3G}tEZS*e= z6b2sQZtR1dvWS!kbUcAfq@Gw@GD&hKco3`>C9YElNkvYl_J$wKVlxOqZJ@C4&}ihY zZ^(x+u`_rOD2D2WiY(h!3U;;Vt`41q13T<+L#Q|i!2N!lu|%mcnD=oQqH-1IvbT#R z{MC&dp1Y}+?>3ozC1Nnewo@eb#G(^AxuUg2I4XMiIDZW{#vp$!JB%P@#Tgrb18$;c zv)mi6^+3B|<_Rs^+f(YCNZ<3n^IgQ()f87|tl=b%@Yv3;LuH=n$QmAvoj*j*KW<>VUrHY zdp7;FzBhsxkX_OKfLd=xlp`vh?w&ma5ULL^x?GJVtCq)8RE^;Glo zgnLGiIY6JCB%pIJz#vL#L(XQ?`~C8zz?Lm z$eyunrf+8IG`PfmB+p=HgBs6KRmIl#SCE2QAw?FgCT8jVPw#duzx<#Od^ zi}FVe@HM2~f9;enc7mVCN)2)c;)0lVF!pJ_D+Vk~EEJED0|a~HZ&!G3}e%W#zW>?ry_}ZbZZe>b)8067z@dEj4av;Iey`_Fa$Pa$*hp^5ujx z*Ta(7@>F}4JJU`j>sd?rJ5Z(WfDBQ)$J=yAbRw`FVC3nch2w{d6r_D6DH z_e?Lusd0M%B>q&&?)Af;71Ymenl^6$+X`F&WKtP)Bi=4yL3x9h>^Zuo{IE|z(BkxX ziYsY!S4eVaVzM+UNx{Ic0#d)x>yo_YTG6}X;(FwrLppYoJnSy~i1t5EYCG^On3gIF zHo&aI`9w5HT_kYQlpXxQkw}dvzBFNsnWM0CT%W$2FXNQ)jEwg6k~}sJ#>rSVWgvLR zBP>e8nL6pcFZX2OA*QT0`Jqyxawe++%@Ql;#6N-`&n3hd_#NYIVV!hi)i55wyOkpL zKOb{x#sm5yL5m5^N;JWq04fsC((qExMY!s{+;0t`<}wb>T@ACuC{Qu}i|J=4UL-NO zP`J-&SBZNAuAVZCB>8G;uE%T4{)t|Bt@r{b1xW>7Wv==|`Px@|LxyCzv9k`L;M)1- zH2|rv`f8OFFhT%o0kDhwX1A2~uNB3OuVu{%QpRX@ak(#=eY#(YmT`9r}o-B zqO%WKGZ0Dcl+G3~#cMTDnn+W2l!G)RoD~_YS@o?dRa;*`4Oc0AV>9nV+QuYUe3D&X z&bTy~)hy#(bNM)`EPLwa@Th|5XQ_ zOp5dDLQwiXFVauQe5;E3_v&E_vjzGukIshL=Pc<-?fL6wPy*c^1y{g?=^KfY9ui8T zmMbJJ?07DoFzQ_l?sUMMXO3WI)sW@q*wgjl-BP-}^?QrmKc%u63-OYLsw z2c~M?BUk*Hh<&M&WhJK<8c`p^0yaH(Lii_eaP8vn=}2x`0B~XkezSqjCuBXsfYBP6 z;Puq@yZ{ns_@FX@ukc%mv+DL**62!Q-xSVs{#!v%&O+JNthY~W7!t_U^O=CBIi%MW z_!d(1V`nb6NyErQhLqI+DdU3 ziWsBajlLKLxk4B`-t;u)w^M!vFm-2BhD`}gu=aR;mUOZt;K1cChYcpU-hUv%#gyS& zI?%ux9KK^+SphtAULA*rPDUy#{FxQ$*1tjJNyGT*cx1+4>0{8zWqIn^tf9V$b#`Ct zL8~>=Wr{h;%F=8)QU}Kz;wk#!HA%B*>5B;ymX{Ct{i0zncFtq!w9$Eg?XZm~p_aH* zAu7kZ6iPk{lcZl=4hQ+Nj)eHM^Q(u{o;-JezP2m`Jvc=OS@bvn_ zjK)kYBOBaJ2&Bzu_zV$g9?p}t>3h$QH~+>YxF5>7rk51Z>dSjaUI$Ur&w}R$By9>ePz+ROT7e=35Sa1E4k74FU;5zo`leZ6TAPw#UTj^E7EK|T}E$tcv8vqul^ z%|HqjovBK0j7IAj7xV?bCh>k*=$5`@Ic9k~ebJa8A`KIvyZH|8QNgQ?-*s<;>(LK= z-w98EoJtI!Ub(3>U8Eu{7*4fw+&G7lC9=cYx6UG-X89q{c^p7~3~uFH2(^r$GSlrP zDZ7I&y8_1&U}w-qW$E6xX7I;oV_lBX=uB_l7(uv7u6L6bvStJhw5;PSwbjJfDo6U~ z>W)_I4K>WGU(9-_wQu(ZF3gE$$`Bdtt;A{-ePK!LGrjqdOzC_()(~~Ta`2S?_S*FM z)xK}W$t0rUt&`9EMHS2d2$h#S4l5*rsI)ypH)68LMNM2S>MlZNmbyh+Y5Onk`J8-w zPiqTJlH*a0RVuvu382YVxS#E(T>9|t@NkDGMw)G0||e)+<#Q&sEw zLK0eB1N5$*lJ~8TcevdS52sg`SG|F9slP7;i1CQtbXWlfAU>-HA>FXMz3>P=)HBkK zMXtLqqg+l2$(BboPyK(c-d|-)*@3YhAC6m`*g*mKaSNhqs|e3x=c4_pw1*Er{f0@$sxLy-z{| z!CSXskB1Hs4G)7t=UWe};SZ(P1*>dzZ7>>R zl;>L(lc5PBVIDr;F7Bmo>bzs@{WEw%of10KQmG#m>|ttB^!&kCYVjXKc)05~e+p42 z1r6Z74`}<1=AizChd20WCFx)vtlO|cB>-?AeYqLqUmRmY{MfW)KHBuMGhNsaSMpCj zCX%~CSlPe>48RMnp<05`kTYmxsh?kQvbUO4SIrsWQrwIk!0v8!r#DEKga^)dl>tob z9@YmA0$NVXQ(`pLA4raGaz}4ZDEqJKb%(` z3m?%<0=>fG*oaF<3Ek)nw(K3c{x<^OzCXkad?YK<=P-X;toX|m#LWE&UH00jIU8>W zlQTPi-OHJ&2OD&SK}U8e7d%zG6kw5bFF}9dU+{RgAm^f*rxJ{Fi`>%G<|gv^5}bQl zs5djLZt^g5ty%JWBz(c`4Nd(Zk0TP$x@Uwdi+V3u+$)e9=sZUuq>uYRB4Q+3fsbUoMH1N<@@Ijei?G8u~atm!cvW^O4A!f`s7)L4j$r zUzu@6M-@mo93H0@x$Q9|xCrn9-fXtey$8i6JiCq+pzmPb@s4wK8=FP{{`!k<4qy9IzBXFMJ@Xa^ut z4hq$JnQs!Y_giX-W_?-B%0kVT+%_+`hx(0{u%KyYC^Fh}Ty94L%;IcK%av(}BRsB7 z17pErB6|6qZozp#j7GVx!1KB$G40q{rnw=Nom0(f>2#}{y+zCB1o?%vT;XJ$A3dNb zzp>A>=0;-j*nio`EQ@!gw?3N_D@GQtW50dE=LUx5E!86O$23Qoi2c|oG4@JcjDH=u z`O~Zhcl-V#WI|$YvW^mzbIRG~p=ZYOS!+gF+?c>zuLevy(>%Z7tLPa);9I3SqX%Z) zdEs0EP!Y~b6vyNS*i|#A%e3BzLt;J}2ABQ;++Dn!Z*F@&J{^))V3+<0vof`=p{YrS zeQ3?Kn)OI5K-bkru0sq+ExI2eFsuwr|6@>d_I`K}|9oQF7yIPz3=Y5qvm6s|Y&rs~ zRMI5Qkb)Go*c5JYc=BZ-=T*3eVsd?XG)PHi>0hzevKR0C_4ci}UM0-37$ONQA2JIr z)~yTBmgxSTWHgBEz9y(MUV>=ADmsT`UXSJE7oA6fEWz%CNhR>+C13l(Dn3!|G*gF5 zOHVG%rCJZB`lUvTcCK23s(P-=8{jgT1K5BGgtPhQU-u%Es^?0nAqoY&FT{Lo?Xn50b= zHrSI#ws3v1qAp1*H>M2DGIqN=@`F0Pli`-??dlb;U$Us@?V-XA0*%1dc z#jobgj=cJC(=yDa^&F2JTUV`n_22dLhG4=Uq^zwK(mK>L*?mU5tiz-t?U``@&BlAw zrrfnfBYQd4;zL?FER`|ywN~dDL0v~ud41P!wh#Ren=kWW*mXrzYX$vyZ6LbXlbN4S z6+;;IP+V>g1Ng6h=7MayuBYD|<^N(iGV+{zXp3(&JkWlGNRGr6+rkQxot&GUD{D&n zAFb^O{72+$pA#jWQ?Q6>U#2`2NyKIMsz%$nnr$KwLnD&e<*=u*#g zl)!~cQuppCR#^=7Cc@}&foWry0GYR4CIK1;5$V@;EIu#O&p+K;9M|zXEDF8cl@^fUBTKz!b9o5^Hx-csN0GqV_+ZnLWR#YS4Bhw+9Ls$7-gcLXM zFaN>URLIf;xW4&EOMMR_rz8pu$)|4|$(fZJMU&3()DG->W-1Sfcz=iMSw;K7Q-G1p zr8hBxptu+m0S@aq!M{ZcVU^3~4E#4eva%pseecDI`>@W{f9m$f)W_(m55Ne1x!p^# z-7mEzaUMuS3XZq^UltSG!9O;`Z;06`%1NW>{liGii{rpzI9fffOY=Mss9UTdkWepL z;tl;B%=Ju3*bEU>nlj^!0oOm3;308)Xy`s7GfhEG)|LXb+G_9F+S2C}PjHA>dEw+| zWLl$%@9XmRv@tXuJvB?)rIjm5>T+1u9V8!)?{pm2CTJf{dX0NWO@08Ac!JXydXAng zINg81K~9Hd1Uu5!eaB%>P5^InBRF?9nF!6IrIXRZ00XJ6Z=&S2RzRas8XUc)mHaj3 zf)rHZ30gcT^e9wQ!3hh|K}#M?Zhfm0x&N5C5>JhfRpoh6auih-Qins9Gl3;`)&OY8dvuVY=0( zWzlqjG8HDO*V!6ZAbxrTu2m7DJjWDokGiK}mo*hHle`qE5N!@c?+mG7_rvfAyQ>+p zNceaZ;`DPwX>24PE9ixt36Qotc%gpVhpVAYA26lGD<8ZtgG(&((qVc%kctAw;a&-J z+RFT&`=kj_1ALn2`Ol&2(a+1S$Q~9L%*Bfb>m1D%k0Y1tso8Hk*pAyOgE3H{WTcoG zk;?d);}j?OqHd3&OWa}k#NMsp^@aS$>yJ5H_CYsA%)F4=&acqSPO0g5KYG*ZT=@90 zKbDUrS?9=%e+?wXLgjNtcX>Jdz9N(Atr&I~LQXTFD=&Mwiyij8do6U}h*ar#)-Y^8 zNfrfJx|yA$GjsPJg;QDGP0NN@;1%Dch2A*_x;{!HUgaX+C><~|z_QQJtNcCW|H5*%R9R6*+2i zHb}X+Gj+ypn~?%doed$dFKPz!La<)l^t3u|)DoMwlHe5*w1q@&u#_X5p)w|1V;I^(t9&fcuxn0wMi%S!p^tA^ha=k?|Vke&;$7z-k8FBJPyk3;hCk1EI zZdLz%|BLUMjk>uj=6&ovFI5lT(^e_)+u?>Ch3=i_zPN#Lwoj)QE1FAe6FPI(-s3V> z?l>F3irkOZLa75!GpB}*@g{glr)X-u&+414w=#b%&&(*|OzW@p#m9t$%wPc%DK7B+&P1DA<-i ziJ}+3MFeKWCv2>6(lx(vIzzv9zP&!}avxy=8SOhzqR7TPWMNequ+oxx)JiX-;a-V- zF#)id1&<$HlB9ubDNWM?AEfsesY^H!h6%zL+2x;1W#1=P4$O3v7)up>aGrpyW_cod zvsqB`gS}P%8WaXPaeqpqF7K;#zsc3P06iCD`K@0Xh}JSES^0Dwntq#a%_CHHwTr!~ z>>{|-wE4sLa}H}2McpRPJV7ZD*Cz?CiU-&zyfW^Igg}FN$NLh)mhNL4wxQ)G$*?_~7bN$X&hbJ}CYd?hUHQ8QZ{?QW3+jQv9~Rq(jDp^s!CyvYLnF%BPN?h#j5n^czHMYSdT=O^O^CZEnSWp% zh+WV85wNSboHpqy{wk@c+Hv(C+gj0e;=r1!k+BNfSS05{8P^1n+qj;T&Z;C^jug15 zWW1M<87(%&Y5ANs#dr`!?H1@2$l$oc#)e+pIHT z>GP^ihN~q8@SlL2+j*Z(B%0TETtK?)>=8)p=Z<5mE-airo%Lm$YvhLH&y&{WwA&k< zUo(3m%ZiI121v_pQ2}p!=O+B$&g#%i)E2q^+PiHJfcY=o-mEQ0-mJ>5ybAvN^jJvl z4YWMpzoV$N*6W|AU$-0}c6oH^e|g<$;D6S=LcN}TJ+$Yi4ad-;ZmNOe4VV8OoDSv| zI;xJkr6r=_R*~!F5>h`;_I~P%-I%zm-0iY8cnGd}(z{-1N&9F8hDVY_jD?MozEA0YO_({45!yFB zLH9a=-%hyHVsq7x@L1cVo!L}@n*BUw^J4;6qHjdJR)WFpR$so$T_Y8?IHU7ueaXKo zshU0j{1PCuP9>U(Px*9I^rFw6G78F%vNeE;9(!%K(uS)H#X+Pl=w5cegaoOdQ23FZ zat1uZN!;wJ1<;?{CcQ`LuChx2HX_p>2gLii-AXtwgx8idg`4pK;}O|yBamfs|7u`E zA;a}QU=G7nk1RwwcpR}XX#ARCg!3H$>McziM6z70PauFU>NZXdg*vF8jhRqJOx{-y z8!Xd`P{2?-3~w>vGIqZ_SI^`m7cv!kFds(SfTel1mnPwc^pr)4T%^U?fQahwvTT2l zqC{2*D%SDt7|wUAn~tggjYE_jk#bc-Av=)#czc~6nf*A%i{!CX?`%dD znPdHs;-KP#CPuoTN%!GUreUbmEBlbTkcUsaw?g&zB3BXrd>b6M06d{(kPV2 zNI^pSGo{54n*L;q zM8g7B4nt2#2}KO`_iX@py+rr@g~Sp@td;OWhB@&=IizMYi9-c>eN&N z;Jlpa^%AzQWAihe>J>HP(Ju*OD*St6=Qb|^{TRI8bVPd7Kzh3PtJQdJe}7jQl#;dyR1PXV^)Ls z3!eB(0`E=hpv9{!N`r5O+TYh&Z51yrsbciR+)8Q@7+RibhS4>+l{T@saE5NHHyVw& zJ9xkZjL--d^f%Erzq=CQr!xui@?aua{;A>AZ-KfYNiQjeMZHsB#pP7aZOmaA>uJ!Q zLSe&0@182uwEtfDJ!8xDC;lvl${}WUeMfNeyX-gDG-59eCH31xNOk{4Ud2#wsqmxq zgm2ta(++nl0&pwPjpc^eMWuY>-^JvQ31|y^#;Fk!X!V9Xud&>S{2N2Z3RFFMlilb+ zxfcXpvjzIc(h=V*3FF}k5jK~oa#i7HaT?s3#|PaAf6G0W|5G5TKY?5l(m!ceatXx_ zv}RK+pM1y%uJsb=10MrYWx*2`ZQOs%o>f&fUEO%o_YWdL*atxar>1?y_X`{vO#ARDpxJ#4(MbAD^)h4zrnxslReFSLm!AKg+qTsv5MQM4F9gq9iKO>RkTD|Z z)RU_#;Nz*qDhP@+ip%u*G;Ibh_w`VO3wE7|@S8tKo?f5A)YDuP=>mAqf%)5eDWGyk z06>Z6WEAU_5%nX#8z0#I)h71$OFTZT9Mj&2hfxxQwfP{QlCtMX`}BSmX4Hgd0?dE3 zf+czs81TAM6(ZZ+5wB4|%gE!qQoe|#K|oI^3e7YGSmhJQ(oPZ)_O}U~=_!okGQv;h ze3hY8W-K&U-*~=aqMg@QURVq!bld4A8Nj1~Ow#6j?z>BVWa1znEcQT#^tnB1lGF^p z8cu!q{`zo{4vNyUlCZd7T6bv-uqrk=T@j>tbEB@{BvyI{YjH%qT){?m|KmRm-68m% zCB2TmZX*%1Vn3y;;`xGNzzpFFPTmXT^C=yorAR@{AEKxL*XDpKvc(QVQ?u&sT8=|8 zCbcAYmDd5gv8_>*P`QgI_47wzEa_k?s}26`a2N3QTsL|(P)g#ICnVTqPZF74)_SqE z|HZNFY_i~#asBhbP%yvdMUCHkPYea`QMc4d#eZ&65I}Uh(=5-icduHEr}xhJP<>rw zRt9aFYww*hn6-%-o~M|Knh`6HK=U2;@KMaYFN&Cact=nQ<<=T(#p4!x-}2rO6Lt7t zgL5ZZvJ2bf$XX?l6Q7&BE;x2&>c#6RH1?!2*kmmIN2`PpyY^r-+}1DK;G}q#MbLKe z;xy5VI^HLkjwRo`aLe@PO7lRa+B1QGe9^StS83^Qq)Qp5buGgvjV8O;PtW>hE`w(> z4Xjd=2l&r)hyTv)S-`%1{3O}=zjTRqJ`5lma+b(OW6>-OIc_FTs zTq6mst}>8W0s6B6>w#=``x8c&amySNsa&N)l8IW4!D8M=PJvty38z{w_)ntSok7QO z_h{qc1vW#n)IP}qn0NbOC~f)y;=((m^>4P1vgNXQA^02QdMaH(`m#Kr?=8uN_tb{; zspwJ~4P;D&tp4AK=Yw?3t3D&o?uM-j5A2rXW#01ft%TpfpXSzo;>HG7p8XrKl1~2O z?pV3WLoM?WwU!&PITE|Ax=w_sa9evj3%1nH(fN|z^CUo6B3i5=23uj=y3T2$;VZYj z94U2{c_VuBl}>F==l@LBsM{{Wv~aHtD1^u_V6HS!pM^X3=1oZ5+|fm)Iz;>e`S>9| zl2U{$<9<80VV&3I*WfTKB`DRDZ23@fTc7$>X2GI^GfdS_%_`HlCj%%q+y;L&}K_m1peIpWjA1OtAjGi;?}KcQyN7e@n22e{dEdoHr~?I1?i;C z5Qb(}usP)5{+J(STLq!MmP~`z9Q0JYozvo~WfAL3y7&_$VcKlc80q2G<#DWAj!B>awRWq;|<`rOb)&)vsH9AAU0N zw({pqxbLx&Yu7i@kZ1yF0Z%d2M_XATF@(KsGLZXL3bxlByH!zpPcTjy8$a%iQY>i_ z&oQu>(TGPC=l_}dp{y?T$bZHA{k4wlmaO*&DH-l@746^>5n?Z@P)dW?>%8mG=Zb7C zdCk9)i|hjDpFSZ(VT*RrxYR;Pu!OnbGR|J5PF(D>rb<>M_V0V= z)&0s7MTE!b{O^uo`5}+h>m)FM%oN>tH@-921o||7F3T1f?}ghl`M{JK4!PKnSZtI; zY<3?CnA!~RI0sL~ZnW(a_Ull%Sx}fsV#g3_Vmt3o#Rhw-1SfcGZE?m6)S3-PPPaNN z&E}ha7$kU3hkEl_YF*na=8>kwigdGv;-1)WvY6Xv_MeTYxm#rMe#X)SPARu@D4-VJ zm40ZM^cggh znccmK8b6W-Z<+K?T-2&z8-!A3ebqnJo<>K%bBoNc(-1c|g6>=ehPNkd-(x<1K%HJ{ z-pq8oO^^+RRYR>pEtUS&e~e;muNYZ+!rhYi1hUc$&*h{%(4n8uZmeDLofs7YZ-abH z)i!i>pjnjV$?my`H8BE)ZQF$LWp77wgghi1k9@{pWSSx>z)#B_Uvo&vq)9TnragJn z%8&c6zwq(LkKT`#5m2>_Mvr%AzVv2l8Fs25W>P(mqv1PKi>qh&p>A>oc6qiK$z80G zvpQQ@nt;}23(e}BCnG5j4$I#YElEKC)^WqQDqdIY>ehKNnFmOETotqpQoV&4Sr?~Z z4d=FqcJd|7Rl4;hejUf<=*IkR6T(d^kv$@WPhx3& zyF}2E5`;ZHLNV?yP!)V+JKc-Ak(@^bWx@x`p&L+x?C@iIgNi=Y=!DiJ1Kdo|qN_6P z2PA}F1(Y1?aD%;JXg$T(9v?w0)ohAk37TbJ9nHV`R3u$>Bl zCj0vbu;4bbnD6xTRUlq$H*^tDa~{5Gu@4*t?k0+8<|f7Cor9GL zsl$rPh)6Cf@vbhGGYPT96_@bX(cQtFhuEiJX#IOsXnXIXyeoW}k!rrnl%4s~*PFl* zR`V6c#N^4!YceTBU-!C8m&{%8H~iz@bQ`1N$yG2+?J{acG`9tz`+Pg_{LW-JS16m0 zT^2TMaI9oIPxKy_at(?omxQCeaMpcg=C|klvK(i~D)pZBDtt3UBu|J!RG{p2HbfYl%e{)8`+85RH)C@;-0&KgXmCl*^ z#*(GA)FljaJ+(58*dZn!+6I#hhNNirUG-mYr(~0^G5Wg)FCGUG*hk z^|0*B5c|ehLp$P}T8=?YOnynq5i)3~#7U5EAi_!<=aqnuSJKO0^rSH%?`D=sGJF*n zg{6!j>ef0O2+}I@S%vHECFBKBdChu$E|}n?m>LiWr&k-B?NNmcVnnJ!dWzU_G}R*? zFlA_3B?as-sH|*XIs-DHmsYR**r*HE9>0ol;TqNzh|3RYobTPouvdK*Rdo^I0Y@rX z|Mb(N@*tn>{WzMwc;V3O`0c}0DALPZN*g@)Ea!X7w&>J{A8Ro8-!E)mbKBBncauNV zAiZ9b8J6LArI;Gg_1!2U<+iJu0)3>{4Wqg@m1BU$pUWM;kjB#;LNv*IqZdkDL{fjyhQ6>H)6DNoI$$lH_8 zf1w(mVDt2LY(6`{`cvQYrbn)Jyj)iyK3_k64TyR4W9%IF>DFQ+)i>3vqN5-)R;74e z_LR6LI@t6JS8}oS`9mqppsj~Gj#1@pGgm$d&y|LqRRCVjAC$uHqQmB9=|O9TQHPWh z{Xou!^Cn(4$KGKLH6MOdM#3XN53`MfJqgnZPzAhxtT8=Xw1n;-?59#`L`i}&r%1fs zu}v)wkfFBm{KwC&Tw@0{w^Nyj2f$+DKj?S`JxU9R2Vmk&(~&;nVhm0rJMXw)o|aAjDDAQ$}>L9btKmDrIM~F;`k`WB6T}1JyKWxHkKOmPNPjP;a0~R zhi@9H6fOhl*53Ub#ghIVA?*GmnDI_G)icNuVU*aK@q*g^t98i+LbTM!;%N8* z9P`iKsEKejw63az9(W~=1H~1K8u)N&Z#j7AK6by)JnnNLi0ZAl+Vla4{(qc|Mm!9eNOH1yPdiW zjR&TE#Qax(oiG28?f%6g*l1b|WWNs&)iBg~mNs%c@rw&q&3b8wmMZtPlAnJ+PpdWa4l8>)Mq%uAgOecikY}pv*rbA#3%XxIdO_D2a=E3U$A^N}uyn95_ zBg~uVdU^W^mS5(OU)3AF?mD#as7+=K3JB{b$Oc(EcWVJ4Nm_BeL*7zlC;hY zJ?GrtNlzj-@SuFKMjnOqKB_~RYEnk&`Q;48&^As%nA{>gbVkDM%W?Jnlc>`dK1Zr1n1q|feiTv|Bfc9|*EZ<; z)R^p`HA5+@p6BB@zgTV`-(EhoV&Xj zY-I?jc}3UR*U$f(v`q?#$YfddwkYExpT11!Ua4^DGaN$Qa4GQ?T{)+`KImCupEH%L zA1I`CO;t#UjmYlrJ@np=;G3GyI6ix&;z%n5>q;L?-z;D|t505ce^DSUL_VFIIB@hI zfuPDgs;L%AAT<$)HaY(L-^gu%q@a=Xevq{G)o|IBw5<8@i~pZEn1J6pc;AVG-NNEP zboQa=j7phSrb9fqJUV4vF3A@e19GC##gD@Kt$`EID)#UNi3-{^mT%50k~Z^Akrblt zxI@G1kb(D2mWsrpEUSo`A5OX4fqwuFCWbQZ`a9g{5K15;t7ej9_ayXX2UagW#)ELb zFlB%a#7Jh!f-xtI|kI5@M+Ae(uOFmJ?xyiDbGYe;r0DSR zeJhP7;~#Ve=`ppDbr-tSQ)zuWZKaodOg^iu*7zj0O%(W*VM|DX`rf2ORyv*jhxWUry&YhrEIG5CDNV2lXGwKk)uHVk|M=EOnv)P+cZKNt4>>#?OdTDb z!gBj)R~VFa9jKl~7#CVTef1TM2^JAkj|+a|!^>FxvhX>W5R+6|iF_Lo{K1N;ri-DA zLeARI+Ac=>!@XG1+F4xVefa=rw(W1&xcnANxcDE~Z7eelTjWfP%?+8D@kpn)LWBgP zM5C%7VD zdwX@>d3#&tz!QkJCP@18KtvVMDE)>Qq7gD8o{+fBh5ic(&z-#fF&N`sF zB~ke_GK^^U8F}G}r!iwng5_i>FfaqW1H?j0^RGouObgjhSWYxZm6|H=1%iK6!a7kB znB~m6CYGjz28Yt#-n;>7rBJ2LDeyo6Y(N1=lc@UZ2F4ySJ{NU5GbS{^?X3ODOf%`s z)2GTAIWWBQ!6Ux#JJnZBr%dg)?1?LH;^B3MKgkJP>CFn_o@DR|PBsiYc+bbu;=H>o z|AbWVs5aMiST!|NuHZ%_AwM9ct8pQ-#@JjAX*b%qZElYYRSO5Y;mm$wGFyUUQ|A z`wWP84#XI)+T?F&0prQq53(u<8-kTPo_?W)dw*a)mcB*sd#MoX3qy#at)>=6751^> zQGFi3)s_JFaG%5L!DGaQj6^%;krFzoEaoFXzN$SVn?apRvI=j?s6cYkMR$}y`lcWC zx3jX#V^QE!(Ss!tTKlOM%8$Rs>^nnAN|_F_J1V?ANHmwDqz^iA7epuWL) zkK_5Vd=x&MuMsm7wJ~ZBIOq>jX~Q1*(DeTL>jGp6YYV@JeX&&^Dz!>W3rU9?HF;^q zNkSjhm$3zk+x*Pshfk0wg?8pWDtO5~@@|g;tq+^^vpV^n`zxQbVHi?we_63-rB-~G zJx!2&lY8Bx=C8BkoJvBU`7W*M1{4eW-4V)({NQ6r(37Yz@CQi$Z}&Br)`4)J0nl$# zB#^8KK!bfqhM4>ptWKxKTk*~)_R@a)>^86=(MOSVc+<3m=0MyFryO9#_a6J-Hj#@w zBdM3Ck=#D%mb1v^s18%v=D&NGX1eEtipK31e7q05k=k-wi{LW~a#lae140$NR4{pR zE!x##wHc0*;t*C3<;V7XXli9#{G+;Orw??Xmv#L zxhfuc%??~~lknp{uNJPwkJ7)IIGFVJO(eu~#&SD2NAF#QYw5 zc)-uQZ=3;X$b2k!c7GNuK`ree3xCvQF~bPq&ip}gkxS;o%FK3cV2nkPY(u10i`+{U zq$25QPQUs#*t4+t#oj-J`y?26^u9>zjiN+hfb%(F*Y_zO<|UwI^1Wo?$A7Q12ECE# zy^2d42YMERB<^xM;V1h~->l`*UktdL`58EDQG3?RHu9yuQ6kP+3?NxbNlSD}-60CRKIyZ3*NLY`WrE~4eBQt9a_(N=j^k4%9&6mHn4xb@ zmFy`A9!Uiw)=ms|NWt7GqyCx=mv!7e5^oQ8LT>XQ+it`{PX8$-XA;{)=fA>D z?}cMlx+5O#`JIY~#_FVF1}CpAq3p(Y&0~g*X8(6-h5vW1;lHI@R`i_)(EE=DnEIa@ zU?G86p)DNgc+YF;1ra3gua%pA^{0p@IN=Uf-;gb6lD(LURFFUmC8WE4( zMKYTn?;5)l|4_)f;zFS3Ot{ktv zSPtSpqVj@rF+a;EJc`1p| zSg$I-!d1sRqlQ(qNFr9N!wdSunuDI>Y0gZKcDTWv^eB{bPwqIgO2)Z+^X)3iU{M7e@v|H zFA4je+J1^7l+-l4jU*#1Az)!@QCH_4xC>+{A}6+6>EhH;4)tK6;4fI_9B_0H?Rl2= z7(jT}EJyoX`-JhbUrwZYK{5ot7qJ3XyPRWTH=U|q-BN8@_=lC*Jl2Z0;c}O)QGtGq zYQu5e@gtApj$}CkZoLdGB*G>j?AS-hEy(@lCtrw}PP9o2A=a{Ql~a!YCK?7CTj<(e zt#E%qe7BkgWJyM7=Fy;43J>AmR@EtQl5TThBSUgNZ*5;dpi{e}@*C<^UQ<8Mel1@+ zUc9QPv;P&=o|ska;j8Ue%PM|7oL)Y$rB+qT;gUPeRsF46VKe&X#dO2ZLUJ@22Ml(|Rhx%CWx{6vJe4%ghl2&V>fCL`;H0eSu-g)eD*KHmAMNYNN($DIAJ%3c2SV3@ zTL*iqUAOQj0H1gJ?uG?fp>`SmpRP>@)$K1}%wy;TU5-HGO|m^Mp#fEfsezz43^laCmE)SlDVG8@<`jW_5a`?1B1{uPta6K`9mD=J;&kn!0z3y;n; zwpICm3*AA2aO~zs8poB$CzooGZ|(?{ugiK#no5V4r=8a@OUuijLvdabe)?0x&c7*U z`!CD*`3UO8j9$q~=Vt_HX@EGx{q=SAw?mxH65?4uU6g%8{7h_Wn%=l`_F2!biF=&> zuOt4GdN3)AQr({TocCc1Mb0OEF>=eeBkq4|4Po2A#EoKJG{a3NUB)-Ga4bQWKmUS^ z0z`3w304(e|Hs7!K%jDvDKp^kL5(l!EB_9W6T_lSGaUB;&S!NA04Fg0u6kzDwg}N>$_Pn3d3-HqGI()wJ5+b*i2*F}P z%(8;I+nZSgP6*EEe2`?uD9bwcEvffV!EUKqo^l~KvnZ$^Q`H7dQwFJd-e&@O76Ct6 zw4&%x<4MIv(1D1FN`I`si`d1zsPbJ!C$ghvxWa;5*EgO-g{{KuJ~MgM2t|5pF!z;p zs6+HufOO-^YtzsT3anbLl{hTohdv1==dnau$E;UOhLoEEesa+rca#z z7Y#uagRyxBB89G^?qoeG4eom`bqZ4NRl%h8k39p7-CHP5Gvt&^;(Qo@d-i*1uWy#h zqa8s&K$i@l`&W`-D=O`{!~bjv5+Krs-f54ch#GPcGm(6rrZq^}J*Hk#1WmbFTuWt{ zwGk9z&^!v1YH_gB!F+T7LhlpsUhTbf7O9Wa+9aoUcPpqFCF+{Dho5--`p8gUVLqRo zjkW4kEl7oj0g+{o?;T;UQ|c+&jW-y&A)>|&afKKOC5H4Cb*HPGvqGV;mBYuGxe^H@ ze$!oPn!6S2&5107+|?+Z^{I{TzUjG+TiBZKhZ#H(?&*nC)D;jD%BVWJ9ief~=j}Af zcz1X?C=366SIM<=OvaT!p+r7Y`iSV>X!SYYxi6V=>~MRs3+-JnVq@r}E0vr*lFuf6 zN%&E_85;z)-R24xW!mdTmjwn0ozQ-0{#dSMVMF6EkU zT-x&Hs-G%A@xa{VVtF}=4rg^qMS5Sh)5pKWpZdv!;{Th99HsGcvC0T2svwY2JN+~c z#|)j5FuG-U*GDHTaE;62fuh`O)rORiw9{EcPLbAcsoc<*Kro{Y2)3M8^4dzAnlNoE zi0fw6uR#z@V?eewE4}$RiOUrb%*^Lzyx$e&(5IDrmZfPJ_lNI%xE92BSkUvB=0H@|S;OKOM!w z6#yUkw3n<1AXV`5FKfcZC*4WE2)96~P&XG`gUD>0XY7P;ZJ72U_Z>*Ws<>Nio`^{r z;xci#>8j0>Zn)3hH+|UlR#vzW*Y2s_{vwr?NY_)CKcmU7?26T`e@oQKYQH>j$UmvL zfyN3#YTJ1Je!2oCFO0qM6DhUzGpG^Eadk3)vkb}SQ#c^lgd>#?ev5tmn9=Hh+)s;t zX%ip#fD8;0zQPA$c4G9ehJ#86u)fZ65Qo7nm4BsBnp$_+Mk6WTwx>hFu`@PXc~Tw> zkj}UpiWT7ANBnPOIoX9V;()Wjs<2y((WxtG`T8aWy z*WJy~ckPAi-MHA%yQBg&Hzp09TGnqh`VpivPg0QR>UIL_wqy>3_8kwZ;wko6iB`Y& zLi2gVO5_;k{#Z!Mw#Yx)4m?3M2p%)|J8@J922THrje6K=(agA56m!TwJ-my}H1uN@ zl2!1*i)x|v}lo3dlK@<1x7I16Q-|k10P=c0P7uN=1rT$%S zu~DT$Q;!y_auLAPG<8pUWbQQVqQh2PTup7erBDc+GBwty_sm1MsdHJVWqHyh38s2G z@%A6nQThiOR)jS5ssDjj%c(~-s-{rLc--Yt47P5QvwkMMOb@6QG4N@UWqI;cv>EVZMm7;e3bo`f(Hl z{u!yu9r$duvo^OjjL>Ip2t@>lVZEI#eH5xWy{Zi+dijygM_&&cI+ruSclV7A%6`{r z+qE%0c*Kbz&L#G~3XTj3#$>l0DgU1~$)QS-tHv?#fd)s(o}{3GdVx6I#d54x#>rpPjNJP>QcvK*nnZBiA$p>n z4k7TlTW#FzTaWy56+4~r3 zfbKAFo7AY=j>KtXj^L~&Lm-MZI@ggeN7% z0Ed|irG=6e@Md1YzU0r}ieBQAOPX>IrzNhda@S;8iAZ?|}J+FaI|4QU5tc(MxH z-a|hCe*U8`ZLfWjKL90_Xz4Yp@$$fTF`Y~O>6K{(>w6fYO2^4VG&>jD3~a6A_l&FF zr!kIF*vcEn1S5G5W8UeZ@~v+dWz#9(+j4xc$RR2o;}{-y|6$C`FzMZnaJ8lBNL{h7 zktk&3`+oxr*SajpDbp-RZd0;vrw#nqYbr{I=SzgjBmpO8xVXUOKA^c2YKa4Gs7_>p6NVLsf1>A7J=)#pI5@j=cqV_ zGWzim9wsrCo=6P>WyGxP38&t&t^p@(96R$IBpF-xYL%Zc)uq%Y8dnTQEJM-^Y=^H) zmm%=4QS6jn%0=V|+1C?Dc7SJ}VTr=&3invXh2bWo*3BNNu|{dCenO2d=BDON2b_ zU}sr6S@wi}!(D#x4Zf)SRH~IacNJUznMNLPvDZ$)x;%_Qk7s+9UlhN1>lkU+oFl@S zA>4kwj+myfpBNY5SX0bn6+V3mJl2XgdEa?fFQQq#TjVE~QaOK-5ovf!m(6hT1a7%l z3K~LYOi@m;CDBf2i%(~me6;^~5_dPIL%ZP8%iUR0H$M$NC8)T8uSjvTx%1?6!91JX z{%x}4D&nsRZ6>aSxqTXUe*$5MSr_Z?Epo?vtf(5Fbi5ZKuU2aYpeL)2!KCi~Q^A*} zMHjzl7_G8S&3DMI^{Hyj_j*yn+xMn2;KX2i)5B&{obIjWkiJlPKPt2gE!eS}rMi^}^^z%if6V?jNou>Sc z5NU_d5ce0aof^)yb`$H&d77V66F!4KQm}$B&u|7{g!^h$^VM;6E<9Hs{K$BO_$IjD zfb+?JUBH3;X2mA}v5<6rym0kz*?r+Q-p_jL@Bb!({Vx#4$dACAfAM#moD!|X)w|+V z_TlND6yq`(hvi&ag!-p;-23#zQXXP&3WKVZUk2);j}z2?YTyhUK{%6Qq#Bn&kD^oB z<*;vnD1r|}ZSvh9&8{ow0J=(_~^j~U^rkxQZ5acj)Lz>l75?|Ayl3!SHI0*7Ej0+1@eYwcgSo@wtztjF8y9iidU-*i9s7Y%rw=*2X{ij0( zArXZ$dvCCjiR60utqSUa5~+(TbWp}X1%M}WZi*n+ek>S{b-XwhWg({oY%aV$4c=2i z?ay;xKdt2>`JvFUN;H{G$QCRIHg!i^+~?Db!1?=BW6uQj;r0A$aGde{WCQN~to8>I zJQM4MfsW`njk}k{&j7l$J}L-fzrca1TXws7&Vc0`x9s=ckI9aDCD`L^QR9_e6hiqS z58uv@tt`Gd?jF>hrMUWr{ay>b_8Y)>wk zop>HnwTF`Zp7w(%j&lM&JmL!7KRGW8p2H7tt{-A~(@vfS9!Cg$gZUi(r)DZ9AtSrT zh$?rddH^o^J@{r#=5>hQJ9$cy;AEpJA`sBE$f z8GA#H06%kc4b%x<#QiVcI;QJyLD?xd@qa%zd|16=Y|9@|^YYu>TuUnTvX@~o+v%a) zn=hSqsHnq8jLeXuu`)a7sUhR58s18aLpA&AT}2Q{M92fiH>N7cBCk&tXzsw~5d_Yn zfNRtdPonc*nMa3N%BvhtW&6s=GG<_L;UTYH_DXC=MT5opg~6{F0|!Ot@kVnFO@+Hk zqBonV4Wcokr&aWP_iL7SY%AVYn)LkphNADeO#GgJdH-;_;I*dRoR4?&*{X%bLypfu z&fDM1GtFLgl~5Xo+j*P++79iPshR>1F0YX6h>M zHq{B^S~zRz>LdSW`j_nsC9QAq=&&xzO{YzvLmX9$K~d?Qs-`MlV;3>R(1Eyfjv?G} zFZzQV!eY<`$Utk6|l=*;BHxL)PHydDes&(l!DBAVx3fX|tl-&G)3yg2b?>biPP z;7p=H3*bRzR+{RpjnJ%5kK9w%wSm**8usI&s408 zJ6~jgeFQpEo+on0-o8f=`>)FBDW|~NneA-9p*@H_lbKt#IV{W?TwR%Rq*`_T5auEy zde*y|86gPx5|-{*n@_P0z|w&cN(f!I^3DJeR<$+a1SR2wsaEq&m9;6P%8O;i7D8Oy z^!4+g8@HEv_@^f*#cQYGDnSq%MK4Wns{9QKEETdFTOV!}3V5*`zz;|i$j5&9(wy*S z2kZ@?RN}fK#)$Ddk-|)kQ`#G)uS)7SlD@=dTeqG8qV4jjHKZVK#d0`|n`=ZV5XtnO7!;4*9H?j^`*W2)=&Qb@7*fF8C(n zvuD8F%#e@TlY{yVYI3K~+#bT5u~eQ}DH7Gq^sqlp(V+flq9#^VLc{Gdh6oeWo;RlU zVc)(JOO7@)CXLt{*#CwHO-Ld{hbYX_7)P@eK7FrVKMpEppbPgIhQQtZ{Qo7&UM&Sc zb+mT`@HK==fGj+YSN*udB^?Ud{k1Wlm)_|!&pg`eu;-kWB-R!gvVtOag72{&Xa3;kS(g)T5L(lrZxT62PB3k|M5zcp-piD?nYF1USsw-$sIsZdN$_A0O8M38Vm7_a7%zbAd-NIBS==P6qrWf&$%UjF~AY&8uy4N zvL-BqvFCs-A~@JCs?hSs!w3bw2Ij}DVF`~Z-KvSgfH^6)D}}+y69mP9v`V&rf0bk= z_oBX^I+KetPzg965~Kwx$*cq6puLKcI*BdDoF*s&*%=ST0RoB9{!@U)4A7Ejeu+C_ zPFEC;q!=74{}Nay3!AO}9~J;{6uI&9gJi&vuwJrd3IMgXOYhxQ$R;hKk6X)s*vNEe zn&#?|u@&xxpzJ-EAZ4v*dnO=>0z<4`Y-aGGA=jh9V0I}$(K}KAgL!rL=<=V?wKts^BK?s-Q<(G1Z8ds`Xr6 zPm`0vVW0OC<_S{~*JQDM2#W#L9p-+BjjBYJ(e$?8MedJd;hHv|W%27{9xhW{{a{zW zB-M_Hb*{I(5`vswb>!o(j}u9_z!?hr-zblnLLH%?6XN2!EQe3EZkx&JMqW#oG6qL$ zBHp)8)rOF=>la~7{Wa0UeH!#2*x*xs+W$|a<^ zOz3)aA^s@u`rV~WTJm&P;z7-cUgO_^?l;>dCnk+jr6lCv_?E8EXV`J~3c*gminp88 zKvpr)X#-}Z>VNGVFsnks2^kJ=*mrzx}R>JyU#B z@(wLw?fpChP%=(HLSgaFbuga)qiLW2Jut<7c-2SRWAnT^4%VB-HESz=eK+H`MvW<* z$3*$x>8DqUCd^cYeR(MD`ON`Xe6ROMaCEYliQ5`%5hh`5xf=*Z4ZdxwNucYLNce zp0lZ2^R+)7`Y=iZ9YY9Y>aI3)mFW9~DycS$H2<&%PJV#wPVvh0kdNBGDAZ7c9=UXl zRM89PDs6*?I!-Bk&rs{8u6qJlxHyl%X7^q#lW)C8QnP(7i}CD<3E%rSu$#EeH!6G% zMj)2!OkJg=?-+md!xM<5s)w_qsSZKw*m_Q2v2GFh1v~&(82+OV1ZVQ?aQ# z45nGqjom`eL91}$Ucd~nEZc4dbYaGe4e&T)ms*lOGHzwY$0IgynT)N9gt%v?=7!I5 zZ|DL8cg8KCc>~*zR}=mTa7j#2NzjuW61$~(;FIMhEk=W3dbbY69P@&dAhL3H)E7YJ ze$(j!APs112FHS$lG3}(jg$U-8S>t93dO)N62rlgI|7r%7#er9&;?Oz_*I(r5ru5z zqNG`bO~8Sx1V+0A_?Uep&L@ht84FHUfQ$((FjcA2yF5GUq$7p0U;kI>GAm^LQ4OQg zicXWNl~cROT$0qqMFFfXS?O_81X@O~& za~y^KuHkE?nNFY?3g6z0k*uvIM{+UI%*VUDxX>ZM$;P3Yhv^;lMUSxcW-p&%v1Hc* ziwm_=j9(kM{Xbjm+|keQhR%V_u)x#`u~mWF0G2CbhrwJ#mq!E8^Q#OVW&)b*?9C|bro_*?d)Z=lGrpWjy{J1-mHbr$xXevYp zh8=PW}5PvUv{v+Z6dxLS>apoSJGlgsj>WN+!we)lGw3*UN`)shntiT7I=ZS%(dHQs~d zQBil2^v1#HVBvD`-sc6E&;R;bE*4fc^krm<-{|xi{=aC<{}J~k1RhG&@XHSk9+|wY zdWQD^J6p-PkDkT`CAbT^%yaS{dXH+4|3RfiLa1i&+_pZ#x7md9;EN8y!UU?;geL`D zPYO7)GwvN}5NcvlnGxxC2e3x0-@nA#I&!()D`N$`+~mx6BRR(Bt-Du=t87s<&WADT zMWr@Hn>{?cZ)E4X)9*)-*z20}^UW@vYhmZHhU zw9J7CU!9d$v3!lz{x^3^<63zDnV>yT#z(F6$oRp(haVssRHz3okJl`DK=RwvKUz&U zoS(-#ZdfM6r|$qR|ct z2o8kQ-4;7&8v<*Qsj@@8yU!Ag_T+-#u!ZY3PGMjHh$~WFjBX_g|T-Tmo2Hje)v=xhgP$DD=r(TP$ zIZ}G*NzpoJMYl`)jl=wh>ruk^C01T$vdw!mA5iG+YT5FkmhElB)s>b0Gz|7OCE+?OaVd$N+dc2zp z_l=A-$!W3#zRZHuV;8XcmmIU-dm$Bf1Qm0q7Vp^VI69TAT|(*5Hd7B+BW zMWh2|OHV3Z{Mg+JO5ij$PQ8E`>e13AY~Ka8IP>f3$JFXc2VxX6Y?{XI!f1a|vOZ@0 zAT1lw#Kd^2st`b1F!DrsQo^1iR#b;G)-5&XheD5!U$E|~x3UC8NQqGGxc$670&3Am zRywFKOK=za_R$?cF~O8Z-rN6KL=?vEs)5ksFVih$` z=%C+JZ;)#AQnuD$edyO%ztEu9nyoZw6g$_jK$AXAxgB3aV7je$XFuihCfi6)%p@W9 zg923Kam#x9WV^xtoh`5qtm2ZwyQ4-wQn%r5{y@B)0JIcPkOf%d%Oac*kcUDaY}^r# zlm6=6VJraXt0KxUU1D%14%ejgPMI|mx@s0A`6>e-UtPYZo?oQ@&{!DZOT0uUY;`a; z@`0d-kC)T9>Q55t#Xn65>o;pvQ$nf`FH{DgnLg}G7!*<=@nN#NTi}|Vy@Emw2ezd zY@n(Gz|@!Kuh?`Sl72Bk5Wk|W+uydDb^$+`Fa19+1#}>W(X~u#%$w;lF6bTJ?J08~t(;*ISrFJrpQCK{nk9*9HNH@naIZ0muu-t^f2|<4n)TbT_>nXV_ij(avNVbPwM%MA zM`6|(3}NRVAC%7&*VL&*q=V0UXhE0OaO5Pp>xPTVZU$BS z{i8L@CTDxJmg%Rvjq6zp*WbC;Tz+y~r@mDyHhT)2rFL=u?cg3SzzN=dv?we6dEv6m zeWTO6fdU@YWlb<^9PTC^?P2tA-vo>AkV&u`q@5z3eaSmM0ENp zJZbP)Ml@WQ&%-Ax=lT)GTrdA}Tux|d^Fj6|2h`U3S|7U6-V=?+@CkSRC4@33;6#&fJ@+6)SkNk zVUXniPYjYbF3&gaz9YMl7#Z+%tJIc0?r{c<_ZBh|asu&ajRLBlWUmLW`NvjT7MfPcDa8Sf|h>C&cX393Xvg4lH(`F5m@ju?ql6a z`s+hV@&hpX`Y&0Q<-0fY#ali7zl!>c8lOLV-r2E_sk>ahEH+y#_ugTOJm|)S*!Q@$ z%Usr+;0a^iLSmPn5*eu5pIzbnXuT|z=^j+~VQ7v~T=?#Fptcr>N>qa_V>NS&5Ju|n zVhGU5oPPvR^ho%no(mFI;Dq9^uhVel{DdfFvGgFR2Y1bn^cXpQ{J!NK4uYHIzaIpMkv4)YPNlBo>8@KRx(rM8JzMPmy zRTV?g9^I{c(h8Ng;NWcKY4S1tFydfkd`F;UR;MHJ4E7c2Gw1n7rik- zTYeKJ;6Q%oyWbLzv)vg`j?TfNiIF2ElNsN4dUyyPop@ME+f&=;A<&02vl1UYbo$4= zrsi}?n{Ti8-&yy1u5W0$SUM>RD*(xBet8-#6xMt`Ier+~Dnh`2N{DxiA}4&@IgD}C z2+N=uz14m?5;_~!qsE!=LsTivmkk7lQ3wKXwo^0fI;`My<&Mhb6$&MGS5qU@pob#v zV@8IToG1+QQLsj&t4DZ=4o`^ z!Ki^#ui+u_!&|g3$O#s zZpMrfknZ%{5rm=m$b_lxANRo-xAcDIyNi~JuqzDV2;Ocs*haeZ9pD-feL6-)lGMs- zUT2z}%2m=$=l6}K&>~t!h)+lr6GoZg6wFL{NUl}Kq}U_~LC}4z?8MB#D-Q$gO;)d@ zpePMSj~{U%w*M@%B5ifXL?EbGchYM1&@CSPVcA2E1E0A~<#(({LWUa#qgI~B$at1O}U91d* z)U@ATwOsuM5`)Bvl}XB|jGs>QHw01dMDz${)=T56B`TGlmHKC!i{XMZ5SSZ)qN1oi+M0AYqT5;Qe) z%=7f4M0bP{mgSn0MVAgFg)9oPTBedQf)LASWUr#yGxrh;!O77_ohqi;y|N68xFU7;qWKPu0 zRrj6VO_tVNs4)+{30a%=j5H>fCJvm?e=OTLPkC;ZQkA-$Y%cXmrlcposRtepe*bS( zH1%E0HvI1>&T@43H{?Kgadb-}J?f%gV(Td_JquDpZ(=coxY#pIXmE!IEw?Yz23BXF zUFBr3*j=7IDH6afX-jrS*ZZA{M4a|xjpjm^hAIqL%;p96e7R7s2jzZ{7__e!^KCedV!%BKMi?Ai69&dRfjOhkKvZRvd*XDh_`WaKBJ#Wws1i>q0R(0iUVZ-t^|C zJ-+b*Usl!;uB3m(@jja_^>_4unyU{|25uZqI&%s$Wy&HFL=$la2_Vq`mxI@%<`_)e_l|Ng_wNlfk z{_A1f-a|JSrZ)zMV|x8}dTF>z9rRcpei6~xme>fQYp>WQMFhMs(v3!rNiz16UfE}P z%U$f*Fu(IXQ(ydfGsJRT#Xy0*6#G1qbQA~25uvj175CRoya?>rfvHh+%Wf5@w(?_M z;&1cp6y2sDqz6&pRDq-KDkfc~8cD3Yi@h^DNxU*Aw5Ev~kVIO5TvrC9u$YHYGJoS& zxC@YpsI}1v6TY>#U3=78&1GB#4Yaz7kKZ7CDNz9R;d?qrBjZkPTxqlmCHO>4=dUR3 zhp7Hsi3Dh~5K~FY(#W)w-EAc}G5(0rh;s_ba2M&?ppE-c@+)86Ri3A-g13*5IXu|P ziEC}1hWn$rr#93W?FabNT|>Pzz@`2Kl&#bcVHG*7Te$G^xRTU4EQEZx9YegI}9x#ST*-lU1POT=I6YtX2~VtZGj5c{rE zpY`-HY2xw=+Q)=UwLi8;XY6%E@0(jCI;eOhsa@ZvOYkX&aoaT{eC?Gr;a^G;@8OSaRgJzlrP3}L;L|VH{!PSBsS(1Bd~%1iH0NmGJy60O^bcXE zF*iU26bl@3OXo0cE(-yQ3$c=-XWB}kTBj^?5Y%1ge_|#S7I&6nPs*#0s{y2cXRjVB zaDvbUAy=q0Kn_7;hvQSNu zpRt7Lf7(kAFmhwGc$MUFL^BWgn=Mn-JvF)btK9tOoTLJ>aq?a^$oIF7Ns-X`h@4ZB z67hCck$DsyLctkKH^6EUKuIs#YT0caDZ^AtPE6rJnPI)*FNdbg%q|5t+)Pi;)5mAO zVe&@sZ;yL(RViASKI4z%^T_4fpj_=Uz`?6-hJU-fWD4P5`s3#IDb?JN_`RH}%=IZe zgUK+1eN8^Hh!mUPbdqB8$S#ufy#!@g(4{*4;4z8A0snSPo}F3C9Lp*G$7Z)BXQ$3^ z{$dq=OY%y=_p83Pf_Hf!EJtIgA%l6XO}|E<$<$XF(30wVj@18r1ZuLsHCLmhKVlhbe9y8PMBa*SOnJ{UyiGbZY_udcvFQt~=FT)Nn$#?eEKNYL2}75ODa7z*t`-S- zy@*uXUD_-c^PREi%H&#HU5WBqfntOoL|gZr=eb}d&6FEI#UJs42P#u$?OT`ze}Rh+ zNtyFu{R-(KGPM#;Oy)a{w``EcnFdalG^p$Zr4wjhJoEJJ%0hlYXaMYz$~?AIibOgO znxDh(>x7JxXrEUKF+)nJF@TFVnLqX%m0FqyjgBRbZk#td_h8(sV)bv+$dIaP@mFf0 zx5MdIEcy3c&S?>#|HPIE>&W%tf3)@gE4FKRv0dK6i|x6xv{EA_-rdFu%1m4%eLmVo z^74Q{l=R@mM067q^-CG?lnu_ie(&rZ*rOPKh(y~FDsdMC@o`UfP-{%MCen`lBw45e zw1y_npiJxB)tX!lXVj=jU3MxA=f!EuM3nCW$Nn0y1n*9nYF&0exgMHtA zLi?FWIocaBd9q=EBpMuw(}h%Anf!o;f7Z4lkMPsCZ#up39^PXl)#GnLZ!g|9?7UA5 z=%nd>w=wwb_bvaSCci!_bguWMwnb3I`^RjGbYYruT)?>63eHO%EzEP@*>F<mjgHFgmB&O__DLal<3KUWe~rT^t(p zzJFS&-MM}C=k3E&+gg!#@Ifk5J0_((`xzzOrWm!$5pq^%^-I#YHBbGnah9u?&%b1^ z{~2vbP3&EAgnW(d>ZVZ-LS{cQtTdm*eUaH5tZ7z3wwn)B{5y7jfv=yeI!=OjBOMT;BOVjE4qhHcVm{`l!Q=FwFi;%v%aVLXq zTR*f*-Ys75F8;D@@hH^OANQiBI-eL&B~U&+MjvJZ#6vuuHfJ|Ey@tq#j0cp~6dD2( zT+l?yj@(N^tQ#i06DnbV&rkR_^k}ZdK@!O)L>W6|+#V0@OCyMNUm8s64D|`lDgga- zCsEc%?*bKc(-&r`rxHswyDN%N$x>3k9h!IdfWoVOpJk4SQ?`USk67Qe>x_}XCUWb_ zx+;A;lE_OmHOLiYmN2=Gki@+*?t5}5bKk^;&(pI3MgnI8;)OFmBY3E5qn{NOhyb-D zSg3!fwfeq>aoR^fw^CT{D7T6bsfNy^?7L6Ad4F-G@v(0hLR{k9PkZsF{)wt%!vtOT zhXc}#BO!6vAtqXFXkJ&uv{=CT6+H%ou(;qn?|!HJq2r4a^hSKWb}g_yJRI{C=F8s2RouVL^W7IrqnhhESEhOfPO749m)%AoepF zYFu*tPb!CG3PtbPlIe6N@RB_3KTg+5-H55fO77~QOiL!?h#Y0%Q$K<*9ae@W(o}RI z+Y#=Dv=miHS2K4SvhmmI1F#np%sn+gjdcVpXH$~5By#Kp3e6q_CZKh?CPw*SHeCT* zKZmO4GS9NX(7Mq}#hy+VCfL2AJ9ItA8U`_>IWG-p6$og1G^=>aV5IlLrI_I1rQvJ2 z?3Kc$QkU}nm3#3-3&@EyN5MI29R}6(#-*sqwxjd!7l&v6vZK~V*2A}M^{&8wPP494 zPC=haL#AY%o0`u`ue)epJxXm1BEA{^e7B15sin8KLMw(40YZSnp36YH5-JxCq-F`^ z_di)1a@O5FfI6e14^p_+4c@n8KoMGiqSJlZs1{lW(69k5@{CZen2hAN%zrRHz>~(( z#1H%`qJRR_2O#kWk^2DQOQr|%mY@qe?`{3@S-Td)`Ff{(5By!#gavf({^bjb6VpYu zAxG+!Zgcfq7C^e}`C7~Y3eU~cg<}8R{Elg2yulJCu{UuL)Wx>UT7V@l5cD>&4cUg< z(c**VBJXG4u*hW6i24jdhBNh@iK&Vy{6D4uX*G!{j#g<=)`?4BQ``V8s8kAmA*v)V z=T%3GVpR-K$24Wm{OCg>=|AlDsn7oDU&brtH22I|B_r88fa@mD(s-A(YH)w0Jb?Q#Uq7 zn`%tp_Fpng^J|Fv91Lek<9-mkTwo4eTg9f&X3Ge>^^zJsZ`mYsufo*)45+Onud=(Y zy#zw~tmkRIo9mMHv`KL6c}=qKCyUpvHkdJ*&8_c7UF0r2{tP{La|Xhkl~WuWyHM5L zO#+Ca_nAK1detsAJk9cd;<IN%6}fR5oG#c~P?M#Erh%2fLjz+H1Y zPKW|%#}~_Nh(80U#d`)%MjbMZL^O2~*8l6a*@t7|*&L2+wL7KNpo}55eVK=bwdAVw zbI<8VZVpo{m)`ZNHPu`VT93+iot4Q7BKtAn6kbjdmABQW3@7ya$=LY{w<|h3&mo$8 z(q%9oZYoo(lzxz;gn~qu#%)l7{MAyCYPeNDBaRp3kTOasbb54EG3Ub6P(=RNNg~rl ze?%NPA~BTNr>2@7w^#yZwgyM?o(UqiX5i*Q`0+SSi(hTQ{g&C?!DHdY%>Oz{|8H^+ zDC%6Z;bbuwBiZ4D>Oglp911u*AQ3i;*m%tc{MX}8;RUI*=N+VP|YFaoV zgaH)=B;I5TMO6&fT>csGz24vM%=N1Q`2XqplH;oU9n#t+C7NHZ7CgLjTuA9S@PZ}o&;4#l z;ty(vphL}^;ukzZ#}JJdt*o|7?3^Yc)e74~S3WUO=aa5`N{Q(Y@V$p3lx-1C#<&N&yW?zBx+Ng2uYfFBy0Z(Ew?RW#aPDU-0=&tssF z?EG_*SL$-V2&__Xo|dZgqKAjY+yQVeeLd-zq^0s8>`$_B&sMs#%Han}CL-~)QN7Kc z?0{z8KK{}J($CUvqfsTi$PpjPgEv}xrvG%$I<_{#2e!6;RB!F2&W@*w*=@^hTUEPw zztMu)5$SlCUqS3Xsf9ddvl`r6(| zDg2wApN)r09>#7I5iWguUZ*FQPyhVw;lzaB4^FbX7D)r_6Fic+U)W>7G4Alh`16t8 z%}Iqn`WzammcGLtXiL~ur=NLCRXz3fir!c2pfxZ_e7v)>sFOFFT%u~22kJw|!{*?p z3+aq$qXHhPvP+-hF;Z4QlI9%nau^NkBu47c!A&nb_Oxn*a}mF%@D$1m3o!^=e)f!1 zC5OfZWi3!N--Ugl1XZlrCB)q62TmE<%1y%iUw5Xcd%>)Vd9fFS+y3c3I7=4}vIy^C zegYD-!j0STt5@$yyh#pS?)-kGBOLkUcGt(ygVE-t)8CdYr}HUREyh}1hNu7`Pj4v_ckz`XcV6rulp*i?U^zyU2IpR zXTk;_oLqXWahe_CAl=2*qw3uMxuhN-(En5R=yOK1VY8R?1l{$_lnxE+o;8qPbj1VP zvudNO)d+R*RINxWuzq-Q|0;80wYs=)ymLn7_*nb2N-chMqVrK+2jR)UFRQVKbi+;!atb9~WW?TAOjbJmbaswFF^c z5{5F)rH6xS8w?1k2itg4jGStbDjdL31U;<1YdN{xXfh9F+5s!mM=_v8;29jKa-fyo zJ%HMS>8~LE>UHJTx7*eg9FGgpv1~L~c&0Z7VWH*1G_GyXLuCH?XL3Q}Wc0Oc?^kRLq*RP3~cI zTq}7FGp*L0%0`)nwxB$3m+Yd=s zq!h1Zmgex*3%&!b5#2D<*;gzl=pknjF#Of2*l{`6@k7G*Zjv4 znxc52d?(-cP4S*umygK$c11~+L!6+N7^$IkIi0K4$YYacvu-!{ex|tfGPYN;d5#E*pXVBf}6`e zw$aPrF?XFy37pEz`lCe79DKh;;Ik7HRxQbHw_*O*?BGN}L>{+1Tl0w|mBpaJ_6vu{ zcudDUA<iPAUbwr>Ax$ANl_rfyv#s!e}GTciDgi{`1dTD;^SQG-u6eAN7g9^P!e8{o0%e{ z{=Etu*l(r&Lz}i-I02$LtO*F+e9K4o;1`e(hCSSUd{1n(p1KbdnAx2}BobcW5c4@F z5}}<_NJ0UYZQzUP81m#+UDG zHUk}jpnSt*%KAgUZQ)(h!Maix*KoyDI*PjV`y{*W$vXv`!%tRwz{^NOJ_TT49?4ff$ej;*sqHJnNmK*&YL|b+YDjFZ(f%{z zg#BRC`rw`pQptp9G&OzYrd1Y(c-P%mF9`R3-cooCw)PRn`<+{Ax7;}GJ zTGLB*!@J*Q!1u(WXpF#zcxlo|{6ROSd{96)!cgz0E0G(q{qHHG3EklP71F!66%loz zE(WP)TPx*7PzWJ>T6@+=cIEK*NU_`K1K8x!irWvFgxdaxA+HN0glQ+X*hOxZQx22* zkAFQZ&mLIHQcxGMUN|tNeB&=QFE7~Wn5tkncv&Q|U8}tp<8sO9Q8&=`5g`p!*5V@i z^VJ&Cyg_B;jE?8SbujCW$NALfErrP@{!{eZbRDL>G~IgIcPIzP2`NdGet0s3UgY(O zY0P_^l3fT=N~gc`K~pu}qif5>K#4loI^;;v8o`X+WC)fB2~cTcj`-Cm{s1BU13h_P z_u0n?f;=$3m9Ye}x5a64JNxEo0krW zWC7MkmMc&R_^+G9r=iwBJMDK*Z!1ssL%090yEI09M=7Z?RS_F1#-;N0HbDFMuYao> zAh0~j>+)n5kSW(j$M|w<8+FF`tx0M^$>#^aILz>BUUT1Q&4C|aPY@V5Zi=ubE{Psm z)ToLC1Hj6?tQM_r3qAh%3unC9e{IWX&j2sGAq7w#2u&mcyGEeyRS+}<{W1lBA@ZGt ze1I3u%M7Ee3dk+4T-X_QQ$;tqkzGrPL!7}wFRO~lk$Ogwn z&AJ`$3W2=>?*!POD%FG>JO41{gy8V~Y!)+<^50L-a11!9xD$>blDd@0KcZ7^I#eKsJ zz`YHzlQ2xDGEZ%ov+RumLyFDVS(MV6Hlt|ml$l-%Y9MPyq~^ZE-TWiGg{{__rG z8a+SoIy|G+9I6-=b>CBcrYGC2+u%B5mcRb{ikGc|jRrTYeZsbp$S2qGuaoiqg5@^; z&g5YZ!TAgsD9R!a(SIi$^|*5Woh#N8UccFJU>j^e(ZZYZRB!S=v&<7);yJIBsdh7h z&a;6wkr673dAYA}b4DY%PEuyjf3D440GY=iFDEZv8kd6wSc08fK7|^;QQc!dbQquT zj?y03Tzmo3t>J3~GOb;R0^f`|c&1@&Bdboux0aWN#2qNl`X8DWx8sAReTzBh`0H$2 zeK9quKw?Z)TYu^mzKDR5>#^Xv;As5&Yy8`0>-faTcx-w)OQ%XA(83bgt=9&g()V@#rr$^UP*-p1=Rx1h`HE3t(y zHPDY^@3>_{N3%)99k>n?Mbrr91bQ4UI$6X@5C0hTnt334=VCk9X(9J!9~fIMLcXg` zyK{rE+QyXfKu{$G)PS_;K7dR5NKb>=_G&ASU(5*@_>98O*tu2=TJnK9Nr~mBnBv+J z5tYPcIt~=^=da1!+%v6?f2>X$1aH4Xp4ERXlFD=tqPLEWS^^AkphTSj5zMItHUhvD zP=>W)x>ks)p4`fEfvLv%di5)y4UUbodbpj6_1jFQH%e4TjDYTU1~?ne_=;5|j))pe zU-?kMftQs7AYvOhI}9sQ1pSrQV$h{(?R6ZT^jcy)-x2_MQIL32BEHj`3B6CGmiQ+w zzvCX~{F+Jvo0n!?ReTH2K`KR0#y$Ke~H9a$!Lb=5G;9 zINck1CCFv%w`Em*MDz0R-~DHlZ4#;=bHb}&TZZ5;v69%pvuPB%p3`5>UYWm$+ETcZ zoh6rmE+sbEa>3OwTp49V#Ws+jOB;~~`v z;z4xzoceyUQ-ROZQjxAuo^F(_g2FdPr~@>Pp>o{-=dUN*7{cLT#dS~zeY#H)TRi%q zKjts8l!A3)kSlRT&c3PSLzsD3a=ln)PAV`ENkc-?^zWF!xvjdx9%-ye>PA3kkY+<- z41TqDr=7~Y;m9k?>4KNP^fPCb;6kl9SV9%!67DDrFI2>SpWM95LB&ukJ1fxps7oW? zhk&YBpeH&2+?erlF{Wfg7z32gW~}+pDH_53I&&yR3SeLL{J|Lkafa}wJ}Q^JNdr*Y zmlXed_V;)N0O(1OyLktHF*2BC+LVNB5B4!|@pBU3Pm(zHR9$IAk6W(0z$ZCjz)y+6 zGRmeL(fUED*msj=#R9y1r}2|3Gp2_lX5slrVhve0hh<~m-!pSM(M%OJMWP`f-G~YC zNN1pelz`dSLO$U?S9Ol(nj&MNL`GgWiaOVAj>mh0wt&XhcUZw+K0g!MvU}cwe@G#B z3hfy7RgU=PfaxSb$ueRhg^?^eHmi@dp9arrmrF57xiZD_#mjKHfio8H}9OpEk4b$o>_ z{=Pi<7sqLCfCO=#{iyV>2B1m0W(Hbf&XUzGgT0(mqbM{eSt;ykQ11YhfFHoJiah`P z6S@g~9q+hm<<=ZPt~l2LDup~L%jQH5V1>$Cxw;QK1KJX}sYq4H(N|TyuUBU0iYxtB zL;lM1Y$|dL7Ep$TWx$URvIl@)fVN?orCFn^725aI3{Rog&iZ4SHm12y2OKy4Vm)zA z{2*GLS$?~o{Oj*9@xg}LtBs(mb_#x_E@DH$Wdfxl{UZoccr_HpI3hEmQ z`e85^k{7ElXaq%39ILrjHdhl|xYc5(knZ=X9#>3BX;o%<&`FW2`B$YYw$GX=-WravQ`o)zylecMi+rl% z0s_FLx^4 z=vTE{F5d0()AHB=>D^Dvhl_&E?k?CE39o?X8VreG_gP89rF7H#_TTbzh7K2ON zBesc-x->>^`P%pNDV)yGwLvc1deU9XfVx>nEL?sv2-fU;kiPzL{Y|_>Yy55l#g>lw zj-rhIRB}S!!srwiyi__ZEPazZpKk^cxifzfmObn0%NujbI^*CO7@;q^4X96~F|eZ} z8DPjPc4b7zT|YC=jbQq0kt(^1J~vZN^iEuih!=k2a09TScqA+yvU^q}>|R$fSmaDK z?u@1J=w#~(lo&}l9QtJ^bGvc-e^B-oUQve+x9`l*BCRw-Nl7Uo;Q#{&s7MIXsepip zbk`sVC^3LYcT1;q2~tB0Idu2X%+PV>_nv$1IqRyZ8R=ecmQD^NmjP zfBN3<@IoRPJ1M-2DooOxB*73K=#`~lgZ2SR%S&OhTJ z+j&rPk+7dPJ1 zN+S;zvij)19`tPT{i(_->tu+U3UBg)7;I?utprnJ2EKy!U%-StzUt`O#x3>t^S8^M z_R(2lxfT~+x5ilq54HQVN1Ud^Zb0MjF~7-k$hJPQ^0vfDodwfUZ0N`c_xLf@IZpOI z8ZP;F|I={sxL%*QGxDJT$J?{2w?Q^pF_mdF&I-!bc+51mWtG`%e9{f_Wfg$y2Ob!2Xh_U5*$>^t* z>n2!YFGdZqmwQYTOyy=20oWq&-+N46=nbpDk7a0J17I9I8r~i?q1kd!`YsfHR=kG; zE`o4LBn=M?($^^Cr~iRWpi%;c4Fk>nq`ld%*ghcbBk30cN;n=Rx9+kbK9maN1K5Xx zo}aKe>NR^phonL#if(RV+A{#TFZiu?^h?~&0N#UrpGsx%%Bwj|n-86%A4_&1!_MeN zE2oR?J6d?(?j@Xs|F13psk>39>lOXj`$Yb-dN%aSRwCN`eea=L$aqP zF87{+s)hdH*$nA3pL~84K4|SkQlkF)^y8<}@={eWZe+!HnXABpfmIe%!HJ$yxisu} zNiF(PrLLNE|%8SFoYfBJqD%#>_i{5%8xkF7`Aicd?QV%h%hZ z3agKh73b!qUh2-(a4_jOtGNKK3HYU7N$qR`wl{K6b%GP9b$+R$0U-F}fueDdkNyq%ITkUaD%)iU~ea1fbV#8@z3PeLN;s~Q8mgJe!^)Yz-$*;ElEcp z-NvChiU7S8F1nqo!W4_&gGG4}6BC8cqCc^=leUwzGv6It%4uHwUx9OiU>L5f8%gJ& z9!Gtrch~<3Hel+9o!HqJOnLu3?gG4uphqphI8p1;_`}$aF1Od89cG9=A)hQ+LOUtI z5aK6d<|4Q1_%EzfV+eJC=~YA+LbD-b1R(SKN~&cKOvK08hVACPA3=DflqcnP7?~6{DuvT*WIqY!tk8?s0}6Ag*{HZy?MJ`J8?EcIFRd z*sI*17QJ2xKjWALku#R#t(-eEe@_sb{C=V~TwnEP2_gM~qMB#eZsIb}{_LM~{f)?H z#D)lpy{m(iVJ2(Ss3}7F@M{~(w!yx^#TFj;OX%rQe2Q0p!;Z^0KN8jeCf*FEuSBlv z2I^8?0~&}enTVSifK@lj-hfsC(k#=qtmD1WJex1;_u@-khp$(58}?!rCLZk4_C|H4 zk=>Qqu!ki!)Ft`3(RIdpW@U!XK4dJyYjRa0{Om!bExKZD+moTO^<-vSBtryFlGXFi zYq-cxHsCDad^5^@nPB|Cw0EEm^84I>ue~SXwDvCV(bv6fhVCKy?jXdNV6gr~n@KlISPN z5*?~Y4Ca{J)U)Cl04xX2-$~zOw$uZK(g7i!PvqM+p_H5fl6~dDx$jJmb&0amVq}-e zDJ;W2V7OQtv!Ob1+G)g@_!W#qMr(hy;Q@enVlvd@P0M%5mv5~S<$AU&gX`6$XKb4m zm|Z@^nnj@=<$Xk2b`QM6*nE8TTszs;IxV&gW%5>9o7z=&pC~8f)XCmY?NnTaKzaw2 zis#FH0ZQ!)@_^bCu2kLHmAg#=@_+diDGHYbFj6@;Snr4Xz{dPfN8I`%fIaTaua?a3Xe=4HAWAqJc0Vg~7X2Vdq_ zukR&W9~K1H%)W24#q1^#GmQDAmFzy4zlLT(b z&1^_g3Wm#skBAbd<|zH0EoYNHuSeE#@*i(&DxG5!+v!P|Q?rOnvVB+i($S zorjXJ5;x3b965~#h^&l9wb$kZ;f#12z4#B6>8FL4TRFpjolo{PX|vnBb6tpGG{T2~ zPx{Et5g8V3$l(}5AQWbU`5LhSioaVSV0QxdatKiXGjMP_#kmS#vA{<Rj9~QQeJ|8EB>!uX_N-%V7_+gTc-^b|{8#nA8 zl{L#>*oBaJ5;X71cU%5=lVrUGD$*Sg_VByg-^VW-v{j4Vnsu(X8rgAA+Q_EX3E&F7 zNGcS*T1yR5KFlc?6&1mfm|7RazZ4rf$?9YOC_7~JqW`G(dI91Rh0a_1+%O2#l*lw| z?=fD5{&QpSxyy$2@cbaENWaL$ifV#s6TGM*yk-8u36_vz@eeHn)7O(k5qA6?L3WB| zF@&H~m-%2kb3BLsjRc{8jQaP&hd^9gpN&Va(cyP5Q5gtBJKx`mnx{p=OBYoz2UY3N zL^>azY?SfTLx3TjYZap)zf;aHfQttqSJ<$?= zF>>I*El?y$&bR>7ZKQR3b44MxY3ZlkPvW<&1TBj+U_JaH=x@buX)@j*#khMfTG%n? zl=`y1+C%eZs14KP?X)D1#nQ3%e#Pdu4^_P`#Uk8J{0xkIuLdQ=aiq--qRce={37Mf zU~A`p2J41rC7W=kpi&CC_VI1OA|rkw3283u@XMAJsNDt@0iav1|MIlAcXb&2wID(? zM)Hby=_$mH9##@)*VR`bo5>5+0+a#YG9X|0c($v1)&YgvZ2|JdTPsUF8pv`)2ylpQt2qr8;C5o&0&JMa4| z3d&Gtu9hqFTlEw|KYGnL>#(7B+clV{#8^1?z!}B0C%G!0fdsP6Py@&+Ml((NM?~G0 z!y|%+PV}=SnyrXxLR9VmKeKXDy|-qskp$jnQ|(Q02$;V%|IceubO?Ic}XQ=gHtA_0no|DBJ1&TQzw%iDRBmYZ~ zpf9h=$7XB~{jXKU`PlR;&Ss373A252dZnVZWIq}5#ofNJ)nR87v%yjj|CI{(xPD+g z-$P1lt)Xn2B_8`aEgn;*vE^-*elpMP$35J<{JhmNe9qx?Rb1;>Xx-7L`k43RoSjEx zI$>0E!@s^o1mk@?mv!HJ;)Da#RCki_WkT53VLDk2emjO53*e#-y)Z6N_ ziUkXY-)54~g8JBuSr2el3!)!s1@`guwy%ueHLzP-Z7DM;SW{`9|I;&*HS0QK4ZD!S zKu)G=6}K3{_I$}T>$c7!8@}gD%&`<^r{c|l!>N3!oSqwkSJGg^)HAl7iXJDEdDP^1YJ66-4n#P7GcYvB(L=nhG}M4mJnj3Y^HD%G@KayPcnv3VsP8?7)R6)z zx@JU4Nx12K__L#}Qd?Zg5K1Mci+=6J3FHCF5D^3eP-~U>EEoNXaNijgsc3$iRSApi z2MDCHVK8k|qJ-Q0(`|_`bGODl8{1LaRQz+>CIGxnMErHXEy{sP{w>-v`%%+Ee{zhJ zd<@CQ0fQN}oor!Xu;Ky-1qb)ti?My}5jo1Y;}n{LnZiEwHG#-AnZ>7*)@T)3%GXhR zg&*OuGz!C$C-%pZ8r25in(K#C_-XXx?PCnvjol3N z4wELH^^_Gaxv%Ga!|x@A>pq9bgL<&lu=6LC;{6wy%_M9!0ME(-e9FtSBHT5fagSKg z96k)#Q10yjXaBJf{(`wGq2)_ykjXh-^up!k zx+%ptGXG@xvbJ<*D5V_HkFMS69^{|kud6F6Mq#|xBK-kb5>{N^_AKEc2sYU~d>E2f zr?eL&z-lTP8*_GbmO)&Bi4oAc_k;_u*2!~5!04GR&Q4k#3KC&P+u?zrRpk~y+GrXV zC$-F10+;V668++Q!Og7SKWfSm2OL`#NJ|<{;yKAYp@R{afNtj(rcn+2PbF197;j4m z8;x@s73a#n{!pWBEB)MJuR^;}$S&x_Y?I9;NEGhEH>C0K{W|SZZE}oaljizu9FK(5 z+N@P)^=VezfNMeM*W%(Q7f8l*ZorVxC+2tp|H!10ThYnp>l)6Azkwweql>8oeEirC zdsN@u`WS!#sq__QQGv+a`K>XwDBr`3s$9r8V;Yp`&bq;HKQpJLN-eT&CO8Q7#`%+H zIt#H{fTP;{0yC}LJkhW5&CkZdkDNAacP&c0g8X1%Hx+9#l$wd?8bCL?qwRidsLrq? z`q!|kJuHvzfruF`z7{uJIP^aLYn3>_eVcTVX9z>N|ESG?Ks!4o+z#ynyN#Wg?sv2) z*sn7`+6TWr37uHaQwn5UJB!K{tu6gf%PxInWEk^Mv#%moyjeI?6uQT6r#De7RoYg* z()iP^F|o}XXm9Fmxrgv?r z1qtkbu+BkHl$q+Jp2NImhS+Sq?xbqiLBM7kw1jkX=nD8})7IFez{4z zzBZRlHM%Dp?A~-P^h6dZKODr1LNKsL+k-jeCNG`Jsl${-|>p*TOHN~fh zz_JF&@Uo;fkp!+7DixbF>Vg5^mnr0iV_BSVqKo_jduCU{jgf%MO@Gg!QM#>|p4HB4 z51I3N;d~|9Ug^6b|gjm4#oxs+XJ#X7~^^7QlR6-9|RE_3bs&K>a zp&4#OtUZDh>yimpj{{T@j5y|&V(9RIMdbo(vikn3?$@rQ}yGGl}m)N{I<&^{01XMelCd zrX6KNZ`H;IHr)eaYF#mv|NDwZ$41}g5S{X#7S}EM`+TlsO+y~o2kO_=qN-XAIQK1n z2h6zM_4XL>Ov-tcsW$BsxkhQLGwfB|P9Z*e1!b*%)7yh@n1pmKhkG!^{~qvQuy1O; z`rx(w^9l_a(?2bQtZo{t$906tt~#w%o=)RU6;I95vkpCg{|rRRI{fZ2?eGrFm=(CP zYbez?b?HuM`2jhQiqPAR`6lMWf5nadcg5osm#~+~(@oTB!B$hIW<%O=m^YMF*DRDH zS1%&xlDugBs}`O7=l6VY;)zqTqi*^MU-cImZuL5J?bsm>Bez*z zX*{`oe!TK2`)Bk2#?1c@_x?X1x+yJL#DS?hbSuH?Wor`ie+&VKgS$1Au_SFN0iXcL znKLP6lq_1g?jo+N<%bUdKRl&&u6dQvepYSMsoMA*a4s+z|4ZYSjfA$w4ukhrq-;@E zc)c<0DVYzLUKf8-VwZ@W_?oVWr{2+M77#W^Fn?=%W}*tvJ5u` zLQaG)L58Y#s%);7$fr{6OMqdd*0F9zA=6$TM@_qEQu#6EOqB}O`W8Q&mLQ&ecx5zu z@6mcmQ5y;6%&OdU|FqV77D?ARZu|IDe!3pAy5`{{dk9OQ>-A#&+sjOo3RRCAz1YLM}@7#pwb_rv9Mcx&VjrV zIP=j;&>Hu!G1EnFjJ0gk**)!%7krBm+&uF$(2(>@dKfUN1&ArXqipW~&Q z2ElHS9V7EdwTK2@odN%`@xDq7<3x_zF9Z1aS+np-^dHB^kEJH5@jEO_8=E?63pE)3 zy12N;o{+s_>^=f$8~DkT;HOGaR#dbJl#&`ZvpcRN10pyBAC{X;$E{DA1X7mk)tNQu z_@Vcjs_<_b1#oi^_gi#K8k=oV=*ZZx^d46N%nUPNcdtZ+N1!Fzkyp%D5hD7(w;+gDS^N-k zHZg2H2U6JOjgkzO>IuJ!W-EOsUnF*xka!TGJTOmeA;i_T(B=DrV4<#o9W7273Nx44Mt3df_|V>iY3SGqQ9W8)yUW0qHwrx zzm2N6m~wDdQew@PG(B&d>n@&^w>xCgw?+pc!kr^iYjmJW#y?Z!XGyyqO=_STdiu#E z;_4B(3!s0T!fUPPN_t@1d^lWfM9x+T8f+zVZoP-E7YGb#49Qt&2DAWzSCe0#P~5}Y zpusO?$oVcxS>g3oczlF#avA`X^~Tg2QYD%<5ej{XbaAqh0chwed^B-R`(b4X+xKaj zeSNZ$3b?1LhhG7Vi-A&??cqk`!9%2nsTnjGbVyG%GyJ46)yGXBdeMhT6yZ)}KFoFj zR$i6f7_4IHZ-E^08-=0u^0^e$~;@+CCfmOVCQkXX546 zc*lO!pM=#Ny0#N|e@DxcqyM1mXn11hs47u#>l5ww`I&cZZr zbtZ?XIdB1JIM(XFeVhj{h;;x6xjDrXU4(VACXL9kiCYprk}Z%)ch9sK;LBNDpecFY z-=`wnH9}C6PICx&Nz_i$&f`LUxN6nc=l1aCv>CKZ(w=nLhX-Ae?|s#DSirJD=obyqLD#~@&cCwDR5sR3Q5=o#nsic|E`a(_u?c>8&}FpK_|9g&R0GqAAh*BrrN zrQ>LlmYC35b7)o#9?QjfiwQ8>%T~ieK`t}0+-d6@+YBzsy>B)hbrtev5|15I15XX+ zI#|na4nbZ%b=Z+sXE<`-a!w!!^pDQN3<+=d*CWgxxdxc<{7Z?8sj5m7QBSgZ^o5A5 zb+-*0d|RTSa3Is=H1NKgN_vCbu9Ft+^>lrv7H!CskX@2`0K1jDJzuSOJ-o;T$a0EL zh`wl_VozW>HZmP+jHoEhai6LAPaMyS9lI^cexsm!V3exldHNXQL+K)Q$}wUHkMFqQ zy;_H$Go(GoGHD=?*YG(c8yp)-K8@EfX&KNV`ms0Y?DC02Xdd|-p$MhNR=u0N2|}}5 zP}r+$K1314H|v`E>|=unt1O0Yp|@LhRVK}k2r26G$E>9CoA;^o>C=r`uS^PbUTQ#% zwHJen4KnBKv&{&eJx%L zc_@7HMupe*oZ&Jx6`pW1#F$*So#sA;WA|oVw@412IwgA#7he(G&EI`+H}M3D zJ1zvMm_i@Aa(Mhdn`8dhmENwJA9!SvOip|g8#zGwV+@#8@bEM|;1rJcK?6pFH@CVn`Lgu3FiX->^qQSqX2o*Tx067&< zUPb{ia)SLIKg5Ms6lX%^uZN?ZlH6-|mE;GCIn*9ds?UB$$E9pMQ=(>QPaaz7HhCOY ziZd2Rs%r)I(vqH`zRce{c{F3QO_@0p%ppMZo+g8ot>%)s-4HBLtE^ompCXkf^MAR&@s&p`a}=WS9nj(@%2m2#RGaU1 zr7Tz9!LeO(RXb@A(yz)FmBhB0UsT!6M=P}lO+LK?(t9&v6L*d^315(_tb0Atdl2Znric zmf`(-vp@N8GI0dgR@uCF0>w2~3%JkDf#LZ(|pat3r9eHclQ$qdl+Ra=fGS_+j;a8qaP z9~FYqm53IkOZh-VE|5kADT#%~_{c{rGe?D1VW&&kDwwA?c#h=_lPCjL;|Y7E;=GH0 zp69aB|0I^*VmV;V8~Y^EVP4vG<)FGHUF$u?pI5(vqfc&Qe_!gcX`i+GCLO7Q^2*CU zkfoB3@(YlYJ}N-p6QH2LS15;1Zn@;J9;i8XBt%sS4Aa?aiF%Re5vqQYX51WbIU}nb zY7j9+*On=0gIRvrIjl5tu!!{*q`%)zAE8I72yMLIMm~3ywEJOWI2mCa`IGf;_2hS& z(TzR`l&B9jicfAzW%ENs;M$4hp*cY$wzgQWD6L@DNw6x@uFk9P*=Vr&?#6nI_!ga| zp9vJpIT%o;0uTp~JEnv-3K^SF*%&~gq5#Pl{Lf}_Ydnl7t6H9l>7Oe7JzChWrV8~` zJ|k4Z4@PB7!r2dWfZTsr11;@OeY!$ZlFc0wZreN4TN_v-Si$qF z_6zANs|H7N|7`eyOo;cRfU2bo!Co42nJ|TopS| zbTs9n=+EkG5Z>p!;hEL(%=4a3)&vTo;07J9f257Rvr^EqWZF0n?)+ca=wv!0=D9Gk3WYWCcM1h^au=0gzOSTwQyfb&tp`?oLr zE?@R0eci`PY;ApOZ!&w2QcT!l$*;`QH*t271%f2=fuGsC;+Z{1PprPSxoGKO3qlP@ zmN~5*5S_l-AUOdrGzS=F)F?7to3xfEyf~i?6#Xk=ut=Wu&qyygPRhQ4Bn?Hbnk+(Y zvW=+H;^B()@*$VJ$nkgnbtQ8Hdmo0d^#)Ag4-Wlu)4LuAn|!uFdnd) zwiNW*P``y5Mk^o>CdvIOZgVr7a$8&PCzEJ0K4=JQ^NosTYUpy>;)9A(JG{-D|94vi zFrW24|9!tpuW2ro@D15g;&3{lId}W>Eh?}){UzaAcF%oBT{jtX-J9fJTHCr9Ti1Rd zFWvwludf&qj}5HQ{`%(MhsCe524C3NFM2x*Mu5Nn-Z!Y=R-^w$89b)nH_B=eDL&8& z5FzeYbA;->Q~q+Pma-kEhpunlHl`yC{- zO5@dhln*5NI!Q!DLd)SP<$dM)c*y;@@a(x8p3f^J!Q6v$*#{(&Vf`a2r+QEMMQ)|y&o?9BM%S5-$2eRio*58uN_(Ig~*QVjG>yhdnMqclnI?flO0 z?fG4?I=MIzUMFIM(`&(>k951_ zS=~NZJa*-p@%CZ;`ODCGPMkT}f`L2e;Hfcw`N`Q2XVO%!Czm&@L*1a5R|!7_j@`}ZhYnmjU3UIJJJ z&^vFI15bNc{T{)%0eLlz5TsP!h4aC}%~XyT^6Djpj#N51QL5YSQA7WSG;fwCfTtnS zP2$2yJE_?XXFbGu_Q*X31e+RDo8McC9r~KiXoO5Er-<*l@DBSd4F~iV zze7W>cb5e-c?5G6*$kK8^m$r#QJ}bfexarG789vx`#l^cOiJ9+&`?JHk;3AOs?beB zYEPESZwbS^y9SOKEwR}AM@mdUS!ItERw8rlXYt8paMXgNhjMVE=S=Y|rgh2HL{;yp zTZzF~rLNs2v+7#En<)*^q5;&VjULE?4h-!xZu4{qBRYnS{ry^R88_q!v@?KFj16u# zQe*;Q>sV9JrDRv>yd zl=b$t-QEvVz*H0+UFIrdbve4$3s?=0BCn02dEh3gKjBoAFo7AJb!sUEGw7e-nBuzJKMC+%SJ|hOc$rC=I>`;6#sv8+zyu&CSgb z!|2$yOaiy+)d|ko-WFwbkW{UNpz1V38JR-X1!kpB@l|0AsS6(X{Ws9w*&ii-Ad0S7H`k! ztNu&JcQ2Fq{qshh$=sUi@~_%=lEAwhR2|+fJ~1O{Dh$^F%V^wno7nSe|0iJ(3vqK@ zc>?K_#^Ktk#oeg4g`8;Oy^7eDvnLxGA+nl&7Zmnz`L6; zmLvz5jKf?#l?Z2XPx>Wb3Q~uZT5y3$?#YKL87qv&t#0MGsWMy7OWQBJ)lbM_MbANa zJzBBW1|^($Nh9JX-=h7qNt-vTW{~vy6hCZa=Tm+&_}n zJ^$O|=WJtI?YbtVBvYr<95;RQgjGSPw4UQfJu$PP^<>@2^7o#kZmZz6U&n;Y64!yO ze&TY~d}CIr$0BMb-ORFEKnByt8LHNCZzpWZf_%S zKl)p1(_KlLKCag<86^(Bz%}C~{~c4&`DwSo1UZUZcFJ8oxTS8iw=w1k!&-QKHvj4i z7rwL_TyE*1sUloPHrHZgF*|kxvtOM5agjq@8+Zv7+;7P-GtFGy zwIE+13;rnlA>-8Zt%N0#)oYH^%D;-vMM$KrMOc3GPt1f%bbU_;I+*g7oR4S7)aF8; zC!HoPNn+1YBUSvH02gI)<=4qQs{H*#n(+ZqkSSN2!I6PiU)F`-MPfRoUu~MLnnZCb zBq60WO)vj@!jKyRvQn^~G9-N>Nog3m*Jzb|-gdNjJN$9%|3}2X1;_CHpAmnYqOYCQ zC_dLe7O5JzT+c@?@Ul+9%>$ltb;nW5hNVoxN`a%nRz_G`+wUob z7!$$5eR)8?RvloJTkz=*14&C%y_CV`(7n;GxvEG}nLY+Zw>3q&p5qSnMn%2*-+Oa~ z!BH>M4a*_7ra%9w!mL#QrEWp#^3Wj*zI%?Cr%q3`DFq3vM-T0#lBt5e&!q-f(TbeF z*sKPrJukA<=O@LkVqZ}e$asrPfBBThX7Of);HwDyPjU#O!LoRtLzQkmXic^_^H)NS z{Bt)W#=6gSz1n;yi;wyg#2Ln;^Ws%9^M6*DCqF1@eU*>{1zXJTt4uHUc@Jykt$U0a zI7m^XsS-6yhm1KNtX4{^9{p|UxRD!MBxIq8^($xEVObOHKFgSKxwpD1g4M?JTcoMkG=X!MT6km zu>gT^WGJ#-ROaeQRYmt-zAI1Tbc5;u9gP#`-5r~+Nh7tsg9SKt{aRLyALoFB3bkFg^bHK>Y9vRbR)!=(EJlvCcUD%{nq@@G6ZfYzVFA?M6qv( zUS>Mlo8D);3Ls;o6QE@Mffs5GfNp`8v|&oAevflpMmt|Z`$8$e1c1vJ7!sbbuan{H zUG9zXtZO{e&(Nb~6Jc%77Xm6Bd_E!Z4E&W>#{=RT_)h0@nbQLY;kWQCp(;o9v;Tc% zqR-%+@xP&@> z@TqqeAG1YsRTW!tBf^QSz1e*CH(dS9%8RZT>7*?3t|*Ah?9ubsxv*rHWNHM#S*l8~ zT0>P(w`;Cl!Q%!AtvaW52$>H2LR_p%OMAM^TZfL@GkmmLTQ`5YGZD@xMUq_gSFlII z_NNIB(hRZ$Kbd_i2L+NQ8#R&}{v=q{0d&DU^Z20`CmC5x4ACX{ll)tuIif5{2Ujk#)r|e>7(SDmqIp^ zBkk&0S~Ml-%k*S^9q`R3U@=}ttI3Y0c9ySBG*;}|9!jdm7j6e=K=<(`(=O@aFCK{j z(5)L{_HzCLP$u1UlosOhWum5##S{cQ1+(xmXPnbq7!@E-)_i$kC2K1shJxylK^Y5@dr&0op{ zTlfID`1j$Ph?`Us?$R-k0BDQUoPqIF_>>lJ9Ka)JH@uQZ2zx__&|EwT#W6iP_7@E8 z{4g$otG|nEk73qFXQf+$bnlxBbLrKT;w z5-RPvN0CFo)hv*b=z+2f8s8hCnD&3yx!rT*m^2`Z6(uu&((W8TEYjXnWhA#gy>wZo z!f>NdH`xTVjaZzdwWtTLemWGn$(4Z<>>=}kWxdL&lnqC?1@nCJYoHaVJL2e}-08+> zCx!JPm-)x`q^%GU%V+dVjPQrfKn#8uoF^)8RzvpU(VD!_8QgmddHI#d59k^?lqA=C zpT!NCWE(Tsn5*HQPA60_uzu*y0zEfpPXx+Kpy!U4VGaF(?2V+aD)OC z7JdZ{b9p&uPp$G19Vd3J+Q6IR;BIBmH?}TJJ+#A*#i(Qr*dyhTM~&F* z@+gfkVye<)m;{+Lf}8XWbsswORqO`YhG` zW$UK80qa7ZU4e;mE4JG!u*^PbR=9|slI7|rV5dWM*R~EbVAVFz)i7jS3!d{RSe8#m zsW3lwmPS0*9B4RN`5y%~R`XH_b?@p6Y}_^Z2- z)yxsD;8t~&j_2S%NWY}a!K1zZ9_iP?A^rc+*{oQytNU=VzXGhQJDV5`{6z?Kx=iT0 zkVwdvW#rWu(>tgovqT1Xn2W@F@ycA?FnUsvUf}rqW4VB`ttl>jI`Fp08#Y%LZI?H) zR3nOE(CqKR0EmtWW$*Wt3K^MHKz*<;FgU)pF{WM7rBSMBAV?rkA_&o%1ZnJ8yP-LbA87vk5P~)E#dNS z|9d(F%~1h-!kKdz6>mz5o|{cTU04)TuKrQy`=kcOd(@9FmdS|8pCDcm$G2Xp-6^_{ zqz8*{jh8ySE_gN~3=U-`Nc3w{5~dlc$jjCu1yT?ZsFcY8Tya zXYgKAzOMRG#Y*}DOp%E}eq-9uU%*KK+I9lFsyytqkxJqkABlEEGC$V`cBwgQ>Hzt-aR7v(Qa=bw9++Iy?TO+U5~y?eGE71M8pVNfaMco2(@I?x|d1g8Yq?HyDrA z{)m?P>~JS+NT7ms-;)K$PrTa`?3BXpy`Zq&I;f=qW(Cw;jVzC{&FE&s(r3eXY!6g#d>6LTZz#SFSTU~rKs9$dTh`gTYYLSAn4GW z{7zi*w=T8XkiWpDM#@k)5 zl-mZ@3!I8XP4rcfGY{$pTK>t{f0q&9u0fl{ig2zL(B5O#&G7SY^R6l#4jwKi%1rX# zL`bPjBvfI11psU5C5m`L8%n9GfdaK8%s20resM-VT-u5`#b)&r>F1B9!~gv@1!SRb z=%pO9-YJK9vTR*< zkE))ZRB5KdtBC!wD}hkiXj2#Oe}%T|8~&8Z-#5gxd$KE)`9kC0(8W1f&Hk1ZpAovS zn*Vr*u!~zWI0-Mh{N2VJJvXP@hjI$_GWCwcbzB^mC^3%3EbbEdPYsDH8xu{iY?ja& z7aCF_%`L1Res-vBt7bxJ8yA~U)9-1bz7lzNM7mdeOkKJUb@!%HL*ustgg;lhBl|Qb zCv0U*b!o0RO~Rk*7K5m&dyM|d0%(AN4f`^2I+ms%o19jYM`N3K4lCFGQe!)yljq|@ z%ZHj!%YR&`zDn5iC#BLJH*{qg6=1TKx6Rs!T?s#{b!~$)e%}3B{;# z*6(%s6VU65*QFDDurSrqa>)d0X3M_R~`b*u+S?fZd)}$jHS~T^%kV~VWnvi zz3qPM*G(|rE-=^EU9k>rVw>}IH zbT3f?DDRqFo4l~m6v})A@xs;S5So*j9^z-dUUwp=MiVg|f!kOpHrZaRs3VbzXt>u5us)fNxNqniu_jFC&98fUeEg)ePX zCwl`7gd2DF_q+TLDpgpKS*&nzNZ6`vkQe^>&|a3&&M)u0C^tJ3L-PJzUe3i;`8kYJ zWEQ(i!v)P>CTV!7ptI3%I?X;F#4-3wr{6cCONFy_Uzd#e*0JENh2tmbHAHe7;Z`{^ zXTy7jAzL|ec>X{6P~Nt%(yq_vYQ?| z&3KWU^z5b5Dunuv@Ucr*fL|{h{%e|Z35=Gy?q+g$=g@-H?P^fzb|X2VZRfQkyxk%; zoD?&+DYu&xaRJ^UArp&S8tJkOMw-@SD}s1p19)g=sTk58`YkP+(RD}l4L+S6pQ1yF zUZ}e9Z4qlh$FwHk9U$X!YDQcXO!XmK}fx}80 zU=&^|Pu-V=A9Q(t%IyESf!q>@-D^~FJ-z8NQzz5b4LyDKoTN^dU;Ga-)5__Hu%8-I z7Vxu%2N$tvGR3X~K5G>!9;k@#Wq^zrdIrIkR|1dB5pDyt6(S^cS41!jyTryPR(4v^cGHw=j66G;f#m z_YYJZ;?e3nU}G>)Sm}trF}LuPuc9LCz^gJ*w=jjiJZvXbP%u!)z9FS_4h-hCe3bk6 zmzs{1&VsA%$AyyF7hRF3n0Z;>wx^SIXLEK3G)^2WLlK;%3{TH?yO~`Eo;JBnUQX&C zn&t`**O3$33z`ib>fqcCsaoW#`TrJCEdNQ!U8jq4JJ4bR!os*bP&#V*9}L;}*4A7N z&-a`5f*j#>cc;nx6D|i^jkX^IxWSypIDQr^rh+>2*9t7q+5~Toq~bo8+68E7>vKyk z^F2o~N*fCSHjX880eQTB0CD8Em-1q9JZSGZd|G;fKEfS92v!#(cC{6!C&jbH3IS6kT!(1Q)6axLxFi2^&jH zi`#6%DnXBkVUN?W!=3jpkktsr*aoO>CNi~1OO=@*S^g9s^o>9#&-Oq2u>@K(v{Ph^ z$I+yuC>fwPs6O8q^G#g2#Ne4ua0fzC_a4pXU@*-)37&Kjp?ksP)Bl6A_X=vdfx3PZ zLX{3ml_n}6CG=h*h=5c@=}iG?QluxeARr*UOYa~MKsrR4(tGIAdksAl3GK@>^Sv|Y z%$)b)+$FhS!VL4@o3+(N$Fu zCG;dClqngsTJ6^3C)lUI+;q{R6QWNcrsqO|RJ6#CjM8%ZzpjdO&?@;-PoP?Zn7XG` zPQ}n9lkq_UA=ojF4osqvn_ZG$nk}-H1&Ns87u7w41p`#Mq|Hzu8`HM|MdlB+xU`Hk zhlMm5Zvd{I8JixJSsGjm1&o^odZ4*vWRSA0p=w8Dv2bmWRv;<>?PbmL-LoW3T4TuS z*GE4*l;_KARD-Dxs}&2nq39sg`poW*C!cLkZn&_1*$ew*q}lXURCjo+6CugxHM?cG?E03n@Ps1$@{kvQ* zu-I?s7qq|!5(NJKWxh8l{?93m(?CI9|I-B^(QoYKlqBH{3TrJ7#bv8_Ao-qK)zuu! zoWdfI&slM*3n*QaYu25~B2z=WiPq-gqnLmrPGH`}Ko8yv1>a^`c3Z2tgcUQy?#UZ1 zyxbW4oZr=jh>-(8r!?xe#l-)lBl|~ct$~Kj6<)B@;XzOx1-pl8j%)jQSORAXlEP3) zn6xt`%xY`u0+y*89e!( z)d*M5oZ@B&v|vZrjyGH75ACt|0JhTBi?nk?KS@;1pdd+7w3X|mV&cg1YBV&>C+uHl z-#3>d+^H|9!9VSDoE8Q)Hpm@HVPh1+Z~9TlwVg;J$&Q*Tjp$NL6^;&Fxp$SK<a++yn)>)9juGwnEa5}zW32AzMo_%lmXa46gj~t|j z1kXi&Pr7KsMzm4oJZje>yu?FTYySbFKp8zt&lg7=CTq{yJ6Fz z$$4)a@fe>^y;m#}`0mzc^y-7jk|_BvmOryTl|hKC;(}Z^)#hYssr|u@6HtA%wMILt z!Fh=Sjo2n-`5oa$8i8m#Gj4n5f7K8m1GgZWrJt$UZpehvj!e_`oJ{_^fu>-*CosX*c$MJ&en+ZX}6`M+? z7r@&r1;SkZT@mP}-EzLQiq|P4QKk~+y+1qAH5wWsdsHwoQMpA4t&=d{-pj2-Ki9pY zD!8iFTKG{Q;1?ZBGTI@ua zY_YJ5w8w0e0nJybG@IaSbBV3brwl0E+mTiP!z}DaPyB6dPh72sHST+QRVE+>tR1EQ zr6)t-Dh+#?ksMcx5=q6N9YgrbOcwc2Am8*IbP@SvUMxGhd^$MB5hV`fkJcbI-)=m9V^|*p8%Cy zvKwzuN}(OoPf4g)^O(J);OT(2#>Uvl#ty8lx+gklTwe8`A+{)pS)Mi3DpX<*d)3Rr zw2uB4tercPx1*?FlRD0gXr3-~S%QyK;4t>T1gWGUJo8}~O@CHcJC5+#{_Vl^8$(#~ z3O+G8JlMDf9+O2G9DS8b$X7ylMq|Jb?iOH>!;2S#Aif6b5W5h5(z8mcEKYAS2<{dZ zJC^es_EBzMeb*I=>}!5(F;K0c^hUd3Y2!>s)9=BAm8%;oJ~iEwKpZESPIIfuLW-4g z6*#QZPV?RYj~y=-M%Kv4Uh50Ug*x%N^roJE(H5kP2L%)2N9q595y!&bQSWyJrTVt3 z%1bC$NfQ4fXFm^zNRz2)OT2Ef8xAsEmGsW_YJV*$Cqm|;Pr>21Cj1b@XM!*LDsNMt zj*5#;09dUGrYQwC0cVbyPDK`Ki4r}S+F5G56r}pT*8TZe#1FlcmHR?EQY=rrosS*B z8`$d|TOJi+dB^i$(j3e8Li;qxdmcZUsMO`V2R%s9CUd#$hx4A=|242C|YA#aD2sBgEEPLiI>c6xw*IgmRDE1=P1SmYP?TAatO85Y9AgZ3Y zTn>+2)ZwJt5C=+yqxwSRXo}BCn5J;Qi0+E4{)J)j@E54E?(D~p^U8s!pGxFMVWF@0 zj`s|!MkX|XG&LCOEcHj9u-^c1_Bp4xtU1wwtsd215v{U0x=-N0cnv(w%xJvz+h6U^ zagyKEm8Ea&CPkfWcoBTL#ex$l+py1@Ja1kBa`g#5n9vc!41?9HADaG2lgaO#w^%BE z_mFeg|Bp%hGzaWdgHk5jk#vxccepzKe2vW?fjO(iMVr~D4{{NThh?`qbC{gHy_4`0 z7CG(*IV&%0e*P^cn71^nnk7LU&|lz3>*0p8=zi}ve)eG{Ly?!pQkJz@wIpYjF_3{< zt}o#kc~7FpY|d${3CaD+!ossRu*5C`HZ1(56)r1yir}PofjOXm&t?GQ7z7>Z)L=1f zh(Q>kcO>WsOjwGj@0d>q>R@IzFD!TRGSq@$OoX7ypoMRS;g{sa6EOR%Zr`7?o|56= zAU`=Wed#F#PR@GhY;R@6YV)?Zjo5qy=F)Kk@1YV+7=#R zre&kbQMX8enWJ`xNK4uKQT5b_V_;TR|8w)a{f{vp4)Al5OOrItS_iOQ7 zn7FfeAj^uRrJ1*X%D}-S%}5lP%hHKSKcFDPlV3HEs|3t@O7r@YNjxKztx)VW^PV~oc;4< zC)EAbIipg}nc%4DGvSVM34kKoSFt^%9f!xf800FgV4A};K9L&1EY4pkFM68d;YLPm z1lA|>;S8*k=)Y(^-TLqtJU3E?ODWXd$JBuo&FgmrxefzvD_bOhX^g(Fhye^bZ^_NR zwUo@(0NQa_o^WAV%ohi0fCb?OQ1uTe{zDWw{dg%_*5`zU$h%9PfQk&lkSx3-BYKKi=?LBM3b^nZV7nP*BVeF_n2>)F z2~fOYo=ot26~m?QM}NN{hMglZ&}w%kKkC?6m+*9)Er?<89lv5ge1 zPUC_c%|3GX$#4*S>Q~vr1d!bqe!3m$Pd&93;k)j}I!2Er9D1Z3&}-x0J>YzWw~X_q zppk<-SORCO+Ex~%KcB;kK_QwODCO`8~RL;Uz!FbEAnYMo+3_9Ns?UtRHyLBy2UagM z8Fn}{cQiYC(Kg6|p3L21+!)ku<%4fIPdCrqKP9b?GY~)^ZFBk}hDpx>Z(%r=e9&KudQMJH^6rV2<^{%2GLziom`gz{JlA7ig=eHgF_?R) zC%Ghvk!&8LrgNrb#8HHE5Zf5jp*Z6uB9E7y#Vx&~s$c5)X0|-77v!C-)r!eZGdL^z zDD|MU@|dF2DEqS6&8>5i<64KTajfB}DA@x}DfH%sNVXyJ^8OlO4)v`EOP38G>{N4K z@m!YvgKZH4H*Qtg=uyQrnIA2;}3u+#Z??1-b$Un+#!1g8CxLUUwZGlvVg!4|*X zJkrQRuNieIr0?kXwfR#V#8yrtL0;RcDl0__yXPpOeyQJjGq4fh3`dQwzgV5XSHrYQ zQl;G@1M2pM2VPondkx1CxYQLTl4HLU=|b#HOYf1h6;W2_)wG^};!~`Vxcr^PJkHB3 zay>M(k{EsL;UxaS^!sMBi<93E>~6Q_{_(6e)-uqG05#$7=ZQ35L_TRB?tW!x&X`Z|{yEpL`b*snQ`!r7VB$cl=G#0Z8@xTQlF)y~N9Z z32e_Eri>6&U+;~NfbN4_E_2~SSN9qk&e-*mt=hb6%l*ukRWI```F@B2a+KPUg|cyH z+nM{O?|-JeRk5%GprpB?wOq5R)g#5WBrO@j{4@CbN&C{|9#3-jmwdF@bW6lovK3sq z75R6u=E@U6Qc{BPe^8^mmG$a?nZoitX^;$Kb!lx3DVd+#Cqn$+L0&+%FTdI=CNE#B zi8yjL)=<7)`$BQ4Az)~ws_*vNCfkh0h#H>h5IHVH=i7Aq9WS@ZTZ)>UZdrT_wykjm zoMy=w0-aH^H+&V!ob7c3`6cYUBw=y3O}Drudtg1;z(?O!Q;wjXhJ9z8S{6C{0%l5y zsWD-1d#NJbmjsrwCmoCJ-$+r)nP@YB)W%s~l5*5YwABJg+%ExHLT}|Z{nxZowEK~O za5+<%jC=pe$~totHVFiV$%aA$Apo0YqDd;>pLrC2Q>WK#%PP?i5$cDekHurNa5gjn zLF8sVwoi--W;58xir@IN^!#fFFVLX-*=cTjyYJzZ$GrtuoujuUBR3bN2I6(;A=Sc2=TgI)f?~z?o1y0t*O)3zPZvm zBa7CEF>!@><_fT8kj!mxq;xp}3Og~Ad*Zn?n9xSMLmS=v&hTOZS^WSe49IA6-dXBl z3wSuq23WGs$(VEJ^=RW(@|=C*v?Wc*nA&{;jRcTdR?$Wb!6#(>QLlT>RwB&eh9GjF zNwQ$^u$a#rG4eX0^?(i>HR+e*Kw5zM)*^WTz~%_TCAOXE8^e$6d_4^eq7*>b{48J)ZszC=Z0-Y`3{q!&sjo~ z8%>AO8(RkEazC~))VlSh4S6A*2I}ZGUe|Lk;kX^+*AJ1cN++gE(5(=$J0$Dp5iZ+V zOXa4m?@F`mT45I^nAsnfI&51=#B(2zxZT};!xBXV3NF=WQ;y4`JhwDlr29mkQy4uh z!r?)NS4i0#ENgOwc}I097d(~f@x}Ml^0mCRf`g6Ju4lR1MY=pQ0NoNQ2uF=+&Qq3c z3Y~opuB+^+a?+*`!Der%{W3#*{n}t%H_Vb}bC|oQV9ChM*_J%wJ}gqM zH1H;LbLA$2im}DNTziDg-CizFeQc0-SZu`jgxm7&f>bE@sC}+U^YAj`ZZTq%K>B%d zY%wESWrC3a=1DCDcMm7?qTBE4H@Lj~=u?Po>nk`Pp`ud6A|GY7@kla>8H&%JqFaqL5(!n&o6~u36*or|E&aOvczqgB<^Wk(N(%Tz9_n>H6o-^BWWO2PO?5#RipC z*Fy8NrMQ%`i_F^pPoDgLslX#?dka^tA0WlH=nl8fsW`>Fxk4Trb!VF<1?-9Ms=b() zjv4^;YpHQ%S|-6RNA#bMaR8s;nnu(Q_GV9U)g#5 z_J{`>K-UR##_tqRU@zWqhp-*|H^}=bX;sc}lJtlIMnHwofIxQ* zY$?g(r)edLc&Fe`Y2bf4)P-Vw{mxprpjEbE8xsKRtA8T!X9a67<(Y^kz5^D=f6_3O zk|d4GX3J-5kPvFh8PG^-wPB0v*BOakQlRLt6L;KFsKz6WZTC&MZ?k1j5NxtZ> zR`Ha6cz^p?#qdR=@o5P}FFlSm=-#aTP;EY6Cr}~?{P_m9>+9x|rWAShA>|B1h+HLR zihlilOz2tdfbXBKp_8!Vgq$F35sXeqVJsn8`p=}W^{>?IHhZs^U>+3WY|HBL6umn= zrlu6pdn6$$^)YLvpSS_Py@`WdiwyOsu>02jtB&x?0=GKY!C(w?{LharsI@p{i{D@B z%*zY@y4G!F5=ZjPCd47&tuwrB=ZAMYC+TgsbJb?gPUw+|JIYpj96TKuo|L~Syb>ZT zNeZLEr%C)Z+COBTS(xX0qB;fbxb7>wWnR{Ir!%LHb*c@mu7t@EKl_p9;@euIrF1ov zCme$;`kfT}IMx2u&v|Vrm=(1FIF&3J^P30U$VV#b!3TeooU`=nO0NmCS$DFce~_$z z8SyKdhi&0LIX`pVNHa@jv+||;6|qUlaKoZZw%`px+~>1yx_v~0^gn~gkXn@ zk}X7@k|1N|K@KfxcTD#2r9+_i85MIxQ1fX#wpMFqyp~Jk@a>yl%Gh+HFy|j@u^eX5 zs_4ttLcx(@zayU4Mv86c!VAmr64~x`4mA-F+ndut4JnDL<9)nyh?ZYf;V#;>;!kOc z_QtK%q%o`erC|~~YV+t!-x+1H*`O^tMPi01k!X-rm?uD>pByWA^9vRvN##t*!Ls03wL9UqHuTz6H!Zf|_ zp^i1Ozdv9X-y52?y{R8Qo$=`Fqvz?{7vgF&Ob0mEW>{KB%O@3^M=`c1P#7T#`m=%?Fjy7+~5@Q zz^dKM8&vSOEKGL<@(AH}@&=u27VUj4mu1HS9MbF6OJ05Y<=oIS+p}`ZFdxg zU8Q1bJvN}d1}LuzsAP|c6U%Q>w(2s|*_WPJ+jhBYe$KTwBg~j8Sytxl+%lHhBCl;% z%wxn==w23=Q-_C{xO;kX$4;6yzskbmBcpzB+MzhQK1)B~b*i;Uj3-Wto~xcb6>u|X zAYyTP-OFT2k($yoceb)6wHYhxGg1c|{xe|dBtKC;UAMMw`TBM^Q|5RK&xgb6!mSWnhTyhJWi zH~90@9|F6;3=&k)EXW|tqxlCNyTCU77n0oqH1Ggb{LAP4qx-y1@f?T~m5CW%T);eP zu60%nn@Y9QEOaDnN z-z-qY2#=i$l43CdYcC;+!;1}`S0wmaxTd=>f8QD}7brBY4fOnJ!i}zmd%fi3^UGyh zxSuizFo>b>#DAgYVhyj;X&D0y#(|&z`W9vi$PLk3xfKSm!@;()a1`DkJg&R?X&9Z{ z7aTXd}=-d+ovMLul*yq-hG6Wvbwi2kyF zu;>ZP{?pgJGG^3*EX6ND#QeEHK211^gRF}r_!|_|w5oq+ z@)5f`7*{@igcG?ml{90L(muOeu72?64zb9kuKl2$RpJ21tlmgVO$qNiyuX}b$m4Lr z#dRqZvxfp+lB{ani0E|E#bw?g z#&N^L$>c2N0Hr-5U+&!7_56+od!}WApVD->N7{DmuQw0Wo;gwPDt=7>r^8BTO>eHM)NymVabEL4=%lBcEUoLN&*FiV(k8<0%a!%>+=O#;I(K> zGLxhC$3Y%CO5oDN}6TXS3@~&%#QL*hJ8-vp zxcs;;5O+R}stnL+J)iU%xH??qIcy1NFlqB>X+9gStM(6ZGtj#NV9%!}m|I-N40MYN zgTL?2M-n~{!uz-JgdAQky#!;P75=)hNa=4Nf4Odk8|IirklzRF=uLHjHqRc*y+NLV z3Y8u?Lt~#JIZr9LA)Fj_mSsjGeLu{bPtabr^Fb^L`*iCtB#X+!=Fn0_3-U#pf#&z}EFQJl{_J>3e?>S<;OqNsKpLNrvAPo?I747g}TYbcL1VFG#IJ z{*!P-*6lLj3ptq##ln0&z(bD*zr&gJEs+N>1Oy7vG@crDbei<`#IFK>chxwy3&d-^T!i?ERk?_zwNe3q>bqVy2j#jfU7DXuh&2 z9e_do(jeF@C8?pRVh86|k)JqYVPDp)Bg*Csi~>qpT1$h!0jT&RB({FR?U1bUan`m7 zEpXZX!i{58jXXgG6!{2#54ID2;qsttKTYTjjzcAd%VKKwl6vrRLLdhDbOyiLII#F) zF66S?Wp@sieQo*TXHSwwi@sVl$u6$J45r6GXXbt;W8b5`^5!-i_qD=V2JoJpPc|?k zKe8riAIkBK;GeQaPW2NVwwTM`{Oj3B1FW*${Jzsam`@fnY0>#v^;sEAf;W{C30$3G z2)|qWjgwoY;sq%Bxel+-wtN2X*e{-m)aaB6nB=JGolvo?QI zo7{7ibFO_&v7=r9_sQQoUm@@$KN@dyOCiU)socwe zLmrUyxur?68f`M-`y zty?DjD%Z9~CoZFDR}s#k+oL{YYhgA4)`y?dq(I~zgPf1Z6$aF@);w&DLLKD`S}uGj z3*=-e%&s$mM~mi^%cOYTn>oL`vT9H@nHUM`=7p@^y+^-&{E>G=SYwzr*c^Gc-ENZ) z?KB8)n>#V7zaExw?p|_h-{*AJWIHjEx@Skaa3>0}MYnvAp!G1`N4-e6{wOaUz*L=L zWv_^i{2F#W`>SGS4u=7Dzsz$<{%A%wU9yAXvh$Vmk9=_P7@*{qJwENu>JZ98HEYz8 zvGSkx?`of$fc)RJe=c&31Jr-ozny`ZS@M6{f6W#smlrE#@diWn3@(qV(!j4EiSR7& z2&z0L!8O8qz)sF=pR4U2p@4^>MzZW{PepQQ165aV#ocp`b2 zGIBsIC6y6fE)iY|;IY|e%~21`mP^|g%B`M?{N30|{u25(d;7V&HeDGW6`DDLi!;#R zG&VW?7-{FnSN6458WjY5UpZjFo4|r8H`5yIwc2T z!kL?gdc`$CE))^dd1R0br|zDp_f|TLQv%07y+&#>6GQagG3lyIq>(dG7Fufk@Fx%U z&-#yegFJia*ullB(XQ`5#i7jK=ezUv?^p3nk5@@8*}JcCk;6;9k4^Du@<$`piDJ`a zQat1LJJY1Y%*#P0+ae#X|NV~Q{*W=xwMoRv+bS|@-`vh->X1WR)GD#reW|a$bGrz z>uwK~y$_2}Zm`Y)emtR*)mPe-Z{K%bpJ01$h&@zDe?Rf++Y)_R>aIpxQ?N6U7-MG} z?~!#q^sXm~$sgT~j7^Ps21M=>W^y^1R$a6+!QP23*?5y?D| zLGyNz!`u|`PjIq?Daq}Spy|?(5aTd+GjZD>(bPW#3whNPSH#3ze zWG2cZ5D(vdVPP&QQW_&hs01{;Ao#MlME_T%qpRujtb>_1@lzg*RhkAiUeiiOO=;gS zThwHr0MT29#=mjBwr9d`OqLSF``$jotzr!2&xspXI-zaf=(kD%5Vzdd`yNz#8E858 zS^31C1(_;6t8rtK&B7%ylF!4x#k^jTeR95r43?GEXU22g#zv*I|HK>eAh#T@qdI$c zf0`bVU03%mkU;b>8h`h}(ZBv=KJi1j2&_u=pXLH|XWl8Z9XitEv$qCF z2R_;~`Xel&_XDVcv%tJiu!yohc$j@}@2SPS4muItPa8E3I6{t*O(6vuw@2-I%QoE? z+;EzIo?%>u0qMrdg^*rPSExgGR1|+Xqv6jfQr`=4zZcZ{pf-{T~BP zXVc6~Y%65GBD*)nT)b==$g~YFWOe9!ji%c=tjiS)*|ww~49uz{%~;XAY}#i#7lCFj z+ZXPdW#||1H9ymYis;i1aQEsu0>~=jdc`Y1$EgKcd`bYv4e>5@Fq!==Ndv!WfM3Hg zk}+O=%^R?P!c&;wofp{Ve)SsnFF7xe4~A>v>7Vmj6!5AOSoFWz|H)wYlhtx~$p{eu zIv@s`#i{s>0saBb7TN;Ze9vcWR;unr6{@zY9fj9u_>f)?M){SU<`l>bX8j`S2PQ^*o|r!F*iTiAm9R7r8eC zXan3bvXjAw;PtbmT-CojC=BO`*70))d&gLRRs((DGdYERr>_DQz$dn}R9qIekWoo2 zUX%xjQL4%#S-V|^XX}zWmu-tf<$G_cT(>P>A*JHXF3rm!W8q`wR99iL-O;IJBH^Pqz zyy`>Ru)S~=V@SIRygqMLGv8lP^NkZ3$~!?KOr2P0VcE-tGuRN?!?H!U-In1qhtzpi z=nSi$LGxkoB0FM=So(zVQ|fo6qm$+}J{wA#yKZgVBif%Lh&d|Dge`T3cO~fJ7Jc(~ zZLQ_Lk*pu?wIAE(&lAsCr>zwl_JWhAMFng!RA3w*4Z)p&uxM%Q8^{+In;!a0sf0#~ zl`g!2c-W8|X=-kVPb;;erF19{^j3O=qsgOLs{xbHk=QCwxwiQpYEns|xrDRe`4*#p znx5y?q7`jYW&P_8RyVFcazAx@n{?OJcBPQ2OmC)0-n`q!3C_JI9VbKnKc#<=|2OMz zS!}$0T}y{3*njBd=98}f%y###wq*j!`enCPRN)b`v8jYVKR~Fpx7SAiDK8$XQg|h- zl%#hbFNZXqBo+6BJx_x0^Ko%0EZkDSKoX(A-Q38~SUeA&sCPE-JR2K4O5kj4VM`T) zH`Ll1m=juUAaOs;k{d}L2p;bC)icP>q9-PBNRxA7AYFEC2dM>Sh9WO{i>Q0vhyvnV zA4iPE)0zyIU;`cl`l}EM<*xY#wU&TEk{vI+ucz>rkxCudz-%3vIEoKrsbzX+I$`P4kJ3KDpOLd`qc$k54e}|B zqk6-J6S+WPr9XVvgF@GX=tD?O#=nys(Hc>a`{rdo8>xs*pfIGV&KeuV^J~v#ga17$ z?6V#sa?fEU3jWqprDlxL^|2?bfV0yAoTFz5o5x=}8%;OWaIC%Baw*bh$fG6)rn`w!;ISEXz zDh$&rtt-97b;#!@*7km%3ECxq9k``JTn^RIa7;yl*ZI&PVa$05T8F`oiuhPHuvD-Q z54)&O`UZT!eGmE?*nKK_Rkm6>WXrp`=zjY$Ytu8DqwW+;m@NBh2u?N3sD(-5U;d)i*rgz(LcY4S7sbj?JAiV?ggTDv5G46Yw$z;d1Z2??}j>_(E>Nln#{-MyWcTJ zZy~feMGXe*TdV1rlbUTk#3$#AnTg`OlbyGgEH@=6~oU@1YTU;muW=vPMVY2(w5@fTa82-+L` zJ$1DyZP$UpI_l-d4El^p0JP&-?PPOppS{o?xP8XJ5le-8KX-0%4>@Bk|j1IYP;PtVU1kW zV)Q`Xp1D9HiQVzmehTXrUpF^(KxBH}+6Kgm&O1PRxU7(LuR5=}`q)F({$CQ;Es8r~LciyAQAXug7KMLDpDyi>-e@u9v&p_zO+s zFK~DNEkpiE2S+cQ5r4_oR{dI{wL;`|fH_{PrA8Iu&9Ka2qWN`~Ip1N+g;|C*VXNf2 zFX%o&EV0UL4#Sv948WgY0_S_uR=5#`jKbpqottOh5UmcCd92ek*Ix2CuUyBaM!C|6 za(|rTYIB`Tz7)+avNQAR;4#wiUjxuAagMrp9sO6K9M}tqfgIL=?M>WNrNgKA27lC zfx12>B}5SNR35ISsp6H;)}wi%<+Lsg@ojC?p!dZBTm}&94O-55owUtt^UN=ph?NLz zRa3lABB>4T+(UP90(=sc)a7Pz^!m-`j5o+wrJ}w%<%5KyT>t%*jZ@4&q(YJ1!0Td% zS!w?`PrjJBk`AQ*f?0ZzR>PWyTn~$po}$mL%u;iX7t2;%2YpgH>msYyYDG_DL(80) z=1|9pkzQ!g=ghRwOCLEm?WoHEX=qWKsdv+;Ls#ulQ0QfX^Wt#O*T!-1w_kS?S5WDJ za9Pg-iQEgkbIJ3dsI#c*`YgEZIiqaARj1G+7DI`t7$tOrKD<1-+rAV^4#Ih3J~YYOfCZ82RHVjxBtf?kHx7{-JaU5HUIT z>=qHsQ*Ipr9O~6#V!D2DXkS^Oa<{{F>e1HMGn&1eD@6%sgdPL!ldpqO8ru`e0}KJ# zZow7k<9hjdBCF-J4lrG8y%M;0Vk&OV(-x+9^6}3m@`*5yb1^e4Wn{wfSU74g% zmVnH!8ynXDEdkR1Edjs!*Efw8Eg}XP1>YpGg$#klNS41^KLWG6OE2@Dlorj+^!IxQ z$0ckx0c>me6uE*Qc!yhhp9h)*mUerafYO$xxi1=v7Z<$z|{L! zWO!RNfhN!(I_8weZQ-%pB-bD`XDZ=|JmQGpuOWFR32{v&PSS89%x2k88puKb$M~{e z7PrJfgba*jX<4eXGu~5URVDlhGX8uk><4_^zErnxpov9z5(E?S{dx?TG=%$j3#R2f zZ67ljiS$WVd~hO2>o5$FJ)S?61>wA^!TLy|oEO!jT<~dtEnq~5(C;kW6B;Y^;tVF3 z2A2tbWB!&6KxzSjD+@VclZ?j1IHo8V+js~#dCbUDanT~9kF?d_0POA)`Q*=jw0zh4 zhWB!{$mvw*1s!!K_V<`zd&S4|*b)E7Rx-z|SJuuhI^P+2Z0vWKMc&CzA%^00;Ri=6KYv08;lrbGt?e)wy!>w22a>G2KV(E`yZFW6m5Psh9+1%$~>dhr4;KrQ)4jphwSxf)uuFS>h zuB-VCy_&v5K?~W6s?_3}>Vuv~kvG~`w=|ULg3cyV=h=WSqR>7Ss2i-}+0cucck6>h z22$D|RXZby&MX9Hde&A_tPH8)g7Oii&AE^?C7_7DxZY_F>}~y&b?Q5tg~{^Qm%I9h z$ANZAC z7tbo4{h`__9exZrSi1Y&vq5>gd{uqQ2d_a$J3A|kUJ`EG7(>(zy%%ZQ-{wI1emgl2 zJj#O*&BC_Nu#q$spT+?KQ9O9xat zHV`f1Ycgy-v?uA=E+V}y%ZsE<1LjCE9a9-WCX!yux)hrt3>>67XM(NK;}(J|ctmGv zd`q^G_8vV;kINg1*>2HAAz} zh;V(qItf|c{3L&a;MTi?fZkHmiP6_a4alUg=U+_Yav{7(I^?ca18jm5k6e!%fh z0Wt<``qFignF%fl%CoN=Wn(Vx!rg7YMQpu3moCN59h9qZca1q&{vGt83)-WJdOof@+iSHd<9zGoK$>wO2B%n)ykav#cuB_3B3wF{t$nPxf2 zEw~Q|M8D_|$tSLvEE3WI0ib^l=&I%yu4lUs{DhWY&CJh|QMr?==96FKvr<|;e+hxY zlgYmjvUfAgJad;5==ID)6Pc9;a@j%L>fYJ@6S7$bEt9p3CR;z%Y65=FP(Lb_gZ&&t zO}pkZV{J&0fb-?3&|z$T7F35wg_ZU8lr-jHuVu_Ne2p)tr+*Eoz59Es*kdyav2}^@ zHZL$m16a34e=T5UOE3=p``7fxQk4~#jm<1ZPKq&>nfl{0PFedn{~C@;Q$EKrvXK># zMY=xiHsqe*DJIr9C2Ss=D6?3BGjYx#g)rnjCRR=~Fv?Q&)OBy=z?VRO4c$+Z1#g-n1@@?Vhha04&x7fP($kq9p!QE7-aB z83rx#Dfr}%kdCOWpEokZep;*zFE%GsOb@+^Xr55%o@L(NL*2Lr*hUC9*h#1OG?#=b zRVD|zg=2<&{N8LIqCRHiJUQ@hV)NLRUZ25b4>JSeYSGdKS}a^qCZ3Ttl0;Fm6(T&L zw$FASj_`>mEcZThdEBu(eckuS>9DHy;NjHi@0Sh-`gaF+2A}uxQZzyTMd}8o?z9&F z_ek9hE>d?kii^~>{f07z|L5zgZ@pj%NK2EMX-yxBaw`^bK6q*Z&}GM*uuqVG;9CqC zSEBM3<>RafE;(D7{wjb51~cw{#e^gJUh^Qxg5J<*@$y43f^YTs1g*JxxY$nj{0ny=)yU%%K-l%S%Bm@3JX%d14H z@sEk{9KQAV@OHv0PKhS^oZxawVNySXiint|#p+jTkDuji_ipj;g=GlHTcCA$o}oXy z>|Z(GR?u_?<4lYa!g0LVmW|Qs$vef)p)*_458v3P_~N2GvG&=EmYUjzz(q1Z@wO@^ zi1-MPUD@nhOL-Nxv83U3+1RfulF?wN)|6AYb=hi6F27~J>iL`YB%!6OvNg^6hlVmM(CANok+QDv zMDfXN6<6_F4<{L|0A2av)+6bFdU5fATs|Jla5^21oYcuO2fSTG66I2x@$IQZ>r?hq z*Cr2#n)%jz?c>E*WhG#4{NTYSf#c$J7QA|E{lUPWp-!#*}P;nUp;+2AD}}<6SM8 zhj_KK^Wk1{@yMy6cMF+2`-q|2W7OlRZyq?uQdIOHbFNfbQVDGpT#bC`D!P%$aG4%#6Uv` zsNoFKU*ksQaYU^jvIO z+k;;+c5?Hbp)>38SlA->|KaPc!0Nec;?8xhB^8qHOZU0CMP8EnT>(X zbr#Xvz1$NpiCer7hf&LoA^g^{P`vI!ff326Q|VLbeSf9a_ubG{T)ok9Y&Ldl4amK+ z+ewU|0lfH;%3P9^E+1u1=2f!rfflg@k$~rUR(#=nElROjj_^TUPo9M6`3aac+hUT+ zz?zG|AM*q2MprgTD$moK5^#Odhj*QTa^KTYd0nB*?rXs7vj_+8T<^=(5c2-0(!Vso z88g6>70OK04BC;3maL9vN4fG*e?>97Oh7EVkQJdLl{abyOZeBhz#$C+3%s+^J;!=* z9e9qJmmd8n;WHGmFYM+hpL@SDJ|>Fqs2ejUacj-n68kyXtS>tGr(Su*13Pj50ChV| zCtZB(B!ISaslV21I4W=CLUUEj@S-hW^8+jba(Z1J*1mt3TmZX7HpdsSkde4JQ1T@1BrKcc@b*~}rw;DL6&ObSYg zHTo!i*bZ$*J@Lr0H~g3}9KwI2T|(H+8P(kZ<0Qu#3XO0|~*_@H4pIV2z8jz-knauvMVz;{pGAO&9B@!H@(SNhy96==h2@Z4eT4xbB2P-#An|#|yLFD5_eBAh= z)Dn~4vU&od-}29$0-mcT=$lL8kgs zhYhLz9yjZ6q$1s*2Y@=R!drLXv-UaFUdLAzUm`MI$lxJj>t-{2zG8sF!@@uH zdjUKk1&}s`(cS#~W3Zep%1@^{SM6oL zZFFI-kJF=+>v@y7*SHu+b&;Hw%?(MSO8GZIAz`PUiL6^|wx2rZaqRm=-7ps}Q;X0T z8ML>CcJ1yt{%Qy0FGrl@pN1ms^8nr{2{g;L?w+EHc9lj5{Hb{{&#}HU6h7Lc? zqp<0$YtmUJ>p!^7$5yrR^A5}G(+<1s7#;X*o>UH4Dh02JuUqGP6bCrgoY0q$pG@Y9vNUM<|jWS2gXfKN%aGBKe4(Etp=KQoluN1H<7 z+T?0O4HEw}-7f7Hz~zEOSWm651sc15w>$er0OE3!clI{)^&@=lwKbwMb`2)@hR*K| zGsC@bqV#BaET(V1g@|=wulUM_uS+LEke0e=M%|&OXL2qNvQRC=NcUPgH)Fffb)uy6 zK&o#j;fYlcd#LJ*bdwfWa_mVkYAx#x*YVR=iCA@T<1( zMK3L#PF0QPT#w?w)FU4`)t>9h`1rP^Nyl!B9NLUPZ9Kcv-?E-7N;mHMCP*0j5+E4c zT-BY@$9Iw?8`SjUc-&sSN_9HtGwk*pMJa>VT__SgHE zIVmF2C1_%%+T<1#U{hTRXAK)_x@F5cv#K-nz0H++!Qg$AF*e6%-sz=?0@YY>1`0S& z`HK!vs^EeWTu?Oy!^If84$ssXKR3kz!+ugk32`&xCneX~pg;umT}&Fo@>MPA#aO-8 z9bkSNhiQ5b1Kb-^`9|&U_t1KE0m8q#JM?S4-C&a%tyTP}=*wG2LGU z_h%P8k2ts$c9mLy61E}!(J9JI5xNSryG{S~XygyXY2cN|YHx>(QqOYkE%DpbTf2BD zogJNS_6U}(v%%W=27Ku)^YyBOhaM;>6Um(F{{`kVhiM6k^P6Wo3U@93_Rja@sAsoj zti?Pp+?QpBkW?GgM-+{%Or%ciKw33kgKc-DQ6hBNL7T)>p#pm+1*ijl#$`X>=#2}F zlh@&7I0Kqt3IF@f4q+5rf&oX?fdf2=rwO9MQJmK@nZi*)=B!msA_Yy@@urG2cWuKy ztg`YuVb0SfaCwNc4o_N-)YzY>Obh zpRNWOE7;s2>Okg`?hY|R<`tBz!}MU1PD#l^)?R(-hj956;UU<3HZt^sy{E)B~bdQpwXE*36g(jZgubYsPeddAWC$ONRJ_yIv&u zoMzJHa6eOR^GyiH0kh3~Yg&srDrVF|u{>&u%epGv<+mO+dDfmI{_ERR$W1WbWnOgX_ zAingj)2;Q@&oJA-NH9!_ zt^;y}kgBq~+QnPKymVaU=*3FOJ+cu#8GIzoE~U(2={Erf$4Al>V*Tpq{Qag=_|PucQLEe5?ufan+Fu-)jqbQe8A+y=MZ@j0Y)wu2z@gKS)Yd@%`<3Z}LJJIPZtsw{ z%kV$RI}N<_f&V#q=V@*1Oq-8M-Wg({E5lBbR_XL0<@l56!0Q}${iJB5VYZ)G-y{nZ4V_;gRAsD! zoc^8%PH94JGsGtYL;#|BIVut?tJxLK03M)ouH@8ZowWo7;-AnC`A7%x$bRMTP(po8 z3%$T0@i~7oJCo6Pyan+mED@2e0kj6+s9DN>{;jm|-oBPpUHcQ1?nFbVt|WcSlp~J)HXMEq#(u2SX=N!Vzo`OYSULmA$=X{FlubGKQBPg{i>$mMVMA>lJsqx8 z&#dcvyu-vv;dP#b{U1u?RW#&o{Hz+&|;67h{$(USP@tffQ=yD(AU}zOCLDxeN(66_-to?%EkU ztJ~{rAlHn8gl^FF{$XZ3X5E^6XFO=BmeE!3{ba=wWjL1vhP8aLi4xWmpB&y3l#M6W8LRyv#F z`H9+lY+E#zeR)O`ZR=^&6Mg3kj=t|VsqH;C#vH%r-{av$wwU);mfAe)`_mUzn&gV> zY>T6y*B6-*yQ$nZ9q;d!cdHEuB$DN$Qm^V%U-}%vaxnh+k#nJ5jrAf_Y%r~8(Y19g zJ|dx@_p89>2GnQh^XbxthgyyTI^!--B3`5m-omB+`dHH+zpf>qxU4!Mu@}vB$A}m~ z(3oB6@auaS)1#qn<{SjPN`ke5IHZuo!ujF9-}$)J05mIeu6fr^D8@c2?h-xe7OOE! z1H!;I*nUmhceZYjd|7c)!X$A-^7%&;y1Sx9a;kdFQSQ?+cDSU(rkvCSc#oU6{O_OqYtrz3mt5}VuPv#N&qST5~whrCe z0aHm>Z$V!U4w4@|Gu-eP?^zePZ3#^QmpAob4We|fX5>_V69TX9ysAyTL+V9`-q_p-rW=sd1C z&W|v`Sz1mdde7m!Qu92?NK%oXYRf>iQNfD$U{5qG#dG3#dGiQS>$4aPZC06ScaUZ&}pZu}by6#vLJk%}3E_^P0aw z-hG6b!5NU^g&q{@N6pt_iQ^$6MZpY`M5L#dnLZQ^0o-=#QKXU{{UJ>oVl0t`oV6i_ z(J`V!7v4qfn24DF8Le_EgGa-|5hJlw({{`@C9hX;%u`*l?)hv?4t^8ny9hqnb6(p$ z(M8nFTR-}mQFjBSOA(~MatoVx+`U>wd+@SeZi|!#t*vd+Jwt~KR~;%UQ)4RNVkFBL zwq&$#8g$S?;KD^WgW=mOCn*AnvM-RW^*{FLrn;-f1?$>PU$MYQ-km1jreF@j%}5!e zZpHPVQQ&mdbL_2i^tRfEd+J+l3+Y4fQ00BetCL>zeb0SIiy3CQW?DBN7I0W_PcJV2 zCAnh0eU4x9s&9ddoW{A6;3CvU}jHY^0P$ovJR?aQZqx*Qur2=G-_iXaVp7A$p)|5hznKAo?{ zReXr1L+AizakZ7fZ{%WxI6kh*0^*yofW@rMEQw$RV_HKgfVbCmv4qfWry+k8Zp-ta z@A1B}1$ZUB#EAD_gspq?Yb{C1C_`Ca0Gfd+fuat@pp?JP0&Q~bqh=^Iu=;baOi4um zR5ScF)!Vno52kT#l)C_6*7$?1B6dVBrm2s#jqrsT$b(V{4a9j7=OijJM?(EqI-h3U z(Bn^#_2xF+#gPXImBcgGuzAciL|-Cyc@N|BQCo#yRny@kxSkSG(M<}EtUQ`8nu*D#yENSgU2fLvoJgPYx^bh2vMVw>0X!hVZ2KX&Uq!3 z3ELkA1BweD3j742R<&fz(^X1oZpVAA#RdgiPnz=39r4!HHIj=`$O-E&uRn7;+xc?m zl=UxmH>mU_!$okp@dAhN=zG$+^ZpT)(t7uLbU1)ss)!V#gId;a0R@U-;WM!{@y~(! zTKq;a8-EHDxLy@1%}M%y+Y!J<(eH~*`j$<=Nt8W2-9m8_3k~R{R^6qkQGIFVr(aBY zy@r=4zOhD#o5nN88zi;#%Av(c#j96iHWs#RbUPQa+04DndD!A!yC0sJ0G6uLtC@0z zWb7xB@e4W3p%MuZC~EJapkgg>tD2RTz&{y5<`3Fh4lJ2U7Cr_AFwz|P7t@?`Xu zoxf&t8-=*YJXA;p?iRRoRK6@@DySTYuVkX*m-xK2$ICL*X&!MHJb+*x#xLrneti@Sb#XTrB&rVv1Eg%mk(OLauSN z>6?QE6Q(}uPpq*_Wz$bfAx0hd<(d+mM3i9m`08V7<2X5@}9ALCM*&`=pp z*|&V5Jq9|B%Gb%TD66_GyBtYy`LCI6@nZm!L2{E{_j;dTO|1>f)l(1W9@|EmUP0 z94o*T9x@e#n9~E9AEFc~bl!D;zMgzF-M`u!IVS(b?+LV(;bEhj$7tE>0VBWM2h1@4 zsLgD?NJ>3!)o=eV-}`@!_R{)43UkXhWe){IP@kvSL^pH1|1N>h`GP1XFUS z3jK&nssiBF9sW1lc-c6L4v@ejC1;9kg%j@u;6)+{`-p9M9WGa5fUgtVm2tJ(@pR8k z#Qkirj=oZ&s1yuB>{FfhbcaY~rEm>Qs%hu}!CjsLXP-;?mT4WXN&SnlN1%9%KQv5?Rvd50LD$T~S+6fwImz$-#%(cvRz|iw3pfi`K1D)} zhCB+AEQkVepQyBsinQ_2*=dtNM-bV>Z{KPGvVo(fWGTm=!#VIg{}4^Vd)QiF3UtXw z2T8D<5z#z5tWF!K@R{Qgf?>(|M=g3+%%uZhW!5#m-E^U`%Ud_pKX0b?)hd8&N=Id3 z=wuoWTX5YDYOh_}mLy%Hdn{x$?UYhcQ-n0gBf49kKWGx1b4mBKcZu5vphrD+ z_rVz8gb$qicdi44|JJz|^87}U3Po%u-ylbt2H2UFzWb|JOv71(DT@yuoi zxZ%{sbHUb+@{@CW1VlPX#=7_t}72I3fyZS3RFs-&%IbfM`LDMyjs)0|T$lb4GDGYA9e8>02Bs=g& zgN7d=2W|wfD+&joR>LA2t3*d4h}+SExz$6{9fk4fb86g@Ve50PF#*z)hKcsZmhr^p zJ9NF(Rk|U6O*TVsx1a0x4Ad?j@5*XKZvO*==yfsY?>%Q1 zm*gA|4^T8=;*2*k zB{XYDw{i6L$PE9S*#R*9BP3EiH#(zf&%*ghazvm`f?HwT%?BT2CA$LThuwcz?+`X; z`;c`#Fc@st^J5Sc7)-Q?e)ay*Up5K&CO-oexk>>^F2D0tvYkn+1Z|8hn!@}e-$r%d z3t14?;@d4AN}34OzhS^^vW}+E)}A*?sa4%yr13l~z$y0(i#TGNIzo+_|8BHSvu9 zsUOW1O$#3yhg!S2CnUgq55MA@X4(R_G-bPWHAB&oMwG;-=X0XvPdy8aW_dn_Q!2$q zJ=<=`-?^|ozP)@exxD=2qVi+)eX3w8f(5E!k-hZLQwd^_Ro<8n1 zfnOY?SMcs9)Y>nyFW+uW_f;2N2R1^7+*{A{D{5YbwdMNO`FcU4 z;ng;Z@G)>$P~dNS14su-JMA-oac`y0n~5;w0{O`b#}Jin0ddDj`QbBt-M)L2hYVRi=*40n{>#TG^EiuX4Iq?dJOPt3as*H;ZF1L zgZ`xPb9;0usnG35L|!$>7+v*X*Gat)snkyW!Z$@=SJbQ>P^Bb(U#Q)e>=M^fZ`R_# z^{a!gnf*0PrSaqPutPLDLQs~>ZX4c>r0Ai!8=C>#k}y_X2hsfb{gjCjbeGEouo^?Aw)q`8EZ?a69VD?c=j8XG4&6Be(3bV)@K3Ep;e>9PM?$6>LDr5a@=pag+HH^d zP-*FQ{hqgpZSZ{CQUgM0^@pt6^_f@g@tJ!x=TO3{uEAGxAtPtj+MT{9wruAw41YGF z&j+LB@sWTtr$K?}7B|_-|JdAb_T8`dzLmBE62V$9pIGm;Q5-$a;%RDE z9$D1~Cj%5?3Nm&9Ce)#FkXw%2O@g=A*$f`g=1lJs#VcuUP2fp>%Y4Ap89q|jyeG!e z@oP!13q!9wLt?V(?w`=^Go7!ERm;@db+oEOozhOm2<* zjG(vB0r8K@604QoQYsMdmfD>oloxEj)I@!@3M8cgN7FdGK7J;lXVkM@XI?vS+UvCNrKMqFY%2K!F~w>PKxVYC}!sPpLNrKFxhJLx1Iwq}R{gQ5L{ zICXYsN8uD1%m~l&YSHf^;C`L6RpuOin1CyN6NG=BH`hTJmD?gSr@v9cHZB*mRaj7l zo_Fe3le}#LV?8>*|C@o7=-!UK+4i(+QPm^Cx=v@Ug4rV5+Dr~(@?D$)MexMhpKKEk>w8< z%E?ip3kcf0&kH*~0$*aEN7Dhc09Pl}E{OgHPWF{hMAOM|22P$9D)T2% zS%~)+-L7+N4rnko(cvS&V_rhnzii{fAE-&+xyr%!lr?=x;Z7YICoupHP;{`k{THk% zk;kuxR=A)dbqFLj6px^HeEa)zknv*EHbGEZ&~=q?0#{>G(&*=U89b--QPcRw@Co+DLh0Z%a+2eA7?(KQv7u*y2<7t8bF-SjYWvNbB_4|AdXa&_4S;yQcJIHxop~%w zYKT6-a7eM@yStW4z!H-x^)B}5sG;QL*M`!h>dsRliH=)1Nf0Nl!qC)L251fCaRAG< z%T!3qFFp<1EzaJY!+$D$J;`>=zy|U@7v|#m4=gOi;9Z-cbb=Su=)n6GiH_tO?Hgqu z{CA`u3(-n|5-N6cHQ6W35yN5he4{AwOwSsI;lgz8bo{9&<-E!IyFUzp2R2(I&qX$6 z1(LaUI4nFh34iPNvmX>Dm2v7-WDYIl0Jd(-nfE#IP)l#y5;tq}U-Jz-|It;;d;lD zeN-IazSWFkVVgl>Y*qa+$x>pa^sP>;!Mo?p9N1JeZ7yIaKSj3x9~b+d-bCDT`3%Kx zl1@IXUn_^He#*=^NIJaF^?UDobf?zG;CmR=-yt8>-!jxA#;ADH&>Cyzau{-V(y zd-_k8sY-^Vy&x?uFwr_T8-M-YdpcfiR;?!~@AC3}2>kV%_3I!}%@*CEJr~}UIdb0S zzTi_Qi%QnICt)Hxo@AR5bHyZ8I{^;?m-MJ}a6yiE)ylszgxv12iS_p?D!&}GUuLwoH{>A5n^AF`0) z{YHvWq7al#@>mj(@HdxIu%p${sFXd^&b>BkIPK)0TfV#y6d!_1YgS+!_K>b z?6{Y{q5$uoYAM`h-GafuIaFYVhB;lP7Epw^zNFMg=|p z+0$V%Gr(-_ab;}|#QVfc=(s$lfvP1AXZx$i z&!Y1HLY|`bnKvrI6@OyDNyC0A8*Wv1TF(8)?`B(^O@^J%oqiPT;wAGMK;KvhYkTAP0!Ra>Q*4xhIlr@ilN+Nom2( zsd3bf?&32#I{LcQFwp9+`Dw>sxI)(t<7JD9keq>Y7({a5zR6`c?P`K$t{9-BT9K(D z=8!FwhvQT7S-X-+M!C5fdz)FLaMQrFNjQ)k-mV|qVz6x8H%F2I(cGbcPdj0f`lY6G zia)cTOe1}=r5WT~cA|zB!>us|HgoGZ;51}a z$7Slv1G#*CF89=fGMPS=xU_9}En2a0n5%OCLCWiJidoTl^Ge6eY(oNR*!kH#Zl5)E z5b2oMKT5=}Z46XY166T{EeZi+0nG%BmEbvg;MW$!5)P{PZ6z89TVjWHM~-dMZgq z)8l>DbX!D7vakZTW}Y4Lj176lJd09C?%wYS7U&eVBA@t(b9Jp8^BuzI#p#gysnzmU zCre)CwA&o>!-B_DFJEmjK z(H}2N#FF36ZWHcXh*62#X7PDTW~{W^M~;kk+_QH3+Bqen;$%PYrNf4HI(^B6H{E{ z?l*6&`)IJeL88c3vas?}g)P0)ra`kdd!eBIfa8UW#=Oa#rx~Q)=&4cu23+2ytnmN? z!_DlR8%TOEd7T-={TZGfNKW63VH+q7sOGF_AX+jz#G7xi!JChi4Yn%vE&Ai$0fe%0ObFXZ5Ru zM>ZEwPb(t$_=!IT?61isgev`Y1ZNtCJ5Kf=xB?6pWLFWPmbu9Tz)>A26Fw=Jk&A+mpn- zgalb0?Wo_*@W+z1ekc2!T&JF&{SMtBT<1iW;z{?|j+9?$RfD-nnviPpC;vN5+o8Bd zW9sXzX6pe77djhgI&a|sACM+SeL0i_Bn7mkPq47WHWSwr#;x)Qehmx^&P>*#qNZT3 zAhApMS>ju<6lf93HKc6*D-NcM7P%>Xp9xCkahFDX+fk6PG16EvFSh|@3v`F7GZLq2 zT3O{F5)mf@ZRNg+uVHkS*1`!PcYz;M{9*lJKnPyVU^V8~%SlCr-c%6l+WsNWIzjog zpmcFru8wV=n)f$77ixUKfxm-@%HjiK$6Rl-@NPU`x5JEv$`))NJw~+h=6nf`QuBC~ z&)Izt+{6)rH)TNvq)}lEwk^7we+D1zf^P+7U|G?izAS2A#EZB9vNULJ>gT$bWSXZc zn|=nDbkcB#D41NoJ%DmA4GudpW*a?c(n^TEai`aG_bt4SQjusk*s2x1sRl zT?C$0It(XzLtn|bd05xdXR_T~FRtrKf#yg`2oOoVsh6F>q&2uSJrJ`?g>TocDl*mO zU%nG7Bl>(M5gDznV%zkDoSU!Q9y`>6ln9RRL6!Q2Gu(fq$Gk?QhFV*!?ji4@3S5IF z7z$GjlKm4^p~}p@3fzTGD-^px;-`&%7=Khgr1YE=+LKeq6HOcyN{qICr^D6&dRMdO zK1auQF-)>XeI~ZGCA^kmBYw4G_IAT!L)6g(s8)m^JmrmGU4;&ggjD~lrgWplry{ix zw=MMC6|9wF1Ee(Z4kNEs3@4+`{?ak8_gS-#z&yt&sFH0eTL17=MF8%@i6zpFPu8xeUt(%DxYR00UzQJ*1 zHFDd%xPV0zk@e}_?S02!MwarU>dy|;?2l8e;ruP;O5B8D+a*2_#kF4DRak09Ki z7KVjA&t6kJTX&YtxN(*$Ez-2b`8myK+BO8p0@Bdp+eH-u+IK<_ixPs@zwD$lBv(pc z2zxONc?h|qp)^Gs&(`BvK#Ie13;lX`5i69})!ad7ghcXLn~BH5l25QNsEp46_D4cN zf_uZ-vRQ#T;0$II|Et4rrql3uIq{0{o-G*pW;yY&C0i%adPmJnT!5+pl4L&Gg-X-a z>M!X(7;dsZoN!j0Z+Et(t+g(+x4d`z(l~M;YfS&|tj|m(m6ARbmX&F3LP0Nq4~aUf zB8uuiz4kb6D6l)))qOccT%)5kmi>*l8>dZetoH=}3SluM5d9V_kf6J44cC0b`I z;iKP<^)od|LYO3Gv)rr6Fl=HxBid(6faOXQH^5hX$dmX7ZWN67;bHm3-HpfdVJa%V znpFq$bJ9IKzDO9L0t4cT3Vcf&VBPCAIAQ9{aM1k=r9a<`T454?zFd=f^Yy?=CvT}6 zun7vbFcMIhh8m!!PmsPl%Va)C@lB;9uHF2N{#=;eJjiR}I!@klzYEgW@+b-w&J|gZ z9ftZ6UC}?raZWb%Vx8%_lWK~?guiUB8>K*B!rinZ&yeQsoxuW*>b9R3mczRr=k`l= zT>M({!ixwtfBl?#N7jtTe!j+z5BaHZgFxW0vTqAU11jiwz4+@YT{<(t-N3*>#8Rbv zw-PZjQ?gWMt8{&qc6;1<-CyZ8d)ypI;W6qb-x4UZ|6%X{p348PG3{dE-=xQuk3lGk zq}C@k(33WplRjO(L04k#Hm4h{*pO`|vQ|ueK@kg>tZr46;dWuQ)Nouli=#lM z&J2Aejrtpd+N@X2+Q1a7o@ivqLlDv)S<3W6?%*KL_I?-Hvs}H~Yg-`%m(QLdRI}+F zR^ZZdTp=aANE{cx+#vyJ|pAl z3rM!6?mLlBQUI%wS)rOcM<$2QxngbfQFo_HQBGj(a+;*4KD=9(g(mpyANc;tKOB)M zkdfyo=Y4(~nmU9@sPez_>Q*r!qGxib5t<|p@_i~V&OG&l*`Dhr*sYjw(0u2G@BTj; zMkw>+0fwM0wxVKr1HR2m)#`<(xqpYBKoaiTmU}5MxvJdkEAuq-?KVi^k8Xdc~ zTo<0xhVYUZ^K9ccrGxY(7AQTU)<2OoI_>valF`bg;jy#L#5U*~?TIwts@p7P zji6@{Bm3y^$okKe=FLKXv{9U^gLr`NCjenZIG~=rtQ>&X3iByhsB@Cb+J192T;EK^G3>}x#@atvcm06RwoXz@>&RpZy5MF5=+MCU8Jh*o)TDQ-5ekC{Wl%A8DMEs z?h)qiys!Ti|F4z~0BH*4<0>Sdv|Ka4D+hpoDGMhQH~MO5`L^PAFI}x~_+hL0!~^-$ z`#g0S+wmB>-QTSy=vpelL8~Uz-?ioDF=BpcqNeC*oDN5M4#u3re9c75tC>^&CBKpB zJcsLRj|rDp_I&szuIT|`=Uyy=jC=L<={`inYRgt%)?L-tf zH0oqGMl#;zk9X{LRKCd*3%b2XViR@;o^OVctj?0lJsHuXn&o#?zci5*OdRi;m{mR- zke<3~I!L6ss}uQ$Zz@vYF=UXD@oq}7lE2%6?uQCrZ|0-Gp`^Att__nD62o3o?u2Ud zyrZ<|J|ceIeP3C>{WAq-PitxQK{K+z8p=1wZyL|lZo9LpCV2CN(dLtRcS?q$+T`!aFwlaDix|Ii!rL&3Hgi1^uB zZ6$zdjk~M z*P^i!WeORt(Muj03?!R_x*1vZEh>P=hC3Ae8JkDW&CkUEr>2qzzK5+OcSG~TVVH${ zJ-7<9hSW|vzF)3=D12ZY^1HwBUym@gQ!^YB%CL_IOWnRkv;$m^@x9SogP{Xbc9-+v z_)vnC$6gZIrM0#J=EADq(u9PyG}QQ;@AdF>>6`Aes*!WvF;76F4v>_ z@ff^G8I2KbfcE3>M1R7JeG5Zj`q4uvojPhn>M96=&YxbxSV<$KOkGjWhPPmLP@M2ap1d>3(mQz ziU6=WADHMvXxDR>MB_xCg&B)fE03rB-F8#Wo&+{vq44t(m1gab$53}Gv}OVEElT}D zKD}SnMz8|>!iB%bVZ?U9o6V-7lYKPRAj&bP!gHpb@F4CNzt-$2Y=6`P&-R3+* ziW}t~R-yjK`I|Hf8bl>yG$NhWpq-l3E{hd8xnsKayV5rF_VhQON*{VW0}r2547+Do-j>fHH(g9}>X=hQUAHhRwfUFRw{>Q`E8 zZhc1^ALI_OHXOa?g(&QGLacQX6M=gia{6Qaf@KCzt&ZnBuiB$p41BLE50iwJJ*)Lw z8a^d{;unmFYDbr8alHTo;(v6P?5`Ur3QrrYlk8|8xKjR0Z?ck!L_AgtO(=qOKg zY1OTUD63-R=TLx%t(;WlZ9cBS(*$rl;+1e1H)jO=N38lpM}O*alc-FCTl7<5 zKBdF29d3=|yp1!w_@}|xQ<61X$ftq+;+F>k)7)>`MzS+;pKRkyJ-f~^`S6y@63gI& z4X=pO=;0e(Z{G&eb=gp{t{c6JVm z{dAf;r3D!>k!D+D^KZoFy7f}Uvj_&f^U9v?uP;(NI_Xy)=X@=dg5A=s`=FrH@uK00 zQ=36L#_I`_{Xli3P3g4@-lp-Pb+QyqJQiG|rONZo^zVQZ*$k;G1$^jE9qYu|-|?vZ{FujKX&Kul9Bki7vDD)V@I4k6K|9FD`?dloG^lx%lI z2rDM9EkXJ$l}wZ0!Vuj|Q?xciUZpRi<%6M*M4H8s_LhMfKkd67$b#}syq1+qM_ zw$an}^VktPP{QANyJT8xs5%@XB>1e(+b3t{&hPFfvwnlkdJ;YxX%9)<9i=88n@iENgmSEO0q_Z|3Y$BPEDGg%&h)8<7rOU zbr>%vgC{Lg`j9twHFqh?ON9(X_D{`=tFG2Yo@u9PmF#iC+`drTk?df;#>nzheQut& zAfsQa_q5^%#4RaJQ(-xDZ9zh$E)QVY#M3))ZDUC?tNmIy8m4E z+%!jmE!7Y!#5!cZhBI0&OYLyJ24~y+FdGs2?TE~JyIRKU@@E<9BNC$oKwjB}rX^V+ zTUO*G*H_aT%E}t)cFfJEiqFjH><@2<^B{O<8+Mk%Y(8WLrSM|PJDcDuf=1^h)5CM8 z020~$;N^Dy!o=N*D}_b*4FMsPdM(p3SM9t?QSCs(P?gnkcqM1QI85vWHY=_=4?~?4 zODflTzaM7!m5Y4n@VjzYG*8NqA#B=dWggBZ5KR#K|7zR+y+yA)uWZ{XRo*7Mex91V z{h<)^DCM8QEKr^+G5-%=Z{gMSAHRQZBb64U86~BZbTdK0pi$}3B`u(g93r5S3et?x zAl)@!h%#VwclSVIgrxUAzjMC#{X4&Ne)s?IKIiqmuIF_@D8hIvT-m7w};=in9??YQq+a(Im&(ILko9#_k+c1 zcfyQgjBX&&?9?L08+?7x^GJ#B**h9>O0>9pFX-dfU_b&u=vF2J#0k=&3|mSd+foPL zJAywB3<{Na%JOUunY7lnmLq!6CFlpq2_bt!K_1EWRY_QBN*B%Usq~fDp`%mcoH%93 zba%PuA-MM=L(g5+>nG&F()?Q;{U$%3an;UPV>RMZ*cc2_(Z|{CEtEMwmLdgRh__8t zN!d+wo+q<^E@)wH`A7-Oj}kiRfv!Zzb9|ZvdPLQz^*!liQ+Jkp-I=WdiJz+YrYlqR z(&>u^i)+AffAC1nZ3Tmf0d2=4VtjmIIY-}QK?Bwi|8mYfb!#M_tz)Erm3*! zo|~oM1kuY3fLhIfOR6V7xyakJkHozGKjkAnO&190dCt1LpDkz#9<0`3A-nACfvF{X zL2UdB*hYhs*)=ttSkzGbwtJs`8hnU&ect=Ql`e`tJ$g^A?5xk>JRHSzDCxF$Bl>pM zTgoCSw(K=YO>Dl#gRY34u)0+F(|AgMS%+gHI-hXX+72XYB-d^}Qt&RsM@}962E!~z&Rw|< zmPd|Is6Wex&U&wn7*Co`>y8rkTTO3n27@cEw$2uWUzB*SfA@e+R{g&JQ^oJcx;-0w z@YdtqTT@zEw94S|_5LREU(vFgITbwJE-rA7&K1Ihuf{6N%rInY-nb+qyjRa@bNRLW zOprnF`RVNX;_M-fp1vKN{hRkBWpiTcCS6FMSLA7AI^Bg%v9T!NKkm8lc6SeodD|f>;vj4wbH;c$ zEQ53Fwm!yQ_cT4h2sR<9D7RTf@*4r&P#8-V@i$MtZLTCxfq4O%rP_!ix$ReKyB6Fe zE)ZW!-AMtWd+~f46z%1sx8WOIe$LC$o!&RFD?i@TW`dVd)pYU_Ndk+Qm>azH>s@8k`yJ_?Ki@0LlARz#?% z1FOWKiJAc?Bu-gWa3*f!imcWf%couE6k-HCOI*J3zl&V^WzMV3%|XG;E?$bOi^Z#` zMp7XBcbcqRT)Pmt-(#{VVhHm-+I*0GWk%`yunEC|-{&)rhcXNwH-){Tul2=34FQ3Qt%cIeu~r?R@IT zF5`SNphgC&&g4m`HVo@4O@3taXLd;p9RSZdtPI+lse8M_AJR~SD5>908pvq-wAb}_IFm8yvJAYAj!H?Gf;BZXwDOM>6$k6VKd+it5 zr2@ciVf~v_N0GUlZawM(mPD6Zll5K!eoOgUwf&TL?5^O5DyGAg@F;r=XLFp>-f&Xz zcH~pUO<9;d23^9rwP*Y)QWUVwEZb}xJRfPFE4ykF2qvrUR_B$_$=NO?an)Ar(tv?g499#!h(c)%)_#{w12|q^;$EH9)&}$^cBTVeai@>GR8~6fFFa} zd8AV#u_`Og&GJceWT%~oB&tkt?Ls7`N5q&vSS@%|x6Hf$vE^9Rd-~~gst*Ny;La$f z-Qk5!r#ScM?<(=una_e$toI$_r1Vm*KPqeiehKkL%5>M8Z`E=?2@aSe%&0Yjn+|3t zwlq=!Vw+UuEX-u}`MTHx<1Ko5ov+Ien>qcyQg8-|h}rvFLBFa0?o!XlSw2(IlaZIwXw0xL`7Q}#ppT^%53ZPFYl1XlVb)>WoI_M_9 z_Wb+wC^4DZi{3=mcl(yjbS~NPD5W7PYiB_YSW3dXt)5x%+f|3W z3;rQe#PRJilwTz1(=X!_3fg2P#Ph>1m=rD``URlsM>-P9qxsMJY?tRS&Ow1s`Ig8> zmei>c?n_U?`iI79M2!haU=%F2yz6M5J>ctPZhSnQT)M^##QP2qc)|IglZp-ejTfe2 zm&rvj%ic54e|`RiqD7k_cag7*1$?!-&bmql_!db@MTn4&Hxau~6HX!a?kf19Y>qy& z(Rpf9-XG=QO_G;NQQ7hiZ&fhbg`01#M^dsmDIR>F+O5WD{a~gaTg(2Kyy6O*@reCu zYv1QPBKlGy_Bk0&dRR=dgW8tEkYDBr|JW|(!r^+?a)OHHEC0HEalx<$33G;sXRXSc zB>#bga{V!iHV5~0yx@0H>wRK=eu`6rv9_M8wMLgrvk!JH!+ zbEWE^lzF)L$mj7-feeQVBQr6p5)%h00}H>-J($IE$N|bj3)~2MSRhHGT!jjmLWMYxV4F0FMUe>T6C~Mi8jgK$=g$$rD1p<;ujCae5-iM~!X4*V~ z45{gZ-ozwx5ySu7A`iNHso)wlC<9Ry#vn?PL2JX(Gt%H}8WKd;?4OL&Uc|8|=5qbC zkTWssUwepI@cAE2dv9A~0?1|SrcUIt~5Q?X$+hHMm7}|BpfBug?k627?MbC!-cE?J4dPBHIXqDDlgUiZCwb5AjYs)tr|a`UmXIxq5_neR`f@HA2;xm8;u%I@9%pl^&MEM02H0p9zeIuQY%K^@34RC)xx z67qq4O?G1>xc!3jM!wp?`z4nk_!&teRFI8^^Lx6idtxL_+nuRP$hAe1k<0P7EA{?j zz!FO9@VD7Nsm;BN>$WYjDd<^VrskG+J##_PWr^w~JqOdRcpIJ76gRj=BG3sa3?ing z>;^8eAYjiv?^@U*>CBt(zYzsNaH*nFwkM$4yiHi*Y0|R)u~)bMjKgK)zz@50u?dIK zxJ%D}@ImH;Rt`mJ@fk=h>%p6*q$jCuLX!%{?}=I{S$X+DTD&&0kk;h7N!lJ;^&LPY z_hiW6Ff}b_2v)r&cp_hCII4*!_O?5khrm0?*OA!)8iq>DGMg(lt`g*om#OXW^z>=1_?N^X4S--z<*F3J|5Xrik zi#%~J+^{Z15yM+4t?r%7AUWQCMtDyU)$e&3xPbyE`m2ZMzg9$A-~LNpr?mlPx|?eS zCLd5N!^pisYPD*J%%XHeXiR=7O&po_O8L1O7M6Q+MhpFMkrp~{);-hQktSvT1N#tRn|W>0lk*aBuCmW?YeBJc!f+-he10cc}GA+&0`Eh#i+ zi@@qG9NKBRZPx2Brr50NQ-GMFK34ygWEphw>Z4wps$XM1a7@wgF!?LD&_*8bP%(OQK0rG|Y!2bU$#rZM@J zRs`Aup1E#9P5X9k;}_myPH((_c|&p;?_>BH8pSHk-b_VPtgqwmJsKZr z83ex*XPPzpub~*F?S-fq0m=D^;#{AQhp{;g1mNc6j=oP7lf*oK{uX zN^4KE>`99R(qi}lZX+%Qzlco*jWtvaLx;$nwwX^k>v}2U_>h~|fy#di#GJH0Vp$!j z7(TmGF4=NTM18CT&vc-q=l78LMM>2TU_u4V+VqRVYNXewTvx4(B~h%E*OSWS9WwU% zh#48Ave{NCWGgWO;jGP%QI7SY=f+tOW%tBgX#W9ZH0#`JtaJv4>63R6vuK=-aVnYB zcQR1rFZP_fHRN8E$`8sol1UYeSLWD6&&n8RPes7&<3j&5@2gd!Ydsnse% zr@tL}apSl3=Z$xA|g+hC2xo|Qz znOMm@b24l_7XJPm9lfK=oD zU56x)VH62@^LE6`JGZWFsH9 zBAoHw13#ZlQ!l|5C$ix=EPa5bB|ja9S>Fi_F~8nT@s1Cr$kR~u&?1^)vxS9C0K1Ea z0)wAbV@Q#7tteMV5@7b|=?~wJyLbOem8&ciRaLG0cEPP5CQyaS++))1Q;=yQP3>&; zkyPDUP=!t~Gpz3g;kRRt=>fV6S@=e}TK~!d=gefIty%wKJ@5|kf|dSmukG>hSEVOn zUo@MydQIPf8Cz$OE_^e5w6=oCdaHnu&$zWGp{cMYU7`tOT-;gh$XRDgz%IwG=5=^= zA})JK8d9VUIUP&!WF%eZ79dVXEfI_T+(Yz`$cot%OM591D1ZnG?lHo z-w1dLd;@rfl`sYMuSV`2CG!v9vjfl-@fdOAXD2SFEA1cck-*`Fp(tYMpFOpW4}@2oa_-Sl~}jkFQkj&n1DVxdGcBD zp$5^=-xfBgf!&>WRgoF$u_nu~PRbPtIhr9b-I64FA&N)Ca|6%cMU(0SFx}NB;FO)h|c$kGld`}}>nL`R| zEB35|<0Rb%8@;KK^mB;Xi4GXH_`F-O-ae(hAi)EhJ6AC7Hux=TqHSXIq|PF+4??ts zRq0jPP!3CMoeWGG)=|EZX)SBO&H5x4SHR+3(hTtze-CfguET?-#me+HTf1C1QWtQz zRTj1>nF7pV;pHIqA^>qc8o+--Y`~d2_4%|u{N!HvMxqy5Q!&Il zxn#RLTluQCj&h$4^_V5(vWU}fN&4?}F|62S_It1#_^G_d;T@Vyq0y(Ak&&k#-`$S! zC!1_h(n-a86%RDUocLsJ@6}qU-p40fmC!Uu$Bm9|`DWsEwvo!QUYYrY+FDuPB^I3N zZV1bv_3N;{*8iO9Tq=dk|GQJYUX9*LdPbNiY2x32)e$C21VoYu10f5#3q`Kp{Ism# z-;Gg4Y(X|@31=+`8@Mwu^H*I3<$Lr+q?LNBZkL9b~=c1#u&Ui(*cR zl#(Z2B91fm1YXAkajMe~{_A6ikOm?FZxY@s&PS^b#Vip4iRWXMBpJ zbh74gY&6L1Tz6&=eAQt^+{cC;7M7geIHzYvOc{Gfx3R9DME87rDc{4L*f3LuT&C`~ znWNtKJ8Rc3Z9yN&kfE$wnm~u#BxG?$Ipq{ z;&alfyRvnUNTfpv-p<=@ydJj0l*-2tOsFV&x{5^9fU@~cwSWM_${h^ePP=R7IfFN~ zI=xcxs9+7$Z)=EpqikE~{&y{l!6HwQyk4`oFH(F_H>(ftsjKvT3TGoe=JIcCj2V$* zTq!aP>Xm0ZkO9Vg8Z^15DJFoSR65XlRIj7_9m)DRn)M~+eN%R6V0>WxFMpLj<)DRu zg2m~X=ZiHvOwS)aKka<8`_OOW-sZY1ewj{1k?_7cHl+Q|W+{%vo0t!UF5Yq7n=@iF zt#d6Z>`v7Dp|pU6eFg!fupeK3QsYSPCkoJ(S+!|h;<(VG^C+45klSufVcR4sz~^g4 z)8MXm#6FpqofVvSoPwRnesC@DH$}w#(L$DyFT!-RbA$x!Zjh8b=7D-=v6RBLj#0gN zciyRbRRxhS!j6PXD--{|tbrorM>;G;_+V6*4o(8O!5LE3= zSnJWck>dL4wVAy-Jkui6rD{`7Ja}L;Z)$r@h2?Hp*35@#Q6cC3#NVj3I`xvnM4N&9 zS#4|PugsDiHM>4GdONb1?=m)ltoh|0q@Z$Y;savJ`OP#<2mlz?BwPT&ZGxMV&6M$Va^lsLGIL$ z-_7Oeli04++2uz8_HGtdTi>f|N?eR#q0q7Lk#F!JikSwV?}n$Hl8xnN`O^^ezs~H7 zj7b$%=^c z{ZK?tgQaNOW7COFe!M#iIf~nHR+K$wBCtj=;?86rRb;VN1v!Ki$l-{9=64yo8^ou~ zr7EiY(nE-HcqvKhQs-UiiyD-!oxz*JJ_EOAx%==O#4qo>q`T2r+4eKzOGU2CBPAiXLWqn>}5SH-SMu#9j6XWF^L_-uMy! z$c-ZeePdAXd82|@X$Ij1sb-LAzgPBP;9Y+mR|=w>Dh@ia;a|M1(Vb1`X6D@&Z#Y<( z6n=)qmY29a38606q{(@-0%!Xy%{*XRsC=|V-vV>{#uK-6GpCzr;CLw?zVV6DjwR!1 z8-lZo(9mfgdf`H2#pyPWkXds}_uu0Rvr3zc-;03mEj?@!IU$I!2$jc9k1vW0M{%b~ z+B^O;Fm1UfVt#L0-6&=|uT2WpGm|Eo;{^b&#CFcJ0p+D(h8M-T+ufC-YrIZubPX@Q z<|K#Vb-tQm!v=jvM`WmOOl6O#5AKxl!tgd87jA{+73*As)fw-DGB@Owo^tFc6b;_? z}%a&-T>%h`Dgfaf< zH0kuyWGGI*5UZ>cusXttX1MkdBPQt#a^{i>{|r0CU^w5QMeC{d`fORM#5}(bDqEF3 z!PZ`9suhOJ$oqRlQgaSt1Xq#K?$ie`O9K3Di`HK%$T(zUXj9|N{(5KZ+SAnvYY`;9 zahP!R0eIcA0KkCWtx~(_e;#uG0QJX#dcQ|~W@*hVEV4Vtl^R@B@E6U>4-O{30|ME}$+Isj>3-re z;rF~jX6(aID8pu)4E76{(EY6uklV?I_gg)SprSSXv-8oH9zY!*?#{nDO<&>X=ZUaP zG*al0m617tnZjmAZJAF(XaQ@0950->c*UY$B1vtO5wE+`{&wi>XD+}~rGrmwt;QS1h<(4O#bk-!;*we1 z{r+%RQ`X-BQ{CgV@^WR|YsE(Idqf4BIz=mXNWi@1S~^waZRtzP)Ij5Aznp&qT3_(2 zDihJpbn-~2sQfO_(d0t+jUCJO^BzmRlF}9c?VN*QMFRXNHTomjbaBk6`{Q&CWmyD_ ze299iPTk)?$NyTfM}P_>F8?g^^_TTAnZ8>Z8ZYB+N0_$@gbo3?ZynThGYG(kc%B^| zJP(Kn#ylwd^Dob0fb`>QMcuS9$dh{ynU3jCW8Hmfw^HO^94JkoKR5=ZJF-^r$_C0+|7a^*hH8M_!N)&`nT$8DM_I9V36c z{$a?7AW`&p9T4Dcn_2wkQhxp;lL`4Z_Rqkz$8h}5i!Z2LsLtUp$Z_Wpnd&9< ze1grA{+pU6X6}nW+N>l81xe=7El(r@-4-9_Wp;^l@Vc@Im@u2tzhr=#2Q<8lOm>1K zWc;IMP3O@h*J)i!XpY)+g8toZdV5LOQf|M*wTrZ0jR&lsChPW=wWP1->T)Js(!9rR z{4uiEg%ql1W_8|4qt!K2I!LPZDspoQ8g;P6jw=~BMr8i`6FQV(x%vZAT(0aBRK@l3 z&&an8RzvVt>RQrGV$pGdl)JXVtWMG528YU*2eb+PtZah4HNig&{|F~V{JFl7lJUJy zvlbn9l0#8rwUL6`zR={XWruVN+-3B4BWd~GckuSSK`F-61F(eQ}d&BatOq@ zm|0hq-;fU-qz0wV*~51AGrt66*lkz?pdo_Qs@~~tDZEg&5W^Wji;okSc5>UGf3{xi z&lffa@4x6$YifK~H`jEAq)a05nLxbbqCJ@z`2nAz@HaUu?h?@TnX))y8TBNG8v>5b z*N-|%{>2N)y!0RWy=4?n3S~^-0@P{6Pfi4ZGg}VXE zK|VapTTd3?PqD-h>|zONA6lJb^6_JW@W|Y*IyDZV^KE?bT02Y?{i>gW*F3I}yz5dEf9lPr>T^Le(AI!T0b zMAq)D9*(p>LRr(_s7x|b9Um?FAKTAY${t%@tuXypACGN9o5^xLA}W7IC1^WGK$aB4 z`_G6x$(;W5%Pvw54uP{yRx-j=0EPSWEll9r{e@OGF6D{v6NnM+lgie{%~A(qf*uMA z@}o?2*5zoXr*i%EI?8-%i`{7OMPJPZ@VxekQN=4Fs%3#Yb4f~WTcYoqOKU=YdGXU5=Y( z5&I95jc)4CYb`|RRVvs9%PxPwzB*gXSt^EOLhA{twW9A8hjOG&F|TD|_mQ7SGDF)t zCmc`7v*ooqDxHJw@{egc3-)K$972;p=?yx|pC4|qivNq~v!zVi^MKXZafdBkq^aWd z13n0l7hV|;8X6-^#_P4`(HClX)}t$V5@8o)#hIA_U<4Wo7JJ)m=7BB6EjvdhC`c6A zielLeyIjyga=w--!KkDuPL#*Aq7*JOIaaWS%+JHh@}TK9tTrEU=-+o>Lv|WC0DK(w zB`COBr<89dVPs(SiA*R1^p8BvG0Ecw&A3LIvUZN8?AAE_E|3WCDRXwDd`EcaL zpy@m3^-7Wc2L&A&elPq0QT*>rU1uKwnlwc zC%pz2N=@!zjxK$2^B8Z4D3dhdGAWFXWWB=o*;k-jRxN2|%n^ znefkdAlOfHD5|8=nqLZ3DviHpNp*&ATiNz~-Py)K9M0BXjthhlZ>6dOf=vZW`ys*_yX`9q>jF{;~bsMPOZz0+4Z>A zkVugltT+#!V=Zfc_|!(`U?M1w5gOE#l#nEu1^d@qky`y{bWA}z(|$L?BcpOIC+Sei zW$!(i+GG%K{dUN=z#O}TiMxb4O+>+)`J7`GwYNfl*8=*U1~Ihl=o4^4=ET8F?cE;alUt4^T93!s#ni2hdLV;wQkiWU$^~hoy6ii%*ERO1uP0J`d|BRi@iBGvI#IRzYjVypO|Pae+c|Y zn(>3|>&5r3FKd3w5pa!TlFX@6Hsj-JJ)tb2KRbc9nEfk0gS@*gKw5kx-&LplOOt~b zd*{t)uq~<~mJ8G#-!0q!dBISymkUAvl8#$mt6c12kL*_K2lAU74{521Hk*?LNz8st zJWbEv==qw&Iw`r~RhhZ`-2XY{eyeRgi~MO1%PV?2I~xJXgo*Qq-lgr8cNNWlTBjPp ze^P)x-G1@oL;wa-8^o=PLgCXB(&UzfTzQ&yrARIr3l$|^B->?|qd59Bq;1;daDrH?A)Tx5(sPu_NE(fQoKJ2YH!q8y1%lx*?#8W*9Nhj1pF9Z=y zTUGiDcLKhmoSDx|?4I*d6v%COIH~;7=4J2ZMYeagFRz_q^;TlZ{mX2nAq|EAimy$P#Pwdv1a8bo+hFfTWecVlWW3ciF z1&jie$bn;q-EK^gSur1y-utpe26{#5OJK^1eJU+CkC(Lr3a@>K1)NpIjw{D#H{V{G zOVIqA4NaS!r{{V;*-H_|2lUR1EC^F39mM1Px7CunP0c_&Vr9SE-X9)?SF0v&wuH4x z&{nd+Z@#XPQy0200|jANy#NQx52U8;-ee$EqCb<-RO1fqgIH!b<0dvA>jE-R9gq45 ze^MKH;L8w-WMULeDr{*z+Vg13X|-+GbyX6LYxjTY4h<=rOEB6Y0cJOx*)vTWS9~Bp zDDxsZhT7c#Y;hL|Tu^A?<{Ag9*lc^-Vb)r0X3gS%k~rZ0e=oOVl=YY9_KO=W1q!=j37;JwNvAG`@@Ii)lW+7(Jmmb>X(o}UOBQ=Yb^2=sHKl#F; zMN}KEO$q6gc}$c;HMgn)*o#-(G24u*tSh&7RrPth2rj|6H;4M{w_Uo!HZ$LYGHzyE zDoB_ItRyb*#(Uj zb_|mnTNC&}@ktKVQV>>y-?kQVwh68Z{9t zY-Xx!qC}^-1Ut}hSxxE6ZrOWB-R%YTVU{7*`-}OJ4la;3opV&EIcslk4V$|Yl-mbAT zktv4FxZO)L4d(azAiiD*#wG4ZCOGs|AsAoIhAW+NuQLP1UG_1gH)^@Dtw0lBpMVPe z*`Gn_QZC#Tn&A zt+pJ^;a!mHPgt?aK38WDZ=uNSYGoNptV45Q72izU*zfzOOiW@45Bv5mNqtAfO<*!t zY}kHnh^FH@CmEwROPvnvipcUWtWUMC9d$lA(4yGVi}V+R|2Z5}8fbA-belAkiNo#G z&Tl^EaH*KiD(ES49#DJ|i!Yr1rIh!$B0(X10hoE{*%S6Du40+9?43DKDcuj-AARr#0#hr1d^sbZ~=vH)jN(+ALK`3s|<0`*KkDz-q*(mW-;%ZXynpviUlBUnP4F|MMEZQM{`C#%4 znRrc2_g#>C(#j9jPi#F(B>-mi=P67EH1YGHC?Zl?qgVZ{HYVy8LK1E8#i9`R=WlK4 zbt9F0qN-$-x`~gIbL?BXrMDYjc)ch`3$6~;77f27XH2b%A^P9_o0N_ z5qB%pc39vopm{lyU9+~{)4#%w_rrbVG>#LGwAW$x_{?vK9;H>$QPITT-}=`>mh`f& zGtXkC?o|`afr;l{2#?zovghozA!z1tqNsLzKW!L1vbQH5)1Q)b(%MAaSM|D!%V_6l z!(Zh%JLC37|J&GSCj5^DJyz97mKaQhoVTX=rS5)3@@ivPoFhuv@Q?b3$=^!%#=$I9 zS*ysCzMGGRuo&8Iec_(eee!9SaP#%n+mLgKWY;vXupFJa@`btXr_BsVx^EzBe-!NRRsv7qwBP#tp83S=kXlaa&EUAYFjKU&HpS5h2-LA=npSA zAx@b_r*(t-yHWfdzY@8dj>^9nEYwuzxXj<-)2O<-Rim-Xgn%Xilq-7uvZY+ zPUNv#{kAg=^kX55)5os&{(g{+E2%IS3Hht3D*CU3^QQ9ZZ=pvLA1o@<()<-o$&B_f zq^Yp}c|bUW?htmTunOoeg=gFB9&($ZaY24Qno|@886|0cVf)qtV{FZLn#!@HKKVQw z7SnpPbfW>g%sj(ta?Ue)I<{PmTmDnqoXkJk-h7W`IwQ=b=qesQP4;RJmj9KQxIePJ zT{RI__ChhTTlVf+kHf=$F7eXaf#FY<@x;u zjp*B-m>4zQR9d6vYJ-%A7JI3GwrPzXq$uYq!%xQ%=$4&^h87PqP4}N$912p1*%};s zG1pd6mrf@Y5B6OTxfIM zSzaTjH!Rl{$RgUCD};1_5GzbZ#cpm89P%M7lR59(>uw6>DjH`hs~6B(te81@hcFv8 zNieCNN_>NpPEP=t=K4xL?q~wVeNd~k?KOX2-VCH9>P)q~4&EOHus5P`*!1HJzX<%w z^uqlIB@dR}?gB^y{6N$rHSEYJ+tAN2peIsB6M$Z^Z_lm1zmJasae3_TeJZ$q3QjR1 z_OliFv)!B=WCD$WY&FIXTsK;!*53Xk}s&Akvqfx{! zvdNIKCnt4pacuv-@4mnJUo|K1|7C55;IhjOEB^JjlN=(WtOp|sY-!w%#8I6#5Ub-GM1Uq4ShPcl7|L=!Cx|me==rxVAh(E@!jJnmbly@}`Js26sJb zi88Jy%sdFCZJ523?m<(?1uzj4NW_mpob4~hIa%Gm_5^c@GtM%w5O;<4yAE>6_{=J!Jnn zPvjclPMm^K=E%9sK>!G(7IEkXTL9$D@56E;CpINXtz=tt@cDMv)xf0vVD@YS)=k<) z1)H8!KdXOw(GgtwYNHN8v#Fa-G&yeTX_>Sy;ha8bfA+)_-_!giac?KEpPuU2)=cl+ zVqSrww5rf`hq@`wsu{ObCww%Kjv_kQdz#sObwq#S%lc~rBau1bJDA=;SvWcqpmacs ztLyUmc?jBKqLupE8g@;o5MbcOYc~uoykm}ei<&OjYttPqCR`a*yPpIT^IefRtKiJf zmgPU))Kzf2v0ODiQ*f-{tKKI(`qyNsv2{wPIs?koiB%L3r&EKYvD}g~t^MR(-K|h% zi^vSqkglcHTPz26n91DaMTe8UDVirj>$~$a?S~LfK}+0ev2BlcJ|Bm*QEx=Lx3I{? zw*F-kZYLBsDFcZO;z}}2Pix0ed(9?3$LX&fO%?0R_c;^$SDW7{lq~odY~t!iFP!k> z>oX2Xs}~9<8Dl~x9JDj96|=Vgqjm+FW{)=if0(ZS!{3JTQ>ijRDSWrP!QW9C8Kvpws;YP2Wmfd5{7UYx8rk80udH%bKi`F9TI*Kt2gy z-5d40Rqw|7NG8J@?z%4kg*(`wfVKk}vZpVQENjQv6i_84Qna*i1=L>~KvDN9pM9+d z$B|XMkMmw=hPCo~fI%5U+XEF8Y%fcFamPd_R~E;a(C?$$D10jz6um0Vzp2SHrrs?SL-*Pg&nE^Vo&TBMKxG z!=<&~@aLZ&y#HlIHE{bQ7?^+m>u5DdCOl0)+16Pjajsu($J!*?L9W`D1LEYP;ZQEm zb$;t3HLXc^t_tUc8Kbk?yV2Bk$?z`o?5G*7ygODL>)!f&8pgov`OuUcMQt0MNV5*~ z&Y5}acA&e;TCw%cbBppKC1_%@5}?_7(n?K%h9&W_u3$7^qTW7||B>T00XWEVar9W8 z#Sh^0MUtIr0;ct%{PaVv<(ZqjfFas>FaDdzV%;j)!vd`r0zXd8|9WV z{&imN(4nE+NZQ`}U*5VADmWywTbhOOetKlgVKqSS5e$)(KFzCC!-=-)nM;^e3GWNB zrGo=eWi|1$_Y#y@S0l*{Lx@`RXzI~55{BYQ~q0GV4f9RKR{S$ZWsza|rq2l$+N z<9CHTb05A^AL_FH!&e*9ISGZmT0n{=ao%hxt`~;Ti?#HrKCd4qapp`d=x;pSdK-??;q9gjMrMsrlN7S7EGJS&BdRi`Uk&wr7rG4T(@~Fm9mBkDR5#`fyJxaf>pwabxzaa!;7#(2 z)$Y1~JG4QCMMPWxZV4^;nahn!3i5k_98wUE+fx2B?w@eSd}H_9W_aG<&3FEq2PJ8T zD%4dhiebzrseRiP8K@nN%{yn-!8^*GU~S%nA72CCMu)xYi^{Do?bq)sdHy12;(SW2 z>b?7Ig8i`7_przJE+P>~D$W!H9JBR^&xU2kKw)0RV)3535NCe3$~iGbvh-$$`O#n= zaY;-?nEI69TO5z<3^EzY7{(3;R(2d=DtWz7FeIp z6!8^~8#*Fh96iCcm9uXTy}$@Zw1&CNzY3*`_bLj)LBu$OOHhlW zn~fxMjh@yPXxkI+u5$;@wZ=|rBA|Zkarj-7mJ4=xy#-D8t>6D~Bn8vtI`Bdq@R{j2 zJc$H|B7odIvIgI{MCu2i@8em`J{;8NBOo?W1eZKO5-|w$!LXB$w>Dtwez@|9ZD~dl zaS(x^x)VmG& zfr*TLtOmt6?~j5vw%X>D0~D-0!s@3=DB;lIO=iDG#Cmdc>G7ZuA|xhiz+6%S>>Bgu z@kN8Sxu$Z^C{1$;r%KLw3JrWdEBM0sd@Vt@ce0Jp4WLwc~bCG-2v;>pdwPy(%G%g8xUL7~NRcJ>{g z{Q#wZO$_Cy0))&&$7+mD8s`pqd5yB$XtNer<%7M(BUShPME?u^6b%ItiLQ4a2ZJgX zP#bT!q?D5OZ%_qtWDkR9hXRL@7gdxqinaI&0{5Z}H{*j< zl3Q{4v3;PW)o_;)fN{{aX3E)2#>ECUNpE8JGIAnwo%8A~wRu&wnf#iP>Wy}rW6mA( zH}b(|v~#jTJ~!j_UTizK?iAdKMrNEOHmA(j3!$JU;_{8Lju+A0_qW)7&BPJYvh#?>wzDHineMHai! zRZw^G>!K1&=4o#Ldr}VtBBPUhibkG2YO5D(u*Tuaxn|>y<>K=PSJDmpWYL@N2MbSL zMTb57+f3Y|uR%5_qO^8vZMetQwJ?cbh))(6B3_gA`xLt4js)Fe111$Y#&u0(-N4DX z#M8nar^zOB!cS1ed4|A$kM=Pk-qrtQGxGF5l!z+tzSRE@N@N_AtLRG5-1eC{HQVF= z8RXlo|4!N`IkfaxPs#hKg1||4fcqO^;djxGdOjU@w|)b8iIi zI6RQe3_liB4~orT1}jXGQ0ptxxcyB33NHHdXK$nP?r@VcxgWtGCX!kz5K%Z>y1R61 z{nH!WMpSUI(pNHSr5GNuM-zmC$s^;G*cZBG?%f_JJ&{RFWOvV9oseESD4gZW3NxcpTt(L`kF%u$$UyApp;DSJ6 ziBAQ6xCWkW9@t>yA8mdO0^U0V=06Xg`^lFpdZ?T2#z^KzsdThyWP?u9B17<1O`~L%dcx67B%!p#rby@)%{#VZ#i>@5 zCMv8)1a-jc<>^|4L^v=jlADz+AaVB}^&f6$TmKJk{l2CO5<5a#^|nXVHMz!!h7lff zb-<_JHL@;A0KcT}Fq?AKPb{T{hWfsAR@*0mJ5{jJjbpn&QstO9oFp7wh!>Yp5^@yx z&iwYCMKtcg-nYH`X~sn4983yR5#F&zq}Ng|F9SXv{Oms;H8`^Nc>4Ns%4G#Ud9I6* zn~WZcO?T-TqcnZvCzW{ZgrT4cw0|sy&F(_MTRRsXnV641FalMa{U%-7&?CgBlag!~ zt=dGlQ#iJ!NPlUCuz&9JJuddW#TAN9euCWFb#>to{;m#$Z%Q%C`%sJZ5~3g;E*!@s zDk|}3+v9cE8O$09Om{UoV?I;cf~JsclVr~go(O!u@4EjTH|dcWb4|>)RF|qUozVDa zX-57LV`p^}AI$`anDpYV6Bg)o4$dp-fVsUC$;Op5DYyga?J{R zMqmoU%%}uT2+KvQqNoYk5bvKXA@6qp_;VuGB_1BQFb{HSw!y;%`xGh3wZ$guPAtgE zWqAGm!6jX_FiqthjKXDjhtUD;t*S0#$1hu(R`MH?nGCEF@|fklzXO?y%N{Lk|{=d_!gIyX+Y zY@8V({1O!j2FO#Ki9g7~abJ}+ z{E3_bdrR|vpQw?uvED?@!Y$k~J10~0N|V)ZWtZtIyXRHnyxvoMn{i?czV|hI+fla0 zI|0#FEe55Y9) zTZ3`p+9yTJO-<%u=piGf`K8y8O{aFLy7nMY3``eiF>ma zg90SFp`k_9JH;!qKnzo2ymPHzbY*13*H|2FCTtmVF0Z9qB#l|tSDc} zc_o~94A1E^haI8rAwr5{w@QbcgJn?g9FxXxvT{M59DM|Tc2t9Zxsno@pun5go-YUV z0djRWutl{@!E<_)ytHP*Z96TaVnN@dkl95IIdB@d0+Q^B2+60{pyYu8^p>d^hZ7|u z$cIuos}gJ^u!!jUv#N?p#(K=1jDbj;0GK~QJ||31sG>z|;@plfbX&1O~WLw7>2k=7j7& zmLHYPOSfISLWkrm9F_qkxUv?;6I3;j66vFk;=v<8_Ink(3ie(PgEv(HJ4XgX*{?Rf zbFw6uIqxI{8rYCmYQuFtrjPk)#65nfcqEyW$UYq|$0Tb_glY({_Zo{_CKqpb#AdH9 z6UD$p3{)i{u1xoNXBH{X)e*u>VHqX2!DgqQ2DhCNIaaV!&fKVAC>T)O5$Q?6T*#hR zsIGkd?T+#Z-gQJJ2CEQOru0(3pAjCb%jZCi<0s6AVEke>*?Vn6>!;sp-^Ww=k^a5o`O6s|gJo#GcCe5E<1Z-TSpMOy9*^kb4Hn4nLWHnjk< zJU=I4o9j}*VSU_~9EDjdoRUVrz0b{SYkX|qu+CX4bWRhnksr9bqQ;$=dr`$A>ql3A zE~K8cocfq^2A8`+Yh63P1G(*tk}7jTwe)yZLh-4&={jQonWiiz&V;fr8 zv8Rt8!e@vZ{qa`pO!>n}Vmo4ZNL>7&;>XHd-0EQUj7iyeKD{-Up|!ND@pHp-EZbsx z*mkO~XxBj5U;h9~{dPsUOzWIf5!Y16_m2+)=p>?9%4h#8e?0UvucRdE`k zn*v-|T+(nmJ&$mJr^1;|$`ju@1=$DsnP29KCy9ZI>x%7%hkVRI~Ri7C@0C1e6fktQcs@JvcFTmj(U45ENx+- zJG!u`SoaL(^LJHwDCQckEIeos6$}@eWh|2cvn@dgyDLU za&|cn#rBJ$Hm3ryKTvk3*oEEcnOwEr_lmIi*3Z@7eT>v-bYNGfb7MoE;3!53kWO6y6&x5_t z0n-9s3S3J?F8c(pT^4ui0sYjB&sTB%h}enAAZE6`FOOf&bS$37Quuo0^7yEq@b@Lx z^T1oHa-BhI)XWw^V0}Q&mtjEPv@jt3h-9Fd2vJT-Zn*T6j`mE%d4Us9kRouMqi#uq zr%Gd@)wcH1(#*mmM}6%ZAq*R>uv1gRc4ju8V53el^c-czqS`_&>F`I%)T1XIvn*rheZwIu{CT z4;U0Kbm8`Wt^TBP5lW9X^G6GpGF$okmK~Z5E%ZVNyOUtBkBD}K8&+Q!57afXZMv(* zBtVdH^@GzAA2KTKewZA&5CWH*cG;~vkqOiZ5V`5y}N@J}@8Q3|e|n2X%` z9$4Iq*3MY(b37hXSKX}J@Uwynij&)|US*_HOw1zuAU~}nsu_&Dd~|%$hSoL3Em}RK z^EQM^jHL*hodmc{$HpzDI^AZ`)YmM5Zn7u;^R9KY&m21audYL?WY}*0|6bP-hpFqx zl8E}>QR{_=zQ7_j`-b{ry0nH$u?BLgC;^XLF6aK`c6HKu=#FjjyBL8wlOlzaF}=j=XyfA2^;H!dpBJr7Gg`m1@T3}B%F)!B^cop zHMB@D#p3Mm8kTW{f2r`1WbHHEK*Kx-ub>5H@PU;^GtJ_0XK>KQ<k4sVVJ#ow zcqOashFt@xA}Jaen@bcXpHAQZZm%F^*2c$A0ebqyi7kQp;*r;PPsNjPvG?c?RKMtR zgs_^_zL$UV9}w6R$fF14ILhyA-b-W4iev~xkau1eEn4_~+<3}J`Z~|~Pf~6e4jH=7 zjrRFyDvrwGWjx{X04SqVYU7>!I-lGN0L7CE?*(2AUM}sF;HBpHC|se%faAqm+VIz> zx|83tb%t#hyXo?|kbFrNMO7uvyV|TS^wn~&Yy2kF0#W;zAE34oYsrnLKlj+HyB*=d zw8i!9B9A@P@W70Nem59|rWM#$jFJv6stNF|dH4Cw_&MrjD|=;I@SB|~2i)UQ0(M&D zNT&Pe32l@IPD&*BOq>w_`^)SB(A17t3QI8ZjU~O?5|g8MRt#Ny}Pd0C;-AhP`%F%!Z{0@jW-^0cKB*s+ErXz;rv|`>7z{TT($w=$` z)0Piiq%dxl9Uttf!L^D)|%MPP_<$_hL3yn%2wg1XT2h+eSF z*rU5ToE!dDpJMIk5&c51E~O>&xPtDWI@U2qD-Vh*ruvl`Lsal-{6ZXjYus3u+M-6= z&1SZY43*?+>3(b3x+NWXN+tA~VX2JSqqoW;(972feY^GX`Az<|nMSrFgVA$|uj$Qf zQ9|2jz2Awr(2MJ)U#tsT2JY>UY^+HyqbyCnanI$J39-p>B{h3%IQ|u!k#vfeOPEB`d$6!(M`BX&D7)MRCJO55!MVu=^%gj?c~&~ zA&|w0lG@-AR(O!)*yyn|PvbiYldU!ZVV;0p2#gpm!sA5`Ah=oS^enSoHGE1QBeTe)u+i`s1HCJ|2woPsRr*2OC$RpzEnZf%7LD-K)L2~YS`+% zMMU{vs%^uVZ64!JjAK+ZDWeooS@)J)Q{Y3u7G83H#ayD7QB)42=g}jF-7ri_qAJJv zbn`mQ6>EYCE1>0v{R>nF?g`fJGg@9%L#$1sV9{5^Gv>FbHl^iHgUL!ckzCa3DAk=@K@p?cC0lG%SOB$B~5)7H#} z?gP10o(>NUs(2Ss4WsWr3w;{gPkX;PKk?izvLGfkgam-Ion~8KD#9ZU=GE9#+899t z#bFaUgK3lr+5xucYTcnP`bF*^CvOX?wP#YSX=E%amjao~xNJVu?u^}f(jIqcgF96$ zTO>m>4SR>n3ug^7&rthb?Ri->464qUkqku3T+|h3=y8>wYGnlGdtsFu;LL`|`{i1x zGgmFNHQmb_Yog(~#CRo_7H&m(?ae0b*^c!^;p#}w_xclG_>mXeCYe*aio{VA}Otr4v8IT);zBm|9n%6gg_@e^1qiEM7 z=Y`vbl}Uw@?)so4bGL`VGWmc06XJ*_DX(IIQ}GJ6r+=VUeM^XAK8&<(a(2r2UKrLY zDljxJ>K9x{W{Ko56Q*pv`sFk}ZH+5CCM_<*#?M+jSEt@dIe@Zt z`|ODRcHmyWkFU&b?^u7!GtKTQmC{GBrrcq)W?)BrGv<$96*I#L=X76v`%rI(=-#~miq)QXtG~-CBjC7%;k0Nj2)tznll@~!}>H7GA3zq zE=$_8QjTjz3D@?2ssU&{UEhv^@}&?Ak4y$nVhf`~N-Sd*6}{l1TO!RaZYP&`@Guze zx3Y0Lt?n<1^}V?JUkUCCJ8L&7;;D+i{Ye%XtMru9O*?d%>i$S;{5{?7_=pgYh>FPb zTpLgor!^fTYs_ar;{6E@^1}n5_V8$gPoD9{3OE0!TLMU(lP{kGPb}#9BKxy%+X2ZKAL*io4cj9iec5J?I z$f}bP;?Tp-Yq5Y>!B!yIA+yZ!X*hE`EK8thP|Jw(=}=&42v!#d(82+HmoD!oc*U!tH8U ztf>!Xuw5Ei#yvTeFFgM56EWDLPI1NCVBwxn_ zR2N`tm>2V1l=IpO%<7u(nmp5I`>Z)+H@Lp=DhYVqFil{4m@!y#RdQ)dGV)31S0w+qWAEryl|-pMOwkknhPkY|qL^#XGuf*5F*nDy+?s5t z)%;1J(7id=Pz}!+ykT^fbHqq3N_eAphTyot2Ip59u*Ek2@6r!3V76+OK`4g$INMOL zLoX#)Xtj1lS3R!uEyr8m8Q4a=%X=RrX~P(S-DLcDN^JHH#@+tbatLRFB4Qx{f3}sq zjgO}x-12~J3tnT#QdSl&g7U;N-$iT4Z#^x0v)gDgyuH`;;6nt7U~dEY+o`zw zU&r5G(87LWt>_yY>JaI%j>Tqf&yLIGnI@ZUD>zWL~Nx%EI{_Op)2}d`#_Nwy6O!7e`Hrt=< zANlOrJ955%M}qA$l-Zv`nnB@l_c3W!5~zJ~_HE)F;H3UMg|yo7hyDC2?9Aa+T1i@d zcRi6139ZVoqbV07A_zw|R`SE_ZpvY` zQgul>BD(8`#*;A>T}E;c0^R}7Z8*wycW(b>w!?13j+HSJq$f>~<3R(k`UIKUg`UeX zX_B3t#p+pI zpx84p=b)G@yf>i>)B^t5eV~#N#8XZFBc|7}ihIwd`BC!{jkEYxzM#7YC=F6>f@s z@K=XPVlO^DLa5+E(w+=83XSQcE?hEbQ#(vKCN=D%9BTS9Fy^nJ;G!ZHdV(u5!Uiw` zn4P~N0??)aUp@bphFy%Js(hW zv0R@ySxOhsc`UYIE}I)2<%;zcw58x+Jk2cVF~u?FP;BWL4;0SchCxx(4@+7{lZ;4vFP7^v4XDb!)V}oyVl~0LV?dp^3!`(n$eXa>-PGL>uor0n1 zi!>l)FGH$--ECcR%~7qxfO$x~52MM$NWlz89=;=AMSQ#8+`?@(pJPwqs{`0+0kf(L zL&I@;;>j1M61p*;gH)2O?m#*u5t5lT?rMqXDo!z zIBu^c;LZSX()F|T0_!}(9kQ3LnAnhIK++c+erlicC1w)r(H%yzP1U$ovo4j#!+7W} zQJe4I^T#eJRLx_^@;lo1`Vh$2*DcPbVV$AXIVHw+q!l@ovOpN#wVLbb?sxc9G*abk zjMG=A1+xvsa$T`s=Rrq$p;_aqPbcZ2IwNjcwpg)OWwK$c#-|LTX6fI~1 z$%;Jo8mzFv5Z_{S0c=i%L297?&n4+56m9YX1T*Z&v$P8fRbn9XG0{J`KW{CR<#GjD zQ+^a)VHBCc5+%Y@20Z%U#1{7b4Mpu_uGj;$Uo)?D7rqIK=gyyzZtzUScRQZR6 zrN@)M6KBsJ-s(!)E?fWFCk%_Cei{q;xSSJpe*I-Oq~YR6bh93ca9QTD*;Y`K$!OrX zLjRveq5#}F0v=wS+)Euv5!4wk&+Q|(6Z!+H;}v$OAm1`O%4-KK#*SjkP*k|nDgeO4 z=muQn^j7f!BqB}jp2KmGp+1_a_A1Mw-fg_g;gNvq5&eJf5=e~Mja8MmSd*-VFb=Ks z^@!?wr#D%T@QC|4(54I2LX0r8{yS#A6T?l);jv?%09m!GOK%Y!dIcm>i@Yy0pJ|1yxsBgWZWw<(3yOA0DU~Kn?t*npLrTdu79&D9!qW5 z4L!BHOmH`Ff3NIs3>9puFt%O2-mP#W&G=xzf}FF>o?#kGkiVH~{?XB5;Vc%l6cJCw zeOUnjnk{}9lmqRxKLh58wegt~BGosQ&|aK|(wcPVjI*~&rjMtnvgDBT5qs3;2sMDL zjW0>y>+LVvfU$a(B_=cYZ@tW1U7aMX$K9ZpcmO=}TH=qa{)o@{yEt&ZL6@CVOhjvY zJ;{k5b(mQF9NJG;X8bBG33prl;UtjB|Hjw(mBi0fQd{oV`?rUpvl(0W9~p7i{;V>2 zEy04k%0XiD%IeQ@+QbzN+1VxQPelC>7xqqX9+tq{8QxM#2Z4vLd@lYNV!;pcGeFbV zwp;@)`!QNHx>Ew4Y2NVo*5rn8+Dp|-|eX~Y2#w?ZlbD0`9{wblmDqgGWw`rE%aF-DQWckDHOV+ zi)@7?%Iej}N5gmw*eNL-a3J;gz=gNrr9jz>st607zK~ziIXmtVKPVPsN*_pmq8rwi zQvu$8h!!Y@!mud!@h&^VJVSj_unrlP>`bOCR7a&Ylq)PMe+yIreB+N+{!IM2IWA~P z!{s=p9H`e4CUkV+5^Dd`fZ)bsnKLwa(uUBz+p=fH;w&rWEcAyJH7UX9 zcg_{oza-5In%g|VXzp32fe@I>0$Df7y|OH&H1bkOV44th`5u)F-d@&?8iha!r$tdi zMujWHsR76%a{pyjUtK8N1Z89}2q)U*o4g1+PHpB&p%O|I3Nk%pX?3+?cHs9~SE{kN zIm&ccL}R^nAUtIIc*4Y^vg1CZeuK4QOzwgWSd=kXd?WETD)M|Z;U^s?egkek&8-gn z1k7x7nIQe;*!3B6y3`wzxMMwRwcdrjt9)&yiIk)~DXtfeX1`}`U)ahfJ{w;SqF&;I za-zyn$$&gpz*pSp&NBi>`u?90B7!FN1-apZr?-1HWR(6ZXEehnxr$Lttm?G-0EHB) zJ42`5C6M%qmt=)`X!-@>xs3xLgSZZ)p+c)s*7a3HnbE0l@dxft^4c@vK$2a4;B-tB z|0T6Ye=^WtGcp_~n`q-_vIge?zKFYx&jllfGu!HbjIGDL9NNw!xa6ZGD4}frJ{!q{ z1N`{HB$sH0wlrjnf?At5s!Tb9neJ|sEp(lij8<$|pF(i350*YV^Py{G%^oS4)uN8N zg#=@KGSw&}E8f7J9Qz4h&aS^3>pqxS+h^)KMI7td2ci#l_xd)O-lurY!DEre`%@NB z^%+IFX7uOg1xe>p0n-zXRn{R^Mg)2GYIdgC!a$3WQz~>KYSN=I`L3%Eoq zaJdV3nX>)e2hkSxQD5~ojTyPT0tu{&MDerkL3{Gq@AfqJn9-3wm!nCO(Uaum!Jga6 zZlg{T399RA6cp)EDrc+W75SXc22KjN3tXzzag(Vx_WtnOJ>Z3!`+4)=e?>tHM z|H##STycJUS*&eNB3tlftv_n>UBR#3c*o+bf~Mg*#xjdprwd|l6e{0;L zt?&3DyFxr=hZW>}Jj?N$xPzolp`7bsWZhc5at-y?sutpw>%X`qDYM3iP#d(@a2_>< ztkLHdo`&WdIWQvyBK55lMUpZ7O%wDQ7Zsnlj7WN=s5hTeuSygr1k)s*wCbMPz^|d^ zVl-@v-(ka^udy&hS3C$u|J)$}?!Gx?AGA3iJ0%3@LVNrE&Q zQ`t4SC1EE)>_NLFIBb_a2LC^Wc1eC5?kT~Xk4Zf3skh>8PTs<=3Vp)B>=piJEg#Ij09Houzjf7NtMxK7qKR-V3)BV zu%yDs81-Q>6)E314CTS6Knw-gVKw&HGeGRv=m8&JiinSb_@A}yQ-6Gh)$qab8NTPW zN~4o(*Plm{?Cn3F*s(-tjKqeRk{qt*eCgY9d!m?(BddG&JLd;DTIF+EUV>n}E#)_u zZ}tR2o$zB~Bn?=kKPHRrsGl)NY8xzn3ex*)!FK;tI>_T0^|NT}EsJrjmw5UaI#RKG z>Y5pW1-&7R9G{@ZZ*RW|QYjEi>qm*9DaU#(9`!rzxB5^QgyQfKKxpysFg;Hee!N77 zPqH)0QNsu!*m!XKp&EC_vKS>a?!ArgS6AwE4FZ)0E!mFK*M_}DBpkKxULHO*g$xff zfo67UHuyNy9kS+F9y%esrd=*}-QTWy&}NCIT*^HjQhR5jrUHg5R~cLxLx08Jluxo^ z&fg-o1O|@2nXw67Uq|jI#OSJoaZLDiTjyJU!KJ@c^Do@YA!b42>g{~8#}R zCp=*jka204Jm`ZI8C0V%btz^*CsDzM$rH;oXv%c0YeRd#iKk-srUAIl=oE!D;l@BKu0k-6V zDurZI)6GcI_Qic!VEn@Uw&HfE^eyJ-J(1WxZ!W1KMk)2u_C&sGH~-aZ(I?va{pG|b z)5tj4YFsrYSL3O_siqsHXHfaZ$IZ%@w&b)LpM*5CY`$;Mzi-CA!k4Zuq`>>}V&p3Q zF=5d@Io;QEl$MA{qD6!yR1nRV1=gcO1V{4l{}Se^lhBcx5@+PA;47=lnNTv8l9Zf~ z-z&<5)4c;#w-lJ!D!o->*d#WlJNsT48%$9__Sqk<)v6IqhcK(Wp8S_Kqgm*N)~v@H zb7%4sbAD^A%U1)nZ;X{8pLC6{1S5Nhpn^5e0V6vh;1lNQ&}Ts|K>P5#zz8KPK=eNo zX=Y%~sxspX(#3ur&C#KauR!Kbh{8Lw;=W-hAhC)oJgV(OUb!B8fOfUhiMD z<{z1ko{fHhvjDcP8oEW{&k(_CKHHWL03N^D?LX*;27*CTQ8ai;YVpy3gYmVH)JG48 ztyi_b1J>+Af1eaPP)>?JLv>HuxpH+NHNZSpZcZSS*V-x~eCUg^plT1i7nZBJmFQa*HiSrJu zz*=R#Qg%8-5Zshj-uL=ic%kcG(s7dA$ss~dn|^JcP0)(2@Hx-AM`ndqBtJ26yH(z@ zH)XqbilIXCQw9h+&0&ARGro;#8zNzie-qJK}#5ckft$_kmnJsZDnHRG1u zT9Gbjr3#4`h+3D?2Y;+#9kTJ8!1R--b9rca|9=a0_E=k3UeGo}`hQA|skH9HfMJ`S zUYmjU>SKe60PO}U*e(zL$uDZNuYiiJxD~gyqO_X#B9NVs4D2|9-8A1LXikIX>yx?|wh%>GyrU@Lh6GwZkvCUO;3{A?M?&DWfb8iMKfDYsuQAc5OL4uibOGzL<g4f37(Tv^Ux`M{6rhDr7GGjnRAFB{Xnk)?eAq1q?CRD9ywC`g&HUBy@FGkmeya5H9qfmy|+S!)LaQGc9S5sF;B?chn=H$*_Fngr~KTjx1-c=YARmZ~{sQ<8;;_xg{_w*0a z8o0*5v)g983CIUy>63bLl2YN2^plcbAX8+HUG`;!0i(NPewi`%)j@}{jm4p#(|Mx( z<)LvR3qAs4y=MahKPsqQ?@(2=#-S@XsJVyUiO^PzUk^CVlN`|hh%kj(=1B(uQ9dg4H{oyXN zNA8pEwfV- zXnvk2DeGP$PkYdfh+!nWokd51lAFF)WcHrph?_jNrREtV3Ty5;`)1-wCXx~SmZXjb zdJ}XmWs+8}kVgWajcFnI07J-`nBc;BiH1f{DfRaUqRhLKgn#6moPy~|*l@44k zW;C0PB>!JhO@}wI_(XM>+?_s<=S9Kbq|B6P8R$MFyj5ABR2(1^h^Y|M9vVi~IL+0O zqqy1(Q0cay#miawrX`!q^3opx&za%6y}0cC*+y;ZS%LTUEzl#i2KP-h#9u*b!utN; zdrppZ5?nid$_p!h#M~gA19<7`c)d@+%ogqq@FCuHqq|=JWrXT_O`~GN0HuKQevmPa z=fiDtqDQ42wa}Zs7^&}oih{C%RLrD%#10BJhdCq%{}2?PLhiR`#rd-%n);%>)rFC! zkepWnxHJ0PouP_an8jsqKk;6Q_N83dy{H~oO~N#BB&4Ql+2xR4Ytw9+xK}Q~GH=dv zUG#E?if093vSdLsA97jeHdeP_;jt^E(!4q0?sTOpmv(%3Z9$wvbzBwHLS(g2p>^Ov zlU6vp+0rv`oJU;cSbmec5IPxg!yjRhBoPVuSq)EhV?1<76k~jHZC5H%CTC899=U65 zz9~%qbMms;jzQaN#w>u`-MFjsN-7kQm;q z`CUTO7RN+FDPKK`=f=ylqbs2?(q}BW)#4-vLgPR|uZ>%>87z46d0^>K40RqJcXV|d z%)k~k-?ia(SfO(Dh-_~w%q)dod-MJ~n<*qeU^~q>9CRo7E_HOn-21MA6r4 zcAjnzA8(-K2GaIcO1HG(8IXk)%SHt|mfHRMr4qalklrB&Z`Vcg7KGx@jfK-8UUa3I zszZ|Smq+*jOyh)`Fv|%|B=6ur6@2Z& z@&Sgl)6MIl@^D}g{CGX0TZirj>0T3ln_n`+GC$zXBh2Ex zshTFw+BvkI7(0={x8~sE^`3~kuO9v<(-#4&3hr&0wx*uqj?azXTAju_XYX`M#P2MQ zYcPDe=rVdVANnR?_sLTjE7U@}*)#ub5ub!XF8k-7#C~@@ zRZ762e}h-N^Yw?8-@JlS&UeSxDQUWL_^GMfXfY~l8r3A-wnHbzV?OhV4`NhDT0q7+~9dE z-4B2K(hGz#xsZsxmcA*w>H<3&+1Bu!wTMXCCPC?b?+xdG#9Yg%%=<#{$5O`QTIED# zfwlt{f*shsaDx_AURssvUmM6mrFNvwUKNzBg_}&=huFf6XjMUaz#;R*+D=(YxT5zT zvA>UyeDMdpqU&wD1L!N*@R#QN-+HM{?==$HH<(B$%0 zRExNX%Qs94>Ru@l3$Fz1v17&*?{QwBhasmA0OF;^T}WtC zTiA1}^e|ByhV8jdT|$6-8DV&HMNKR>I<8(0NHQt1UZhcl2*MHkqNopRYk6L#HR;4% zxHl5)akTUI)aJgwHLra!UIp=SgZ@k58>!%yZ@Dzo`bdpM+>h2}=D|g)WMt1A!ye)U zsSolpLcPaq4g!;<5Sx{!f%k*bD$@5oH`|G*VN)!%mr+_Vg9y7~*NBy-Ad``15?5wR zsE1nCWmsJo?#4HQ2&%`JRA9FtErq+BOW!sUVUTE;>5~y66};Xfo$qh$ud~TkqeWk( zbM(oxiO{-D3y}D>^9(Pur=B(E`H`++zx$In1rO^L-VrN)QqKvhgr_AdpW5eh23rVx zSAp9Kb_fj;k)<93WH(Q?Uz(0~2i3h+PuSznqIxm<*_`FA3|FuTU9bBlnxs70=>+<- zQy*A8A1m6Q5MYFRQg?6RxRYE;PTnCGkP-YRQmgFAKx)0)k!*Sx>FFVa_vpjm-qC1E zX9v=7gQaZ*v}a*rX&&jdKAmjeaW+6`=V`@NDoKhhyJ3JjVddH6;tJEbJ?}_55vt&J zYrpnT_p>aDr?<0h(&Hs#r}Zt*JGL@{qQy@&AkiSf9ARc)B&jFYtSNoLziPtXT${Zv zkiX{3b&d+QDUK%iNkZ(1(qwyYS*bN#7`j>5u)opAfynHX>O9Lo{m>G9QPdj+L?BKn=Vin;ogcdt?h2N_P~dxsr|)-J0r?1l}r$rYIKZ^ z*;t||3b^oEWaSx_iObb#eqf57l=uHD-0rpX8`$?pi zoQO%8TUCx>O(UK!xMcsuq(R>a^^yQk;^D(;`$;SWq2rX?zj_AO;^!qlA631ixieS9 zUjxpqTs?yFw(+2bTQC3ejNaW`fJAY5dyk)r05iMa!{2v9mD9^UQObdjyj!;GJxIO00eTT5RoPt!fX%NSFCJ~v&iC`YXbmEIEl`dfD|;pWDig4+7{pV zRBy%w2QyxTsdR@DWopj|;GUW>q>5OTGVdW@QsqewWg1#8!8h>4CtW5!4X#2%7DBsv z>c6=2uzAhs)h4zh&B3+RoRM5flf$n54b2vaG2HoV(Dk|Ayp2E&tn2R~3e$1YSB}*5 zo|EwfqpOXb91vf$BVb-# zklYgpc)bGe9qIE*$=|FaNnIAcVHumysJX+Fbh6pZBtNCv^%S`*MJ~p2E04wa9I9)J zrgV^4bWT0#T%s_^GsaOX7YM`4OnVh~( zVjOqyHobPJNe0{bve0IO>D|x3M$3QsLn*j}m}Hi_@U7b1|K&Zj2Q309#M?YSg6S-2 zn?{nv{3qfS3wMSO^-eoL4L}=EG#LC2#eoFm&~^Rpb2)LBhnml4gweU7{sO)n(;y&D zI4A=nFYk3eys}ZBt-sB1R2S;gA)wH=g@8ts5S7=;@i_s-)KHx!-N1c-_-%>*vViX3 z+iuZn=JkA}dYF5#9>f<|kI(+wQK^mn7Nn$XN&|f}&-8WQrEwS zg11D)a|-n7o*aR~w=ZW@x&~&72UH~TlZve#PDSuO)^Cjm-s@KP{C;z~LTyqd5U9*s zCcPst+#BE3`Q*VUszX01NSe^!aEIo%#ndbB)N|^u-FCpR=ipwCLlrM5Ko9Yu(>|~1 zj~X_rtMEOF4+#E24nVfWVQLv5Urg#4KHV-+M8znsN*+!2QndE4OS^<%F<^D(mC+Y` z`R;DVVEDV?W5D|!_xdHA*S|`OR-qBP`ZH6@KHK)qve zS@O^4GWH)bqy)NV;QAXr5JNhMw$g$BZk>aWSKQg0jf`$zzgA}$5f@C>=Z^EebNLWS zwK}35hbM1DXQ`E0(v}X7y{@~Ddz9zgp9#f8$2O5P19;PQ@?QG#vs%PR&r4`~0KylN zS5kNlL!!cPT*Ovn@&TP#=0AS6p(^C%xlwt5r&!u$B_*#}&kLIp&!ezsUfJm{qyQZ_ zcW$ezu)ni_lmRlNA;-|>JaF^qpI^0^CjNIqNaeT8ccyRpL7kpJ_Q`RD*d0@zW-otZ zh}M}92)`V;{S~J8;5O5A|3mQaWyrB?UziweS^G^0%L*nWqZ_E)MB8ttpW0v1V@;(wIZKPHjK1> zecN$&NNF6j?&f&tn5wS%8Rtf8lb*q7FWElR^qT5|EY$>!nsktc7i#M*%;`U^;X={niTlNPa zmg#?e0Xg7*R?aK5Ku4UA4Q1A!2D*w^4)on)qEH7E(W1|p&_Dd9i^~|q_O-nKvD-?J zM>&(maZaiHc{Ls>iB*}0Y80`_=q#gLgv@*)-+CCwwu`RdO)9v^#Y#SVW8e&6$9VYY z+x2WxfDTR`>rge>>bO0N9r}m@m~F*aAFw$8ii*eK^^gRXW}m>$Yw42WvI1k{lU3t~ z`{u?S3!dhylF6~LF2ijM3}11jyzTP9zPGnusNQl>_R4jWC;bfMFl(}cLE7&p?$XtV;%w36`U? z^CN=nFenNyO?|Yc09Rw$CMaq+oESjoHUgO@wyorr4Vc#P)vO_^T4z5~@ZF$?L+)gi zX*|*?qJyR!_2{~HrAD5C0q!Jdk}KjiIksZr$)^&2qU?pzBtz9_TT*iq=)S69R}B&# z^zdE@={4JMqB!=*OK3{6f6h#StDhAG9wirq&K9U;R$0ntOZvNruu_sq<9 z?FHF9BXZsr-il%x(yerdhUpchHfGySZ#37enHc=(Un80IhN@shvI7KnS~>SwP3WYG%SIRF~}px4L5IsiBp z2+dmJRQT11lnuuLIF37^>aF=#h7`9Rh@r_o`KiJDsD2PH+~E4)m1l!n{j`j}+l;7t z1bb(vm3^bg#{NYwa&?p#Y9k333d8yU*jUPRkg6jeB6fA6b`Q=Bb@5s1maE%#N`%dw z{flwl*bvN*kC5pSlszdZGk8yQ`qnj8*Kz(js^uBJQODCRRNd=Hlmp&aMK^jGh&N~V zee4O+<7Lsf%a7=HNKfezm1~H-D=q9-&X?T2%IFljiY{$QUOUEtr)E8~8H?MbKevhr>lGZP%}?m+5iDT^WQ zt@wkVYh&i}$gWMMv*9fAMPmD{=*DbK1T&@iQ|0_kF{t2rV(r&z>dO6DmQ=2|{GS9b z#6Y%6*YP(liN;es+sB_GA~%$5wfy1PBjN{@EhZn^aVtlr3?c8-SAREYRj>nCAf7!I ztE3)IL76QlQ`622_SkkXV3}@&dsxY_FlW`1Z0*GJ09u~j2e>zR`572s8Dem ztAK*isn*~AKa9P1G}{jt|C_`JwX3KVTD59K%_0b@v?yw{Hbqf;6Dz7kYuB!=irRaI zQmqwx?>%CVn6YlYzu&$0oO|!@cg{U0e}B%&AIbB1p6B(v-Ud8-SM0ieZ`OA29js_> z)QoWg$)Jv(PRmSwrzGl4jCkElmW54yvy6Z9=QG{Et>D89E;BE>@|sEO9r}&k43kd> zu^m#}5ZM=J`?IPV`wl-f=CAp$_ZDuikAJW=r_Kl5wjck~4x;-PA|mNFNbX>VdZ8E) zFek#@1=e^kmR}VKH&_R^K7J4#9J|VK2dnX57)dlpf;>dWNSaY?*s3;SlyOpMp+Ovg zr1|l|_ILPE5gKX#dYT@Cg>QT3`VfURVxP4>Y?!C)=Hz;x3sEwXSK&{{N^E@itVEr1 z1#Pi9md5fF`m5L~Q@b?b=R$AH{C1$WUfc8Ne%;On^u2eya|2;_=QKZ(XPBbfuHIQ3 z4b_HxG!?rK8MUD0I{L<Cq8cs_!oRN#+S5W)gpt+AO-ZE zSeYVikatmkL!-crT#z1%qmr3Akf@82gXi(GsgrVLmtdr&(^HRAqNnrHlOy3YMFxb! zktVRWi4OJ9L1E-`B!`Ug%F)Lc#7?UW{DXp~c`CT0o=PO+_I@APKH@I)736ME7W zf7}>tkXRxo1Cpd!?dke9FOxrpb|4FH3@3r}raC*9b3{gto(VYsUeC`bObwGU(i*=Z z6TQX^tsJk{nI=xW_d#?JzkI$<8a)DSzH)7Z3az$>Mh`1Z$(&?(*42){8;z4XH)MR$ zA*yGpc9nK0H7=@4KIWpz*f&IzzW2>`win81IG81*t!K|Ff@8g?*h;}KDh2tgh zw8}0+O0*5r(ScbSpapn8j*Go&EjJCZJvjdZIP^ebZB%igDup@A}fF;nakt4hQJmm~Q{s4`jLfy=80o^tUkZE-i*93jN%py73)E{dCownjyh zZF<>U;Bst82%IUMgBEBq7;lGmSn8a#C5zdEn^bfs;i$N-FpuuPd9b{DqT8`I;Xai6 z*|SH3^lbM~(zKRS-G>oRvqh!v#Fy&x5nS$PiDo zXG$KTyypxyR#W1Rgk)R|JU(ztOs8ot3DEpAy&>nv|GMmok{#AO`S4(bKy!Fq0b z0=7hbA8LoKJ|KCcpJy&?JRKlZH$cTjg@C-Y{wZ|Z=b&nygXiO1T-CFTIs1U!`cg&>{9 zDJrNFQWeOF?cU{Rh0IQj^^Mjy@x?G^T>i1Bf~^2!+W6d&rt!poiIc4!MtdOD3HmwB zz_yMZlNcdPlZTxuVLOTs^j%FqaLW?=721YeW2S&+yp$M_3T-PZQU=%A zPDJfB(mMX$FMiFv6hX-@3V*~jl-UYvBr0_mXFPsMgtUR!5wcd_p?hJRn5qM}(U$6W zSgy-KN53dk)0$Iz-)b1w&;Iy%WPq0H9@#+Ph3UFZ4{4Ix`0B(CoryrDM0eLfxdId2 z3-&zTf$)o7>ROlADUTQ!;{n_$WaGT@s{B1~tB@>73`8ml&x5=G#ubS;kQl@^^4ae$ z_C}5;qt}5$cM3S2CND2R*BBsy3B4~F@}4(IvBvwo1Lp_m?`Ki((@##t2(H&^3?k&X zf071kW5kAigSuVxy>t@o=_sLOs68* z>dfDc$s3*1K{HiW_I5K|ofB+e?6Y!yNn#^u=Esf679+v}>Wx!+{oM$??hjGrs@b2) z@+XvnfbCIV`Gyx+4W7&33VyD5ATL^n2W{E=31CiK{G=)*7$N)e$#Ut#o|nDDkDkvG zG^@0yt$H4J2KQ>EDH1EfAcsgTln3NpV05RHGHGOFu`h@U^wuPvK_`Rv8-)LZoGMY= zm*XD~=)DpWyg5|NKi5 zt@Y?DLJnF)f}3TP&7fN@r3TJ6`_W#a4`F88Mny@%TnMuZY-V$kqyLc-;*xv+=fZ_t z0JQn~^m23PRDL=^$~K{G8+%<_awtADecH=U%{2eL9rF?Ee)@lJQd2Cxo+q1VHxLV z?Yg|*Uh*+6?K8)-)z{h;@3-9{9M=4H9UBK1{{1FBr>*2+;qKXjfDx^tezkwz>gh^4 zg8f##5Kk_-Rb{D}Wc&PS2Z{-gfCC8CoQFv|Nj1v~A965-Z4F_r4t?TGnKYnkd}cfL zHJM@O2p3!Yx`1t-R>S>cbaPL@*!$7ZE+gAAXLT;BzZO&96{kpc19o@UP~u|6oV#m^ zL79wTNZ#4uU~w%OL37pv$=!r+c0sy6z~8?60RRTTD}cD+epyG&9wY!KHUnGaZ@ zw=5z)y3?G?AP1QZj4w55dIUdizmNS2pXKO&21uh>q}cqno#Ei~7edM(d3O0_T*B0W z5wIT9oMwg=y~&rJ**uw8h*6%JX*8KmkfCE&G>hg287!b&L}2n*iNA$7pR+O3=z#v2 z0e!jF+Fee(Pb#x+ObEI^b9?<;#4!f?hyKp1=a4DpM5drP-pDK&*w+*!}j)(;}XNVhw6;2Cb-}{fq3CRRL&0oDEk$w zq6G2tufmi&q@h66DIq>Z1h8FRLVP-$VaCc%#xBtDSMq1PfMo&BC2%jUOz)qMg7v)# zeYOMnXqJeSNehCk5W!u>xSK2qYNm^r6xW@{)yQE+4hNo4u)o3Hy7zrDFuM&Bec=B4 zfP=!!@y!OAO|mcLNBO~CIsb>us6_&bV`7^h+VJUOS|qwF^p%aZv5=!TH4ldaJO0OI z#Q9dD`g6xgM6B?%kR#6QI+?*$e*08w=t$Aur?srN?q{lKibD&rlHjWQPDNv+l5+$0 zub|s3znhPtS_)O2-LO8_7HJ=@vN*-FWhYn|jFl4HcioPI*@E*^UE=zEMjEcMf2$oJ z>)Sp#8P#~jd}(OMWxTNaPPhsHSMla zOD$WemFg)tlW*A>!0!OCd^2X~U0tTRin0pD$rOC!=ww-HK0ya9vt+OKu$KnP^{~uF zW36WOHctOS6uVPT_eP#num99Bauez7We$?8W990rFV9X36*O&OF|+CDl4rK@mdAuc zTf$Il2U0={W~FRr3-lxO2+E02ha?kyw_+KPdso=?qjhKLEnBp=?TXvyk%-V>*ajur zu_B`fClvRQVU1GR)$xzax4R^f{P_1viCt_5#A_-FPu;!t(SMU?eNj&TUNz0G)+K=H z&4g9wkam>dTZ=1bd%W^k12)ekV={C*%-A#!UHPq+Kp|=RY2aoRUK4(0n-y38|Ax~4 z@5Q-^D21Ann>!rC;P4?sBLiwXbw zR5)6%bEp7ypO&%G#qDih?2kSFkc0an-;6CaL%{ka3kM`6Pe4z1$XJym;TZWqeX1?q zU_IO*th7|nt^~6bJT3vF*YV-0UU}QqM&wgsbT8}9KmyFnp`395T9;1*2forM)N*pI|(-pZg+6}HJ!f^q*e#UoVZ>C=G&*Z!WD#Ge5n>+;5a z4~-oz9s)(tpcSCO9@$k|&^jXaJ$bS|6^{P!Pukg04m>K&5I{ruIJ*CO{^w#lo>Q}e zHSO8kE<~Il-9?%Y@wIookJ&abH#7nSjS>s=6EnjObA8LNfCs5=S*W)vv?Mz}dhSY@ zt~X9U(q^L!Z!cPIN;C04@x?`4r+)KSLap%*qJQYw+VwPrVMTmf^08tWS)bG5TL53T zt^~}`*BbkI_@u%g$8ni0NjHnP*Yda@fmfb5%m~zLPgNnd>g^J~O}qKdR0Sgge13Lzf%uHHNoXlKMJ%|gSK`n$Q*srPK zF)lT$bMXzo7)Lye{`t-A;r^L7dSPyEBK-c*{YEacP}IZ_&ibs4g;cisITNxQkMD4>Yk9yNtF6NCk1`82p* zKgS*X(6EI5PQZ_>X`9b09#D%zbALHC(>W_bKLLgbW`nG63>PjXek@>5-Tpf^^ZoKa zou_!)&+6|>Rjs!feCb@LONnb&RTmX>g2D7~UVyPZ?P)xWeWKG;<`vZmh+qw1RA$o5 zbV+BHbZJ%w#5^=bC=k`7T{imD4+tqH!-KD1m{zYiC7=5?Rr+_?HSlv=wSdja>4aYs z*M|rDk@kbsI?eGHuE=);z7(^6#4VU(+4OrjPQRX#wOK?yDKtf`Gsjav?YV>pJ4F8y zc625IPA#_w!2qG2r@}(77uuJt==xW_1rx9zy z@r(x@3kevA0cG&NrRb|ct>}njqR11a=KVgki4aRs=kEy0owA_814S_AAA-F$U@yswST_Gx^=QvDH^dR*yFQ!b~&v@loX9?EHu6!Dkd+|9n}ONDm4 zh$Dt|(LBRS?mvLOzV~=<;YizLs~~=)np19vq89CtcE%+CJ~Q~K*U>|ol~pt2gLkXf z;InqxK*@;%x0d(@Uav$V8Oz7h&Tk!eIQ@O*QlP?@sKuHW=@%SzGv`K|D2o}3&I~qm z4CgRpNS&lVf$~^+p>_ci1Zz|zMw{a{zA$=8%2_q8y1j0AYBMxG$~`o$<5BoxA7#OV zb~kKU7f*F!7XsHUWU=8O+VIVGvRb5cxUvXZ+`lSDf{7kVTt0 z!n_=ACwHU{FrQQ=ry9n%xxOzfF$?^&xx`)0CS$VdV+W`Q+@7v6egP*ckQGqL%=R6` zkH&GsVCvY#dy)WaXGMva_hTXuxJW3dV=Sm7-HNjxTyxO|{x#LQ5+gPEPMGN7+Nn#N z-rA~;;lJD^eeen-->O0WDUV=5{Jqb(WU~BcgI3;deIPv*kXl$EjjGd+!sr7M<2mQd zZIN8t*q@&d+;u*@jg+qHnqKLEF0V50t&1v74qN<_Z)H!szg@Dx@c4D>5_$idH(DJ` zOG}eqk;uc~2m+D|RE@%3^qVH^|-@;_Q7EF{s=5IJt8!&U;SLeVC zc2g=Zt-Pul&tlPj5qf%fe!UaZ_GM5vuIK_SoT*n<<^T51O95lIN24ws$%5Q>?uCF_ zw0c@rmJGdJ=&1#f0WkitX&@l7k8N8i!DUAP(qT(wD@hPWNo|S$RxM=Ih!^mUY*=`u z+)y(cMgU62|4XLs5mhe%UN4zVdq^prSh64dNyibWQ`s-#rwhQJLML+gR{)?b+eO>U z+*y^Hqg}F6lP@$N3#tn~+mY^ve+&@V$cf>f;i;QnkVrIh5}`Asi}v^{JP{$p!^rU0 z>rvTn#b%xg{>2BXJ~{Q=gKG-6a6h81MC0kn`hu0`i0!^Wz0>ua)!_?|)0C#3X@aIS zH#cJVHg?%ND5Hxx7m(Qd=b6c-7ewww;CU0Cf4jT@Z+Zos-M;vJ8y)b?Q%wFcbQma3 z*OdLJk-=W-X`&o{f?n)}2$&1EF1MI33J9~HVI+wpk9eECBW2Uu5QX*LhW+Yws#Q~z zG)^AGK1o-Xbng2DN~3?4qYJIfPqP>&{A4mRz2i2oDGigT#GSjgX0+FL{p}tPg(fa`LZ}GM0&dxDR~<&M4pj(C-LjM>G+O*gMrj|b7Ps@|lU}CG;U=kO`H3Yr zD{I8a`t-l*MpUe4o##jktZuvKStaN#s!+wOk(-LBbtXZ!UN7iY-e7xkjij$z#co}* z_Hb;%RD&(>w8DPjb))lz!t~V4H^Jka&!rBGxA0AW+-1SxS*~m#zQe{cv$7Br{vdjVV zUG>Oumt==QD)9T>&5>zWdPdd4e_|G9+DlD4i*vicy)@fg+PcwJjoWq8jQ6PECs|eHC`exNdy7Om5Y4q;~EA2V%iZ%n{MBt=wJ;R^~K$H!z1(;;4R`T_}>m54< zwe?T@?}f zcjrU>*NUq17D5An*?i^OUAt=zc8lS+2JP#>o9T^Af89cKH^CN;>F zEst-;AUaAlATPg|JTXCd*orwxY!iJXF4;HYVdeLF+T-A?(P6u3=eJtYE^nx^q0O)u z*1>^?&*M#As)rS%kxSrYfVMZd-T|U|p}x}mdf2z5oU1}+hiZr1%y?Yvq*(p*yG&kH zsr~|H*lqcSMT8zrLUp#AEM>FVj(^NdgTEomr?KdnCI@}5@70})H+}iNN&cGqunH=y zd{P7%^GDeVmx_f8#PA1V1#PPIi@`)cLm_qi1NUx9pd*H|??#@6boiCm^a||$vYt=2 zUXLJ1fg06QZ>XczOk3RbCyJ)H%q1k>a6Jrm94 zc3<=O+{@B6ATQara^iPByOn%+e$Wt)6%0KgDEpS_^C#0~$TTgE5VXNZSbH5GIAZ2s zeVAP;Ac~G&8Or7J5!-&13f=5+?`}#FHx?0R4V3S^{gA1S4nJg@sm;os%e=M=oak#h zXZf&Lj1L0|eT;dw_rE$C{~!H1gBrm|lL$TxgeWy-<6b_2!T{gS^}>~gJC?SdKZe?G zp7efB>aSVRe-_N_(AIy-fUt(Z4ZOR}oGAlm#<&Ix8>KLjht{`|tE5;1VhE7y9RiCK zs0$Ztoy1_iFVQr>2E=;i!wu>Ha{aNhl=CLNU)5?oe4?o(5xwU3D&v|EG1T5rf#ku_ zuoE1FLv;46TSAZibXoWAnhQC;b)%BBBou1zo4sO>2>9_)#Z^e002ckoO{BGm@xBXT zH{X~Nr3`WFTS;%wG%2z|1xs;^5&W($sb^1rAj^MYPS4KvbJR#q^VKggww{cKmL?6R z_bB+<$T=t(8LN6uQ_5)1b(hmsw8g=eqvQ^_IM)xtq;Sf{U-k(%lqvhqN%r51Sbg9| zGL8Jr*1d-%4ZBkoi;HS1I4t1OFyLeU%Ew+kU7*6gAwPTG$@h>-8KAXK=1oqG(3q#w zXWjvyb_O9sABH6nXTWY=F6K9TYxXHxK&n@LWMBLc`8Z%zUFfFYMb3u(mZdEux{Y3o z*%0-GmL>ImJlYAG^y#!QR2H?^;PYP2^W!}M1`*g*CrdL(ERRb%4OU|_IlhAS2TrFO zkKM075LPs7d3OGM)mdh&F%){jB&9fk*Z*K+ymCCguLK&vZFZa^p3ABH5%1GeWONYR zBAK+v*W#QZFK1@A{y@LR=}{0mQecJf)vW~O>sA8BhcGn=x5^_1+(AKy?_TX zIjHMjZ&q0_M&k5~Ow`LcfS}39G62J!7#X8w06*`38%TkTm2%i{;f8i|`12bN*?8H< z#=vRI^el#**CJhPIbWZiT6TEeS4U<=pB`TzWJZ5qUuhXx-1IIcRA zQ``4k|yS<_ma|pz+CyrAZtaoJI1WVYn%!!pFBdM z_59_RTA8=8R?Ay;@1AIj$6DXcIvLM;-rU!CNp&gaAVSpdt!2`lbTT}t>BbO!X<_`t zGsv+9PlCh7qz+Wv$P4bw*})#zB#K{J3HmO<))PG%^c)j@ZRIYgC5f5)ic4CsivqTa z;5hsie9G12`4QMwspIa$Hb|F6;4<1k*=WPOTh$ED zASZ@HYK2UG*0khOq1-G&araaPkd(`)Sc)&D9BXs0b&-kOh3$N2v8|qy;n}5PK)Q0R zdL{_l=2t!Ny4rAO4Ug%!uF93qCRiFfqj!VpHm6=wsged$iugZ0ROf=yfI0*s3h73w;uH|PmIt8 zG0>PZO1mSiH_e$y!v?}b(A$ksu}0O>ux}Duy1)jjjgU%zWFydtpxpOh@r(W3=RsR! zu@&2ea74trKicA=p`iEpkng+D$M343rY(0fDK^%AwV3d$k{#)kRG9n@5ShC^s(q9c z|E?|h@_RgmPwBkeEM2*y^mwbvO3U?}T=a0i@qY*7^BjNEl`;PVW+x_z?0fh$gQM_H zGWOeZX_-_0u~DGGveO;Fi>uu>baG4#xa;b$lTA57hA@|y8rPG+*GOqFUK85#EnA!= zW#W;HPAZs+jqv=Ue^+{Q{@Qm4GWcf4?ZhhU-YL_RU%Um9El3I%QcDq|loC`=JUB&$ zFWW7Ha5Ct2uq@@VgpBDHue^B|IQ`NiHAbm6JW1(37OC;+FU-bN_voRUEY(<+@}7Px z+d)c@DJCtz1}x+MmKYgtXn52Ll~!>!#96cay^vLL+`h>YYwfclW@?WMzL6wfd_?^B z#THpLY6O&EN?Nn=CU zESwFGK{D)qH;(TqyA?xwDKW9_Qk?36eS^8dE%u5sLA6#5`0cj!O&?y7>XTC1+oayW zt*)FNJuWVAvTlv5Y)1F~?rlo97!jRmLfLOuzMrW*%InXvO{`f`JKVX>qyT;q<<+Ir7Xrs3ebOOuh_0C&oU`A z4#uYDvzL|Ssi{x#hvR!l*p?gU`iJ)F23!!mgC)G+|9u=7hS981&~`x*^rvj`Fg32{Rn(xp8z<3aohn~?H3 zU0D~MI}~~i1CSkm${`RTc1G|VD8mW}1z6=x7*EPyoi!7DQj1mj7aST$!gO2oT1hLM zKI@%5ToY4HS=C@v+F3ydRAKDqm%PaD6N#^)H|o??pCe?R%#!V(G~yA>%9T z5SB9hi~Pt51L4&WZrFMkI8Lx*G^*$U5j}r!hl&Ki%0`MhUVW0u-w(<5K@LfcZ^APZ z%=8|&&fFu}C7l4|nY9;Z_V)385nDf54k&Q*?HQ~*DShg`20QuW3al@=%xYPcZ;?rR zMRg$HQ-{sD*CaXz>x}!7Y9$-QbDnOrZy?aE{i)W)l35d-cEWGR6)^5I&RJ!Ww6-Ta zSJhOSmHe=nu*AM^2PKyp&0Ajdgz1`{ZYExa@qxY3t2+ewCwbL{M<#Ua8pyRtj_(Ba zY@YfDizx0zhSR>xI|CbcAk?n?t+a(CAix}$L_i+!jDrG_{pO^Vj_RfAbm-2TRs>6z z#Jx#Dm_m{Ir1>G!>1wvV-TPdGN#0N>f%_{Ee*riK@c?Wl#IACr3eq%ft}Vrm@ED`2 z)8?;E?LY#*W9Jdu(zx7n_4FUF5tSSR{zqMB{}{Xoxf(O|PT24FsSzgjx&hukhjbpi zD=6d1omcT=AhcYnS^{xVOpHWsFANh*q;CFM*R3)BW->@)(JR$scH5;V*ShZY*EHiN z(Wh6mtVeh!Oq?}b26cO(5ttEh)90_ zczcC_tCM2wrR}brDTGJ|#s_uRBK%;B4(`d8LQ7Rdd@X?bl5uPMRO7yshy^wk@SznzoX6f=B3^{h61^Be?P znbW>Tqo-pn&34(jp_cq)<@J26O3`+f-G2~kcDyWPm4P$98bn-rXIsqs{lRw@onK_6 zv&{!m&yZivCS8$z2v72Fb)zM%FH5Rj{;AX*4m5M>o(}2UCi_73*44`nYA-&q;T;jJ zO5*lZ_1Si7W;b4quqJm#YE;V^qPn_`sn zA63H(lwbU~gx*Lq^tW1cz#7!YHm&F!e^Bl_@K<)!U<NimeR5hW zRUl%_sNKIXz)Ahpj`xN*TVU}K>}I~n3yPAA%j;bfB^YH%oxm@@hj(Y{2uLC&Y~Vq@ zO}@A$Dc=my`{6ef-+EkK1X8Vj_6JF!bwQOeBkcV4G~h)^-yq_wuwuI+yQM=20_WB> z@rkiMWGAAp5lM`o#I2X_EiOr|%D)+U<*Cjkj9G>~lBx?1xxoYn|6V%3?3W6T632uD zOHmG2SM@KhJkflffwUKtFtrSZ`rrucJKOx60R_+HFp;9jz9z4IVhY$0{<;O>{XqK4 zW?-RmFC0M$Q&^~X;aL5gh_sIgsz3Kh2p#R@IpdY-`V`4r~ z?m5K<$o7d{9r{sL{ib%f|MZogLzIj~`rS)!z1zeYhwQqYQfXenizJwlqltP;Db!+m zWRbKfq2p`EEACSr$CIKv zblacc4Gs(rvCPz>8Cg){mU|XC6t&^dN6wRb4b48Z(yYBjnR&2#BMfcFtCGbcb@JmF zQ&ZaMiE!?&9(iPlxXFs_gt!Iv(fUDyP%)%OjYxoH4rQa$-Pwf~ zu&C|!wSo1vMu+|E)uHE0h^;hFqr{pTf$h1DicK_ZQ%a7n3eB2?>I*-gxM}~b{l4i~ za-{XY!rdRT@MY$IU%0b~^Xhc)g`4cD^uUAH_`>~W92&5_FyRJqz1hXApyojhpHi&ADcxYDSyPG3J<7+h$OzAKsCjtl@7CBt^qU` z&;`xueE%wzDGClFNIp?nSq^b*`I31t9HRHmtq|#6F5WPr>osx|EA_Es?QYGmmE(>p zKs29pfslkE5J%R>EAOWx)8(zVuta0<5F|*r)QeLJ^d=$L;U9Zk0;UFf4?hMD(x(HR zm(AhCsua#Eg|*jP=3-R%%rsU;6>Jv3$qIJv&x52k13@gY>`SRc&y7lo@Z9&G57ZG* z!U3wcTa54NQ(((d<$LdgXQcaUj?;oSzj!>WKtKMb{R~e}i522(iax}v1D7L@-iz-q zyx)}D^qYBFsosNCy4C;vu|o6{?C$yg$*m-)r26Kh44ARYh(bJ1{N+HOWe?9lsTPLDyonk?L_T|w)1~xl#rdD%Fv!@OwF<6rRd)iq^ zrV8ST;OyM%ueC=4oIr^Y@f+K`WD2meHDmqZm&7Kdu$R#gIqGt6cFh3;Z%-4Nb3$hW z)1xR$!$ao*mVZp6PZ#CxnYNA?f-b1Nfrs$ga66`ZV{ti&dW4CIR~$iA6}qTV&M_6@ zpu3DgrNQSjNCu^xz0IIix_V8hH%oWf6@coh@}D8dmx`Dvn4B!5n23`UAogJZD!HYk zwCUmg2zg;+x)>L}Sqn&szFl?tWRDL9`>)^`%FO!p!qsdUi#n46CrCuFOOpn`>|(!( z{6?&KO<`! z9{*j)K2{7Qw0U}fK;T_*_qnSHI~*Ij+f$#kfm?YhsTDOEf@cQ7_*`FC?>YGaVBnd# zF^!=(me0al+qC0V(r%idExJ-!`E7L|yz9%7lOEkUj79(gtj)b3Uo1G3O)`r;P=oHl!PsY^W< zh$J%9qqP+E>`xnHh3KPjJc4h;L0EI$10S^(75&4jVRKT|O0Eqq#|a$~-%iVKj;`$8 zWKq;kQ0c{$A;#~C3uCiPz0FMr1w22=Ls=%JZUdURWfSKQ;D3=gKA0F-vrkVpN7q4+zinO zXK8~o$yi1tTt~(&*4CcwMS7>xrfM)s_u*ZCn3-!@!{=yaIsCp__BNX=(`#qNW%#T!vaJ1$f+ zPZnY~GzilFrV~s3ubrp|Ikv5JceL?P_)y;Z#VX#}g2f@uByL~MhOVrCKz;?tb!oq! z&BC%u%{>B#{jq*8azN-@0df9U;szJOr;I#-B(+OtOam0w)*WDz{EmM*cIAMuKfbJx zeb5eQQ85ifSd#i1^l8z-%UHr%zJ{eh0x`-u2XH4WNRX2Gn|^?NB@seUkmCZV9J#HJ zB_U~-h!Z&vF)8$oZluxwiAlC@)6Ih6HP@Zm+Cl;l^bhV8Fb>aW*aLqOIvtJ)*mJKu z7p)9Rc%XJ!eANDLZID@t&{s^gvI=hn;ZA>WM6?Wpx8Z7*9wJ?Tl z@hi6BwR>;42=`xn(M@-vw${ghx~Fl3^&{jDg#TunL3n^+NoVZ^aL=F|v0^Kfz}JdG zJOIr#^g9ER=s@z6hiVnXAW*g_9~Qc0p#7cd9fWchZAjL*0t8Z#14x1OXYFKi_2)P$ z%C{oDX&u(lg(6G^pQ6N6rytny>baUAOAC(WYrk)V&5c`$`Ha`sK<)@UPH;Mcen78o zx(}|Jx+bezv%9CFI9a2Q*C(F8IMm>p6OY=;&Xe%_dF#Vots_;VJa+yrKtm#G1eAU4 z{F5bch6TtKF(fqhumfiEs3C=3&VvwDD8+iIr+P=o21Y`3o)5#n1a#VqN76)hqtYsi z7{HUt=F!5^Cv5~$y)c;f+vK1@WExPRlK{TkP5}%*eEl7NoYTYv9rULkIXAJCVPB!hYC;FkM8|xNmN~M68|gZPrLQ=Hj=9xJDR8 zK%gv~0s8!)^)=X2*#b65fTfZ>SE&U$hocC4g0JQw^YNB-hts`XL}?vG4ySvMh2oHL zs(c9NUlphuTVN@{=wBhs(ImQNLUsP#WsaJH+( z^yA+*Q2f#M+;D@Jn?53e`4Mb5P6_{GtUZo==U3~4HRNW9C_GNpp7(`AaM$=Ju@L8oa|KlJ<; zZIk;qDGcv|eOUh^19qLXNLV70mZ^ny?rnIN@?7S$C%O!t*_ey%x;FDnn^2z&*P8H5 zzD+!X`v{xF7~elU_+3^6ETySl;5M-Ew$0N({v-1@K&yU-iJZBsvse(w@L%{EXd}N- z@y%4SL(rfvEaYAm5#EvWNpl2#%@1RqK$5{A*6UU4`o7zP&wHeVGJ|CFlaSJEW!!O(g5MLx`PIMH@~31~(<3bq2;l9fsvSeqH>(8Q zB}uZL9_pX!b`@(Ve8uCHw|>$^5*ViL22R=mC%6$lH2arcj)8*g$EKEr1OIb?En=ej zKPK3Z-V@@rRYwbhvfW4{s^UJb;TF3GChPAS1q?SeM zA_5cVF*FCd6s^nu%EkbxjA3L4yo^@vGWmQ}B| zX6}vSx*dQpIyE3`!|DBY`3^LU4}n&&pOf@7PVth9>Z@aHqIwsdI(ea@S$coaLyLp|54e{^uW$Mn)Ls20j%+Cq@g+$ zd(8nYXLNP}ja&&G{pF7Ofjc6>S5w->ZYCf6k1^)C=oS@PnC#gM7hkobVeR4lS6}-E zF6SX0no!CSLr7BZ~WcaTjq7`mrDUXmBMo@ z46X*UUpTKvCx|C)uq#IGLFzRnx&0POWh`B`GkcR8CYga8>sLGo6W5Q?m-2dO%p@Ww z@HBM59~0GB=^#12@nR(D(rwm0(5PXvcjZxI+}7d>qH}#t&+BgFOiG7KcYccJe05YG z`ozKIg(B|F?bd=Ly~l-HZqR?=Hw#5GZO#84{MN*S-%B2N@Y_A)6|dfZP46ha=`DL^ z-ogkjAcWE(dGgS*3xKuf1vf5=O#x;-!6J^O>tO%U=)0vq`J5dWSH1~bR(7P&{B~64Ba$Y*5 zY~=oALPxeu8&psFDepuJSt-)@;lIAy$p!s>XMuJL0X2 z3{079y$gFe#_L7Jfe|0+5n{>=kMF{@vK|5hD2c{*$lg|?(%RC%2ByGMhQ30`9yaD9 z0`(-sdInIs5xS~EU>0{&#_-k_DL9sLs+~y9%R2atI9n-KOXqW`_39nB9(0D7ZtRrq zw!{%#=oCqS*nlJ>C`)E0M_@u~!|jumsat{)5CLpF+dZ68ppIGOt(WEVfjUsc|zKz!jit6^_)k_}&`pk~S_DgyN`(im)z z00vZ-8;Zd*d03N~@TdLZ;%Y^4Nxx!|l(juS zByZpEtmZiX<`_yg>%}f~Tys3VU6vaJXPx@`j-k?@n4OVck&5K^aQkp5738M_kQ$#e z386VZhr=<4L)yTb!8Ew+QG8>4ePMtYULmBXcS7yBj(g*7 zxqiLBc6x?_Z=;*NE-U!a*e1O+w`E8yO)O(dg6^2Hu74^qS;t*+61Q0RGR;M|!doQu zU3zvoBy{n~x9dN&w@6NlWX9ln7}D~=;X65R%WjDM`ug5x#^zSx-d15xVSi6gm+I^Q z=g0kxy3?~XkJBmcWlN7qOBG+;lDBmWxDx!QCct-Ne&JerIQaB>C+W~)d4nEhn{}eagoC82j-kti?9u&|mZ;iZUg>ev2lW_d?&qFnMxzBa_ z9$Pt)a-V_#>`$`Hfk{@u&q3s-7>>|zGNtsj@EEE{XHLDq$UrW`Eas)^Y$~4qew?ia zJbdFvFu-BOf$6eNFh)qC8C}WALE+9Ho$8%rLXYt&xSWdZ7oKSJlj{N-fRxG7{C^#q z;wRdba0fu=z}lCK{!`YueEYDnXJhC2)<^dQh%7I8%WK!Cladg76^HW?%DA{53ryjj zSJpPU6^DCtJ1mKaV_Lp1B30y|(|T|86}MORhd4 z@!zg(k7y0tD7)cJ58gQ(g6jfQFK{uyisBl1H*;RA51?wD>r1Kwn%jPMCS(UZ9>_hE z6gUD}%poViRSn3hviTjz<5uG|I*^aO?^-z7ss)z-q=C+2W#y?k7W@y7yWnOl*ax2z zrIZP(&H=%ugioHLA^H^G2+~N9l!Fgx$`dbqV5=^cQ4vJqwb$#F5*Swl`4$9*wDwCpxhZv*vDT@4$+ENifoN zDs@L@hGFJ@CY5)4@bv%$4A>0|wULDb0NWK=*Z_gf+KAkK4u(e2X7sC)4If_j|AVpf zj%NGu|9v86jp(w)ELA18B0^D$8l|WeS`@WDwG%{?7Oh>R_NqOL+OxH{+MC)!t;8NT zpYOT9bAI=pd+)h_<(!=S_de(S%=X-9#hU|3~W zZGA6cNSnbQQtu65?1u)dsJ=)rL5 zJR@Xs4Q0)4m&I`tu@-z1{~1Qu_ULF+wHh2|wAqR--quVjy#?d5*B>g-D9edgpZft@ z+mj0Jp4{e|SQ~XBxF^0f@v2OicNd<}uNGJD@I3#9)?1g#%@OFm-m*ALDsdh$%?n7n z@>&sk@mSEcFu)L0Om0G3$zmrt^frA=@xQ)kc*DY^@PIgXluq?DWIht2M;X3S5W)!l!VfT3i#pG5I3$p%;tuEw- zW(S}+4?V=V_d*Qd+;hFk*s;H7WOc9?bsZHK1(y81(H?jMi0_VjF5S>}&H#=8Vh(=_ zji_2(EM?R_Qteb1lF8TPinQJR2*_3zmi+i|!-#9eE#=HwCt}#WougO{G*scMxHXWa z*je);yB#+7J3$G)I>ilb70+eWJd+QFO+c%xJKv+C61Z?ixuCGQM*z$8t9v)r-YKIrjh z3GmN+Y&8E3%!Pbj?>f_)z%uG8T_|BTjL6;_7c`vN&aDLq2b28lmRbgmNr4x|U_G1; z98VIwru?4-oYeT@!O0TbvfNx#cOjrjyGZ(@3myXONQ!K zi-j(EcjHT5B`$RL9^!kiFG{-{w%L(+tBF|}o9C|TnCRZy{oyzr1*%4>X>q@!k+f_b zIFZD1@+y224%Z^-f|) z`dACS^~Ng^)v9(GEkB*jSYj22F)ACo`YC=)@;H{vfXn+i>y&6q?YwUMJ$qj!{ca{k zjr|o7*PE(o$;Ry`gwN#;*}w81Y-vO*VSl%sB$5mkSpu3y+Gsxe<-$ie$(u)SN@_G9 zYWa@W%-qr*-2yP}cFlITmHOnNd0l=!kOg$zly7ryLr}bq`zo35tY;C4) zG^m5`EqrQ_hk|4y2;GY$)-Mt9PSFFWWm~IDwJROtfV|c$pQ9V+nhU4eXD=63UxZ`N zHJLjfU-K5*y{fVv8IPYZU{KU{gS;Co0?W}wrs3os%<1<)0NS&Y#5euHRiD`@{cFxW z>1NbT93Qmb`z^v^A~|d!m)9$e{)~5L>;4&mmihTJ zOsJY0nM4j%J8M3px@f+h@)x|Kbr|~k_%-0mNwrXw_>7KmOHIgTgMePCi^=fc3*;bWVzK1#sMV=T+7q(?_(Y7hPs*lU$Z;^|FE8}s zMNfM2TMc4E$*qu0Nkt2CuVL7I8ZW8TT0+a;VLV5 z-%Zx$hHNlu+aSqvtu7OM@ppSRfh0H+dX~s9rnGBmOcO*-NhuQbPII?(V;CdTkgK#S zDNR3Z#YJtEuDNFI7i%Tv3`vr}{q`WlqUWpE_6_s~XY!FXW;(c?Se!&`Z{2;jFYVWH zsVRvI?i$x-RdKUdS&Q+^^LpG-Z zZC0)vZEg86L&-wBow5qv;*j+yKTT_J#o&Gi-QI#!*ZPdj5xZYwu#i_mV)MFgmE@`> zYPwi6cWwDjBJO>sDEPP7_&FBVoh6<&6T?^qn$g0mF;r0#9M~#7=1f!1PK?GTW_pk> zRSzqQ2(cb*M|->6=*NJmebW9P-98^BKScOp=6*qLFByP661H{-)KUS>v{!Eba}yFbDZf4NTfhA#(|y*j~>qN}H5J zZSnS?HJyuz=A{Cu#t$qtoBnF^N_Q){tN(XZ{x6wsamWeS*H2`iyi6?a6Z}MUY;Erz zeX%&Fe$Jd^1_mG(4OLl?fa$v-ffUui*U{KV4MNNE5&Tj6w;LPMhd|Re6$A$SWA8q; zUt(umeA4ok)baCr7;2B2ej03NMMGF$5(Ixh*7SlFGSKLAC4e*{f&eHFWh^Iozve-e z&X}qX4#tR-8-3=2hCTsvlI?cFEcrOGjfy0D`h$5Clv+$2?yH1fKb})y*4}cuud%na zwk~p>?32(7F!L*nzDXU2`rVJjZQM*{v#*uixJ#gUeECX%R7-JV=z7#KTPO7EkLanG zbuM3HHR`ggi+>P@Uw-l_+6A}~b4-ua-4L==boh6BFmpO&;g1aANaG*zpEDlVyP7DD zNe(g!*H)}|*U;5!-+7WUlc<+&qSXrJv+H%BykAbU4bsWfFc`>9|K`x6W1ksnX@)(< zb}}0cT5GWPNif{ik`+p1>?%()W_>#RxZ;YzaGR;=@6KGDm;U7gfD_8Nsj)FmiuB{v-|7V|A1~<< zFZ3pRK*sUNz?JqrW{!PI7_wW(589hl4v0B82+K7zHW~v-pc3Hc7g_FmVT^gom)jTl zB_F)?ey_R&bc$M z+pA%*E;=y9c!}TM{ERnkCPe<;y_!EB+4bM0*rf13Q9GD?fUcW=^`#bGN^~g_AB5aL z`|J^w`xsHAQEY2gt-jx5G-*yN!rtLYEon0}B=NX0$ed@zW3aeZm8GkF%Y|HNM77c0 zZqyg#ovl{GsHJ90snp=Eh^uZQ}-hQ*A$*A!Q!hgEgtc5F0#PQ*I9HaI#JC zO60@3qZk(XV?JPpxIe#J3T=wIUAsBxn5|!o^bOHX5j8;E9OZXTe-?APCMS4eu%oeV z0nKn5at`>QwDH4H&-`g&WA_g?47<`X34evpi{ir)sX2XNdyYjd`M+bNK?BDYB*Vg> z*Yq64w>ejRr86t?;EbR-mvqo3FXq*s$dr~hd#~C~PeU7uQ>ZY-@5VUNxsJceGsjCJ z=~u4s&mhr*gXciu#d!}cM3NDy$lqf!F&He~S3ZERiY(&Mi|YUYg_y>zi*3Bh@h@8z z3ZJaB+4;%X+!HLx^*qQYWq@o5LPZ%aKO$6YP5MlnW|0NME&;labaOM6TH#$$HR4eW zDK7^9U5J!X@I$48?@QTO(T&8wgfu_@v`ous+}UyW^p3Bp+Rbr8n!~ZxTLX#ig3yh? ztfr2-JDkq^PV-aGprm`2e;;ZwW_=R=VV88EdO4M))27Vvads}QapmGWU0o@}^P615 zOP8(@7z%ge!uJlR-4zx6@l2w!5y07z4N+$Fhev(NW{MZ4b-cRz*TDrITfM#P&OJ0d zH)lRI(}*`^y{_u0^;^oZu#7DIl1x=h>=tbD^T~`oDZSiOfJ|5oNVn+v43It~59!13 zomrcP3MDf=yXx<04*VWBM6&p2_Vsz@Lz8K$Nzp9<(8~GT!sQ%58I&jg=urp?pato) z3TD6SKS3dWx!>$WLz9&PCwH!G#{Fqhu8K#BS`0=X_)Q6Oa|#`MrCxO{?nf`Q2Cly?igE!RnrBEg2*gVmpYj{yj17`tUaTM8pSzatecv)0zHRs(IyKM%sH@CM0Dv2 z@9wD2hg15s?BU71&W4^QzWNBG#>QnXegZjE$&grW%jwvtv5BcvUOOMl2#oG{Xz{|9W z;HP=Zv!@`+8DLBPQqAMb$-s#Co2l_Bu-3B_Y+^_Ly4kw2kG@@|GUWZt)6k7y9&0u! zx}Nj+lB`r&d`GS7!m0spIETlwz> zmESD@{R-ZDoGn9L1HLaE?6$dP9dxe6ykWUEGY!5e42_eB7!=1;PB}CbZ&ebp(L6tK z_67l`9#_EcIAd2asU{oa8ubr$kM_Qc$Be)tTw`CrY2(^lU4ziTdzsJT2}h?-j` z)L+>BujUd6kBMy$0rM+M?28(Zrtka66=pDe`Ocp0t;1iQ2#F94u-dP})UvxlH1EeX zg#t$FNK60?dg>dWx7te}t;!u|I+l8ea zAjR7+p@jN7Lo|_J178vLq*n4f?l$jN%!qb2)%l5ZmFZ_vlii-p4o+2&0 z30L5i03f4q^VvP`>ttGjY;p9RHWRt1+?=8;CkD!5gCRNW_DvQ$9%urPwI3Cf<1f!- zx%w`d+??wThA)=|m+V@Ly8KeFc72gKH)2cX0akQPRdL+cv%%oVOWa+Lb@=^%< zZBW*-?(J8N#UCx!PsT_xa_<~}`p`~Do~SZgFk;(EyMK!RTu}J2=O{ffIESOQEPJHU zk+0L!uz%>_jLDQORXz@}mA%f1xUr7)1nAYc{=?_mSLJnQvE$->O!Oj|`MvH(#D2IN z-zR=NmQu@`FX2v&7$@^Y3`0pAOS=W}DeU3Emp1hCyW?arA0Z}Z|BRnw4)E`z9ER?3 zJ`bmka`C@LRF;;OX1n;GCvEOjL%OWCT+eK;C#!#72G=JTaz4BK8$deu;(Wx-)J2 z)ZZJ6eZjPTNYQ59I$ld5M7rDoWw?=@olLW4CeNRD#<~ISo_Hk!iIyh6Ig;-U-6UB{ z4{jW!D2_4`4pSOJ21&Ws z>KxI~Ex|OZ$sTq-?<|d53_mlob#$N^|LJZ@+UGPlK%iUG#n2bp(T3{A2V*M zsK6Rdc#$MalLi3*+OAN|<~}l3PowmzbtvNPcE3CNOfR*}CWEvIlKdJ}Es8!PFu=cz zbkcq5mDS&PXG0s+Rsc_?wQ|t&3(= z>$*qBB`x=7HaT`K)Hhd-J|v+7Qc9`EYF{~B5w7=+1hV72ivq6yE}Xu(m>IW}4^&Rk zOWV~vX!f5Io$2@8ZEFs^bg@1lR~71{psD))QpEVl4^Sov<>lqBze3~n)%j-k7k=RO z;r#oKo2F~TgqX|TEfE{$XVm_IrO8UWuyjE{s0ygboE)YZ)Uh0ea_k*=NgfzY{G?0i zbiWZPtJ4#|Z~^cJ{*y&J#9D3)89^oM32)JSB;{3?coY^ZHU3Q)dVI@_m1@m2r!QRW zOquRL1vX65M%pkS%R;#$x)|&$>S8`x69F`_@;wSA04MB=5^$v}1xEVc?|GLz3+W-p@`<=Ux4n2W@gkWyE&H zba#JbL#_xLXD9{i(vsqWSj~2ilOZ$|=E}me9lIKwMG}L2Be-j93#7e$RDEfUqqvKvQ*_(|KFwlDne-zVh1TmVF?( zNl>Q`{5+|V4C+0is=@Bly`C)ZUzA2zT6i&ES{n}L9>^N7ZGP4*PJV%FJs8x?@KVrA z3y9G%ul{$!TYWToQ{E!?-mdF*m-vU*{n4EPR~rnbuLpOlP7&Zz@Pq)2!BqH=)2YCr zK-yfM0L$}ATHo>TykSv#w{r46X2_*sU)7iQ{p_Sf$<0YIpVnOPcN$0`8`g8e6g#Yj z!h5txR4SVyo<-+M=x$bKEH9&(MXuB&X1@<$*-d33J<<^Ru6O@jBhG`?2#I`vES0q z6>ZKzRZC`%-kjaFI4woX8&&$dWRp9eEksxAQ56sU9}VPxN7X$Od&`TbWn@athPZ>C zpOuOm#&L~M&PtBiCl6x0H}ZqS_nEN4wJ75%-t=eQ=#puyk9RfcPzIK2Ur9*e;a%Ym zbT^^-6Uy$8X<$vr`bSiH9q$lns>r48-N<2B8JYLbK%4rtzbN+k~t@suTsvxZqE78C0@fnmc3=BY! zA{HNEEvi;-Ax;jGhl4%LOO*%LV$b`pJ~SfCwLca;EgCHE)O+~U`1aeR5_)NSg%vkt zNZ`AI?iaLoeFes2k)$bCdxyKzz!-MLxHn~Oby~-?D8XRERb&G~FAgagzD~I=@N+|2 zS?E?JRj zjNV>$$F=-cT%8wqO(o|HS*>jm#}Vry?}bb}Cx!EC&gv2F0@1Mt&Z7@Mow zmjOJh%<++?^M1#;x*Th8ss9D`x^^$9uJ#9?kI{=iurhrwkJp%wL z$V!nX+91_DMA&$ExsuC~6Nx^0H^c@ZiS36j0Z9(H=rL*y6P|S!MJFPS-dEfnAJ?Z% zd62n8N0}1SSY01I@3V_ry6gD_VyJL^@fn|`a3SKi>jmj%#k=IDQ35WrIQ-K+8z$fW zWeIn{oplu8IZJB`sE7dAe-!iY8=!`4be?;VXwZEt{l$0?QFv$QHF^Ih&hhtjq`9^3 zmlme3(7cguO?;n$tT}*Eh_b$G=@ooyoKw%uJeArfype*U=$-rts!dXOy8WTgep+_Q zrfHXfi(qenfw17(Du@(4R}&-AQn_Iw`n3=|_w_#Jj}eKITl`e-tb+l}%Efg3TS94i zW2@=iWej@xNyE_{j5#9tFo2W`2R{t;%X{eYO3hfJF>kP9^+|nEcuQU5qxG{Bj9>9` zV6G0@hE!+R{POqH7->gXfkUT5P?@Sh!MQrnNJ^@j)G&JP7CnoIBqE;KC5Yk;VYA)O z7S8DXehn_#z*V?#$T(;t?S9DO>NO4#Zkcno6>xvs*!1~5CUxxNYv%ntHqRZcm>T0jw-&fWl<5gl9%GY-|0ygHc z7D_TB!8a$dBVVxg*Cj3EF*e36%b%k$H~-CEi>A@)NbFXO#xb7UL|K|!KRdO|%tewj znYbxYcu!66{x)@ykA=|vX4HWMhb6I^COYUS?lu7yyxJ`)WSgJ5z{6_&tq_C4}(U$w$ zg~*s&HJ(;UWull9fI{*P6epm6XP3R6zB+$T41!+`4zTwMeY(O z;1}8lR%C_*hQ@}<9jHWN4G)jLzOp4yn6`R<>x(A#ubOgny)sAo9=`Wt?gyba$o^qP zAQC9bIXTLI4hFzU4|xYCH>h-(>h6`3uW2UP5ZE?4ACXo+dF;QawKrR1u{OPNK)fhU z26)M{yd4J%XmUzkj21l2uN9Rr7$PWYegbmIPb6qaAUp=AQ zunQaz^LEKHJ*p10$%-VXZGHc0p>NGbl5gXwVKE-yDj)AwNwcP(<19XiLLx3RAk?@H+FT$vbsNjz=PNX+q-`FNqC+hFSi+|eww?^+K2I5S-}YP2 zKQ<0;EmT-FOFW2rzI(?wgf4zW;Pwy$>#ooSpHnTiGb1(RFWdTXosNKJBOPRtX&bmc zYdbd~-gA+Jp``r|*;>Z#5TvlZvA*&@f0a+i>mH%fbsXt%5n*N&dz4yRV3lp)g5pMw zhaJmAx$#Fao96EnIIgR?7l4Gug-IQi4pq;UCkykXO-Hr<##K#5gjSyG_zW=42Kms( zoT1|t>`2OI>Slr+PfPIC_`8(O%vGe=q^H!r073KI3=&f+FnXS(rf!=1t~Rv}Oo%9< zZW@#1Jcxs>y^_VI)XnGPaQ2NUuGB$QhR(LAk?V+t6cf8_=l^x*`d{uYaS1!24qDC? z6rw-#Fo`$9X8)@J+iJ~6jF~aP&S<91;9OXCy zF`BvwQ|awpK!^HTaJJR@P=tYqK%-AlgbuYP?IYd$bOJ%)puw>bKh%+J%xc$MQ9m8c(E+!^jV^{AmJ`N@4qp_zLlie)@kwtsX@aDl7%Inm z>Zu70wG<7)f`>}4tT`nr;)Si8z4f{iMS}BXD){e2IVL_Ru)Qj?*aDtzah1N#>3=W) z-qkY7H`kP#nUJtCX@o!v3x14jyuQg3x+x*|_VCQ;&hw8{fI?j08&SDAnYn|PZY-T+ z6%KIc#2)YPoCg;9x|{a|`HqeSJ)j{;*2eA-vLx1Sscz!3?aiuHq;QoEV|?kf5jp3V z-_=cXV)U|uBGW3tm+gAx(woXxN{cEzz25H`^2!(1$%GYF>F9&LIvpswkB4{mcp9yA zr3V2>hu0Hj;d;h#()yTwZ>zZ>&Aqz;xEMur!wJZ{i|~tM1mMWKFyg_DK=ptgB3z)t z1FO;Qf;$Vp1UK^$U!l1!=;b;5j*FkTlZ(^0dJ=AhSTFtgG${2ylr?gjEM=rb?KBmz z-0n@RUIYcOF=N3Pz(801?-1-WN)!xA|d9bM`-b(rW!X*O8*07Ye26&y32`D2hx)=-)NI@Y zcto42o0OuqXut8TFS>9d&uHH{mEZO)5!~}a(o=QWI6VjW!!(9Qr7bpw4EbI zqkI0RvaUP_Eaa^Y)h%zS^#0f}BDXGYD5P@7C3JEut+<$dj`fqF-#G{wfw%LL!%hcGt1DH)nfs@j~LLAo+o2Y6NCmJ72OQb61)ddG=u4}h|plb zb!FkxC%sGwA|vH8-$-fltsa3U zMjLmig4m)YM;X)MKr*563f`LwSCd{X=75>Kvap8Z-373v2*AmDC9A3C!eAW?C+!8@ zr?F%?dx9-d3s$kVG_(E|e$}ORKfrouEO0d!y1&2Nd6T&p5g(lfu&`THPpuV!lz)%! zYN;8&>1I_bYT>hz6WJL=;kT&fe756F9yB1A2ra>hxWu7r!*&#!3s zyDX!tBXL+3ndrUWOpf<>ta~AVtf|}fGFXTy5!jW@HQGOzEKT0>Ua<`~=0Nxle*Qic*w){( z{OIV5yfdf7c^aYGcU;K6yA(m}RJ!bG${ZjL%3ybkHmGIUt`qBtWjdN+L+5_ygIKeZI_sEQevkJXMaClHMDH(iA_Nm z?RpN5xxK56opE!~u)2PVaJ*Y})8`5MCD;OzgAIl*qXKAi6dWu#W~@|u+5@kD2=8(B zY04Yvb*MyYI}MiAs&v@++J$Tk5BtqB_~KvjFWOo}X6z%&oF94#P#`O8dEB4b@^E%Daq+4p zQ!>3>E#COAfvYW4srUadaKHV}rKzk?Z(;9mqJisibX9uYo}i)7(4ol=wE?<5qz!1f zRltany*qUJssci_M)7m$yUvTT{Lsp!$NT_kdC?NY*;;TXY?g0t4_b!_RemliJ+pGNuB5p(#Ukq?-<))4^@iqGKJ@1!Czj(JT;fU+J5O2@%1;J-D1h6- z+f3m{nX|eFRvxaJ7k=reW%Ldo^uPzHV3UtC%$tbN#loNMj|2{mx(F(Br+WZN@?z3BF{h?an`0(?Icqk*-_P z2Tkb5%>~$yq@;to2b`H*q-&EJE{(O&z2zoYQV&loKpk)ZLGOh7e(wfpvTgH0(t&74 z!N_1aV8*IP+`ACbyIl0Z)IZFqN3t3m{uj&m{XzIsezmhzl17ov^UVVdetG{>7@VHP z+?|XYb}K}=>dDJ*ooPgUsRBfR8ot4!bJzGcj6jt}DuNMD{6q5+Ds! zIpmJF@U`?~reM7V(9Z4~6O?pGv(M(#+aq!7=d`F^{VjN4D2gIw#~8NP{BavwKU2N_ zwD2MoAtTa{qV)Wsv9n^L<#w~BX8rA_92w{-d8dj-Qi+O*JGRBfTOyr?UZ~oT5HK z-2b~fuhj`9Etm67Xd?8xWGl}tA7xX(h0T8ZNzW$@k`}<>s8r9YJ&4fmZh0^i99Kep zQuZ)lC@p6S=bQ~qgHSEbf&mAC!Ct?XFE&HbkDq8v)_YlCTGs8&7u#$PE*gLeLdUu& z8wW=hmk(MBuv=xuj)xR?r$ASqTIM6+ez8r514Ifn*m{EQ7oSU4Ra0!ZmDAV5@gr4Y z0sdXInc=J*FU?7`g+1&*+(gJzvjCKQ-K9!os^8b>mKB0S~8lQtn!2 z$}3Wcm>i1P^-e&%iQS2!QGpv`9t1_!R!-T6aGOHK3%^K9=$T6a|z*cyo| zuKx3jQSqOmz;*M8&=AmEeFBA|n!CCRyd#Ttk;ye3ycP8UDHdTL^`U`h`6Xkj^koQO zis-oagpl$S(H%+V^T|A|m+}pjPFqtU56GZw5_~D*a&Zg&$qASOgD#XsmZMVLtu2 zW1xJlPxHvfhj{+4k-Z-C&eB5XF{dVLV)qoFztf~njQwL92h~$@=UbO2^rtUdZ#a>j zz50C6++8tWi)NiVpQE-{+LJW+ct_gOdgFx{-@uO#0OA~d%wa>ley zd*^RZl21CO%D@&%pDm}!0 zzX7&xQ?>YZxBIJ{yKcXlY#e9&c3+(#6}a_Be79ihaX2yERL1`-IuZUIh1IoYIzmaf zUa>QxIHq__t0>PkcuvTrOr)JLP&)0*4&ZZ$ybQS?LmG4cJ?Z=3rcOgp=@;@2owvmQ zdAQ1lrNWxjL8)U?6wUkC97xxG)NOzS*c7QM^E+_RyIGXv;c^tmCy?u~{`1Q;4l(6s z-aB`T+o%Ji#0=HI1%)LE!B+*ZlLr%Ksbu4jk5W%p(K#X#b;ty4lJMNg|Na)C%gf52Pw+e|J&9bGoD&-}*cQBAm(0xJcB>BihBCg* z>UL0;jPMR=gg=E>)O~ye%E%4f`{^^IbeVAtJ7x5v8fh!7-F^QF9VaiZbCTJl-jrF} zQywu@74NhePgpgZE}# zV>rL5HGuQi=c$W7U$L03XQb&hS?Clx%d}{OuXDDG@1a(Jvge50Zo|FOUayfl`mqZY zXQO$83X&*t*1pfP9^ssv67%U;fKqSsgNet{mTz7%;|Cm}tNWEBGG8F6xjGz|k1ktx zFI6N+6nh1iLjhdguRb2E4u`e~Tin}}fKCaCuhNN!2s>;!h?zP*S=8Wl! ztWAfWt+*w0j{9lMe%8Xx`X)Kj)%_Oez2LsL+hV6;eu!N;t9gaaai6}+G=-w{X}uce zY- z3^QuG!;*7w_d)WpPJ3EK?6Jc(nR`xESvW{>$XmZ3(FO7rf?T#HG-Nri;{5I-)ul8c zU&xr?93-)=Zk2%6n8O!}8wUNS{lPBTR%0otz02v=j8*|HMx+w4Fx$>erPOWgz0OZ- zZhVn{-{YQ`MZ@=IebLiYr9&wtaF*v5Fgq`g>rYzbW=&qlXw?3}BZB1M)rQ$os0TY$ zLlsZDB!?}HRrpij@tzCD`9jW89kA~akY`gpp#9qvyg*Y%io5vexPHh;65adzVfVmV zq&BMj9^iNps^deVvD?FXy_cCbj?Yjva_A0bwmtB?Je|2ts2(WRa5*EZa-y*(rhg1f zGoDW>91ET@a+RlaNwJuc*)f$drR#CGJl6v}R~c_6wP5yUtg0lLx74HpyaNcmiv(gA z=<%H#{%kE44V<92BzZkGDu;Q235&~=v_P3h*OP`TnF=-sn4&y>F-FBw@?Xs98_1v4 zE6jZaiXp~w=Aj<%_<&e?PSeyUU52LQBQ4?spUz~`8P_@*_MK_IhEulCib%M+l^%Dn zx~QlecMZZ8)xIhCZbZ`3K!Ux?2Fp>;N~sUhS>I2D%Wf)@qb0$DE zbe^$D{v5#KzVpL|Z7`q#gd7arhpopzOmM}|w01pnbBNa_Ehhw#$avKIk=e*g(E*t+ zBU`1LPx1%8TtPZ_^iy6?qKr^9U{#-JY39ua)QH3nQ>l@!I_fjArN@Hyi%SGai)k(W zwYk3prrfjYlz?7@zujgp`jby|PXy8*`1;=TTFd7q8*81~`TQAs9*bOoO^vB;WzEXV zKYb@`Uu0c98`S#KDqf?%g()kNud8e6r$QZR4uw4)*PojT>vi1wIbr+d@aZ>4^Ew5q zvm)2|&@~GGj);8^3o{h^ktF8MyvNj6HRdgw>apYTnx-umA`RO2o2<-LHMv_E1SjBh zX0asZ$i#s=IqR(;-AGWFpt6uQHags|(Uu4ID*4HaLK=smKsw-U zlxAezJ$}sXn%f5;=d-QnjT%Urn5a(_iv|W!$`&LQ<(91qk#Aq?MPVA!Yse{!6FSO_ z(_wulF5RWkmd`f(loaj0o3l~&_ulGVdj3ZLF`^@mE5EMo*U3Alfv()xj*lF^K;BjC zO*=#Rf;{VC-A{)3_aP*57W?_1^vw>x>Ki0(aUaHwwtxP_5}cpuIr{>M<_f&cx3g`} zw@$Stk@ktoz)kz0)>QoQb2-hL#nBs(>ucLyiVGw4ijB|2A++DmmM|fKMnvYAKhkQ< z`#)s|cvKawF+snMr)~VR5W;#aI)f??L0of!p(HKTGIyPjhM4FHp6;ENRy)eHT*8qgPOKGgWcO#ox(-b7KcTQ19~K`VHol zcj%0%0S8={lIzj#q!K)6YRC+r=%QkFOC$kj_?5IjSTH92qdJzdG5yYGYGmO~!zlHb z+NMwQ;U#|c3#joW+YL(ZR0Lb<2Q)wiy}#1y?#`Va0g#&ee7Dhko7%c-Fw>uJS~=jB zI44qq#B!k54Oy!7f&X-??wfU5d%gBA4RGl%CwMqwSPU**+a*0p1XjH@TB*{sM#F+s#q%(@At zWpEfw_WgZ^V^+LV`2hTOrJUIxF7E&lzh;qUP(=Ki8(dqAL4955*;-ly?5lUpF~lPrk(p_yJ(Zw*<^5WsR**JfC{HqesSY3vdH-X>*{BF1DWuuSJ=2Hlc;(%swHbJ_D zW?TTDNyF)hxuxKb&);5C?yh7w0?vWB*Wt{OQ_n<4ENiL(-N>v|zy~#jZ-Adyus3w^YS>jBsxl ze32rZ_MaMg-=7qg;s*el4oxvjJH2t>)i|}R)icbE_{e3J>p z&g%VUk=^PhZ6;oJXb{&o3p>_TBy=vw2Yiby$f{? zev=pJUUR$-PwtwgU($3}MEvEdwOyZ2iJTgS9%Ov(6Pz&K4O{-M#30NU6TA;I((_hU zgKrd!S`8Mu)t^fa*Y?}1>yJOT*a{PS9CN_Geh+*8s9(r?@rzYDi$C5=603e#kAt?<4=9 zD1W-;S(yb)RX|OqsdEpmLcVKsg58;~Najf6-==|l5WuGEoeeK|2Ej6t6;8_s@RLut zQH#k_+T4tOW&B->70*&-JMa_&@GLxmg0@Qu6VWtjwZflBfm?*H1+d)%uV4m7JiwgjK9dJ2f?a$c!YXMmkS4l?Oq1Y5*n?{ zO{(}(;t%ibit-VPX1={xdt>kB(Ab2KibN4lX0_C|WOJQOD~pUn)c^jlOJl0euxM0p zN33t?3((YwabrB}A==m33fBrlKWM98fTS;XyG#o{8gBnzZcZy%yu&3#(8 z>5a^P14G$V3!xYW4xyMKqZrzWCtM42$+szng2d#_fvOW(jOX%{^R2L6*Bg?+2k+AtA z_jmy@oth$8EJp=Q}+wiW}KB+Y=CK@+l>CN3__ctZn3q z-+Q*7$tw9gjX>*JGc3OXGB_@B{3+01__*9wqh%-XN^x1kbDwO*^#QX0xP9X(;58;K znf(ZKX4{wxDqq2FA*=K5ir6_~9!>!q4DuZEc~<0&V9gSwulYRsH>B+sQI;rQ_uRH?kR~c zjk@b_IdHK6B0#x4=DDK#z*|Gaiw73jG_{H^Z-GIhoX1UEgVY3okV6O^#+cTZOVQa| zZCoUzDf7%3>&91>Hn9Kn;!n0;UX=W=sqyZ`$s4}Z>5Opp6sse#<2di^f#$cFjSobG zeVmLj4mqB(X8Iff60sbc=n5WmA5TQtrfnM4C-lN zm1=qScMNC^L*bEi&DS3t|K@Z6*`Vi`*5N-w)GydM1hz=Z3S<-q8|99+KRC|L&&_>W z;I!7y#V^%gN0T=E=h)`X~h;!6GV5;rYfaREDB1$!6XQ~qu|Zs z2vQt7VYHi+?PEE*DPm6^$GoT_uPBEx1*9q5qCXqaQP8sR-G74dlBp(_uZ4;|N(9>+ z2zNFbl2v9#h)J~p1TjYBP_mvW4&ms&s(FfW~Y8?V(?9SCQdb|>pv~UkLBYzyM zW*4vwOVcAi2y>C)*1yasrWuzcmiU}~{|Nc~Jv8S7#bG90%FRC}d7~E@lJfZ=_b$gW zG2ET!9CuvVNlu=s&~f81P5s!>Wqk`(J1T@vU^erV8gvzujZsfhWP$CaEz)S48>(1}G&VBB4KhJZW z^ZW}rNj~52=lgoU-iW#4^vgf+g{iUTS~1!g+-DN&R-{7qA6&ASB3{X2`@0b1ms)38 zz~6!I@#Bc5=e~V+qM*Wt&+o7uTLGjo8N)&AbXOPN%YTY}HVn}utkJ-#{vzV90Ky{b z3J(iMXdV%}kkeLy^Lp;)^TD&$p-<2PjxWalDl33*cn3j7_MIn%AdMiN=8YWUfcGf? zk#?&h&F-nYy8RFJ+236BaMoCSCK>%!K|mJ~G{iiu2xmiN0G^74T`dh>x$|XYhypT8 zsdWXxgz!7AjXI6tV8FQ<+dJQZ)1X{;vVCFXP&yw7kjMA>k0xFlc)X|taVev8Bh(r+7=+S9+!`NqT7q zJt_Y7L+kNS=Fl^zFiTa<*X?zIx)(u(zS`>^K2@m_(PD`+);dPs zprLUI%P+linaK}{qztH@JcrSEsKyb52xS-j(*C9;u4VUYu5x$h;`a-mBdGmxp3!`L z#-yAOZorq_Iet1xd_Wm$PhfrofjJK^yfprJ%s{FMdpGegGTnkf`Lrds#c-}2ShDZW z{m$F`l7{wp`l1^)A0IkLG}b%Bh%0;h*yZZ50x?{k4j|;nI}K_ex3nN<$@M3g3UuH- z`?p;gBc9R1fzSe2f+zoCr%~e(A$EBF2o7O+hJeofRDY~E>DvXbD9;Qb`^r0@aSEQW`DRZ{^~j*N!UYspZNkZ z!g#iTg^e;Ow>ZKMZ6a`>mOB-!hvaECBs!}GxLr&WV4a`fZ9vj)*AKorQ%lR2&6M1h zP120{tSuxhFu`Eb0d1WXe^332_h5pMmRscB%_fo8I9A>5KavIKr!)8ye)CCy!PlFZ zy?5-1K%-q0)f$=@$^aEW{JuOp9o@xz1pKJ&1TOwLVQ`^8CQfY)6C*bw+ut4xym9wW z+<)wU*v$j{Li~z?eIUs9<=gpPr2kk_h$W)XrWC05B(n3V+B(qaPBax1ZL1z|2sp-9 zYlLnOC3_>#L<3@hP`j>=8Q_XgN@moP>DxXOAP^=>vXyyarmzApc^_Ck zI53l>zYI0&B6krzZfZ_Hy$8$|lUj2Wxo-tMe>pHI7@qj4M04($$f;-RAtV%C8`~l~ zLAft!U0$s+82u!}PMCHW<>{E#Qn_N;6KX*fYn}GR`)qeBIJWWN=4~@O4eybS9}K4T z+}OTSV5nvAGRQRw70|U-EA7czu>QtB)+q_?pR#I|>ZX1C5LRrKeB+pu=U9pEfgJrD zt(OzNR)zg`?oMgw{pbxTZTiq$sOWJ7`+ZY)Q`*)JIjM_l=#`VxG?|%_EmpjYl5a&< z$lENqD`W=61E``cDG25)XTYOI)aOsJZX)?GT|0}_fSgGGj^B4Y6+8Tk9W{n<&D<0U`UO2f3wghsJ5_TDUK%L}9?G}s|W`)eh2 zw$t!QT7N)@8e`vA$+g`J>#$D0rG;?g8@(n`#rV+jb8mIeq{PC~Q+{hWo2fULza(Zn zKq+wIf&Uz;5vtgMM4cfA$vi)voyW(GVF{^*ectZT`R@b|IPI5*kF|EnIq)CFvNHTk z&l5Wr==(8Jx|wFd)hox0eK3}bt`*# z`aUbJ;s4l?{;xOFpTri7RN-t+zn~kFw$GZ9S^gtSa%Q{fNJl*fFK)&a9r{2E*H01O zN##1%-k1}w0QVPL#R%`R-yM7iv?i1`*4?;Tq%R{sxi|;J2UF2_`VvF|$blimg3xya zEfBWqgJ2`zk9P#&pWx$JZw)cKTS1KRCmEC9P6|z!$oA1+UsPT@{&CQvNxwXV+=m%& z0!X5s=y;CPi?!&c;T}J(1Xu2xWx6KWpw%gcd@ts8=tCr&Ay~B#uL_`>AEP0p>^BTyD`5f|_Yra$SIb=u7DNnM7*K1-8q^EBF6707NEBb``07_8rq~lh>+7YLn$pY0B~A?)=PCX7YTQs*V=Qzs!d+p)aQoB! z8oA)qv#_skOJc+Pz5SsHH?%72y33$&F7kMU1gQwK@~2;dG9&H=!e(R&>nov??IC|= zP&-vy<-@E&vwrb9g9mb4JNr*XPh}fR$-}?k&EM=yBQ~>ls&%Xs2|CH5*z;V>0dg-E z=`e4JKAO=%eR5>SC}ybO{+RKweOUt1LJQ&j-5t!cUILEY4<%bX>w9@p3%+9Wv(4!k z_?diA#PMCMDLx?6ktPQXr$HDlD#2X`CYXnEpkFd|8k9gc%HM|GPOzfGB+!0-&z`RR z$e?*B6azqggLUs7>)H#ecU z{PP#FXt-N0&&U884>(=a26__d;r9>K&9UZraibLGl6-6*oi;+RpcZmVh)L?rC z0RstUK98K;CP~-8r>v$@cpW(Fw&&-kgAmoZy|K1pt>Qc3Vd#b5ON?C^aX$+cFC%`b zNiM1Iz`6Aqw+eNX-yU?#*9KHDeC#R+dK$KH>C&fSVo5$x6W~bsG+%F4lxWbQW>tsAiOf}QJ8-%2N>gG+nW3FzR#jhDZSw9 zqN*-40MF-Gn+jm3GHmQ54&6te=w(j^apF z7Ti6!&gSdS+JsO-I)snaZ?WH%al1#Rg8u%5z{EC;tg!y=l8T=jllci@xQe#IXK4t8 zvW&eY%;=s|O$lJ!$nGnHDGh26Uww_E4ZRH9(foP#dD~s5VxQ_xH5fH>O#u`VTJg8Q zR2UMa-t7Nt7ACF{{x7iU?g&0Vb9t(4{uVJr-GuHuQ8@+D(q(W1UYx!o7fB$siXgpD zrpr`K?sJny2_?^9fd1mqL1zyt-paKMof1+dcKhE?X;f*312Jnfx_yg$!5yh}O@x1d zC7@TtiQ!+6dJ3^3T|MrqV5miTDHjSDJjVH8xjlXC@OxXQ9|`VE!o8-UkK~5fi;0jl zKarF+nKYlqe>kDVZ%DQR6o8qXrC=9#EX$>Vo@aC%GPA5bS&|{L(;v?4s~>PcE8yz~XB-9){gi%c3Rz0_`}}axTu!%)n6g$g>q5zMlgX9-cE2IP;mdx2ORo(83?c0L zTCx~XGK@cfLRP$Gum3qTWp|M@dJ+rzn^k{Ub7C^n*@8!p40?7!F~I5jC@Y1J?vPT< z4p;N{c;D3DN{?an^Sp9BH?h6d727^}Rd*iCt|ed9Xs=hpPd3~wWhRTO ztC{wd@vLg4KyOPN=Gr>@2D*R#5bRg&6xN804i)=UtOApPf-HM&%%L$9yOJ8SQ zg@Dkd3BEev>Wts%Iu04#B5`VoN#{JeKOdBagJP%j1`^9-cE5{qVds{XH>r z^tQDSH)hltJkx|}w{4z7Z)$078RcCw-uB+23nl0DsOFBFIh_lbP0CIG-=@R=p5==Y zBhV8gp&Y#4f%#{TA?<%6H+(xhf%;H;1TVg9nUIftsOMXQNVgyt&1i&EFW@bh_9!YA zne}a}qw>AH9m9RXvS2;@SbTVuk?r&g~`oeoOZ~K5&!3aEK9kdMHx7)8*i`E` z2%LJ*;h2|)ktwn3 ztD@)57T9bB1#lvL;6Ijnzf8o#z8(gddigVVa++7(`1@N+JvnnqIY7z1!c9hg){|Q&nb7G%XU#Z5EeMbj7 zU!IdyR}am_x}PT&KGwJRHMciU$Q0zOc%055_ke3(=nK`74-`7pimH^3#_JEc`TiWrndG98z zIsFDN7)EZcqo@gOSaLdbj*m`|B%9~kBJzqpNfs<*W^EF>OJz<*oYz0Ij;dD2pE}-U zo-qzPe{dmJ%2z~K0ACf_hMDYa+WG;A2t`fC!O;o{RUHWcBiJ;}zCN^DB1lY@c~1rG zI0*ZP=ZNbVr44V2g#j_J0=``;Bl)%}&w<1BlN^bJ%Gib#PvM!UC;(Nf|1*k`H^C0V zTd&@tDtLe@rJJ?~8lsWJ%%D)WTiWOMHVpiZ)St&S{ZU9ZGMU<<5sntqO_1E=Q5kXg zRK}3J_5RT<;kV)dR#Njxo^}rD%gZ7{Q068@y6z_-^Hipr(&Lw#kJ$ej_uoa2o7Vv9d=1}Pu(k;G&&4pSI^&)H!L z^b=K5iwFTeT`q6r$q@Gb|~sg{#Q%_@E+G$nz@mB z_6zl!k=V+gBf|(mDLyg7jDSoNMYvuqsfc3<{tA4xXkk(ir)8%_4Qa9lz4}aW9}5uW z;qY|}ye(;fVD0i(Jy~bN7`=9bf#RwEJWb?;R*Wz8FjJT7-*rwuibM4Mzw=xqFxNkT zet=5(r*&S1anBiQl0e%165G@{HZlTl^!$N>&hJl)MyM7c@P>Few&yWacC7Ix=eS!s zm4`!7l?M9uaa3l!lbh)2C!_7=IL}=ne4WInX9~mA8`A; z!N8YYZ>-{gcvs;xgAHwbs|)d3v>wtN5!rP=XPfwf>G78rRS#6YP)?U@U|v~?5ZDGc zW#oW;u++>Y60qvLe#Bc)#(}ifABDH=_hXtSWEy~f@Q=^*B#)DyB*`xC&jq7wqS6kc zqZ@$l!}k_XJehpdu?eEr(MbCt))v{GsyOSUyh-6%!ud|D^1X==fcy?2O5J47k*T2r zW4VDKmG>LE%MJx4Y^t;A%}{x$kc0;dHL5QvW3YE2v3|u=!$%Zv_~C+vy!ESR4Yk~B zmfVYwv^~zg_M>iFkKOo9dbC#N08R4uYF^6;iGyOi8t9}+CLML2ER)d?^<&2p6arqt?0}Vt{xb!9*2B|Zz!B;G=F(3`_24mz&WRsf7uauVV%`D zvz%H0WV@0PVMGJ2x4;uy43NUDd9^Jcl+tr^rhYab8#TtMD|z_eg}J#ewNC;|?jZ?+ z*s#Ht9#iykUegn=)=w)U^HNSxTX|w+moKYe4LsgDI^ED2QX}i>pJXvkoHm zS1^lpxEq0ekeD1Jy0FSXDnGIIv+uv=a}J$J=KnmOe~q-9 zKl7mo3HUj&8W)Ne6Ib$GPTyW7EWi1MPUz@WZ5TO#-lOr8qvcw>zFYRJ0rLgfAMm?B zEMg-u2>frl^e`)rWK^#BD0uYnp@1hWXyQlPRg?jOO3^+i65tPGx`!&{+q&if6TaW* zGhB>An1-X?N5Nm5kzMfX_GOpIOe#I32)Wl!VzT3!Fs$J*Q{^i3IJ6q`Nyt7ej!g5wWr?;wbGz* zIspajN8W#7_6vPpMi+Fz`Z-kfOP<`a51P=GdtFuOYlzk`9AyRaNfFY`HCD!Be1g-P=QZ{Mu(Cd64G%0b&vtinSGA0D z_YVhp)w+G~&+VG#4Wyhg2yRV;*8X=bJ{&-aKdj<7Q|B`Se;jf=k;Lcj#vPrZLwNp0 zZ|_gJ7nY>5xW)y%lnJ+RzA%ztN&4q_MHRQSnXoyn3FnuCCq-%>w;3gj>-y&SK8aR{ z3PzN;mFz;q}+0pHQiJ8k!^d)M^E|+!1&hyIN*Co8IfmdQE@05=L&y_Wh_Ln z`HtL@mSyh}?VI^O+Fye@E+i~2Mlkg}>0rC<7WO$h$xcK9vPLr%3^geYx@EX?>Nc@} zii-8uA#_xTqSG~~@RBf>aOwpu#r3fS5<(04koFlwN$!1W4y#p7fBkzarOk6k%irQx zNp+tdiCCMajFR0GkEFd`x3t?VWo)mfmP3JM&7iTATtt|Y+1=p?4qR^${+CZY!~_t) zgaQFackX~w@9=2D%|O8~<8>hmQ)ZLu1naF~m!C_{y?!x{(_1el!PyZv6{oz5`9}Kv zY=iB9q;hpu|Ei&O(}tT~=*EYjy`d;1L>=L`afU*^Da(?xk=2`nI zeBG2&n2j}A17P;cA;Nqc3a8UdoM{x+MYo_^NF#<5>vcLka zv@P}aJ|&DYinfz&$XI&$dcB6C%fxH@(@`Vev@E1veGBBGf$zy_>Y%-Xc+j^boct=w z6Sh!5{Sv2z1k4i+o|!2B)cungKu)wMZCA>#D{Du3eNtCMpp(uk`wH#rk2ogqbtXOU zzlmm$$YMNuul%g;JPyH~X@h6L+apU#^QC7HX&AGGK<&HBg{}Ay|36bIw-4qV%+6Ho@ujwO{%p|a z0~+Bi>EI>GHc{unNnW>TsVVY{vL}RF%jBQBqXI~~fI1_I%AN~MRrey+-=TAO z@MX8bWTVGW`rG{G9oZm_Go1pzKi=Ldeh-P3bhdH7aWB__d2s8n?hxXP8CQRg`MwyCwriBz z+xQby%g(>(6qxAh7jAd1)b&XrnrWJ;UP#fsjM9_6%5%GXEyp4y*X!u<87X`+h9lT> z)8{Db1=Q<9V;~u#!j^`;NJ5C$Y^wyuGoy}ARpk>{R5{7E=&1!>OkW+!aF>$5-3qW!urrYij7nRL}P#qD29?{Y2Y%>NcL z=@R|y`k#eN$#@|XtOze;ddGkCZRtOJRj5C%`Dz@t-!o_h@&L5ZwMfdJ6K*g-xzYO_ zpw%n7A3oJ)avH@5E(ALv9q5EzlkG; z47A3=ia+GhD3vi>=hz-b(aXOe@h}}HbV>STL9N0jFSptZ7|nD9QS+-%OGV|$K^XY_g@D6SxtN*s5sNjRm>kC^g^c#s@K#-s$Y6jpQ24{=4 zmWt-k)W80~YF7<@H+ZLSi*jCga9)miDpbhbxBEw5{h6WG^lkh)UYoT$nctlB@Kx(? z>m@&i#Xm_dFfR7v!~|cdJfCsN(I`(5!AIz@g4PMUOUgwhVKwFL=W28Snx~>($0L!I zjNnY$Nq=+&PvCaY85|5oS6=4O3#u8a#!KN7gP8`8P#4$&T7W%pJDzL(8)At6u%)j0 zAp-L`pv?@rfj3Tgop}*~=fY@S0-k+z`k7nrYr45Rpysm=RrGK2}iwG3%#k||_4H88N2c*qpXDPOYRJ-g*|&`97JIZ;ZKD1}%L3&VYSXt5IV<-U6t4s{WlVBlnm}q!HO^ zZa(@uH@)|Ady^ME5No(i@fb41GA0hT6%}`T&;H3%L-H8>YdrlMclM8-%V4<*ot3=L ztcIUqFZ%+9(d>Y^_!ffrQ|kbL_`$I+_o5doDJu?t4pHdE@qSDtaKDYQyz<%pmVf_z zOWuN3DA7sOP)w4N{dhH5{F50VbGm(_9a5fJuF1g6M7pigX?(Wq+KJ6I9|MF?Lqkv1 z%q(jcMgwt~hh_YF^(9}wYp!$12|CjMwu^YnN$575{BM&9ASSm#W5h=5p+gQ7@GBrc zWy35Ox>y%W?%wV%rtUcb{J)gSiGsH5Xj^KF1+g0DhAnSBh^1l1>kl$`u?ek1h({BD z6nzgsePQbB2{6Ie&A$wQgIw6|?xc+)dH!`mru*Lh@cWW(kDZ6wo;(J)MP1Ek0$K{O5ruzKms*UcUYYXGiTNh?Vb})sgZFu?btz z4NrwN_lk%gAqhJ1SKO0S&asR>ji!*&h_%PX>0MEUS989J|(E5-9~Ln2$WYxG~GC0>`b z?((s`NvX$$UWjixXn=(x=@3(k7{H!uf56(85@j3-j5vAz+-e&)6Yq<-8DdYEq=Sn4 zMtVL<=D9W!JIV(LVkX?k4~`6tUoyI&4QlYLu0auaxs=`~>r6 zd+03;iC}mRu<4}YQqaUQ&pl}je)LEX+jI5efw$Ip^J>q{faQ2icEM9ae{N+&syq*-_ar4*Wm>$CV`j4&1b-Wg{)ba7vaNWV{ulf#<%8BWbuBcqGWe;;KC2hUTQ^-ikF=YQ9(E8 z`oVfnQ2%%)TzDAS)U|GJp>2+$TuJ*b96URv>1R__Q^V+ms%2j7|QZd zUF*s;#L{5D&Y0Na*<;VmhSkIS+CTXd(j>>F#+91w{nI{L!1WXx2OBJ6yfkH_Tb;DE zUdH1Kf}i1A3$&Jf64p3|&sst!0Lb?Gvbt9Y&KxnTimSW$&f8;-?Aj*C!NLN~7H+ERa2-22(d z>TRHT9m=5#Uh&d>X1#{o{2Lx8_?-KrMs$vX8YrodG9A=qT;%p{5<0-p+rZn_z;;#40=x^(yp`Py<`R>-PEA+MPI(M#V*;`B?jwAZVuKh4Izj|BKYI($pxd$$>#6wFy*Y=J% zf~8IZvm1Kx)!+X%NCxzJZWdi?`r{1GTp7OWlpKjUVP}qTT$5+6!kP2 z1?+N#y)gAuZLh?4K__3kYhV}sC#y;2mpv=zihF9gDL-Qzf@=h;GC>A5cZ?N3*8+|CAexD)#W&E)e;Av-FZqCf1`}Sb=&b0D;%~)hrrktGkOdgRyxX9Lb zVF1~sAao;wkw8kjFg@_N3bzoj&SrRfBo&b7b9h{gyXrpLDkvt1^dS9e4I3toln;Kj z0V94I!SU?-rCKM@?<4=D{dJ4M_aQ-wKvpTifGM zp9TEbXRwwMB1#;)hFWF}6|@Z6*>M6RM);2Lf__F(3V&W&`zmM8aV;L&y7;_ZR3wI? z^-Gpr>Z-+dO31*HaiUMYn6lxVuZu{ZA@|74ZZ7q@L!t!XkP z`P4}ybu`bI*@{QCu@Drs={H6A)I^6KI;63Q;l4Br!ni~W?*IJS*n7Kf!chyuT((ru zyumP|`VzaR72^R$d9v;(!RhuUFBaht;+foEVL<*k40V>A{u;i}Ks4F`Pagnc8CrJ- zGG?OVRuY8M9d^GCV!RqYAn=ZGAWQnFlms#K0rM%gF->_MlvgaUho0EFxNtzEB-Q&5 zABwizpm9P`M;kBBM(zUtjTyFduQL)DXfn>q)>l*u^Y_Qu&=k!fI%{uh<88<7##{dd zgp2ve$iR)|qkfr)h&E(uNKecVXtbJ54Ttfi%ioB%aQn`7ZrvK)JcUN^@5~+(QA`<) zOnN>$k+Ol`(y(2{g~DA8=}IpFvy**O=~WEG%@-&2S>Ln=7^q^Q_7j}G3}D@uR*eBp zD&77GSzr@WOUDesRG5T4qACR8&<#QmJ0FFxMK+9p(0q-vzoy3QbiPUyUymT<5#C)& zGqzp7f5?McDuAE5XxJm0|54?>&vh8ReiwQ4omDuDo#z@#4DH_cU|Up`si=>jt0I9> zIRlRIt`FP{C@jw;aQXfz@(fIr;*}T}y0sVLMS=a*#3&N@w8vqg zMH2c4FvTQ`iy9POn@A`K4u`QgY$bqe5B94Aw8B!ya#HK6OeZ8*uR9))_M0j1tzjWm zK}gi9to>+)&KJFPB{Wneyy`YvNVkSrw*aPO-2KiB@%Qwoh9~p&usKXTJ5P8p9&0;S?~?rvXAaHR>Znty zHlhwVj(Oh)fN3rnuypw+U{K<&bGlj)~hw3Rc0%J%Xu=?ySn{W7~N|Wc($s4?J3^NI^WHe)| zD?s-Wyk*@)$0tk-f!tc}c4EwNiv^5iwacBg3sn&{S96?}-`MKZ)Xq|_lS`GOkstF> zlyi)FlVBPA!??SxE?sLhtb50_0;Pr>)o6LF$`y-^-nvWiHNQ$5G)^ z9*f+6xK>ZX+RVJZ>yQM`IKKoRS4YLgzbsJXswTz$uM)XD0b$SmiRSgpQg!t5z}c1X ziTLPCdA9x--WIw2#7q)7Q6rM!Ngu}$28-i{SjCg*OXRZc{p7;Vsf!%H0ZzZTEAE}b zsw37q`4L--E~clCLVMr6kx`Vlo6aDwkwj%BU$o~k@i^_djY>bdwY)^#ntmFXe@WG_ z+swI_&kQM-rSf3j5Fc{L_exOY!9oFgaibutx|j$0cIw|orVRTr*9!>@YJ;j zxySc(GLl4MAEFF$XK+lS@EJC${E5S3U?X5&)rSdq)r7f>~ zS$_@U($d0C^X?y!B^bbC$(Go|5et4{Nn!Q8s8Th*OWs)2hg&3x=KjF3$gH&RO8Y@7 zon@FDja~TnNXyYacR~T<7;0VX&HOb1WUM8L5p~d-zw6x)vYru=KSXrT$luSp|Ni$o z>tDXD4l(Mjxzy;i(OsCD@xOOao}(VG4MRVO0(Br(?pMYpEp^)XuzgbBn2g`6+$RHv z5Z2(#@<^NE*G9#Wd{S4Bba#k984s&jiwOQuCQA__eAe_uE#MW^Q#uw6&?Bwu{>%8I zILu&*9v8ium4c^OtF(A*gnjPd^N-*D%+M);-#xOu09@tPIoVp&JK5S|e4K{7&w>N~ zRRl8OSDu&#bNaA#DM_Nu_X;H@H=05nw!Af|%f`~q?SI^x1|ELE&brMTc(i8P7#{!Z zqRw;|vI(pl%!$wVxcRYlWzF7H(I+{4T5rPEM@(`3=laY3$WwiQ%kcw+6oMZvfX}OT z)Sq}x9v)Xi{Z~3$%_y8rf~1^^m#fCtF%Nx81Ob;*mcNBQY}B=!AYqnP9geJPqCNgS zT+5LyybV`}1G3JBvc5R+vO{DA9o6tnCV~a&J1)D|%o#8_j^}U+krgJm2@o8Zv&Y(8 z1X|@}6>xU68vl)7i+BnR*1dZLcxvqsAN6|G+F93_l9}`GFONtM!|JF)P4mgJ)S1zfyP6f7Sx;2S zQe5pPQl3B*(gs20WV=sz9MRN|aKE5^pzeUjEv=cGtp;`7t z#(4_B=ZP;No@OO>gO*#g7dgd^h0#Sb-tidKv zOL5Aw6z0>S_h?d^?eP8kKdH72hq}fFD^JOHrLx_dSBUD9>v3ognW)MTu}SjAgqB{% zG0QK%BY=letcSv~YXv7!?xGG^$Zu`xxG$Fx0=1h`>kV=PONBBxBNK$EEv3<$=+aXfz4h-ej*ai75N%Nl!f~ouEKL-7V38_}EX|tU6x^QmWjw6~{gBG0)(<2IPO=4qU zcitgI=y$+VXNts{N@2i(hOq6vPh9b*Z%o3(kwl42YXNXgr;Qw-P^hUXK`Et;fqx|% z7DP+lpiKnEFv7}^3RUZ@+idxk!CNXVVMmqvK}G{l)vuLwpi4mlKhy0oZnyJ{(m~fX zg^?(m6L4*nMeVL=v)5-5vaCf5lM0vSmHwk8n5N-TbW3;p&-tw-6?U2(i7p^* zT@6>*rx|3m_u1dl(s|lOU?i=PnUzDaQRM`H?oCjjIE03FaQvQdzsp`JBWKmxAmIpF z0|VM=-#8c@RJgMNZ=S)jece-8^xWY}7&P!UnU|$o)Nb3`+o4ct_nXSUxj3-2UD-|b zohO;X$dby24S9cr2#{S#HN^)CS0a5sxU;=*x$A1lncufifk0Dwh~5wL6#-QP6p{CA zg5Fa}A4#+|^v6ifOIq=sGmDQ;NbZ2DG&9^kZ2*>l-?_4dR<|8P0N8wx@XS+fIX7S# zf$plfl{|ECU!*Kd6k5@x`XD3+J@i${zXS=+w+2)N4Gx|NAf)SB+fz7r#(3-0se}8YDA;8ye9TA>yyCwO`Q)(3FLu|U zDKp$>yS{jvPr5(YZ+Eq9k*9@7khGOh*Z1M9LXJ%xs=Tx6_E)$!_SK;-b&SbweVfPmI&gB8Wj>_Fc)Hc7g zJsgg>4mq9UKH&{chnIC^SX1ez(>i0&Jn@x;g9C?KGBlPeIr3XcjIMsQxs8MDsG|bx zX&*>tu|43ahK%i)yQTf4e+c!ULhR)o;qDc1pGhV4ob%J(x6{*|2S7x;b}_|S!s&Az z|1)4fm)DeTg=GdFJ3x+XD2tV!o`pfs3n6GESUr!dJD3== z=3Lv4qD8~j;WuSo&)LOSwbmQnJ+Sq)O*8Bcyk|0FKO(zR_Dp}Rz7I~_-6^BfQuO|R zy8z@V9{4)x-SZG!t*m24eb2)}LI$e(_?X63c z)|EyK`Trit`=1@GPP=MBPn+Lx;&eV1L|Dp1v0{tmz$04Dt2 zGJ;V-Mj1t{y?LUu2Fut&9+I8@`&UIRS6B|PfZU&rJ&7)}=g}<(j}R38X3+TH6Z-3p z{4q+$dOZk{v&3X+Vn=@)rNmI68umlLUqMcVn(fsgEh9TA!^2T#E4L4z7=m{Wb@A&> zOOx44LFaDZ6y-%MsUwZ?D2ax;m9V{w?fsLD)E-a5mkG%r9Jlt=+FI&T=6gVa7Ec;N z8iiX)I&1I~`YM~cLm=`r@KeNB=~)J;P4?L^FF>*21a87KE!Q) zItejhBkhL`bu^@XSa5>S-zKpPm{LzV)ig$ME84u(9{U#N0?sR~CQgB5C_K&8F{T@` zo$stBF#cE3=V#8|*awYCGIYcck~592o{UV?)cPH5Ie9qcZl>&Xh_D}jc>8-WEIBL3 zc5`hfq5Rz*uVc*Mk%FxTH3KNx?S>4>vyb+gpR$V%yt^L)K!$9m0X%@0PTe!E4S*l6 zUW)V0q>c|~j|~|G3C#!&a}xV}iDi&yJW`YJN$dwU}4<+t(l)(;QM zj5TG}ZR$_E`&M}nIRe5)%M(Hlzsts&zbKu)Jp&|3{doD|UN6V->|RqTgy3>B`HzLW zpkx1o2Y}4lk_>ZDCQ)pOQg-FVy&mKM)ZV;?u&-};Ihh!$rt-pq)&8C5@Y_sH*d~fi z{$~Kby1Pj6YIm^k_WJgmXI$~xZlM_6EN$zvrI-OUCIZnjyFLCQ!tC^im;cOl#7U@A zGC}>YyPV@=`Y@HpPgl&?i9vO2QKpBGYhiRpeY0YII66T7^_czp5g-K(WfqCZN{vA+PNWv0jN2N8-}5lY zi8`7@@vM@TWr^EP5)5Q9dVJcwG+77-v0FB?lyix^N>6yCLNjcj(*lXJEZn`fObInP z`yo%}%C)Z+!q}xkJ{Kc}0_ga>N6i5^xF@Kv!zv6_LcY^Bc zH&ibLGgyAEtEbBqcoABBzSXdDK@44K4c%SHJY6V9tnD`j-UcD&w_+w_g`Y**+zIgB z%kVi}vXz*c=%t@Q4HE9I-P~YKvLFzmQ#$<6fkpd&cldq3c7J$rz2MD*?`p}q>!C?<&DPOL3vT7K;q{Tt?w{28BT}q z(j}Vd#8p#8XKKWLlMk_G7zJm31+jyo?7+m#hc$}WNw){DR%w$Ch}HDdnIHgNe zli!fn1~+r-oXxX~+5BM^Xa5LG#+(QuPn0(#i#3lCsnTnoI@v71G)G=Zo=U7W&oplL z!zHdye%C1+=X|hbfy=Eg+FsM;DXeyN8sQfOu=r~}Y+JCX>`c3i_@3yaNN0EKif=^R ziQzcE0}JZ3R>y&{)rR6tcc4Kkxlp}eNHvStNRGSzy2PmMjh1aL=ZBFeY8!Nx14J8L z*3>ig3fOse^QUY7{{4$SCG}5x>N%xuw1CLeR5!JtDGm+VZ7loJXBLb)<2$e9Zt!kt z7o}^<>#wJr9xggl!zP}D+XbL5IFP%o8!5J*?B>!BwqM8%sdpLg3IFNt^i|B$f=Ms< zqVR1Ks=g7UYE{BaL;BrFQ5)6t?RAUE5=U0{(#{aMQsbki3^t(&CpI$klke;?8_5vr zf8%SfR}-o})(Z~WR$)(H*qMLNrKC9DYdo_sa~u-(oC>=ZrGnba;`)A16FJw7Vj}KK zjaG;5f4j(UPXG6^XMQXbtKWH)5QPg@4@o|1NWFjb+*QC+d0{MX_F;DO(2x`=rgVHY z^_{j#;O0m9kJ_9mN6D@uIsBU+dn^+MIp}mTlYin=dM?Vd9;+#D^EZndz$9-!0Wv`+Tq^NHsTF<=fE1SA z{=7Z7E1vsf9I!`rUl~l}3>*UnJY)9B2>d=OXOC1t9DKnnElzqkwLH>y4IzQ4pQlG9 z{cyNkQFhR)*Jje|(Vu)thm|6Hors(}a#1Uz??&cz^H6wN_5LO=KH_2AUc~liW ziE3+m4y#J9h?V9&b|4$a=08sa7`c9dt9VuGyGO}oyL#SdcqL|cB8(g_((L_CgdZYS zGV?YzKS*GO`mHH2t^4kwunoQkpF40TEWI*BQq<{gLNRTbBooT>Uy{FdsB9ikR>Uc? z7_}r+&uLdLkQAwP5fcGec`NsfhsXIIl;}>*E?Gq zm^Yq#t>wig&OIEPO~pzJ34aZY2WOaGlMt{Gged$D6rjaen25atg{9jV&eoFZX3U;0tc=9dO9J__^w z!n-aXp?GlF@rp~|d8%l)`TDh|TL1^P1VTxZ-2dK`q_)1ItM}hd0V2yVtCRioYYVxZ zu<;<-)4y(l;&lR2ETR&ZEq<>8ioh8^H@Tb#e*KMW_l&{)xQ0U4o1iV>{D>ipF8kes78jfmM>#?HZa_rb^Pv4p-Y=&pr3P_i z70_ZB{K;Ao^hk`B6ji?AE^NBcITB4Zf5ahsIjjO$N1rx;f1Ke6N*ct70m4WDX-19^M34}qyJK`WNHa>1jcyp-IqLGc zzZ>V?bHC@@|6phFe(m*mJ)@RkbgYI?(cXUdlXrD%2E+Y`s@$T~-N`O@Cma3P+2JAz z@Y3jHUYgA4bEp0$Amua8BIFH^GhFAHZ8vWxN%eH zkuEiJ8)3$cn=@{0xJx!4iwLJGEcMwL)}FsO6)$p|lPXa+l8H@^8^88c9^ae0+ z0Z^eww2~8cYRXpB4hip|1&zE9mitR}2q*@I6KH8usB%9Li60U$Qp4IKTj*e5&a zF`HyTPxA}Po0UdrbROzSFjbRP9Shh8<+@Gq8U3~!joYZHJ4)oZ z>Z_!jo^oQ1`@hGtXivZCTe+i%gEN`z0h>V^@^pK=463Ywqab)^qWR$Si1;yg_l3m} zi{0hs9(T$(n?Du0l(@wML8Zf;^*p#oGZ!;xa(^w@;F#9pf+UIqP^4G8EeLHLfg8pX zA6Hocsx}IgX08>WwZY`*&`Tg|!?y@{WUzR#(p0xT{rP=mdg$(Q0(cSx%XMJg>=+(8 z3h;=Tl$_rXGSJdS2ZK^6pYl$#4;dj2j64GKdhpmq=rc(F@>CoNQD7bzDe(pLa4;46 z8oaIuixVm8U%*O+gvBym6e~pp!^>V9^f--VV57%U8Pp(_#LCj{WA*&_=@3(>5!$LR z^d=Fb=AAcGcqr5w7PlkOQs|YM=4+oYmw{pxy8j60@5Gp~Of4Ztwgq45A98CzF3XIG zbeO{v>_&f4&d2xsw^Fwr*WUU~x-7E(Yumb!KBO#6r>*~gqv`*PRnI-A7y#wmZNlPT z%%Ja+DM^}beV1b*lxz&xV=?Ny_DWO49hVG-U9 zudh#JTL%UT&~bN12G^e`nQ{Ar^qzg`#`j@Gm=i_FF9YQ=*cPM+5-Y=}f35zb&Smdb zv`$jmO>KKFi(^l)Bx|Ap(;_~9FUn%pdX-tvC3gnl^qh3^|MoEDC#8j5Uw*FsK>xoJ z@(F_X{gLUyA8D7KIx$OWMz#QZR08@nEZ%)Mw%V z#)e2yoFEB>_)buWf}I~cS+n`z3oM(iYDv&>*>?=STw>j=mHHg3y$UMZFlf92gIk|TKQ zXVB^I1phUDPr)SY8}AoJmg?R*N$xjCa>SQnU3w`~c_S2p4cX|j$5IV3B8aGJEXR&+ zzS2Jo!?^(E7C~Ldl=VPY!{2qf6q7w@2SkSjdFs;Jlfhy<2vD+FpR@-mI;A$$)|M(6 zu-@FWBst%2Z(at7Q4yl?tCZ4QVb$&$?9H|FaNV8W#H|)2n2nY79tl5n1SR5(aJP;} zC7{F9n_kygzJyEYE$>_SePUiygO&JFfXcDt8Vw1*>>w-GZ}wLY`bmU?Y1N8sXo!1E zfnQ%^$Cc$T(><=vKLTsqiuSzE-k%&#=HtNN^}SxsV+#$z!uiVp`{0HNGIs|&xclOF zS?-h$1LY&HcNl!d;anA2K4#&Ys>G`eLICRP!1zSbQGc(*i|lJZzNt-IlN)ka#MJv; zSTIwix1TrWnk3JR&wG=f`55jdM>az?lG$z_ zvDX4IBQyAK5C1eqM#4>pWm;$ZcJdHguJ?^iI6cOiHa|(9d&{bux7RmyxTcwIWg9tgxpPy#>jqcQ^vuS26nid( zlKIX4tMxn8z<-PTYFpQA0ecWfzTp-ksVz6x7nr<>#kSxv0uxd4A1AaDsQA?$uwC&?7#hbvw`{w z_|03Rk1r6dk@w3$;U4=03$NC3|FVqMiP&GXRp)7>4c)zuq1^L3Obdh>=OZAQ^*mWC zR0Io5zsd+N<1d*^IJCe@c7=9%T?-7d|WHJ`T`S0u6?6TtShd(<>^E7@!{bEz=iE#DSci-i{me7VQ zS!lJqeIou-DNfShx5h-N+X z+K#{HrP%YA!gQf|#N;`K3YL@S?P=L$uSvCcogf*WC$JU4F#4qDZ|-%h-R_s>xN1WA z^N*$V0(_NcOn1y1Ci={#Y~Nfi}M39e~U>{X%;;vJZ4x0Ts{iaaiPe*eSP z-1L?yUbcDbt{r%^tf_&ImD&ShG2C*X?*S+z#^HT7Al-REPrbCQNL8~8c|t;g5b|*M zb;%&Emm;Tq@+!w;pCVF~I0dh4W70a=mjLlD_6RV#0Vz6!pEt5n9rY|bt)_+AA(fT0})zze1hE*}A_erNG#$s)<|KBc|5c zfp0!MqGq~RrCTc+%F7CQ?%?~XVRTgn0x_UBQ|9V998474_ze1vR~9S%P4$x^Qc4w( z`kFZEB7@3hv8iAsT99Oa2@tGCB>PfXi`Qj%3er>lm^x6*P9`2;ToZ&!aF@+eq6kjIeg5i69t5i>ortRpy%FrX3P2lrXr}!T1r-Galb3fO)$rb0KCAl>BsJFa2c+}>N z@5Dt1{)B1p{s$qR+&@g~504n+`hT^e{SLk%V$9P$3ZS*Keh(31Tfqn{1PEy$fBp)$2fS$Py93Y}}liC{eHc1Mmme zIfC@$Px}3y7oXaaLjd6Q6-B_qZvfd2{?LSrr-r+9FEV;-l1n}XPvtqy39jYk#_vFW z>-xLW{nCkMCfS)n8t&@!i>&N44F8(;X%?8gJn!+{ecO_+!Y+b~Z@hX&_@VaT6?3Yz z?GbFKr<_1hpKRqB=!|}4k~cOfrHDJ^rD<)C6j#NeeJ7a{4F_;kG7<2*oaASkwf*Gu z?AUc0-_}O-8p6J|sym|zk6=JX6C*}98eNo%tQ8g{G;cGqVq@A;lkNZZC*KtymETU* z>@KeD!E}}*=@zx&@fq7pX{sT#x8lm~ z(dI*>=@DL z=T?F}FiAcDWE~twc(`_^1QB1M#4? z^%Lvg6CdfIOzhr|a#^|lR^L6fG#7CByjH<`EkdCd$&IGo>Vpp$4jZ{^GT1`~LQnbQ zdb0VP;FDBm%n1j*ioRDL@P#6SdExha^ocerEOfQ+GWEoou%Q=T;ff5a<#>hlcp3+fH)1c^v>e$`7rKVh0 zh)ig;Ysj|gek*=7Wd;fEKB2b^tzYyC=59Xfk33hi+HAbS+@j~j8wHvInA~UYng$i< zoH^b8zm;C;V{Od2ev?@xlqAb!jNNIy=v*(PZ(n)+@%YmLyKrI^xHtSrvkKI( zCAt}_X95(4aUR^h%)YKJ7 z!&-6=(7IRvlLw_!yL4SecR#uF_0n1e*PTg|S33 zTj7+7D^&XsjrUuiwIPHHL1b+fT!O%ISS}TZwIQ%B>&#{_;8(=*;Enl>$5EGz9n~@+ zT`_P^GEDpzzA@!*-sT*oN^8fcjv~cV(bruc#myNEwQgQI6+eYb8u9&oY%6s?qi)6Q z!#&c`lWchb23^S=Uc7WFCI*>hiVfqha5uwT8CwnJZP1DI{!8ex?AYB$wCno|Wa^K-N|BEEh1}4WIhq4q3;Qa!q}hB*WX~Ef>Jsze**+%pUF7Lj&}++4Z>rI7J>e#HMAzgS~rTBYkk~!-aVo zsakny8b!B9Y`62{c^WPwg@Rnkqz}j+M4kki(@OMhqfVWSieVux>P4}yX#U#ueun>$ z&1*Rw_@U2LXhL^0}`}=0l*pevx6}I2q+r+e_6l*CDs|)eD_V$A34K%yAXxm%oL4xGa4ue{6Q`XMc z$W<;fF_kVwFA_F*PhQNffT$niI98P3t)AjVN($e#HdnO(SGz;$5_y>M{#KwN%jG(N zCx5*cPUoIa0VY___!~g>>$WxLE3#ET#{R92t9)C^sDF7ePS>2ST5L5}?)Jj_af3a< zo9N3zq&nHL*HcY_Hp?}&rp~;>c4MQn1k%lPvhAd%bp_ee$1*Mx&*1Oz0sFboYzgTx zGXK1af6_DK+lluK_$9^aF?6~wuj-qp71cwkpF)+2eaZl{?~C8B`TYnWai94>wJ z)Jc!Da`8GYlal7NauPZc%l@i4kW+HM_r9Zzy@EMdiz}7Ul8SqlAQ!muXG%U+Ne~AACFljHdu4Z4 zjSNUeH1~Gs@ysn)T1#ta-!%7^04m~VXR9@B@ZCM`9Z58#vF{m_Qyh_M%92&7RL5y8594j+ z&=l7&1AsqmaB9Q8AnVCU3Vcj#=pts4D?oNNT;E*raA%OmZvG$N>S>A&&t+V(+1^HHBZiZ|RseN=uRnbcJOv_L66x;yait#q1#W3&)mRjyQ z@iE?L@#N1l!7d?8x~bYiI`^QDA_&JNLNckHa6RhZo-x3D)9scND6w+D!sQHquo)~f zHX`QDK}F1eofuZFV-wNg@qDi0J+y>&OgcO4W-_`PqI`_1f`(T0RDNnnT`A{wX7P|l zy=@3f0;QsP;2;Le1G}U;n17I0L@27?@u+-mAk^b@W$_MXh}AwzbD+!1|C}0VmozeD ztFLqHcg@6ptZ(0(V?o+*hL&HW23wYJZI2!INZrBhU9Z~3ufLlHy*53e9K5Ng4?Tl- zsgCd?2JZTZeHvS^QXH`TmcDwyDpLLm2ia$(YN@E)Z)qnJ-OLTSHm8%TgIDGruX~IX z_{S70t)8~_nQBd4P+Hj1IaLifC6BlyW>_Wr>NjNbF53mjVB<`LTN7LxS*fQI>yj4# zgVuJ|8PN^@Gqiqm2d#(ygVt7esqwM@LF>w%`SW4?!1k=ca%B6ROvX@yJWFg!zVF(@oTp2_G?mOyn$$r3c@Zs*;~UTYP_8a@&YMD{m9g_9N;ZQF=}~ zf0Ga4H$c3%MWaHedBmO1h}dat`wr9G?bjFi!JF<6N&uwpLWvPAbP+PJ18|)?7={0- zjqR=45908$gz1G(&seCwUw;)>Vr3ttF=m#W3KVTfx6S70#Anyg308<6<$jVUK=jm< zXOy!VaQ8e>n*hB=Re#}r#XI7}P2GTe3a@YqP2evW@qOw=ruK~2WkkCvo}n2s(D1a2 zyN{_}mDD81Srl6 zm=3`(MLDU1vzi4$3DblK-Bn0OWd*wYN!+4$4moTFY-v4`SE2fLhoGu4S!0sH4X}|| za`MVACw0Z-ee*bTA_w}el zf4l%ZgpdgiODVaPW(tF`hx>hB07Qt6NK$rDb^=@< z3!8?Zh!38t)lF&|zMb5I>*u(!Ei#F}AB{??B||ubb*J@@qe@Py<;u2EvW&K06-#O>|}S#!D*LS({j zyqtS(_tpqU3pV{)aP6*xu!GdlyC(_?kDzIrSt=@>kk|0WI|rSUU;f$nu)|5T;I*jL z?ruHC8?j@ub|+j-lbW?`gv%ni8r{FiL{qyGJEl`GkP=o=>GRM`#3lE@&C zJ@xMn8opQ8=hB8YOw^o+PMW*+<`D!L(D;4a36;^Q`6=}Zu<2V`KtUNvigrR@4~Nme zk4d?~JWc!o@VjppxiX`t5W8sGFaVt@=gnjV9wB5RD#P;nOB9CF51%4<2oX7dea*ZA-0Rg;m_aq^iD zVe?iJv17E+kaYj{QzyxcGahVGxM-MH(|{&kMnW`{IF}#G2U`ni%9h1K1besO6s&Vz zktuaPbmlWK%8c^6SDb<3PqLDcQ~wxVdsO#+-m!i_>IFs93_~pizYD7rh|xt}sO7xz zO|7nWZlaKcEz|h|zckLwhh=jP*B(GzUdkaX_(C3zd(=I4T~;z9e;%iNffO+>DsJARrqMFRFYO3H8fuP!W^Y9_qSH_IX`v-bM z6*Bd!_QZh#)edJ%|B100@1XM1|A3X9ncTd+|Ao|(XB5PZ`*C&Rwn>B>7zV?PYIMijpmd_~U zF51ImB(L;yC{;Q&s{{#kF0GcyhlQRD!E}op7(Bui03M4SntB-<91DRbGsD%* z;tzV+@69g+guNS$Rg^b)aJjAXDgG8vLz#!Wh>Qz5)MN@es>$eg7Ri>N7Z_9cMz%@P z#qY>j`tr;8WUo2aT~R&7apUvD9R5dLPTLLsxOv6e-ofmnj!3j)^zUokxA~Mp-)$rb z40PVSfxDBNVoU~NkkWg^-I`ao*hrI;58IS~mwj9WEfN!y=oz(Qv zEHes~X*)Ha5;D!uD1Lpy`^O!C0HjAyo@EVQp6&I09>e#0qCDR0c~-Q%OpN!I?Ne6h z`=)qdKqn9R;V#q&nzkn=@nGVsa_~1P158GSfPBTM)L#xyjr2_}R`*TedA#EtwqBeu z%W+`<^1ak|0duFQx#dUu1Cr|N65l#qQas_>vbgj2CmTEw-1Bv~i{RFLpTp%eZMNH` z=*^=ZjUu+|eV%?#79;Jt7=H~xLJ*DS$GYCH1`2hB?flB^mRja*Wa|Avvp%Kg!5)ZB<)%(tqek#~2)y*tzC1Vpp-UMl%O*l1G#R!+rHr)A^SpF!O8!R}rrq{nH>i~^ifQ9$P z$Ur>M9&BU=8ZO7da(GV!nE+it5Vi5`_V!DJ0MLsf5bc4z>*EuTy8=o!hH#Y^g5CWq}gic!Eul-0M+j zYWld#X}lfVzRVV+L`2yfQr29>s-^AoFi0q}XGz$G6ZyI57Bh7lw1k=f(Clr&h}!1X z>G+n1hFZ`9+F6V$F){_}Ib@qM67JH+T@Q`kta)@!B%ShbKrIB)o+fef^{g;P_1_XIIpyxYbMYLD{O_C1=hxN`Jl~gnDJD&|DDtl(Z_n07C`=& zi@0kNz;VWI&iRiZ;E!$MzuMb%n;-0``&zybqnUcshv)i&$x=CBo8YfPCGTeH`B1L=Z) zesv%Ip@ObcJ}+~zoDJfhW_qJ8*)(f$J`G_bYI+fS+y#EuHggR0ZeZJAY6v9sT?rsg z^_o(KV#mxU-Bw=OS*j?v_&LR7p?V@*?4RBAnzOdEN#Tg8r>-AGxXviAMA= zqDb!|8srO1;oswMu8k!sx>B3<5#iA_Zr2r*4*hrIuyMdE*>xhO=EZ1dfvCwOap#d(xu$9Qz(4sUJU1OoXSkJbU8Xy@gi2bc_Iv`m) z=#8CGo-3&&yY}QLxo%7E^;xhaqq=tmGB9SjAXG_v<%fq0Tkn~i zpo) zkm7mj+87I4E!~y1VPlF`#$_hmeN%ka;khQAOy4Q4my{92&Q;iY|AE!HoeL%3b^MIg z9DyNREqMZJUMtjerG9%vDCT7G?@F|7XDMX(&tqF*+dnQx_E|Quak$q9tDl66mCO!g z$_)Yq+#bSLCFmV6yjD7gPXeEAgm49?p!y^0yep0V-5pZVbF<_|{~3lplBN9nAC$`L zBKwc;3`55ycZQ+29fzA0{~3l-u2+1o1YN%7XlULeDb5PomjyDFm`(D7+BPI-wE!7# z_&l z8)M3`@5}QTKDcHLqumr)8}7xlQH?`w6Ub_X zpDUVHcD|-KPJ%u870ZfZ!Ih<^Vu%&v5blGow?vP%wsa4=AZ3N}E2afMJ^q2wxpPiN zkRgVRv|fHx41Kjq?i7|_LC;yV3>f&ePU`9-o}#DyGuVo8(FPs~|9Az1V~sy?jM#&T z_~NgH*Yx{;#^0pBrY!2>tV{Q)ry)_(bKl^`;wM%ZxAf4}a|D!-8ZZFHHl&`n=~eQj zJJ!{5X*88qq>eu`&Mh1iH{x zgI&Bg{c|m~T)g^tZj^*fs|}PR-XDW2lcch9N{=r;0o3>uo%)(TxWgTu0{FImUROlE z;Da%2q}KsSWT%;rsxu-n&*Dj2dj(h0e$PJ0nEN~{W<3k5f(fo#1w-!cJ%N<5KkNo| zTW7minYwMaFc_=TpL`l^zg*f}@Yyilwlu&I@#5X_hdZN`8H>=!#=!}swbs!G7UE0Eo}&d2&G-lJUHc=1E#nQcIqbqvG#7{G~emd-j%Dr9V%?KY1y}r-RbV-FdN(Hw8{O+bfQ(l?dJ`-Y!btHvAuF&AD^tz}Bq)#7P=YQ#yqy zt~`y@*m-Tp>=$T_<(m}V5S_y9#i;v_w|R6|>>H`FUmQ+~9}ta7{^Y(+J*7kh>zcv_ znF%N+=t4&Tog{tOIdV|%ADJrh&b}&9 z4I=sY?rPEu+4?Ls_2aVzUbu7Q|iVz#5GcSST~sK4@%_< z!lm}KlxkmDLXve3KT{mdm%RO$%dq4kixpKmkHTK*tlE1-$a?Qj-2Wx!t5_;p%ixWs zwtST^{zW~ZMly|j$!s@~$fv3&88-ZN8sxc!u7KY}M$}%BEH)*8f7DUI=G2^FMpn_M z{VpibD>+I=Q^O~e8ly-$l={T+`|?~KXbo|x7+g&`VHx&jS|T`VL?b%RMFl=tveA#T zLsbR3=Gp`a*pulT@E)N&_D|!*t!Ai#1(bc)r=9#Sy5-hvST9yZ!^+LPtWYv64Yo&o zFsEb>G!Xu;D{gsDreD^LwV}m|Pug)>IPH67Y!kN8_g|&3VBX-^MGM9_#X*+y*aZ*1 zZ7^*0ry>I8GwH(^oSOjsjftJt7GG!bD#YT=(7;F=v!QNP#{3LX@*Q)x`?5c3$0 z`r%Ln;D$=|A|(m|DR};?e^3+H@I7ue9^B}?k}$~L3#`?WOVEx zoU&0O{mxYwkM!wfegR@3BQFlF@(M~OE?}uS{iMO||H<^eCNT>zb20r5F)!X10*$HB z0A0DigB@T{1>Wa&P7xPL9bo>Sj=6Haw};=;I%3J4Bo!HMsi|=Q2d-%MXH*)kPsl>u zSq%1#W!LFX06SL-rPBpehmoWp4*U~q#(-~|gouX;YY!Ne?GC>NdW?|kUV??H_aAc)9>V9$8`nY%wLH_O&NP#8&7=l8PQ0D zSAtqyR`nz1J+5Kh{m7l->m0TmugP0UYL61Ct#2*!D^tfpX-8Gcwre$)Nw&{n3AIEo z$3WS-m#Wxuo1mCqJuM1G5|$j!vadRR??~<$sgtma!-RY(r`CwU5bfboM$O7y%%8im zE(QvW5!-fzS`W~049L-`FhoPLU*6W`r*% z`TRgdtU1W0MEXamssDq(!q=B3be}LmEnx5aZ1+fHM=T}@S!RF}d_^OO+WFg2>G2jm z88%ink`bAF5XqZbo{{;JAoe<@fLU4KUS|sr^pd!-Iuhah7*Ce1kL{j&et-ppx}`;` z_|)z4&ed>s{M+An^tCKra-^iLNdR{g4{fN_kRLdXbPqa z$4ef-oq9I=(Mra2F(xFXO~_~)^oj6*iBpQ?{HpF~85i6Db=`LCZ?9~_OddNE<87!$ zYQ()?&)3|SHxB(tjBX}GvuyeJm87OR$aAz|-^AjO==rV~P zyJ3%dYdG_|i<;jkZ`!QJE2chq7Yv-+FrDhMzCaNCuFQrF*UmSPkGh3HGt>9_2WgLaVT-&Qti^H8c(VVyra&#{+${ zXlJ7=NCS5EIj!)xSb}T^OM8?9g6B?Q3MU^tBpEE>N*?W;$JEj1y_wCPY=;L~_64Ni2H*C3q7n2)#E! zu@Dib`6ve($+BJMi=QeNa$W07s7Xxbh7U}0nHOXfBoMn2ZoTq335}314BullpLd>@ z`|WaTJC4nXv+?F!yTIm+U)taP0{q4MMW)&!JcGPB%^7t1KeGT9;%;`y2W}v8&f^twLyALO{C8!hJB`sQZ}vttj=gHNUk#&xo6?E~F>ZXK9{vwe*4> zYNx@j8OcVJae74TmNJ(Hq+wzbQLU>$HOA-P!m1Q3!R&2j`eQHYZ%(n_s_W$5Sg!A% zISU4Ht8e}pHs-@=%}r;Ltpnxpy#(4vI)P9nCGV|!pw4Dj@;Mjz5n-VZ#7r2cbzGop z@5_2WbIQN8#!_1tcG2J!B^B?8l%7}-shrzhg7YB{f(No_xqEdJ*XiCz3Ig3xHcT=L zZxecwP8n64$=MSfk6*T0p^VKpm&*Nr$YoR}2iisZv`quF^@D<_Z2#6^30=O%PG7rN z-sEzvOtp(LflA^oVsauFw7aG@EVB=kAW8b-w~yy+y`~QnZD(U#6O@j)4A*`;SSH&A zl^Bgm3|9^Q7kD(|l;~hu>|WyT_0Xvle+hQICL^RVtTD{CMmuLiASZE@rM5ahB!$R*bqw#2kPGR<{6adlTvDD1?Ip zKiIVo{K7kJ5K;IL@ArTIp6VDK8z$x8t z_t5(&y_@L0uaO${$Pn=TC+kb!#V14YcfEovUjt90+NqYTzI+`F{EEkCG8C6l05oeG;j^cFAJ(^XiLnKiZt{{y4Gd_$Ci*n_KL}4o%h(C5f6cKkLhBC#)SBS zrAm@uBtSs=Mw7V6QPM{JO(Hj}!8R3590|-0tcfimGN#9>R(f0enZDJe=j)UWB1`bi zd};I!who}hlbMU@(nJQ~k(ia>$8@N55|8Tw;KTHRG?&a)sf9y_2J$OYF^d9IPFpo#F-R$z13WYV#nAC-HvsX0%4? zr(2Bth3|2}0d}0qXJ6r@gYD)CC0!3duXC-d03i>Mb6${GTlk1Gk?N`bq?TLa(sj@U zcBwFI24~-NPO)o*Z!I0_rPHxwESDJ*jQ8lz=#7a;IE=414NEuB)$`}vo7TgFb>yC@1dJC$SI^M zRq@*j6WNew0Ii}~w|Q@kG~ZhT1Q%qCE}vbY5Y@KeO2?txKMGB)ucvyU?o{Y=I1qJyEaZZp2|5lvcWgB56u>p-O8$ zuG5>7!Wu~vIbe}S_$l`HBE`?XmuKI?)L43L2ESMj|M8F&Tz=6FP_U$B7jf<-jP%Kj zlOTV|c#puVK=NDip93OG#HGq9@hQu$n&9h-8NL?jiZaz{hO9WPw7BQaM&G}ks%WwF z`d23YaMnPWw9z6G#m!{(q|J|QmKy}03!#73j)O2|D&GK11ToaN{189i)2p0A;IF>K z$MidS%;O=4H7AEX&grtM-VHI|ERZ}-Jty0fv^(z`hS)a;l0pi;S*+v>j--K#9-uf0##5CxYGjrb9PDSiOkaBcB<1 z#hy6~#^dufqXdjPzWoy*L*;pup9v*JtP69m)?L3^?7Z=_exN1Ql~!im0VX z85s{3)+I!G(w&Zlwko7{s30JKEwzTV`#Rh?gz|t$iP<2;XJ5?%N@+TfW8Xb!>}qC8 zZi%1HtbNPKwUQwZqS~T`N(9@{&K-YiVSGt~h;(?QCh64fsQ376Y(r?})L&Xm+A?Zv zNXnipgQIn0>JXjdU|5Smo;|ZVvPM5WVs#@aULGu48RK(m$hKNuJ^VH25S+_#%wjSi z6COCS)J&;*r$+J$nNFD7`m>cLa^#fZU1(+5ca+Rt<;0vl`&vJBV=+L`>Ph8QZWe{- zVZJF-ttoWwa>93it~JAgKjtJ~C9#DjQCYaDV4$Kde3e&esmS2zT^FW&vd9Ce2=^3B zSZ$8Z>TFB|A7~hI8JlIv46+T!ZPV^QIRO^KrJd`~OoGF{Vc9vty)l=9%Nz9oK^YfD zuDzZx;g${6y-3HEbUR7$8MmpB>-yb~lY*NuC%U}ny2=gnSZ=P<%g07Xxwa^U@0IE# zeZl}1MlV@oA1-A`9&+o>=@S6IUOr8_)Ah7IQ}c;ld#pDW=Q6cq3+FcKpSGMjoXOpq zj}?n>EEe6W^B#*`g*De4eh8-|F|=OZ?fTzItOkBc=l@J%bMHv(gO)oIYo&B#efS@V z^}gO__SGS-1|*3L5}y9CUjL0Snpm2CK(f7g4}1^t*&8FJUgh3f*m2Kq3jhZE;_w{7 z1b4V-YLkA!`~Ffa`#A99f*!}yA;Oh9dN3z)=HA0f4nSuRsKq}INRndlSq4nxHRz~B zA3pSwYYx!+m7tKH>Cc6U!vmt@tj8ZB4bFcu0spO)ogZJpelfK6$!%E5^V7V2s+a}H z{NZ|{ME=aH;oryZj}5C5lFz0A&r{#~M{3yeFDyI(*E)XfxbG;kS(Rko)K5G{Bh1p^ zXHFCo>w|Hyn#8%j+x8MSw9X&UO8Pq~WUu8VtB6qAl0f#({c~See&8zww(KTcxZ2s( zLqElazj%pCB~3_;E2V9O2nth5MJ8y}B=5uw9ve~Z9P)vowTqD~l#vgm$LmN*2HRpn z{q&&cKc;^Zvz8Srp``8Qp|j)rSm3eS0LJJTV-CGU5F zviH-cgoJMWw;Tq+b(qj{2^_EzKn6puSvqmC>`5+&d@@$uo_H77}?>Ge+WE+ zqVWAeBri#*8}jf6Qz;4lN`e;;Rw23pbDIS$Z53;nRK6-o!0LvS5X*MKEZ0-B2f^Qi zE3{>(9|}o%QIK%;2>+S7`3$;uY%`KBJT&SVwz3Cez01G65XDx;&#R6z*_#XIUE)pStGxkI6XE4ftvEFW5a(! z0%k-VaQW5V%|<-aey_=Yac}D4NCAk$NMeMD_IKbtRneMWZ*Ph+IA>Wo!eHuXiI;l` zvyet6$4LM zE96r{H2^eKavs0rk*c%|_6V|LX@updu=h-S7~Xbkv1<-u^M7OPt-qp-|E=!{N@_q9 zBnK5iBu2Vn1Qe7~5a|KLp$DXMU=R=~>25(nx@#zr?v_RxhVJH`?>XzN^*rl-&RWl} z*FUhY&wlUy+VI%)ftmqRa(t3!i}ZOR`s8X^$B7pZW>b57kg?P8b9Wt@&bDtXbf8ZD zVT)c3<5V#~NAS0pql`3k%m%Z9T^GG;M9oZruUYYKX#o056)(DSpk$wG>D=dN_uTl~ z5-Tq_f^Ug06~@XtK>oP47}UnXTUaCZdLj41(Bt-N`}%(;e2&%rLtdKmG=FoYHSfWI zt0iEfmp9vcw^Oc9M+5I*Ff;6yibJ~$)rV9unHB2;R5oOlSpd)U(85$x8HGv=_zuY? zE3pTaJ*dC!F;_Yt9D@l8EQgjtmn;J6&P5z7Tdqq(mfNwk-WQ(~Sg_{AH<+|iZR_B{ z3I*u}gDIY4plzzsp3|LbnsmOdCE<1A1(<%PHg0^IMwd6Bh-_dOEcnWMuO(Ar%HbPj zA&qN%n%q&4S#P1?h1uKGTZFR*_K)-s%QE=f262a?GM_-2}m$LE8KCQD?lt!=}I6UWbQeF~jo-uBG?k#Ei zv{h(L>7du`lNdLng~x&Z966^6WU;L@GS%};PdZNLtEpH;P5Q_U|8THXfz~+19FEir zo8EC<=B5!QYDJLW&v#YXzo6Is&r#3ZEBare@u#^x->o7O{+uM^a!<`f&k3Q>R?YKH zpHzc6aszKoMf9%FV2!lhp|c|W+-14kYQ`zP6__YhJ!2bje@#qz+I2YO^@cfJn8OS| zT+jW0hvTrr(_+A6TX@F#FmcB#z8^ItZI`_AdFGt5Hg<7V`r!d9u~XlO@$*9OM67}7 zTwjS!qs^3~->S~47`_RLrLRjp>=ATBHsXI23YJ7OHj>wlxVcYm*h6u0R_<$+{;1=W z31CKHU_E`~e*nYTwBmXHJ78F47%q*BlxL>8P+^GGiu(zch2geZ=WpuWsk-IfyZO)_ zTfeshZ~%r0KHbd)!#@j+`TU@iNgvjcJF^0IyGoPSWO6`^vN+Q3u=eM<>fe$4q0oR| zp~rw~EWlRoKtEOK-*4BAxvkw?li};0>p^cv$K|FjUciR)KS);G=ZLhYZ#SC`E^jD% zAI7+3^hGZCa9`&GmltQ;Xhf^;>kI1bud1V_ey^jp6D6q9C1+lgIr<&ED2q2sHq)su zie7#*$Xm2}*Z6mI^jgp}*pC-br_EJagGb-Ibo}VYg1+Igx&gGYv-T`YrQdtX{i^1o zD-*bI`+5+P6k-}A*`HtwVXimlrd{```+}zHp6AyR8IxB4M~)baov0ihPb`GYPEk)8 zWTI$KmB$cBzw+K@uAaZhIvrv9uT5fEFBdxtbUeXS;>RK;u~*d?K(-*v_x=vO zp}Ny!-g}8P=Q%|H4#d~V2&YjrW?X#6qj_s#lD|>z^vXa9OwpyqN zk+BSk*vk`w?t2eb8I;iV!)-l)BNQ1yC{i1MMt9MtjHmvV{O3*sPhGE!&kyCJB{kek zKe8{s*czc5>!Hisj8aI`f_m=x6jV1-nXeUG?6`Qpy*}%Z$yarRdpUYOopilJq7I7Vzx=!NYzUHWy;F&~jXu#ubX@<#dC+(85*#J#qbARd2-bt4vxUd@mHObgN)yPU6 z1NBDn48F!x^G4Lxhp32?1Qg~oW7#Y8kMkb7_oLq14s?K0L{lp(O z6pvdNy_?RkR8VRPt?Mf%1{9c}8AM+)`(~2^OuYfmkr>`)gOku}G`H+7u~BTrM#CwQ z8jpLyVR=(Y@q_19>AaUTsnVpJPQv)5hdT@0?-Ex;8zIst^^u=*L|AG$NtMhXam#E{T#iHl}Hr-*G^3B691L z7_o{_Z5jEd` z>6PWyexg%9V7)Z$)daFpwrj%XX0HPl-yNWa)0fU*;-{e{8$4mto-u=-NlwYTRf#Lb zk;27g-!ESwbQ)E$1t#tRHkk>$xPl-NT(m_Pg;S51VLNB5n{to%GNbFJhu7{)1jp)% zJ7u1g*&H&_H9>904XHSTicbyqif!Z;fKBjh91!-^9y_0KVppMwOjs_14|Ph924P(6MwM#YgyT)|ZDG@{Io;fg|7Po_ zlZr?D@6tyx(!9l~foJQtzFNKCwt*S!A-!CO-ZTJA+RQ3^%t%5??||eX8>03A*Y>6^ zvDh@HlJpsZX-->it0Xxzzg|H4^8}LQA-eF)NGECT*I^t#s4=VR3$)y_9M9x2&kJ(_ zJAqBlpZ$18v|z=2G91fN|EqD6MBcYg966>+-Q`<}z38+_wT*m5(p0kE(W-w#m|prK zD+|h`@w@dE^9E7GFQj&lKhY|P@RTigLu1@Cowvv-!E$s+N9#R^m2ge+w@!UfCWojo zFy`~uzV}RP?(*Lz2KLJfc)4FJzbjcZ%j~+kzn)d}Bqwv|Cl-HbvL*8+T=b@gudfK3 z;2%O(E9eDng^{g~Ote8nUP-ZA$26f4PA}k!F+dh;B-~FcN zXFYxwz^X5`??9KnihcOhPpWWZlPc&rU#~BkbYvtdI>9L!pIR=A)8B0k$tiv#(MnU#XFy_u>?n(S)0JaYk_AZh+o zl`%RUoP`=Uf%VK?cn(bF9>C5;FAe_TDizb>hp7YT%z5i!ko#s~7n^C9md9&NCsrWs z&)YRc-@lhgR_km-&HKp|9~=aVHU~y}v+X^9Fmb2(AC)fi+`W>w<6|NsE-|efam7eC z$N2I6i+W21426NO`xySl_{m3i;wd1~)ugxO|;LkhR+!w1nf*ia=q1+ z>%Q-)kKS7f%O8;Oeuq9fgybuPNf&zE9IE9*WUjQ+?R``Tnwf0K9yYFG!!Zy*NfE$ORkEa+1n~7{ERs_;c?x4+v+5t>RHWp~*7fMuP|=3z zlfsDOaq0r~AR~1J2NeOgtp{AqA`G-htG_}VfDt1p>Sj!lBh%S_lSpsPFOYsJ$d&H% zVaULJGEbHdUxilP+VamQJmd>ByJ%Rg_IFXQ%hg!}I(9^08Y;*Yt!k!356sWIu1D@X zvID1=t7u;#e#nqUUcTFFdam>6^FG&;@`UDOt{FwvPdO@vg`zUj6_Z_PmK zB0ENl{zNn3nK@=s0)P)2Y|z7xcyy$Q3WyizX_J(RHqs(K8OEDK9^7#($-9)p!)jDn z$mAucj9i|w8i1Nb(+AL`^nh0;Jc;3Af07l{>OntKQnBw5b37CT{dFuk_t&u^D{~qE zQDMf_;0wM%eS&BQXBOr=2o}1Nj=M%ws15%H6~y06mGL=0VFK&%?~#Xk*P|?dScp3W zbSP&?drkqnIb-YlZO?d|A`2M6fU$ ze1v|4Ta|uph8~P#R+dz%Gw}J>Pq6Ol#$J*%oTo=M17IhxnTejOtlA+Xck@0?XGkIO zM6>T@H1}zHv5>IxCz6H~+Wj3-V&fR*`apGxe35oy;g2H{Uu%ob+X>LFrrGw8(utqD z$C`Ld-28=3+4<;qmrwI#n9RMi3+)f`r%#AsuXEMHq;D!N#!hcToN@V^N0VlWkK@K5 z-q*Xi{{NltnUFCi_G|Pw%;4NNl)h5LeWG+1I;*5`{WG;X^n|resn-DT!3v4a}0Wd^<7U}FFw275x4pdvA6)C z3dF`!B#WX)>@)Qw-Q~VMoZxAAIvgEpAEx#^-@7-7iuoZUjOgG#fp0&>ph?l&9q}Eg zh2&MlzxDN8cRYypV@L*{?S&tcsAJ%F3z}WN!nPps(enOpO9e{cj9Ks1#LIPY$~*-$ zZoneW!{+Udn+nsKICA}p)%?7)02y&ER-C|ls1=j2T2-Rcq#S2=Cb~U{uRWyfe!h?H zs(-zNpR`#~^^oQ-en1!2uqJ)nBeu9-al?5kZiL{MN!*Aec9@prmJ<-%b&}iE^V<9y zr8a#wTp1$=h9sZT7OR{*!{T(*%HN*q%|N1fk5{XbG77as4lU{n)EE-^L;mo{6q%H1 zTC7P3Hni5X8oo~nHns2LXQ0M)W0?~R625z)WEdJkXfM@YlNk;`JBH{}YuCiqMK|t} z^aVe}e(FRQo$4HB7;o}@pA(p^k~2@Y{Te;3$C48vaw0Q}JG{$jfhXL}vX?DVcskFV z561Oh^+@)t2%85~OK;8OsdeJ^{D;8BI;sJxP{Trs*!&FU$*er{2rzw7M zRO){YwXrM9G3Q7oar`5;t93te&TXa6V(Eq3)wTZmkfQ*LQv&{$n_L2xjhm|R*#9q@ z&S0x`*_K;of^a@O5$ISw{YI*b0qEIfa}L_%es{Qiwaz7Q^>x&_9WX=FdSp<-hTVSIXrZ1SyvL5}F!R{3rm z_Lb=?(}U}FZNony_qpuXq${Z^zwBu9hQwFaC(nvw~v?CZjo4Pg4`bp z6+mk}>gILXW*K<;$yU9+G%1|iNV#SDsQLZ0EK3Fuxo}R?NdV(p=UN>u2Vq+tVX2^oeCDR6Y!g#?|^cskLIzbyWW ztD~O>+>4m%n0Hq;ldSo=`8CU*8^Vn3m;JmV+a~$2E`_5q_CxlY-e1!!gPZSeLyRqW z4NLm0>q6eaxgoCfN-D(Ujs}Vb8!k8gAk>u4plU!6DrI>ECEUpmyrW3^YWiPR(bKGnD7li`DVq z4V<82DTe4clo{3ZAJTD<84V01dXQL-lJs@dAAvhtq>>APsbMw!Kx{!ufGx$QH(Sz&M_Yo6th`>1H|cQcPVg&`elK&|04BG1{yIX?ixq8Y{_9c#8Oz7)RTs45doSFydZTBffXzCh*?qKw1+iY_KCh3$(YbrPk}nO7z?OH}Rl2xnoV5l6fW`WOy!D%wPnh@3ot|8h6Aq3M%P}apmQuo( z6*K{3mT!;pB zLAvF;uK9LB0gnliApZTt@!cKofL~X?!1gZSfOnXx-Y4mwF-099vyb3@g;grRmNK$( zWb$_%V3d?fbFzf9CksZ!`^u;X%)fGD@(7QGQC(JxR&^{sxM9r@AwN=kdg?Ll7KS*? z(CMFwUUEaN`8b?ksq0lwuq{`D62G)X+6L`}S`x)qbiW^fp_i3(89vA2ozFwIeygtU zFwk(%;@p*9YP(jR38s6?X}KG2lduG&30*HKe2R$gj8G98tbP)rL@C0Mt3p4 z?|hYx(?5Pv!VPVs2K`OH4le9J+6SyLoCdiTBs2BYSI~lSM4vsAq3V8>4=`6X3WY~Q zUv`#i(jv**yV2Zk((5L(DvrX7c4E!-Q}ug_Tx}6QFrOR70GwnWxpzDCbjua~d0bB7 zw8o^|-lZx+CHV~xN(1|gy3Vk5-ezj2BLPz*YkbmJP6wjTRfL`TshL`MkdHrvfSss< zFLnao4`!5`T+%m^`5n|x1h;>HGJvDt6q$XYmaMGj{`V+s&$ql+UtsNGk1Cozb=`qm z_>fI}Di;Fs2qOigo8j~L5qtZmYJ*#^;S9a!5#3u`DYH_Oca4Zx59}&y>wh}%H%!?U z+2WYyNyCZ&=@7~jC*}v1h@*GC@~IXp8QvxeNUWKOmQM~apeLiMk&b%M4qsGV?C_4t zn629@H8fhgF|(``79wtKI_aqHXHWSpKz5~<)HEa(iP7>+rvUhI6(OfMlEvf=C9srF zlR8*Ab2Ro+PDBBmzSuVd4FE0RizT7Ij=nmxW(7ipA~>^wUW^%#!=W)eCsleQ%{)Bz z@+GgJBcE$;^NX{LdRWo!9^is7{Hv$O7q9CJr|1ku$8SaJYETSUgg}8+!S}I?;)*&(YDTF(KAzC4PP0$;Q`H z;jpeBiG#mMIc4(*STASty4VwylFk{NohYkV<~;1Qsp2bCPIBu;0d-Ij$K9RD%w6r@ZJab~l>xkx@?$l7v9oQv1P>?D`>T20a& zSIEU)Iyab_iA#?p5BH15I=o?F>9HpbRg~g8edAStLibn&bu3D+hn++#F*t&pLi(=l zZZ01`*jyBQb2ZI7@V3VyJN6~x+GCAdi<9j#jlbQVdbPBb&D9~_C9TJ4XS4)_iZ?1; z=A5#g^tt7%I!xwms4CSRs{XS}J*sBz*uCYrEv(-j)-(4B!*9^)nSW7T=?A3{ijz6g zu5%CSq?g0ZeE#Rd*&pub=nA}FEK{0r4tK)WH-EG=o(J6KrS@*L+*s8%TBo{X#N?CUPaq7b6i(W=x zdWzw?@)LtkYWnB`PO`Kl_d!+E-KIp}2|T%}zI}Qu(~|A}jj{WUkzx${Qv~>ahWOb( z9;A#Xc|kV)=KCKxE$8(5?z&@<#*TOXCcPjoT$7X#wjjc3jdxxhzNl++%^6)LGWUua zT&kY5rTV>7N*b9EK^?C^Y+lwF42}Qggnbe*v%$tX01(B(^x{ z4pU$%Q9a@ZD8J%A2k4XQ>b~mZ%BK!?6mEz$w_=-RdVLgpP6!-@$fbGAd;XqIa6f|o za{VPsx~>5CWwGt{CfsB z@#!Q`Z>fLQ+#AteG!Z%mPqkG@k~sKM$II+Oz$;l)MVQhC++}A zH|084?R=O=9~QV@AEaO0)W?mv%uC!{X|FdH~)VS(*POqrNM;0HvX5qt)%-Qz`fI;+;!~paoHBBvDMw5oz6)lDbxLU+V zL}-HHs_gX}Ub1JmZ`f#lbW+pzJb7mM=)Q*PvoAtV-_@Li`S%O>&#t|;Z{(TG(CXfO zO^uZuIn7>mGx5Cyg-WevMxIXc6w(7fB6~DyIUyKVY|U5=)la_iVOL|uxf0EQVL2az zbM0IhyI2w}75aVC9#X|TwU#&{1rYyH1fFDu`5{L$O|atBog?-L@&r85W8oi2wz0^f zZ*=F244YEKj-iDK{8jmKEVH1!a|eiOsVl82y7tRCA?SGS zJiez0=R4u_a4m3$53Nm=Ta$io0bag0VsO6xMM4K!Cpy!*{@h-ox){eZYO0w&&-If7 zFs;28)EaS8-<|w=i}6I=H449+0|)^~7B;F8G@5As>q{)>YfvW3Ej-}>-QdR*)Ka%x z@@*S0i|XD=IdGeYk4H~gNlDSJZ%syVl*YkU>@MCneH+%BAES5rDI^&f_Na!~bo=;k z{jf!@-8Rbh!)1rsSdQrz8Qqb;6vtZhj7#s0(IySzQ94Du=K=+D4Pyh^R^+Gn<~erD z(Ve?^giD;u@q}4rt}_+%baRer8l;Yx52rKRkQ!8Yy52seldvuqQ4)Y>NQ0(RSU%`& zn#lo7vEpedi1n+L-eIwPD<*||sj50Oo39Qz!e$}^iU2tiyR(Hm-6LDoO*eH@Q6ZNe zF8Q~(wCnk?xfBn}{6npYASX15027HKk3oBxk|AP2i;aADZ_5BMnD06>&TzG6coU#2 zRt@vqqWfE#^NDDfk_3G@E~l~N?Qq0pP=8=8ND?y&TwpTu0XnW+jqny7AB$O1MQcon zLYm3KpTqy~7-;Md&U_FKf8YhW21Y+(z>uAtZ%i|m&^`KVX53OS*exw5Osg27a!F7_1{F3+p6Qv4sswhZ07_AcK`I+P!dc`ptj~)y zkWW!Ib=#^EKYFtKhIfc2GU(hMT_omMtLa^o+pKqp4t1TlZ0=7|j*sw%D?xit@y&1$ ziAqz*{6!>(Hv2W}fWwHV)jlk zZSdC5aXPc{LwhNP9G1?xCWy9kT|V&~v=HJVq`%ofV93)5XvWHvL&~u|bdcFx!92Uq zy?aMubCFhPI&o(dHLV^N=g=@<+`iyOs>4W1RhM<98?WN*IDZ0UJlL(|Nrc0bA3MRdw#PcX=WPju zO+JIkft@ARpYBSgMN92gSdk6Rrn(>WnKLW7?a9K9UumUPHm15tA{;uacz5czptS@S zAFaP9Uq7K@VCmsJK2FSPB;QMH$`ZMB{_j7R0rf3mu9#ZWB&2v^ae{8_fYm0m!CJ-S z_zLnkTY~32#bs*wyk+SrIi93|8kUH)&){%;X)&iUlCv6O(%1aqqN z1mN)7uym-CKJQZ(LhV5^nU_*AE3b=K&D|q%iPP|${3}M8K=hpj_Rq9H(V-=6pRzr# zJmNu6+*?Z43Q6)`7NFft;w~?nfC)Ij4HL!daUo^{7`N70mg#eGALoZ z1JPQ9Mk+5IslLmH1iiZpHF^m4W1YzG{EQ2TaHx6oXB->xwU=$VlgGkM99*EwIZ2qe zu1}EL_jYql{Oc?^zYcSFg#8f%GSOxG<1fS#$0(gu;=PObiJGo|2k+@=Y~ojyR_IH( zIwG2RL+`^uO>nY1MbC7ooaHMQN z#mQagAdtB3TvTR|Y^o14SYd|eEt+(9R(79vKM<9OaQCHZ{?N6+J)THRVqlfkegSy( ztri8GbC+9LId?&&(1l|C^z(#|fAe9bi&2^`&bxn<4(9NIkfAW?Viu`JSV>0nkOw1Z zcflCauso~DYAHP3wr>M?0$c&EN-#n1bUsTj_>}`Ur(gpV5BpgK8M517|Ep{1Y4Sm= z+M-b1;AeY^`y}DBP}JtP2s14M7l1y?c2i*$!6#`k>D)P{hF{+)&&5uH_pY$FAK)o2 z9Ap1(v;pgJW5r(QxXl6YZ&pKC$Gur@EjUbf`j+{3plCL+QF!?b5qnDtV)tStd$Q0Zcdrl&r~JeJ^I!i0?b zr_;QNvsfR2XKK9ESQV30bSO!`1+uWTTZBYE+#KPjokU3CcDR-`{$ukJBvG~ssI#?M zv{|C;N=^6Zw!7Z>pe+S8!yJ3{FO}seqnh%E)LMTp@Ael zF*JfK^Jv3rD(5UZbOD}dQ6jdGYy$P|2U9OQ?I|6JJ~*KC+{+!nfg`GH**hGo*`qIo z9N^~e1p^ZsUWMl#>p9qypRbraOJP9a4*GsE)wD_jS=EDAyNU4#Ohy9ZzCMT&lQgg1 zsre_mqr=KFo#&@iq0DBtS%RMeT|rMi14(Eh@sx&@W%Jyp8M?aF5|L7gxe%d-()QZ+ zWJQ9C#;JlJV$5aC3E_e>D*Ws%#)kI@lm=nivkCdCCGH{$`7kQ7k+)e**i7F&EqM9^ z!?;fK7Kr1#pkgjQC@AMDWZZetO4~VsXmHt81!Pz>u|J<4+J84jr(FZl*29zSR`1Qs z&i$Ihy3+#?&A8N$R1*rBx5z}4AuPm^mOUREkk7UhyZ4bU^+Blsz47j zt-CU&eQM=ezI!^JUu{eID-iCP=Izxa?s@t_n4$X>h`7k+y)9*GkRH^qvq$=Lhh}my z`6ilpug~qSgZe*X!_!r;G!}5iNBMll02r@DY?Vl}A*mk~w;n?pR|~aCa&uFEZ71K-MG38@iYHn2H2HJd7@Ylum0a8U%tWOqtm{>?GLYUfa^32C zaJ496!fPnsv47rv{x|6Qjr6L48KLBI#wC+LJlWfO=b9;K4E8B_haWy^B=2G7uiAL$ z*AK`evnNAyYQQdgqQ7ziNJ)~`|6mmNWtC@UXDJpQH}g2kn&DI#PD$*-q85xUfYD?% zRB&4Rz@r!5uAIW!lP4K!pQcTtHy}D!-K}|EE#Se=G~A|oQ(i~Gp00OvptVmg!<^WE zqI67^dyP}aF78J&9EGS-JHa{0%b>7MOH4U(^0DASLGX%4sO;%qlw7ga1z@i`etK)UkteAlWb`o^qYz3t z<@VzTQg>HiF@at?~FZdR*cRY0X zyS6PMR1%zVSl3(m>}Ne}iZz(OEQNidtjPi#78ZSbHowi2A8pit?kh=sjQ-S3oH|$t z!BTcQeoo`9moYRE@NSH^93dw*gnawIz)*_~(Vy{Fpsy8;AV}(?3 zVxOfrosir({rT8f&sf8Q%CV$@Jh#N_>an=8q~lmTq8EjaV*me>>I*&{O(*!enuV^k zejJ`RXkKpXeUr8^R0e`r9}~~07}*}Zz1OVhI?o2HPR4q+<}*HkVAntiEPufB<_WMn z$Fku8&XPG41K#dK9bhAIOt2@0XJs*xIB`KB6Y>xRuwkQ`f;=NMqE_UMc-;9`Ugloa zFaZ7bjDfWR`X~~_l0bwU;|H-qLC7)(&-dJS1ok)z`B%Yvx<<3#OGV_STaj=@hZi4% z%;tW{Qc4NZuj%%Y@;E1G_Ss*UmIfG8ukvguGlw|Ix>ug{Taw! zUD&G4@AAK!)juoxhJGk-4Kv+7qKnSP9_Ryux;?*l%j}a*_+yd=u8UADUiLq_QU=I+Z#`oDH#V7yc?b&V zT-wxz$ANwB?lXksy!*H9SU6}oMo3`$L;EgOy3`=3fbc2`CJM{Sbfo<l|_3b8oMR zgDMo`oiyz+rj2N9R|o)&bbD-ey~A(Ay}w??&994Vb#WcNK3<+S1HDSqoWGG#`(@j7 z-iU8tssMg=fUJfcl9hX@$ad+IbsD~d1ypeH3Eg4DBi6AWO0 zi4lS{NsXc)VP}dYR2Aer3+yaEI{3U56v_g-7q1}P_mV<5z0g$laB4({71E>27aj3tw6|UKqa(vx zsW*ijK6Zpm5>zENdVrP2@j(VCjrpyS1AGdgJA7C^o|5&?*z11rm~qlkuh%ocu`luI z*p9M{k5`s+UB{T0{_KLZ@WccGRWY_xz*IVM0Svb$fcr>2_4`~2Q#&xJ4V)jIybGrb zjX<1Jfmo0J{nHBtZ##Xryj#(*gm8b3zdEd7Lrc;*a6TIoLygn5A3r4297zC%BjJ2a4U!vs{-}G@}2R zG&P@0DowfhHKK7DdHYRX`)W&A!I}z!7w7KC1^p|D_;M9G+tsva@qRi5z`Gf>2hU%U zmXN`p0pu~?0MW0vD-*=Q&K5W?iV%JPU09Ahpv%>ah+O3lqu|1)cDTo<`34UWER~Gw z9vmvZ9w(jkcmnF%Qvycrw0;{Epk01Uwou+OkaYwUjdMSG=&B#$ds1X3x&H4`;^@(D zwF;>SA7(r}6*G9`d-c~$Jg4TBJc}uzqw^ot<<|ygtbBrwvXCE6m4%#gr;<7x%R|ti zL+k6LL*wTa4VLvRcpK4+1?p_N^LiFy@-xM)P{v5~k$6QLVbXeCpqcly&y5c8(aYPB zTo0cbqu`;Xa?hzpbhF?7hMCVQyFgK#6-h+PF&R3}29w1W&_rQm{nqG#zO&^;*{G)~ zpN)yOvC`Cl>*~*hIpsdh;hx&h4Qm6Oj%U~#9kMy%0^$?6!%k0CMUL7hQMFBUix;Me z$JIc1guNK2RCmd(aUg$+lA3f#rjw>=phH264R)>8t6tY;Z_J}}bN#8QbGW(#@)wQkqxj%59xCT)`U#J=uK7gGhHAi^R6fvAOwNY|5@GVC3%)Z z4uAZD+1;U7;rp|E)yCrACigK}4n7C~+fQzcwPZzhC_pfdWB)43esEb6GGOoS#dzIT z{u!L))$!~@G=rOmB$v}z$(SyZbN=Vj!f&-FxNldNA4h$;8uZmYTw)}_l0e?Uu% zsXBPWazf6dFmFzQ7p4YWnNqG&{)-)2W|A-PE!$hY=!v0&y_T=fQ&?|r$rY>GJ3ne) z3&*cmP~TsxS1&2ZG*)X44&CgZo!!KbHe_B~$^r0-dH{GaKO4hg>SMS&JNwJ)V2o}| zOXj?c!A6+?GZ(}0;@Yna(4CZYaQB(fBNjs#?{dsr)<1g-5_8{h1V&gnpz!zOj~DWY zC}6uP!N=7&uw&O?B~coFTiLOQ1V4rHa*LRi5yQU5GLcys(GQWV$M4In8wg2H1iy77 z_By;!sch5iQ~VzmKufU41^{pfhqvL~G^H@R-gQ!I4y>%8Cb{uW}YgS z54bG9R_NiC>&|i0TKsIWkE2Ft`bBdp)B&ockW5*9amDT6Qt!>FlwY+Ad7n< z+#lva0<@EmI`_#X!01dCZ>Rg3{$D>7TK09`tFwL3rY#~u7&)BWf@Xt@r}~?`eKxWp zZ%A4Ksuck|=nwv6P4by}5Rd-&OUBBP`d4txGIzI<;O5?$y0ZlB*+FtxJ{vtFl1h%? z7z@vQR1EDZzk&(ZyzaDm*)`p3HaSt4(2J%03iQ>kK18d|oU(;E0bNs1nai}$^X$R- zLa5gcr%Tl0C<+hvG1`Y)l+AJC;EYR9YPlCIy_{8(ZY{cu2)dAQ&vxxdEQ0tA2xErr zTAB>0HMt8gEp4y4#aY49$NkS*r>j?K!~Vr3))Sa0Xhqi3E|^ZWG0-IlIIFCY3-;e> z25n`iG!MB?4g`DmgZpVga1gc}Tw%sHr6jlwgn}1p!*?(Qd!$mJ&p8muw|m;DsbLVc zUmXy_O^Qj7RZss%4ZxYoe7<;+`-QojhbGR>Au3GLJOwIKusL_4ZDbVY^zvlQ+NeHi zP4ERRU_}Es`?GPpN_uKgtWtQf@l3n9{GE`rSd>(?keA!OX(*Xw=M{m`+uy36$N(MF zAe4#1SC0a|O@~*L@N{Rl0>g+kG}Z`w@20-b z$>VfMHO`w?{DAIsmUxq$HU&m-Cb=K~^Iyt9l~O|rzjle|)C_i-seA$AX`;6v<)7ER zx5;6E7AD}e-3d^ch=hWb0l!Qm72gPGp2Oe#|KPcy0b1r^t?34aG=qWWpC7X%03S1c zQZei#W}c(+OR0M-(@!*#4y!r*{{R{*Vu3>l(d&yP}D@2aa^w9AP&KV}U( z&k9AEPU=GgkMv$m`<-<1YD@=?9?GRH2Ojw##_!awJmBd$wh7?r5nr1gHnP4dO{F+^ z?>$nyr1xR1YF8;~+rat1?#I`4j_o~7lTi+@l3*emu~zN^Jh;5WIiH=%1u@6T%RK$l zWu4trjq3d=`vmFk^&5lTQAZpfk5&F^isz=tPdfTy3B|sBcTXfK^wiH2-&@4?9$K+( zG5^?oGAS|Vg4pfke0)5r<2BjTVK5%!HW7!KY9CzYa_ek@aYyYs7rC6XZ%T zR&5izt&FCh>Bqld8+B~P`?`K@YY!*qFjGr)8@Y{CJZyEW)?w;cq@T7ff7_T1ITZhC zc-)+3k-pQgWZsM7guIZs47*Lr!}2;@a_^PiGP_-J4_eIpzpuyt57A9aB+L%u#j9+N zun;s`jo1%SF(Gn$?alJ%VyHY7+!N&oU;{s#1Ed11{~=qb!V+28j^4hHj}kv%)gpWg z4U!y{XcCPge$l`>(nGxm%em;<0sOdAF!Il$b%UsQSTFtP-KtJ$3@V8f* z`-{E-e(3hts}gle|iws zZn|lX8i!Z4)h(B8Dfx(K=o;IyoDKLP(MvA`#}0)nRaZne8+E7E*Mz$!PPD>0r#piM zVGC`EVnI?;BjsanSRMJ&-e0tS5mV|7{6+S%J~7h6+RJ)tDU2Q)HqYVU^*z>MUO9D~ z&}@d{i&l(I>s+F(Ufafo0+B5EX~XN94Y6pJTZf;k4-T@J?_5{a3*l3T{7t&1GZ}&z z8i0E95{(a}R^Efgd*b-02xlCo8oukJ)ahL z9;DXsFt5Bxw0h)`YQ;0Bd)UT__j`GAe$9ukS#CTwVn<{guKYr5rjjzDpFOXxLlU~) zUw3%CVl|uXXsOZE?jb*<*&4iHYIMMC`EM(MwZ7m&vM_!1O>ZijTCd`PGb|zqm4zSEssRN`+hk*N6Q1OrhBLX=3C%Px~ zo5w4sZ>OJ^52;(~nzajb9Jk3rf?YnrolLfA+C{12wq*t)nqun+D&clF-hUn13BVX*Fe-P0X$zbk2g~!&zd~X3m9IXMhGvxo$zh- zb@|Wl%C0LKP^&l#tw|jeOqY6kgBFN{kKf;@fF$7#lUH}AJQ}A>5^n(*WLJuDj zP*VwV3U0pn%z}OxcQ^>w^Yx(kPMAwhGDV%vAAzSgNwZ|^&J4jko~jFPCAdKNI)9So# z>qU<%w>xR{cRdp#4as|7bn6!=xjmV^jut#XHucpd#U_;*I9rP0(^$+&u`eETq(_#JcilZ{*x{^~S<=3o+x3`4{vT8~HRVM156)#zb71T!6c@%G!Jl zqJF$oxp22^6gx`ube=7~IH9g^gLj_IU_3i??iJT%d{W0pH8@9I!#UPja&6SaWHq4t z+oiVj!jb0-lS2Nu##O-yg94A^mGUWceX+XX!I93Z5ye6di;9UR9_=Iq4Ee@;PGO7d zN6)C+RwvppU8cRw-Sqmd*eP=c4R?7$?12gSaq6Kf_PbJJQm2E=6I+e1Jx_`)koDP= zt7+Mx0u^p^Eof0xbcyll00Z5nlNFhhrpLBv zgyNwR|6f_G|ETGLMtSqmYZGF>o6+pm)+2nxI{4&bRqf`*wd@Zf1{|6MqP|3*{J{$o ze>7<8;5Syzd)j38+;-m5EK#=qd`KXx~_Tq2Ix_k}jUfjJHSKyESd#-zd zHWjvCmlZ9)3_p;YEy^WOez^cFF>C}(J&uOF+bxxfws>Qh*y^QZ@GUS+4Q7- z&Z8<|9B5&olYRc2R$68hG2VXER`uX%=#eyig^=2mQYZAwID9G^1j$mW?_Ji2qn38G znR>Eu=&eKHqbqOUtD%#2?H;L*%C<0V3{}F^+R(0cR2GDO*em-bR);9> zjfuPeVcD1;3|3Ei06}qjgkzKSM{WCg6Prkeq$f=KVGe>(QOZ{a(IWZv(i7~qs&Q6{ z)s-ldrUa}TqmHT`6a_c;2rS~E>r?A-GK}w&RGl^z={Ml|SK$TRS}YSB=s{KrTwuyo z54)a`8?bo`Mox@5A*Q+>ADy@#pNC23e<1kXio?}Of2!p&>dmb87|Vut8+v->T%;7U zXu9m8-g~%IpaxMV55W(yUIJQ zb|()WZCeqAO2+AH1c0^|2}xnUBs?VSTg1nEbm7By*jE@v=pNsu_)k2WG&m__M{hjy z*g(q6MYSpkViX$IC0ne7@!Xf$#z+oi^EcOx?*bYdgy3-f{vgR5?av~T#RZa&vl3*t zT=;ppl5#Xt6T<0*gwxfGIfc{!<83Yxh>=Gy7I2c&UatImtI%8hHDyDLve%O@9>C_E z{V#eHy#DtH-{WUGb~PktEaP%h$N&C&4|s=_m0P-5l(jm&B8SU8>y=!7*S5eEqp6L3 z)~p8+)LAU%)`>3a8J}qQ(sbSX`mOq#?(+`Hau2d2w&=sJl;b8|Oj6{6|A(^oiiX3D z!*!>qQASAgmIxwh^fDMkh#o|*(R&Z0jvz!Ay%R$8PIMyb=)IR{!$j}>%zy8-*V+4G zpS8}dn_0`n{N{Vh^OhlBbDXl%fGvmB20ps832o`wZGW`oA8Xv!VCrybd(fW>bt?fq zqs{7TZtyz7DKq?e^LA;(#+yrk^|1Vr+K?Q8)okgZzdSd78ruyIKm)i)>*&N+kHsBG zG(Am3;7&{WU7QAnv=|qQTd`MrU%w3M%&=YgYvb?mA|_Fk0RTAc1j7ONRne1@M!9S! zxeUn9{y>IRIuAp7v_Jx&KI-f-h!@D}+@5AsGV<5|iPP}IUv0^vwyUkL48$B5t6Wa+BvXL0*kYNSvnqp$=r*)=WSj7@#@`rzK^XHel z#RM)UZht?z7~7Q*ng&>2eMmBdZ_n^nEaRE{DyRWLMq~mr9pp+2l#+_X~yrA=t>b^Ey)3Q{u+u%GIBSXpWK>{Va)#@yq`G<*CHp_oc$ z9+>O29qU6|E_JFquP{3`|c#yiCqbgm+Y+uRlZ&T_#2i0lL&j zbhnI=FqSpxo8%K>L|Lm0HLc>DQ96)~3?m*x)CFH)L`1Hpq^PV_>w#%V=L&bWO-1Ggjt2l zD%E?(fw&5`F1Yfy~5BlNj>+Y2K0ImiqsRW|KMC_O!8|Eh@nfZ552PIM&ZzSFP=)7`__8U6e>5?hu(yF zmml96S9~aZJ)0y+AE21{C%?41T-oSU|3drN-@1)$!J@EFKdE7F;o9C#W1J^tD!Xtb z|38r!nAw*>GTQ5=+*WF}oVxAmM`JzEbaI~)wcSR`;9kLbA!BSI=2a?Zek-TnbCIv1 z-Wp@@mV8W9UrYDXL-|RTnd)KS&Vr}YIxYXw`r)!g%P>#FxA(!6 zf!Wxvt#!8@Y0m06m1|lo4QX04gc`Ufs)syIS&VhLZhmp88rIP9k2IjG3TK$uw&O8U z^i~~~bTg+}4sq%rbM?>lY$-rWt`JyMAP;V>|JGci{-5P8Uqb8C8Na276T+@z&I>;_ zZ*OkU=Pl}0zHHG`#@Vc)geFQ)MFqojiKMk_-d4ro;{Dt}_+BRgg zbRCh&{1;34jZjJQ>38+ctv5Fgy+_Fy>afFyrc-jgRkH`NWAd~djmG~y`~1JXUNf;J zUK32l@Dvw=r2{_lodoV;_)xMzcUL117)jVX?qp&SQ9FFf9bJ;)^ebM~XkqOb#-IjteE4xtvLz_RmgglXK? z>tV08cM_5u*;7N?AC1u1G7>%55$^BO)lG0-RM1-u)YGF3f#gP>nKjwwzh;2N$S=ALXgii7Wqx;oI?i1H};Q6Jdw+r7a}cbvWN%tDPEp;d9>Dv7}cpu`1HV zAN6niiWYz>%SG^jgbw<_Yx`PtCs#6o-asiQEl)x0aVmok+2So4cR$)s#ikBkITGa0 zQ2cVLtV*?e(KC>mkJqOI(}t$d_oH88_=5m{x#K6-w^szfN4-;lEjZz_R@|$y2yZX= zl(4%YK(h}iU9S7jz`q;dr0oJQN7hs{)`NDLKVFnkn>=ESzQ+O8opS*x6a>GUK`E{qFB?E|1Ae8ujZLeK zPa*ZW@f~4SpoeNPZVNk!KVRKcK|2rO5HCkkwH(4(09C9i!pLzU6J3cn4o??bjdfe~^1cQM2 zlJT8w83%Ip;a@)|!xR)P=c_IE)_5Rn+R~S^ZHq!e%x z(k$UcQs>Gv`xma+MK9)V)8tfdFs#R=TtIE!TEYIBxgGGb3te+MnlzcQJ|!&aZWj5b zg%3P#Hu9J5`VBfI28@#Y_v89jmb4$o>&MNXuhSA2X=X#7kl3<$u;5z_iPBke=a_Q} zE5zQ0#nZ~9>*yOzP6cZ+wmxs>ZW&&?uih5mCq$GCIaJHvk5-9OQeut|35V_%sT^!M z$jaXNA8iyjamNg*WHdlsKis}uWlM9sH*d?^E`1r&BxE9E*#DRDdsL;zIUU&k+K8x2rmB$EfJkK8+$iv zMAVz63K(J9YmbxgN>%Df3w0T!!bD?wcxiU>;;{_-z!z!{1tcRuKAy#a(+mA;{&ifL zf=?a_m)eJaxBkz=yUe=xzcggrgZph^FySv3YAY%$7kmCa=1kT53qC8VI9`*VfHyAF zY{#a()a{JVL`_UTrgGaXhgK!+`u8n}<%`3>vAovdPn>y8tb>yGo~8NOS4<#s_dL=h zlvhY7Y3`t0K6$=nKCgTbZ|RS}0%}q50Zu01o}uY2&H!txo8-N;(xjFAW_v$_`)5Tr&bCxsLYQZ$jRN7v@=r)&vXbJqI&-hXi%yXmon_p+wbpVjeRodQgWlH97 z zx-g%*ViS+sWTwx++-@N(5YTU?*B_L%oL(R%AZhl}#-c63cpM4Ew1VfSTQYZg?>#s6 zYNZQ3{@>Ek|8aOl349gEQzUFLM9}QbR^zmmhHEp0mdU}tn{%iSpXxVZ+N3j z*J-_b5Lsg%KazLyj9c~c^rv=!8)k!Ck^x$B7w&(p{{ZybT622t0?;w1K@#wUU;Z_% z1+cBul; z@2_Ho&T#qpmR4)aL@G}3#Ge*K^0P;bcaqA}tu^Bx5*iLr{GcX+rSj21iWKTiaZ{9-`xYqux&CyZxcryI z7B(wzjnX?uqU z&lS5>pSFC|`T>yg>hJeVbm&=C`BK;u|E<@Y0hjT(q#p%(Lx6%=$E0-R=V~TUC1f%I046Nfq%zd0Qy$~9$px2We$`)26TVzNCXES zrM=V3Yb^-?;&AuwG2+o^GA_ zdsGJGB!4fQIyi z4a_-Cr)eep`a-02CMWpjBDbfSP4yQ79E$id<^RDAFiW#jBGYnEocTQYLq}pE$V&xe z&gR`>u%}&-CGivwk3NtbJ6J0O`WCs6+OqLQFiq)`$jl@SwrF-ywy3;A&tuF_@X3H< zQOUBXHcYj@SN(5%8{ke@!0R!dPC{}Qj*JP#fHp{J+(~uaWblpuUw_#PR`%)z0Aqo@ zK!;d4tir3r;*FJ8Yb2C4FZifESdZy?!}ZanM1@T8dn)SOHU*2dwD!nV7SsD{#q^eg zK9BF1|81V7iaC6LoQ%n&ZnJ6N+>OYVo`u6NUXEZ-%)Z#P_f98cy3J|)9!+4rKxo5c zj&!s|8j<`F-c);=^_-z_?U_jDKq(iTo5I->Dly}|OoI3%bEB9A!hT{&bo!Stb`wB{ zbmLtm`#0RmDowSN1l6x52jtryO2LLd{_NYt_V)rXWcQgt>0^&B{Td&cNV!hM<=gn5 zp`Yu?>0blZr8^K`2LKmxI z9B^9(y%LL+bAa{v4H32HRX2r)ik3N)k?HCqP|9U@bakyHeQ;yIy4lVzbqB|F0X?hC z^WVkx&Bbo}8*c!+5?NJ^q0?=nUgi17%+@7yXfJTP$o68*V z7m3MUt8?NZkwFm$KNKz<00!1tUW)Uy_KU@e5(N{)$@<>k!ryd+^mS{zj+4Mg^~0t9 z;GkmcFFJKfDPXo6UP@asIQ4H;KTe(ipFZsPdb&6BW~!v{wt0FgWG;LgFDJ}0Mn{)t zasS(FJY1w+{X#e|+7#(~{nZ8K9n$N+)xZARah8PMyauBZ{M*0!g6l(tXLVQBu)VO! z%h_wVwI-!Pg^D>MO*i|&d4`32=8+$ba*eOxh<73|;(*%NPC_W+(l#=^4MVbH7frL!;BPEZ+5kED~=DpS*uv(8EMb>p0hbA&J|j)+vcoqozb5 z+0rJSp$)S#$J~CR!kJiY_Rek#`N@L5Ej>xG%`(e1etI(ZU&)4mF>Y`@v!m7ZfBvjk z*{IFZ|J|SchVf^u{_|(~IT^|o|MO?(D*W#uZ?OI)nGhm4$?n|iNXUR$fG0gC8tT$_ z93MEt8Aov;?l+)Z!ka5zZe#aH2G2=wVARq8%hSUc)~w^^#}IxvjDQDA0+T2qaDbz5 z8P}x|LiBy0U=_eq7~5$qEy7&@5uZ&NIs$Rp>1i6j;Ky^1hjh4ML3I*Y-e(5H$InL& z=Xyj3rP-I&+P|4#3w$KE$`=7!?#503+pZ8ZyDxt8sE>GDQuqalozXixNisp2^~n0m zO3#9L*Rr0>I!pVlXYGqjwe!KDAET;pLX>|5b6U7ZJQP-6 zL@j=#nWxv1zNb24(5wjO&(EJ7K9AX_r|(+Lv3+eflH?2jQ(fgmGC#kZGe?^A`xCZY zI@iRW@kt0(c-?|loecMhOG{jcM>i!trI;$?Z*TlnkEWWaUF zu>o!1QQsp63 zq6b7y2}H1m2acu?k}xsuMl44g`3}Tq0ftqxp-%y-2-~`V>kVD6Ab&QeAi3lFTdVdf z30QFH7C@_KKqbm8(W>n>{pPm`YLV!cxjcA#S=YyP`LUG637P@ z!9AXaxhlK7G!Zh&4+YU+BQ)xog?1J?%{5sIIR^xZJ+0y={4=d?OVJHM?^;>1eRY)tRntL;*RS zWnf*j@{$l601k3^inh~WjEo&qDNQBW8RC*I=tAF4pw5SU(~Fp4xyZz_bG^ zrPPUne#f6d@eYe~DB?+rgdM9~yY*IGUAcfH`6#*bF%HbCEWUrhX3_ZXTFRO5Wb1n4 z?o3_M-(#}}ddF6rg!kyOxT)mDG2v;gDypO!&$e>y%f5rHgKyoVd#jdf%U->K)iy!bH9}+}qJGdCLZkV<=K#i5s zIX6eMujRSF-%meoH7Lh~SbR-r7w*xS%B&_=D&FQZ+8ZT0OAl=_ZuPp7t{=aSjXFRx zQAwCwZf-xc%`dn8ht#<74@n5v#z=Sz4J-;#51VCj0r1)vJ9Nh5-}Wme){zLe)g;PKYuUh zpAhp)i>H9BK4Bt}{a!&64*HUt^GkW8+Obq&fHgfu6OU?SRNr-k57$v`oh-!+Q$_ze zuZKgR_r=<^g+o3txnLTWZn39FQ%i!$PB|7h+BP9)zoFEo#SUttaObPNCo;M0Mtr^e zbSUOc%tqMUl(IyGxQ|OE(NQOVPNaRFqlrX)Hle&&Mjx`(0rlo;B>wYWqoKygC_Wzx9m2Iy#_j#L)jL1H%{eJ;#4oPNX(6YS z>7cD8>+0h1wxmxy%0yq?aln;f%Ry0*zQNPhKl#7vve=XY{!OFOygd#75ho@gbc;Mr zQuL#Vu~AuL^_8D%QPKF_LbywterC~Z0dK&Vw)KDZl>Ud=TliG8?Ek~;t?oE=!7$zK z6ACuFJpMC#1#hlZ?+F5_PGhwmcO+)*y+W;38}+OoL1N%XgxZjOFRgwVHG1sc6BBEH zu2Lu@L@vBmS&c8}5r7J0`6g&ik>SqP^EQDC;&k^tF&W}D$P{@x?ri6l=Y93h@UDZz z`)*XLEpuM>9zG2A)<1NT9J>dvi;iQzgZ@< zJXiqlHsVqoFx4K#Eh+0ENo7h382PJJP!uslDwi0+r)Tu&ex&JV$-Qz){+){+yyo#;Y zBh`Rr#zjpVwel~z7)209mxx4+I?5}UXBH&Z^!O#PmHI9^$D1_r8C7Ic$^Io5Qq~n8 zYN*T9y3bLfRN&04NAq@b3SNgXYfMnul((hvkWnRhOjO#@_p!+CCfhQ<*7kd6Gct0v zF#JuEvmK>}q=l{01sc{j2x0}dB#|kv#F~UijQi~&c*WnsLk_x#dMRMqGz12{S!hbj>{!7oY?zA)3g0Oe~;2^ zGfAy0gB)~M1MV^L9mjCK@x$&6h{Z^Y`+S0(L-Zq)|JJ3!OuK79_dwG8pv9o_Z6>bt zw&tT*9ZZETL&mn%b#hc=z{A5r7DjK_P>#isKLq;?Ojw>XDw{s~#7Rbs4LfiEf2aDg z6wIk92Kz4Z&a1}wF_Y-U+2e`07UPR+uf;N~@VIUEovXLp7plWp_L}%4huu5&##>aB zugC*-W&2-iS{e3}bIkCa0;J6#B=>0xR5_G8fV3Z+dr#OZiFH63-%)-zvCsbjdD2{v z=VWv5q2NGK;4fmVKVes^sP~goMypDJ!c;FwEoQ$4A9gNH^i-=N-$q(yVKwhEgK+oz=|I7HLHOzW4&qnCFTy*#c%~NvK_sFah2Bdr zP9@OZ#+`Pn(U)9i$zkJbQ)NC!*`fD{a9M1;CBl{r3K% z2IVm|ThW@0kD<{pD@afEaGpzbOMD0$@vnsbBL4cPl${@sP7LI+mz1PhfFGd6lz1o^ zHU`i->yC(B*2NLTF}H33cUuT`cx|IaWBi+Rg4SYJz-1 zl51O8`r?`M;tzg=x$!EZXsDQfiSiqx8U~}1DYbg4Xu*<+5`oNKACN${<^dL$mB8}S zQkmeixjt|%=6t1F#9vq>?8Y5Hh4Nv^5qY4e?58};3R&#S#!q8t8yE9myJX$X?`KR?f$bIG^YE8zk(#7CzZoNHs z+0ppFTCZQb^nV8Ninq1xtz7SeUB=2kk7==@14FauR4ZB38*n{g7-({^4fI5oA283h zs*R|d9AmjyC9EvWV=F(wkN#ePWb2?}q#W~(BL&Nsv?@PRBdi$pjr~mV5%w9;hr&HP zlG$6qh0rSnj?$-#D==l>Vj|7Oh1ZFX%v}qZg2IL)yS>c_cJUXtow=#L@P3xE!CnnDxlc5@qw)S5j;SqMDIKlf>mPMmJk_c}VG}xNa z_98c*ECs^|nQhgb86__yLvRRU-A_XT2SI)(@5`Se0=a`w?v zcJmIg79zuZTlL;2A_9^&REu)&n2hV)3~3yw4r-MRunmhfxFVxQ6AY6wJ$DN%u0(wr zj*=aUJVg#3xh`shLABv4%WAouwkLw60!7PrYjKaN``h*a|G8Tk)M#e&;XUS zPg#N%ViT?V1_xKpyB_Gq4cg5N^W}b~-cDXlq{Rup#wD~NuDbKIeL+{K@YGCv6e;>G zX$BWC<{LSX_Wak%OH7RxcOr$QoG#;LGmYf{9l8Mbb+q%YVVH^M+Dd%q8Ys_j4fa{l7 z_{FGH<7xlmpjrO|rw47v*&hv~AcmWjxQ0=z%z^(4MhnGp_*FN@pX2=p3=5MiJr$x^ zh*?sg{)c{8JHS`My2OR>bi4rA;W_8ymb9d-v-SX^u~5>g`tUytvl%<(KP{$5;sZl3 z=R_c-Xyxw$Cj#NYgtZ zPZY1Q7}efc_cIZ|^sw;PuyHEM=rblXA|>wuFF=A;%R8fX;V%r2c=WmN%tO6KIb>c4 z1?bljlX{%~eCbc``?o6nRm_f(n??zvt^QAonc~j1`YkR7Um=DjmVjMChO=7Lk#9+{ zMVhIQSG`?&KO&QS*%;t9*l*>nAEi(vkAFNxilEodLBWpj{C#9?!jO6di8*!6viuxa zWaYgv9lMKup{~X~XD_aJ5=1bs?7m_O+@#4Lq_<${$eWw&>k+?&^&9)uF;4Ceo3VlU zcj+SBdEY~?e{l8dmuE_=WpZ9o*e$&LSCyJLFKj!1$`nMUI&rQWFFH7_*XfjwYa^It z5YN}9OHBWqS6p!W1C7Fdmr&$^^y%s7@P55yY-~|xpu<;s;XK&=M%x3ZHKia(&ZGVcthskoLYxd5 z>HGKF&C=RX(IbOawY?H+97Wu>^8ECKWMy!S`wo z++R9%IA10T4Vd7*;3_#bM~Y<4yxc=R4g8MXVL=DM>cOHFPx3rGOe+!GK7Q+;>jRla zNai$=I#Vt&zrYQ4R43FMEz$@xgmebI|MZD?NZ1Y1R5$S}qB`LT)bqZ?wp?g{ihP8E zod?Y)tX&hi)QA&uM;HM$XYMlR?EX_9T|n~r8T5*{yt)JYQDob3`{9NKyDo;lfC%dR99KRbpMaY9 z>;Z`Ysf%u)(rqJmWzkJaAK<;u-Bumo=9)wXP%D%9KGKlq;FA0Ly=QJSf(S6mT?_vx z{%&m9nQyo*(B36CMuaqDByIA3<}ElSs$pa5!`y}vTHnXb$4A>_%l~YDHRK7-Eo;*` zy5|d&mjQ`PNA&%hdAc`~HQiM3?BB~D%&G%C+!O#Vt&)agcdr7UozM#pOZ07zT}@|{ zSH7gAI7NpZqjjc$)%;C~*Y_D&lbkb2(-9NTxxKM%2v%Pkp4z#{HjYuD1=%#^#c#U| zZ5MhZFDmECFu9Z+*eE18v*F=wu*bll>AAmB#!`J%A#ro@v30Rt^1pa>#gq%(v?vNH zy;A@5bw!1^wA=8Zldk&54E+p44}P9vd=>!&GAj;91coh-%9+?*E97BGO-$#o)vm4- zWyq*39W;9${O;oGuzX%E*s$T(hNA&C=wW)b%61xr%RPvL3o4c62K>tQJJ&tCJX$}* zQJ(9-m=N;v`Vwz^?yf(0xmX(ZUJaaSy7>5r!6s2Es~jK{p>?vvC_eph-y8b%XU{`l z&%I5+cga>mLO$P*COb&!V=`yAqezof<|ycCb@V3;Fv4iCsMlm6+TB=iQoMFM{OWjd zf+fpyvbr?A*G?QL40bPwq%{ZQ$Pu>;V(5_6gt$?SY(ZxZn8&z{dz2_r!DX@FNf!$B%T&$moltNHTikij?JzW z3D9Y(<**+|>Lz`L=e^#|{(95bvY$>3wZAv_;(QhFk^oXFng_T{I}`u5^KbZCy-z@- z9x^P>NK88zV_+}MQ>Ijwt#R3xJSLbMZL<8Wa4;D<1l_c(grY3kHrO|P%C}E#GayM* zr;+xlwI0S<0m*A@H##~R)v8ph0x=p3vv$)qBA$mG2Yh1yQ)EFKtx(Gw=^_R=?n!gm z&NOl_rz_pga?8fg+iz4?CCl5r!C`UvF2Vf*n@Hl?T&dKeJg*HWVI5B-itkU8?sD~{ z-^i|RgKQB;SW91ai?X*a*NJmOVy@`{Z^}p!+Tc8meWyHVt7YPwlWyAvhW%Mz7cxC8 zR8xpnT(-socf=y{$%<+v7Le<9dYE@c~UU#3kzj|)a4Z~P7 zq~gsPWj5@kN;pj~PXy-f5;7AY+NO3AquGLGe1{{FVcAX-8{9}!p`FC_VUN}8SY399 zDZ>U1>;cU$jh|+7h+6?!8b3u+dU@O%ZTZ=m=@UfWH=lB;V80GA`XI-rJHSbxyx=WP zUL5iV&d5K$OYz%CxKp+S?w5R)F6OGc7r8v?q@}S{IhSF99BA}y{IvDT-{e`~=z-lJ zG?6?cyRNRquyJ~@dp=_>sHZgU(k>}!GILg@>3HjGu@{Nw?KSixs_i8m?qSjSmCNFCRJq7OYkITPUx81>5X zJ3hU!H8zQxI^5FxfLpQr2e~(+VBF$GHIsCAm)FNYPrGxSmmEqe0C~#xWpvP+DkW>; z?>BWmVb0?D>YPBP4UrKzBrKtk37aG;bR+Rz7r=DYjra=fBDP45LqyQf0PJg3u)Y{P zz4Um2xVEl+#$%z1poGcX8i><-ZFYWOL>=iERbeYYB}L0HtA`htn%q9vq~hQ(Ht}Ek zAVgcjj1epcA@B4=hv!je8Ap+v*0_%Tfp9MUj;Y0&z6=`gpUkQa4#ev)!a3Nn$7FF#5$ zD?OfJK2FLr#F4|Q4bK_SluI?4yjvYe`^OZ7Z?JgaW*H`Du}{`zR(p;v+Mm%nUHj~~ z@l#V{&e+Ayk558xHBS^V=!IyD#Wf3xA!0G*bRKzU>)hW6O}+rGj=r^e;>NtzNoJMr zZR%j4MUzY8vu1v))lxV$EVw+KYSu$+VxiM2?n_2528=bd9dc_Idm;6FyD1f6B)m4Hdn6~_EPZ>HnF?%ZY9IfdSU}mO`o7B=mkP_v& zcSbbajv)#F1?-qZGu0wu-U$i{mXHPd5MMz4u7`{HG*1O~g!?puG?4|7G&#a{roUcC ziUSZn8i*Y?_`-f>KT{EO#|iJJ%l7i8MW3wxg?5#vMb7|DSXeo9fQm0}t{kyH{GXaA z!jNq}#ZSLKel;Mm{a0ivIP%nv+YdMtaCW&ez4||2*C!li3zhen@47wx$0yVaO#BGC zVXSe>U`L(`;18~N>Gh0i3TwnD4y-wgfB0!XtMeDEodS+LSh$sGk`JGwZ4rc<7%m@~qm7jc1+?@5K4fd#n z7BaW~t4NT|La5BvVl`56C=H|xu0t&vxGj=IKbn;*X3SZLogPt&H{=8EbqL-JzMsbu z*I1fNl~}4cLxduh#J60DDI;cbd;KlPn*SFIAjIhK_x5VN#k>|IpkE^?la)DzTd}5n z6gkR~?BQ^QzD)NJ;!Gd0(QhvhfEzd#Ft?*~1h$8Lt5fWgm`}t)6qe)ap$25`u2I<&Dry1i9PLF?N&wU~wc>mrnIha3H zqA-(b+xwefmFQa=3jKcbL;Tip-B-h^fn5X1 zjAd18=SaHkG>g>^l8FBsbi=_$;P)3!ua=DeBm zIQe&msuy5RCCzL^BFaX|ts?_%^T(t12bQfCOTqqR%j$)K{-@5)trIMn#~2y$j<<~^ zQxJ1&*%z1p$F23@9J5*ezZ=ux*afOF|J_<%W=W-(|88wV#lzUj+S7LkWf%dFa6R{x z5gG8upLMOf9eg}cEq1KzXhHM$BwfkmL}SUv)riHdF0p|>Pg`F?XM*&yhCuGQL;x13 zJoq#4g&WIh7~SOb-*u_V%BPPNl*}tQ%+I7(Vgtt(U%bfplL7PIr2xGw^~E|Xnn^w~ zj@E^1V}r5hWd6+C>by9UR#`U{RIcQ%R*xKCtrD-XN;^jH3{}cY4@AyqL>!xX*AUN* zu0H!#XzVl0ar0%FFfzWJ>cV|cK%=kpEX`&nfya27o$7JrI)~DU?1K=tG&nMXM4F@n zDutEuM&ZrPI8&{>qV$A6VA%EFT*oV}@^;@jena6iVepF?6ahRUH>$pGYSJkV9PSPH zGmYoqfUKJ^c?j&zSh*0YXST|ynzroj)7^G0Oa0MEpWAShDmh^QN$uULziDY*Jn&uU zR!_gPwiAUTMq87vtVIN|jPz?GEQT(Ig=t-B5vo%zv|Q#pG!#Na5t#;Y1V3ro(eG=q3@}UzOD0S|8>{1bOVZBdcQ*~K($IX6F z?qcI1$sCQ=n^q~3cK1QJ$~j;$+&V&y<w>jsB;z>aZgL;Cmlwz{xNvWWwtKCwPFs^ZmzC zvOq7)F>UASE-C-sj-th8o4)pewn#YPTo0RY^;k*lR?1E9ILd8a+XC1eX)X8EhyNO1 zs7?P0rBWv6r0Ryn*;x-N4#_(qjNh#j!UCTDx=0%!Omxp?>R|WSF-^ZRF`YD6TzUC% zJPR=vYm>y_swv9;7D(Ph=IZ5cIgYh&(T2aaqw7XU@=UTXCD8V8p2)cazz*wO%o|UL zVf_7lyt$$Jha+}clGW*Yyr;sZN7{`7rA6d@_&Gv?URW4T<9B>AVZG98SFMh49h7QW zoW5Ma^Yt`l@UXWpEs8OyDV?Y~$G^d5=v!o}c$7eHLRt1s8kr2=J=LX)(aJR{HgXq-mv>tRyYm#rJzliyMRzLSKTdz>rO^ zEypT%oHDHYmGgKo64Gq00Z4HFeOK@Ofm@Wu-O+J}(9{o9NiV+@2Uzh^VK`hvY?RwQ z7}#*HW!`CSpEX^BW6J_1S+a`N!| zoqN=0_obh!)UhDezrv0H-`lVLR`d!xEoA=}<=V!w!3;7vl$gF>3D`TOaA|YNA|a}N zb;8UzVDgjY*CeBL;p7O+>%>(=RaX+nnTo^$P}@0%qpdI0p^hksRi?`^hf0BAD%|4- z3BxS{dB{AunBRGPaDYK=mD~r!sMiPP=jr}thKfR9E1TX%tl88j64!icH2$YjavLDc z$Qy7}l~NHmau93#<%5`W>+0NRpea)QB>s7gQl8qVVSQ`n`0&X@hT=#SnrQlD-Z?ud zBrAF}MYSUhaWWV|KM8l-!%pD!r7t;iP_#L)_8-8yel|ah+I7(l7_kwFR+mIt7bLAH zDN4*F9?x43d3)g@QMzIeo>T|QC}sNO^dcYrrALAR66Fk3yf{h#7}{KJAJ46{4lkl->hlE(odIbyZ=^Yjs1iH zgWf5$$Q~BM#O(inIKnpX|4&DFYdb&=qIouIgoo3z599$E@*C(wa-J|grN^njgR_UJ zby)sALNCf_zW@9(@(pw-zawwRca;(noF{N6GXXXYWMlCb=~qlRFYA>i9cZdBii)v=RZA$VmYxlzSld3?sO?)&<05sNxb>XHECNx zQ^!)?HPKq5ANTWL!msZhz<5JmI*PydmtsHxqhgd9+q-8ENZs=6G(9T4wd( zz{hWKerfJd{H}e@UeL-Tz7+qd8XXz_v8x8 zkcd}1*5xw8Usk>Dt(rpn&Q~_`c~KSieChoKQCmpm#uHx49|rL?ydv{yD)fxGf(HMZ zH{Kl3YRr)m{rT|ixs&e6)5FK&o&twt#eM94*M|S?6P^7gCRvit`Y=;mrtJ53JY6$e zyp6&H)f>a06>zBSUvYgWd1;W9%P?S91al2k5YS1ylW`CDZVbYr{b1!31Ge_!7{MTt zUP$^KsjPM@z*}R|WX@av^@@t1OxeLgod<0`&$-JeKne#0`7hN7)82{0f(%Xo*8X07RaIH88S;#( zpP>uFFVhy3knPp=UPXNamxr>?ImX;5dxOH740dIAV1OYHL&=fTiPQ9{%w~P+8t9Nw zrgl2odyG4We>=x$0rxT<%{eRIGH>)1H^<`uDxR8|8C??81rB7xen~NboVfwXfJLd_ zWkCf%{K>Yc&H$uL89(7if;(NcM@K@|UZL2B#rHpC5UJg?2=wZpB)>lP`~Jnr3kH{i z$MX8;9i^Nza=(lBSuYdur}wYkz&^m&==#|&ubW`Mytt<4v0e@}t$O=%sd1f14JQ8u zNm%=>`esCt-2AfayNYuB$Z;Abw|k}5&>t5{^mF8dDwo=Aa_WRLla!FtM$_lBjk_{x zMvzk%0Ops$4<*9jQ_;5#exQC^VjPdfH zTRSJLnJwY8U%r{7{>JrMd$b|AOV$afKOBu+NfxGUhwCpv3&3g>92eiCV!)ufUsl%Z zkP*Hk~qlYGRI-@D2+e>}t#j2WvsVu23CWVLkYYz) zjidCFbPu;zF-Km(ZA>E%V%H>=iZ`gkrSx6Q#q9n8Ek>SPKOmQz@A~TPcMSR1YpO8} z=B1gotkw|^%&brEFW?+65h&2&Y6`C(ry(R5!Mc3=nRCM*)JYHk{)X-UhF4m;C7l9G z+Jr!;Fx_nd-KMqVq?@Yi+y3|j85xOT{;Cpo$ueJxlx!l_NP7Y8db;MFHHx`=`>n{2d1 zIc}C@0R0)@J^0HOBIep|d~+=?wCQ{n|1Ov6l28)Y!R^hoz2o^6tunq`zl`o>+P>u`Vz1It`$ z6V^$0UEt~OVHAcu)&Q48F>Ia&ncT=04C{wNhv9~-+#@zg%sbyC7rtB-K-ucT?w|Qa zn5XQ|@@8_cS1(>cwMI}z!KwUornMdZJ#8+Btte$T^ z1V#Z_H03fGF%@S_!#4?NJNgl^gH#+TvA0&^N$cK@&H2fjsDZ1_ZM-esZ7_;BY1218 zE5T591bJL*A!?+lHJ*7v%e~;)xJl|`lxCU5%Y{5?f#(YRaMQy`_uj%O0i;$wC09e} z*%pgs_g;&}lRum!q76MuiYwomXSeQMUE`!ty?w{iX7sm zRN6}NBy3!vIKLN+wNAcnZW;}R9~2C2$q*mqafpgJ#m^`hE#E;f3L3ye=#6W@`w=26 zlE)3QUDRi?6=vK0pH6p9coT$3+1d$5b^CR{~RZu1BWak~^pXk$+@rf3PklJzj zMM}??$iaj3?RU8EMs|NWY79~~x97WEJ>#2bEb@O>!YT1g->sLQ;uE>^tB@vhP%w++ zS~;BdeJZ?2gz9r&A^E1$`yJUcP0i4jfLM?(`3cRtiR&5|YEosAh|yp&zdqV`BZvLZ zqT;)UYi7_kMfVT?h)YL>_BrUUfh`L~jr3&Z73P==ZRrVv^wgLt2I~*if`wg^qvmOl znIUYW)nD(ds~P?u%HH~|3Hbl_-bN}h6alG$QU);T8Zbo#R0Kh327;7yGhi^JL}Joi zQc8D@P?YW(-7sME2pIy0&xz~4zt=hEy6*cg*nZfx=ll73Jzvj<*#}u`blCA=-=H^b zpO~HUnX^(Q(Pz|AQN=Rusl_}+PIp^tT-?zfbwiWTU{3&@|GRjKc$tFc%OlG%mJG#0 z-{Z;*ZAH=$xPa>)d@gHMh>d}h`}f4|lPl`DS!SZebA4qqWB{b}tvA%8Fae7A0xM}o zoi@nA#>v)Qkgu5(oKyi#<;QcxpGj~O`jFgWwC$Co2KKSbBi}-Kp#M>(gM$aO-xyy& z+j*n`iP+!szBe!|0MgstkiQ<#hMLq?;{Ccx6EU!n z1p8$_Q#yx533!2Q`aQ4HHxao`P%nr+LD9{&+{&%8ilE=*RjS5cBkpHMTs0^ueD53e zr+}<^c7B+-^?kQV0>VpmJ4Dp~Ek!Tb;C^GCO&E>8FmTU=y*1y`GN4QhPdhF@mxr|S zfsh=>qQ~#zZJyWBR>G~i{{$goP_VH~g*#~m0OrKk`2g|Ui+nHQHn08VX2WmLE6o}5 zK>B6X)Y@!mt}(Y)JP)NG9|~i$C{%J73139FSR~)FakFQF*7#ANw;Ax?=o(F^l6M63 znD%LLQKw=%rFUexh>6cR`|(PX-T^=_OED9_H(Y%2xMR(8-%u~ERwH6kx0S+5zK?zF zdX2^TRE%3~WeMTgPiG3+=D{AYK}zrCyCd^kkktLZeJ{bD70M^%ziU}Oii4hJKg*G) z0e6k9Cbj-L;D{7>13%K2+LAIlTD@rNSXAYN{$n}#wuS2ACV9ezI4vM%ze@MWKC=J)nMD8k3ft*)950kZ1a9GS*Q3h_BC+*uG^PAaIEfVJGZ z=T*qoDJH>v7ChIAwZztoc|Prrje^OR092S7UKVi7x*Y28u4=L|n>_1)~>t z5lwVxL}?48bwg{Ljtuw|BERyC5y&c`*gh5J7AmYhdb2UdEnB|f>YvJ60=G}4tUNYO ziC7;P#k?@F+vYnkZE9|p`OqXQ_lBz)Ebn{p77J4S;-JQD-+n4Ja1m_ld-BWfs+3wb zOd?;=hvc^x;xTZqxSf#(5XfJ~^4DZnoT0l_AixYL=W_dYP{IfLglQYziV3R8@`H1| z$tuhyhlR#1^b$|88oV12HcKf|0X%=4uQv5Q15K&u22`i|tdG+@qdI%@{A|6VxXI!w zWkqU3*s2#$J|+7tT9uk zMrC@h$|j@u6N)4ehmVu>+r4;qTd|WLTQpvx+J-NOqz0@{7=1t4S)Q)+@IZSA;`@4Y z-zF*!Ca^L>>d*%*_h)?~Q$95IIx(uh=1C*YiQ6e)4DOF0iE5_qF>IMM5!oCr2jQgz z?lAX*`lb2>cMiPU%?L?D*?AoDqCp#>n!~SPwf@5A9a2VTmZel^JnrQAvGTEGsXWe{ zvrJ%8+bT45=3+d1^hb_Cuo)r7E1k3{t0v+zNR$?3oke!6c{GRLubtb`npDJfxqVuL zZD32DKMSf{9dE0U&*w;}a8_t1S1|oMSeu_fJ86tc-`)V5HK#@o7;id0>L0C+gcuz1 z>o&VN$rBd5_Vm@Kd(XeovQ@|ohSe_LZJZHV zU4JuWt67?*SVHjpWpKMG$9uL80jY(r&#-wwQPWohC3%`Ew%Y%b@cu`MTRSZLyX>Z! zsn5&l`a(8FKw0?hqs*-lV+qua^=J1+PrDKx*+VqVZe{eWwfc<3Bv zl#3Mk=rKw&aM!#@HyUiFxcO?mCS9WtEr{dGBdS1pfF!md3lg$2Fsdf?l9;k)e`8mD zNXPe9nU<8H%w6cY60_9FzWueoLJDTWPrH*~Ucntte*{_N1Wl<@zA@rsxUX^c&-3Zy zeY5kypHilMPm+4n8im`*7S*2cd@jr~RValC$4Kukkuw-4yyhR=s#8BxT6Mk3Jl@lw z*`|K`cKYU~+fQeq^7xx$D#Wp~NsVc1Q07Ys3Fk^%8fUa>k47Zd>UiOb5K+zTWqJxe zNs364zQc(o-Hhf7TE#k3D!+xI#{np9JU?F|fr-P8A0*x<`mSY+KhO87Ua zYg$HmOv8{=K(Lp#fO`5vP`TZ;t-<1S*yN2tZSFJ))fQN>@8!T{N$bFTp)W~J@rT0c zq4m*WOtIIG%ouZ18idN%GL5(hLQw+;^_CAW!)Dia(iqfFYx`PVBeb=z@x+stnW3!Z zof}1kjQohem@*!;R(^7g{@#MAt?yKdutZ6MEETZZ`_i{omU$1nKvc2U$EbkY$5L<( zWA4f($xWLpi381Gij^B>${lcHNkG}>JoL?&gKmk5w?QucAxU$UBQ6GpllK@ZAkvM0d;2S?xyc*V1%-;5BI)zY?)H-y+wV7qp;sxa!x%ofJ|O` z&EKXdh?L4eRHYNZG;D^bWzy$JEH`U7-Z#wC|5|~Di?A=~z=xD3xhD6^^xmy-=zu@# zfE-;io!EcK!)N1}`8#NWsj|2Ca#{mE@j!BQ@9dmSzLaS9 z?96{(n}KrxK#Gk9-phe%i8mC_k72Htr`|^UHsqHq~+M$1>y)Xr!Pe@ zv14-)S=Ag_HTM8D`@zVrNTvUUF|;Xdm&OXK&$*Qq1CtN1*S?HgsXzL;9O5;kl%8CT zDRQuHPj}C1a#ZolA!y*Bo}LzS%kLyx*Jxw9L%diQ(h>24e~@mxm_47|AQ8%ma}Bta zd+uy)X@NH=u5#Wv{7Q`#n?7&@#8KCF$IAt-&vf=sP8s|)SUM$ml>2(rtlrSSlyn8@ z?GX5GO}gdCR0x7`JrzBQlYeWIB0Yp>j>)#Fbn@Iry#kwEM&7?(n9!?;%k<5SMfJS+G`sA0(VOt0(x-(n( zr+Op$s!7L}6Wf{DGLSAG=IovQoY{F0%+8ynrJiY@!g3612cggz_dg9Sv zcGK&SJlJZI)JTGKZ-DE7(tx_v-2B0Xl7~0$&zc0+DJ=F-6bu#TS~m#BhC91T_F)er ze34gAZ40pZz>=fm`HZlz693N%&IIwzhUSsqh>%UXwbU3hWTcQ3MwM~F`g+*w^{t4}Y2xlg%$R^vH-&-%*fB62^~c}sRpi9Y1S-PE(M1M+T1hmx&Py#~6hiXyC^ zF4PE4|BGA{*!J2RXV$^=nI=rzyGBfj#miya1(D%Ji*V(3sgTY(Qc?aQE z^7zj%m}$eUvIbfwu?lWyv%e%q3I^HO_&_+@#``ZYt8bx#d1MYD0J{o>r{I5&?l`2d z;|GU=Gh72|q1^Q6i~O*6jCD5k4fzAH%k@+a>FD78-~;}9d*fFOF#xsaojnYMzq4N{ z7ZsxbthHX=1hhC{e{EE)!e4IqJk690;U9=oOQkH7h+7qR6Z#}1&4_!zr?oT|rQz}l zT{05V_~s+bB_nm0h&(jz*FB_v^pOqX(j{& z15PPgb7)mtqGdDGokh>G8bIDunc-scue^^BovO#@8P*>IYWnQm910EOQC_89dnUys zor~2LUDR&Rz;EKy)9sHa?{^J%pfRl8+2rnk7kLtHNGufG*Y@$`JP8&|UoijgxE}jh zk>xW3G!W!YTkS_k1xV`+&{1fTfB!uC9v1r={swp^ytl$z>dB()wJxQ>=Ew)bgT}E; zfA@=~=H+N*5q=noKn2-Y9jN~u;NPs=y{aL4%M$VU?~01{-}-~d%ghmlFI?*(DeEqF zuRi|4CKnDHUEMdfcy`Wv$=Rc z+yUtxgLrzhjN)NDRrg7On-%Cih{SOneof=w+hdN8GtH=r2Cuz6EntX*1;~isWGuA( zI=Ix6{}nhZDJDHi)zbQY8cZN7$oECj{Y9#=y+9A+K8Ll#NB!m%R7{B&&z|8_7;`2Q zrkSnz)+1HUcwX{JBmbWXXCMM~aj50&M*TZid5)G*WK=8JrV_9jkg>0M0~{){ue(ha z2*FU)y?d2mB@F2wh{Jq54fw0 zURr0*SuSKH)$~ia1dm#K(3;;-IWJPFcU6Lu8lvj>Pr*>F2(a=$R^9zMw_G{7Dd~9 zbNB{HN_tHCvqO;$$s2S>*d}BCYlQl0Q&K~ZSJILpccZsg`6m`WVM+m6#qSv}habBH z*=Vfcqc4PSQ{S5#yPZj6lY+_`nP#v;y*xWClV$jPKqzgwm3dGd?pER^TcV8HT5Q#ckW*{0)bebIHwB_@iSVz~tdi_iWDo zm+RJ!Y<3MCjoi39J7y~CrYn=$1)K9fUkJLW*%-0afaj*rMbA)`@L^c1csf^Oen#l-+ap8cM_T4z=yN2&1# z?={*98>BfrfO#msn4BAUA&bN$^uR3o<%Ca5z9nG84)Ww`dO1GO7YlmK?cYr&bQ8T~ zN;ftf-aFr4fz_+2dD!|crN-wID^k<*7f;vbFQK7Rj>gX{AD9hLzS=LTCpG60r=fnEYZ)2cx68pbIAE`+}6pgE+1ri zX|%s#eDG8d<6XcgMHOZ-zH-Gj876z+j70xfe(o_F*6>?AB{9P`iIqP9yb32R%EDl_(?bxo@xDF3=iz7d+!L4L+>w4Pm`iK1qhV$v#N z6?!bARvcuhQ!8s{`R1c&`knjsA?mtOK3bT;-u#px!)}lk*bKyqaVh1=B#X#Gvtk#7q~?9zocCW{ z*zp_=6sRjA_2qr`;M~?o#<-5*dXdmS*PdwD+$b&cdgSqUCj#AlHddHGHTH8TbBd{T zZDAe0z$_mgPC@%!Gu^0K%{_ka;6<;}8-FT_I3Pn6bnlz zcfR6TGJN^JmSM-Qk6tTtDq`GO+)y3Unv_G1Lg)e51&T9Gci1%z93Ln21?|@3nCy?p zcZ`(iPbJ>kqgVJT0Cj4Z$1|Uvuv}2z^LXvqo$XMYgNuQe zHuyAoAT!s7Ia8NB&aI)HzLEH8w*NQ}w#(IN(N@sH$52Q5g0pNLz_zyP%fcpb_1~aP zLt!ir8pi|#R{Cf}%s^?`1fBP_3ZQ>;P{QOSb>k%{t|&)GBNCJb95yM0 zZ`K@VsmHeHZjP;#)aiw6HJFg%kj|ZjWxxz=*{OfYB1F-b8^O7tQICYoC zw|k$#?h*GnT+-jYj(LIOqY>S6GHNxsvN{*t zmo`a`ol-Zaa9UF6E3)|)kHpW-!)J|qDlXRh`~^Wi_37z4_B1Hk86``SN!sF~BYS71 z;V`|h2ghMosGokvfnXc*uZw;rl_y*sc?mwL`Fnv|=e^rV7_0J5 zc7<{I0LjN(rqlA@clG3j{RPa;?Jtazv27v3IVfGJ&ASOCh~Hr+v1(wkiK|I^!Wh{l zkXQYI;j0{7Z+5KMEQ)(qraLuUrrl#(-hqdpKSIT>3_^0m9Jv*$p_~z5x z|1!NxdMqM#wLihBB&NqXdE~b+)QkvM22&B^PXD92jn;EMk+YOeG=craPA9{)=N>Dw zmGDBR|M&9uzifkjY?%{h-0l1axuyqw5*36Pyyg(4mnn+ZxhYy{(3&%#ouxaPm5|Kq za0%?@4M%;?`;OB=3QE3`gMIotTr@?%d-a9VXkm2RmsUChfQle5w#zA_mPcmBHqyJ9 zq-yQ?o9Usj<`S7iv_0+FaoN*nDQ{Sk)?ZXwXgE7j3o)}OhuUgXSr55EH%TO{ho#c? zH~G0tnL!=!4|B{dO>Z^0)%*nS+CqB)B&xmdV4Ktb2JkD*))T5)kDZ{Cx2-Fl{n#ys z5Ve6Lv;{Z%FxTD({6`M5xmXGrCzob(Woxg0oQayZ3YoPgP)E3)_oBDr9;fQWH)>#L zQn8{IzB1Ah2jm+5dy+To=>yX++lwE-5C|h zryTn|y;JOP?&7NdOJLFqU7RKjVRr6c-~hrO(Sgri7Z+-NieJZ}G@KtV7)mi(6mVk# z7Nl2`{l+?^opOhHzof;und#ksJ-nbo<+!ndz3KOsxmtmXhxwh`1C~s!3}dRnU*&@6 zv$nIb;b7R{_1M$ZN@xMiq?=K?X*s?E@TCJEGFAZ_LR|libf<=+vPrHU72v|{z1HGuECtV4poI~09|8B01`HX=*I#rmjYW$u-+IhxG39Xt zXU`Nzv>Ls2c{)1AmP1j#@wl?TLpE`_Dx!AE9`Kst$*_{sRuFz6s>E`SgVRP8uL=2{ zO(PIRWLzC%w!8U!*iO_u*5mS%pJ=`W`xpY;=uFU!64;RN$6O1GF>`74*%X0FSlPLxNsqf38Fq9w8=hpcpQAA{ z*CUQ-Ja03|K`pF4X`?<^n=UNYt> z@hL+8bAa7VlQ;Z>ZW)MA26|sm_O5rpJ2sfAjE&s7a)kgP^+8YT9h-jRdvsPwZ!BkY zrBMEqiTbG*C{^QTxK8@WuXw>M~b*};XC zF)rKn9S55Y#YZ0edzH=Cc{C((IS;*l03N+4l0Tna5c%**ucPQkzPjSroIG=#J~ZD7 z zP3$I!o^q>KBEgI-iw7#?|UPY)Uog@^~R0E0KJcZt>aQTy7tYSmN+7E$fk6N9!p8t2sw; z-}9n+M$FT$@C&lL()a;uh~ky*otAvLznp1|4ClaA_F{zwCQ}D0nE&vVuC6&vS|9}Q zJlplJ(tP@pFwSfBN0Q)%gpgIFktbASVe~BQ#H6Qp+P(32JzZ*Tgpq}8Ihi>*QCgU= z=Cg+Ra)jw|(SMQerae6S`n55y*`22MYRR?X^6sa%Cyxhv9TcW#MO>fAL~a?SDoKM^ zU2aX55M*vhMm(Hyg>?1wnWd$AG*+phY6q?e6vPD8RQ_O$toh|v?VU%A<7o86Z4fujX^d6ho~ybC;6u*08VLsyt>3{~BtE?Qy;_yn^e<8ZHx+Vdtr z-sdCs=4Ud@Z|m|LW7RLp#WM_nAaqbi6gpXRGFF{@_WNo=E1k~l)-4Cir6{ScZ@0c` zg5Kt*%&&)CkEa}10_ZH+dOdm}|H6NnZ$o2HmZI7)|0d3vkK1*Rjap5Bd@30bzge@% ze&n|L*(Y1P^?AdO>(tgLq!1+Bg^X)J-18G+Oo^z5Jd?vo2kI!h{na&Lvj51%dHusZ zb$!o3O4g5e(%OO@qOc|`QPI`h*qTV-x=`z|^3P26(c-Q$d9FiK@G{|W z!!zVI%{#HRxdriVMurAR@$G<(&U)Xal)2xMP3gJ)dD3J{1I*(1eRz=J_If?f22-f7?lQ3cO*fKE!i) zzuJeN78<6)IWD&6YA6 zBnO(hCSpamc{?jv2_Qo82^O8OrUNzB*+sMzxzBUycvBr1dV=mb>T;&-*w7hM|Nf%G zi&Pj(6xzTJ59w3!di-$drhtC3;-u?;4qDqERCmSpUYB-p_0eoXo;7 zZ)xwY@=ar5vT(-LXBw@qKGpnLcTr!MF9-N+?QvN55lPn{we$CUNu@}OPi}iPHdPkw z>&9?f>&xmp)gEOBwUq8fAMvpP>mGG)vGb-akf~bHQ|T0Q`=Wd0)pr)YUjU0PSEw?& zd8)9_pvBtk=X8^t+(m*Ff?w6uYv7SzQ(5vspFgF)l_z)VM;?)?KP<@TaeH82ZUSy! z*CE%9lV;3}A&Nsagsvra1+=BNM-n+-fJ*2WR>;YVU37#3Us9AnO^k*EOsCxRW?wwj z4~iC$dx7)i!lZ1pY6+PPrUR-xca4U8)^hLk7s7lj5c_~+g@r$o<4GSlce~h2;f01~ znb$?;LawbeJrm#-e|w!Vz^lMj=JEGuGKaqtj*q_zvz`5W=Zz}h;SVAYjNDfX{Cgx* zFKIKF2e*o-3s~!h_hn2{2x+YN)vh-YZvRTWE@KS`32GuiZy3>=GUx zr2cS|i|$x`X(YEal*;78tv-lP<~2B3P11v}10DvXLa4(Zf)CJy{a~LG`3Rl6ULR}O zA!*ef)~}Drxe=O;`O(wHO#-10lRKtrsvL?xUe*sn7@;QCm|vA%>co{4>Dog z_nPPFQ=Fc2h@p^bssEJeoRd%u?<}ceHhSy&`r?xsMI1$I?%D@sDikCY(mh>Wa>qO+ zpveRDq=&5Xc=<}LRgV(9(531}-#Vh!Dq3R*>g1jp8Hc-D|DGZ;an-fCHj3><`H%HG zdcI?O7g_C}ot4dj-{8m(v?u+s%N}lN136c_0&iY}{fgh+{d()t(s4LK_M4-XMaxYC zsd3WrvG&mz&iLwv-Pa&3PzvvwE?OCq72u~Y_RRjPVZf(Gm+UJA-wH4uSzf@g@yyntrh+L zuD|!pqhteK4( zpJ;Qtzj&MnH?r|VaE1R&^SSqUj7U{_&QPCAMU|P>Ttg$hh<^>szSip`FrJv`3K4vm zAB9jU?bvvc?v)-ZnwAgUQIFxM-A)XB^CdN&??=C!yFtHP|Aq`*qww{$hh{{jlPC-> zP_a_4Kx}*9u0iZUYDQ-f-4fQ#sfhW}^ef%pg!!sfleqh=j;l7E_SVTmoeS zd_^G@mjoO};MWG+T$800i_8!^B=b}pPa4imPcH-;FzqLU4`@n3Xzh*Jw{HFJAo>J4d|v>B@bm*+`M1*^`vH7Gh%4 z2$eT>WY0Uj-pG`S@D$RptxFcPj6rDMjv-JqKmyr2Iy+#Z&xU7Y3F^Cn&&{ zLb)7V&=!9`NP(&9vS`?ls+l+7mOQ|z=OFn-gZhV#(e^(#88n`>TC_fMrp`~P9^xL>Ky^`y z0`RyKkS>|q;HvPvbaK$}Au#5i3vw9aoi@Wj;TfqjE`*AN+2_&dR+isae=m1JF+3FD z2M*(bcIJJ`^ONkyX zD_xL}%&b(KrB!dM7vizQQc`!1n}nM}|LQ=(>-!|`YSGTO#vsnCLN${$tY1+!3`2WB zVP}tOmEs!iPRk$A)Qu@Z3y$`!9u1`*8Bk7(YF;rMu4S;$P5u$TvdJ*BF18I+wOUv|j;PnSeL(E29$(JpaGC z06KqZu#0!U41<1;)zNFcxsrH-6DjP=`)L~+R%D1s_efR%toNT*rBDHw2O8u0MN)0Z z?KkEbA8lAyqa3pJnb%!hln|{Hw45}f6C*yYje<7crdb9xaTI1q_gP(|Quq0t?wH!v zSda*$^Wh2nSbhviy;~J>(9d}mUUKcWWlh98Wb%%6^C7uw2hG}_Kfbi5T_RAO#gzoA z21Cy8bX}r=dc(B{{u@r!82l3>Gb<4aZhe&eNWBB<9Z?pN*qvR5#qp!x9I&y1TgRjn zGI|3R$(H{fIrL63?L&H9kZUcqINzvF{GT&{ah%modrA|W#`T&J!^(E2u# zj_pjh`^MgOjsfrdaeI7EOdd?BbgU#YO*OM2OQjZvtIMZaETTBldbRh=&(*G@&9&XI z;7_&k=t0oez`JCnR|OsEo>P=2CBAzY7Ur+)o2nm+jMXGdc&);Y<%amrBee_D`tl2) z;LZaDh1diWz?LDNw*PBoftR6T=E#|sZ8g_-Qm$l!vez53(jzLW#sghJjr1wVwaQQfGt*vNmdqn+Ux!*7w z)j9zft{WdC4OiRgoUxm^2s4P9_`=U@yvj{@%XTZ)&T_4izjU!zH4lp*ZcgaSl5MdA zjxC&jTm%88)idM^=UTj30AI*}WJo=-uM%dzWnbVD*Slc}A@0|jb%%Q#^a}wG+8g@i zaQZVh%bZose(5@?`SC(~171Kb#?~tSPEY~-#OBop=ySuctv1`uewQ_*rAp;7Z=`Qi zty?MSaAe@<)796+g^XPcy|2ED@xr9Tt}*a>+o>;{c7SWm$%@aHmHaDlyq3JvkB%Gc z-+906@n$my-Uq8!l@_V22`tIKTyRypg=o-YQd#vw9y)ZGd?HwWd{6+edy7~hcjL~YqZvRAp>gX@%x7@Z`>Cpk>zJK#|5sD|3 zikts3$$UvF^UjZ|{3lOV=`Qw{J49NBI9ZRWBj_oevcvps;a;3%C^YgooFb=&UlS1Pn z`IyA>Fd{_cieE+VM`~2}HfvH35!Q?qt=$&w@z8^eNNuj!;m@SDD?*&r22hCI{al4k zC%K$!F(O}mx;do%h+|A^h7HUM1S*b=U3bq}+@KmU(FHEtc9lw(?6l5N6L4=>={hZW zU{kQ`yC(WV0Ux?yz%$r(nigt#1aJ3gE%?OOIC`-Nu*(N!}3KL?5<;tc=`O64W7N%aA*X9Q*sPL>_Fm=j>cB zNDXmj;9-YZ12@|RGUPI5XteKQ$pwCi0WjcNnQ?$ZAKEbi~F zskUJ}(oBe0W=OmoCGp*q&67lSF0mg2w6tB@yzK0ZAdEN)xL#@eDxH%OqKO2GU7WnR z8w6n4pXeg{fQIt`X_V0h)gs~PV* zNeP^$e3C!ZpxRU0C+64I^dl&beT?W55^|E9JE97!zoDRBh!@Ml{7gbIm~tjx**ggS zz{M+R$90&79^GuZZ!HPXaFzWt+K^=Q>xh2~7np)%pz`{992{C#6>hrSt$DZd(_#S) zfB1xxY>!%Su${CD{xrJdbo%oU`NDh8j(5rTfx2b1kAI9sQlqMW#;3}B7X9$~Yu)!a zdf!zYiA{IXLEQsxR~_^lSdsnu`^5staPbjoOddE5Db*Rnw464OhNR{TFHT$bh?|96 zzS_mbJqBrjvTIv{?_uHk!=BWGx9z^-Ec~3j?w~8Mio5A=p&2c49W5tga!4>mX19Vl zDxTu&OK>cZj-Oji86WQ1$!EU7(@_tLfOPUaK&ZBHIR7vBfLg5!?(yKhX5{VC2&*#MZC9apJ zyV)n;KeU(6Pk)EZ%>RHWP7S?OOQr!Sm0H^ZB|zUeHvJ#q`CvHu4}QU{_`hh@$*=98 z7znir#oGCkv$mm7fTq_Q%X@HM^igEHRUB1ILp;O3XHL-8<2bAu8NWOO{NO2ZWh-@m zxH`mE1gY^b$l+srGdyYEQIA`_brAhcCffyJM8A*^bNzFwi5gOb_!?V9K9U580CT>H zfk%+*eNH7vFJaE4g3SWyT(HtJ4hcSi@Pb}m-b~GUEkmPmE?Xi@}({x*R1$=G)H0NIC+m=Xf$*sNRIahRP}ZXPxa5_ESOPP*~J9a zJLw_i<>FKB2$12-ki=|sYjdF&67-0uLgh5&;1iK|O-T+NvfnJ^4{(xsGLTgwBJtWY zkV=KqbsLDzkZ}HTw#an4br{qRe)Oe;ueuh{Z9LLrYU5>XD{iW&3IHIwTeY~j6#;`2 zx6c;s(g}QP+TrE;xutsmL5tUiPh^(;e^GJcOs*RdPuEZZFajH`c9 z?-=hnh>XPhxhuC*{_GiMGFi&c@Xce{ldP`YAv_CJ|CI+tG#B(sTmWX2vrBAC&y|$K zIW~i+{r_+&dhr6<>%7h^bf9l%zz(%-`_tkz`d4Tblr|?}DpnpS{|y}dr+H6Z;WA}- zc_(Pv7cH+B!`8w~jXGIV`mx_qejp%%qq|2D{^z~=Af*DC_8PkX{lfk9vs1Z5`Ou?Z z{}yH_1|=?b7*$v^MRDq>mDGFf)iJ}Pz}Q!3o`!Q{FX`1Y6e0q|L;StVA%DP+!j8@S zw7s{e9Oj!Nc&MI?l;8`G#3p*qUHqbeo@~%j@DYgS-J7`~Cko&a8~r4yS(FE@@f>Dh zSu?`#2wN)*dFg3OGmHQu0_;=d!`-f0z2^^-iC)o`VI$yp(4Tk*FMbenj__k=_iRzI zm~*HlgEqK0UYvwMd*xmE>(ZC8B_rlr7Xw3tYQ63Ur=8H)H|p(#ZWmU*Qld^@Valj- zr1{Sbs*#=vm<*?U_oMp*$6_PB1gzNzX9}WScwm{CI?Z5tC)eR@x3kgGUwirgIXV6> zTjwg~zY~Iw>eD7bS&B7Tr;kwj+=tkv*B2p|u>xcbT{Nx2e>^*ueIEcU0k?q{1daZdd&8S0H)Ay|D?GDqA*v|O!{d#hVdo29j)Rr-o9K? zi+Lkk?lf*fn|9CBw8-7niff9InsoHgKVu&97D^sS`L@CP9;Tm^3^;X@Cf*tQ2~$&+`y1{j?lJOkLo zSzat=r8bL7Q3167utI8=-iw_@yN20ZfB5a+49rCEtr)`d6PU8k36?_OnuG1D^!jq5 z9dtQdeT|}^@f@_K-fkT94Sd+&(s`_)NbzJuXPjC8-tT%?=o8b{_ff@{*QooB zsBL6u9xT6P#B$?CBvh1Rs0VtjBUE=i-#mY)M(29O_c^CvDo(-ExOwnjt1LRrOfZLL z!Q(K3m~b5B+LYP+(N={h8t{c;XO-=mdMEZ*9!jZiZ%Jo3P5}r~Y6eiUo#_%E-KS82 zzfi%GgW7w1Qs;OR+)ZCeU_C!(8ygZp{0khO!s>mU&48`K1oE04YfdZ07w7RDO=Upt z)Z;`gTX7#&a|1}+kb|S}?r`~8c)=OiojkCeu^Dc?$+FB!Dl|s(-c&Jw=u-qoCTNm> z{%s~|Y`pl8+vec6LVQyUi*z5)q`fL+KWP{Jdw(uc>acn3?_^hbJ78ea9z+auMU&EZ~cf(l-aVI0^ZhH3Yxcg?rn+fKR>y|p)Uc{&FR4u30hOQl8 z!^KfN{TqCxJsgdxbw5f@IZ_6WoEv&FB_cuySAngR;m)p(hxjZ(#e?RQbfTPE(umsr zUH!Mi7=rqNzQ;d@>wBhD;{jyiu6%W{+PI!Y|9)TuK*%_MMFuN?MCB&3;D^Jgw=CE0 z^iNmPcGzbetKgMYvm;MknpJS_B54igUk@MJNp)mwC?%OQ;(xjatW}*^vXv87oo(4o zr@L#~BDW0Ilqr9%&fyLuo78XMy%SGF4)4|piyTFX($jx0L^};>jV>tU`!Ha(!n){C z98Brkzs`Q00yz{8{as%G7wkA<1wZZC%s9qu-vy_k%@jSj`YwfBkotuE!hqPH+_lwS z5!47Rt)%sAk7HXmkX9(Ky+x}s(FmLPp`0p3gj9IZ3$<~$=fD41Nu?P3KT2xIZJqRR zu-qKu8ZF>4W`%qw1DQ)8y3wBhQD8P5%EU%-!tpWOuAf-(90jDMBAm@)nXI*Bl|d`v z=iD56JO;?9CfxPsI;3gvkld{c1Bl6puf(nbBEumn$AbWEZ5Q-WJKB!uy|k%HJ5@8e z1ez2?&_m|dCnsm8K9RPqM&e2SPfE1#r#@n`>UlwEZoYw3?3+S(y8cm|W^h1uf#4@}lr?;|z7!yQa zGoi>eF`gf^_`z+BC?hLHK6~hkY2iicz6Fo%7U8pd$B#CHG8V(+|K55N^TRzY2)u-E zzsND;%F|T3Op_+Y1LEv{2vh%yBwHgJMIa*QJ~U?4zD=Y8S^w!&Bn2}{D3Tj_@GAeN z>+K+v0vK=DCT75U8{?dfTBWMHFz>CuJmN0fFK_$YZ6hETQIKN9LOqO_KUIX^s2lTA zatB|F`0HoUpc1}~=%dK)(^${VuBAEjzKs0KCmUy87Ogc5!|*R!7;tQu0Y9U^ebmv} zR8w9pu%{1gB1pM{OXKFY3@$Fu^9pvyws6unx$YM>+0*XjTqUt;CRUs}%T!0<%3pf? zHuv_t04brN1B3}zc+(}|d871X(YnyFoc^klmzH+39DR~zMUjFC&5?Uvf-3;NalB8k zObLK@avp}u4D#?Wj8!#y=4gV*E5N&Zduscxr;qTy#*sxeEzXD)zPNqZm0wU&IOr2|qnuCHF9a>&fIhBP?el#U}y?V$})w z?MY~{OVd z*>BCA9|jEhss+v#B|*HN6!k=b2#(W2w>GTl0+{oJeKHUKU1Lw}PO-b;O;F1(nI)KwQO;?=% z95|K5fC1PfZssu@Jmzq!75jPGU7JYWdGFzwG=l{jp+qnucFn|%FU0!kDvwa)I6^e} z&ZIBt>V|?MmC>C^$P;H+;F0Gq24-2g_V<-PJh{n!+l)n#O?4A~psveN#O{0gk4SG4 z@hi(%U>RkM9~3+WFn+Q7WI`-sPIoBJje5+|_U7ycgEUuqQ zFQJ99?2_q7LiM3;2b4mLX;f*P3P{L|3#7&?L~uxt9L}Ie`@`$*If{$6h0A~)LTppN zXXa2Sf>a{@nl44m`tEd1;prbz0OBibxQ(KzrwflL0p&?IQY;QB~arRcv z>x#4($V+M#=_v)trERw4?96O)wDfqvYM7Vn%wSO=Qv(J(N)s7L(-xxw`7hls`tma*2VjznzqYL+}`Sh zbPRfC-?9b;u9Mh`08_)iQ^kNuI+=)e8FB8j7Jewmwj6H!?{1sN-J+gZnu$zU0AVTF z8hnAZZuTlfu}Uz67Y~!dY)6+|7NxJ->UL}&shp`@3)wTFOB<{af*nF1IPI7jjwQt! zk6SM%!(Ev${qX}BN$9$3Viuz|h@ViKx5XoHL-5?qO~B1dyYlq=f?0;1lJ2lTglNlB zg&~tZJYOJzE@3k+NyP|ujBQiR^qXx7F-w`_hTe6ARk!m$V74ho69x!_m zOgYhIyCzbCBLO3hb^MP714v&;wpZ@xw3@Nal(AY*n+DBRo!yG_N8-8CPZ!? zW)>|kX|_t|ZP}G?Hv?~bZi`#x*fxt*6q9L?)2HscUW4>5T_-kF)07(_KXqISvuT66 z#dOt&;jwEDx<`U(Xb-a__pGQAv*_z*$vt?)7-rT?vd_{OjV?i?qzCw2awD#ZJG^~+ zSb4T0z4RLL&AtAIRTut$4zm5XOACbU#u9tuWpH2- zz*EnxLx1{&4NN}BLSvc*N*ysbs?qB0+a_uUlI^l&G=wYmDz;uRZneAT=EU#4Zxb*_ z$quC%+kM>vkWqc*YTOKNFst6;HtT1RvH19!?nk!eG+EJLtx-r@^yxDe`#}H(ke^R> zL0O$aFMd(t2l|mKCDswRm_yyP$>R=a;prR@fuTNBPkBARD`Y#YZgst7V7KR(QKIlb z#UzN`5wEd=PU#hmZ)NFKn>jECvyg-t5{oaN=*gDnNdBm&qkGq7_uF;ka^kbAzBsc< z(D7ZLsdAcU?2ci{U-UQ7Ywx#kzX8Sv#omu~ife%@17x2YDDy{%zCBUs_NX_u4)0Vf zg(`)_7MNL--WRcHc_}qe*I?Pd@Sgwm)OngBxoLt{%LY5@Rg=5>pyNXhj=xfGvNn0z z`|6b`>2(w@Dyqmi$ew())dNrz+1kM3A26H69h+=8b6>K>oOZ z?9`NDo}ZyNSLB5mW}6~!cA|s8NgodZ+mc_)T{W+<;$R}1@PM@{Py`p9#9?NcN8w!b|+u$($pcuB$H&6-X_CMm$?kDPPWjM#_dE{$*-R*r?+hVy-t+KwzsiSC&kIDHCCxy z|GUMi0uhI~m^25-2=%i<7or#tnVaN2+SAXAkNe+cGiRr^@7&%*7;Iw-9avq)NI16H zHajYsWsVj5(>0=V(_d;FDHAa=QkXh_-rYOYvOEpB1i$z;Hz*EhM0m%K=ms#}yTd_0 zD7^ht|LHHU(9!**233bbcs}I93LiP9emK3Qo^fbu&Eb^EQ1e^f5y;{u1ET4spZs;% zfAu@fLi9#5v-zH8ld>84@dC>5S ze9$;~NM!rpQwf`djUnRa2jrW=2$?VTWW{dvG&yCPNAD{JL!Gnu(yDll|b>NB;tJb^V4BJY|)v>D=7evMZ;#~h^nN1-E$>y zyEZ}(E_jYOwAC`x_0B~+8$kiB_D4B=GfevgVaCT}?0Q);tElpRb- z&;ZJt_iyTT^9NCsQwd(FT)%lRF%v)_VL$K9daTJ6q=b3|cw>lbK=tIiLSTeV^K&x= zAgKF2JdS#MHDc}@IhIu@*Ad6!SzmnjdPE-zFf4@sZLb&g%*jx_KD)FhE}y-_1`J;q zq3|H=GTA*i|0_2Y!oWRNZIj8s5JMB$^`#MexDYA$zb?L$8m9gd-W4(%b>a{21m8|C zi%)mB({qRbHm(3My}-fygU`I{m{Z!EDVn%ZO8IKpi07mqpFI~@yW{MLLKmr-fJ(gi zG8zNXM0WEuD7Y>>H<)!YfYr2=dyZOWqso4PgoD{o#8$pe3b^Q*EEWBl8G)*mr2O~Y z-wTlYAFWoCz!?}b($eDf26;lSwPB_6F;rxA(pOA(&#T=_bEeah=DRbe3mLQd)0+vW zneOL~Z(sC}j8o}Jur8h&#W@R{y40AQ6zlGM*RzpcBek@7SsYRrKVp%5cqp+ZBiSC+ zB2@!JOlRwb-nVrKtJ*UXKa_N-LwsQRD>N64XA|iKxC^@4#4RTi!HEqIhHj)&59wD{X(ypXBVC&wC2`EV}36%<^+``Jdf$_}3R+9)vA8Kl3`~6{` z_D72y`9U#6vO3BWeP$0Ec@4!+4sZH(dwd2*eR$Bp{O8ZJ*N<{k{a=@JOF74Hh^MYX z5K?HZ;Z1p^I>AJ=jvalUSu6D#JYi(0m$@Vgw2C2i9K)W}^fRs(cxyFaT?xk*$RM^|qCXP;QY<#c<$O46^ zo|cZt5tdH2lcMM${=g@|YT~f<28@#8n?_|^3rx!xx?pydNIw9luZ4#i-IwcgI`ctgqvA{+@m26zWgs{~E{ej2S zNV0)gmcLQjJV9-?-?M65bV?a|hBS|6_X+J}+LRDloG7ABDxsAwHZCW?&riqaV zqti9Eq({WC=x#3`-}$xe*m?dtZpUV90u(W0=m~R~Do>!|VKl`P<|ba`blb2cBtzd| zAu@^3r(|{0MJ>e+KN9<#Qi&0xJkt=Ozv;pPZ6ybU+JS4qjPxIDlbn|09<#&S|G z53`fzay={NZT*@NWvA3(X`{v)CznQul}P+IDShz?P@c5LfnVAN_VVll=N~VelR`Y*1*$MNWi$1 z^IvDVfH{HH<zWkJ{N0zJ(EKRc0`Salm9wEzwte1|N9^E^>) zK*29T&KrHi^`D>RD-kv5k2@PzA;DPb@j!|o030ieJZNu^K4IE4Lj_mE45B8^Mn)pG z{-y`S-I^bYH#O)>ObxS8@>!vGvpET=R>KHB$O?eJp{D6lUzEy0sV%IoXX^`>M{jW- z2uKKh35ecL6E!8UA@$-rQd zL1W>6aMimX@r08>K`iYDPQ}=s5@OHpzcnX`wXBg29HjM%Rg}hl(cB_RzA&0x=tRl2 zZF&MV6`N)JB(_-&%D!UR0SOrqb*oh>)-^t#@Bpdqe7o)(aoys?-#OuuS*ZcG%^+mq zak(vH)TxQ&cvoen05!JrQ{_A8gu~1@4?6Z(a`)(WGN$K;r^ryM-hKWKh#4#!ZDs~r zca{pZC7pm%hK_{j74asIBnU3YkBhULEE{U!sUOCna8QeV5~lF-_~wOegOK2=NE8}k zHt+mk2x>k>7<1doO0=~i<-Rwq6p2F(SPzxVIMpw%-cg@0IB-)oOe_gKIwFw@JO6w0 z*N1XTCmG_eBxyZq8;71Gb&eYzoLzW(Pg+pCrZ;|X(pJKy4&O!8t(4%*KpoLhRlDvd zGuIvJpbiYR<#7`YJ1}nM@!4ef7w_W+5;mq@s!(!A{+3eJDNU0XxZ%LdqnPp;Q$aWB zOo20p{_}*;IU2Wj>pm{zA;&_;)7-thjU2C-Yt4`gF4D8g+vpxH+o>${WrCMl?Bx&X zNM&K2C`WQtrp)|d7yOst{g0enQKVb?TL_4{aDCFrc!agi=93rQ-02Zsq`y91jokc? zhM+xvtor}NOaJd%@2x>q)5_Tgif;`wa&vgjWyk&j`xRS~%$>RnmX^59+Qg>^-$Av+ zldr3I{x)oo>{`47h^eis+X7NsRLh%Wua^A_?>u1%0*GVn6EHMS`Y>HufClZ{Ac$7E@rk86!Z7v#)eHl}}WMv;LmNs65ErGA9cB#p5K>@UCh3 zTv1lzJ^C)tIciDh<6AECuGjjI`(*>xN|r-dXm+ zOJ%a%G!?hyqI;ZNX(Gfblp^N)RYp>3N=+&_|8~vfHKiUA+>x+XOPRCO^Q6y@7jhbI>jzfx=dX&AsXW;2QJIw)4{)>i@WY?Kwz6$%9Y|7w9#(a*L46)x z5v6gI;LdNK;dVVHDTm|($89*IG*zI44q&;eAsZN!+(N9zWE5H>M44t~>PF^D%G_dK zYP5mm*}e_}4U=rl*RP){3L&nB(mx>sa1O{&`BF&HVy!_A=ZlY(1l=*}vkR!N9DWrxla$S&Lf!p$Ht7ZF^n-2)sJa*N#CnEiPo?ID#&YF13S_2 z$Eg?qjc90$917`tnvUSpFJv=*N$|(4pZhBTK&d$skUCQ1TRH9~7Tuy-efd-7DMG$K z=N=abE~VsX9lIecK!&)9?QI!a87In0Q{ych=5{pvzyW&MjZ z*XiVqOq<_@%jJ6_8V4Spsc5mgw2k1pe`@z>#SI}%66RY0sP19QXAdM~cmHuQ)wT5? zhZDmyiH{uScO1P4d(#ct4I}(0A$^IE8o`hc@C>)>4x*8c4N@ zhhLpTJ>MWN_V#a)FYBzOtF8ev$andP_&4Z8R!c&|?UM2-G12ud30WM24)7(RKez3E z7zq(!^ziV|ty73mJ%OEZA_3~m=qnqJ9*KHcO5*YmCV9&l>-igdqcc{T3LkW(?jE8+i8fiSxt?eU;ny~`W)In~ zXG1XwwJ_s?KS{sEjhgfFT00<6aqVCgmdOJU9ZZMf@lbwmh!A zT_Il+W@N%SPDV%j*i>zwd~%s_Ak zB3XbBbwIGqOq#4rLRw+(C0F#4C6wzL&bdQHo$$hKDum+SQr2}y*6SIE*BQf`C!JbF zA9NUsfa5^RlPoIs2gWbLtEksX_y?Rv^d=BR?=IerWKFQ*=#bo`B7W|3fD`<0!C z?B@mdlFin3H8r-kYgQ#+OZrHSM?st>UNdyB5qidD;&szpgGEpI5XYDiGtYH~J~nin z*Sxd^z9u)kHam#IAR2fRNBFBoTTUR{ieEiDem<=guVtBDIA#5x4bW+LPxJq8fR?{q zl%`wL6qhIdU4!SG%Qihc2y*aK0{Dm6Wf0_!K|lYX`zM*+4aojV2tx#u^grzIfOrh{ zEdyLO{5dV{=CS_l=e@vY-OkwO$yNrxv;T%Pxkbb`eNr+xs^#J6|Cn4Z|K^CKPf-^n zanWAxL~khQ8NxciwwVeNXYu3y_>2a9NyCU7_V3PgOJr~}Q8T35bju+PaLi_yTN#;G z;m2;rqeJ{OZ@&tUHkmJ&o+)l7C_nh5{_E98ekVGypWJWdWo0aYuMQ?V6me>EGNkwL zX?&c>;q%Yl@BAE|a!eD`h>poG+*=>nM=4X5|H=Zi%yIy}k(j2_eaa6&|DyVqr5Bu$ zv5|VL2+YfU9{bE0cYKyEoue$;(`+H+LLsU0w}3FU$a0{~q`XG)RK1aW zM&S4v4HN`w6k%6c*x-C=#)b)R(K+YAMn$z`(GGJ9(c7wYXjK!j)_tNi6eNC()aRCA za?;W0xp-sbrS$%3{Aadqe2M<^&vAm&zuidtAoT@~eO0>*$ecIx_}A(m3E)l{fraWR zH}SlI+8ue%w;`0xUgUp*Jx#P^EFf?@`=YKHtL)mw`lp6FCI}zAuYHN8;ScO~$MSS% zYI$q^`gCh)Szb-PNepsE>MNw3*P)5)*F@4UPE^^S6FEvolWw$ZRShhV&0^I#Amwkt zW8bpJ;WEAe^lmDJWLMrpoET0NFj{5;6@k&GsL$tu`$M_B8>giu^5@yeV&GDR`k4E) z*v|%n5-@c(Ea{aJPJi-MBSL$4w$J`gG5kC#LHYtx%&*2D=5)H@j1ULo0>*B7mAP}{Q7-;1CMZs zOgs>4csh6uMXc&YSIw9p!eK0Dc^XCY3YCzJEw@v5jgtQ5ErR3kVfx*%XE}S?CarF8 zTLLn7Gqt9NrzWqPRFj0^Ak*JX!lO6M&O|7U9pYjU#G`eilJ=)(;PHQsn76Hxp83`! zvILbv=wVSJlhmH?U9<01d$IlP7qm%4PAdM`RZD<<9nkC7pHj4>1|ep;1uZ|b+mUwJ(({+olH1%74$q1t%H{x%-l^&YPN-1_rqaRbZF zQ71YUY)#ljaPT6;nI}Gn8fxxEe;h@p|BLY*xR8|esK1x7V01!q`gi%>;h$d2Fa?X$ z58#FSR)DE(S$vAjKCwTG{j*XI_ zP}PEJ-p_gThsXg`;V%IC%RT_ajWfRW=s`nJZN15AT%=~#p6@mNDOK$s7b8~`s zWv|SdGVKhSb_HxRP3mdW8Ui7AEof-gpwADD$=0CtkUan47hR;E1#$0~rcY+gZi3{u z0-m0jp`!q@*@sZP(j#7=sEeX8e~R6{(`yUKV4sy=7CvrV<$kbOGA>%%i99L6)NQ}^ zX&4`n#Fh0k@NALFgrpW8;-uCK?_3BnzIHB@Qci*fp5IGuL}=|oFxhCG6>Wn8q^>Ue+KA7lgwJs0IQh!?gZKJ>B}LqTkbWeXQ!>x> ztk$4rZyeaBZQ&~_d6z1VG3*)O%NYlC;cJPD`0x^O4vIxqEH^sj5}NS&f3=tcV>%91q#5E27ELQQb~Q#aG)#G=Qm8Y zGQ!Za&{|u<%30|iE-|W_O48?^9Ac;*vq8yO_UV3_4Wg~oWWP&2J1GZx0sGK~RCCZ1 z9+9@fZAQ-$(&x*o&*2M}3)j8_h8D)5^qz+phYxJNII-|NYg_#vm3qaEBfXq6Svdk# zCUXMujLgoKXeXu*aJ_CgGh*ve%Sl3j$X_$Fg!d7Y=-9RD3^d}n#-JbVf#*&2?+aOE zc&;F_i+=HPY9=keN*soRvX@_bQ4yOcC;wo}rzu%S_pruyEUO%8eX#=%0FSl(&F;#< zzq$*q$wuB*cnP{fji&|V=mpjtYL+oUCy#0`2RSEr_jxuky%rM=ZO^gZu^*qk&YC<3qMl&rkd0m}BQP<^-Q3s~c|& zy*ftWUl%$#`PL6_Y}tN#erqVbf6FR@U;b+LE&3;65t`qhaBbf z&xr6>O1vAM;3ErkHof!eA4!ROcd+q&Aa?0Zmd{{@=Qm6k?0U)niFk%5{mfxxx)L$! z_||BD&dal>6jxZWKLIaNRnwc(o7;17t+VYY`AH681T97J(Ehsn<6bIC=11VYZ{LVi zKDx=^vFtYlKko5@51Qx+9vx|gHe7Pe}p3jbPd38TA2l8QYtQ{(3YZs z62d1!iW-|MYHV0_zqbCFY64l+uS#q)$Ez%MrD77QgtGBRUw8;MtmYU@R@0s(Y;?>> zytJrt2$`CZ0Oid3=K~Z>Lg<|hcxjw|Uc?;Tc^5d^grwJNKZ`s{&#){Fdi!+iYjv>o z)noNHg}+^A#fA}xRI1_$`29}jK1F(L^fiT$Yjc0iJ~sWm|uycS1!Ea#|R-ofEFu-Rh!B&-I6lw(&=I- z6vm#^ILV}MM;L8(4NG4LMSSI59CW_4q4}drC5xjhWI~1IO_7I<^<&+M29hCvk3`1(3<$;(=_7q5w6pJ1>P3H1kTo+cD02Q@^4x6E zy#CukoWiYcPt4=$MLd8ei z;@`QY7Yn$vgM*v;rN3Lv2TP=(z}5wz;V-7?;R(rTqvYeo`G5h41@Va+>U0;H58dCj zEemB&vu+BRc>zexIiviFTVh27v{2)E>0~zBGRu~3pr}CrSh@*&B8B=O&?E(OO`VyB zvcN9W*@1%u8~|E(3fj}>$SRZ;vR}!$Yw*#b?JTQ7ODY+BH&?)voP&)L3- zQUqTg_+3G;+Uv}9b5M;F!)4c>hQx!**)Z@;6pK-RK$ev57PqTOuZNG2hY$YI=yd zeqI+IusC5g^VI0W`-&5fJerQ+Wp@UY=)bfV*qZz|^q-!7bAd>`8MT)g3`x$s4|ME&#E77yI3Fa(yEz=& zD}LBjC<#14QWck5r<%Vg;Ktnt6l8;edoFsCnGTaf*=D}?heQ`Q=}F?itWqvfa?sJ9 z$8h|gX%JRwXra`Q8E^9KM8tD(`n~72IiDj*Mxj2@_x%ao8sz!Q!BZkUT#H;GS9=>BSYE(Qdvw(We}aJF_27U zU;;&)?ratVY2nU_C~j-$b>Y}W--~n0j?H4fs7t`KH14Xa_?F?8%IRva20yF6fLD+I zW}?N;vCwkw$Q6J!CHihCmN^;S-JD0U+BnU zJu442dT_M=`H~35FysiL(&RJgmm-w6yHTrOK_dM2`3_Ax-F#)BleJa9&av z^B{1rdr2FgR;)Ty?a7;GUsEn@JEoj;naObW@chYy)-_77V>fJGAxslxyv5t^s9!tC zU34D7uz=Cm*n&95^XTnojOm?D@xE1xgS-b#*yAVuM+>8T!6(3NVoJSrmw`R{j|TsS z6t=>YotO~mEFFGJLF7ID23teo1uKsm*IAep73%HB|C-@idW42v5C4mIjsNO)QodZ; z?rahlJ?%A;m2p~5-hs}d;Yli=KM(qNJEWEj6O5?#nvI!1$p~)wX+E2=k8{xyJANxw zRKgecPTvA6g>x`-V;(rzKm>Hed-P;brS4ubR?g1{FL&V(BLe&PCDUFk5A{tdCwb{P zdDVaDnBAM;n#jsu?(e9T*IGZW^m;{VsnGsu7`$D=&f~1OwPTqva(W|SgHcvUtT%9v z30h4`UfQ_)Rmi=qVfq~G1YH=7FL!`!hOFlsXbm)vNMY^{G{m|c&D=P#QQ9{2OO=Xg z2N)%Kv`Yzr8oC1QWAo#+l2xm=ts3Sz68jyC;L9Ez!MGCa!G5sjS<$s0{A>& zUD*ACP}X29pv157w#uK4f5Ir+R6^%p*%U`YH1N4wdg2rH_3BO1If!^reOHIT+r47< zh^Ro8(yWc@WCQU~WxxlEOV!d^E#)_avdT?w1`#7J#MZxkmt-0~35&bFD`Vu9u>VQ{ zI5A2nre$r?9U-nKx4WzRXt32oqUD~peV8m4poOK)w+3%!{#jl7uJB@>^33WdO4H4- zTTbJdn&wLz8v5tov_y7& zDS*p^bg%j=S7hMenZbUfOB}zd(-=eiH=iWMclAl%Rwn4PGemU4RE6HWgS}yg_YQ8p zV+peUFs1sTSu~_$bD~Gj*53J*#>Vf4#>06!T?(l)9yWJ@eW6sO%vZD7a>@CT=RF^L ztM~Jlt)_Q<1}&G(W(2o|O<{;rSs#({5KYf(K>ti#Rr5tf-B zU3!Qk9s5w)L#o=ZN2J8^Pu#0NJ&#v|-Cc1d(rEL~W@e_9fQI3Bb;lBZ(oQ2=Gx|lg z2iM(?4%QCx7H%__whg>RuFecDDwdF%-@UGu2)m1iOB*B>X0Y@5lYIk(Vc)LFIW`K` z!CUZkWneGF)0gY7xlYTOU@`$oK&khSOjViD!cA>@b#uOK*TuG{veo?CLdnXVgbcD* zlpH7X#lfrV$DRNeaI(pB7gCuFOK<>#rkKYaLziuUlzz&TG@irE%va=Y=~pq9Srp9S zos-_4^>b@ESHW9X(YB<)JA0Ml4qM&9NRh4w?zmYG>=@p*ClQW&WNC%U`q%t+p?2pO z))#HCkUq_DuiwAO>$GKQM)RB3)qMJrNxm$F?tO<^AL8{FuHwZT*G_KV3(tYo`-G#q z+IKnX$=pZ`v3o9;<~w=g9_68J!u(F`J4T<>Ddt-4UI(j9t&S|U6wMOa)N5Z6zXS^u z8eO|AzTD%z3JqAey_N=u6q(thfCN@r*3&qt#D2kPvpRc6z#HIB9f-n1zjdpeCVeiC z^_<}K%(0z{63|3gX|~1lqwOSVPjD9WW07b4nU&Fi1Jdd7pM@f$Kjt0rr9w#?l*Kcv z{1ISv5sKmAE$v1?>fJ{7B`iMS8t60VxeadN4YHT>d`W&wkn$2r9Q0j2SlW{ESXu8P zGf>JNm;`T#5?vXq*Wn6*&zH2m0 z^y|f%F~=T+7uGfPrfXL)2c;qV<5S~+%1Yq4kl_A&9cia))bm=62P+ADa8NAcJx{#h@$K|HD)@8>04O)`mrR$IzFY|{0o__um-(w%I(aw$ zgALT^_Ur`$CbysX?d{nVQY%a2HV;@Dv3xE4f$J@Iu}ux)j!9p==7=tM?jgMS!m-Z0%JmFkZod8qDgy?p`Q|!n2UdEZ^7pKd?zY-Y?T`Yi+KZa6h;%boHwp?0 zC=>>hTFPsSSSuP8`?ZpA=Nx2i7kfaC@bM=krU4?4TqLG-6v3eUWT z9$Eq?dE?O#Rb{tL9eF1cs6TN%g};*4rSftfKU8_*cC7oW@zDm~vmzC0y_}-TN1vZ{TzcwG560^|IDNjY!#KDPa4tnAuLWck@i}eD zqR(1s3NCBhC39(|*G`w8to~;A!a79r>PLua&zDypY+S?m_5P8w?2j}nG!`MXA>}5u z;+dfcGyS;vo`^GSmCv%Y)b_RhS!Zf;&H4fhg6^d>T-dp*N5QwRWL)xgyV`BIeB1Xm8N1U9@yD{7rDR-6N|_&f36KQ6u15JGRk8B>?~O zNiWNfI`p*cs1T9rW@fsT$`~+v1@6K zL5VwE;Z^KKywYp;LCYr&S6N5zCfLzT9dfwZ6PUerwQ{_=Io3#5qq~iL{roWA;y0)f z98v7mE;B64zHkEbh<9`Ir1K{EcJpW&TPBagBSNprCYobk2~+ioJR52HK=|Ju_Txwd z_dfQa2KTim^rBozzBT01nCN)#+XFNKg9KrW67PZc*J`vVD+xFPzkZU=>&spTz9xT` zi>sJTd2r?E`(51Or7tg0=cvGyaFb0hqkSrc{$b@29UuhW#O@nP^wUk%>%M)IvI9l+ z^m=O3un-3$(II?}*k$SO`?)5({8LTltKbp2Tr6ou>g(wmg1HTPDADM5B3SNHlCw_) z#*#nu?84vRhT@;rz5GWqZKS__-vjI>sUtsDgRXn3uQm0OalZ(jvxb zEn9h`_ldsIKe$ch>dI9$jBxi&GBr(tgk?Sg_II1QclC#gE7m`F;Q4h}aOTtIvvG|i ze8As|oF>U*<%`bX>0eo!P4^0{I9VSWiw(121=@>p6k)~k^b;44#m*`cBwT8S=Cch} zjrq|P+stihP4+#pH+g~!Nqo=7f6SG;045q`&9;d{UQ-;F1iF2UCV@Wp=T; z@8Nv0*n-nM@C0zE7gK-N%M*TJwPmChQ*mi%&TgHhNk`myezcmmG{Q6BZw{^uV9>!~ zKDPMvs7|QxN8NF|cYOyi7=^U6D;rfa94`HlEjkWt8c-@&CnXRmwreCMJD23xCS+$O zj7IuY3=bs3*j)Vemcd^F7|wCJ4rNwOIFOM4+^^dwUq%xbuD~YT#OjVf=YYJ;iv#C6gfKf zFM3Gib8U`j96x-l&K#H|&JZR?upS21w_MdYXhhcOtWGgCsc)y24oe%Io4;(>D-dn$ zf_=aF=TloDm+S_;%23&skRrDD0#nMX=NY3`vATnNK$|e|w2wkZs^g2O@OSrxpg5D) z*f{n(V~fdQj9gD>tERuN$G%!TV*;44{gz4Bmt=X)G%Xo?^_!_C#|;RmSw~}yNo+@$ zOWYq^#0T{A1mbpW{Dc?)tAz(?Ef2R*@^=~yOFm%qWm+6@mf<*Crs9n>oV(FKa?cFh%USxuSsD2HK3{|fmB(`-ec)ynBS4W;Lz6S{eI;yXs@M* z&sH(|4aXieornk9{o11ItgBY_z-MmGeaC#B-=i*+!F z`-P&wbqfoag@m7$ub35rK2lLht_0QpNP=kO^N)D%5Fb~vF%gA<=RH3+nYL+b>k0Br zC&2}D&2_p3)6&~G4UCB*`>>dAV3fDBC&CR&pfE_YM;U*vwXTN@sakSU=Qy<;zjKvu^fC6QYcF$On@jaU7frrZaaBsX=9HvPU_0eiiEsPPDG`7l=Mw)w$q()YZJeZYxx;U>m19quG4}K=Q|Krg!;0dih z5Ei_yzRr?|;kp#+x$;@tJ3N^#-EWSDGn4eCfumae*4j|$K)FDJ2d%Dri+ ze6?cUd%g^VJW@TvI<-KH9Q31BX_uK^Ec1$B!}**~4q?(uD=f)tSzW^;vA0rjmHg!u zsbF)7)dW8Ba}i59r`WSEg=AssG{ai@2GbIkYi;xsYk)L8z7FdUvz2hEl?eB=bp7_x zDAH-yJa_vF@?tDlkGBR z#A{crM%8S@mJOzXDO3=;h?EvJE90Iqj31paN^&q0nAh_T5WJ3p?mJ$)%-LDjIAhVT z7uLR=rWciSHf&eoN=u(AIE9~`yGJU!y+JRIc_4zM=Yfcb!+UWT(8dhUPycBN(wK2&uW$dWB^axX75VR- z!2kYaKaGUD3K(ES^398(ZeL{$ziv`tActP=-x8uQt>sMt_c5idl#{Zk&Z)~!T8Mkd zvcGalKFIoH)bm zoB}8f5Oy#ul<|k@ubuDv3>Ls5+1hBzSz+qp>HGGcDNA)3QO%f2` zHD$!hTG&GX*D)-HSO!k%Ex;Wu%34J`k>WH77F&lOXxirg#khb}wZ$*g8@CCD>G@C@L#c9mK6#l#F1ARP9@pcekHT zf6%-&POvr4au$8=3-ZlPBMT$lpb#jWeM%f!`%Z_8`&FcMF)sqsk088t_nIDBk9^Dh z>Z7TJP#hy7s%Xq+t51nL{PasM__r_{8FZ~Fdz&XtnCI@ZTtTu37d{TBL&mDAxexo! zkKoAOsWks?@JSM7P>yuF@oEO-U6F%KM<-sS@nu-HU@igL)y3!zO%3&E-}UtTnMFDi z>5^kz)afPZVz>6#cEdgk`$*D+!%5m339~09gT|WnBl8jS?E=Mx6}5@!`I!6{`~eUY zy+8k=Qq$rykCP?N@%@M;@QrYz=v902?fk*v1Un78=P4b>22S%9LuwIFQSv$HM(<*m zbbP_b+0NU#iobGie~(64+S`Bi@9q+f*9o3dF}D=MU|D$%fDPa_U14)dQ-~&a{K}M= z8U#|FHf{VIM%Tsc`s4y(JT+Kx7@KTPdU0iiBz-o&R80J1?|>|?g;bO6!K?(6(sICC zB^r4htDn+Za|3}Xq;P=@yuv)mK$)mc#4<(e7x}^%<$D(lFSCzS?TKP<&r0A z&{b@rnDTn)AlUv!g-{twOokdf27r}|sWILJw4UY^s8ZUGB3p!Jw}~GEJl!Y{$WU8? zs8d_4Ed^g~9YD0Ad|UH+vE{s&>^cV8h5k|gWurnHdH&F|`qat#Vr4`*K-ud^b<0;e zIg$32?xSS^i8V`QoxlN73irq~<|9uH zO74-pw}mZo&n2k-3rXLYa$nhOm_||O*KKTlP64mZZqoo<-9H1N`bfwyNAmU)R#E#P zz9bUu*XRbz+8IT7_g{^vYab1~Y70@q$Dx|||M2yeaZLtpzxe15ML{Gj5Q)*=>ziW< z98W*2ik*x=NW!bR>EZ8(>zz|gNXC2pRz4pTV(}ZCS{D&)qgB51gTQ0vm6=LPyIbI! zEP5^r%geNcbsJIt;mYado3Qq~IXa&&C&P`$o1divw&k@*dQly?3OiL_?nBZ)PZCns zT9zz1&m^;O0KkA=q)DSleK&Ja&fV&cgd9vaupXG(!{7|L;Qi}6THOVgE= zhvi!1bDwXH3RlQ6(x&PtkV}mBdA@k!JDaF#AZLi&?`XfFC>$mbWKR1IoNhL91Mcj% zTfXj3Iq~XT3~R|CyD_2TK;4dE#e~`nM)UV$V5oT($~7Df#slh#rdEEMuQlEr!I&_t zQrUoL6+z6kJ4&)<8Ap$h+LYgFr4daF-r8cOo8fO_K3!-IGs^5HNFJi4f}-SiN#Q|V z$?hRhtdohM?}hp^c3O+rxYEK(-%!OtxkV0dE`P%;-tFw%k9EDkzS#fo>)vjo2GvhI zxfZ_GJvq2O; zuVQYs>CVS0e#N{Ao*>+7uCc&FFh)Pm_0th9I^x)`6mUXtzonWHG;>p>qHnAL(c|qW zx6qV>-@@L(^6f-6;l>_aN(b44{`E;~pp=y?FXK4Qv&57PNBvdS2vzP=-gp;NzJu}% z@$`nRV41=G*cPDYTiHN;TTl~l7Q>%<@#kDR2@`){Wz>u%cx2H3{9(-Y_GQWe^ zbpMs;*|!v@G?&^3IkRkRs`k4B{)`N|enz^eVe_yA86bgAi604+J=TQBQ8UHhA{~s9t^!adG*ZlYYFh{$C#HauD<@O#WwQ!6vHVY(80wU4h zIHDKbWzTrV-_#p9U(rJS_4lro2a7IqjOv{dqSb5U=K?3-p2`oAQ?#Qe?9zY^POCFri?9rlNyjQ1R)8+e9p#RhsuP+a*5k~RZh=K+YnB&dZ37`qLS&E0 z&k|nQZp5?)9KADvo;i3vL`a&b=<>ZJqZIl0)lZ`J--`B!5eW;qvV<_A?QWDb({I?9 z6!14?)@Ci*W8i)j(|5nWx1NQi@;M(`Rzw;EsdR4G{jFBs8Srv7$M6;5HV~k;Zyy_d zq)*8kGF;g1tUO)r?rDg-!Me7(W7EK^Z6j!LQ+(qsJrxOwKO#h&g(&%Xh+frDur$ea zxjM+|8>oj3ZWzcIv!F=2R6I1=1i3HDbqPR7fBWD>9Rd3`LWPZe_SI?M@q2>fDgK7L*KLy zS2O;&nuz9RI+I3p5hN0Hv6a;bsc`t_I?40z%Szt&iVwC352;@e zjj{^IfOc8Xgbyt6_~H@M1!I|Bos?qF^3mX~+RnY*2R(?PT>%_B@~LEXD(I`k9O^V@ zZdDuyi-Q`%HH>4<7$6nq|@?nA9 z$T4#@^wgHe+g$MlMu^vK@^T*ehT75D>X&yLmKSVJryjL4xabvGk#;r(<0xm z?mnNNUgr3_#`7z}KJ?|z=)U-1Gnlsu+bLl8MEL#r2NbD=CElyIjENdyu9zJG3@(fq zov`Li_hZa)tXH5^`V?>TA#k?ux}j}S=g(6S{HvtfLcmEm3iIPwf^s*g=>m(;x4Um$ zSj#zeaEFQm6c#GbNp=_0oVaN5q$2HaX)57StLg_YFqrEGy>MBQII6ZomhG84sjTl8 zDK`ecVkfiJ))f=g<@1p>c?aV!?J5@(b_4URpucyfarx=BGAyPAP2pfx!3(?$4 z%U!XU90&}`fE@umbO z%+1Wx?n{NvUP7;EaM@dDa5fK<0}_kAq+$xoxZ3uFF9=F$Z1?e_3B`;>|9yiyU&y`& zwGIiXw|YKZ{@!*y8+?^$ba;1I5{>}Cx2-0rFpU6y;K{9zI^U?uw$K?N-zW^~6Y79A zTsJJXKWy|_Crl()u9fg7LYyi!1mN{MYM>xi$;+e7v88{p{A{R9vrnr$^^l$4=3}eH zO%&@N%5U}aH{%3SAW5n_a0G;NY>=C}Bt(3$vb9^cL9$^c*0?gROCCRATp4ZlHBal!Jg0MXAU5hPrQbQ2%{+7x&@J6``G@GN!TM@^v> z90Gr;*#;74bt0Z5I#J4zE|0LB6D|Y+{8}__m9JQ zG(jv8`n*od(2RNc(0M*4)oMBT%%cbN6hzDJ;;3V~^3?aAg{r^DA0aCqI;S8~!g*#! zTz>J8+?Ts8D(wf?Q@^hgtw|EG-TpP{+EbWPP2{+32&u-bm|sQhb}=0|id zmH{GZ=v-d@(6gGOlnS5uE^QR#8{j8_^6>M8JZr0`i*m>h@!244_Xx2f=atI5t*^(( z8ms(929$kdDQcsoBKnb~S??m^&9jntS6PwGZ|H5obNpPPjL#07ZjwzrwN4aGd8?5( z?QV?Wkn58Xw%6Nhb@c@gN_`j~oL}kR?L6X7Zb{Rc&2`yvoZF}xB*`lHb=O~lxj|4? z%ASFA5SW|(%HZ2zuX*=oTn+Ij6itNu6*lEC94`rh*iZ-CXvi@7YPzoR@9}kOBW2dE zUXG^q4C-D_d-pVX`faCzYuzgvUnNU#>ULD&QL4C~x@{b7PfwP|FIzz0S_uTt>{6sKxk zBj6{vnRsnB8ZigT1rj!+0i%j`Fwmc^CvZ0SaDb5q)N@#UNs(9C;Gxh(g+V$lhOOo> z7C**jU*+iU`?%nUy2ZriQm;542;Lp%E~6MWxC&qq9Cr3Dqr9JeH(fBiCo$OtnpFUo+g>=r6Xb9G-kC&ol1# z26bF5}x3%8p|IXH~49K9-VTXwsMYQpGng_;g*SMOx9<4cQ`JR@Hr{ zJw!-1Da@0ArRGJoUzwAzMo*y`Hy)he@#iPJByg`bqq2a_7vKc{v#p8!=`nta&jz0r zitUUF<~Vm3X798dS0e!nfdEl|uCg_Gn9?w^v6FQLb2etzX{Srn8@{=k*flq{s9CDP znDz}%v}7Tkk8OJl%9)Y;;kU%Eahm2dQ#cv8Qs3uo3#NG0d+~X9I5JMLy>H8K=2$gA z+!jGfcyKJ-j!2pfX}bICHSb-ZB#F_~{B*7v;5GZojv&)^<6mN7I2$D`BAmWKKA)Ms z_0>_n4fq-VKtlxjmj1N-tVZLu-I^nOH^Ce#ms*%T;HdfF$2S))nV{ZT>@TFFY=qET zXUoC!{e?OLl)m?z-fjEC$3*fwPqo4vBF6(~1?}6fk`#KLh(iGRk2|)%0e(_+4M~78 zm*2x)_;gSm%iNxgkbZ7*J;5Gc^0^cUO&Hl%uN zn8Jk6N<~MNdz3~+IehYb6aF{7WDpU&DIh(7Nce@ZG>MU7zxI!h}Xd z%2i~!$+eM)_5dQ#{snq^+q|Iu6LgBosD6RsSK$P)b*Xs#@bnW?7|%sJ4C&1d(OAAP_+6{EIwqO z=}UYVH7DwxKyxZ(@ffpod43`Y4j&=SoR8fSe1>2f^^=RL=pL76M2;8YF^NDhiq1YH zt1}-tRNdAvcOCe0fbC)2`<9S$`aUE|0cEK+J(^sqh!fX6o8_L7ZVE~*4hKvx8+P)k zELkedv5nT8F2##?H+RUi*u=NvhuHKwbkEe$pLSL=DwYJIXHp7;9GZE~w8tJH@5g2w zJsnktG>GiHFWq>rvf1mbFp4~QVA9)FYr48IYb6`l*?7Vb(ERUTP}Y$<&T^={IJ{3ce#xCvSHGS z`RKKM;>^w03`B>WU+hb?>gt|`pLQ)`E?$DWnHt?Mv^Uph`TG1KG0KRV>3SI7a>OQi1ijQu2(Nl68`#sb(s|v`!cYiS z*=%mgOJZy2&bka$c3ANp6;4qS1iIy@2(84|5#luL>JO5C`3BlBIQu?ZFb@tLIN2Io zvod|a7UcK04#vamwIj0)D+J>5qQ=v_E^{{Xn-3&(obnYfK9TL1Z`5MO!qz4ZODp)i zMb6AdpSz{XM1}3wY>pPzI*2HC2icz=eICGe!W1_z@94Dn{gV+Eaj*&o1)-xL(AP;a zOYG*Zof#xq=up;HMehG3jRTR7DwFO0Z_>FW%AhxrqV){2^#A#j&F2!I_^Wd zQUkd3tz-3=WH?LvP>AT|=lYmc()*-QvTGVbCtpZZPc42>dBT(GRr>6zNeTew4ha!U z#xfjgM!qX7Zr^1X$#y{sN^RoctVBAmdw}QrUkom){?`5>Q`uwS$&iluhD*yhTf7;= zpqjE?(5cW70!cVNh3mFf93)%l?y|f!&|qel|_N^yFxe@odP^3)PYn z8AFD`J#U)<`J?ZDFG&14du~X#aHnr7UiHzxdi*Q!pZWqT@+?nB+$c?yFdTuOFJ&l+ znkCJ0?ePRg#43p1)H_TY87?_nyl0k30h-ADol=kFo{y40yB<_I=jcRU6MVv4gRv`1 zD@Yji9l~JQw?`YKxJsRLJ76Xvle69H{5%W*_9?s5q;RoaIYcsIq4cW`J9n>5ck);c zwQYrZCakDnJ7ipIG`}@^6Ppf~6Z$4n7R6r1g=jK-f$S7JI3?ST8>iJ<$; zGx9roHE~t=v2tV-o!&GatbK!!!^56;`3*kY^>8JBV&OgXMt|Jvw1Y>(AjBeOSv}PB zPgz20=)VHUPyV#0{ggr^iU`=xL9e+95KKfizWMW&tldX8PEge4Z-;sk{h_n(pCTah z1wYA9Pz>Gam6T9zDY69D#)=*Ask#*q@x`>a(=#coPUUh_7ZUBxHk&=924{qv?2Uo} zPnZgsn5z`hVKtg)6)L^z>dJwiUbK&oZoyHMtXX?Ztw&lsOdNnhX_>vuuz1VhJ!{{y z4^(X%_Y4GULxYc^uicvy%CV;hYY&dqCaaI1e_L;zS}LZM#p}!eIr)AL$!pt~*OFH6m_gO( z@(|JVM}vGo+PJxX^&HoR8{1epDiA)X0gmW8te9CQ;eoEm3YlpSa-@H&ibFtc`y8a^ zj%PnplniI=k?7dXv!m`D!8dfM4b9R8svr0Iw`;kn#x7-fG|ePwx0T8JH0wPi@fR}L zXx;fjp`mK4y@k8f0iZj+P*MxV|E{&VOiC>#Bww}2IvZl7mtw^{Sesz z@z%lvW*-8EN(PV_)aqV=B|=ss@$yPOw4(~-pPTBwo3oGQ2AuyqmQ77vp$jjL0glg^ zPN@bX%A>?d{*ex(g=v94+YTTrh4I2^qTT{~zgQm!mHEKmpPq!-HCb1P0%c>$J6pTz zpDvHTwrRPjt)(*JVCU*2t)sB>R|XqRFFyYcohhm|L@}GIE7rOkRrQBUGc5$XQ{Cy| zNRgsCVItRMOs&=3%1pO#e`ai$+Ok$#pQ@~{e@=q>V`*D`ak`zQX=CoN86 zGTPH2VE&=`=UASz@#I$~aSsgbg@LZX&L#ddNkWaFs&i*=cGC|5ucZ>#Swfvn+#?Za zZi}*u(c~zICWS}NivXKze?T128LTNd7xY#)!}c`q=x8Fv`Z4zdxo$<4$vxya z8k3Tz1qz?%WHP%LJ_*7dNq8sk899ni&^5;f=}zCh-u@>IT;U7y4K+YlMO2Q*yR#Bz z2}+3u)DPubk;P1tO?L*g4zu6F&bH$2;jx-N@za-|m5JQ=sBp%m zc#Hqbd7_qg&)W5cIjUpdpeAQplkHN~CSmjJct?~oJ=Aj|JmyKK$n>)1G1gNuI{~mmKmV*X`{zx^Paep3K40#H6?Qre; z&oEEmYvok_uVJ2lyAt&O8sS0rlFL_`(@ZS(TH=fVTg@b2B8p zYQ3L~N(hw9H)Tzs*VldnfLI}WHc_#-s-b)a61~NotvraS-qlP4rBT+bHJi+S%o+cV zFfFpY+P;miDpUPo)wW3Swc8`Zf)#3cK@P}NE&Q2SXCdJFlcUvZBd<;EKG+u?PFuD6 z6hnMY4o@b$@B0(YDaK`^d8c zjfUKX?GGcq;CmjeW1U8v!et8*W_sm0OkrL$|pUuwf{0R@p-pz?2 zMNu#_dP;jG-{wdwkvnGgeKW1>xS0Qj3Xg?hRph5FV@#^t(g@C#z-2Pr{H=5|C-K0x zR|Yc|)D-vV!^}k7OgD7J^}Oy`E)jko7XNo2%aj{r?$Gm+ez*GR3t>~>kqVI_t>s@3t2*_ylrFn67yUiLQ zsWSF+k&e5c1ZQ0ajS2}o6@b6^$CgGX9{vgt>UA3(|83^Y9&oG-E_sL zRN;W4^6%BbpW}yz{A3knoJjVk+i_J1&tQd=|L(AES&J**q03L^k0Pa!Dlt?bBWOME~gkx zvm<`~3yY_OcUC;cFi5N!hZP0qMCGWn{ek?Jc8An*JSDat&N#7SOxyK=`c;AlwX z((6_04jc1?M0=V-Pp2WL9Z_u;d_D3XgWZxG@f>4RUL4>O5+M70b;)yKZv0tU0a?S|AEKLJ899>FL8kXaC2f>m z&616|lgAuE&sZ5m@69uKS{9uO#x0Qd`|*TN^#!_oV1i6T08u5Up60~YzYS=^TUOgJ zO`nvEX|+JJ)O7eB`CnVX;_2T^XywhMucxAo(K*gLuD2zj)Gap10$MY{6c^6N&f2*X ztJB`#{UWx(7-PAKPEt&`J|8~Cjtfr_A&>OsgJjO#{@8I;&%5zE9~UdHLc(YfHDMeo z&xScJ@MpgS%qTe!#q~LWVWV(vz}(=uR1CgRs(aAX2e2x_YocW2?NVuLUotK6PY#Np z_P2day)Os{U_*GD_g9xzPLd{-Hr&-5DUkbv z@Hwa89zVRXn!Nc17pTTt+jN=Y4rZkgqd8c7*u=IJxc}(aP|z{^AuRY51%!q9HH8NP z;{4hzZ_Kw|xAV328XBDkE6=U0h52UzNY&=j&p0y%KXv)R#~$|`{^_`n>z7a-F2^3q zv7c}&tBX9eh#VFM(7U@JER|-ZY}lt07qg%H30t{dZ-Ipye0DIzeW0{H@}{Fwrmh{) zrR4m~H2&oJ%=Kz#t8beo#BpAbT+)vw2&*<+3Ngpah#qS5;wU{e05}vYYBs5_d!9}R z=nQDYNjarM>`S*fNM`=^Xzf=fVsj09@x1m}rpzJf$Hf)f`=np5zBC~Mq-+n2?{5ih zpm*7aa8aDiq5aV=M0$I9mUYtK@7Swm@=39N&|A&ZSz=9jhlEvg=%!yvUxICW+7^=-7t1Oy@~W zkXRs{3MxOaS8U+HI;|87C!LyUY)Xjd+^t>p9OpBu5 z-$V`5Ni)c@-JnKoGh!(V4Mt7(lw9|||CBlMP|0H}+HBz5WsqN`Vxv!Uvd?-(+n*NZ z8@ckbHt;wJ(K+(G_XUfReAJ3~RAdSec7)_H9&q(ADCijVe;y5+Yb|U-bC?^4<11ND zuoc0zr=-rNNS4l}5@I%%IOXW>wq`>8zb|2DG$%oV{>I9FlV{Uc*g_@r>cXED=w|Nu zKUw;Wbf4btJqPtk%p*<}NrB0H{-G+0{J>f5cR}~+15Zc4`${BJdC%Q3CtJH$ z@Jvg4;RsK%e_tlD`No_zbK9RzOJUQFOVY;z)?dEo76-)ry~j)-{}YDNoyE-fG1HlS z%qIz>`CJo8nw`jI2rzUY!7}U7yo)O&kgQVAjc!TSwvnhG$oZ_U8Ym{hHz}KL9tjut zXAU%Uo$ZYNxTwzb*UyB=xsjQY)HnITRwE71?gfx&?N@tExkRL(s{9z4htG@q0A{Q| z_KsG|R7HG9<~S{3P>y0mE?tSI`ip7`(Hm7?NeiAX^2mS8s2*hBtZCn3Xt35hQbw#2*p#&8_E3a%isL=BxhJ?Q_<{6Mf{^25{4b=PvYQ zfP$Y3-|cTB>+nkO=iMWI%kFgS(9}ee&t)h3@x3`tY$>mCLZxLq6_f*>x#xsnOz|o2 z4{)_QrDV+vCW_~+P6umS-wJdmbuPr%?+Eww9&s1hJE+rL*IvRODrx5+@QZLth;F>yby^7P6o zz9bFyZxv0UrB>QxrW3`OjzQ+wTisAz6OSIX)E}n~o`5Po*Jae{P`gF!xy%e*{C)(6 z?-SN38$RrL^dJ5V2X=kMnp!Xs^EykTn=ITq=E|wq0P2o_O-0?|b~m-n{R7S= zI)e~(-8ZLV^sCwL?PmpE7^oKE>t*Qfm{GhFvVX<Ee{P5=G;fkXQD2LJXcu%kj7XIVP+ z@_D_7mKXZ`hyq-6pxikPI0$z{s z`ePJuv9R*q5?+LLDi} z$V%PlBJa((B&-T0}siJ*X$oooxHKEVf_r%UTvHMX1^3DVn=g3YqTN9XBHDo)=v0PVbdn0OwV2=O$@m<6rOL79H)?3ZJU&!Yn)8Vv~XyqHGIzAX># zxCP0>oD&Z;?$w;)8cW@pa-#e^T@&f{Po!7x@7tT>uE~k`joF1bZS(GGMXyr+hP#+y zlbY6_+;?YLjQeA2P8fQ=_^f_&ot2i636J*wcbgFB8d$PYMR*9az23;tg%MV?l5^Nm z0t-3+*lgA$TAb`gLI1SO@a~&&Di#W}>oeOn{vBDKWS+Y3MesM0`DUT>xuvJOC0Ehm z5rl>XUGq^E;5DUkmo;wekT#kqdQUlh)OylcsT*J>dvuVy(+Qi-X&saSPX03Noe#CM z@3y(A%f+rqpy5Yiet6``8FFDq?KtIha{kr*Q%qF$Vuy^%*ED%8!8)gjaiRcKz{_W9 z?@U^0FF92T`8{=mlLOv11p24p74>V74=gut)&z=Rbkd^vJ*5e+f_m#1?SxT2Y0!)p z$qh1yAYm4{PX3n7`n=pnz!u3+=z-wqH0N8m$@&P0x$U4s8u2~=l0z~W*S~2hL)LOaQA_*~@2Cg)! zU|hqBEcAP9l!U8YgVE+ET(eHIqb+eeeV}51T76nTPb=AzSh?ZUr=_) zks+2TxHWDsjWfs$jr5c|<>n033lzowa)fNwY=SI$@7s3|FesPTJ)1qLy-m-YYVjOk zNEO6r79+KI?{o%Cs!dD%tjOT(Z$ZQ23uC~SF0?gIAg_Y+n)@r7cLvXLE7M%Poavi> zARdnU*XRfYs@g_6=6)F%$zljfsd-|#70nb}YPXsNmm4W;*)$Jj;YsA1)i?avnXNlM zTKTR-I4!vP@nUYv_`p(Lc*$}aStp%QZ=x&N5LbrdT+5~~`0?%*xOPfsH?ll&( z^u$&1R;KG0DI1oy?KCL>GV^kG&V;As1cK&jxf(z+pikF(I%Qf9miBL;GAB`NVR#0_ z(uavk#6e}Au&_%e+6LeRFt0Jc#SAJQAZq93n|!Z|P}LwUegMv=tN@5xGVaHo+sH0-#qD`MYMkBNex&5$*cnZXQWfP?U{*i8h@&Ww23$ zJ!Jg-&fAsv&w16-hOw42?5{`J4r0;gO&t>7boj(AT5B{+OY()EZDtr)-zZv!rfHgUGOjOdN92jE4L z7m7>;zMqsjVModaW;{xPZNCRHqsAk?F zV#|b^a?Xu$yCb`z564f7p})!wC{|B6mru#1P~GnZ4Yty$NFYi$Pi{Zf`uz0Wh38-& z`$XPxN}Iu!9kNZc?!#DO28;pS!?6z!GelVbJOQp&e80)msu4}YVuv<3@6~-GkJL|e zf2!;R?e{lBxPO^(KF@MynKLo?_~x_a2|eaF>&%Wy+RcC2Z6y&|`%zgJa7{tlC|W^HPgC_;8F``H@F=^o1fO{BCs z(pjr>cIK*vniWk7fkWa(k+wgDB&H1SumQ{TozT9Na~~r0bk2>$M6sPGDgYlPbo=@aKq3ut^OT@hsjU=kQghj8X4wD$NW{Z*bnf|xEN}pSo zWX=Y+ke88D?|g-6>3wF+q)?~J0b9NfNOxwP#%w)$iouA`GBdmJZw06tv8`JnB-Y@v7+8wD?a~tn);4Q+2f%0qe zD_>gQACq#dYP~%-sz7x#0$UJ5Rs+eN2;c+G4<#ndwFI0EO?zD_%Sd^X0eRwKM<$S2 z2pQ9vI@ zWy8!;(jYXAyEJ;o6!dC;asSdErV&GkPd2-At4obS7@7T@Xh5PRcydz?!Gsq2$_|i4 z19U11P)Ighp@Y2JO1~rpu2ElrpN*C-$RLW#2Yn57&A+iBHT3aMGQ^K;a$Y9UIQZ2l z_$@*F)YfXsC#UO7dqE4w6gj2bor2bK&3&=ma{5X(q=}}tC;E{~nY)s2{7o3mk zo*ied8EP+lV`nXu?=WSn$js)xzIFKaN?jA7DZH%l>vdxdekm?xJtZ$iLq!J?w^N(g zs4J7|v01yyuN0)Kz?lC!Bi(~g*xC_$m98kUI)9GBGY;y9-sEu zyuZ4WwYkxT>l>PK{>JCqVj0Rvrm#|7iBvBbezZ{;na`k&J3o~z0VXy%?1&*-{nHJ7 zBfM^;D_z!c$;9&{GDO!d4Z(+9pN50EqyJO?k~sO(c;Npy6{ZkYA;zd z{m>UQ+BARaB*SSlFyP@?f3~ar!Bq$-EF&ncoO+;LuMTiOHFzK}g> zX@feHAFqWe#CPXyn~u&J!env5dQB|@aNAXnZuQ2WlHfm|$iD-weE(?M3R!UPxLdIc zjsmEQMF7JgnG~z`JAS#`cW95YxJ86DXGMh76RX=KRFx+x4FABGofIZ0nR$fu!XJ}u zJb3(98WN({Rv}YQF+D=U%2GB|oNwoe_|qPp?d$2f(Mtfze; z$9_z1on1onX0JL-DpA1iv72$UAH%Tqo_H_0yY^P0BVbDbb>~GDo{gNE;i!1i7`Cd< z5|w7^ctkjDTyWiL-fZD{;Bg)+uNGhHe*9}U5yEH=Z9&MLm8=WpqojjMZnxhgc z6{h%Zv}DQU`6_URtIgM^jMN`9xV4|QcR5Oo^*F?8!lOT4u=w|_mVkO~o5z455kAt273p2Ya zxZ`A9_i05aHp4(S`mDFD(rzd$0IqccSaNpVOXxy9MKHFKmif}ACFE16?CJN!`m^`k z$Ycy;E|N}3vCqA4=Fv3(!J1^_CndWkn#)xjFK*k6fV~ENoA4_Zqrt2jHpO+STQ4>K zn&N25wHvbkiPvPihGV~0_wv(4oD z<07J+f{y(1YUQLXRY4{2xH98rE0{HFXi6b^8qJh`{+^r=31TeUYN&4f@_y=eLjo)Y z1bICygBh;NZ|O)rV^+iV3?miK=Ny(PCHh z&f6aO&L}c9?1VY{A$r-o58zZyzkRh`|F7OI-h3x;v^yJ|wSV!3pdR(yJg`h#Q1FPP zVSavISUEg3LkLq}=+*Y)Dd2s)A@9}!Ctu67ry2fB#V}*l_w;$6v>$&Xh0<^93S^KV7_J3Wb4_EiPzB-!tW^ zaD1arKSUUoUCFC%#8*f9e=F@SKt)n$0Bn_4=>7cbqNO(8uCr`zMSOfhO)yFyE*(F6 z(OnYlSmN3I)c0hae<=Mn?>T+YmJWBipqUUu#!4}VT1i+K;!8xa+!6LvDJMAYkQuwB zW%L_Ot{6zwHwtnMf_m#E{4y-CBT;@_znO7LxIDMHZ6>&X*nhYM4!Ub$20;XN{Ru98 zv+uLre~=r;(l*?);q?(oX>W555WH^r$iv~doXTusAx#>NAT%VSZ7+}N$B;;^#ze;!2Ac0Y1x5rksOTR*(@TgUwJ0);MF~Q7o1|W`S+MMM8{+z zMa1Ul+|9=O?3-r7Mz8OL=B&TpYwY|lpRM9^{;ICyRecqj9#{Fws60A9lMLc~1^*CG z`N7}vFx2yr&JzdWAxSJXgPg75#m|M|T)OMi^|@Q6O*e+LbP}^#E^M~mx8!M3Wkolw zKN=`=;dCub-269*ERL-l!umZ@BD&LH+q!*3)7s;pQT+uE2Z--R%3hrpBL6i3h=uz_ zUG_^Irp4BCx+d&kY4=WHK^x0j#N<8`$Mc=@T;09SB%YTkDDy*?SGsbSe~WowM>ry2 zv4d4(h$(LI8k7KHvVsWRP5YxvW;ocJE~o<5>zJ7s7r>SzBpAIf0aScCHWnuB_bop) zXwSd-1o|wD@REt>2hbiGa@&Yijv{*JAc0;#q{cgu!CmjUE(S2{Dh)rtN9kfh$PHr^ z@#IqMtfeV;Jtz7&%chAQvo$$Gj0l{Zk^Z3o-NKIQ^ysXoIO`~S>dySVjjl4Egvnm| zERB_>%t;yZe}?(Yt znEtUdfhgpg9bYGI8vofBGJ@!Ar3U{WY{74b#pS_~|6&Vv{);W}zUpax&t%v)$|Li& zy2Uipl6(2|%$J#C0gBNP9LwZ3FjqbjqWcI4_N(gdiu~Z}QA(@#V;y%dOO>WXgSMz3 zWqA0T#Em;my-y9)ymZ9d*+{GD*%sM?ZQ_T#t(K1JR!JX{F81ic=|=wzbdz$C<=`wo ze?Ub-04k&qT51L`4__+j-(-$mva*}h&04UqIR}b&A&MBdmcYx@F!?HqJIwG~jz*c> zB4rk`?Tal5l?`D^h`jTdJ+^VIoQ28M-k z)x0;W2FUCuN`FVoC8Sp%KD*@I{E5}n#&I>T`?)(Bc2K#W z^x!uZc(HE}*kES4TsP+B{RMd?&8CDVW;9(3CU?_g-hmCT1$DYZ&Z3I2s`iCmbclQ# zZ8m0%cxJmF>W>tvspmvGjEQHSqvfiaDJ;76Y-GRMmFP{n&OQm-yWBbflvq|XK@O)5 zxe_LaB~}i;N}ViHFLFSJ+*(MdYoD9u2oOKQ8uU!tP{vFVoDzL0>^gXmy=*57*;w~xBQ6T6;j zwJZNoB&Tm4GWR6c(-S=2(w8c_VHVgK6|x{zG7;tW!)XSp)wm?So1s3g)0>=laT+Ux zI`PQ19_y&bk>I4Sf5yI@>KjSBA@Y8x2*rByNE?{RZ+Rm2aTwdASJ~9IKu&geOrpz8 zdOvN2jK}m@GcWKhzoZp?3}N8y!bc9w6k~jEIPfg4YN_t`Y{L}bGCtnZ!P9%&5|jOu??88y z3B3X1wcn*20n@y=Jtank#I zIrg&EFhQc+fGXyUqHRTDi-p{*fn>@*H2v`Qx6_uNQ1bvAEQoO3*qXZYO z;~i0#AgjOAdRO8!ti@T>qjx>&1s5c3rt(j_n8j=|TcntFfm}sLxJ{75Q+9G&Hs5rQ z-5XD|il^|)cX2a$64(c>XMype<= zLLKQYtZ!SC!k4>9%l(o`_4<;Rw47`;GO#SgD%qCkm1VC;0O=Tw@hY?Dix;1XxXbA&>a8Rn-mXz{f#x$r9r z>Va^#)Wkr))z6hnigeki6{W;MF-_@-W@j(No17MUHIqpI89I0$p7=byOoxQr8bLiZ zNm}Izq2V5M9)FFl2z7|OOUdEG!w@iDIiLk-d3{oi47Qr`Cn?xpV}wY9MJS2mwm*YyRt z?Ok=3g_-+!-^t%Md#Z90vq>FO1Ki!orW1BnsC4QRu(D5TL4l6NSDu`sDXlD>2dZ(@ z*twxC8xEV*)xJI%pR$WVtvH0H0z6m7_g-frTNP<@ziD!QS~>>Y64+&Q%o(5@h}#K< zN^YSeH)ez2X@?7C2+K2LXOaqmdQN z6vUJo!u56)q8Lv85=;{6&aSvNnf3-cAwQvHDYUu?a1G#l{WFP_9~wW!uALKjsdO6>@$s;#1})|O~hQF}`W zp+j3WT1w4OtF`xzS$mI)8CwuLk`U|X`#kr#=l;&U|9;NNU&%S|S6=gML^{cDWiHEc zlUI{=&0rtNPjw-dAJp{S*)s1muDcT@LAjnEj{EMcOet_NTizx4H&+>y0@3vSH0*BEr1}!Qm;;-K8X`vTDz@U*bJydTlYV=86TY(^bw;uRZto z#;v9`ZJx?+nk4G{uhB*~?axJ6{`c9ha?;(*EW;n-Gfu5GaNcT4ckft!fqC_IM)>fL zjbD;SgR~H&n#)0VRRTraA*?#qc%46rqTrAZ_1yVKap&hKSjd1KCFJ+7wrQRx^N>iN zj(nkP7|J@mD#c_b1r2%Gp;6s4TCi6j)1Dmncqi|s<8c;VXzwb7&@u8jjF`|UO- zzBZR%HR6_WZN*=aqA;q<9DlW202aos6Ydu0=5LYTw@H4yIgisn*o_V}KRyKr<#+ZM zw~(i;yaCF2KmV!xzw7({!$@p}rU!L6HN5=!AN|2O>A&=c-V-{)Es9&$7ZAol-Dgze zuqOfoliBu|Qm(>V6AFo4AcM;@cN;cADIX01mk5uSc;p(+0qexQ2-WVdF>p#dmrC0ST`&ztM|OmH6y*l{M0*_nHr2TF#N!Rv34*x{?a-EK z-!sLrxH5}GV1eobkFL;*2p};YGrdY~t8i;c4RYk&u75FZ|TEiM-5Qh_7ai=g};;?7v`K8?0K8s*0FoU6A-^4h~V(=2Dv-(XVx z^!c~!OsWH~8J>qtzy13c+a6eE)e|SdZJcoRQys5I#O=(Sy4o4@hm@!bgJ6Ek%)oE` zdyQXhbRiX1gYbJ#%#Oq8X5gp+jx4NBlR2yG)s;5CrFYjeX(?ZM@VET@?EdBWuKFg+ zQq3$^YD8JLJ~PIFYy6(MMu^mJ|Ye_+M3&@eW8atKJ~Ck zKNpX^RYln44OpeB)ov{1)k_nmVSDAgqqmJ?Uc(em(m%qMV9K~U{pch@e$#ia!vJPI z^-Fk+!(wyEbaJWiXTc5Ig87S5`^8IEsiz3s5r|1X@+$1pf_4fu&=y0bBny(yLkjQj zaY^)>F`}6YsmdD5%927g(g#;RW2y|75>Px(_=U<%t#T%AdP!P@vwTMoAMNKkIx*&N zFD4emS?A*7-U=1id$GpUx<)_DJv_tFoLk8IdI%&=LuDI18$S>*(Pv($Z3DU2oKkP`jy5A0CXg**9sOd0Jo-8#HuuGzB>j*P^ zc^}|x>wD4(prZe}>iX^dm^#vqwAjFK~WzyAE918dq zK6;?{NA40iLR8ZQ29T}motcCWUY2d}LFD((6(cU2{N}BmVHD23$yrG8J>JP(vQVgd z5YS;E+bD2qR&t5wI8oCU1gXFX^ET&lgHgihuiPcskt$uGqNPgds!T^`f)r_f z^@*vaZbdla>Bc$Tg~wbx{D@^G8>sY^ck|Cly*1qt%DFeYGH^0KLTF#528od*b_ieP zhLd&b<-8Zl_*Qi5=YwFtN9Kj4#k;K?QSBNVJF&Qd=U{f&4BcGIa1N~ds zq)ku=b3{QIftS4;xVFjA8nCqm#JB?m*>bskJ{rJ|-t$_I3ie0k{4%O#^9+YCt<*Cu zo#r@J6HNShpRDW)$nO+4TQ-nNUG&(#)oK*g1+#m9REFpOB)2f+S_%(rSW+1@2Tom+ z%6`LW*Wr-n;zD&PAL@xBSLg?r6jpON)(E27p*q_+1)@RJr zMY7m5@Cz=50K7#OqtQRJuJKiip|d6XX13H#HK~u)nbmcVghPA6g)}|;MiWX81!qbc zY`QKrgv(dMvr`iRt6n3_$o8&7lWW`>QULlunobL%iYYB_xCDPiL6QbD zzdR0jTYJqX?4&~l>%Sr;kYef??eFyyB?-y9Q!eHt+f&>As?I+uX6IXv``};Gkl1x< zaboO-sJhL3R-Kz==h6@FkFbE%FD?S-A|~RftGqJYGM*aQ_7Pso&umwh(cZo)e=^<& z#21{i9#58bl9h_J&>F%kOR0HoBXr23@QzL74X3pTdoJOFdH2t{#`t>?pA*!VZimyL zTmhC<{k|itqiSfeO)Jox6I$*!s+kmlK3#oq3gEU2z4$p# zTY}FA)p@XypqQyFs15ugHzR`fxA3CI*fEdf1FC(@`aI(qs+>rah-_i#h0Z3{h8XXm+IHQIhs#Yhxdp>7 zR^|ojc>kthFt7hEJj*FfV(|_`kitYszx%I0iYlmLeh;=WY2+qq@k_`*HS>ar8zxx_ zO&0?^;0uf$X<`r9LUee!C#Cnoh(fDBhB$6WTcX2q%$y(WrR2P8Mn8D6+burKVQZKv5UJvgnd!bg86EM_&J?~4uQPGXp z(~>TYR8z71!gyBMhjQNebMvonpNUn!qA2-(+evwUiYdL4)%OKw=_#*F~-n8z4i{N_1_E`a(4`(%ovEoo7v-UH4PQ*rbK;5Wh_ z%i}3rPirhJLfMW^jk6s3J)Z76k3C)M~Qe$q&$K8u=pnfsg}vzkHXmDl=L zRP0$+TwUEA=-;`u@y`2U{F*<^TA_23u1&rYuF`;qK|8QzZfF&t!SmGMdGooQe$j*D zXlM{kqFMN8z*b(r%)2&19wEgdXTdBp(_fQQcGPlv{untX$LI!{65=%l3)z+f<=MN| zR=N_oW46$mRzkYv5+?7Hc^$h<;HHgpqDgQFr#ZwG8l^e5LeX zckPQm@=F^>@r!$i$hyhSI7nT=Ns6#JW;hG4l9rg}^jlME8KJCD!oVXjq9RNB;slbF zzRw+gz4vMF-FBa|qa#(Tp=?IDy8#{dl<_WU6dfX%!T0@|2N4Bi~qs?QCXE z?{{q`KYPQ4u$u`yHaM|avShf+0+qxlVY0?Kswo7oNeN6gJ%J1GD)-%+hz@1L@xw5u zjQk={GLBJ0wGB6}%U1il%RlBmEST5w9g~rtX_kLpPKAh6l7=0L>+6(xu)eA!?~`vY zhj1Xy5*UQ+xqT8yB`g}3h<5dj69c*q)@uS^{Igtlmp3wBR~T&q-`-|@&&j|iVqnMo z-~sE)uQvqbFlWB*@&0UnA0#EI%li2?E5EK2e>I6}Nk;8V7C`&H(0ue0lQuiLS39!} z#&Fj>>My9iYWcz~Ve~h=gyvGpV)pN(3%|aZr2`CgdCiR*nSzv@ZQ^B zPlsb(VJJp5t2(k*_NvZu&juN45U3|`_aIZLv{fx)YqRU17B*e_(t_YlBqDSYR6c9P zjvkT*|3oQywhq{5*v_LeY6VCO^-V!-XD=_BFkVlP*Cp7iEAWDGlS`Ch+R8|>Q(ZNT zx1g6@%Q}E=op`vVCpebAskI!X2*bu=k9EWb-v@d+Nq7*xyJs;}tU|*Ur7tmkMSM_eorf1{wD8PwRyeSD@T9{vQ%7IZ9|{oV zu@D0+0x)ALGx8k5G6kOx#5cPG>fjja+7$_m2nrPF-l;XGg5H@uqgb+^I8tHav)^t+?0x38)2?)|P?d%_Tlc#e~PdYCWq7?$?yWv%v% z+ry{g8Ni``hw<${3bI)7ph1&a}-EFo>8IqBeZcM5u3Ff0B%jT{u` zfFq4=4~!M!aORlBg6+}$a}oUzfd6WdX=E9xl(Ys3*uLT93`(B(g$Bkr2@RF3DT`DZ zYQ&475;OWx)>8pRs{WLJ)_{Sw=2(RP(_}`Dy}5=fm>w;7<=6y~yqfDlnPYjIb8KiV z@B6!2&~yKh68V*^*f8BrjaaE^^RG`}bSSxSI-3avTmh_N})KgQG$&grcwneJGx%hh`xD! z^Qr|P^)`cE+v(NUL8-uJ$McQt8hh(33ePrJKSf7wGS7&X*LG684_3%8IZ|>omXpQ; znpkF58w>7Qj9Qc}bL3?E2|ROB<9pie_^<}wdzvZ*d*@hd<}R&JOaYr$=N$rYh1zS$ zT`XIaXWXR}5ewL1iC$L>K$XmMZ~eT#{p=-h>#H1N|Jz+ML!S>=G9)AVx74*$QCx^W zAse$K`7Vg%@_BfpxjD)Aw|c8wm2&4S>@_#~R)K#sQ5mCx3ly%Kyn*190R%W*o`Oi` z$}OR;CgbjW2qQflt&8KW{W?otxH-yYgpi}RTtogMwwb_L)t z;a;m>xQ@E=UcP;|s$uyu8>R&l4uPYr)t8hUL6;|O&vW0Cyon4uN`-u8HBoAWqvH%@ zP$We^1s)UJ=5&2vMC`Ku*4w&}sX?dKW;K#5{hizpJKt^xEQtZo#dck{d*1szOC*qW zzlBYsr8L9Vj@AT9RX^HIo84B72+1q!nPn8pn^l{-jd(eY3o)jsQL#C`wp8tpX19Nq z)HN*YhJXgwn^j8TI_$_ItIxcz`z?Y}i~%}ql0M0)A7*>Q5-|B=u?5aEv&fQ_51Os7 zXCf}74kaim0N}89C$Qp!A6#uiXbBZ{sBJQKPWwOs(y#^q>AcCmm^FN`({^&ff>6Je zFKk6LGbAxqV^2HjuzI^(CyF7EPMfYka!k>Au#}f2f{Bt~*j&O5QIm$?4|- z1M+&{n1?yMrwYmOlx@v~Zy+!0I%@eTo?ANq7`@)5tLQwVmwe5s3xVPwp`2pIZ5*JMXUyyZJ?M&uZ-fT@(uGsyq|HNggtKb#dJS&|^g2ObLZLA%DLfj5 zUjHIA-kiXV;3V@l54`g}U-xEX^UfE?)qCI(UHDx4TGbV|okfR2=V0W3<)FAOdLFs{ z0Y;BBnD$w}8gfK?ko4ESYqZwQkx=WuauxAnPOOyMuZVV%d#t3Nge)rk_&1dw+m}`q zUS2Sfm9cp+5PKtO&&gN!8t&vU&qqkZFfMce9Gpc4a?R z5gg)1*n{qtM_ogb=XS;145Id96n^RUwdo)rwdqCS!~w*}&tV_SrxC5-j*4)d5$U1T zVJ$E?-{z>=##BAC^LqUo4yQb}6Sv&N4qdgrsPd!Z+Ou!eV<=brzn)%(p&{Bz=>Rc~ z-C#fcWI)Gvf+iS~ag-bK%?2(od;8$x(l0d<{Z~58KX1CVLwN*SaobZ+E@mXOyHoi1 zbB@6j-KvJ5YILlSS$A)^b<87TS87MX;3#ilI(TYttaa}<_07Efcz@TRdwg<~g1$K# zjy=iT8BWl#O?DT1|K@c5ltz!Y`A7}UEE!wi50SpDydeK&Ie)oY;ci0ZQ^d|{Uj|a3 zdU)UK??p~JKK0+UV4u&a`NBni=TFA}g%$qiVXq`RC{(rN^b<$mxihRst9xokVu8Xk z@2oOjxbk71=UGRbm*=b6@okEehcLd8nH8~$AE`kpN8QTq z&uCj3Rg5buXWpwAE!9^nyFoh`7&SUD2p;?CgaugozlmfGmSm zpvz89{cjEy4m(!d)KYE&UaIw_t2f*m4poc|V&mp}s8O1n&h$f)L3VqoN^x5eSjQ^D zyLBe>V}qDX)tNfL-JBqw6*lyxbHlaw%0sMz(QD>4LF+xvq(Q|W##2s;F}Mmzb;?@S zd@5t~uine(09~V19;?o}>~rs`1wKsPspu(Ht=m@3c6XzfYbI)r`KM>y)M?g z{oHxQX;L_mD?d271M`%@bu9iR&pgvGJ^ar}tLAAbRS(Wio=rpH)f@xf&8}Rn7fm@t zGv1vD?fwQec^IhMCwJiQ)yv4LHlo$KCX3*ampv?%&r!SSg|?(<-f~EQBu}2q%od(e z+Kl4ZJRdk;a01&-nkDxMpXb=(M3bab3^hDiLJk1WOy8LZqCYPV$38R>-rYUi+m>sP z3uzWU*~V@aQeN*-SLEibM>bxJK)}Oi9@``h3+&1w%TQMny8e*Lz|Sdjx1Jb~%>d62 zc01T=b=5OA#yEP7@y*B*oorNnp!KU9nIHWklS zsxH`J`ysoTkG>uJ>sO74^WmF$pAX1-{Xvbl&!HFFcWapMl54#x8!7F&^A`wSOqt|K zZk!vAnGyYHn$bAf(3LbYxHYTe%gn-h)OZc%#DQ^RXh`Rs)E=pigJIeK z%3*J-Spbm2bJ{yuRFkL5^qz`Z{ke+fNxxAJ6uFpib8|+u29xIu+_?m}wf9V8SLSdn z3jrt{Z3@`Ehg3OSvz-R?j|Lwi+qW0wgS^9wt7#Lp(o4k$+LbKdbg8%3;@5&7L+7#iYH zU+OAb;Et8L_qQoqSN2+((Za>n5o?!klH;!!&@~YjY`b?QNB1}< zl$MxouV-{_U#e|S#8ZE0_Pg~MQjOweIr$dILDJtxz&-Bct{j@lkidNnxXYNH^rF-5 zhSQ{B6|vutcDdT@AK8~;suCsp1{ahCPCpg?Z$lfpmU|5~Y>2)paE8A%nc;gOiYrlC zw6~sT0eOdGN5k&|Clr>YXssh}fL@m)kqRuOP8#*p?Q_juXWWD{xh4(dtr(K^fL1l( zXE%8Mn$Nh~G2T~I-)#`JLVb>9UmgF#)qX3X+T#Gef_E#g^V6+QxvFj=Qjy|jTW6h~ z4-6*#h>JDg=>uGT31+E%UD*&|?lO3Jx{8^JlODOPkvLu>#f_=_n<~5kp%5M;X2z&< zVzqXkq>%#)$Lp$0AK@<(X*7OAy8mDJzh=ny%Ayv@$Z54|4~vE&<@Na$EJ??&gZ)@c zwZB+6J;{b%*Uje7)MRzIIazCo5ZPwx`0!$o+a%oPCLpD0jx9C+F@n!v6XN%`CYx`JiYFymc%kTo|igu#?c>i zx88;4)RlR%&2e(SNBD&5Ad<#(0`>Nhz8Q?!+Qw`B(PRaQQk>@?!NgY)xb#Q(;KF#o<8C&DSL)i%)`KSz z)M*rWXZL~n)d`yuGrgAZHET0+o6fjgxPH@6Z8EI-b8hEGCG$-e_3jcV1;yXwA{gSG zc#`Qs`XCCW*G5y^Ui>_I?+r&H6bcUY{97p*_4>SOCv|XavW_*(o$kH&6-E1JW|Nd;DV_rcc3dHC zO8Q7)F}2L~zUg~uf&(`6Y}l{ZWxNM61G0)IZy5xBjWP;%OB!`<)tR6~76j^4ZdN=N zN)V=(PSAQhr;Wyq-W&`f3|jHr_H_C#<4Xws>#oGMw(4UBl!@2TLu4Q6m+N!q00Z^R zk~ObIYx*&CrP^ooaZPa(#BG^Qh9&L5%At2$F4A^q$)`u0 z)W7NyPOLdr-BA?VA0GUFPzC>e{tr$6HMB@2oPHvJW1I1PfY)L2QB*zKD9B0xi&a+z zzIQ+O0En4^dOX6=IVm5DKBM?j?w7u;Lz$=ua;2XMfHP|2i1R z^O;4X{~Dl)k)18^!rGkPCUZDhv`{0}T0`8cIi7`$paJ741#z-Ao*jL5FCAx_`x^9{ z@oqw38q~~brm?s06Wi8&5Q8>V2T*Bu>){7cB-s!x$iO(97BX{D?aIzxS}!gL-7G)^ z^z`a8jrca#p>O$TIAI(5O;mS&>3%bEB{Cm5Bq>vRuHZ~n5&TyCH{5y{AxFawyfEZFFLv#cvChjNxcwBh z^(B~7WrtFF1IwC!`KeA>wB}@)L}is7JszK)fws1KeP>mX@dl9D11 z;}w=>#6GTGX_AT2kKB3-j1n#iDBb|LUxXUMPc$P|^$;%G!J?G$!=8DucZ3vSbz~Dt zY|GT(IJXEOsOHn-f%8c6D*98FPvApEr`sXKmjDw+1*fS%bnk5DJf zTJ-sYQjhM{I?U%5?CR?IVuW5N-HVOqMf>baBuHi`pbGfPCv9E?k=8P3CE0|ZW+-5A zIrqCVWyY&qms85W$EwdWOWI$|7%)NKx7_|p_zwmsaLEJQzx4RC&TFVWTlVuy6zR-C zh)CkV8N}-BP7v*d8h-&hHjw%d8H)Bjx#D$LD@&hlPTL;h9iERD#YD4IJNS|<+q!5= z^qyH?Y^=MWKtq)38k6_-<)icEv!U{k?MwO>mqU%S0Q^&2pODt46GmxyvxFlG$V%Pc zm7%XQr+Lbpwk?CMS;O;wiRQIab7$UNNNns9Bv?~K13nsWPgI;PG$Jp!%pHtQUvBt{ zn~gYLHYohFIGd$@;J(MDab!I0Zz%FMhz_!`B(K_hpX;)>)DZm8CGx2fI(^u~znM7Fu(>9y0u>;JzYiwg4XLp`sKy*I4A=E{1b5PNRXi4F^rXwGbg6T(+)9I2doVb$F%{ zsa>$;huZh99VLV6;2(Q&Dq$l^Z0|=@ORVe=cei!LGYoI#&G4fgijby0fwdj}@c9h3 z#w~O6+R?%yWk)SD2B-h&0&pTUTvYMf`RA9r?MrTxpxh#R3q{g8LDkx#gyi3`^0n;# zNA3wQnX1ZG$s~qHj3R-519mwh=@%e9YssL}UmM2}$4`ckn@u$Vn5mK6F_qh=Os=XQ zAKRh&VNJccY1xMDk$W)LIJ^irBaPo@j$z~Lq-byDIebZ`S(-Do^Dl@eSt+g5vLjio zc>da%iKJ07hDc-{!Wx4={9~5i{e2{3|Bc_hDkyb!zVT8dFlDT6r$+I)_q!dFjh7FQ zfLE>JoBQ_^TTMevR^Lt)g}aa4U%s2xy_!Z-af)+Cjn;WdRctbo1$I2qupvtC5Xz{soV-!#` zp?7q=qO>3x>JEb_Z2s_vP>-=4GO-_JwK`j&*{((eT3Vlhikt5O)NOprKi81_%ter9 zQ+x|Eav)NA5)>Vr zLt+mXvwBePvEEz>`U&=U6$316u|*56kp#(iDE8rNlUwnA=1S8(Vg}o&vh6s zY{-O0ZKls(b9!$)w9tNfhSOtjdmTM382_MCU@&3GLs=al%d4Y{Er({;mCTZr z7S;6ZF6w$%7Q*{TD%FaMU0Ldr&26FXC0Dv2UQWW$=z&pAq?{-&%rrTGSp5^pHDMId zTd}1VAe<%X)ae5+bmD01cI)=KVVzKS|IK{5lt4%{WuLr5-*H1dR)=xm_LaZK`dZlf zAB(Ce$vsJZ>*jlXL)XvJBv~sy-OvS|Si9AYoKsv>?RB|K+S>DK{SR&MX9}Ud`5)S# z05SLH!~d`Z|65}CpNGAY{GiYYx&NXKR{s}m&=$x7Wd=`#^M1s|VxEs|v#yk|0@%8` z2sep95v#D4p|I*860w2uh}dHn)DN29Rr;OP&oqa|JX=PyFS%ZSbdTDl-Ta5c^V{|koyRGX`SGhj zWH*DAHbxHX5<)8?Yye6U0Zr1JF^cp1#xxJz8E@yf!vXgCNzVfBXdRKWLcbIC@*)WD z)mTLGiR(PWfqr~TRf|1repDfQC25Hpzj+XXtU-TQ4fMOaCb{nHTo8y8-W(hN~3+qxPRlzmKb+bd3`EE7}bd?{{cie{DqEg+gJRgo;;72S{&PKd`aM0TCNLDFc{@y0nZ06N@{QDp?Q2wRF zmrF%FTOwnx4Gy#i;wvLNyv;`z3nDJPQjbM1Y|r25P<k+Bc6Lz{szhs!Ya&wSG? z^3U#gEq&pF%FG+#XZaiu_}ccCpMWbt8t#JSP~Yz`*cz1V|A%Mywd;It?;sxYr857I z1cs9X*i^-wGoQf}B-V3m8RCCoVP>Wf`gn6)q2V+_i7TjIj3QxDXjI>y5f2O3@G9BN ztJ>@;!}Qg60c6f99!52;Rpe$iymsU_EDyKach24E1=Xy?q)oSZxwV?wQou2M*@WA} zG8Hp}GUI*_%Q6N!s{p6`0FZ6p-GY2}GLIvvSo1U<^Y!X_&lSx?cZez6?$alZm1r!Z zwz|sxK*87E=_!fkv9$a&Ep7Db*;Z~;B`3{ZQP^3Y)nST<&T9Yi$PWw&QEjG@UA9dm z?1tQw7#_Q^rO0~$U!1j?w5YkQ6i_qz2Or%w4P(ZjKk2yC>VW~Qzvj*+M^)^y9?f0@ z>{V2O!ROTv*CVz$&+qZi!hE;f)}>;Eo=`7Z{Mc5if#c!AfK9SYJ^J?D{);o~2?ERK z&9#!}kC@i90V8u;3oE)B{fP4j^wH}*-jkh(5MF>R2NMGTq@)o;z59bQtSFQn`OVH& zBZ$vnDPHx=TZB=QadWMv(3p1inB*}EqqS?Em+`I+G9A)buufUl9)_nBl@foY1u}^pt?PqgF z1d3>J4YN}K&HO|gA%B0w-W?OrWX)qo%%x0uX!NzM2`~*o(|hFNC*1 zLV#9O2Vqb&+D&WAgZe5zYP=0(wTzk#qf$*OoXK1%glz{He!KhCn+L@hL4>xktr+7@*-5Al6S&0qwMhWrf6oAXiwUL@o7?q60$E5sX8QG1YiQIAalW1OD0(Q=?d? zBo(n)+((w>^L2b~B%YLPRYiU+;BdE*=kzKXB%Zu7z01j+^-lR$s zl?CP^I6Zrc7LSFJRhP%>nPT>eTW&$_tZi;_0ny5t^;uv0hSV^FwOfTJX(vw%{r(Gs zB$4j*ctdVx79Ar^ zF+(z_n2GKG*b1S@L5eaY*ZB_$j-%LT6dRoP#jQ1BM~qMJntP=+HoBAP#optRBTYZ}&f z>STZr^Gbgt;3rP=p~sKwQx(f`Fa;q?6;be+Z&Ku^HF8ooYr)8R4ZET7w`(;OvF)#* z&ePC$r2A0Kn(+3vnZqjdfj2PEsoDD=MRGh&VQG@QSvSri3wh-eCjoTSby0h91tU+L z*ontwg|)}Rt_KQcO&(KJ1cxX@Ys=boWZB~Hk`wv7NpzyZ0-l^0%brKM__zk)6(J}z z{xPKS*yd;xe|;$2ycOo>?ezuj2IBKqEEk^JnjYu|t|d(AIM8}OB#)?&Jrli&UblBt z1LAmF!xNBIJUt{G`ZT#L4>?iBQ;psA5WDY{s(6K z2Y1Z$m7MN6aqDR;(C5JsGgj zDiiq#AjbB$3!ug5mAF6VrFPAbc21)V3(EQ=&;nftNEQLI)0|~MqnyK{H$P0Ydkw|; z;TLWC1onfU?3z@5YEx>wjtYV!yy*LYKWgpYlFjka`!gd6ZJlBo1%V9?LbGDQ8RnKi zO+qcBigq$qAFK9vX2}=55rlSvoHe3#b{^-{0I+*at+L|@k`&rG}K{EE%28uXxe zF?$sJe&M6)lsJIn-{O;#=-l@Zdvi6M__z)UnT8HynF(l}G%Gpb;xXy)cAqyYELS|F z0kV~yQD4iN#KFIrVz^CmhVOzG%csIe2)P4q75&5h=>+BXyLsteA>3-WGy~6cGu=Jt zkGSyttIWl`r0xJ+j)#h0Bo^OpzfFPsXfY@|ZI$jHjZCszFW<>2BPMG%RDFnzbIP|! zru|_?qjOsafR&ZP!@%Py+Q#6kq;zhnV-Fb@q|Na~Ht-uDXf)ewAZ} zy#|Oyb?nEdNtk|lnr!_)L#%gx>HaH0fv*Zlv8%{L?9Si(Y-!bA4_9l@p|8d*U(fRz zyHd48LN(I5(r2@G%dh@qezv3!b{TfOe1(7%mN{X;*P$*~vA zCs6n=WEQ1|-afpM+`!&-KrSIdwpelIkj7y=vsK39eBIuclxvWE)}jp)rGZ;gX7eeW5^Xx{Ao)R|~CMB3)PU zE81}QWuEZPYr8HdBOD(?Xu>Z!K#6GnInF12>{fGa7NH!-_Rv`K){RCS%P5b?Q{WOH z)i?&v#){)ucDEHMh_oo-V0(;WwtFSOQClm*RAB@EirU(0+ieHK48#CAHLROBW7s$vd_bdau|Hl5HA0Q65fFmOFeJN1pnwcf zzKbSVj(V1OygDfoQ}Nk4KYsPwIyW|Mn_CU?{Hf&A1DC%*-CzX+g#DJU zFsH;R_`Acnpd4{7k9&vpQ(OE8pQq6NiEMB=lUB}}yhd66!{Bq_{R!2kH$`?qUzL|XMivjHS~##u z3MOzb3=UEFG4Kh~*UgIo?bRqP0yDHghvHo@Hxejg_!`F*#@0Z3CWrV_AQ5UbplH zpPx@3<$|B}^ir&G?^b3YsQn}@MEIP6uzKd<4T#XpKMFIzxq$%6?P@MdE;;ICwORxf z{eCv?!a}`!!h~>{s%)Vjb7R88UWPifUT_iupV5c&gD2}16N_9tkMrDntS&Sf(%gXs zbqhhzFm$A=0V#p@=lO+I_85L~132LKn9yqD`(H{4(K9M`!ao$z4^_($zcyotpTLs3Nw*>PKN?|Yx*wm6 zqcNEmgC<54|2pJ*MH>^)!g^V__5|4d{PuoKa!-zDgG1|?fe@nowCB!HolWKtYqV+OEGO#gJhh|;X+L@8P!_3Fw5NV?!FMRWG?|5nJvfjC=MOVt{> zpJm)W{s#rB<#C~psx|o4>st)O&b~R4j9iS#fUYElz>3!Sxe~&s;)qHDk8R;hlfo%E z^Af-JcpxH#B?n1G-wQ?|pbgcsBdz1(9qsE#rRj_a+-v=;yiqzH5vX=}NK`MNXpAu& zmI~q7iE*WNpep~BuKKdeoX^dMCMG7lD&fBEZHJ@z@EoQWU4{Wvb69E=RRxC=pLUNZ zy)j*JCY5A8bX4U}C%1oB2)pLD;||MDAS0bj-V{nw{(aMF?eOO~Sed0?L<^|aE!nHy zFh0T&Jfo_MDoVeZ&|&G2Vee6iQ==uXRdEmRhYl zwI!>s{zIOwFSt)`(lbbqonN52O@CY|O+ro~wA?LAB};c?-`nm;c*J0LmGr0Fj`t2# zs_~1oo%T(y(s}CAK-Mu-RrjcWVX{(qKAKjvvW;A&*`SkG>hwG5hYL1`9>-|d0&C~H4UqE#rV-5mVMa|B*7Hrkh7co4(q3gIIBl)n>cX)b$fb8g9hYE|ko#o`3L_2KYEff-TrqR0&-qe+er zU(g-iP|m+2zXev?=gym|shwRDet>s^59Xa<0Mn~+}<%+3^+&tNg}myO5+fZ^f^06tnHOT@?N z{Q+8t0U!%aUkL$BILjd-ws=;xp5q8j0Bg@YNysr~H1L?*hIt6o+!Q*G@ZXnesEm5) zXDbkw0c>dVjsCYi^yZdaWXLRtjb;krHT75{Ws|O+Foo6mf402~4IJ;qBhX!1rT|4~ z`XM#JCBzm2yji?g3a&H}2OlPb-!#Wohqxozxv` zoqwg%Si_E2J^Yknlt1X)F)anv3M5f1`v$5YQIU2WmOc1_YH|giS|<9x&xE1E_xr`*DqUjvKjoz@I1emGMNxYQ_uhzMJOwb^0x4Jau~!q^ z99v4uhikvHJ+~vKsLAK>+^IJ$p5r@@43!lbmg&q|JK(x$!~wrR|5TMFqzxv%$&-67 zX|Tk4#m>ZFd&M(2Aq}k*sILc-^T5rMWTw{PVpb4x|-!jcEjGpUeVGzSRcCpx4iFd6BO#ZrK zQ}-m8(`)&Mc_E7`c!A}oF+@w`nwqNZw`f{}E`T_i>+N?A;L8-z0Ydteb41RIu3JsZ z$wW}gK~LJtUZ`Gt0zZ(ZyM7Fq3|(E^OMzW1u(j6kT}+KjF8b(PLRh~xzcdntnoY}- z%1<~y9MIck-||lF^RscbcYccaOEd?nR>Ca+TQ$_majJP^J};18?RYOl{qpf1;#hYf z{YVOkB4$ey*EA_8v(dDgv&Mgis8CRPYHk0-%>9 zINWsyD?{Tb9~+YU2$r@ED=4}!cuy}deTwxuKR#~8l8gJ?OARTgKUB7E z4FDfQ;84hu7_!@Wm$6;}uj?kOpDOqhOY(&rmY)bvx$fH!`0pDZ1Ej;CVSuQJ!~~?bfuf=!r6L`Ql(f_a3?`_kl!%0MhjiCA zKw?OZ9^E~1qx0VTa~-42uYpp2fn9oyQ-eH}9A-x4=t~tu6KaRvIw2dHIMp3t1ezm{B~4&bD+WTiGWqa?upaUJLW46kH=o@UQcnW zTZTGMyPsq@hvH__lXxsTqX@X{jSz^;m%TZ`fCwMZ6pxP64F?OyMj6Dz$HX|+hL)vZ zi-j-={Wkwm&n9+rLTlI>$)HYptFyoQi8P36PgAm?ol{^`<0RgFzSj`vUw7-V4f#q} zNNAtK?oance27Atj-yfkw?(Hqwn#~(@qm<7>foI^pzwzj~$@>;rAUIG^4>2qHE3%_=7FWbTS?)kK5 z90ioSM}PW$qk-5U5+G-vJ@$VTBL4S7p|SpPIi*aI@$EqNf4ULl)fWTP)ZD@-8lerJ z`c-6?_ZF=!zrd{Yk9q#y70yOljBRovHSf~zxj9CKTB^~Vn#j|RnI$1M`QdbdaKBnRNpog~_a&>DQ%wRt&^Vi5d#J^(a1C`2B>ZU?3cZS!MT;HAvD!okq za!NaTz)#RoZ=mj+)7HbtZ`MrV#~aH6X9vG~kvuv|4NC1pjLheJlm*4tYd37V^t&H5 zb}lHIiWNUNPM0*mR6won1pY8LNHYSuX!7Xq9H;#8M!G%YZ*a>k6||Oh5OUbhOw>9d zzqfcW$ZN4!9Ns+_!|CBE*DhXH=V(eqy047Gp?h<{eN{$;?tpFicURt8lcykg(=>6u zRreBp!M|b6{6ZD-$2lzIcL)>nvu1AMJ8Z>n7PR4gj$NkX)(5|(>VLp+Zw z!&c|r2_{_^R-msgtb)ixyTeo86jniM)cK(mgyc`6Ix64-P!RwgYjQ&zFI}>IoM3ZV zzo^lT{wEvz+kSi(hr!Fu7e@hS<+Dp0Ce6|i9i{N?YjxL7m7~hgLLzH{GmS%)vuays z1q!g1s|DU|W2F(xcqa(m*2eL-g^bxwaKl@S6S&dQrGe(KUD>!QqP3irXKcmB)5U!* z&J!)T-#^(3!3+`@A-skag)b|;n#djS2Sv8iHps-roFc(pF(JERttwGKIjYt(sooKH zv|3pLGJk6er2G`S%G--|vaYiW%lQiJa{NyH2jLmlkzVO=cU~vuj4c%3!t{(tL*H0S zdOzn}$spKE2?OR7zD%F(LS97OHx&&-eCzgl4n)+EjgTPF+HN^O5mk z;n9ih-I)7!s^fn=Fe{GQ(=g>@t4S7QXnVxA*5>9sug6PXzP{2_1AK3?;Imno4O7*U z_~P9p_sI=vgKf=sqADnLI=CzoqdwyLxzJ6b=#(1=8t3AE|Gm+mKKU~fsGPs&Dtq3( zWU@mPw($qu24gagL09l{MS0KzgbrO=e zYCb~+7snz9ha^LY!z1B8TIkBldm zvt8Pc*pQIj+PXdtUGORxq)Z}LAWBM$G};s3pA2%A0r503iq8NoeSMcvjt#I62b)Q= zofh=j?|nQ3`c)J$62*fjUHX`CqOcE#>)xIDfCbOFgNxoY`2UJVSX`y3z`nMu#q_5K z=S!Fn2q6bRNBv6c4Mw7kcjf%A$bIFeK&p54f}nF2qNX}9HAOYR+>&BB`vg{D373lb zhCR)hlq)t+O}`$2fWEXZw@PgIL8MAL(wYmDux6C&zzB&Jwp;`JA@V-_y$1oVJexGF z&tytzU#|VY9U3LyK-n0F_1*8;(A=FrzquEkMkmH4>p%GUL#HOsb%%F+)vL8-nG=f2 znr27v8@JWNiKM?eO6e(?VOJehf<2FYN;5+9kRh<+vh9fHeSK*6@eQ(gH%IG*n5Lr< zyt@Cj!lDab4rZGh7t;y1j*`1UG}6tRhLn_^I9oI)xA4s-3rr#b?Fd>80)hi!)NUo8WC$Z#jU;hiCcbOL`jsgvq{Vk zX%H?i<+Rs=A`iV?{hOg93ikMx_0;6s8J|rwI8$OM+vK}uyqDLWH)t!g7BZx>9ndcs<@my(K~bfbt4&i8 z>SdmKbARG(Z+KRin?L-(ZEY7p?kDt_#R`HVZ@N(c*G}*!s@VzEun7BOuQp{yym?h- z^Rm-eO=|1ozvV6pt0Rwl8uH=52LT500SX&f%1tpH_UdZv|9(XLzj~L4)IK6-8e|o%urTDkzSBhuzA}VPv94WgU7{gI3|IQ^L4%O~@9heXoKnUo0_OK4mvUd-`SkjLF;#;ie8lu2KyS_?w z%nbIan$2mTT}{+7kvPcd`k43Q9;dKDl1NOCo--ScCC(dM%4!txgu*h@l1eUu?{va__i zvrCm52$4#dq{Z^Pyjz=d;JM%IPLa+V@%hYwYh6oK_1?i$BJwl2XQZ~mDKU(+OFPT? zGnFT=AnJK*F4S9rK-?aqSi^fJe}8!l%5U2tRVkioaNtIozuPSH+3f<-(xo!eJzcJ& z!2I_&(T1!X^Kwm`nTv5upQ`vv!Y-%jksSW2VUckhQ395(;?6h1aMrAMIOr!CkDN@w zvZ)O-TQ$p>dR=Eo2O$q090zAOK{1gUl5c7BUEfhOem>mhvA(*aAL1PiUn#mUscvJU z>@gwN{DRngR^cgdQ}U3c{@EztiN(GGBHW^Una3@^k2w#Y?)(nhbw2d5H*)^x^3dQS zbx!_~i+9Yqc^B6oB^MSiY4S}E{kta!S@ycHCPw1=9grIBeHW*qQcfmrC$)cD0T%K+^1J z$l2^a*^eCnqG2^b9_|KY7tXCO%QQZ%Fj5xD9NDwx0$3qr9<^LWITcl(_y)sICyEU@ z=$ZXU3q0lzs*Pd|ea(jRx4ONwsx$TmD)K~@Ojg4}<6-*zYj1V;VrY1NLa!FCabhFU z>B-%)RLPQ-7IM>=FNR!vOJj2%#BTdknmgOGX%U6xqhAoDIUf3V#n(6c5G!$>rNa+b zpNwY8DpuYf_`2YR%K>%Zg-*DAy&3>0MkCiN@~JPJ_Q`k~0|3pTMwXNO zBY;R{Qo9oPA&D4h(D{W&yiglZtnA)Xpcs(oQ6S(@Ah-6CZ5tPg0plel-_Y54u{BO! zIq3+~I(T#9%oY6dP;B}7DKc;AG!D9;WDexPx3;P~a;R-~td=x`2EkF+ZvTMBtF4gY zOo_jzGIxH3zF~4ccyt$YH>E8219*33mJYqW!%SP$*nAdb{$8 zp0rT*!mb#A&jrXbg5YQgl^>z`;Er0Ihxu7sXOFPT*PkS4Pu6+TnfSMjF|K%L&y(W5 zI^sm@*B?zTzc;#*ATEOJRo}bgJIt{=dnizYdlV1?l4v%`=R>tbCL&5O)n+GrmJ0>xf zh$n3xK$jkU*_B<6-9RwR`^XT3oGtO{wYI;Sy!5_q)Gx)`3hS6N4ZG^``Jadz~V~5rKe;=%MRUj@A(nIsy zimrwmHE93CD}y?2v#}lBd=llArFl|_?v9{92iITF&2rSbpLe!(Ts{&Bfh;)uRyR1f zw;Hf=Js=uyhw~JvJ_40Ctz2Ig!}~qKwBLm(G_XZB9Sz_GtmVL^_V!SPIRC3#SONRx z&qPuH&zN+Cc`P(#Bp@YrHx4(R94zH__^4P(r`9dNFqxdW+=@)LSI3txnl5FTn)wml zP!0@&$aa3^1ts}#I+XeQz0Uui;P8Lm8dRGB4;ikqE62lC=l{DfYM>_;7n&$tlvPb0 z`VQdIk3fZg7*S$()cP zedQW6bL*oFFl-opxDe(JQf;Qa%dprjXi2=d>?F8$#(_y}PB9&Ofk!PkQYVLZ@*tII z+i7|pNdjUVlR5E6p?+fKn>QO&%QKE$kA&g_9n_s~SZKQHv2U2YL;ut@5cd(1`q(?W zE*Nq3PL|&@!+3Eo14K{MBiA9t!R}K78BGR*5AGu7e0J!kfU57<7xP1$zjpggUJS_2 zmjl|@f%FCE0;4kf&lKvurk+cZh0H)d2j1FU@xF4~qOAB^Rx+I__6xexSzd%YKkNZf zU8GmMuK+A3oJjplCZeeqKX~FmAG8%UjOBmjH+WtF>p1<@fsadH` z@6zyhInb-3(sRa7SgJS=s$wjVT@Y5M;J0;>!jj@o>f6p}I8;F~a|I{($sm}7?4g!Y zsM+g{1BGwsBCtACH;exgw?}li8y1@OSk+db{q@bqoFG-V-#*`~2i?sd*fViC{BaOj z@fI`__J9t%OL?Z{y@?RMex{@_ z4XlAH^ylXpj`)x<$(?M{4?^=Dk5!0dy?O&J=^@6vff3EPL$SzKM}tqy^Z75GNR13S zJRxJ5?BakQr-9EFmyaDyMU<{~>;?+;ZEFNvBJ6xm0}EB|*?NYKF~MH^VAE)Lk}6b0 z+mrsj`R#|X27|qa<)#{6W@nodnj`#ok&u$ftOfv&_x^iyN0gMq894|4rf?Z-@yeJV z2H!1#SxBamLqh`Hj{xl3F!Q(g8kf;#<0$iOvkFB%lp%!6B6s{pn2Qnnvd>3@EUSoo91dO+D`WF82VD?@C^ z&NbzFO+B`zu_k@YhOlzqrTQlWcU7ud+k#3Jt)e6=4|UPMM^Gz>c!FRhvCNMj=Y?^t zu%)JeYD*VBWtDQy*BCkqusO{=)CHF@4$J*A8_>4^4&+yX1^7u1n*aShfBv8tJm_s9 zZ1L-dQrdIut`Pe$W`KuJ_`tPDA#gCdSv+!&Rtvn7J`PMhmTRmX8&C%4uUh+klvZ5U z6c&a1c{$ex+gUL8%1-h6O}?4IjO@|smio31WsO&A*RbtaS6f>wyoKnL@=V7YT7fHi zV6L_)NYS&ap{e)6JI{RCzF3^jF|~bn;9cI-!5dc7JgQMBm%|` z5bf%>uC8p3-I^Is)&Aw}jg-<&SxoA`y6pQeuwN z#!g^+M~6*cjr`i|F~9GGp@r2M`xEc)(5=Dv!q`<_i(O<1nfV`$JhAXNG}fqUMRfUV z&UrZP&y3=msL6bI7U%OK+xIcKyacO{lLh3eSwp|mpe-`6iO{^nf>x2~@rm5O*~Eu# zss1K%Rrtnb`D+k#vuSnvNVMw>!P%>Ik)QAGA(t<{_g_cJ1&IMg ztbDUGc%}$mE||D8KJhpvX)?As2bEdveemT`k;%Bq__n2KN#~<|<&c#{zr|a=_^{bd zopVm>Eekk-t)x;#z3}Qt+uHOg+mve7^Zy`JTc>*_ayi|u7*AFeFcebU&}3-qGm~1e zISHYWt>?NtvNW9-7;_M(qf)@*6V&qt3t^^uGG!@v8!%=Sf^a_D{sCLIA0P30pOieB zMvRmZR|iD2b+{P8>Hjjb5A2PXeKH<+&o;QPn!H^1-lSi&s%yXh0EIWjS+Al?w5Y5j zO`yhL8RKd7vAUSXY5(7%s;f~cSmSA3vh!=aa^JVzWD}54*vo0ZAiwJotNdcJoA$Wf z7`_Kqi5b!N#!Ccw=scq<=HIF=Iy^b~<~#ZV7Op-{VLO*XntZ+x=aRJ%OP>b?V#CN# z!R0;A7sI%x!OnjEX6JEI%WX;pD%!y*Zf#`|-QK7CxGqsAt%OeFzKBxgkT6?xrTTJ( zo1+Nnv+dIJg%TDva#DTAkE2M~$m@6d$^Ni*(GNyCMsrCp_vT|Ln{}xqW-ws;BW3p7 zt<@`QV_aL%u`^ZT%Yvx$s8dm9_b>g=McO@K%@JWj7kn<{mkP*$mlN=zV$~try)=nS zM|()}X>`zJ@`ZZJUU$`yZJ^&9XEMY zgHT;hnGpm~nwM{A{z;_FMdIl=&Vyqq4P$1>nxf3>4P*1!{)p|}OJWxow^gn8WHi-= z*0Qy;O$tD9h?ttp{_!~n``B{(oGxB1A#rY%^BbdSLDlyNhPY!fPbvvgA>E7i+8nnl>u!3u3I+{xUcj17C8A`!J|MXC9-+j%eh|`ZtXjc>ByN1_M z4F)ZyCh%KpBvjC;(ViU%eJbif_4YQEHX?xz5*oT6)t4a!yGWBU{{J#<$m#+&UE=aV6|$f}}WPP;xvU7nwY zaz6NoOxE5vTQchmISo8aPiWzx>l~!gph|m+mDd$yOLDm?wdl*Y)_dE+$fLE;Vu`2U z!dleQ#fh~-+VQu(#4m`A-%^Z)4dV^pgj6dBsx(>&i6D(HrQG+FdVKh%iZl9@ z-wW3YrANxo8tROzE7#XGp)LNnql4zOy+11`!p^sag;sP9Tegwm!Oa;Ih2DG1DaKn0 z8XApz;rJ|-l?Q~4{&)}VIx}A>J|5L~U7m0Cii_c9`T@f`#*4fz7dlF&vY0RY8NpXSsu#t= z?j{>OuDpA-qe2z~2nqc-Z%VlSn>RJz;iH4U@^!79xj$_qN2F)vbOyGzbs#H~J3FEJ zJITLUXWCn5S*My@c80!0s5WWCE^5?veNBroMX}49v49yt)vOfr2wF!e))YUI+sAtZ zfVGbR;H0-Ll2~hw;@ak|{--!iJLpG~I(tb-{C=zs&vLP#D$n^!j>Ruq``C;Gl(7qS zhz_!vvgD(ti*sNq|+w=(p1IG zw!6cPNSUuaT`Kf#uYWy-(-Q=rt?YG)KcJ@M{%1H=MnCj|89BSeXC@KRTr~@;aQPW$ z>iT@V{DfGkzms&|6E+cl@qYfrsQH zBTVmIKHg+{18kc}scE?K#2>p}mw)FdXXmn}LDSizjemfO**pSQoukIl=^Y&Jya5^b zTP~iY+>=~rZqv+4pkg4tnF4z`I;U=B2n=)MqV&0RWtv~B&AJ!acfvmp&!-adXxaAf z2W}Z~Ipemp{(vdbilJ6S%{0Tp`>9F3a`n<#C`*02}Io6Tm5JwF66l#qPPP_ii<5t}$MF zrP}ofHI?Hx+G1GTw)qY1%or#y`BkrYgqn*B^HzL0tnlXgseNJJ+8DlD)&G=xYgvKu z(}HpO1~{?8zczoI_7|F!o%hm;mcMhaQYxktkw5HtQrE~UBIM(Q43fhPdHcCc*ETCk zu!6mlWe#YZ#n~)4M{4BOsb5dEs2>!Xh|>`_IPdk!-?IwFFsvLHHO0T{RzcDNfg8&ZtT1mnMuGlG8Z z(6b+$kB*g;c)7z#qYZ^~)Aj$sq8#ck&HoemU)F{M`&jQj7t4Z4fNW2r0aZ57iGpzl z5aq=-Ck)pu#)DMWi$f3gN37gvXg2o#9S0`Ua!=KH=D$TCHt3OuHRrVrMC*1r?UR=_ z<6fJc%_6BvotgSYC_d`#XOp*^$rS#%ZHY7MIM_F(Qp`#1H&7xYWUvx*{=|$J?N_jj z9keRx@^Vz4q-kG5jKykC&AMQP9#|Zg>QDtJ!x&~06pv=DCib~w{d{=`?7?mw11X8Y z^5~5q5Ik&PIWz?6(RKX8r!>n)56z+;nRV9N9U`JWmwXG+>bO5Ze(p~?CL_wS(Gh*u z8Hw)3%F6zg3o<#yDlsO1N=@^WzyXO0OR=Pm6cKmTD&&~kZhK;=)4n^{a=x_Zmx0g5 z%Vcp=Ut(6(Z-GOFj?2EqT>~IXam;;$lV-vP=OU$0-64%@2QDtqInGS^A?Fs~pm9NTt`VNS-Y zv?15+2aVcVM zXKY;7igrdF+@KKN&(dsiO1tUH8#YbK-6u2aO*a%!v<|;)wVY2k^-X4O)rhSx4}DB@ z3*sFV+F)ZUU5;00C$=WO$D9={CUX^1UEVK)^~9KAY(wE%+vV>L2Hy{rhPk)@W3U z@^J+svGWs7^YmElGel-Fdp+=P_pj)@}rkZD#HSO=ta*qdf z2LFvQOJ8d^!3(&pY~cSc%qxVDqFi%&N#xUm;O z_)hiR3=K8_c7l6zVlp>49ym>dSnKl~l?w}=1t&M;>g1g$?I9rrSOB_?nq6N=TvHt} z3WW?O`w2|~q67Jyrrj&Gmbc zDb6UzDELe{P{8V+K|D7c|$9B%gih;LjAkaKQTI%3tKKy4)u>6MH5b=|8rq8Mo;`MI> zDr%Km<~p=_e-7$c)xm0&9xAfho)dJqmYLhXs9yO^>hOu4u&Z2Ye92F=&S>i#3+XgB zun+qi4^GU}z+nN;hvyog1CP66himh~4i{OM(Fh+;7*`}{e+8GyD&W4+BggA5oU7{j zNX3WumOGDY8EM!!{k%5Bh$k|27>QP~5oz1E zt!r{cS3TfsA;Uc!V(GY&=1JhvSYES;;Pp1JeuT4aH!FJQ@3Z9_U^LWwr_4CI% zhmG(1bOtQ;BHk}b8_N&6yW9l45ilWSoV6_}pG=k#GujO7 z@220rJtp@6$+a!WHtytS9}BL`bw5%fQQ#lJo|Cp+NhuCpH!&XtWmIV&HcX65`cPK0 znV1s-aHfLJy)j^%1lz$D?A`PI-(+}_nLDU%cv5U8&3%aDsfps7Py?!m#8#u?b>FUy zo91ms7N7kY_*AGKVnywK)OvJu-Ybyo!G-bhHP7x7P$NdN@HdaiDzjUGvZ!7ns*7nF_TcnsVX$d4UkfZFnl| z0iKy1Tbr$$pB)q0?vrV92u#^KM|UT88*Y~a6h77!2@gj%s6B?NF$H3qnb?7>EF^{q zcqD7Pf)kgpYNXtU4)>@^+z6y|(Y8KP1fbH%Jgesws+D6A^E*~PY%x03-w~HVci%)+ z=pMm7qC&vvx{DezGHq-@dCs#{Cdl)8g2!sCb;q^I5p9o&eFi7~ED9&`Q^jvX>?M4b zCe}^R$NXvVt+QtmcOmm{0tUm}9L1eJ2ROV;sIO4%qzDO*2ae^z0`V=-Fa)xs>xZH> zxhI1n7ES$fIg_3ql-~cdeDO>qwgQUm|Hij?6Bz*0&I#W^`|moL7$8M&Bq>&HK>DYc zV~&2#DElG^)HsNToXf~`9ZpuV@B{pYz>k_m&|W`{Z?@U~rEDu5(muTlfrF}Z3`=U4 zCF}4WsRYQlNa7QjbjZ(br!@1K!RF}PvvBv5{f%)ha^Ly0Ewp!cf16Whv)|Fp8%d|T zs!nmmkTgC*Cqi&M2lmOE^ul>PQr;aF?xdmt=RQDG%|^m(&}~lRF~LNgHlts^V9b;b6x}g=?7t!|Dzv( zFIEFsX1)ez=fGdl3<9#Lw|`n%I?Hp$g(RRRXqI47YK&?u3q(Y3LaVOpW;6Glr=4!b zsoc(o!_-gi>rOeE*VRaa*>MSRGxm%UH@Qj$rfil#5P%tgTSzoK56s-cN1h@TCB$b! zROavZ-kDnc!?LD$AAj`j6qK?UQw?Gr57V>;zWdv4=VE-!ZgcU;AJ`5Meo_yB(NNtN zxn`o%Aqx15xoG&f45c!vicDCT>Wvw;RGC_U6}xmxLhdc~*Sz^CKbcimV(gE* zJ>yI^$c8PEMgWm*nMxm`9q(#_|t!ufzMvC4zNYW zueN&LZ(O=Fr6L|?zPGSCF+O5A|7NFcyZEe9m3vdQaa@#XnNASG4?EqyoIDrZs3dXs zCtW8Bv`2r7{rG5LdC$o6qqh$avbMZi85iUny8kuy!T$cvLTiW=lV&3W7q6nHr#@Q= zOT}v4^4P+0UbWHv3<{t{@~D9_TC5xbNTV9-kC{PRp@Q3dA%0Lvo!+9R*i*N0w2FK(G&w-LU`1t70BWdf~?PhWV15c0Qrbv_Sq30#REsR(5>*`}D5%=GR|% zIW-687OB{xOGF}A)FK5TH7ch~7H6F(^&Jpv<4zFU7Pav^zwOQAxg$-$j&E}{oaSOx z2YXw$WoeifG`9JcX?bLL*!AKZSp;PP_|vd|pb{d2EDJI)Nj|GKNo8_Hj{>CxmaU5J z*N@;g`~Gepj+VcnEBWjoYoLMdoQr&6vS2uyE8d|D)}*=vZBeNeT0tIGskv-|8WqY@piUHH9R=7>%tJ>t})Eqo&974~fVk<@SYvEwByP6@Ag*DDNka?P@n zS4h_|VL-%>dg((Cs0Dqgt`zAcfN#!68NIpVYvE@?gBBMu*1?Aq2!}Vd9dlawKIb`+ zX_UM7Z`S-z*tfp|Z|O7(Jn1SL5bjZXjN5mgBTJb+qHi?21oG14bcwIe>bfw=}-;8%QK7&wI9^#jo=O@3#NTPan9Vf91#Jf`GP!=gTso~4cO?(##eri zjkWwVB|JZWyvWOsN+EQ-T<& z442hHVy!)!`hr}N%qlaf)Mfs>_8{7ee?6#agoMzr5G7@5dssS-&x#7#i+In0=$*{l zIz7PCaS`ahVC#+_%2u@^wiZ(ZITL8NCrJwt_-=(QPssPS$=3Wk;HqJ^hz@wS&X`Wp zoYq;3m|%I0l&Z&Utm08XyyASZ6J-%XaTp=oSb_M`l`>^6bB;8J$BWWesme3}KMiA( z@J6C#ZS4j;G8YTc2p54xeW}%7eMiLFV0*U3?XMbkWYe7W9LR!w3D)<@{pnJNqbITK zW;tQoJ$07;9+ApzR-h##Z}T6oVGLpGAChyl=2z+$jheAz=IYJylhc`&bH zxjduT#V1j<*e{WgVqu_quOW|;b-BpCcSf{d{;z{cjQlXC{C_nR0+R2!x)JRur@(YG zj4I7SpdsjDqd`D^7;tOmXlIvQt@pCRA=M>@vMU+oH@LshMbg2Mj)2Jh-l5=IFd-${ z8Q)9oTI?06KlK3`z`Ag%YHoDxdUKeUx_QKn4V!Hqg?ZZjnO*jhUkU}|TEv%B=pVmq zH5$cn*X?W$0=Q_IfZ9fvB+IG3K0+~iKP29|=TGkF6svy1#2u(sLEFXU%JFn;_Dx#o z@Xj!u;ltwIAt@PSx@!zVj%cxQ`*$P8O9M4~GpQf5{Ca!QsK3-7Fs#G(p|m%uS<`_5 zJPENSbo7~%@*0Ih1|zOkrk1gd8G!J^TqKq6Yq;f&0O(yG^5{OTJY%?uB!J6_vF@_v ziXOlOPF{6Sm7{&3B2l4qr7^fG&~&s4#iMcmP&-U^F}KR_$(=@x_m4k~gpTT|t;qYo z!^*=m4xRo6u4IbG$6JKpRP<3TH@$POoAoSLCeX2_+3)0&D)rFMJU`yuDr+vDWOkw5 z7}cx4pF+y+EV}+LhHx-ifee92nghOCv=?@;A={dQ--HH@ir~{1x)`h^yM=#Sn{{|Y zyFWusg}-5T&u&wtt&MrJ#yXiE+;$-Vnx9EH!zIu%COJ$@aDCq34Yv9HU`3SZZ6 z{2G{+ly6c%4ZKbmHuw?&^SS4D`Y#xDC?AY(I9R0w#k2bveo*#>ZJ;wA-Tmjo9ph3$ zLmNrJ>&NVyofdvde&h`)Vl7)fm0B{{@)|&(Q$q8ryMIz0fJYh={YdQ_V85dDxJ8CI zINZ(GOesU_JA9$c=tzPcfj@jHPQ)Ie7kJmY`|^pz?Xe6yfHY@s#XxMG{HuxlxAJ(C z`x%Hm0#Qv7Z9KO8WN2x1k-7ql&O)Rz1JJ-a_b@$~V*8tKMjgeM=3Wq}D4_c#+L*P! z&uwL=>;qMyo^dC)Ep4BUzHH-QmnIn8+%bmJ&%9K# zH4DlG-;VB-6cdU=jTvyigxEp*MN^F4MDJG^L1R)dEfT#Kl1FjOEPN! z38%{Eztd_3Xa@f&J`kLs{#qh4f${dO@xCw*t0#Djn;4ts6H~#gh5a)!!D`!PMHjSx z9tl#y99x3askB|LEpqm;TwydSzF}tSJuJ+=JQ<43UwVdD=pfD=oyWCM)~*4xC*=s z(2q6!*y|6&uC3jz1J5E;Sm}U6s$K<-|GvW*FL+PTB4q$H#`kT>0M1Ng<7O0i>ZyT%@l5^2ApeUAwMq6v#Ih>+AS$* z7gpwQgf1D~xKu$K`%};C?dA1>(FT%BguHx}JR|+ZYzEtxBnt?S_V0)YN*Ql+qRvQd zMWtHs*Fh`S`1FgdYd%H7`E1<56zGqFkj*_qva`K?5Y~CP6x}|yyURdqk8NhdUg(YX z=$s$sgziB-S`4UY%s?el62zyzNg?zWT#Ya5*N%=mEtso!{ua`$i>OVVz=JsH&jx}o z!iSHi{!<)IKH$Gbm+fm)6bF^4n(NyE$8=qM!vsKZSzElVD;oM@bK0AVijT>7|8p|` zIYu(B?>No9kV$nQkdszn%}77q79E!#13hwF@2lX(p^O z0OH?fx!BgUV_~)+nc7<>1oXBvWu8HH+JC%=#2c(J7A+;DdE{fblqS(3+z1v@Jqj*{ zKo@whEOFVrS_jDAq^y8%A}(X0%pKNGu&WfJv|VVlc-{8I{)b(^OueG1TM+!=SWa)8 z%a}aN>_AUtgH2Exlh%r_(TNAXJg3rs<@tfI$3MOlQB`!YcLWG}(02seAsMo`=^aaOLnmfY6kzWh~#Bnx(I zZjO~S6`!+*q9w^wNu_7MVtwrh*X@%;E_G(QZ%A*v5!jGB`_8~Cg{|6up>@t-g(U)1SrV& zi{4OO4v04deQ6==l%O&2iQ}tDk7M(uaYNo0uo;)cQr6@1Zikm=4>i_g?9_C{;%j1T1|9$X?7hY6*^_aSNXbAD zd-9`u%$uttPU@DHA@`INw3V%=A3>gE5lAhxv2z771}Vbll;jN0jcVAKhX z{{y4$xrn$ZN*qZNNMWmXnV>4He3eon5#c!{#F^LCT+w`yf>9v$75*dDd-b>{AE94j z)b%~NhBp6Aw)M8ly9OOzJ7?rJ68gx_Mb98CyujqlZhX!B1I z0*;eSN!0Lf;J~Z8FZYPz|5e{P*?|2KSY8)>iz}hbseP>!@jkV30)Usd?%a2!Zv@0G zFj=YMB`tF>0O#T4=jCctb@05cki(_a&y~F>_}S?RP>6L_1zRz-L>>pmtz9Le6=8r> z$;Rf`oE%^p>nO9$)wfAH9!z(Pf%o9IpPbM%(xT~Ql!Q{iV#tkk`REEhW?t0Y1R882 zC;Iw~+KjnF+z}N$Q{0=3H|HLm3WW1w&8f-d{C{E8MW9I9qqJe6dxvdMQ8Qm!=hYXwCSBIpvCfBgO;$fK_*u?GKp{L zhgRoWN@d2}tqr(9)9V$_+Gq03&-Z6*9iKb7zln1>J}YrF&hEk|p>l>x$fvtkc-HA~ z5DYa^vS2Id-T889Ii9k0S`@u~g54}`P?G5r+|Bb;4ygR&^J#H<(fU4n zIi=$1QOcKIp`)2Neb^R^8jh)VxoE4d3p3$cF++)6NDHeg2!1N}N0xDeXhge3JGONLi!=`pI63qC&A+qr%`3f70gUs$ZNrXKM37FYm# zNn|Oyr-M56s7>tQdI)fXUSe{Z5SY7>Cf%;DR#DfP9HTJ6Z(*CB*k0q|IMkveCgXCg zy z%?6sFbseFKv$)gQyT|;-6xy0joNan~aJF@pd(x9~o_exQ#xr%5U~5_1ku1a#anxmJ zjz+8z?c<&TI+}Z(DV~x$1x4p`8voh{hWE`697C4*$`n&s=)%RMF1_;ZC`WMQmpY)l z)d*g`vh~~IHM`e(sZo-EX;4{w4hB!P(EzWd{ra}lm!ADtOsI%DIqx~H?Aitu)nYko zDyjKkdc)c3$cx-W4Oj@ZM#Tl!<0c~lw&ynobYNRp%2TQnA9Y*dCf7QQjTZKf^7L1r z5-(J2I`20Cnh&GmI8~35swtR-jIcY6r8uFO{Tyor)|HA5zy!Py>mI0;4K3 zC7xIScBN7R2_N8|FL(M#b?4xNYa292CJ_`08DQsOq6_Z-nsU(kAKI9(Vc)N%I zwcci*a9c1P3_RbIKV~oJ2Y#5KZ9JT%6Lg)K(c3Bg+f?u5k?mfK^4~t^4;j9eDPU+I zdZvWJaiAVn`or#XX4b}-wkj(}177*)4d=T^>sSCdy)kHDKsl-+I!@i56T2oZ+;U`U z`JhDJMho3)JbagYaOOQ_ueLINpgA0jtDpRTD0|PSCZj&uGYP$80i>fSs8j&~DG7)b z6cnVFP^3%mEd&J-sYa{}HT9bUe3m4NMv#1v4M}p;j_i=f zfh7~H)_0M1nDQ(lqt*us`W)U(hva3JD=v1-^hdmPokOk9)_k!vGML?}jg5oE?`gS^ zXiBUW%a_s@+nHY!sPGL&UZEv@X8Hnb3f{y4fkzSoMPnA%o?6N4k4GyR3%h-HW2Du* z{-;>tuF;6aMeTLZyRMSvaxD7tIr-KmfCzGt%WnxE$`m%%49{lIDfAL5Ne4n_K7lg> zgY;e*o=axfCa#ZDlcKDq*FMKP%j=U!%J-5ROOWN~uaj-j6|a1yPy@E#_2<|IrjPCi zcgen-*AQO%_ZpU8SXNa!5~uk-i&#*otZS|0s3m>8R%{B&_EBW{Id+hNGu4ltHs$Ojw2w9Bts-?<} z4H0RhqeSL;&y6)nxut!+a<9!M9_*wI^4fR*Cd!OdV`Yfsnt%YWoXhcNejcUU19j&v zs7BqB)E>tf$Unu(@3lk(TG~3$jhMIhw3&Nv>ELqpLqKdc=s`04wE} z=D5s{*9G}cahi@!b8JL>$g?)=iG#f#=jS-JT2X_nuL`%Gzb-8Zo2J)VOO+?phpq}= za2%=$UdV72gyC8d=hqi`Ln~7W{fenQ_k>IAy{w}c2{$VzkQo{oqy+b%Ry9bgJ;@c~ zGFGbT;>4BovcdkatG>ui&G1{Iv{tEwAEqoXr(M|DC=14Gqmgw+lJ8RUOOx;`3?ta* zB+6q}@oscIa!ARAHkRnJIsT9lXw4s&+SYV38fnwO{VV$FjXRR+<_Yb0L*9aZP(GuJ z`tL$nF6HpzN|ef$Tod8B!14NpB00Fk30R~_wS3sOBM8@~0mSz|I7;s@Y`?AnzXh&^I^hR6>}Z~uDE?qXI z+nkbi>Nsk(yMNz8IJ@XQDan#Ci{rO?IG&bh1&pHX0kU4b`@W?L;79p|Zsxm$7`1j( z<#9N`?I?4E|Bl+aU9f6N?YnJx`wTMn*PUtqU`Ou9Lwy(spF88Zp6X0!jym|hbDJe6 z-Ce!&M^%WD!(4O$BFCBL@*>L{c`P!Hn|UpO3}ke#^Q`poNEl)i0(fr0M(=> z>YuZ%>@uh3SoZBIR1>CkoOFsI+87c{I@7j=RJPd2c{uN`Fb2`T8Qq|p!G6b|PI=>Y z4}XlgH5nZ~zRVhaIM7pg3_ZEIYDts5sI=T_SbUjlKZ^N~3la@H1o1{+1*RF8x0=e9 zBCZIRzh=dN1!j^ZD&!r4wz@#?uX-;i#7vy*xSB%aeG!YX8IgY2o3yJFZnn-NE?)B* z-~qWiasCCjnQ{RaiA8gTp~7#2%>0#ZE5PQY@9CO#mvRU9moev+Z?{zU7UpmJD~a~r zSCrENzHBGnq+dETNOG*WK!3~9Dc)CrB@phl_e~~-f%-1lr?Qs5_MEk6aj_oO}Zs7Kq{>?U-07Wxzp3r0F{HN zb@<@oJ~Qc-R!l`a$mr2V;IsK2MSvUB*~5+w=6&h|RNDvqo}p>(+blh2l=Thh78Y>H zBMS->fPpFp-;8}Yb6UPd_*eLQ;MH`r28yA(EH|I9>_Um_OT5v_OcJMPmVYuV)u1K%_YuWg?aR>9F4gHDJctU zZDpF@h9mWq+W*=r`%Za{Zyb9H92sa`2lG5$;IZJv^NVNhP} zcni_Omvv>CS z&pmxVUDEO7J+x#djyB4(ICiPk6n^uZ%~w3-%B?}{U(m6O)$7AA6wHwZkDk*>`qVZN zaQvQ*Xl@h|cCpGuQEFVHU2@{FiEzX)ZLEQ@j)|=h3)Id{cHqcB;FWd>>OslTj2}i# zW~Mz-qBKm`t33X?WQs~bF&0etga&PMcfd$w(eZ7)?pUA_(xT7LISZU=0d{+1gJ`2j zDS&5Tr1<&0gHLTC)?yfo6yf5RK06oyi?yV-eXP`mz@ICQf$$LsVeMYE%gw1fcz)B5 zQTk_17CyE`#;E2`lfFltlei^3OVL95smD0?%tILK#|yhF_}AP_$>*e4m=*)xjv))% z(2TtEVo1au_?8M@G(5uPDO#=|J}4r2D2smzJ;*)|G-I!4QmMwjJxD&MdhEDe(|sKW zHpV9(i}Ek$A2*9)?z~1%f3FVogPtTf+c@Ze_u^v2k4vPHm3e>VpgXmJ@ZfGk@oeS! zJ51;C5+vA+47P_%s*aA;iOf>+jjo`jNFRRbnG)rrU z(s-e7^yM9a`b?>b`t;|Jq-aWB%*|HN2WaUffsteV?Y-yC+IUUo$Q)u2^QsU?1 z6*4Ls%pUxg=cWG~B48l=8RUci+@oWiTK**@q8w(&J(V9L3+6H2w5mqbX(|4DmNQ!3 zeDrq8t-p7mVx_(}e_@P<1Ksws=d=Ca)hAgm8DiBSO2kUo*6H?b%_R}5yuO1#QIW{J z9yu*$=^KTSOJ!=D=!E!xz1q<8_5Q$tpd-Tqt!Y>B?bEJB==z#Z8hU)c5X!cMv^vv0 z$J>AQFin2eMyzhkrlsKcl|MLw*;Ge_+91lX<;1MIGA)UJBh5SD!$ZP(xZ6v@eG*w( z>Z%hq(2d(|f-YHI-&Xz?MeyGR;_sKsyAOwGLt#}-Fv`bT+ik(eO9>DETB*oyt=3ajt^B0+Z++Eed0d`f>P*t#zgPa)7Zn+%@#lt$JjlPkT>wv zIj6sz5}cZY-1X3vpvRBO_7qHJQiCgi4445YJPh5SkjiBtT5gK>SLvx!Xd=S_cGXjx zg}qu@)4e^^k@9RuY~br)8_Ghv2a*0YAmysvXN=qty+(c5c?JUZXJNYeP7~|D4%Wj(cq>cv4`gJBv2uu%!6UTG#*&K%c99 zkfZkYknEeBh6KU)*$nM8(2m78BM56l3L}@jeNM%a2d7^ekVx#N*7!>zC zz5(w<4Qe2Sz4-exA+`0!3V#0;qv{#h&%hGiqrYM832#@&-{T3zHy4-SMHh`P3h~>P z*HVtFxjM1WRR00$W*2eoMeD6Op(8mj^SZO@ePiJU2_c-E=cmv+V?Ko6& zCO02;1*@MD9=NF?7G>w#Pvo9{e|J<=@$Cj_LOEhp51x`VYs=7Em}a+(O1n0ZxTB=y z%Ikv~x)M_Smt}Q;BqpKi#{ihu13nIbtFkUoFh?)6`IH459H`FgFV@D#>Vnc zzE8F#ABTaO>5nEHw%xYvO1d0=oy?BgqN;>r8QyI_!=0Y8%R`QIG>fW1j~5K|phG!7 z5@Y-|;`Wa^??b75&Gc+HIg-jRM7R731Bh#!+*^QmaZ%jCO-(R=UiiZ>D%|!4P+M^H zE4E?z^YTpqIMcs)=VozPWLbI5NG3RD>DXl;eaRk9$~z&QKH2Uee*ecv+n4bG2G$(@ zjs$IjPA1k51BjL?stDfX{qKY{T8Q4d%i>Nf^4(DMd3>wZJno*_lM-GV;Hbn%p$Lzr@ll-aHzySzg|ofu{JNi%ClfYUn97*5fhyV~;*CAB&u5%jZ1K+pdLXsV?ytmXv7 zB3;Vjqp@$~^GxOaaV2lDSkqpvN3ZXx`{1S((8{V4co%U+orpF40ddd1Nqi{B%V+?DjGG9=80MJn)YbQ<{hn$7-x%ffz=O)^k+ z$#OwDfk#kd@Fn9TzTHaA@L`_ptyE4H13;w>W0vKtpO3M?nL`*90H3pV-ruv&Ppa`? zDq)-JZ+Wz9RwmsdTCT2nCz38eXC!=UmSY7P&n95s|izh(lr(#{egGf1Ogo^{F{&JlODpvmVueN%t|tk+!lSt zw@lbLxC#m{$EO>#O#8T7Tc)j>^J6Ilh6BHu8Ee%%%wB&raASMCmxuPnY~x^2se!F2 zhO67}T4pYrT^V?2kn=oFxF^R`O1MN&Nf8pnzs^;>k%&PHp&tyq9B?l%tizBTN}i58 zB_B?q%A`F^TVG@Qd0qzG5*a6VUaplYjbYe?v@*`2>tnX~K9QiV2K;*0^oUm0AFU?2 z5*{;SjL>w03(DT3^PfnA_Vd8ip?G5dsOwoBq&XM4*R|DkkZ?o-zc}AoSkS_DrQ5d^ zi)3AA%X=)*T77K_Ik`DsF-Eh@vd%fncpfEsOTVcoXs95%rq?YEap-I2JvJS$-dPA+ zn{|o&H-T_n&*zs=oL9c%ZM3%jflY94U|$LaUg{!_+nESErxXSwT#2yEZ(3u=;r}jL ztO+=}aGOh*Q9VD0QCIy4{{Oc&5F7okHh}K8)j;q8yXxkC?y*dfK`N{U7ufi@RzK%% zn|TeBj&3TIM^tNyz{QO)Yy|uLu(ws`6_H`;z^0Fg8qt1P8g5}YqFhF7=7~!6@-H^g zQC_QWWq?HK=8Wme2j)zwD*GCADPYg>@A6Q8dc2XRM`$%CfbEIZi3^J)3&3iOg(bO3 zjR<;7Q9DAPt0^GUy$8rGk9c{Ou-l4Dgg7(A-MTATmcrosWcG)S7`^&j^bNH$Yqrsh zS`O&rwGw1+ygmCxLIgK=v?kk!b1eXj?m%zm$i=M_q)90wry?^Y0j#2>RjB$hwDH|N zp2hg~i=LR&$ftJrPtT@wF;&94bAb(_H-108TXbzxx4q0;q{iJGou<+K{lzWgp?Ds- zod@crPh+pR-$W=2_5NOadoNnQLw(v~dQji4Y+7e9@_c$T>J{Mx%3PP_QCxE5I~~MZEAZQ%LBlE#u~eLtEk=RxLXDy@S7RLzv}A;ZnjJD?g#o!3EE)4H3u@E9!ykTOHOqCFw-n_WSj1jYU&=@5Va_ejTXT zF?5=vct6Y#(htdpohUk`} zvvh-BEn#=wQ%;VGS!bTb!I3qyh7iFa4?2zC;2#{mwc;R8(~hgVa$x^5!f9RGEQ;JQ z+CCW0Qn3@r0U(j)%STfdI*+j9!VBh^5PUFjaNiSh))8C5b+4RM9&qT+At1AS zt3AHRAgjfP|A6#~fZ|dasGJz65A`eoQi}TmUX*X&Ov>VA2%ou83J;Hoq8KC+`{M66 zg{~iQW<`R8orOSerd%`ZLHm`}SvTXLf@K=#pK`DEy-0@6gkz#5U==iCcR2Q}=S?co#`&t6Zh#$DDflGR|N^%<1Y+frDv^S36V;zav}JW#RV7el_UG5Rb~n z?-^+SETmM`l!11~pmV3r>FP0a02{RWXK-R!)=#UKj}a|!wt??ODkD#BW$JVaGtB4r z#25to*;@x(iyZ0!J-^Xrv{$25$B7nkEHbb#1IqkNbYp&KS3)=dm>Gz~7c!&wl&nmL zZsc3$|4_f?390KbzaLi;fnzT&ALutB-^nxHKOSUYIPsYe_@3CUPiI&F@y08 z`NXu9u}ZQoHgKuBc*du6gVIT&YyKZ!ZH13Py5KdjahIFZnJBS20PWWUhU5Ny*~XBQ zpL~+3WpPa|3zWo5)+1CPdbo9;KnjH3f41|%9dj6w}TWu7ord+KVt7* z1R3gAZuk9Zt>E`~Dd82q6t#Y^Du2y{C&(Nckc!kuv*oawaxabMsWU4uggH7E9e-}O z*=$)gS*}>U*he+x%V`S%?7X6r{U$_)<1dt$%4!9b$sphm9S3bp@=hsdCy5KH;mCb7Gbt9ns;|9SyBBTD1rhP9%{a2a*E1Vz7Mg7w)(3 z_$vP2pCChs)6151t>d={JxB{O-3ddHGhW*Jz>iRUt0#wl_NgA;Z|Vkf8OeQYZwYrU zlYwVq$z1ou_bCqku;gRUe1>*!z@}KhE*G(vBdHS8)zz?tIGeH0ha>`QhS(6x&xQXM z@h=Y-)YTP$-ND<7ZAe9<|AfPiE}otVvf?Ek@5t$IzP{x3^T>!!_snEWueamj?JELs1f9p;z^tIP&Z^9agO>r&I$@uuxyvu)DsB2f=;L%7Gw*r{^U=C=N z&(FwKfvAe>cHBF$*Gnd0VV69``HcFujb$USdEZShx0g&@ioPdG3Gay z1hMxKNOzCf$2Ld*?k%%i*biwh_g!h05%5gkpehEgxeEZojyCKuKTf{U!C3}&cE%4M zKc4YC3agiRR@3=2?1`%02`D4*k7XhkGkqY_3r6z+P`crJ!PxZ2aEIc-Ia=Ja0#+x(qMHCIb`?lCAhuyeA<{rvXrx=h%~-Ph~JZ`U~v!e`{M5hB%g4fF=X z349$%{-4@vyUc=W;y-~|8xQG%d-D$M{C>%c&lOZXDD#f)FT%#n(SWlw?6h|?u(Hq0 zG@RmYD*b_IfoYDi>b`NRQe$`OBAu|<$MJ6hRD*}pN6R+I#280%@1%Sa&p^8pH+QlQ z(h4wQ8fQHB8&Td+`0m5;ooNY=du~@d!~=0R8qam{x)}Zgk$o2h)u84tdvhdO@ISOn)luSTgzP z{?M(U={;qNKOLXzlU`6|&=&;Y&)(LxoK$*7Pi0dXlrD~fsujZBJ|*J2C{9Gpul;$b zC{mB4xVIzo@K=(5>_~|sJQrx-k+MEIzPaTCh&A{k8{7Uu4AgbiLT)QvS5+pzL?lA- z4oAxK9bwh5aPaeyRqL?y5c`=fX=mR6Pn)B*=%>yv#ch-SMA#>`$$rM)>l@V`solI% zM*mvSP1eLeA}Gi;2?l=W{|G54e4~U@Pa+Jr=n-SrO@g8({oF%Rb6y9~fxTg+H>X^TVm)E@&{o>qmx; z{Iu?q_noFmYtJDxXXQ_WG*A#Sr=CY3VxOaMt+@F8RV{G1EK&@RC;d@$M#+roRYSy` zM?GoqEo*qHh(Vg^pR4EKsTN*o5Qb{nA;O0t_?gOs)!bDD>jm1yW5nw5yMz0mtSvCt zT~Fu@wgua#jYrlzW&%qCLb~+hiouiW2OU*CfE#T9I zWGS6SDdxmP6t!=~9Ei)Ra?U%(n zj1NkR_nMXN23T2>#ls{7&m9%;{u8jOao z<&~@-^fQPBU=z+2dj8RfDPul*z*y?0Z#>@)Rw#%UR?>L`QFSIcBDTwSY!y(RWk)a7n;CI zley)M@K$FID??>q(6o%~Sj}jkD6~48IfR}D9zvY!35iehit;+s@#3Am?}y_vecPy} zY|Y!7w{mj;^vvuuyXHlJ5+G+m{rPoev@LJ1d9jxe)|tcHISjbxKsTr3p3m{^c>5|K zsQuPNKQBPR*Q2#zW5Ti_mfpImQ1i#4Zg&OTW;4ux$gM4w?=+Iv$i^&d7Lx>&Pt^~S z)yUkV>!0IFiwR~Ko@=6bIQOX|^u;FSo)08Baurqjs#!OR0|fkY?oHsjU-^2KRvZm(UTsa3I)GilHl`kOfS8} z_&_dadyXGkeYEXunfLL9DedVkYh*FY)2=qcxH=W1+c34VK6I^q;9W>v zovo;fWV2(QEG|avfC(#{GRaN+K^Pj;yg{nZzRP3oYGp48ugm2%maSbmBoS~wPJq(Uh&Wrz+DUpvYtdwSK1EH{p*XZAS; zb>bFw``DZuAUK^KKO+IBa#-iunpScd`EG$PVc~GM^1`NB9P3=(U&64TjAcs zewp(J;^JPuOGrmwuFSRV@fWir#f0iY)N%a%1&Ls`q5E^IUUNaTg?kPB_+Ktt;RT2G zWp11-Y6|1~1et5YDPx!>nDV!lpo~W8eF9vUpy+3+Rd2>f8W}Kg-Ea0iT-m)Ew>vXw zPp6Q)3TYqOisa#`CwFJ^mP*E2iQ`{#_1{^~b2Kn3hB(QY@tIX-`2;25U;Ah(6y|Xk z?T)=BT*aJ;``3U!V5N`8@l z`q8+uwMW>0Z-o(M_pQ>TPAi9d?~yVq;$_)~R8ct=in$ucd(#JY{MNgi!-=OFP(w7% z)K?0u|K1AR;la3EqG;`q7pb?G+jthn-1v#ovEO{qZ+KEfg0z+XfE_uo#O;P(4iXZp>ks(L8+o8hjLxrd6RX zY+%LBg{9hI&Ayk*K@PDM#9j9R>bQJZJbnGX&WF+Wv4D(q65yquAyOOx4dq<~C|P$Zr7Ux5{MMUnzV>UUbTtZM=H~#0=|Yf6_0e4}2G{<7 zo!0=ut!vOU<8%G4;$`sW~A9}NOSB1^UAU7K8_7?4SClBVM2gUS*xJ#|De zRQb($&r#F;D|SPYOGrDj!KF4w;)&H&W{5sY_#zi^(R3r=d{~Wv<9y&oqk+UuUK)mI zuj!cC*F}`p{+9W-#zdc#6;0rh&KW1lUI^WJ5M;t0|MGh?dtx#`<&)P)ZF4qq zlWJi+_;lBAh``ScT|Ea~QvG+RbANIh!xb-=gfTK)c`K+bbbU&w4s|UBCiF`ZU)nr zP$_WSd~EPp{61MU%mr;KF71IY&f-C4L5!{j*}nl60qP?gTMvb26~2nMmPl_@#t*x#O$L#BAX8lPGD+u_llQP+}`ZoBVWK4_~!=v1Xp z=);MkWs;>~_f}~~?7b+DH*;8;8CB$~Bfw)T;!~Ykaoac9K6%inh_Q@(Ugw;DNg|JZ zYMhT;^=@WHR0Z=+8VTUy(x>8*0YgbeA&ja!9$?i+d956NjBcCnn-2` zxWlyCHMnGkubt(hnosDjq@p3*={d85AVx{82S52Vz@Sk-%jho0b;;+=%NEuFq5v>j z{){#5$GTm*duJLt<>Z$X0>ZTX?50dMF3-Z3)_X;B)MDp;$E{)Kj>*y>|;MsI1XOv>E~k~si7Bho%3c`a5i_Jd&%ojRhOg2 zL&Kk;=rm|IG=Ea+;YQa!D%}lt+&sJYb5X_$XiCYwoLjisDz9DF4UTC5{^YA=-MTghVwJ0*cuz?bI`Wb zX~5Q+A$5yE_;cH>viLD+0(`@#{B}!d*r6Z`MAD4?+h{xo)RUb4=8oFoQ}$aZaay1j z^?F0jy8_U*^v)=)I0{|5;#{7rxg-RWfs0W=Jo#=L%|)-1N{YRl>o;s}R5caYl9 zsMl?)=etVDD_L!UC~D+liHZOKsAT_>LA7-zSAY)P%iOE%vmx%55ivU3!sRBOgs`ko=|Dl?;sjCJLhG151SbR>Sp( zz1n^|x5CfJ$mR)jQyXznUCTJ2->TnRWoNL(b}N`I`XJsv92bF!&H3%zIbKbSh~($$ z7ZTiW5j)NeMYX?AC{qece=&Tt3PwqKRgn0bFt zHUBYQrPyMdc_fXyxH*M`<;PQ7^XG6^K&Kz4PowrSdp4vw%11Di0||(sG~Xj5UlA3C zuXq4wid5NBf(LYO{whgGP?hlTm5+9AY+X%x9wU``#T*!p>;-l^<=B+9cOb@Mf5QX)PoOKt zZ&$AF*Y(s}z*fyREgurR&htzIzm1;y1<$5#y6;w}z>Ht9w7}9C3lYQiGf?`=!1%!j zqH(|EtB_kQkulBjM5Yh^54?6zoUHy14ic5Z;SK>W3zHW=Mz_H{=Wmn&jYrvI4pxNQ zWN6$zT-AMkTjN~W>?#W@T0#6M*lTgyDP6B%DRzA9n$Hzl)K*<(OYMkffkkvlR9Ra1 zLu%yu*t_RtCihcUe*85m4xRs!wU!ozjk6w><;_{7`1v-QMy0|r5~VP0?6QPj1ksZA z1JV~jR#kakF%c8;e0KEbg}uIG)e-t}8bp zS|9UIOZN_0oP=Eks5tc=P6i^LGez0s=<2I!c0YrD=po!)Qq@yE2mWYWLZey&g=2$+ zCB|OWrP-WW$~x@YO2)^?@1f`|&Hi3JzE5iX!l=9^c*y{OlNg)XTWiLG&{GP?E-}$i z2*A8|v)IMyIzYRoCPa4)w-nrFY>cAJ1JHt0PWma|OG?De1eq{Xwft$s#Rebi0FJ^@ zK5Yc$ENG8GPT&*?ak`~nIkF3_TsYu0=rpe0F6PphM!fCMrCda%#e(_BaL^o5z(Z7` z{N7S$ls@_|Z;|XPMAUe#8yV@dtr0iZ%%M(!fc~6UD?}C=_BX~TJav}l z0b$#@Kph8))+UbG43w{?-_pD{U@zQ$-eI>lz%!!OUR3n)tlB1e{~&?V({_}fN%V1k zp5Kk#FJPToQO19~pKpXmzVcR`^qMsUOW$)@LUu*sO2>CUsh36opC9Nt6?O=h9*#g_ zBA8op5-kx!56A77MxWT|-n@QdJHidB6J8Ms`ZxWwcj&C+aRd6D%FzJUK)V1*@qzWm z56xZ0&3%i*g(=rkHV3DIsDILEg;lr*hjPd4>H33$>HJ^vl&A9rg6uzP|Eke_Qyht%J=o_ekYYS!^Gg z8yjiwa=sB%I8$!Db-)@~F--cQ21qi7kQpAIHdN5jHgadA<37!u#%p4I_hrv$9%7^| zz5dBg<@-1;?gRWQGetB+l(bHFSpTq_+a}KZBdX&-Dv74BC&sZ`Xj`qUT&#Wtee{|- z@@Lzl>hju=7VKizeh-B7(g)L_Xpj{=hYChJ8gx;&+Xn+KE|(C*n%1qQl!MnU=C+II zSTbF2bHk)>Yl(z*e2w^~X1Z^YYrPT7o2&Ai-u(K(<{gy>`hc(oMm~mc1=qBTvUR#3|M~toen(&$c^>^Qx39Uh)I;3<=kltQbFKGv3>D=NdbPc z!?hxE=qW8@ow{?AiOI&XM@HC$FG4E}PPHHMh51`cp@q0_@lu+>xOq0eJ1D6fatAN= zKID95;M1|TPk&h50&ZN4JNaw@&9dqaIo9bu%QGz`RxACh(~|xNyO_8J@#|Du5!4Sd z4eaWZ7LBitsv41muJM3%rZ#`0KOX;D9dNY^dqzx%bODdgrLE;1cW)ws&HSGj#c)nv z10_;bs?RqRXN@{kp;`Qnj^6y;=(gdtQ|BCbx%4QmVJ+hgFgdABv=A1(i*KXPVVV>+_6MbK`~ zRrgdI7(r3$p{C(BH$SJ5UK+{q#k^8CDm49B;l&(Z93lycce3hhr)qHi+FH8B*QRDP z-u+}0e-)yZ)}^54VAQ(Sa$n3Ex@pV9h-KPl#>6k3Ss3lF;;>wN-Q3A;i(34r_H8DR z52-oQ%E|V0g$ptex12=6+0&j5sT&eq#D>erBeG=!ny}_lu=qcm9`#(m{%>Q)|9tfL zzpNi+m6XF~4bkL(G2jN-?=e8C!-ro!#NcP%QQh|XTGM>3y~87$XTf}?=X<94y1&J+ zQ0elcI?6u^^%drLlMvKQ@tSfKy!h|A*HP84x7l|sRGRayi>l9>7Wa!;h|LYf_^I$T zUv)C)P;sI34Y5zij;9V?1T5c{U%l=aY(2{<@EOkj!B{&L;1B{c`VPF_Q`nP_w(YKQ z*p4KCereYcZa7I$fH|nr0e`al1&b5dX-(`#)}GeG**a8&KkDDrXU{w-nXT@p`GGg- zfkSrgloso>Glh-Z`kgUk^!@pk!>o=#HDqnWSNEjx*FWXs96={l z-H*AVcW8|oG|J9uW^F`Mjis$g&)Ur6|7SWvhVe;(wiZ?%)>VD zTg6P)fm=mJGc@Yl8Z)-&q2SE!CI^%iq;pPib$dF~y1LWUAGz!XWu`?5yX*QIeKO`h z(WpKjiA@Du8IDUX;SEbGs=e(p$Ch>&4>>P5U*qk!G?HBrAMi8kK9CaIv&>kdzoqADXaW9IBILXG@75Mz+|^9+V{HLXQ$R9zwk{x3&*D+_W9Fw~%QeRW z>L2*BHyHzqTr!=cw|Y&F{l^F1*8)z4syggd`lg=RkePMS@0*NexKTavnk^QDAo1ACcGaTSCPRNQz}UTk#Hprj`G$f zDpvgH4`Dd}zULC*f~8TS)pw%B_W~5RB8<|2UnPfRb6WMs?9s=$f_x_*31>1D)9_0% z?=Q9VcOf(j zUdI`7K8tMP;GvgazCA8&Cpu(tGbNBAN^KLq>d&7l>E#f}!8-Tg;mNsl{;JU1@#Dvy z2^SHoUoWLcyr=Lrkxx|?PB|kJzDIEWi5r$;&fByotu%P1cs-jW+mrU!tDVl{sbgEg zJRgGa>f4cNm6&)#(kdT%!58(w&n7iq!%@Wg+z{Pwln2fy^;9oC+Az{Y_l;eh`F&zj z|Eq{svjJL@Q)c# z;8CZtxfyKeS|A}-2RP6x6iu|Ki8$K%C9x%>UYQ`)@3-ow&q?NICt$$JIsbZimwr)bPQBk z^vXT*V3wcaNLd1vQ?a62gCaLO9vj*qQc-Xy04Z9htmMilh}&-sn_U02(m`=$hwemn zqLBsSn|$O5FRG!3AQzfVSFNm=iXx8B8IcLbbtwS?{igZ>fCEE)g%8 z@_5o$>RP^fFKI@0|+RVa}dDstiftdZkps03v;=JlNr zbeR3Zh47^;4YTWMq5qI=R(2bBd1`ZwTvgfF!}FQ-!$#wvyw}HUd#_mYYLld7z3rD< z)b$%nEe(OxH!xLlR{dVt)}Z1^Tr0qGOWfPR?k+#fKq