From ed4b97215a80e45b57dbe269a750fa3f594d27a2 Mon Sep 17 00:00:00 2001 From: gaming <48131223+TheGamer1002@users.noreply.github.com> Date: Fri, 15 Mar 2024 13:35:04 -0400 Subject: [PATCH 01/13] fix(gradle): automatically download sources for IntelliJ --- build.gradle | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/build.gradle b/build.gradle index 57d1f3a..1d0adfa 100644 --- a/build.gradle +++ b/build.gradle @@ -2,6 +2,20 @@ plugins { id "java" id "edu.wpi.first.GradleRIO" version "2024.3.2" id "com.peterabeles.gversion" version "1.10.2" + + // One of the dumb things about IDEA is that it doesn't download sources and javadoc by default + // and you can't do it from the UI like you can with Maven. + // IDEA (and Eclipse, and Replit) all really seem geared towards Maven, and Gradle is a second-class citizen. + // I mean, it's not like you can't use Gradle with IDEA, but it's just not as smooth as Maven. + // But I've got bigger problems than some Maven-vs-Gradle thing. + id "idea" +} + +idea { + module { + downloadJavadoc = true + downloadSources = true + } } java { From a72f52a241768e6de29591dd7c8cb0172cc89a8a Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Fri, 15 Mar 2024 19:45:30 -0400 Subject: [PATCH 02/13] temp --- YAGSL | 2 +- .../deploy/maxswerve/modules/backleft.json | 12 ++++++------ .../deploy/maxswerve/modules/backright.json | 10 +++++----- .../deploy/maxswerve/modules/frontleft.json | 8 ++++---- .../deploy/maxswerve/modules/frontright.json | 8 ++++---- src/main/deploy/maxswerve/swervedrive.json | 2 +- src/main/java/frc/robot/Robot.java | 1 - .../frc/robot/subsystems/SwerveSubsystem.java | 2 +- .../subsystems/intake/IntakeIOSparkMax.java | 18 ++++++++++++++++++ src/main/java/frc/robot/util/Constants.java | 14 ++++++++------ 10 files changed, 48 insertions(+), 29 deletions(-) diff --git a/YAGSL b/YAGSL index 155d6cf..14b531e 160000 --- a/YAGSL +++ b/YAGSL @@ -1 +1 @@ -Subproject commit 155d6cf113cf94f16c5b3e6bed61f42fdea5cc8e +Subproject commit 14b531eb652c2cb53e7ff695b0c2414c3abd38d0 diff --git a/src/main/deploy/maxswerve/modules/backleft.json b/src/main/deploy/maxswerve/modules/backleft.json index 4a4b254..5af1d4a 100644 --- a/src/main/deploy/maxswerve/modules/backleft.json +++ b/src/main/deploy/maxswerve/modules/backleft.json @@ -1,23 +1,23 @@ { "drive": { - "type": "sparkmax", - "id": 4 + "type": "sparkflex", + "id": 6 }, "angle": { "type": "sparkmax", - "id": 3 + "id": 7 }, "encoder": { "type": "attached", "id": 0 }, "inverted": { - "drive": false, + "drive": true, "angle": true }, - "absoluteEncoderOffset": 107.842, + "absoluteEncoderOffset": 103.861, "location": { - "x": -13.75, + "x": -9.125, "y": 13.75 } } diff --git a/src/main/deploy/maxswerve/modules/backright.json b/src/main/deploy/maxswerve/modules/backright.json index bf28392..ea0cb27 100644 --- a/src/main/deploy/maxswerve/modules/backright.json +++ b/src/main/deploy/maxswerve/modules/backright.json @@ -1,7 +1,7 @@ { "drive": { - "type": "sparkmax", - "id": 6 + "type": "sparkflex", + "id": 4 }, "angle": { "type": "sparkmax", @@ -12,12 +12,12 @@ "id": 0 }, "inverted": { - "drive": false, + "drive": true, "angle": true }, - "absoluteEncoderOffset": 178.330, + "absoluteEncoderOffset": 2.772, "location": { - "x": -13.75, + "x": -9.125, "y": -13.75 } } diff --git a/src/main/deploy/maxswerve/modules/frontleft.json b/src/main/deploy/maxswerve/modules/frontleft.json index f8e7a4b..4c25c8e 100644 --- a/src/main/deploy/maxswerve/modules/frontleft.json +++ b/src/main/deploy/maxswerve/modules/frontleft.json @@ -1,7 +1,7 @@ { "drive": { - "type": "sparkmax", - "id": 2 + "type": "sparkflex", + "id": 8 }, "angle": { "type": "sparkmax", @@ -15,9 +15,9 @@ "drive": false, "angle": true }, - "absoluteEncoderOffset": 250.049, + "absoluteEncoderOffset": 180.211, "location": { - "x": -2.75, + "x": -9.125, "y": -13.75 } } diff --git a/src/main/deploy/maxswerve/modules/frontright.json b/src/main/deploy/maxswerve/modules/frontright.json index 0e9b295..c6c8911 100644 --- a/src/main/deploy/maxswerve/modules/frontright.json +++ b/src/main/deploy/maxswerve/modules/frontright.json @@ -1,6 +1,6 @@ { "drive": { - "type": "sparkmax", + "type": "sparkflex", "id": 2 }, "angle": { @@ -12,12 +12,12 @@ "id": 0 }, "inverted": { - "drive": false, + "drive": true, "angle": true }, - "absoluteEncoderOffset": 254.092, + "absoluteEncoderOffset": 180.810, "location": { - "x": 2.75, + "x": 9.125, "y": -13.75 } } diff --git a/src/main/deploy/maxswerve/swervedrive.json b/src/main/deploy/maxswerve/swervedrive.json index d2b6dbd..51e71a6 100644 --- a/src/main/deploy/maxswerve/swervedrive.json +++ b/src/main/deploy/maxswerve/swervedrive.json @@ -1,6 +1,6 @@ { "imu": { - "type": "navx_mxp", + "type": "navx", "id": 0, "canbus": null }, diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 62aab65..0878da1 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -31,7 +31,6 @@ public class Robot extends LoggedRobot { @Override public void robotInit() { DataLogManager.start(); - URCL.start(); // Record metadata Pathfinding.setPathfinder(new LocalADStarAK()); Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME); diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java index 11f4bda..16022a8 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java @@ -44,7 +44,7 @@ public class SwerveSubsystem extends SubsystemBase { private boolean lockRotation = false; - private static final SwerveSubsystem INSTANCE = new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "swerve")); + private static final SwerveSubsystem INSTANCE = new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "maxswerve")); public static SwerveSubsystem getInstance() { return INSTANCE; diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java index 9628371..33a473a 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java @@ -10,26 +10,40 @@ public class IntakeIOSparkMax implements IntakeIO { public static final double MAX_RPM = 5700.0; private final CANSparkMax intakeMotor = new CANSparkMax(Constants.MotorConstants.INTAKE_MOTOR, CANSparkLowLevel.MotorType.kBrushless); + private final CANSparkMax leftRollerMotor = new CANSparkMax(Constants.MotorConstants.LEFT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); + private final CANSparkMax rightRollerMotor = new CANSparkMax(Constants.MotorConstants.RIGHT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); private final CANSparkMax cerealizerMotor = new CANSparkMax(Constants.MotorConstants.CEREALIZER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); public IntakeIOSparkMax() { intakeMotor.setCANTimeout(250); + leftRollerMotor.setCANTimeout(250); + rightRollerMotor.setCANTimeout(250); cerealizerMotor.setCANTimeout(250); intakeMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); + leftRollerMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); + rightRollerMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); cerealizerMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); intakeMotor.setInverted(true); + leftRollerMotor.setInverted(false); + rightRollerMotor.setInverted(true); cerealizerMotor.setInverted(false); intakeMotor.getPIDController().setFeedbackDevice(intakeMotor.getEncoder()); + leftRollerMotor.getPIDController().setFeedbackDevice(leftRollerMotor.getEncoder()); + rightRollerMotor.getPIDController().setFeedbackDevice(rightRollerMotor.getEncoder()); cerealizerMotor.getPIDController().setFeedbackDevice(cerealizerMotor.getEncoder()); intakeMotor.setSmartCurrentLimit(20); + leftRollerMotor.setSmartCurrentLimit(20); + rightRollerMotor.setSmartCurrentLimit(20); cerealizerMotor.setSmartCurrentLimit(20); intakeMotor.getEncoder().setVelocityConversionFactor(1); // 15:1 gear ratio + leftRollerMotor.getEncoder().setVelocityConversionFactor(1); // 20:1 gear ratio + rightRollerMotor.getEncoder().setVelocityConversionFactor(1); // 20:1 gear ratio cerealizerMotor.getEncoder().setVelocityConversionFactor(1); // 20:1 gear ratio intakeMotor.getPIDController().setP(0.001); @@ -54,6 +68,8 @@ public IntakeIOSparkMax() { cerealizerMotor.getPIDController().setSmartMotionMinOutputVelocity(0, 0); intakeMotor.burnFlash(); + leftRollerMotor.burnFlash(); + rightRollerMotor.burnFlash(); cerealizerMotor.burnFlash(); } @@ -73,6 +89,8 @@ public void updateInputs(IntakeIOInputs inputs) { @Override public void set(double intakePercent, double cerealizerPercent) { intakeMotor.set(intakePercent); + leftRollerMotor.set(intakePercent); + rightRollerMotor.set(intakePercent); cerealizerMotor.set(cerealizerPercent); } diff --git a/src/main/java/frc/robot/util/Constants.java b/src/main/java/frc/robot/util/Constants.java index 3c489e9..0d2a6fc 100644 --- a/src/main/java/frc/robot/util/Constants.java +++ b/src/main/java/frc/robot/util/Constants.java @@ -103,15 +103,17 @@ public static class OperatorConstants { public static class MotorConstants { // Shooter Motor Constants - public static final int LOWER_SHOOTER_MOTOR = 13; - public static final int UPPER_SHOOTER_MOTOR = 12; + public static final int LOWER_SHOOTER_MOTOR = 23; + public static final int UPPER_SHOOTER_MOTOR = 24; public static final double SHOOTER_SPEED = 0.70; // Arm Motor Constants - public static final int LEFT_ARM_MOTOR = 14; // Currently the ids are arbitrary. - public static final int RIGHT_ARM_MOTOR = 15; // They will need to be adjusted to reflect the actual connected ports + public static final int LEFT_ARM_MOTOR = 21; // Currently the ids are arbitrary. + public static final int RIGHT_ARM_MOTOR = 20; // They will need to be adjusted to reflect the actual connected ports // Intake Constants - public static final int INTAKE_MOTOR = 10; - public static final int CEREALIZER_MOTOR = 11; + public static final int INTAKE_MOTOR = 12; + public static final int CEREALIZER_MOTOR = 22; public static final double INTAKE_SPEED = 0.45; + public static final int LEFT_ROLLER_MOTOR = 11; + public static final int RIGHT_ROLLER_MOTOR = 10; } } \ No newline at end of file From dde9507843247fa5296a8fdcab7f8d7e393ce287 Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Fri, 15 Mar 2024 19:45:30 -0400 Subject: [PATCH 03/13] temp --- .../deploy/maxswerve/modules/backleft.json | 9 +- .../deploy/maxswerve/modules/backright.json | 9 +- .../deploy/maxswerve/modules/frontleft.json | 7 +- .../deploy/maxswerve/modules/frontright.json | 9 +- src/main/deploy/maxswerve/swervedrive.json | 2 +- src/main/java/frc/robot/FieldConstants.java | 1 + src/main/java/frc/robot/Robot.java | 3 +- src/main/java/frc/robot/RobotContainer.java | 30 +++++-- .../frc/robot/commands/MoveArmCommand.java | 69 +++++++++++++++ .../frc/robot/subsystems/ArmSubsystem.java | 84 ++++++++++++------- .../frc/robot/subsystems/SwerveSubsystem.java | 16 ++-- .../frc/robot/subsystems/intake/Intake.java | 29 +++++++ .../frc/robot/subsystems/intake/IntakeIO.java | 17 ++++ .../subsystems/intake/IntakeIOSparkMax.java | 34 ++++++++ .../frc/robot/subsystems/shooter/Shooter.java | 19 +++++ .../robot/subsystems/shooter/ShooterIO.java | 2 + .../shooter/ShooterIOSparkFlex.java | 66 +++++++++++++++ 17 files changed, 343 insertions(+), 63 deletions(-) create mode 100644 src/main/java/frc/robot/commands/MoveArmCommand.java diff --git a/src/main/deploy/maxswerve/modules/backleft.json b/src/main/deploy/maxswerve/modules/backleft.json index 5af1d4a..e9b54ae 100644 --- a/src/main/deploy/maxswerve/modules/backleft.json +++ b/src/main/deploy/maxswerve/modules/backleft.json @@ -12,12 +12,11 @@ "id": 0 }, "inverted": { - "drive": true, - "angle": true + "drive": false, + "angle": false }, - "absoluteEncoderOffset": 103.861, "location": { - "x": -9.125, - "y": 13.75 + "x": -13, + "y": 13.25 } } diff --git a/src/main/deploy/maxswerve/modules/backright.json b/src/main/deploy/maxswerve/modules/backright.json index ea0cb27..e6ea121 100644 --- a/src/main/deploy/maxswerve/modules/backright.json +++ b/src/main/deploy/maxswerve/modules/backright.json @@ -12,12 +12,11 @@ "id": 0 }, "inverted": { - "drive": true, - "angle": true + "drive": false, + "angle": false }, - "absoluteEncoderOffset": 2.772, "location": { - "x": -9.125, - "y": -13.75 + "x": -13, + "y": -13.25 } } diff --git a/src/main/deploy/maxswerve/modules/frontleft.json b/src/main/deploy/maxswerve/modules/frontleft.json index 4c25c8e..1dd9608 100644 --- a/src/main/deploy/maxswerve/modules/frontleft.json +++ b/src/main/deploy/maxswerve/modules/frontleft.json @@ -13,11 +13,10 @@ }, "inverted": { "drive": false, - "angle": true + "angle": false }, - "absoluteEncoderOffset": 180.211, "location": { - "x": -9.125, - "y": -13.75 + "x": 5.5, + "y": 13.25 } } diff --git a/src/main/deploy/maxswerve/modules/frontright.json b/src/main/deploy/maxswerve/modules/frontright.json index c6c8911..23390cd 100644 --- a/src/main/deploy/maxswerve/modules/frontright.json +++ b/src/main/deploy/maxswerve/modules/frontright.json @@ -12,12 +12,11 @@ "id": 0 }, "inverted": { - "drive": true, - "angle": true + "drive": false, + "angle": false }, - "absoluteEncoderOffset": 180.810, "location": { - "x": 9.125, - "y": -13.75 + "x": 5.5, + "y": -13.25 } } diff --git a/src/main/deploy/maxswerve/swervedrive.json b/src/main/deploy/maxswerve/swervedrive.json index 51e71a6..dce981d 100644 --- a/src/main/deploy/maxswerve/swervedrive.json +++ b/src/main/deploy/maxswerve/swervedrive.json @@ -1,6 +1,6 @@ { "imu": { - "type": "navx", + "type": "navx_spi", "id": 0, "canbus": null }, diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 3904d3d..6f93ba0 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -86,6 +86,7 @@ public static final class Speaker { /** Center of the speaker opening (blue alliance) */ public static final Translation3d CENTER_SPEAKER_OPENING = BOTTOM_LEFT_SPEAKER.interpolate(TOP_RIGHT_SPEAKER, 0.5); + } public static final Measure APRIL_TAG_WIDTH = Inches.of(6.50); diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 0878da1..743c6c8 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -30,9 +30,10 @@ public class Robot extends LoggedRobot { @Override public void robotInit() { + Pathfinding.setPathfinder(new LocalADStarAK()); DataLogManager.start(); // Record metadata - Pathfinding.setPathfinder(new LocalADStarAK()); + Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME); Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE); Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA); diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 76f633f..e2df7d3 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -20,12 +20,11 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.JoystickButton; import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc.robot.commands.AimAndPickUpNoteCommand; -import frc.robot.commands.IntakeCommand; -import frc.robot.commands.RotateCommand; -import frc.robot.commands.ShootCommand; +import frc.robot.commands.*; +import frc.robot.commands.drivebase.AbsoluteFieldDrive; import frc.robot.commands.drivebase.AimAtLimelightCommand; import frc.robot.commands.drivebase.AimAtTargetCommand; +import frc.robot.subsystems.ArmSubsystem; import frc.robot.subsystems.VisionSubsystem; import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.intake.IntakeIOSparkMax; @@ -47,7 +46,10 @@ public class RobotContainer { private final SwerveSubsystem drivebase; private final Intake intake; private final Shooter shooter; - private final Command intakeCommand, shootCommand, aimAtLimelightCommand, rotateCommand, driveToPoseCommand, aimAndPickUpNoteCommand; + private final ArmSubsystem armSubsystem; + private final Command intakeCommand, shootCommand, aimAtLimelightCommand, rotateCommand, driveToPoseCommand, aimAndPickUpNoteCommand, armSysIdCommand, moveArmCommand; + + private final Command absoluteFieldDrive; XboxController driverXbox = new XboxController(0); XboxController shooterXbox = new XboxController(1); @@ -59,20 +61,25 @@ public RobotContainer() { drivebase = SwerveSubsystem.getInstance(); intake = new Intake(new IntakeIOSparkMax()); shooter = new Shooter(new ShooterIOSparkFlex()); + armSubsystem = ArmSubsystem.getInstance(); intakeCommand = new IntakeCommand(intake, () -> MathUtil.applyDeadband(shooterXbox.getLeftTriggerAxis(), 0.1)); shootCommand = new ShootCommand(shooter, () -> MathUtil.applyDeadband(shooterXbox.getRightTriggerAxis(), 0.1) * 3250); aimAtLimelightCommand = new AimAtLimelightCommand(drivebase, VisionSubsystem.getInstance()); rotateCommand = new RotateCommand(drivebase); driveToPoseCommand = new ShootCommand(shooter, () -> 4000).alongWith(drivebase.driveToPose(new Pose2d(new Translation2d(2.720, 2.579), Rotation2d.fromDegrees(180))).andThen(drivebase.driveToPose(new Pose2d(new Translation2d(2.720, 2.579), Rotation2d.fromDegrees(180)))).andThen(new AimAtLimelightCommand(drivebase, VisionSubsystem.getInstance())).andThen(new IntakeCommand(intake, () -> 1))); aimAndPickUpNoteCommand = new AimAndPickUpNoteCommand(drivebase, VisionSubsystem.getInstance(), intake); + armSysIdCommand = ArmSubsystem.generateSysIdCommand(armSubsystem.getSysId(), 2, 3.5, 1.5); + moveArmCommand = new MoveArmCommand(() -> MathUtil.applyDeadband(shooterXbox.getRightY(), 0.1)); int invert = getInvert(); + absoluteFieldDrive = new AbsoluteFieldDrive(drivebase, () -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND) * invert, () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND) * invert, () -> driverXbox.getRightX() * invert); // Applies deadbands and inverts controls because joysticks // are back-right positive while robot // controls are front-left positive // left stick controls translation // right stick controls the desired angle NOT angular rotation Command driveFieldOrientedDirectAngle = drivebase.driveCommand(() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND) * invert, () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND) * invert, () -> driverXbox.getRightX() * invert, () -> driverXbox.getRightY() * invert); + AbsoluteDriveAdv closedAbsoluteDriveAdv = new AbsoluteDriveAdv(drivebase, () -> MathUtil.applyDeadband(driverXbox.getLeftY() * invert, OperatorConstants.LEFT_Y_DEADBAND), () -> MathUtil.applyDeadband(driverXbox.getLeftX() * invert, OperatorConstants.LEFT_X_DEADBAND), () -> MathUtil.applyDeadband(driverXbox.getRightX() * invert, OperatorConstants.RIGHT_X_DEADBAND), driverXbox::getYButtonPressed, driverXbox::getAButtonPressed, driverXbox::getXButtonPressed, driverXbox::getBButtonPressed); // Applies deadbands and inverts controls because joysticks // are back-right positive while robot @@ -86,6 +93,12 @@ public RobotContainer() { Command sysIdForDrive = drivebase.sysIdDriveMotorCommand(); Command sysIdForAngle = drivebase.sysIdAngleMotorCommand(); + Command driveFieldOrientedDirectAngleForTesting = drivebase.driveCommand( + () -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND), + () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND), + () -> driverXbox.getRightX(), + () -> driverXbox.getRightY()); + drivebase.setDefaultCommand(!RobotBase.isSimulation() ? driveFieldOrientedAnglularVelocity : driveFieldOrientedDirectAngleSim); // Configure the trigger bindings @@ -102,8 +115,7 @@ private int getInvert() { } - AbsoluteDriveAdv closedAbsoluteDriveAdv = new AbsoluteDriveAdv(drivebase, () -> MathUtil.applyDeadband(driverXbox.getLeftY() * invert, OperatorConstants.LEFT_Y_DEADBAND), () -> MathUtil.applyDeadband(driverXbox.getLeftX() * invert, OperatorConstants.LEFT_X_DEADBAND), () -> MathUtil.applyDeadband(driverXbox.getRightX() * invert, OperatorConstants.RIGHT_X_DEADBAND), driverXbox::getYButtonPressed, driverXbox::getAButtonPressed, driverXbox::getXButtonPressed, driverXbox::getBButtonPressed); - return invert; + return invert; } /** @@ -126,7 +138,11 @@ private void configureBindings() { new JoystickButton(driverXbox, XboxController.Button.kLeftBumper.value).whileTrue(intakeCommand); new JoystickButton(driverXbox, XboxController.Button.kY.value).whileTrue(aimAndPickUpNoteCommand); + new JoystickButton(shooterXbox,XboxController.Button.kA.value).whileTrue(armSysIdCommand); + new JoystickButton(shooterXbox, XboxController.Button.kB.value).whileTrue(shooter.generateSysIdCommand(shooter.getSysIdRoutine(), 2, 10, 10)); + shooter.setDefaultCommand(shootCommand); + armSubsystem.setDefaultCommand(moveArmCommand); } /** diff --git a/src/main/java/frc/robot/commands/MoveArmCommand.java b/src/main/java/frc/robot/commands/MoveArmCommand.java new file mode 100644 index 0000000..3b4fc02 --- /dev/null +++ b/src/main/java/frc/robot/commands/MoveArmCommand.java @@ -0,0 +1,69 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.subsystems.ArmSubsystem; + +import java.util.function.DoubleSupplier; + + +public class MoveArmCommand extends Command { + private final ArmSubsystem armSubsystem = ArmSubsystem.getInstance(); + DoubleSupplier speed; + + public MoveArmCommand(DoubleSupplier speed) { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + this.speed = speed; + addRequirements(this.armSubsystem); + } + + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + @Override + public void initialize() { + + } + + /** + * The main body of a command. Called repeatedly while the command is scheduled. + * (That is, it is called repeatedly until {@link #isFinished()}) returns true.) + */ + @Override + public void execute() { + armSubsystem.moveArmButBetter(speed.getAsDouble() * 0.25); + } + + /** + *

+ * Returns whether this command has finished. Once a command finishes -- indicated by + * this method returning true -- the scheduler will call its {@link #end(boolean)} method. + *

+ * Returning false will result in the command never ending automatically. It may still be + * cancelled manually or interrupted by another command. Hard coding this command to always + * return true will result in the command executing once and finishing immediately. It is + * recommended to use * {@link edu.wpi.first.wpilibj2.command.InstantCommand InstantCommand} + * for such an operation. + *

+ * + * @return whether this command has finished. + */ + @Override + public boolean isFinished() { + // TODO: Make this return true when this Command no longer needs to run execute() + return false; + } + + /** + * The action to take when the command ends. Called when either the command + * finishes normally -- that is it is called when {@link #isFinished()} returns + * true -- or when it is interrupted/canceled. This is where you may want to + * wrap up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + @Override + public void end(boolean interrupted) { + armSubsystem.moveArm(0); + } +} diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.java b/src/main/java/frc/robot/subsystems/ArmSubsystem.java index 02df06e..bcf3601 100644 --- a/src/main/java/frc/robot/subsystems/ArmSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.java @@ -1,13 +1,11 @@ package frc.robot.subsystems; -import com.revrobotics.AbsoluteEncoder; -import com.revrobotics.CANSparkMax; -import com.revrobotics.SparkAbsoluteEncoder; -import com.revrobotics.SparkPIDController; +import com.revrobotics.*; import com.revrobotics.CANSparkBase.IdleMode; import com.revrobotics.CANSparkLowLevel.MotorType; import com.revrobotics.SparkAbsoluteEncoder.Type; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -25,16 +23,17 @@ public class ArmSubsystem extends SubsystemBase { private final CANSparkMax leftMotor; // Lead motor private final CANSparkMax rightMotor; // Follow Motor + private final SparkLimitSwitch forwardLimitSwitch, reverseLimitSwitch; private final SparkPIDController pidController; private final SparkAbsoluteEncoder encoder; - private final double kP; - private final double kI; - private final double kD; - private final double kIz; - private final double kFF; - private final double kMaxOutput; - private final double kMinOutput; // We'll probably want to put these in the constants class later + private static final double kP = 0.1; + private static final double kI = 1e-4; + private static final double kD = 1; + private static final double kIz = 0; + private static final double kFF = 0; + private static final double kMaxOutput = 1; + private static final double kMinOutput = -1; // We'll probably want to put these in the constants class later private double maxRange; // amount of revolutions (or other unit) it takes to move the arm from min to max @@ -59,6 +58,10 @@ public void raiseArm() { leftMotor.set(0.5); } + public void moveArmButBetter(double speed) { + leftMotor.set(speed); + } + // Lowers the arm () public void lowerArm() { leftMotor.set(-0.5); @@ -109,35 +112,42 @@ private ArmSubsystem() { leftMotor = new CANSparkMax(Constants.MotorConstants.LEFT_ARM_MOTOR, MotorType.kBrushless); rightMotor = new CANSparkMax(Constants.MotorConstants.RIGHT_ARM_MOTOR, MotorType.kBrushless); + encoder = rightMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle); + encoder.setPositionConversionFactor(360); // 1 rotation = 360 degrees + // I don't want to have to deal with radians because of rounding errors + // The right motor will mirror the leader, but it will be inverted rightMotor.follow(leftMotor, true); leftMotor.setIdleMode(IdleMode.kBrake); - leftMotor.setSmartCurrentLimit(20); + leftMotor.setSmartCurrentLimit(40); leftMotor.burnFlash(); rightMotor.setIdleMode(IdleMode.kBrake); - rightMotor.setSmartCurrentLimit(20); + rightMotor.setSmartCurrentLimit(40); rightMotor.burnFlash(); - pidController = leftMotor.getPIDController(); - encoder = leftMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle); + pidController = rightMotor.getPIDController(); + + + forwardLimitSwitch = rightMotor.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); + reverseLimitSwitch = rightMotor.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); + + forwardLimitSwitch.enableLimitSwitch(true); + reverseLimitSwitch.enableLimitSwitch(true); - kP = 0.1; - kI = 1e-4; - kD = 1; - kIz = 0; - kFF = 0; - kMaxOutput = 1; - kMinOutput = -1; + encoder.setPositionConversionFactor(360); // 1 rotation = 360 degrees + // I don't want to have to deal with radians because of rounding errors - pidController.setP(kP); - pidController.setI(kI); - pidController.setD(kD); - pidController.setIZone(kIz); - pidController.setFF(kFF); - pidController.setOutputRange(kMinOutput, kMaxOutput); + + // +// pidController.setP(kP); +// pidController.setI(kI); +// pidController.setD(kD); +// pidController.setIZone(kIz); +// pidController.setFF(kFF); +// pidController.setOutputRange(kMinOutput, kMaxOutput); } SysIdRoutine armSysId = new SysIdRoutine( @@ -163,4 +173,22 @@ public static Command generateSysIdCommand(SysIdRoutine sysIdRoutine, double del .andThen(Commands.waitSeconds(delay)) .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)); } + + + @Override + public void periodic() { + // This method will be called once per scheduler run + + // 0 degrees is set to (r, 270) in polar coordinates, because that way it will never wrap around + // If the forward limit switch is pressed, we're at 243 degrees + if(forwardLimitSwitch.isPressed()) { + encoder.setZeroOffset(242.88780212402344); + } + // If the reverse limit switch is pressed, we're at 40 degrees + if(reverseLimitSwitch.isPressed()) { + encoder.setZeroOffset(39.87791442871094); + } + + SmartDashboard.putNumber("Arm Position", encoder.getPosition()); + } } diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java index 16022a8..30822de 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java @@ -4,6 +4,7 @@ package frc.robot.subsystems; +import com.kauailabs.navx.frc.AHRS; import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.commands.PathPlannerAuto; import com.pathplanner.lib.controllers.PPHolonomicDriveController; @@ -22,6 +23,7 @@ import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config; @@ -77,6 +79,8 @@ public SwerveSubsystem(File directory) { swerveDrive.setHeadingCorrection(false); // Heading correction should only be used while controlling the robot via angle. swerveDrive.setCosineCompensator(!SwerveDriveTelemetry.isSimulation); // Disables cosine compensation for simulations since it causes discrepancies not seen in real life. setupPathPlanner(); + + AHRS navx = (AHRS) swerveDrive.swerveDriveConfiguration.imu.getIMU(); } /** @@ -315,7 +319,10 @@ public void periodic() { if (LimelightHelpers.getTV("limelight-back")) swerveDrive.addVisionMeasurement(LimelightHelpers.getBotPose2d_wpiRed("limelight-back"), Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture("limelight-back")) / 1000.0); - PathPlannerLogging.logCurrentPose(getPose()); + // PathPlannerLogging.logCurrentPose(getPose()); + swerveDrive.updateOdometry(); + + getPose(); } @Override @@ -487,12 +494,7 @@ public Rotation2d getPitch() { return swerveDrive.getPitch(); } - /** - * Add a fake vision reading for testing purposes. - */ - public void addFakeVisionReading() { - swerveDrive.addVisionMeasurement(new Pose2d(3, 3, Rotation2d.fromDegrees(65)), Timer.getFPGATimestamp()); - } + /** diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.java b/src/main/java/frc/robot/subsystems/intake/Intake.java index eb43232..43093ff 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/intake/Intake.java @@ -9,6 +9,8 @@ import frc.robot.util.Constants; import org.littletonrobotics.junction.Logger; +import java.util.function.DoubleSupplier; + import static edu.wpi.first.units.Units.Volts; // Not doing the sim because I would like to retain what little sanity I have left @@ -28,6 +30,8 @@ public Intake(IntakeIO io) { public void periodic() { io.updateInputs(inputs); Logger.processInputs("Intake", inputs); + + } /** Returns a command that intakes a note. */ @@ -120,4 +124,29 @@ public SysIdRoutine getIntakeSysId() { public SysIdRoutine getCerealizerSysId() { return cerealizerSysId; } + + + + public DoubleSupplier getColorSensorProximity() { + return io.getColorSensorProximity(); + } + + public DoubleSupplier getColorSensorRed() { + return io.getColorSensorRed(); + } + + public DoubleSupplier getColorSensorGreen() { + return io.getColorSensorGreen(); + } + + public DoubleSupplier getColorSensorBlue() { + return io.getColorSensorBlue(); + } + + public DoubleSupplier getColorSensorIR() { + return io.getColorSensorIR(); + } + + + } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIO.java b/src/main/java/frc/robot/subsystems/intake/IntakeIO.java index 38bdd7c..cfc3209 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIO.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIO.java @@ -1,7 +1,11 @@ package frc.robot.subsystems.intake; +import edu.wpi.first.wpilibj.util.Color; import org.littletonrobotics.junction.AutoLog; +import java.util.function.DoubleSupplier; +import java.util.function.Supplier; + public interface IntakeIO { // Cerealizer (n.) - 1. A device that dispenses cereal. 2. A typo the robot lead made that stuck. // fr tho this is hilarious @@ -15,6 +19,7 @@ public static class IntakeIOInputs { public double cerealizerPositionDegrees = 0.0; public double cerealizerVelocityRpm = 0.0; public double cerealizerAppliedVolts = 0.0; + public double[] cerealizerCurrentAmps = new double[] {}; } @@ -37,4 +42,16 @@ public default void setIntake(double a) {} public default void setIntakeVoltage(double volts) {} public default void setCerealizerVoltage(double volts) {} + + public DoubleSupplier getColorSensorProximity(); + + public DoubleSupplier getColorSensorRed(); + + public DoubleSupplier getColorSensorGreen(); + + public DoubleSupplier getColorSensorBlue(); + + public DoubleSupplier getColorSensorIR(); + + public Supplier getColorSensorColor(); } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java index 33a473a..136fdd5 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java @@ -3,9 +3,15 @@ import com.revrobotics.CANSparkBase; import com.revrobotics.CANSparkLowLevel; import com.revrobotics.CANSparkMax; +import com.revrobotics.ColorSensorV3; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.util.Color; import frc.robot.util.Constants; +import java.util.function.DoubleSupplier; +import java.util.function.Supplier; + // apparently staying up late coding leads to deranged comments so that's cool public class IntakeIOSparkMax implements IntakeIO { public static final double MAX_RPM = 5700.0; @@ -14,6 +20,8 @@ public class IntakeIOSparkMax implements IntakeIO { private final CANSparkMax rightRollerMotor = new CANSparkMax(Constants.MotorConstants.RIGHT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); private final CANSparkMax cerealizerMotor = new CANSparkMax(Constants.MotorConstants.CEREALIZER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); + private final ColorSensorV3 colorSensor = new ColorSensorV3(I2C.Port.kMXP); + public IntakeIOSparkMax() { intakeMotor.setCANTimeout(250); @@ -71,6 +79,7 @@ public IntakeIOSparkMax() { leftRollerMotor.burnFlash(); rightRollerMotor.burnFlash(); cerealizerMotor.burnFlash(); + } @Override @@ -134,4 +143,29 @@ public void setIntakeVoltage(double volts) { public void setCerealizerVoltage(double volts) { cerealizerMotor.setVoltage(volts); } + + + public DoubleSupplier getColorSensorProximity() { + return colorSensor::getProximity; + } + + public DoubleSupplier getColorSensorRed() { + return colorSensor::getRed; + } + + public DoubleSupplier getColorSensorGreen() { + return colorSensor::getGreen; + } + + public DoubleSupplier getColorSensorBlue() { + return colorSensor::getBlue; + } + + public DoubleSupplier getColorSensorIR() { + return colorSensor::getIR; + } + + public Supplier getColorSensorColor() { + return colorSensor::getColor; + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index 29ac013..51f8196 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -1,8 +1,11 @@ package frc.robot.subsystems.shooter; +import edu.wpi.first.units.Units; +import edu.wpi.first.units.Voltage; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.util.Constants; import org.littletonrobotics.junction.Logger; @@ -35,4 +38,20 @@ public void setVelocity(double lowerRpm, double upperRpm) { io.setVelocity(lowerRpm, upperRpm); } + + public SysIdRoutine getSysIdRoutine() { + return new SysIdRoutine(new SysIdRoutine.Config(), new SysIdRoutine.Mechanism((v) -> io.setVoltage(v.in(Units.Volt)), null, this)); + } + + public Command generateSysIdCommand(SysIdRoutine sysIdRoutine, double delay, double quasiTimeout, + double dynamicTimeout) + { + return sysIdRoutine.quasistatic(SysIdRoutine.Direction.kForward).withTimeout(quasiTimeout) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.quasistatic(SysIdRoutine.Direction.kReverse).withTimeout(quasiTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kForward).withTimeout(dynamicTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)); + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java index ce3da8b..e0fab4d 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java @@ -32,5 +32,7 @@ public default void set(double lowerPercent, double upperPercent) {} public default void setVelocity( double lowerRpm, double upperRpm) {} + public default void setVoltage(double volts) {} + } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.java index 1a44a92..3393ecc 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.java @@ -1,9 +1,35 @@ package frc.robot.subsystems.shooter; import com.revrobotics.*; +import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import edu.wpi.first.math.geometry.Translation3d; +import edu.wpi.first.math.util.Units; import frc.robot.util.Constants; +import frc.robot.FieldConstants; public class ShooterIOSparkFlex implements ShooterIO { + // Calculated constants from Recalc (https://www.reca.lc/flywheel?currentLimit=%7B%22s%22%3A40%2C%22u%22%3A%22A%22%7D&efficiency=100&flywheelMomentOfInertia=%7B%22s%22%3A555625%2C%22u%22%3A%22mm2%2Ag%22%7D&flywheelRadius=%7B%22s%22%3A50%2C%22u%22%3A%22mm%22%7D&flywheelRatio=%7B%22magnitude%22%3A1%2C%22ratioType%22%3A%22Reduction%22%7D&flywheelWeight=%7B%22s%22%3A444.5%2C%22u%22%3A%22g%22%7D&motor=%7B%22quantity%22%3A1%2C%22name%22%3A%22NEO%20Vortex%2A%22%7D&motorRatio=%7B%22magnitude%22%3A1%2C%22ratioType%22%3A%22Step-up%22%7D&projectileRadius=%7B%22s%22%3A2%2C%22u%22%3A%22in%22%7D&projectileWeight=%7B%22s%22%3A8.3%2C%22u%22%3A%22oz%22%7D&shooterMomentOfInertia=%7B%22s%22%3A1.614%2C%22u%22%3A%22in2%2Albs%22%7D&shooterRadius=%7B%22s%22%3A2%2C%22u%22%3A%22in%22%7D&shooterTargetSpeed=%7B%22s%22%3A6783%2C%22u%22%3A%22rpm%22%7D&shooterWeight=%7B%22s%22%3A0.807%2C%22u%22%3A%22lbs%22%7D&useCustomFlywheelMoi=0&useCustomShooterMoi=0): + // using: + // current limit: 40 A + // efficiency: 100% + // ratio: 1:1 + // target shooter rpm: 6783 (out of the max 6784) + // projectile weight: 8.3 oz (from https://www.andymark.com/products/frc-2024-am-4999) + // shooter radius: 2 in + // shooter weight: 17.216 oz (4x 4.304 oz. 4 in. diameter wheels; durometer doesn't matter here https://www.andymark.com/products/4-in-compliant-wheels-options) + // flywheel: { + // hex shaft: 6.043 oz (17.5 in; 0.345... oz/in) + // neo vortex: 444.5 g + // total: 615.8161682 g + // diameter: 50 mm + // ratio: 1:1 + // } + // + // this gives an estimated projectile speed of 45.40 ft/s + + // distance from shooter axle to center of shooting area: 12 1/8 in + // distance from shooter axle to ground: 22 1/4 in + private final CANSparkFlex lowerMotor = new CANSparkFlex(Constants.MotorConstants.LOWER_SHOOTER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); private final CANSparkFlex upperMotor = new CANSparkFlex(Constants.MotorConstants.UPPER_SHOOTER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); private final RelativeEncoder lowerEncoder = lowerMotor.getEncoder(); @@ -16,7 +42,22 @@ public class ShooterIOSparkFlex implements ShooterIO { public ShooterIOSparkFlex() { + lowerEncoder.setPositionConversionFactor(1); + lowerEncoder.setVelocityConversionFactor(1); + upperEncoder.setPositionConversionFactor(1); + upperEncoder.setVelocityConversionFactor(1); + + + var i = new SimpleMotorFeedforward(0.028196, 0.0017838, 0.00020814); + // use that to set the feed forward for the lower motor + lowerPID.setFF(i.calculate(0)); + + lowerPID.setP(1.0167e-7); + lowerPID.setI(0); + lowerPID.setD(0); + + upperMotor.follow(lowerMotor, true); } @Override @@ -52,6 +93,31 @@ public void setVelocity(double lowerRpm, double upperRpm) { upperPID.setReference(upperRpm, CANSparkBase.ControlType.kSmartVelocity, 0); } + @Override + public void setVoltage(double volts) { + lowerMotor.setVoltage(volts); + upperMotor.setVoltage(volts); + } + // now for the calculation of the angle and velocity we'll need to shoot to make it into the speaker +// public static double calculateAngle(Translation3d position) { +// // we will use feet for this calculation +// double x = Units.metersToFeet(position.getX()); +// double y = Units.metersToFeet(position.getY()); +// +// // from that, there is the problem of +// +// } +// +// public Translation3d calculateShooterDistanceFromGround(double angle) { +// // this can be calculated using pretty basic trigonometry +// double hypotenuse = 12.125; // inches +// double opposite = Math.sin(angle) * hypotenuse; +// double adjacent = Math.cos(angle) * hypotenuse; +// +// // the center of the robot is 5.5 inches from the axle +// double x = 5.5 - opposite; +// double y = 22.25 - adjacent; +// } } From ab135d39dd80192ab250bd306491c8e2452a030d Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Fri, 15 Mar 2024 19:45:30 -0400 Subject: [PATCH 04/13] temp --- YAGSL | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/YAGSL b/YAGSL index 14b531e..1e6352d 160000 --- a/YAGSL +++ b/YAGSL @@ -1 +1 @@ -Subproject commit 14b531eb652c2cb53e7ff695b0c2414c3abd38d0 +Subproject commit 1e6352d216df661a2a84ff985facefd9ca3ada1b From 8d8fb6a502fbb35250c5d531a06704a65cae48c9 Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Mon, 18 Mar 2024 00:26:49 -0400 Subject: [PATCH 05/13] Rename .java to .kt --- .../java/frc/robot/{FieldConstants.java => FieldConstants.kt} | 0 src/main/java/frc/robot/{LocalADStarAK.java => LocalADStarAK.kt} | 0 src/main/java/frc/robot/{Main.java => Main.kt} | 0 src/main/java/frc/robot/{Robot.java => Robot.kt} | 0 .../java/frc/robot/{RobotContainer.java => RobotContainer.kt} | 0 .../{AimAndPickUpNoteCommand.java => AimAndPickUpNoteCommand.kt} | 0 .../frc/robot/commands/{ClimbCommand.java => ClimbCommand.kt} | 0 .../frc/robot/commands/{IntakeCommand.java => IntakeCommand.kt} | 0 .../frc/robot/commands/{MoveArmCommand.java => MoveArmCommand.kt} | 0 .../frc/robot/commands/{RotateCommand.java => RotateCommand.kt} | 0 .../frc/robot/commands/{ShootCommand.java => ShootCommand.kt} | 0 .../auto/{AutoBalanceCommand.java => AutoBalanceCommand.kt} | 0 .../commands/drivebase/{AbsoluteDrive.java => AbsoluteDrive.kt} | 0 .../drivebase/{AbsoluteDriveAdv.java => AbsoluteDriveAdv.kt} | 0 .../drivebase/{AbsoluteFieldDrive.java => AbsoluteFieldDrive.kt} | 0 .../{AimAtLimelightCommand.java => AimAtLimelightCommand.kt} | 0 .../drivebase/{AimAtTargetCommand.java => AimAtTargetCommand.kt} | 0 .../frc/robot/subsystems/{ArmSubsystem.java => ArmSubsystem.kt} | 0 .../subsystems/{ClimberSubsystem.java => ClimberSubsystem.kt} | 0 .../robot/subsystems/{SwerveSubsystem.java => SwerveSubsystem.kt} | 0 .../subsystems/{TelemetrySubsystem.java => TelemetrySubsystem.kt} | 0 .../robot/subsystems/{VisionSubsystem.java => VisionSubsystem.kt} | 0 .../java/frc/robot/subsystems/intake/{Intake.java => Intake.kt} | 0 .../frc/robot/subsystems/intake/{IntakeIO.java => IntakeIO.kt} | 0 .../intake/{IntakeIOSparkMax.java => IntakeIOSparkMax.kt} | 0 .../frc/robot/subsystems/shooter/{Shooter.java => Shooter.kt} | 0 .../frc/robot/subsystems/shooter/{ShooterIO.java => ShooterIO.kt} | 0 .../subsystems/shooter/{ShooterIOSim.java => ShooterIOSim.kt} | 0 .../shooter/{ShooterIOSparkFlex.java => ShooterIOSparkFlex.kt} | 0 29 files changed, 0 insertions(+), 0 deletions(-) rename src/main/java/frc/robot/{FieldConstants.java => FieldConstants.kt} (100%) rename src/main/java/frc/robot/{LocalADStarAK.java => LocalADStarAK.kt} (100%) rename src/main/java/frc/robot/{Main.java => Main.kt} (100%) rename src/main/java/frc/robot/{Robot.java => Robot.kt} (100%) rename src/main/java/frc/robot/{RobotContainer.java => RobotContainer.kt} (100%) rename src/main/java/frc/robot/commands/{AimAndPickUpNoteCommand.java => AimAndPickUpNoteCommand.kt} (100%) rename src/main/java/frc/robot/commands/{ClimbCommand.java => ClimbCommand.kt} (100%) rename src/main/java/frc/robot/commands/{IntakeCommand.java => IntakeCommand.kt} (100%) rename src/main/java/frc/robot/commands/{MoveArmCommand.java => MoveArmCommand.kt} (100%) rename src/main/java/frc/robot/commands/{RotateCommand.java => RotateCommand.kt} (100%) rename src/main/java/frc/robot/commands/{ShootCommand.java => ShootCommand.kt} (100%) rename src/main/java/frc/robot/commands/auto/{AutoBalanceCommand.java => AutoBalanceCommand.kt} (100%) rename src/main/java/frc/robot/commands/drivebase/{AbsoluteDrive.java => AbsoluteDrive.kt} (100%) rename src/main/java/frc/robot/commands/drivebase/{AbsoluteDriveAdv.java => AbsoluteDriveAdv.kt} (100%) rename src/main/java/frc/robot/commands/drivebase/{AbsoluteFieldDrive.java => AbsoluteFieldDrive.kt} (100%) rename src/main/java/frc/robot/commands/drivebase/{AimAtLimelightCommand.java => AimAtLimelightCommand.kt} (100%) rename src/main/java/frc/robot/commands/drivebase/{AimAtTargetCommand.java => AimAtTargetCommand.kt} (100%) rename src/main/java/frc/robot/subsystems/{ArmSubsystem.java => ArmSubsystem.kt} (100%) rename src/main/java/frc/robot/subsystems/{ClimberSubsystem.java => ClimberSubsystem.kt} (100%) rename src/main/java/frc/robot/subsystems/{SwerveSubsystem.java => SwerveSubsystem.kt} (100%) rename src/main/java/frc/robot/subsystems/{TelemetrySubsystem.java => TelemetrySubsystem.kt} (100%) rename src/main/java/frc/robot/subsystems/{VisionSubsystem.java => VisionSubsystem.kt} (100%) rename src/main/java/frc/robot/subsystems/intake/{Intake.java => Intake.kt} (100%) rename src/main/java/frc/robot/subsystems/intake/{IntakeIO.java => IntakeIO.kt} (100%) rename src/main/java/frc/robot/subsystems/intake/{IntakeIOSparkMax.java => IntakeIOSparkMax.kt} (100%) rename src/main/java/frc/robot/subsystems/shooter/{Shooter.java => Shooter.kt} (100%) rename src/main/java/frc/robot/subsystems/shooter/{ShooterIO.java => ShooterIO.kt} (100%) rename src/main/java/frc/robot/subsystems/shooter/{ShooterIOSim.java => ShooterIOSim.kt} (100%) rename src/main/java/frc/robot/subsystems/shooter/{ShooterIOSparkFlex.java => ShooterIOSparkFlex.kt} (100%) diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.kt similarity index 100% rename from src/main/java/frc/robot/FieldConstants.java rename to src/main/java/frc/robot/FieldConstants.kt diff --git a/src/main/java/frc/robot/LocalADStarAK.java b/src/main/java/frc/robot/LocalADStarAK.kt similarity index 100% rename from src/main/java/frc/robot/LocalADStarAK.java rename to src/main/java/frc/robot/LocalADStarAK.kt diff --git a/src/main/java/frc/robot/Main.java b/src/main/java/frc/robot/Main.kt similarity index 100% rename from src/main/java/frc/robot/Main.java rename to src/main/java/frc/robot/Main.kt diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.kt similarity index 100% rename from src/main/java/frc/robot/Robot.java rename to src/main/java/frc/robot/Robot.kt diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.kt similarity index 100% rename from src/main/java/frc/robot/RobotContainer.java rename to src/main/java/frc/robot/RobotContainer.kt diff --git a/src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.java b/src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.java rename to src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.kt diff --git a/src/main/java/frc/robot/commands/ClimbCommand.java b/src/main/java/frc/robot/commands/ClimbCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/ClimbCommand.java rename to src/main/java/frc/robot/commands/ClimbCommand.kt diff --git a/src/main/java/frc/robot/commands/IntakeCommand.java b/src/main/java/frc/robot/commands/IntakeCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/IntakeCommand.java rename to src/main/java/frc/robot/commands/IntakeCommand.kt diff --git a/src/main/java/frc/robot/commands/MoveArmCommand.java b/src/main/java/frc/robot/commands/MoveArmCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/MoveArmCommand.java rename to src/main/java/frc/robot/commands/MoveArmCommand.kt diff --git a/src/main/java/frc/robot/commands/RotateCommand.java b/src/main/java/frc/robot/commands/RotateCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/RotateCommand.java rename to src/main/java/frc/robot/commands/RotateCommand.kt diff --git a/src/main/java/frc/robot/commands/ShootCommand.java b/src/main/java/frc/robot/commands/ShootCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/ShootCommand.java rename to src/main/java/frc/robot/commands/ShootCommand.kt diff --git a/src/main/java/frc/robot/commands/auto/AutoBalanceCommand.java b/src/main/java/frc/robot/commands/auto/AutoBalanceCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/auto/AutoBalanceCommand.java rename to src/main/java/frc/robot/commands/auto/AutoBalanceCommand.kt diff --git a/src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.java b/src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.kt similarity index 100% rename from src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.java rename to src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.kt diff --git a/src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.java b/src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.kt similarity index 100% rename from src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.java rename to src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.kt diff --git a/src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.java b/src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.kt similarity index 100% rename from src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.java rename to src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.kt diff --git a/src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.java b/src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.java rename to src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.kt diff --git a/src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.java b/src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.kt similarity index 100% rename from src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.java rename to src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.kt diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.java b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/ArmSubsystem.java rename to src/main/java/frc/robot/subsystems/ArmSubsystem.kt diff --git a/src/main/java/frc/robot/subsystems/ClimberSubsystem.java b/src/main/java/frc/robot/subsystems/ClimberSubsystem.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/ClimberSubsystem.java rename to src/main/java/frc/robot/subsystems/ClimberSubsystem.kt diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/SwerveSubsystem.java rename to src/main/java/frc/robot/subsystems/SwerveSubsystem.kt diff --git a/src/main/java/frc/robot/subsystems/TelemetrySubsystem.java b/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/TelemetrySubsystem.java rename to src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt diff --git a/src/main/java/frc/robot/subsystems/VisionSubsystem.java b/src/main/java/frc/robot/subsystems/VisionSubsystem.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/VisionSubsystem.java rename to src/main/java/frc/robot/subsystems/VisionSubsystem.kt diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.java b/src/main/java/frc/robot/subsystems/intake/Intake.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/intake/Intake.java rename to src/main/java/frc/robot/subsystems/intake/Intake.kt diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIO.java b/src/main/java/frc/robot/subsystems/intake/IntakeIO.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/intake/IntakeIO.java rename to src/main/java/frc/robot/subsystems/intake/IntakeIO.kt diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.java rename to src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/shooter/Shooter.java rename to src/main/java/frc/robot/subsystems/shooter/Shooter.kt diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/shooter/ShooterIO.java rename to src/main/java/frc/robot/subsystems/shooter/ShooterIO.kt diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java rename to src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.kt diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt similarity index 100% rename from src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.java rename to src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt From 82a6d9e1c9906207df2a85513ec3d0ba95ae0e0d Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Mon, 18 Mar 2024 00:26:49 -0400 Subject: [PATCH 06/13] feat(lang): move to kotlin --- build.gradle | 8 +- settings.gradle | 6 + .../deploy/maxswerve/modules/backleft.json | 1 + .../deploy/maxswerve/modules/backright.json | 1 + .../deploy/maxswerve/modules/frontleft.json | 1 + .../deploy/maxswerve/modules/frontright.json | 1 + src/main/java/frc/robot/FieldConstants.kt | 251 ++-- src/main/java/frc/robot/LocalADStarAK.kt | 270 ++--- src/main/java/frc/robot/Main.kt | 27 +- src/main/java/frc/robot/Robot.kt | 249 ++-- src/main/java/frc/robot/RobotContainer.kt | 361 +++--- .../robot/commands/AimAndPickUpNoteCommand.kt | 124 +- .../commands/CalculateShooterAngleCommand.kt | 69 ++ .../java/frc/robot/commands/ClimbCommand.kt | 53 +- .../java/frc/robot/commands/IntakeCommand.kt | 91 +- .../java/frc/robot/commands/IntakeCommand2.kt | 44 + .../java/frc/robot/commands/MoveArmCommand.kt | 129 +- .../java/frc/robot/commands/RotateCommand.kt | 88 +- .../java/frc/robot/commands/ShootCommand.kt | 84 +- .../robot/commands/auto/AutoBalanceCommand.kt | 136 +-- .../robot/commands/drivebase/AbsoluteDrive.kt | 201 ++-- .../commands/drivebase/AbsoluteDriveAdv.kt | 259 ++-- .../commands/drivebase/AbsoluteFieldDrive.kt | 164 ++- .../drivebase/AimAtLimelightCommand.kt | 132 +- .../commands/drivebase/AimAtTargetCommand.kt | 86 +- .../java/frc/robot/subsystems/ArmSubsystem.kt | 377 +++--- .../frc/robot/subsystems/ClimberSubsystem.kt | 55 +- .../frc/robot/subsystems/SwerveSubsystem.kt | 1065 +++++++++-------- .../robot/subsystems/TelemetrySubsystem.kt | 55 +- .../frc/robot/subsystems/VisionSubsystem.kt | 206 ++-- .../frc/robot/subsystems/intake/Intake.kt | 296 +++-- .../frc/robot/subsystems/intake/IntakeIO.kt | 185 ++- .../intake/IntakeIOInputsAutoLogged.kt | 58 + .../subsystems/intake/IntakeIOSparkMax.kt | 325 +++-- .../frc/robot/subsystems/shooter/Shooter.kt | 113 +- .../frc/robot/subsystems/shooter/ShooterIO.kt | 125 +- .../shooter/ShooterIOInputsAutoLogged.kt | 76 ++ .../robot/subsystems/shooter/ShooterIOSim.kt | 108 +- .../subsystems/shooter/ShooterIOSparkFlex.kt | 244 ++-- src/main/java/frc/robot/util/Alert.java | 193 --- src/main/java/frc/robot/util/Alert1.kt | 184 +++ src/main/java/frc/robot/util/Constants.java | 119 -- src/main/java/frc/robot/util/Constants1.kt | 299 +++++ .../java/frc/robot/util/LimelightHelpers.java | 780 ------------ .../java/frc/robot/util/LimelightHelpers1.kt | 698 +++++++++++ vendordeps/yagsl.json | 22 + 46 files changed, 4534 insertions(+), 3885 deletions(-) create mode 100644 src/main/java/frc/robot/commands/CalculateShooterAngleCommand.kt create mode 100644 src/main/java/frc/robot/commands/IntakeCommand2.kt create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt create mode 100644 src/main/java/frc/robot/subsystems/shooter/ShooterIOInputsAutoLogged.kt delete mode 100644 src/main/java/frc/robot/util/Alert.java create mode 100644 src/main/java/frc/robot/util/Alert1.kt delete mode 100644 src/main/java/frc/robot/util/Constants.java create mode 100644 src/main/java/frc/robot/util/Constants1.kt delete mode 100644 src/main/java/frc/robot/util/LimelightHelpers.java create mode 100644 src/main/java/frc/robot/util/LimelightHelpers1.kt create mode 100644 vendordeps/yagsl.json diff --git a/build.gradle b/build.gradle index 1d0adfa..ab6ec79 100644 --- a/build.gradle +++ b/build.gradle @@ -9,6 +9,7 @@ plugins { // I mean, it's not like you can't use Gradle with IDEA, but it's just not as smooth as Maven. // But I've got bigger problems than some Maven-vs-Gradle thing. id "idea" + id 'org.jetbrains.kotlin.jvm' } idea { @@ -19,8 +20,6 @@ idea { } java { - sourceCompatibility = JavaVersion.VERSION_17 - targetCompatibility = JavaVersion.VERSION_17 } project.compileJava.dependsOn(createVersionFile) gversion { @@ -42,6 +41,7 @@ repositories { } } mavenLocal() + mavenCentral() } configurations.all { @@ -116,6 +116,7 @@ dependencies { def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text) annotationProcessor "org.littletonrobotics.akit.junction:junction-autolog:$akitJson.version" + implementation "org.jetbrains.kotlin:kotlin-stdlib-jdk8" } test { @@ -145,4 +146,7 @@ wpi.java.configureTestTasks(test) // Configure string concat to always inline compile tasks.withType(JavaCompile).configureEach { options.compilerArgs.add '-XDstringConcat=inline' +} +kotlin { + jvmToolchain(17) } \ No newline at end of file diff --git a/settings.gradle b/settings.gradle index 3e30f84..edd3891 100644 --- a/settings.gradle +++ b/settings.gradle @@ -24,6 +24,12 @@ pluginManagement { url frcHomeMaven } } + plugins { + id 'org.jetbrains.kotlin.jvm' version '1.9.23' + } +} +plugins { + id 'org.gradle.toolchains.foojay-resolver-convention' version '0.5.0' } Properties props = System.getProperties(); diff --git a/src/main/deploy/maxswerve/modules/backleft.json b/src/main/deploy/maxswerve/modules/backleft.json index e9b54ae..e9ca036 100644 --- a/src/main/deploy/maxswerve/modules/backleft.json +++ b/src/main/deploy/maxswerve/modules/backleft.json @@ -15,6 +15,7 @@ "drive": false, "angle": false }, + "absoluteEncoderInverted": true, "location": { "x": -13, "y": 13.25 diff --git a/src/main/deploy/maxswerve/modules/backright.json b/src/main/deploy/maxswerve/modules/backright.json index e6ea121..d65d30f 100644 --- a/src/main/deploy/maxswerve/modules/backright.json +++ b/src/main/deploy/maxswerve/modules/backright.json @@ -15,6 +15,7 @@ "drive": false, "angle": false }, + "absoluteEncoderInverted": true, "location": { "x": -13, "y": -13.25 diff --git a/src/main/deploy/maxswerve/modules/frontleft.json b/src/main/deploy/maxswerve/modules/frontleft.json index 1dd9608..04df04e 100644 --- a/src/main/deploy/maxswerve/modules/frontleft.json +++ b/src/main/deploy/maxswerve/modules/frontleft.json @@ -15,6 +15,7 @@ "drive": false, "angle": false }, + "absoluteEncoderInverted": true, "location": { "x": 5.5, "y": 13.25 diff --git a/src/main/deploy/maxswerve/modules/frontright.json b/src/main/deploy/maxswerve/modules/frontright.json index 23390cd..81cbcf4 100644 --- a/src/main/deploy/maxswerve/modules/frontright.json +++ b/src/main/deploy/maxswerve/modules/frontright.json @@ -15,6 +15,7 @@ "drive": false, "angle": false }, + "absoluteEncoderInverted": true, "location": { "x": 5.5, "y": -13.25 diff --git a/src/main/java/frc/robot/FieldConstants.kt b/src/main/java/frc/robot/FieldConstants.kt index 6f93ba0..e7c6f3a 100644 --- a/src/main/java/frc/robot/FieldConstants.kt +++ b/src/main/java/frc/robot/FieldConstants.kt @@ -1,102 +1,173 @@ -package frc.robot; +package frc.robot +import edu.wpi.first.apriltag.AprilTagFieldLayout +import edu.wpi.first.apriltag.AprilTagFields +import edu.wpi.first.math.geometry.Translation2d +import edu.wpi.first.math.geometry.Translation3d +import edu.wpi.first.units.Distance +import edu.wpi.first.units.Measure +import edu.wpi.first.units.Units +import java.io.IOException -import static edu.wpi.first.apriltag.AprilTagFields.k2024Crescendo; -import static edu.wpi.first.units.Units.Inches; - -import edu.wpi.first.apriltag.AprilTagFieldLayout; -import edu.wpi.first.math.geometry.*; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.units.Distance; -import edu.wpi.first.units.Measure; - -import java.io.IOException; /** * Contains various field dimensions and useful reference points. Dimensions are in meters, and sets - * of corners start in the lower left moving clockwise. All units in Meters
- *
+ * of corners start in the lower left moving clockwise. **All units in Meters**

+ *

* - *

All translations and poses are stored with the origin at the rightmost point on the BLUE - * ALLIANCE wall.
- *
- * Length refers to the x direction (as described by wpilib)
- * Width refers to the y direction (as described by wpilib) + * + * All translations and poses are stored with the origin at the rightmost point on the BLUE + * ALLIANCE wall.

+ *

+ * Length refers to the *x* direction (as described by wpilib)

+ * Width refers to the *y* direction (as described by wpilib) */ -public class FieldConstants { - public static final Measure FIELD_LENGTH = Inches.of(651.223); - public static final Measure FIELD_WIDTH = Inches.of(323.277); - public static final Measure WING_X = Inches.of(229.201); - public static final Measure PODIUM_X = Inches.of(126.75); - public static final Measure STARTING_LINE_X = Inches.of(74.111); - - public static final Translation2d AMP_CENTER = - new Translation2d(Units.inchesToMeters(72.455), Units.inchesToMeters(322.996)); - - /** Staging locations for each note */ - public static final class StagingLocations { - public static final Measure CENTERLINE_X = FIELD_LENGTH.divide(2.0); - - // need to update - public static final Measure CENTERLINE_FIRST_Y = Inches.of(29.638); - public static final Measure CENTERLINE_SEPARATION_Y = Inches.of(66); - public static final Measure SPIKE_X = Inches.of(114); - // need - public static final Measure SPIKE_FIRST_Y = Inches.of(161.638); - public static final Measure SPIKE_SEPARATION_Y = Inches.of(57); - - public static final Translation2d[] CENTERLINE_TRANSLATIONS = new Translation2d[5]; - public static final Translation2d[] SPIKE_TRANSLATIONS = new Translation2d[3]; - - static { - for (int i = 0; i < CENTERLINE_TRANSLATIONS.length; i++) { - CENTERLINE_TRANSLATIONS[i] = - new Translation2d(CENTERLINE_X.in(Inches), CENTERLINE_FIRST_Y.in(Inches) + (i * CENTERLINE_SEPARATION_Y.in(Inches))); - } +object FieldConstants { + /** + * + */ + val FIELD_LENGTH: Measure = Units.Inches.of(651.223) + /** + * + */ + val FIELD_WIDTH: Measure = Units.Inches.of(323.277) + /** + * + */ + val WING_X: Measure = Units.Inches.of(229.201) + /** + * + */ + val PODIUM_X: Measure = Units.Inches.of(126.75) + /** + * + */ + val STARTING_LINE_X: Measure = Units.Inches.of(74.111) + + /** + * + */ + val AMP_CENTER: Translation2d = Translation2d( + edu.wpi.first.math.util.Units.inchesToMeters(72.455), + edu.wpi.first.math.util.Units.inchesToMeters(322.996) + ) + + /** + * + */ + val APRIL_TAG_WIDTH: Measure = Units.Inches.of(6.50) + /** + * + */ + private var APRIL_TAGS: AprilTagFieldLayout? = null + + init { + try { + APRIL_TAGS = AprilTagFieldLayout.loadFromResource(AprilTagFields.k2024Crescendo.m_resourceFile) + } catch (e: IOException) { + throw RuntimeException(e) + } } - static { - for (int i = 0; i < SPIKE_TRANSLATIONS.length; i++) { - SPIKE_TRANSLATIONS[i] = new Translation2d(SPIKE_X.in(Inches), SPIKE_FIRST_Y.in(Inches) + (i * SPIKE_SEPARATION_Y.in(Inches))); - } + /** Staging locations for each note */ + object StagingLocations { + /** + * + */ + private val CENTERLINE_X: Measure = FIELD_LENGTH.divide(2.0) + + /** + * + */// need to update + private val CENTERLINE_FIRST_Y: Measure = Units.Inches.of(29.638) + /** + * + */ + private val CENTERLINE_SEPARATION_Y: Measure = Units.Inches.of(66.0) + /** + * + */ + private val SPIKE_X: Measure = Units.Inches.of(114.0) + + /** + * + */// need + private val SPIKE_FIRST_Y: Measure = Units.Inches.of(161.638) + /** + * + */ + private val SPIKE_SEPARATION_Y: Measure = Units.Inches.of(57.0) + + /** + * + */ + private val CENTERLINE_TRANSLATIONS: Array = arrayOfNulls(5) + /** + * + */ + private val SPIKE_TRANSLATIONS: Array = arrayOfNulls(3) + + init { + for (i in CENTERLINE_TRANSLATIONS.indices) { + CENTERLINE_TRANSLATIONS[i] = + Translation2d( + CENTERLINE_X.`in`(Units.Inches), + CENTERLINE_FIRST_Y.`in`(Units.Inches) + (i * CENTERLINE_SEPARATION_Y.`in`( + Units.Inches + )) + ) + } + } + + init { + for (i in SPIKE_TRANSLATIONS.indices) { + SPIKE_TRANSLATIONS[i] = Translation2d( + SPIKE_X.`in`(Units.Inches), SPIKE_FIRST_Y.`in`(Units.Inches) + (i * SPIKE_SEPARATION_Y.`in`( + Units.Inches + )) + ) + } + } } - } - - /** Each corner of the speaker * */ - public static final class Speaker { - - // corners (blue alliance origin) - public static final Translation3d TOP_RIGHT_SPEAKER = - new Translation3d( - Units.inchesToMeters(18.055), - Units.inchesToMeters(238.815), - Units.inchesToMeters(83.091)); - - public static final Translation3d TOP_LEFT_SPEAKER = - new Translation3d( - Units.inchesToMeters(18.055), - Units.inchesToMeters(197.765), - Units.inchesToMeters(83.091)); - - public static final Translation3d BOTTOM_RIGHT_SPEAKER = - new Translation3d(0.0, Units.inchesToMeters(238.815), Units.inchesToMeters(78.324)); - public static final Translation3d BOTTOM_LEFT_SPEAKER = - new Translation3d(0.0, Units.inchesToMeters(197.765), Units.inchesToMeters(78.324)); - - /** Center of the speaker opening (blue alliance) */ - public static final Translation3d CENTER_SPEAKER_OPENING = - BOTTOM_LEFT_SPEAKER.interpolate(TOP_RIGHT_SPEAKER, 0.5); - - } - - public static final Measure APRIL_TAG_WIDTH = Inches.of(6.50); - public static final AprilTagFieldLayout APRIL_TAGS; - - static { - try { - APRIL_TAGS = AprilTagFieldLayout.loadFromResource(k2024Crescendo.m_resourceFile); - } catch (IOException e) { - throw new RuntimeException(e); + + /** Each corner of the speaker * */ + object Speaker { + /** + * + */// corners (blue alliance origin) + private val TOP_RIGHT_SPEAKER: Translation3d = Translation3d( + edu.wpi.first.math.util.Units.inchesToMeters(18.055), + edu.wpi.first.math.util.Units.inchesToMeters(238.815), + edu.wpi.first.math.util.Units.inchesToMeters(83.091) + ) + + /** + * + */ + val TOP_LEFT_SPEAKER: Translation3d = Translation3d( + edu.wpi.first.math.util.Units.inchesToMeters(18.055), + edu.wpi.first.math.util.Units.inchesToMeters(197.765), + edu.wpi.first.math.util.Units.inchesToMeters(83.091) + ) + + /** + * + */ + val BOTTOM_RIGHT_SPEAKER: Translation3d = Translation3d( + 0.0, + edu.wpi.first.math.util.Units.inchesToMeters(238.815), + edu.wpi.first.math.util.Units.inchesToMeters(78.324) + ) + /** + * + */ + private val BOTTOM_LEFT_SPEAKER: Translation3d = Translation3d( + 0.0, + edu.wpi.first.math.util.Units.inchesToMeters(197.765), + edu.wpi.first.math.util.Units.inchesToMeters(78.324) + ) + + /** Center of the speaker opening (blue alliance) */ + val CENTER_SPEAKER_OPENING: Translation3d = BOTTOM_LEFT_SPEAKER.interpolate(TOP_RIGHT_SPEAKER, 0.5) } - } } \ No newline at end of file diff --git a/src/main/java/frc/robot/LocalADStarAK.kt b/src/main/java/frc/robot/LocalADStarAK.kt index 6f2a86a..1c2255a 100644 --- a/src/main/java/frc/robot/LocalADStarAK.kt +++ b/src/main/java/frc/robot/LocalADStarAK.kt @@ -1,149 +1,145 @@ -package frc.robot; - -import edu.wpi.first.math.Pair; -import edu.wpi.first.math.geometry.Translation2d; -import com.pathplanner.lib.path.GoalEndState; -import com.pathplanner.lib.path.PathConstraints; -import com.pathplanner.lib.path.PathPlannerPath; -import com.pathplanner.lib.path.PathPoint; -import com.pathplanner.lib.pathfinding.Pathfinder; -import com.pathplanner.lib.pathfinding.LocalADStar; -import java.util.ArrayList; -import java.util.Collections; -import java.util.List; -import org.littletonrobotics.junction.LogTable; -import org.littletonrobotics.junction.Logger; -import org.littletonrobotics.junction.inputs.LoggableInputs; - -public class LocalADStarAK implements Pathfinder { - private final ADStarIO io = new ADStarIO(); - - /** - * Get if a new path has been calculated since the last time a path was retrieved - * - * @return True if a new path is available - */ - @Override - public boolean isNewPathAvailable() { - if (!Logger.hasReplaySource()) { - io.updateIsNewPathAvailable(); +package frc.robot + +import com.pathplanner.lib.path.GoalEndState +import com.pathplanner.lib.path.PathConstraints +import com.pathplanner.lib.path.PathPlannerPath +import com.pathplanner.lib.path.PathPoint +import com.pathplanner.lib.pathfinding.LocalADStar +import com.pathplanner.lib.pathfinding.Pathfinder +import edu.wpi.first.math.Pair +import edu.wpi.first.math.geometry.Translation2d +import org.littletonrobotics.junction.LogTable +import org.littletonrobotics.junction.Logger +import org.littletonrobotics.junction.inputs.LoggableInputs + +/** + * + */ +class LocalADStarAK : Pathfinder { + private val io = ADStarIO() + + /** + * Get if a new path has been calculated since the last time a path was retrieved + * + * @return True if a new path is available + */ + override fun isNewPathAvailable(): Boolean { + if (!Logger.hasReplaySource()) { + io.updateIsNewPathAvailable() + } + + Logger.processInputs("LocalADStarAK", io) + + return io.isNewPathAvailable } - Logger.processInputs("LocalADStarAK", io); - - return io.isNewPathAvailable; - } - - /** - * Get the most recently calculated path - * - * @param constraints The path constraints to use when creating the path - * @param goalEndState The goal end state to use when creating the path - * @return The PathPlannerPath created from the points calculated by the pathfinder - */ - @Override - public PathPlannerPath getCurrentPath(PathConstraints constraints, GoalEndState goalEndState) { - if (!Logger.hasReplaySource()) { - io.updateCurrentPathPoints(constraints, goalEndState); + /** + * Get the most recently calculated path + * + * @param constraints The path constraints to use when creating the path + * @param goalEndState The goal end state to use when creating the path + * @return The PathPlannerPath created from the points calculated by the pathfinder + */ + override fun getCurrentPath(constraints: PathConstraints, goalEndState: GoalEndState): PathPlannerPath? { + if (!Logger.hasReplaySource()) { + io.updateCurrentPathPoints(constraints, goalEndState) + } + + Logger.processInputs("LocalADStarAK", io) + + if (io.currentPathPoints.isEmpty()) { + return null + } + + return PathPlannerPath.fromPathPoints(io.currentPathPoints, constraints, goalEndState) } - Logger.processInputs("LocalADStarAK", io); - - if (io.currentPathPoints.isEmpty()) { - return null; - } - - return PathPlannerPath.fromPathPoints(io.currentPathPoints, constraints, goalEndState); - } - - /** - * Set the start position to pathfind from - * - * @param startPosition Start position on the field. If this is within an obstacle it will be - * moved to the nearest non-obstacle node. - */ - @Override - public void setStartPosition(Translation2d startPosition) { - if (!Logger.hasReplaySource()) { - io.adStar.setStartPosition(startPosition); - } - } - - /** - * Set the goal position to pathfind to - * - * @param goalPosition Goal position on the field. f this is within an obstacle it will be moved - * to the nearest non-obstacle node. - */ - @Override - public void setGoalPosition(Translation2d goalPosition) { - if (!Logger.hasReplaySource()) { - io.adStar.setGoalPosition(goalPosition); - } - } - - /** - * Set the dynamic obstacles that should be avoided while pathfinding. - * - * @param obs A List of Translation2d pairs representing obstacles. Each Translation2d represents - * opposite corners of a bounding box. - * @param currentRobotPos The current position of the robot. This is needed to change the start - * position of the path to properly avoid obstacles - */ - @Override - public void setDynamicObstacles( - List> obs, Translation2d currentRobotPos) { - if (!Logger.hasReplaySource()) { - io.adStar.setDynamicObstacles(obs, currentRobotPos); + /** + * Set the start position to pathfind from + * + * @param startPosition Start position on the field. If this is within an obstacle it will be + * moved to the nearest non-obstacle node. + */ + override fun setStartPosition(startPosition: Translation2d) { + if (!Logger.hasReplaySource()) { + io.adStar.setStartPosition(startPosition) + } } - } - - private static class ADStarIO implements LoggableInputs { - public LocalADStar adStar = new LocalADStar(); - public boolean isNewPathAvailable = false; - public List currentPathPoints = Collections.emptyList(); - - @Override - public void toLog(LogTable table) { - table.put("IsNewPathAvailable", isNewPathAvailable); - - double[] pointsLogged = new double[currentPathPoints.size() * 2]; - int idx = 0; - for (PathPoint point : currentPathPoints) { - pointsLogged[idx] = point.position.getX(); - pointsLogged[idx + 1] = point.position.getY(); - idx += 2; - } - - table.put("CurrentPathPoints", pointsLogged); - } - - @Override - public void fromLog(LogTable table) { - isNewPathAvailable = table.get("IsNewPathAvailable", false); - - double[] pointsLogged = table.get("CurrentPathPoints", new double[0]); - List pathPoints = new ArrayList<>(); - for (int i = 0; i < pointsLogged.length; i += 2) { - pathPoints.add(new PathPoint(new Translation2d(pointsLogged[i], pointsLogged[i + 1]), null)); - } - - currentPathPoints = pathPoints; + /** + * Set the goal position to pathfind to + * + * @param goalPosition Goal position on the field. f this is within an obstacle it will be moved + * to the nearest non-obstacle node. + */ + override fun setGoalPosition(goalPosition: Translation2d) { + if (!Logger.hasReplaySource()) { + io.adStar.setGoalPosition(goalPosition) + } } - public void updateIsNewPathAvailable() { - isNewPathAvailable = adStar.isNewPathAvailable(); + /** + * Set the dynamic obstacles that should be avoided while pathfinding. + * + * @param obs A List of Translation2d pairs representing obstacles. Each Translation2d represents + * opposite corners of a bounding box. + * @param currentRobotPos The current position of the robot. This is needed to change the start + * position of the path to properly avoid obstacles + */ + override fun setDynamicObstacles( + obs: List>, currentRobotPos: Translation2d + ) { + if (!Logger.hasReplaySource()) { + io.adStar.setDynamicObstacles(obs, currentRobotPos) + } } - public void updateCurrentPathPoints(PathConstraints constraints, GoalEndState goalEndState) { - PathPlannerPath currentPath = adStar.getCurrentPath(constraints, goalEndState); - - if (currentPath != null) { - currentPathPoints = currentPath.getAllPathPoints(); - } else { - currentPathPoints = Collections.emptyList(); - } + private class ADStarIO : LoggableInputs { + var adStar: LocalADStar = LocalADStar() + var isNewPathAvailable: Boolean = false + var currentPathPoints: List = emptyList() + + override fun toLog(table: LogTable) { + table.put("IsNewPathAvailable", isNewPathAvailable) + + val pointsLogged = DoubleArray(currentPathPoints.size * 2) + var idx = 0 + for (point in currentPathPoints) { + pointsLogged[idx] = point.position.x + pointsLogged[idx + 1] = point.position.y + idx += 2 + } + + table.put("CurrentPathPoints", pointsLogged) + } + + override fun fromLog(table: LogTable) { + isNewPathAvailable = table["IsNewPathAvailable", false] + + val pointsLogged = table["CurrentPathPoints", DoubleArray(0)] + + val pathPoints: MutableList = ArrayList() + var i = 0 + while (i < pointsLogged.size) { + pathPoints.add(PathPoint(Translation2d(pointsLogged[i], pointsLogged[i + 1]), null)) + i += 2 + } + + currentPathPoints = pathPoints + } + + fun updateIsNewPathAvailable() { + isNewPathAvailable = adStar.isNewPathAvailable + } + + fun updateCurrentPathPoints(constraints: PathConstraints?, goalEndState: GoalEndState?) { + val currentPath = adStar.getCurrentPath(constraints, goalEndState) + + currentPathPoints = if (currentPath != null) { + currentPath.allPathPoints + } else { + emptyList() + } + } } - } } diff --git a/src/main/java/frc/robot/Main.kt b/src/main/java/frc/robot/Main.kt index 8776e5d..2185118 100644 --- a/src/main/java/frc/robot/Main.kt +++ b/src/main/java/frc/robot/Main.kt @@ -1,25 +1,24 @@ // 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 -package frc.robot; - -import edu.wpi.first.wpilibj.RobotBase; +import edu.wpi.first.wpilibj.RobotBase /** * Do NOT add any static variables to this class, or any initialization at all. Unless you know what * you are doing, do not modify this file except to change the parameter class to the startRobot * call. */ -public final class Main { - private Main() {} - - /** - * Main initialization function. Do not perform any initialization here. - * - *

If you change your main robot class, change the parameter type. - */ - public static void main(String... args) { - RobotBase.startRobot(Robot::new); - } +object Main { + /** + * Main initialization function. Do not perform any initialization here. + * + * + * If you change your main robot class, change the parameter type. + */ + @JvmStatic + fun main(args: Array) { + RobotBase.startRobot { Robot() } + } } diff --git a/src/main/java/frc/robot/Robot.kt b/src/main/java/frc/robot/Robot.kt index 743c6c8..dd5aecb 100644 --- a/src/main/java/frc/robot/Robot.kt +++ b/src/main/java/frc/robot/Robot.kt @@ -1,21 +1,20 @@ // 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; - -import com.pathplanner.lib.pathfinding.Pathfinding; -import edu.wpi.first.wpilibj.DataLogManager; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.CommandScheduler; -import org.littletonrobotics.junction.LogFileUtil; -import org.littletonrobotics.junction.LoggedRobot; -import org.littletonrobotics.junction.Logger; -import org.littletonrobotics.junction.networktables.NT4Publisher; -import org.littletonrobotics.junction.wpilog.WPILOGReader; -import org.littletonrobotics.junction.wpilog.WPILOGWriter; -import frc.robot.util.Constants; -import org.littletonrobotics.urcl.URCL; +package frc.robot + +import com.pathplanner.lib.pathfinding.Pathfinding +import edu.wpi.first.wpilibj.DataLogManager +import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.CommandScheduler +import frc.robot.util.Constants +import org.littletonrobotics.junction.LogFileUtil +import org.littletonrobotics.junction.LoggedRobot +import org.littletonrobotics.junction.Logger +import org.littletonrobotics.junction.networktables.NT4Publisher +import org.littletonrobotics.junction.wpilog.WPILOGReader +import org.littletonrobotics.junction.wpilog.WPILOGWriter +import org.littletonrobotics.urcl.URCL /** * The VM is configured to automatically run this class, and to call the functions corresponding to @@ -23,127 +22,119 @@ import org.littletonrobotics.urcl.URCL; * the package after creating this project, you must also update the build.gradle file in the * project. */ -public class Robot extends LoggedRobot { - private Command autonomousCommand; - - private RobotContainer robotContainer; - - @Override - public void robotInit() { - Pathfinding.setPathfinder(new LocalADStarAK()); - DataLogManager.start(); - // Record metadata - - Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME); - Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE); - Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA); - Logger.recordMetadata("GitDate", BuildConstants.GIT_DATE); - Logger.recordMetadata("GitBranch", BuildConstants.GIT_BRANCH); - switch (BuildConstants.DIRTY) { - case 0: - Logger.recordMetadata("GitDirty", "All changes committed"); - break; - case 1: - Logger.recordMetadata("GitDirty", "Uncomitted changes"); - break; - default: - Logger.recordMetadata("GitDirty", "Unknown"); - break; +class Robot : LoggedRobot() { + private var autonomousCommand: Command? = null + + private var robotContainer: RobotContainer? = null + + /** + * + */ + override fun robotInit() { + Pathfinding.setPathfinder(LocalADStarAK()) + DataLogManager.start() + + // Record metadata + Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME) + Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE) + Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA) + Logger.recordMetadata("GitDate", BuildConstants.GIT_DATE) + Logger.recordMetadata("GitBranch", BuildConstants.GIT_BRANCH) + when (BuildConstants.DIRTY) { + 0 -> Logger.recordMetadata("GitDirty", "All changes committed") + 1 -> Logger.recordMetadata("GitDirty", "Uncomitted changes") + else -> Logger.recordMetadata("GitDirty", "Unknown") + } + when (Constants.CURRENT_MODE) { + Constants.Mode.REAL -> { + // Running on a real robot, log to a USB stick ("/U/logs") + Logger.addDataReceiver(WPILOGWriter()) + Logger.addDataReceiver(NT4Publisher()) + } + + Constants.Mode.SIM -> // Running a physics simulator, log to NT + Logger.addDataReceiver(NT4Publisher()) + + Constants.Mode.REPLAY -> { + // Replaying a log, set up replay source + setUseTiming(false) // Run as fast as possible + val logPath = LogFileUtil.findReplayLog() + Logger.setReplaySource(WPILOGReader(logPath)) + Logger.addDataReceiver(WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))) + } + } + // See http://bit.ly/3YIzFZ6 for more information on timestamps in AdvantageKit. + // Logger.disableDeterministicTimestamps() + Logger.registerURCL(URCL.startExternal()) + // Start AdvantageKit logger + Logger.start() + + // Instantiate our RobotContainer. This will perform all our button bindings, + // and put our autonomous chooser on the dashboard. + robotContainer = RobotContainer() } - // Set up data receivers & replay source - switch (Constants.CURRENT_MODE) { - case REAL: - // Running on a real robot, log to a USB stick ("/U/logs") - Logger.addDataReceiver(new WPILOGWriter()); - Logger.addDataReceiver(new NT4Publisher()); - break; - - case SIM: - // Running a physics simulator, log to NT - Logger.addDataReceiver(new NT4Publisher()); - break; - - case REPLAY: - // Replaying a log, set up replay source - setUseTiming(false); // Run as fast as possible - String logPath = LogFileUtil.findReplayLog(); - Logger.setReplaySource(new WPILOGReader(logPath)); - Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); - break; + /** + * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics + * that you want ran during disabled, autonomous, teleoperated and test. + * + * + * This runs after the mode specific periodic functions, but before LiveWindow and + * SmartDashboard integrated updating. + */ + override fun robotPeriodic() { + // 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() } - // See http://bit.ly/3YIzFZ6 for more information on timestamps in AdvantageKit. - // Logger.disableDeterministicTimestamps() - Logger.registerURCL(URCL.startExternal()); - // Start AdvantageKit logger - Logger.start(); - - // Instantiate our RobotContainer. This will perform all our button bindings, - // and put our autonomous chooser on the dashboard. - robotContainer = new RobotContainer(); - } - - /** - * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. - * - *

This runs after the mode specific periodic functions, but before LiveWindow and - * SmartDashboard integrated updating. - */ - @Override - public void robotPeriodic() { - // 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(); - } - - /** This function is called once each time the robot enters Disabled mode. */ - @Override - public void disabledInit() {} - - @Override - public void disabledPeriodic() {} - - /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ - @Override - public void autonomousInit() { - autonomousCommand = robotContainer.getAutonomousCommand(); - - // schedule the autonomous command (example) - if (autonomousCommand != null) { - autonomousCommand.schedule(); + /** This function is called once each time the robot enters Disabled mode. */ + override fun disabledInit() {} + + /** + * + */ + override fun disabledPeriodic() {} + + /** This autonomous runs the autonomous command selected by your [RobotContainer] class. */ + override fun autonomousInit() { + autonomousCommand = robotContainer?.autonomousCommand + + // schedule the autonomous command (example) + if (autonomousCommand != null) { + (autonomousCommand ?: return).schedule() + } } - } - - /** This function is called periodically during autonomous. */ - @Override - public void autonomousPeriodic() {} - - @Override - public void teleopInit() { - // This makes sure that the autonomous stops running when - // teleop starts running. If you want the autonomous to - // continue until interrupted by another command, remove - // this line or comment it out. - if (autonomousCommand != null) { - autonomousCommand.cancel(); + + /** This function is called periodically during autonomous. */ + override fun autonomousPeriodic() {} + + /** + * + */ + override fun teleopInit() { + // This makes sure that the autonomous stops running when + // teleop starts running. If you want the autonomous to + // continue until interrupted by another command, remove + // this line or comment it out. + if (autonomousCommand != null) { + (autonomousCommand ?: return).cancel() + } } - } - /** This function is called periodically during operator control. */ - @Override - public void teleopPeriodic() {} + /** This function is called periodically during operator control. */ + override fun teleopPeriodic() {} - @Override - public void testInit() { - // Cancels all running commands at the start of test mode. - CommandScheduler.getInstance().cancelAll(); - } + /** + * + */ + override fun testInit() { + // Cancels all running commands at the start of test mode. + CommandScheduler.getInstance().cancelAll() + } - /** This function is called periodically during test mode. */ - @Override - public void testPeriodic() {} + /** This function is called periodically during test mode. */ + override fun testPeriodic() {} } diff --git a/src/main/java/frc/robot/RobotContainer.kt b/src/main/java/frc/robot/RobotContainer.kt index e2df7d3..8fd64d1 100644 --- a/src/main/java/frc/robot/RobotContainer.kt +++ b/src/main/java/frc/robot/RobotContainer.kt @@ -1,165 +1,220 @@ // 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; - -import com.revrobotics.ColorSensorV3; -import edu.wpi.first.math.MathUtil; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.RobotBase; -import edu.wpi.first.wpilibj.XboxController; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.InstantCommand; -import edu.wpi.first.wpilibj2.command.button.CommandJoystick; -import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import edu.wpi.first.wpilibj2.command.button.JoystickButton; -import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc.robot.commands.*; -import frc.robot.commands.drivebase.AbsoluteFieldDrive; -import frc.robot.commands.drivebase.AimAtLimelightCommand; -import frc.robot.commands.drivebase.AimAtTargetCommand; -import frc.robot.subsystems.ArmSubsystem; -import frc.robot.subsystems.VisionSubsystem; -import frc.robot.subsystems.intake.Intake; -import frc.robot.subsystems.intake.IntakeIOSparkMax; -import frc.robot.subsystems.shooter.Shooter; -import frc.robot.subsystems.shooter.ShooterIOSparkFlex; -import frc.robot.util.Constants.OperatorConstants; -import frc.robot.commands.drivebase.AbsoluteDriveAdv; -import frc.robot.subsystems.SwerveSubsystem; -import frc.robot.util.LimelightHelpers; +package frc.robot + +import edu.wpi.first.math.MathUtil +import edu.wpi.first.math.geometry.Pose2d +import edu.wpi.first.math.geometry.Rotation2d +import edu.wpi.first.math.geometry.Translation2d +import edu.wpi.first.wpilibj.DriverStation +import edu.wpi.first.wpilibj.DriverStation.Alliance +import edu.wpi.first.wpilibj.RobotBase +import edu.wpi.first.wpilibj.XboxController +import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.InstantCommand +import edu.wpi.first.wpilibj2.command.button.JoystickButton +import frc.robot.commands.* +import frc.robot.commands.drivebase.AbsoluteDriveAdv +import frc.robot.commands.drivebase.AbsoluteFieldDrive +import frc.robot.commands.drivebase.AimAtLimelightCommand +import frc.robot.subsystems.ArmSubsystem +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.subsystems.VisionSubsystem +import frc.robot.subsystems.intake.Intake +import frc.robot.subsystems.intake.IntakeIOSparkMax +import frc.robot.subsystems.shooter.Shooter +import frc.robot.subsystems.shooter.ShooterIOSparkFlex +import frc.robot.util.Constants.OperatorConstants +import java.util.function.DoubleSupplier /** * This class is where the bulk of the robot should be declared. Since Command-based is a "declarative" paradigm, very - * little robot logic should actually be handled in the {@link Robot} periodic methods (other than the scheduler calls). + * little robot logic should actually be handled in the [Robot] periodic methods (other than the scheduler calls). * Instead, the structure of the robot (including subsystems, commands, and trigger mappings) should be declared here. */ -public class RobotContainer { - - // The robot's subsystems and commands are defined here... - private final SwerveSubsystem drivebase; - private final Intake intake; - private final Shooter shooter; - private final ArmSubsystem armSubsystem; - private final Command intakeCommand, shootCommand, aimAtLimelightCommand, rotateCommand, driveToPoseCommand, aimAndPickUpNoteCommand, armSysIdCommand, moveArmCommand; - - private final Command absoluteFieldDrive; - - XboxController driverXbox = new XboxController(0); - XboxController shooterXbox = new XboxController(1); - - /** - * The container for the robot. Contains subsystems, OI devices, and commands. - */ - public RobotContainer() { - drivebase = SwerveSubsystem.getInstance(); - intake = new Intake(new IntakeIOSparkMax()); - shooter = new Shooter(new ShooterIOSparkFlex()); - armSubsystem = ArmSubsystem.getInstance(); - intakeCommand = new IntakeCommand(intake, () -> MathUtil.applyDeadband(shooterXbox.getLeftTriggerAxis(), 0.1)); - shootCommand = new ShootCommand(shooter, () -> MathUtil.applyDeadband(shooterXbox.getRightTriggerAxis(), 0.1) * 3250); - aimAtLimelightCommand = new AimAtLimelightCommand(drivebase, VisionSubsystem.getInstance()); - rotateCommand = new RotateCommand(drivebase); - driveToPoseCommand = new ShootCommand(shooter, () -> 4000).alongWith(drivebase.driveToPose(new Pose2d(new Translation2d(2.720, 2.579), Rotation2d.fromDegrees(180))).andThen(drivebase.driveToPose(new Pose2d(new Translation2d(2.720, 2.579), Rotation2d.fromDegrees(180)))).andThen(new AimAtLimelightCommand(drivebase, VisionSubsystem.getInstance())).andThen(new IntakeCommand(intake, () -> 1))); - aimAndPickUpNoteCommand = new AimAndPickUpNoteCommand(drivebase, VisionSubsystem.getInstance(), intake); - armSysIdCommand = ArmSubsystem.generateSysIdCommand(armSubsystem.getSysId(), 2, 3.5, 1.5); - moveArmCommand = new MoveArmCommand(() -> MathUtil.applyDeadband(shooterXbox.getRightY(), 0.1)); - int invert = getInvert(); - - absoluteFieldDrive = new AbsoluteFieldDrive(drivebase, () -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND) * invert, () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND) * invert, () -> driverXbox.getRightX() * invert); - // Applies deadbands and inverts controls because joysticks - // are back-right positive while robot - // controls are front-left positive - // left stick controls translation - // right stick controls the desired angle NOT angular rotation - Command driveFieldOrientedDirectAngle = drivebase.driveCommand(() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND) * invert, () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND) * invert, () -> driverXbox.getRightX() * invert, () -> driverXbox.getRightY() * invert); - AbsoluteDriveAdv closedAbsoluteDriveAdv = new AbsoluteDriveAdv(drivebase, () -> MathUtil.applyDeadband(driverXbox.getLeftY() * invert, OperatorConstants.LEFT_Y_DEADBAND), () -> MathUtil.applyDeadband(driverXbox.getLeftX() * invert, OperatorConstants.LEFT_X_DEADBAND), () -> MathUtil.applyDeadband(driverXbox.getRightX() * invert, OperatorConstants.RIGHT_X_DEADBAND), driverXbox::getYButtonPressed, driverXbox::getAButtonPressed, driverXbox::getXButtonPressed, driverXbox::getBButtonPressed); - - // Applies deadbands and inverts controls because joysticks - // are back-right positive while robot - // controls are front-left positive - // left stick controls translation - // right stick controls the angular velocity of the robot - Command driveFieldOrientedAnglularVelocity = drivebase.driveCommand(() -> -MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND) * invert, () -> -MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND) * invert, () -> driverXbox.getRawAxis(4) * invert); - - Command driveFieldOrientedDirectAngleSim = drivebase.simDriveCommand(() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND) * invert, () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND) * invert, () -> driverXbox.getRawAxis(2) * invert); - - Command sysIdForDrive = drivebase.sysIdDriveMotorCommand(); - Command sysIdForAngle = drivebase.sysIdAngleMotorCommand(); - - Command driveFieldOrientedDirectAngleForTesting = drivebase.driveCommand( - () -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND), - () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND), - () -> driverXbox.getRightX(), - () -> driverXbox.getRightY()); - - drivebase.setDefaultCommand(!RobotBase.isSimulation() ? driveFieldOrientedAnglularVelocity : driveFieldOrientedDirectAngleSim); - - // Configure the trigger bindings - configureBindings(); - } - - private int getInvert() { - var alliance = DriverStation.getAlliance(); - int invert; - if (alliance.isPresent() && alliance.get() == DriverStation.Alliance.Red) { - invert = -1; - } else { - invert = 1; +class RobotContainer { + // The robot's subsystems and commands are defined here... + private val drivebase: SwerveSubsystem = SwerveSubsystem.instance + private val intake = Intake(IntakeIOSparkMax()) + private val shooter = Shooter(ShooterIOSparkFlex()) + private val armSubsystem: ArmSubsystem = ArmSubsystem.instance + private val intakeCommand: Command + private val shootCommand: Command + private val aimAtLimelightCommand: Command + private val rotateCommand: Command + private val driveToPoseCommand: Command + private val aimAndPickUpNoteCommand: Command + private val armSysIdCommand: Command + private val moveArmCommand: Command + private val intakeCommand2: Command + + private val absoluteFieldDrive: Command + + /** + * + */ + private var driverXbox: XboxController = XboxController(0) + /** + * + */ + private var shooterXbox: XboxController = XboxController(1) + + /** + * The container for the robot. Contains subsystems, OI devices, and commands. + */ + init { + intakeCommand = IntakeCommand(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } + shootCommand = ShootCommand(shooter) { MathUtil.applyDeadband(shooterXbox.rightTriggerAxis, 0.1) * 5700 } + aimAtLimelightCommand = AimAtLimelightCommand(drivebase, VisionSubsystem.instance) + rotateCommand = RotateCommand(drivebase) + driveToPoseCommand = ShootCommand(shooter, { 4000.0 }).alongWith( + drivebase.driveToPose( + Pose2d( + Translation2d( + 2.720, + 2.579 + ), Rotation2d.fromDegrees(180.0) + ) + ).andThen(drivebase.driveToPose(Pose2d(Translation2d(2.720, 2.579), Rotation2d.fromDegrees(180.0)))) + .andThen(AimAtLimelightCommand(drivebase, VisionSubsystem.instance)) + .andThen(IntakeCommand(intake, { 1.0 })) + ) + aimAndPickUpNoteCommand = AimAndPickUpNoteCommand(drivebase, VisionSubsystem.instance, intake) + armSysIdCommand = ArmSubsystem.generateSysIdCommand(armSubsystem.sysId, 2.0, 3.5, 1.5) + moveArmCommand = MoveArmCommand { MathUtil.applyDeadband(shooterXbox.rightY, 0.1) } + intakeCommand2 = IntakeCommand2(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } + val invert = invert + + absoluteFieldDrive = AbsoluteFieldDrive( + drivebase, + { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, + { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, + { driverXbox.rightX * invert }) + // Applies deadbands and inverts controls because joysticks + // are back-right positive while robot + // controls are front-left positive + // left stick controls translation + // right stick controls the desired angle NOT angular rotation + val driveFieldOrientedDirectAngle = drivebase.driveCommand( + { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, + { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, + { driverXbox.rightX * invert }, + { driverXbox.rightY * invert }) + val closedAbsoluteDriveAdv = AbsoluteDriveAdv( + drivebase, + { MathUtil.applyDeadband(driverXbox.leftY * invert, OperatorConstants.LEFT_Y_DEADBAND) }, + { MathUtil.applyDeadband(driverXbox.leftX * invert, OperatorConstants.LEFT_X_DEADBAND) }, + { MathUtil.applyDeadband(driverXbox.rightX * invert, OperatorConstants.RIGHT_X_DEADBAND) }, + { driverXbox.yButtonPressed }, + { driverXbox.aButtonPressed }, + { driverXbox.xButtonPressed }, + { driverXbox.bButtonPressed }) + + // Applies deadbands and inverts controls because joysticks + // are back-right positive while robot + // controls are front-left positive + // left stick controls translation + // right stick controls the angular velocity of the robot + val driveFieldOrientedAnglularVelocity = drivebase.driveCommand( + { -MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, + { -MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, + { driverXbox.getRawAxis(4) * invert }) + + val driveFieldOrientedDirectAngleSim = drivebase.simDriveCommand( + { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, + { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, + { driverXbox.getRawAxis(2) * invert }) + + val sysIdForDrive = drivebase.sysIdDriveMotorCommand() + val sysIdForAngle = drivebase.sysIdAngleMotorCommand() + + val driveFieldOrientedDirectAngleForTesting = drivebase.driveCommand( + { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) }, + { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) }, + { driverXbox.rightX }, + { driverXbox.rightY }) + + drivebase.defaultCommand = + if (!RobotBase.isSimulation()) driveFieldOrientedAnglularVelocity else driveFieldOrientedDirectAngleSim + + // Configure the trigger bindings + configureBindings() + } + + private val invert: Int + get() { + val alliance = DriverStation.getAlliance() + val invert = if (alliance.isPresent && alliance.get() == Alliance.Red) { + -1 + } else { + 1 + } + + + return invert + } + + /** + * Use this method to define your trigger->command mappings. Triggers can be created via the + * [Trigger.Trigger] constructor with an arbitrary predicate, or via the + * named factories in [edu.wpi.first.wpilibj2.command.button.CommandGenericHID]'s subclasses for + * [Xbox][CommandXboxController]/[PS4][edu.wpi.first.wpilibj2.command.button.CommandPS4Controller] + * controllers or [Flight joysticks][edu.wpi.first.wpilibj2.command.button.CommandJoystick]. + */ + private fun configureBindings() { + // Schedule `ExampleCommand` when `exampleCondition` changes to `true` + + JoystickButton(driverXbox, 1).onTrue((InstantCommand({ drivebase.zeroGyro() }))) + JoystickButton(driverXbox, XboxController.Button.kX.value).whileTrue(aimAtLimelightCommand) + JoystickButton(driverXbox, 2).whileTrue(driveToPoseCommand) + JoystickButton(driverXbox, XboxController.Button.kY.value).whileTrue(rotateCommand) + + + JoystickButton( + shooterXbox, + XboxController.Button.kLeftBumper.value + ).whileTrue(intakeCommand) // independent of speed + JoystickButton(driverXbox, XboxController.Button.kLeftBumper.value).whileTrue(intakeCommand) + JoystickButton(driverXbox, XboxController.Button.kY.value).whileTrue(aimAndPickUpNoteCommand) + + JoystickButton(shooterXbox, XboxController.Button.kA.value).whileTrue(moveArmCommand) + JoystickButton( + shooterXbox, + XboxController.Button.kB.value + ).whileTrue(shooter.generateSysIdCommand(shooter.sysIdRoutine, 2.0, 10.0, 10.0)) + + JoystickButton(shooterXbox, XboxController.Button.kRightBumper.value).whileTrue(intakeCommand2) + + + + shooter.defaultCommand = shootCommand + armSubsystem.defaultCommand = moveArmCommand } + /** + * + */ + val autonomousCommand: Command + /** + * Use this to pass the autonomous command to the main [Robot] class. + * + * @return the command to run in autonomous + */ + get() =// An example command will be run in autonomous + drivebase.getAutonomousCommand("New Auto") + + /** + * + */ + fun setDriveMode() { + //drivebase.setDefaultCommand(); + } - return invert; - } - - /** - * Use this method to define your trigger->command mappings. Triggers can be created via the - * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary predicate, or via the - * named factories in {@link edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for - * {@link CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller PS4} - * controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight joysticks}. - */ - private void configureBindings() { - // Schedule `ExampleCommand` when `exampleCondition` changes to `true` - - new JoystickButton(driverXbox, 1).onTrue((new InstantCommand(drivebase::zeroGyro))); - new JoystickButton(driverXbox, XboxController.Button.kX.value).whileTrue(aimAtLimelightCommand); - new JoystickButton(driverXbox, 2).whileTrue(driveToPoseCommand); - new JoystickButton(driverXbox, XboxController.Button.kY.value).whileTrue(rotateCommand); - - - new JoystickButton(shooterXbox, XboxController.Button.kLeftBumper.value).whileTrue(intakeCommand); // independent of speed - new JoystickButton(driverXbox, XboxController.Button.kLeftBumper.value).whileTrue(intakeCommand); - new JoystickButton(driverXbox, XboxController.Button.kY.value).whileTrue(aimAndPickUpNoteCommand); - - new JoystickButton(shooterXbox,XboxController.Button.kA.value).whileTrue(armSysIdCommand); - new JoystickButton(shooterXbox, XboxController.Button.kB.value).whileTrue(shooter.generateSysIdCommand(shooter.getSysIdRoutine(), 2, 10, 10)); - - shooter.setDefaultCommand(shootCommand); - armSubsystem.setDefaultCommand(moveArmCommand); - } - - /** - * Use this to pass the autonomous command to the main {@link Robot} class. - * - * @return the command to run in autonomous - */ - public Command getAutonomousCommand() { - // An example command will be run in autonomous - return drivebase.getAutonomousCommand("New Auto"); - } - - public void setDriveMode() { - //drivebase.setDefaultCommand(); - } - - public void setMotorBrake(boolean brake) { - drivebase.setMotorBrake(brake); - } + /** + * + */ + fun setMotorBrake(brake: Boolean) { + drivebase.setMotorBrake(brake) + } } \ No newline at end of file diff --git a/src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.kt b/src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.kt index cc8167d..415ef6e 100644 --- a/src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.kt +++ b/src/main/java/frc/robot/commands/AimAndPickUpNoteCommand.kt @@ -1,63 +1,63 @@ -package frc.robot.commands; - -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.VisionSubsystem; -import frc.robot.subsystems.intake.Intake; -import frc.robot.subsystems.SwerveSubsystem; -import frc.robot.util.LimelightHelpers; - - -public class AimAndPickUpNoteCommand extends Command { - private final SwerveSubsystem swerveSubsystem; - private final VisionSubsystem visionSubsystem; - private final Intake intake; - - - public AimAndPickUpNoteCommand(SwerveSubsystem swerveSubsystem, VisionSubsystem visionSubsystem, Intake intake) { - this.swerveSubsystem = swerveSubsystem; - this.visionSubsystem = visionSubsystem; - this.intake = intake; - - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.swerveSubsystem, this.visionSubsystem, this.intake); - } - - - /** - * The initial subroutine of a command. Called once when the command is initially scheduled. - */ - @Override - public void initialize() { - - } - - @Override - public void execute() { - intake.set(0.5, 0.25); - swerveSubsystem.getSwerveDrive().drive(new Translation2d(-visionSubsystem.limelight_range_proportional() / 5, 0), -visionSubsystem.limelight_aim_proportional_front() / 5, false, false); - - - } - - @Override - public boolean isFinished() { - return !LimelightHelpers.getTV("limelight-front"); - } - - /** - * The action to take when the command ends. Called when either the command - * finishes normally -- that is, it is called when {@link #isFinished()} returns - * true -- or when it is interrupted/canceled. This is where you may want to - * wrap up loose ends, like shutting off a motor that was being used in the command. - * - * @param interrupted whether the command was interrupted/canceled - */ - @Override - public void end(boolean interrupted) { - intake.set(0,0); - swerveSubsystem.getSwerveDrive().drive(new Translation2d(0, 0), 0, false, false); - } +package frc.robot.commands + +import edu.wpi.first.math.geometry.Translation2d +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.subsystems.VisionSubsystem +import frc.robot.subsystems.intake.Intake +import frc.robot.util.LimelightHelpers + +/** + * + */ +class AimAndPickUpNoteCommand( + private val swerveSubsystem: SwerveSubsystem, + private val visionSubsystem: VisionSubsystem, + private val intake: Intake +) : Command() { + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.swerveSubsystem, this.visionSubsystem, this.intake) + } + + + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() { + } + + /** + * + */ + override fun execute() { + intake.set(0.5, 0.25) + swerveSubsystem.swerveDrive.drive( + Translation2d(-visionSubsystem.limelightRangeProportional() / 5, 0.0), + -visionSubsystem.limelightAimProportionalFront() / 5, + false, + false + ) + } + + /** + * + */ + override fun isFinished(): Boolean { + return !LimelightHelpers.getTV("limelight-front") + } + + /** + * The action to take when the command ends. Called when either the command + * finishes normally -- that is, it is called when [.isFinished] returns + * true -- or when it is interrupted/canceled. This is where you may want to + * wrap up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + override fun end(interrupted: Boolean) { + intake[0.0] = 0.0 + swerveSubsystem.swerveDrive.drive(Translation2d(0.0, 0.0), 0.0, false, false) + } } diff --git a/src/main/java/frc/robot/commands/CalculateShooterAngleCommand.kt b/src/main/java/frc/robot/commands/CalculateShooterAngleCommand.kt new file mode 100644 index 0000000..7b62a1e --- /dev/null +++ b/src/main/java/frc/robot/commands/CalculateShooterAngleCommand.kt @@ -0,0 +1,69 @@ +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.InstantCommand +import frc.robot.subsystems.ArmSubsystem +import frc.robot.util.LimelightHelpers + +/** + * + */ +class CalculateShooterAngleCommand : InstantCommand() { + /** + * + */ + var angle: Double = 0.0 + private val armSubsystem: ArmSubsystem = ArmSubsystem.instance + + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.armSubsystem) + } + + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() { + armSubsystem.getArmAngleForShooting(LimelightHelpers.getBotPose3d("limelight-back")) + } + + /** + * The main body of a command. Called repeatedly while the command is scheduled. + * (That is, it is called repeatedly until [.isFinished]) returns true.) + */ + override fun execute() { + armSubsystem.moveArmToAngle(angle) + } + + /** + * + * + * Returns whether this command has finished. Once a command finishes -- indicated by + * this method returning true -- the scheduler will call its [.end] method. + * + * + * Returning false will result in the command never ending automatically. It may still be + * cancelled manually or interrupted by another command. Hard coding this command to always + * return true will result in the command executing once and finishing immediately. It is + * recommended to use * [InstantCommand][edu.wpi.first.wpilibj2.command.InstantCommand] + * for such an operation. + * + * + * @return whether this command has finished. + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } + + /** + * The action to take when the command ends. Called when either the command + * finishes normally -- that is it is called when [.isFinished] returns + * true -- or when it is interrupted/canceled. This is where you may want to + * wrap up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + override fun end(interrupted: Boolean) { + } +} diff --git a/src/main/java/frc/robot/commands/ClimbCommand.kt b/src/main/java/frc/robot/commands/ClimbCommand.kt index c11f363..70a0e91 100644 --- a/src/main/java/frc/robot/commands/ClimbCommand.kt +++ b/src/main/java/frc/robot/commands/ClimbCommand.kt @@ -1,29 +1,40 @@ -package frc.robot.commands; +package frc.robot.commands -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.ClimberSubsystem; +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.ClimberSubsystem -public class ClimbCommand extends Command { - private final ClimberSubsystem climberSubsystem = ClimberSubsystem.getInstance(); +/** + * + */ +class ClimbCommand : Command() { + private val climberSubsystem: ClimberSubsystem = ClimberSubsystem.instance - public ClimbCommand() { - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.climberSubsystem); - } + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.climberSubsystem) + } - @Override - public void initialize() {} + /** + * + */ + override fun initialize() {} - @Override - public void execute() {} + /** + * + */ + override fun execute() {} - @Override - public boolean isFinished() { - // TODO: Make this return true when this Command no longer needs to run execute() - return false; - } + /** + * + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } - @Override - public void end(boolean interrupted) {} + /** + * + */ + override fun end(interrupted: Boolean) {} } diff --git a/src/main/java/frc/robot/commands/IntakeCommand.kt b/src/main/java/frc/robot/commands/IntakeCommand.kt index 54916ba..c54df7f 100644 --- a/src/main/java/frc/robot/commands/IntakeCommand.kt +++ b/src/main/java/frc/robot/commands/IntakeCommand.kt @@ -1,49 +1,44 @@ -package frc.robot.commands; - -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.SwerveSubsystem; -import frc.robot.subsystems.intake.Intake; -import frc.robot.util.Constants; - -import java.util.function.DoubleSupplier; -import java.util.prefs.PreferencesFactory; - - -public class IntakeCommand extends Command { - private final Intake intake; - private final DoubleSupplier speed; - - - public IntakeCommand(Intake intake, DoubleSupplier speed) { - this.intake = intake; - this.speed = speed; - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.intake); - - } - - @Override - public void initialize() { - - } - - @Override - public void execute() { - - intake.set(0.5, 0.25); - - } - - @Override - public boolean isFinished() { - // TODO: Make this return true when this Command no longer needs to run execute() - return false; - } - - @Override - public void end(boolean interrupted) { - intake.set(0.0, 0.0); - } +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.intake.Intake +import java.util.function.DoubleSupplier + +/** + * + */ +class IntakeCommand(private val intake: Intake, private val speed: DoubleSupplier) : Command() { + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.intake) + } + + /** + * + */ + override fun initialize() { + } + + /** + * + */ + override fun execute() { + intake[0.25] = -0.25 + } + + /** + * + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } + + /** + * + */ + override fun end(interrupted: Boolean) { + intake[0.0] = 0.0 + } } diff --git a/src/main/java/frc/robot/commands/IntakeCommand2.kt b/src/main/java/frc/robot/commands/IntakeCommand2.kt new file mode 100644 index 0000000..8c98f68 --- /dev/null +++ b/src/main/java/frc/robot/commands/IntakeCommand2.kt @@ -0,0 +1,44 @@ +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.intake.Intake +import java.util.function.DoubleSupplier + +/** + * + */ +class IntakeCommand2(private val intake: Intake, private val speed: DoubleSupplier) : Command() { + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.intake) + } + + /** + * + */ + override fun initialize() { + } + + /** + * + */ + override fun execute() { + intake[-0.25] = 0.25 + } + + /** + * + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } + + /** + * + */ + override fun end(interrupted: Boolean) { + intake[0.0] = 0.0 + } +} diff --git a/src/main/java/frc/robot/commands/MoveArmCommand.kt b/src/main/java/frc/robot/commands/MoveArmCommand.kt index 3b4fc02..0f4d15e 100644 --- a/src/main/java/frc/robot/commands/MoveArmCommand.kt +++ b/src/main/java/frc/robot/commands/MoveArmCommand.kt @@ -1,69 +1,76 @@ -package frc.robot.commands; +package frc.robot.commands -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.ArmSubsystem; +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.ArmSubsystem +import java.util.function.DoubleSupplier -import java.util.function.DoubleSupplier; +/** + * + */ +class MoveArmCommand( + /** + * + */ + var speed: DoubleSupplier) : Command() { + private val armSubsystem: ArmSubsystem = ArmSubsystem.instance + /** + * + */ + var angle: Double = 0.0 + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.armSubsystem) + } -public class MoveArmCommand extends Command { - private final ArmSubsystem armSubsystem = ArmSubsystem.getInstance(); - DoubleSupplier speed; + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() { + angle = armSubsystem.angle + } - public MoveArmCommand(DoubleSupplier speed) { - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - this.speed = speed; - addRequirements(this.armSubsystem); - } + /** + * The main body of a command. Called repeatedly while the command is scheduled. + * (That is, it is called repeatedly until [.isFinished]) returns true.) + */ + override fun execute() { + //armSubsystem.moveArmButWithVelocity(speed.getAsDouble() * 144); + angle += speed.asDouble + if (speed.asDouble != -1.0) armSubsystem.moveArmToAngle(angle) + } - /** - * The initial subroutine of a command. Called once when the command is initially scheduled. - */ - @Override - public void initialize() { + /** + * + * + * Returns whether this command has finished. Once a command finishes -- indicated by + * this method returning true -- the scheduler will call its [.end] method. + * + * + * Returning false will result in the command never ending automatically. It may still be + * cancelled manually or interrupted by another command. Hard coding this command to always + * return true will result in the command executing once and finishing immediately. It is + * recommended to use * [InstantCommand][edu.wpi.first.wpilibj2.command.InstantCommand] + * for such an operation. + * + * + * @return whether this command has finished. + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } - } - - /** - * The main body of a command. Called repeatedly while the command is scheduled. - * (That is, it is called repeatedly until {@link #isFinished()}) returns true.) - */ - @Override - public void execute() { - armSubsystem.moveArmButBetter(speed.getAsDouble() * 0.25); - } - - /** - *

- * Returns whether this command has finished. Once a command finishes -- indicated by - * this method returning true -- the scheduler will call its {@link #end(boolean)} method. - *

- * Returning false will result in the command never ending automatically. It may still be - * cancelled manually or interrupted by another command. Hard coding this command to always - * return true will result in the command executing once and finishing immediately. It is - * recommended to use * {@link edu.wpi.first.wpilibj2.command.InstantCommand InstantCommand} - * for such an operation. - *

- * - * @return whether this command has finished. - */ - @Override - public boolean isFinished() { - // TODO: Make this return true when this Command no longer needs to run execute() - return false; - } - - /** - * The action to take when the command ends. Called when either the command - * finishes normally -- that is it is called when {@link #isFinished()} returns - * true -- or when it is interrupted/canceled. This is where you may want to - * wrap up loose ends, like shutting off a motor that was being used in the command. - * - * @param interrupted whether the command was interrupted/canceled - */ - @Override - public void end(boolean interrupted) { - armSubsystem.moveArm(0); - } + /** + * The action to take when the command ends. Called when either the command + * finishes normally -- that is it is called when [.isFinished] returns + * true -- or when it is interrupted/canceled. This is where you may want to + * wrap up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + override fun end(interrupted: Boolean) { + armSubsystem.moveArm(0.0) + } } diff --git a/src/main/java/frc/robot/commands/RotateCommand.kt b/src/main/java/frc/robot/commands/RotateCommand.kt index 0523789..f94cd88 100644 --- a/src/main/java/frc/robot/commands/RotateCommand.kt +++ b/src/main/java/frc/robot/commands/RotateCommand.kt @@ -1,41 +1,49 @@ -package frc.robot.commands; - -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.SwerveSubsystem; - - -public class RotateCommand extends Command { - private final SwerveSubsystem drivebase; - - public RotateCommand(SwerveSubsystem swerveSubsystem) { - this.drivebase = swerveSubsystem; - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.drivebase); - } - - @Override - public void initialize() { - - } - - @Override - public void execute() { - drivebase.drive( drivebase.getSwerveController().getTargetSpeeds(0, 0, - 1 * Math.PI, - drivebase.getHeading().getRadians(), - drivebase.getSwerveDrive().getMaximumVelocity())); - } - - @Override - public boolean isFinished() { - // TODO: Make this return true when this Command no longer needs to run execute() - return false; - } - - @Override - public void end(boolean interrupted) { - - } +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem + +/** + * + */ +class RotateCommand(private val drivebase: SwerveSubsystem) : Command() { + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.drivebase) + } + + /** + * + */ + override fun initialize() { + } + + /** + * + */ + override fun execute() { + drivebase.drive( + drivebase.swerveController.getTargetSpeeds( + 0.0, 0.0, + 1 * Math.PI, + drivebase.heading.radians, + drivebase.swerveDrive.maximumVelocity + ) + ) + } + + /** + * + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } + + /** + * + */ + override fun end(interrupted: Boolean) { + } } diff --git a/src/main/java/frc/robot/commands/ShootCommand.kt b/src/main/java/frc/robot/commands/ShootCommand.kt index 990d112..f411dca 100644 --- a/src/main/java/frc/robot/commands/ShootCommand.kt +++ b/src/main/java/frc/robot/commands/ShootCommand.kt @@ -1,42 +1,44 @@ -package frc.robot.commands; - -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.shooter.Shooter; - -import java.util.function.DoubleSupplier; - - -public class ShootCommand extends Command { - private final Shooter shooter; - private final DoubleSupplier speed; - - - public ShootCommand(Shooter shooter, DoubleSupplier speed) { - this.shooter = shooter; - this.speed = speed; - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.shooter); - } - - @Override - public void initialize() { - - } - - @Override - public void execute() { - shooter.setVelocity(speed.getAsDouble(), speed.getAsDouble()); - } - - @Override - public boolean isFinished() { - // TODO: Make this return true when this Command no longer needs to run execute() - return false; - } - - @Override - public void end(boolean interrupted) { - shooter.set(0.0, 0.0); - } +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.shooter.Shooter +import java.util.function.DoubleSupplier + +/** + * + */ +class ShootCommand(private val shooter: Shooter, private val speed: DoubleSupplier) : Command() { + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.shooter) + } + + /** + * + */ + override fun initialize() { + } + + /** + * + */ + override fun execute() { + shooter.setVelocity(speed.asDouble, speed.asDouble) + } + + /** + * + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } + + /** + * + */ + override fun end(interrupted: Boolean) { + shooter[0.0] = 0.0 + } } diff --git a/src/main/java/frc/robot/commands/auto/AutoBalanceCommand.kt b/src/main/java/frc/robot/commands/auto/AutoBalanceCommand.kt index 550d5ac..433c98b 100644 --- a/src/main/java/frc/robot/commands/auto/AutoBalanceCommand.kt +++ b/src/main/java/frc/robot/commands/auto/AutoBalanceCommand.kt @@ -1,86 +1,74 @@ -package frc.robot.commands.auto; - -import edu.wpi.first.math.MathUtil; -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.SwerveSubsystem; +package frc.robot.commands.auto +import edu.wpi.first.math.MathUtil +import edu.wpi.first.math.controller.PIDController +import edu.wpi.first.math.geometry.Translation2d +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem /** * Auto Balance command using a simple PID controller. Created by Team 3512 - * ... + * [...](https://github.com/frc3512/Robot-2023/blob/main/src/main/java/frc3512/robot/commands/AutoBalance.java) */ -public class AutoBalanceCommand extends Command -{ - - private final SwerveSubsystem swerveSubsystem; - private final PIDController controller; - - public AutoBalanceCommand(SwerveSubsystem swerveSubsystem) - { - this.swerveSubsystem = swerveSubsystem; - controller = new PIDController(1.0, 0.0, 0.0); - controller.setTolerance(1); - controller.setSetpoint(0.0); - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.swerveSubsystem); - } +class AutoBalanceCommand(private val swerveSubsystem: SwerveSubsystem) : Command() { + private val controller = PIDController(1.0, 0.0, 0.0) - /** - * The initial subroutine of a command. Called once when the command is initially scheduled. - */ - @Override - public void initialize() - { + init { + controller.setTolerance(1.0) + controller.setpoint = 0.0 + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.swerveSubsystem) + } - } + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() { + } - /** - * The main body of a command. Called repeatedly while the command is scheduled. (That is, it is called repeatedly - * until {@link #isFinished()}) returns true.) - */ - @Override - public void execute() - { - SmartDashboard.putBoolean("At Tolerance", controller.atSetpoint()); + /** + * The main body of a command. Called repeatedly while the command is scheduled. (That is, it is called repeatedly + * until [.isFinished]) returns true.) + */ + override fun execute() { + SmartDashboard.putBoolean("At Tolerance", controller.atSetpoint()) - double translationVal = MathUtil.clamp(controller.calculate(swerveSubsystem.getPitch().getDegrees(), 0.0), -0.5, - 0.5); - swerveSubsystem.drive(new Translation2d(translationVal, 0.0), 0.0, true); - } + val translationVal = MathUtil.clamp( + controller.calculate(swerveSubsystem.pitch.degrees, 0.0), -0.5, + 0.5 + ) + swerveSubsystem.drive(Translation2d(translationVal, 0.0), 0.0, true) + } - /** - *

- * Returns whether this command has finished. Once a command finishes -- indicated by this method returning true -- - * the scheduler will call its {@link #end(boolean)} method. - *

- * Returning false will result in the command never ending automatically. It may still be cancelled manually or - * interrupted by another command. Hard coding this command to always return true will result in the command executing - * once and finishing immediately. It is recommended to use * - * {@link edu.wpi.first.wpilibj2.command.InstantCommand InstantCommand} for such an operation. - *

- * - * @return whether this command has finished. - */ - @Override - public boolean isFinished() - { - return controller.atSetpoint(); - } + /** + * + * + * Returns whether this command has finished. Once a command finishes -- indicated by this method returning true -- + * the scheduler will call its [.end] method. + * + * + * Returning false will result in the command never ending automatically. It may still be cancelled manually or + * interrupted by another command. Hard coding this command to always return true will result in the command executing + * once and finishing immediately. It is recommended to use * + * [InstantCommand][edu.wpi.first.wpilibj2.command.InstantCommand] for such an operation. + * + * + * @return whether this command has finished. + */ + override fun isFinished(): Boolean { + return controller.atSetpoint() + } - /** - * The action to take when the command ends. Called when either the command finishes normally -- that is it is called - * when {@link #isFinished()} returns true -- or when it is interrupted/canceled. This is where you may want to wrap - * up loose ends, like shutting off a motor that was being used in the command. - * - * @param interrupted whether the command was interrupted/canceled - */ - @Override - public void end(boolean interrupted) - { - swerveSubsystem.lock(); - } + /** + * The action to take when the command ends. Called when either the command finishes normally -- that is it is called + * when [.isFinished] returns true -- or when it is interrupted/canceled. This is where you may want to wrap + * up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + override fun end(interrupted: Boolean) { + swerveSubsystem.lock() + } } diff --git a/src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.kt b/src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.kt index 23b56b5..42bf115 100644 --- a/src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.kt +++ b/src/main/java/frc/robot/commands/drivebase/AbsoluteDrive.kt @@ -1,121 +1,108 @@ // 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.commands.drivebase -package frc.robot.commands.drivebase; - -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.util.Constants; -import frc.robot.subsystems.SwerveSubsystem; -import swervelib.SwerveController; -import swervelib.math.SwerveMath; - -import java.util.List; -import java.util.function.DoubleSupplier; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.util.Constants +import swervelib.SwerveController +import swervelib.math.SwerveMath +import java.util.function.DoubleSupplier /** * An example command that uses an example subsystem. */ -public class AbsoluteDrive extends Command -{ - - private final SwerveSubsystem swerve; - private final DoubleSupplier vX, vY; - private final DoubleSupplier headingHorizontal, headingVertical; - private boolean initRotation = false; - - /** - * Used to drive a swerve robot in full field-centric mode. vX and vY supply translation inputs, where x is - * torwards/away from alliance wall and y is left/right. headingHorzontal and headingVertical are the Cartesian - * coordinates from which the robot's angle will be derived— they will be converted to a polar angle, which the robot - * will rotate to. - * - * @param swerve The swerve drivebase subsystem. - * @param vX DoubleSupplier that supplies the x-translation joystick input. Should be in the range -1 - * to 1 with deadband already accounted for. Positive X is away from the alliance wall. - * @param vY DoubleSupplier that supplies the y-translation joystick input. Should be in the range -1 - * to 1 with deadband already accounted for. Positive Y is towards the left wall when - * looking through the driver station glass. - * @param headingHorizontal DoubleSupplier that supplies the horizontal component of the robot's heading angle. In the - * robot coordinate system, this is along the same axis as vY. Should range from -1 to 1 with - * no deadband. Positive is towards the left wall when looking through the driver station - * glass. - * @param headingVertical DoubleSupplier that supplies the vertical component of the robot's heading angle. In the - * robot coordinate system, this is along the same axis as vX. Should range from -1 to 1 - * with no deadband. Positive is away from the alliance wall. - */ - public AbsoluteDrive(SwerveSubsystem swerve, DoubleSupplier vX, DoubleSupplier vY, DoubleSupplier headingHorizontal, - DoubleSupplier headingVertical) - { - this.swerve = swerve; - this.vX = vX; - this.vY = vY; - this.headingHorizontal = headingHorizontal; - this.headingVertical = headingVertical; - - addRequirements(swerve); - } - - @Override - public void initialize() - { - initRotation = true; - } - - // Called every time the scheduler runs while the command is scheduled. - @Override - public void execute() - { - - // Get the desired chassis speeds based on a 2 joystick module. - ChassisSpeeds desiredSpeeds = swerve.getTargetSpeeds(vX.getAsDouble(), vY.getAsDouble(), - headingHorizontal.getAsDouble(), - headingVertical.getAsDouble()); - - // Prevent Movement After Auto - if (initRotation) - { - if (headingHorizontal.getAsDouble() == 0 && headingVertical.getAsDouble() == 0) - { - // Get the curretHeading - Rotation2d firstLoopHeading = swerve.getHeading(); - - // Set the Current Heading to the desired Heading - desiredSpeeds = swerve.getTargetSpeeds(0, 0, firstLoopHeading.getSin(), firstLoopHeading.getCos()); - } - //Dont Init Rotation Again - initRotation = false; +class AbsoluteDrive( + private val swerve: SwerveSubsystem, + private val vX: DoubleSupplier, + private val vY: DoubleSupplier, + private val headingHorizontal: DoubleSupplier, + private val headingVertical: DoubleSupplier +) : Command() { + private var initRotation = false + + /** + * Used to drive a swerve robot in full field-centric mode. vX and vY supply translation inputs, where x is + * torwards/away from alliance wall and y is left/right. headingHorzontal and headingVertical are the Cartesian + * coordinates from which the robot's angle will be derived— they will be converted to a polar angle, which the robot + * will rotate to. + * + * @param swerve The swerve drivebase subsystem. + * @param vX DoubleSupplier that supplies the x-translation joystick input. Should be in the range -1 + * to 1 with deadband already accounted for. Positive X is away from the alliance wall. + * @param vY DoubleSupplier that supplies the y-translation joystick input. Should be in the range -1 + * to 1 with deadband already accounted for. Positive Y is towards the left wall when + * looking through the driver station glass. + * @param headingHorizontal DoubleSupplier that supplies the horizontal component of the robot's heading angle. In the + * robot coordinate system, this is along the same axis as vY. Should range from -1 to 1 with + * no deadband. Positive is towards the left wall when looking through the driver station + * glass. + * @param headingVertical DoubleSupplier that supplies the vertical component of the robot's heading angle. In the + * robot coordinate system, this is along the same axis as vX. Should range from -1 to 1 + * with no deadband. Positive is away from the alliance wall. + */ + init { + addRequirements(swerve) } - // Limit velocity to prevent tippy - Translation2d translation = SwerveController.getTranslation2d(desiredSpeeds); - translation = SwerveMath.limitVelocity(translation, swerve.getFieldVelocity(), swerve.getPose(), - Constants.LOOP_TIME, Constants.ROBOT_MASS, List.of(Constants.CHASSIS), - swerve.getSwerveDriveConfiguration()); - SmartDashboard.putNumber("LimitedTranslation", translation.getX()); - SmartDashboard.putString("Translation", translation.toString()); - - // Make the robot move - swerve.drive(translation, desiredSpeeds.omegaRadiansPerSecond, true); - - } - - // Called once the command ends or is interrupted. - @Override - public void end(boolean interrupted) - { - } + /** + * + */ + override fun initialize() { + initRotation = true + } - // Returns true when the command should end. - @Override - public boolean isFinished() - { - return false; - } + /** + * + */// Called every time the scheduler runs while the command is scheduled. + override fun execute() { + // Get the desired chassis speeds based on a 2 joystick module. + + var desiredSpeeds = swerve.getTargetSpeeds( + vX.asDouble, vY.asDouble, + headingHorizontal.asDouble, + headingVertical.asDouble + ) + + // Prevent Movement After Auto + if (initRotation) { + if (headingHorizontal.asDouble == 0.0 && headingVertical.asDouble == 0.0) { + // Get the curretHeading + val firstLoopHeading = swerve.heading + + // Set the Current Heading to the desired Heading + desiredSpeeds = swerve.getTargetSpeeds(0.0, 0.0, firstLoopHeading.sin, firstLoopHeading.cos) + } + //Dont Init Rotation Again + initRotation = false + } + + // Limit velocity to prevent tippy + var translation = SwerveController.getTranslation2d(desiredSpeeds) + translation = SwerveMath.limitVelocity( + translation, swerve.fieldVelocity, swerve.pose, + Constants.LOOP_TIME, Constants.ROBOT_MASS, listOf(Constants.CHASSIS), + swerve.swerveDriveConfiguration + ) + SmartDashboard.putNumber("LimitedTranslation", translation.x) + SmartDashboard.putString("Translation", translation.toString()) + + // Make the robot move + swerve.drive(translation, desiredSpeeds.omegaRadiansPerSecond, true) + } + /** + * + */// Called once the command ends or is interrupted. + override fun end(interrupted: Boolean) { + } + /** + * + */// Returns true when the command should end. + override fun isFinished(): Boolean { + return false + } } diff --git a/src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.kt b/src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.kt index c13290a..15353fa 100644 --- a/src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.kt +++ b/src/main/java/frc/robot/commands/drivebase/AbsoluteDriveAdv.kt @@ -1,155 +1,134 @@ // 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.commands.drivebase; - -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.util.Constants; -import frc.robot.subsystems.SwerveSubsystem; -import swervelib.SwerveController; -import swervelib.math.SwerveMath; - -import java.util.List; -import java.util.function.BooleanSupplier; -import java.util.function.DoubleSupplier; +package frc.robot.commands.drivebase + +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.util.Constants +import swervelib.SwerveController +import swervelib.math.SwerveMath +import java.util.function.BooleanSupplier +import java.util.function.DoubleSupplier +import kotlin.math.abs /** * A more advanced Swerve Control System that has 4 buttons for which direction to face */ -public class AbsoluteDriveAdv extends Command -{ - - private final SwerveSubsystem swerve; - private final DoubleSupplier vX, vY; - private final DoubleSupplier headingAdjust; - private final BooleanSupplier lookAway, lookTowards, lookLeft, lookRight; - private boolean resetHeading = false; - - /** - * Used to drive a swerve robot in full field-centric mode. vX and vY supply translation inputs, where x is - * torwards/away from alliance wall and y is left/right. Heading Adjust changes the current heading after being - * multipied by a constant. The look booleans are shortcuts to get the robot to face a certian direction. Based off of - * ideas in https://www.chiefdelphi.com/t/experiments-with-a-swerve-steering-knob/446172 - * - * @param swerve The swerve drivebase subsystem. - * @param vX DoubleSupplier that supplies the x-translation joystick input. Should be in the range -1 to 1 - * with deadband already accounted for. Positive X is away from the alliance wall. - * @param vY DoubleSupplier that supplies the y-translation joystick input. Should be in the range -1 to 1 - * with deadband already accounted for. Positive Y is towards the left wall when looking through - * the driver station glass. - * @param headingAdjust DoubleSupplier that supplies the component of the robot's heading angle that should be - * adjusted. Should range from -1 to 1 with deadband already accounted for. - * @param lookAway Face the robot towards the opposing alliance's wall in the same direction the driver is - * facing - * @param lookTowards Face the robot towards the driver - * @param lookLeft Face the robot left - * @param lookRight Face the robot right - */ - public AbsoluteDriveAdv(SwerveSubsystem swerve, DoubleSupplier vX, DoubleSupplier vY, DoubleSupplier headingAdjust, - BooleanSupplier lookAway, BooleanSupplier lookTowards, BooleanSupplier lookLeft, - BooleanSupplier lookRight) - { - this.swerve = swerve; - this.vX = vX; - this.vY = vY; - this.headingAdjust = headingAdjust; - this.lookAway = lookAway; - this.lookTowards = lookTowards; - this.lookLeft = lookLeft; - this.lookRight = lookRight; - - addRequirements(swerve); - } - - @Override - public void initialize() - { - resetHeading = true; - } - - // Called every time the scheduler runs while the command is scheduled. - @Override - public void execute() - { - double headingX = 0; - double headingY = 0; - - // These are written to allow combinations for 45 angles - // Face Away from Drivers - if (lookAway.getAsBoolean()) - { - headingY = -1; - } - // Face Right - if (lookRight.getAsBoolean()) - { - headingX = 1; +class AbsoluteDriveAdv( + private val swerve: SwerveSubsystem, + private val vX: DoubleSupplier, + private val vY: DoubleSupplier, + private val headingAdjust: DoubleSupplier, + private val lookAway: BooleanSupplier, + private val lookTowards: BooleanSupplier, + private val lookLeft: BooleanSupplier, + private val lookRight: BooleanSupplier +) : Command() { + private var resetHeading = false + + /** + * Used to drive a swerve robot in full field-centric mode. vX and vY supply translation inputs, where x is + * torwards/away from alliance wall and y is left/right. Heading Adjust changes the current heading after being + * multipied by a constant. The look booleans are shortcuts to get the robot to face a certian direction. Based off of + * ideas in https://www.chiefdelphi.com/t/experiments-with-a-swerve-steering-knob/446172 + * + * @param swerve The swerve drivebase subsystem. + * @param vX DoubleSupplier that supplies the x-translation joystick input. Should be in the range -1 to 1 + * with deadband already accounted for. Positive X is away from the alliance wall. + * @param vY DoubleSupplier that supplies the y-translation joystick input. Should be in the range -1 to 1 + * with deadband already accounted for. Positive Y is towards the left wall when looking through + * the driver station glass. + * @param headingAdjust DoubleSupplier that supplies the component of the robot's heading angle that should be + * adjusted. Should range from -1 to 1 with deadband already accounted for. + * @param lookAway Face the robot towards the opposing alliance's wall in the same direction the driver is + * facing + * @param lookTowards Face the robot towards the driver + * @param lookLeft Face the robot left + * @param lookRight Face the robot right + */ + init { + addRequirements(swerve) } - // Face Left - if (lookLeft.getAsBoolean()) - { - headingX = -1; - } - // Face Towards the Drivers - if (lookTowards.getAsBoolean()) - { - headingY = 1; - } - - // Prevent Movement After Auto - if (resetHeading) - { - if (headingX == 0 && headingY == 0 && Math.abs(headingAdjust.getAsDouble()) > 0) - { - // Get the curret Heading - Rotation2d currentHeading = swerve.getHeading(); - // Set the Current Heading to the desired Heading - headingX = currentHeading.getSin(); - headingY = currentHeading.getCos(); - } - //Dont reset Heading Again - resetHeading = false; + /** + * + */ + override fun initialize() { + resetHeading = true } - ChassisSpeeds desiredSpeeds = swerve.getTargetSpeeds(vX.getAsDouble(), vY.getAsDouble(), headingX, headingY); - - // Limit velocity to prevent tippy - Translation2d translation = SwerveController.getTranslation2d(desiredSpeeds); - translation = SwerveMath.limitVelocity(translation, swerve.getFieldVelocity(), swerve.getPose(), - Constants.LOOP_TIME, Constants.ROBOT_MASS, List.of(Constants.CHASSIS), - swerve.getSwerveDriveConfiguration()); - SmartDashboard.putNumber("LimitedTranslation", translation.getX()); - SmartDashboard.putString("Translation", translation.toString()); - - // Make the robot move - if (headingX == 0 && headingY == 0 && Math.abs(headingAdjust.getAsDouble()) > 0) - { - resetHeading = true; - swerve.drive(translation, (Constants.OperatorConstants.TURN_CONSTANT * -headingAdjust.getAsDouble()), true); - } else - { - swerve.drive(translation, desiredSpeeds.omegaRadiansPerSecond, true); + /** + * + */// Called every time the scheduler runs while the command is scheduled. + override fun execute() { + var headingX = 0.0 + var headingY = 0.0 + + // These are written to allow combinations for 45 angles + // Face Away from Drivers + if (lookAway.asBoolean) { + headingY = -1.0 + } + // Face Right + if (lookRight.asBoolean) { + headingX = 1.0 + } + // Face Left + if (lookLeft.asBoolean) { + headingX = -1.0 + } + // Face Towards the Drivers + if (lookTowards.asBoolean) { + headingY = 1.0 + } + + // Prevent Movement After Auto + if (resetHeading) { + if (headingX == 0.0 && headingY == 0.0 && abs(headingAdjust.asDouble) > 0) { + // Get the curret Heading + val currentHeading = swerve.heading + + // Set the Current Heading to the desired Heading + headingX = currentHeading.sin + headingY = currentHeading.cos + } + //Dont reset Heading Again + resetHeading = false + } + + val desiredSpeeds = swerve.getTargetSpeeds(vX.asDouble, vY.asDouble, headingX, headingY) + + // Limit velocity to prevent tippy + var translation = SwerveController.getTranslation2d(desiredSpeeds) + translation = SwerveMath.limitVelocity( + translation, swerve.fieldVelocity, swerve.pose, + Constants.LOOP_TIME, Constants.ROBOT_MASS, listOf(Constants.CHASSIS), + swerve.swerveDriveConfiguration + ) + SmartDashboard.putNumber("LimitedTranslation", translation.x) + SmartDashboard.putString("Translation", translation.toString()) + + // Make the robot move + if (headingX == 0.0 && headingY == 0.0 && abs(headingAdjust.asDouble) > 0) { + resetHeading = true + swerve.drive(translation, (Constants.OperatorConstants.TURN_CONSTANT * -headingAdjust.asDouble), true) + } else { + swerve.drive(translation, desiredSpeeds.omegaRadiansPerSecond, true) + } } - } - - // Called once the command ends or is interrupted. - @Override - public void end(boolean interrupted) - { - } - - // Returns true when the command should end. - @Override - public boolean isFinished() - { - return false; - } + /** + * + */// Called once the command ends or is interrupted. + override fun end(interrupted: Boolean) { + } + /** + * + */// Returns true when the command should end. + override fun isFinished(): Boolean { + return false + } } diff --git a/src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.kt b/src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.kt index e9802e8..f97134f 100644 --- a/src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.kt +++ b/src/main/java/frc/robot/commands/drivebase/AbsoluteFieldDrive.kt @@ -1,96 +1,84 @@ // 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.commands.drivebase; - -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.util.Constants; -import frc.robot.subsystems.SwerveSubsystem; -import swervelib.SwerveController; -import swervelib.math.SwerveMath; - -import java.util.List; -import java.util.function.DoubleSupplier; +package frc.robot.commands.drivebase + +import edu.wpi.first.math.geometry.Rotation2d +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.util.Constants +import swervelib.SwerveController +import swervelib.math.SwerveMath +import java.util.List +import java.util.function.DoubleSupplier /** * An example command that uses an example subsystem. */ -public class AbsoluteFieldDrive extends Command -{ - - private final SwerveSubsystem swerve; - private final DoubleSupplier vX, vY, heading; - - /** - * Used to drive a swerve robot in full field-centric mode. vX and vY supply translation inputs, where x is - * torwards/away from alliance wall and y is left/right. headingHorzontal and headingVertical are the Cartesian - * coordinates from which the robot's angle will be derived— they will be converted to a polar angle, which the robot - * will rotate to. - * - * @param swerve The swerve drivebase subsystem. - * @param vX DoubleSupplier that supplies the x-translation joystick input. Should be in the range -1 to 1 with - * deadband already accounted for. Positive X is away from the alliance wall. - * @param vY DoubleSupplier that supplies the y-translation joystick input. Should be in the range -1 to 1 with - * deadband already accounted for. Positive Y is towards the left wall when looking through the driver - * station glass. - * @param heading DoubleSupplier that supplies the robot's heading angle. - */ - public AbsoluteFieldDrive(SwerveSubsystem swerve, DoubleSupplier vX, DoubleSupplier vY, - DoubleSupplier heading) - { - this.swerve = swerve; - this.vX = vX; - this.vY = vY; - this.heading = heading; - - addRequirements(swerve); - } - - @Override - public void initialize() - { - } - - // Called every time the scheduler runs while the command is scheduled. - @Override - public void execute() - { - - // Get the desired chassis speeds based on a 2 joystick module. - - ChassisSpeeds desiredSpeeds = swerve.getTargetSpeeds(vX.getAsDouble(), vY.getAsDouble(), - new Rotation2d(heading.getAsDouble() * Math.PI)); - - // Limit velocity to prevent tippy - Translation2d translation = SwerveController.getTranslation2d(desiredSpeeds); - translation = SwerveMath.limitVelocity(translation, swerve.getFieldVelocity(), swerve.getPose(), - Constants.LOOP_TIME, Constants.ROBOT_MASS, List.of(Constants.CHASSIS), - swerve.getSwerveDriveConfiguration()); - SmartDashboard.putNumber("LimitedTranslation", translation.getX()); - SmartDashboard.putString("Translation", translation.toString()); - - // Make the robot move - swerve.drive(translation, desiredSpeeds.omegaRadiansPerSecond, true); - - } - - // Called once the command ends or is interrupted. - @Override - public void end(boolean interrupted) - { - } - - // Returns true when the command should end. - @Override - public boolean isFinished() - { - return false; - } - - +class AbsoluteFieldDrive( + private val swerve: SwerveSubsystem, private val vX: DoubleSupplier, private val vY: DoubleSupplier, + private val heading: DoubleSupplier +) : Command() { + /** + * Used to drive a swerve robot in full field-centric mode. vX and vY supply translation inputs, where x is + * torwards/away from alliance wall and y is left/right. headingHorzontal and headingVertical are the Cartesian + * coordinates from which the robot's angle will be derived— they will be converted to a polar angle, which the robot + * will rotate to. + * + * @param swerve The swerve drivebase subsystem. + * @param vX DoubleSupplier that supplies the x-translation joystick input. Should be in the range -1 to 1 with + * deadband already accounted for. Positive X is away from the alliance wall. + * @param vY DoubleSupplier that supplies the y-translation joystick input. Should be in the range -1 to 1 with + * deadband already accounted for. Positive Y is towards the left wall when looking through the driver + * station glass. + * @param heading DoubleSupplier that supplies the robot's heading angle. + */ + init { + addRequirements(swerve) + } + + /** + * + */ + override fun initialize() { + } + + /** + * + */// Called every time the scheduler runs while the command is scheduled. + override fun execute() { + // Get the desired chassis speeds based on a 2 joystick module. + + val desiredSpeeds = swerve.getTargetSpeeds( + vX.asDouble, vY.asDouble, + Rotation2d(heading.asDouble * Math.PI) + ) + + // Limit velocity to prevent tippy + var translation = SwerveController.getTranslation2d(desiredSpeeds) + translation = SwerveMath.limitVelocity( + translation, swerve.fieldVelocity, swerve.pose, + Constants.LOOP_TIME, Constants.ROBOT_MASS, listOf(Constants.CHASSIS), + swerve.swerveDriveConfiguration + ) + SmartDashboard.putNumber("LimitedTranslation", translation.x) + SmartDashboard.putString("Translation", translation.toString()) + + // Make the robot move + swerve.drive(translation, desiredSpeeds.omegaRadiansPerSecond, true) + } + + /** + * + */// Called once the command ends or is interrupted. + override fun end(interrupted: Boolean) { + } + + /** + * + */// Returns true when the command should end. + override fun isFinished(): Boolean { + return false + } } diff --git a/src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.kt b/src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.kt index ec52542..688a21f 100644 --- a/src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.kt +++ b/src/main/java/frc/robot/commands/drivebase/AimAtLimelightCommand.kt @@ -1,68 +1,86 @@ -package frc.robot.commands.drivebase; +package frc.robot.commands.drivebase -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.SwerveSubsystem; -import frc.robot.subsystems.VisionSubsystem; -import frc.robot.subsystems.intake.Intake; -import frc.robot.util.LimelightHelpers; +import edu.wpi.first.math.geometry.Translation2d +import edu.wpi.first.wpilibj.DriverStation +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.subsystems.VisionSubsystem +import frc.robot.util.LimelightHelpers.getTV +import frc.robot.util.LimelightHelpers.getTX +import frc.robot.util.LimelightHelpers.setPipelineIndex +import kotlin.math.abs +/** + * + */ +class AimAtLimelightCommand( + private val swerveSubsystem: SwerveSubsystem, + private val visionSubsystem: VisionSubsystem +) : Command() { + private var isRedAlliance = false + /** + * + */ + private var rotateCW: Double = 0.0 + /** + * + */ + var speed: Double = 0.0 -public class AimAtLimelightCommand extends Command { - private final SwerveSubsystem swerveSubsystem; - private final VisionSubsystem visionSubsystem; - - private boolean isRedAlliance; - double rotateCW, speed; - - public AimAtLimelightCommand(SwerveSubsystem swerveSubsystem, VisionSubsystem visionSubsystem) { - this.swerveSubsystem = swerveSubsystem; - this.visionSubsystem = visionSubsystem; - - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.swerveSubsystem, this.visionSubsystem); - } - - - /** - * The initial subroutine of a command. Called once when the command is initially scheduled. - */ - @Override - public void initialize() { - LimelightHelpers.setPipelineIndex("limelight-back", 1); - isRedAlliance = (DriverStation.getAlliance().get() == DriverStation.Alliance.Red); - - // Take the current angle and see if it's faster to rotate clockwise or counterclockwise to get to 180 degrees - double currentAngle = swerveSubsystem.getHeading().getDegrees(); // (-180, 180] - speed = 2.5; - rotateCW = (currentAngle > 0) ? -speed : speed; + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.swerveSubsystem, this.visionSubsystem) + } - } - @Override - public void execute() { + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() { + setPipelineIndex("limelight-back", 1) + isRedAlliance = (DriverStation.getAlliance().get() == DriverStation.Alliance.Red) - if (LimelightHelpers.getTV("limelight-back")) { - swerveSubsystem.getSwerveDrive().drive(new Translation2d(0, 0), visionSubsystem.limelight_aim_proportional_back() / 5, false, false); - } else { - if (swerveSubsystem.getHeading().getDegrees() < 140 && swerveSubsystem.getHeading().getDegrees() > -140) - swerveSubsystem.getSwerveDrive().drive(new Translation2d(0, 0), rotateCW, false, false); - else swerveSubsystem.getSwerveDrive().drive(new Translation2d(0, 0), rotateCW / speed / 2, false, false); + // Take the current angle and see if it's faster to rotate clockwise or counterclockwise to get to 180 degrees + val currentAngle = swerveSubsystem.heading.degrees // (-180, 180] + speed = 2.5 + rotateCW = if ((currentAngle > 0)) -speed else speed } - } + /** + * + */ + override fun execute() { + if (getTV("limelight-back")) { + swerveSubsystem.swerveDrive.drive( + Translation2d(0.0, 0.0), + visionSubsystem.limelightAimProportionalBack() / 5, + false, + false + ) + } else { + if (swerveSubsystem.heading.degrees < 140 && swerveSubsystem.heading.degrees > -140) swerveSubsystem.swerveDrive.drive( + Translation2d(0.0, 0.0), + rotateCW, + false, + false + ) + else swerveSubsystem.swerveDrive.drive(Translation2d(0.0, 0.0), rotateCW / speed / 2, false, false) + } + } - @Override - public boolean isFinished() { - return (Math.abs(LimelightHelpers.getTX("limelight-back")) < 1.0) && LimelightHelpers.getTV("limelight-back"); - } + /** + * + */ + override fun isFinished(): Boolean { + return (abs(getTX("limelight-back")) < 1.0) && getTV("limelight-back") + } - @Override - public void end(boolean interrupted) { - LimelightHelpers.setPipelineIndex("limelight-back", 0); - swerveSubsystem.getSwerveDrive().drive(new Translation2d(0, 0), 0, false, false); - } + /** + * + */ + override fun end(interrupted: Boolean) { + setPipelineIndex("limelight-back", 0) + swerveSubsystem.swerveDrive.drive(Translation2d(0.0, 0.0), 0.0, false, false) + } } diff --git a/src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.kt b/src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.kt index 674e0c0..5163ec9 100644 --- a/src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.kt +++ b/src/main/java/frc/robot/commands/drivebase/AimAtTargetCommand.kt @@ -1,42 +1,46 @@ -package frc.robot.commands.drivebase; - -import edu.wpi.first.math.MathUtil; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.subsystems.SwerveSubsystem; -import frc.robot.util.LimelightHelpers; - - -public class AimAtTargetCommand extends Command { - private final SwerveSubsystem swerveSubsystem; - - public AimAtTargetCommand(SwerveSubsystem swerveSubsystem) { - this.swerveSubsystem = swerveSubsystem; - // each subsystem used by the command must be passed into the - // addRequirements() method (which takes a vararg of Subsystem) - addRequirements(this.swerveSubsystem); - } - - @Override - public void initialize() { - - } - - @Override - public void execute() { - swerveSubsystem.driveCommand(() -> 0.0, () -> 0.0, () -> -LimelightHelpers.getTX("limelight-back")); // Not sure if this will work, more math may be required. - } - - @Override - public boolean isFinished() { - // TODO: Make this return true when this Command no longer needs to run execute() - return false; - } - - @Override - public void end(boolean interrupted) { - - } +package frc.robot.commands.drivebase + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.util.LimelightHelpers.getTX + +/** + * + */ +class AimAtTargetCommand(private val swerveSubsystem: SwerveSubsystem) : Command() { + init { + // each subsystem used by the command must be passed into the + // addRequirements() method (which takes a vararg of Subsystem) + addRequirements(this.swerveSubsystem) + } + + /** + * + */ + override fun initialize() { + } + + /** + * + */ + override fun execute() { + swerveSubsystem.driveCommand( + { 0.0 }, + { 0.0 }, + { -getTX("limelight-back") }) // Not sure if this will work, more math may be required. + } + + /** + * + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return false + } + + /** + * + */ + override fun end(interrupted: Boolean) { + } } diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt index bcf3601..db5bba8 100644 --- a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt @@ -1,194 +1,233 @@ -package frc.robot.subsystems; - -import com.revrobotics.*; -import com.revrobotics.CANSparkBase.IdleMode; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.SparkAbsoluteEncoder.Type; - -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import frc.robot.util.Constants; -import org.littletonrobotics.junction.Logger; - -import static edu.wpi.first.units.Units.Volts; - -public class ArmSubsystem extends SubsystemBase { - - // With eager singleton initialization, any static variables/fields used in the - // constructor must appear before the "INSTANCE" variable so that they are initialized - // before the constructor is called when the "INSTANCE" variable initializes. - - private final CANSparkMax leftMotor; // Lead motor - private final CANSparkMax rightMotor; // Follow Motor - private final SparkLimitSwitch forwardLimitSwitch, reverseLimitSwitch; - - private final SparkPIDController pidController; - private final SparkAbsoluteEncoder encoder; - private static final double kP = 0.1; - private static final double kI = 1e-4; - private static final double kD = 1; - private static final double kIz = 0; - private static final double kFF = 0; - private static final double kMaxOutput = 1; - private static final double kMinOutput = -1; // We'll probably want to put these in the constants class later - private double maxRange; // amount of revolutions (or other unit) it takes to move the arm from min to max - - - /** - * The Singleton instance of this ArmSubsystem. Code should use the {@link #getInstance()} - * method to get the single instance (rather than trying to construct an instance of this class.) - */ - private static final ArmSubsystem INSTANCE = new ArmSubsystem(); - - /** - * Returns the Singleton instance of this ArmSubsystem. This static method should be used, - * rather than the constructor, to get the single instance of this class. For example: {@code - * ArmSubsystem.getInstance();} - */ - @SuppressWarnings("WeakerAccess") - public static ArmSubsystem getInstance() { - return INSTANCE; - } - - // Raises the arm (the right arm is set to mirror the left arm) - public void raiseArm() { - leftMotor.set(0.5); - } - - public void moveArmButBetter(double speed) { - leftMotor.set(speed); - } - - // Lowers the arm () - public void lowerArm() { - leftMotor.set(-0.5); - } - - // Control the arm via voltage - public void setVoltage(double voltage) { - leftMotor.setVoltage(voltage); - } - - // This should set the current arm location to be zero on the encoder? - // MAKE SURE THAT THE ZERO OFFSET IS SET WHEN THE ARM IS AT IT'S LOWER LIMIT - // Set lower limit before upper limit. - public void setZeroOffset() { - encoder.setZeroOffset(encoder.getPosition()); - } - - // Sets max range - public void setMaxRange() { - maxRange = encoder.getPosition(); - } - - private void rotate(double rotations) { - pidController.setReference(rotations, CANSparkMax.ControlType.kPosition); - } - - // Takes a double 0 to 1 as a parameter, where 0 is the arm at its lower limit - // and 1 at its upper limit. - public void moveArm(double p) { - double distanceFromMin = p * maxRange; - double distanceFromFinal = distanceFromMin - encoder.getPosition(); // Final - inital = delta position. - rotate(distanceFromFinal); - } - - - /** - * Creates a new instance of this ArmSubsystem. This constructor is private since this class - * is a Singleton. Code should use the {@link #getInstance()} method to get the singleton - * instance. - */ - private ArmSubsystem() { +package frc.robot.subsystems + +import com.revrobotics.* +import com.revrobotics.CANSparkBase.IdleMode +import edu.wpi.first.math.geometry.Pose3d +import edu.wpi.first.units.Measure +import edu.wpi.first.units.Units +import edu.wpi.first.units.Voltage +import edu.wpi.first.wpilibj.DriverStation +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard +import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog +import edu.wpi.first.wpilibj2.command.* +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Mechanism +import frc.robot.FieldConstants.Speaker +import frc.robot.util.Constants.MotorConstants +import org.littletonrobotics.junction.* +import kotlin.math.atan2 + +class ArmSubsystem private constructor() : SubsystemBase() { + // With eager singleton initialization, any static variables/fields used in the + // constructor must appear before the "INSTANCE" variable so that they are initialized + // before the constructor is called when the "INSTANCE" variable initializes. // TODO: Set the default command, if any, for this subsystem by calling // setDefaultCommand(command) // in the constructor or in the robot coordination class, such as RobotContainer. // Also, you can call addChild(name, sendableChild) to associate sendables with the // subsystem // such as SpeedControllers, Encoders, DigitalInputs, etc. - leftMotor = new CANSparkMax(Constants.MotorConstants.LEFT_ARM_MOTOR, MotorType.kBrushless); - rightMotor = new CANSparkMax(Constants.MotorConstants.RIGHT_ARM_MOTOR, MotorType.kBrushless); + private val leftMotor = + CANSparkMax(MotorConstants.LEFT_ARM_MOTOR, CANSparkLowLevel.MotorType.kBrushless) // Lead motor + private val rightMotor = + CANSparkMax(MotorConstants.RIGHT_ARM_MOTOR, CANSparkLowLevel.MotorType.kBrushless) // Follow Motor + private val forwardLimitSwitch: SparkLimitSwitch + private val reverseLimitSwitch: SparkLimitSwitch + + private val pidController: SparkPIDController + private val encoder: SparkAbsoluteEncoder = rightMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle) + private var maxRange = 0.0 // amount of revolutions (or other unit) it takes to move the arm from min to max + private val setpoint: Double - encoder = rightMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle); - encoder.setPositionConversionFactor(360); // 1 rotation = 360 degrees - // I don't want to have to deal with radians because of rounding errors - // The right motor will mirror the leader, but it will be inverted - rightMotor.follow(leftMotor, true); + // Raises the arm (the right arm is set to mirror the left arm) + fun raiseArm() { + leftMotor.set(0.5) + } - leftMotor.setIdleMode(IdleMode.kBrake); - leftMotor.setSmartCurrentLimit(40); - leftMotor.burnFlash(); + fun moveArmButBetter(speed: Double) { + leftMotor.set(speed) + } - rightMotor.setIdleMode(IdleMode.kBrake); - rightMotor.setSmartCurrentLimit(40); - rightMotor.burnFlash(); + fun moveArmButWithVelocity(velocity: Double) { + pidController.setReference(velocity, CANSparkBase.ControlType.kVelocity) + } - pidController = rightMotor.getPIDController(); + // Lowers the arm () + fun lowerArm() { + leftMotor.set(-0.5) + } + // Control the arm via voltage + fun setVoltage(voltage: Double) { + leftMotor.setVoltage(voltage) + } - forwardLimitSwitch = rightMotor.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); - reverseLimitSwitch = rightMotor.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); + // This should set the current arm location to be zero on the encoder? + // MAKE SURE THAT THE ZERO OFFSET IS SET WHEN THE ARM IS AT IT'S LOWER LIMIT + // Set lower limit before upper limit. + fun setZeroOffset() { + encoder.setZeroOffset(encoder.position) + } - forwardLimitSwitch.enableLimitSwitch(true); - reverseLimitSwitch.enableLimitSwitch(true); + // Sets max range + fun setMaxRange() { + maxRange = encoder.position + } + private fun rotate(rotations: Double) { + pidController.setReference(rotations, CANSparkBase.ControlType.kPosition) + } - encoder.setPositionConversionFactor(360); // 1 rotation = 360 degrees - // I don't want to have to deal with radians because of rounding errors + // Takes a double 0 to 1 as a parameter, where 0 is the arm at its lower limit + // and 1 at its upper limit. + fun moveArm(p: Double) { + val distanceFromMin = p * maxRange + val distanceFromFinal = distanceFromMin - encoder.position // Final - inital = delta position. + rotate(distanceFromFinal) + } - // + var sysId: SysIdRoutine = SysIdRoutine( + SysIdRoutine.Config( + null, null, null + ) { state: SysIdRoutineLog.State -> Logger.recordOutput("SysIdTestState", state.toString()) }, + Mechanism({ v: Measure -> this.setVoltage(v.`in`(Units.Volts)) }, null, this) + ) + + /** + * Creates a new instance of this ArmSubsystem. This constructor is private since this class + * is a Singleton. Code should use the [.getInstance] method to get the singleton + * instance. + */ + init { + encoder.setPositionConversionFactor(360.0) // 1 rotation = 360 degrees + + // I don't want to have to deal with radians because of rounding errors + + // The right motor will mirror the leader, but it will be inverted + rightMotor.follow(leftMotor, true) + + leftMotor.setIdleMode(IdleMode.kBrake) + leftMotor.setSmartCurrentLimit(40) + leftMotor.burnFlash() + + rightMotor.setIdleMode(IdleMode.kBrake) + rightMotor.setSmartCurrentLimit(40) + rightMotor.burnFlash() + + pidController = rightMotor.pidController + + + forwardLimitSwitch = rightMotor.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen) + reverseLimitSwitch = rightMotor.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen) + + forwardLimitSwitch.enableLimitSwitch(true) + reverseLimitSwitch.enableLimitSwitch(true) + + pidController.setFeedbackDevice(encoder) + pidController.setP(0.01) + pidController.setI(0.0) + pidController.setD(0.0) + pidController.setPositionPIDWrappingMinInput(-0.75) + pidController.setPositionPIDWrappingMaxInput(0.75) + + setpoint = encoder.position + + SmartDashboard.putNumber("Arm Setpoint", setpoint) + + + encoder.setPositionConversionFactor(360.0) // 1 rotation = 360 degrees + + + // I don't want to have to deal with radians because of rounding errors + + + // // pidController.setP(kP); // pidController.setI(kI); // pidController.setD(kD); // pidController.setIZone(kIz); // pidController.setFF(kFF); // pidController.setOutputRange(kMinOutput, kMaxOutput); - - } - SysIdRoutine armSysId = new SysIdRoutine( - new SysIdRoutine.Config( - null, null, null, - (state) -> Logger.recordOutput("SysIdTestState", state.toString()) - ), - new SysIdRoutine.Mechanism((v) -> this.setVoltage(v.in(Volts)), null, this) - ); - - public SysIdRoutine getSysId() { - return armSysId; - } - - public static Command generateSysIdCommand(SysIdRoutine sysIdRoutine, double delay, double quasiTimeout, - double dynamicTimeout) - { - return sysIdRoutine.quasistatic(SysIdRoutine.Direction.kForward).withTimeout(quasiTimeout) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.quasistatic(SysIdRoutine.Direction.kReverse).withTimeout(quasiTimeout)) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kForward).withTimeout(dynamicTimeout)) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)); - } - - - @Override - public void periodic() { - // This method will be called once per scheduler run - - // 0 degrees is set to (r, 270) in polar coordinates, because that way it will never wrap around - // If the forward limit switch is pressed, we're at 243 degrees - if(forwardLimitSwitch.isPressed()) { - encoder.setZeroOffset(242.88780212402344); - } - // If the reverse limit switch is pressed, we're at 40 degrees - if(reverseLimitSwitch.isPressed()) { - encoder.setZeroOffset(39.87791442871094); - } - - SmartDashboard.putNumber("Arm Position", encoder.getPosition()); - } + pidController.setFeedbackDevice(encoder) + } + + fun moveArmToAngle(angle: Double) { + pidController.setReference(angle, CANSparkBase.ControlType.kPosition) + } + + + override fun periodic() { + // This method will be called once per scheduler run + + // 0 degrees is set to (r, 270) in polar coordinates, because that way it will never wrap around + // If the forward limit switch is pressed, we're at 243 degrees + + if (forwardLimitSwitch.isPressed) { + encoder.setZeroOffset(242.88780212402344) + } + // If the reverse limit switch is pressed, we're at 40 degrees + if (reverseLimitSwitch.isPressed) { + encoder.setZeroOffset(39.87791442871094) + } + + //pidController.setReference(SmartDashboard.getNumber("Arm Setpoint", setpoint), CANSparkMax.ControlType.kPosition); + } + + fun getArmAngleForShooting(robotPose: Pose3d): Double { + val alliance = DriverStation.getAlliance().get() + + // add 15.5 inches to the height of the robot to get the height of the shooter + val shooterHeight = robotPose.translation.z + 15.5 + + val speaker = Speaker.CENTER_SPEAKER_OPENING + + // distance from the robot to the speaker + val distance = speaker.getDistance(robotPose.translation) + + val difference = speaker.minus(robotPose.translation) + + // get that angle + var angle = atan2(difference.z, difference.x) + // that angle uses (1, 0) as the 0 degree mark, so we need to add 90 degrees to it, because the arm uses (0, -1) as the 0 degree mark + angle += Math.PI / 2 + angle = edu.wpi.first.math.util.Units.radiansToDegrees(angle) + return angle + } + + val angle: Double + get() = encoder.position + + companion object { + private const val kP = 0.1 + private const val kI = 1e-4 + private const val kD = 1.0 + private const val kIz = 0.0 + private const val kFF = 0.0 + private const val kMaxOutput = 1.0 + private const val kMinOutput = -1.0 // We'll probably want to put these in the constants class later + /** + * Returns the Singleton instance of this ArmSubsystem. This static method should be used, + * rather than the constructor, to get the single instance of this class. For example: `ArmSubsystem.getInstance();` + */ + /** + * The Singleton instance of this ArmSubsystem. Code should use the [.getInstance] + * method to get the single instance (rather than trying to construct an instance of this class.) + */ + val instance: ArmSubsystem = ArmSubsystem() + + fun generateSysIdCommand( + sysIdRoutine: SysIdRoutine?, delay: Double, quasiTimeout: Double, + dynamicTimeout: Double + ): Command { + return sysIdRoutine!!.quasistatic(SysIdRoutine.Direction.kForward).withTimeout(quasiTimeout) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.quasistatic(SysIdRoutine.Direction.kReverse).withTimeout(quasiTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kForward).withTimeout(dynamicTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)) + } + } } diff --git a/src/main/java/frc/robot/subsystems/ClimberSubsystem.kt b/src/main/java/frc/robot/subsystems/ClimberSubsystem.kt index 6ec98fe..46a9450 100644 --- a/src/main/java/frc/robot/subsystems/ClimberSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/ClimberSubsystem.kt @@ -1,40 +1,21 @@ -package frc.robot.subsystems; +package frc.robot.subsystems -import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.SubsystemBase -public class ClimberSubsystem extends SubsystemBase { - - // With eager singleton initialization, any static variables/fields used in the - // constructor must appear before the "INSTANCE" variable so that they are initialized - // before the constructor is called when the "INSTANCE" variable initializes. - - /** - * The Singleton instance of this ClimberSubsystem. Code should use the {@link #getInstance()} - * method to get the single instance (rather than trying to construct an instance of this class.) - */ - private static final ClimberSubsystem INSTANCE = new ClimberSubsystem(); - - /** - * Returns the Singleton instance of this ClimberSubsystem. This static method should be used, - * rather than the constructor, to get the single instance of this class. For example: {@code - * ClimberSubsystem.getInstance();} - */ - @SuppressWarnings("WeakerAccess") - public static ClimberSubsystem getInstance() { - return INSTANCE; - } - - /** - * Creates a new instance of this ClimberSubsystem. This constructor is private since this class - * is a Singleton. Code should use the {@link #getInstance()} method to get the singleton - * instance. - */ - private ClimberSubsystem() { - // TODO: Set the default command, if any, for this subsystem by calling - // setDefaultCommand(command) - // in the constructor or in the robot coordination class, such as RobotContainer. - // Also, you can call addChild(name, sendableChild) to associate sendables with the - // subsystem - // such as SpeedControllers, Encoders, DigitalInputs, etc. - } +/** + * + */ +object ClimberSubsystem : SubsystemBase() { + // With eager singleton initialization, any static variables/fields used in the + // constructor must appear before the "INSTANCE" variable so that they are initialized + // before the constructor is called when the "INSTANCE" variable initializes. + /** + * Returns the Singleton instance of this ClimberSubsystem. This static method should be used, + * rather than the constructor, to get the single instance of this class. For example: `ClimberSubsystem.getInstance();` + */ + /** + * The Singleton instance of this ClimberSubsystem. Code should use the [.getInstance] + * method to get the single instance (rather than trying to construct an instance of this class.) + */ + val instance: ClimberSubsystem = ClimberSubsystem } diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt index 30822de..f83e03c 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt @@ -1,508 +1,569 @@ // 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 + +import com.kauailabs.navx.frc.AHRS +import com.pathplanner.lib.auto.AutoBuilder +import com.pathplanner.lib.commands.PathPlannerAuto +import com.pathplanner.lib.path.PathConstraints +import com.pathplanner.lib.path.PathPlannerPath +import com.pathplanner.lib.util.HolonomicPathFollowerConfig +import com.pathplanner.lib.util.ReplanningConfig +import edu.wpi.first.math.geometry.Pose2d +import edu.wpi.first.math.geometry.Rotation2d +import edu.wpi.first.math.geometry.Translation2d +import edu.wpi.first.math.kinematics.ChassisSpeeds +import edu.wpi.first.math.kinematics.SwerveDriveKinematics +import edu.wpi.first.math.trajectory.Trajectory +import edu.wpi.first.math.util.Units +import edu.wpi.first.wpilibj.* +import edu.wpi.first.wpilibj.DriverStation.Alliance +import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.SubsystemBase +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine +import frc.robot.util.Constants.AutonomousConstants +import frc.robot.util.LimelightHelpers +import swervelib.SwerveController +import swervelib.SwerveDrive +import swervelib.SwerveDriveTest +import swervelib.parser.SwerveControllerConfiguration +import swervelib.parser.SwerveDriveConfiguration +import swervelib.parser.SwerveParser +import swervelib.telemetry.SwerveDriveTelemetry +import java.io.File +import java.util.function.DoubleSupplier +import kotlin.math.pow + +/** + * + */ +class SwerveSubsystem : SubsystemBase { + private var lockRotation = false + + /** + * Get the swerve drive object. + * + * @return [SwerveDrive] object. + */ + /** + * Swerve drive object. + */ + @JvmField + val swerveDrive: SwerveDrive + + /** + * Maximum speed of the robot in meters per second, used to limit acceleration. + */ + private var maximumSpeed: Double = Units.feetToMeters(12.5) + + /** + * Initialize [SwerveDrive] with the directory provided. + * + * @param directory Directory of swerve drive config files. + */ + constructor(directory: File?) { + // Configure the Telemetry before creating the SwerveDrive to avoid unnecessary objects being created. + SwerveDriveTelemetry.verbosity = SwerveDriveTelemetry.TelemetryVerbosity.HIGH + try { + swerveDrive = SwerveParser(directory).createSwerveDrive(maximumSpeed) + // Alternative method if you don't want to supply the conversion factor via JSON files. + // swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed, angleConversionFactor, driveConversionFactor); + } catch (e: Exception) { + throw RuntimeException(e) + } + swerveDrive.setHeadingCorrection(false) // Heading correction should only be used while controlling the robot via angle. + swerveDrive.setCosineCompensator(!SwerveDriveTelemetry.isSimulation) // Disables cosine compensation for simulations since it causes discrepancies not seen in real life. + setupPathPlanner() + + val navx = swerveDrive.swerveDriveConfiguration.imu.imu as AHRS + } + + /** + * Construct the swerve drive. + * + * @param driveCfg SwerveDriveConfiguration for the swerve. + * @param controllerCfg Swerve Controller. + */ + constructor(driveCfg: SwerveDriveConfiguration?, controllerCfg: SwerveControllerConfiguration?) { + swerveDrive = SwerveDrive(driveCfg, controllerCfg, maximumSpeed) + } + + /** + * Setup AutoBuilder for PathPlanner. + */ + private fun setupPathPlanner() { + AutoBuilder.configureHolonomic( + { this.pose }, // Robot pose supplier + { initialHolonomicPose: Pose2d? -> this.resetOdometry(initialHolonomicPose) }, // Method to reset odometry (will be called if your auto has a starting pose) + { this.robotVelocity }, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE + { chassisSpeeds: ChassisSpeeds? -> this.setChassisSpeeds(chassisSpeeds) }, // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds + HolonomicPathFollowerConfig( // HolonomicPathFollowerConfig, this should likely live in your Constants class + AutonomousConstants.TRANSLATION_PID, // Translation PID constants + AutonomousConstants.ANGLE_PID, // Rotation PID constants + 4.5, // Max module speed, in m/s + swerveDrive.swerveDriveConfiguration.driveBaseRadiusMeters, // Drive base radius in meters. Distance from robot center to furthest module. + ReplanningConfig(true, true) // Default path replanning config. See the API for the options here + ), + { + // Boolean supplier that controls when the path will be mirrored for the red alliance + // This will flip the path being followed to the red side of the field. + // THE ORIGIN WILL REMAIN ON THE BLUE SIDE + val alliance = DriverStation.getAlliance() + if (alliance.isPresent) alliance.get() == Alliance.Red else false + }, + this // Reference to this subsystem to set requirements + ) + } + + /** + * Aim the robot at the target returned by the limelight. + * + * @param camera Name of the Limelight to communicate with. + * @return A [Command] which will run the alignment. + */ + fun aimAtTarget(camera: String?): Command { + return run { + if (LimelightHelpers.getTV(camera)) { + drive( + getTargetSpeeds( + 0.0, + 0.0, + Rotation2d.fromDegrees(LimelightHelpers.getTX(camera)) + ) + ) // Not sure if this will work, more math may be required. + } + } + } + + /** + * Get the path follower with events. + * + * @param pathName PathPlanner path name. + * @return [AutoBuilder.followPath] path command. + */ + fun getAutonomousCommand(pathName: String?): Command { + // Create a path following command using AutoBuilder. This will also trigger event markers. + return PathPlannerAuto(pathName) + } + + /** + * Use PathPlanner Path finding to go to a point on the field. + * + * @param pose Target [Pose2d] to go to. + * @return PathFinding command + */ + fun driveToPose(pose: Pose2d?): Command { + lockRotation = true + val path = PathPlannerPath.fromPathFile("Go to red speaker") + // Create the constraints to use while pathfinding + val constraints = PathConstraints( + swerveDrive.maximumVelocity, 4.0, + swerveDrive.maximumAngularVelocity, Units.degreesToRadians(720.0) + ) + + // Since AutoBuilder is configured, we can use it to build pathfinding commands + return AutoBuilder.pathfindToPose( + pose, + constraints, + 0.0, // Goal end velocity in meters/sec + 0.0 // Rotation delay distance in meters. This is how far the robot should travel before attempting to rotate. + ) + } + + /** + * Command to drive the robot using translative values and heading as a setpoint. + * + * @param translationX Translation in the X direction. Cubed for smoother controls. + * @param translationY Translation in the Y direction. Cubed for smoother controls. + * @param headingX Heading X to calculate angle of the joystick. + * @param headingY Heading Y to calculate angle of the joystick. + * @return Drive command. + */ + fun driveCommand( + translationX: DoubleSupplier, translationY: DoubleSupplier, headingX: DoubleSupplier, + headingY: DoubleSupplier + ): Command { + // swerveDrive.setHeadingCorrection(true); // Normally you would want heading correction for this kind of control. + return run { + val xInput: Double = translationX.asDouble.pow(3.0) // Smooth controll out + val yInput: Double = translationY.asDouble.pow(3.0) // Smooth controll out + // Make the robot move + driveFieldOriented( + swerveDrive.swerveController.getTargetSpeeds( + xInput, yInput, + headingX.asDouble, + headingY.asDouble, + swerveDrive.odometryHeading.radians, + swerveDrive.maximumVelocity + ) + ) + } + } + + /** + * Command to drive the robot using translative values and heading as a setpoint. + * + * @param translationX Translation in the X direction. + * @param translationY Translation in the Y direction. + * @param rotation Rotation as a value between [-1, 1] converted to radians. + * @return Drive command. + */ + fun simDriveCommand(translationX: DoubleSupplier, translationY: DoubleSupplier, rotation: DoubleSupplier): Command { + // swerveDrive.setHeadingCorrection(true); // Normally you would want heading correction for this kind of control. + return run { + // Make the robot move + driveFieldOriented( + swerveDrive.swerveController.getTargetSpeeds( + translationX.asDouble, + translationY.asDouble, + rotation.asDouble * Math.PI, + swerveDrive.odometryHeading.radians, + swerveDrive.maximumVelocity + ) + ) + } + } + + /** + * Command to characterize the robot drive motors using SysId + * + * @return SysId Drive Command + */ + fun sysIdDriveMotorCommand(): Command { + return SwerveDriveTest.generateSysIdCommand( + SwerveDriveTest.setDriveSysIdRoutine( + SysIdRoutine.Config(), + this, swerveDrive, 12.0 + ), + 3.0, 5.0, 3.0 + ) + } + + /** + * Command to characterize the robot angle motors using SysId + * + * @return SysId Angle Command + */ + fun sysIdAngleMotorCommand(): Command { + return SwerveDriveTest.generateSysIdCommand( + SwerveDriveTest.setAngleSysIdRoutine( + SysIdRoutine.Config(), + this, swerveDrive + ), + 3.0, 5.0, 3.0 + ) + } + + /** + * Command to drive the robot using translative values and heading as angular velocity. + * + * @param translationX Translation in the X direction. Cubed for smoother controls. + * @param translationY Translation in the Y direction. Cubed for smoother controls. + * @param angularRotationX Angular velocity of the robot to set. Cubed for smoother controls. + * @return Drive command. + */ + fun driveCommand( + translationX: DoubleSupplier, + translationY: DoubleSupplier, + angularRotationX: DoubleSupplier + ): Command { + return run { + // Make the robot move + swerveDrive.drive( + Translation2d( + translationX.asDouble.pow(3.0) * swerveDrive.maximumVelocity, + translationY.asDouble.pow(3.0) * swerveDrive.maximumVelocity + ), + angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, + true, + false + ) + } + } + + /** + * + */ + fun driveCommandNonRel( + translationX: DoubleSupplier, + translationY: DoubleSupplier, + angularRotationX: DoubleSupplier + ): Command { + return run { + // Make the robot move + swerveDrive.drive( + Translation2d( + translationX.asDouble.pow(3.0) * swerveDrive.maximumVelocity, + translationY.asDouble.pow(3.0) * swerveDrive.maximumVelocity + ), + angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, + false, + false + ) + } + } + + /** + * The primary method for controlling the drivebase. Takes a [Translation2d] and a rotation rate, and + * calculates and commands module states accordingly. Can use either open-loop or closed-loop velocity control for + * the wheel velocities. Also has field- and robot-relative modes, which affect how the translation vector is used. + * + * @param translation [Translation2d] that is the commanded linear velocity of the robot, in meters per + * second. In robot-relative mode, positive x is torwards the bow (front) and positive y is + * torwards port (left). In field-relative mode, positive x is away from the alliance wall + * (field North) and positive y is torwards the left wall when looking through the driver station + * glass (field West). + * @param rotation Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot + * relativity. + * @param fieldRelative Drive mode. True for field-relative, false for robot-relative. + */ + fun drive(translation: Translation2d?, rotation: Double, fieldRelative: Boolean) { + swerveDrive.drive( + translation, + rotation, + fieldRelative, + false + ) // Open loop is disabled since it shouldn't be used most of the time. + } + + /** + * Drive the robot given a chassis field oriented velocity. + * + * @param velocity Velocity according to the field. + */ + private fun driveFieldOriented(velocity: ChassisSpeeds?) { + swerveDrive.driveFieldOriented(velocity) + } + + /** + * Drive according to the chassis robot oriented velocity. + * + * @param velocity Robot oriented [ChassisSpeeds] + */ + fun drive(velocity: ChassisSpeeds?) { + swerveDrive.drive(velocity) + } + + /** + * + */ + override fun periodic() { + if (LimelightHelpers.getTV("limelight-back")) swerveDrive.addVisionMeasurement( + LimelightHelpers.getBotPose2d_wpiRed( + "limelight-back" + ), + Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture( + "limelight-back" + )) / 1000.0 + ) + + // PathPlannerLogging.logCurrentPose(getPose()); + swerveDrive.updateOdometry() + + pose + } + + /** + * + */ + override fun simulationPeriodic() { + } + + /** + * + */ + val kinematics: SwerveDriveKinematics + /** + * Get the swerve drive kinematics object. + * + * @return [SwerveDriveKinematics] of the swerve drive. + */ + get() = swerveDrive.kinematics + + /** + * Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this + * method. However, if either gyro angle or module position is reset, this must be called in order for odometry to + * keep working. + * + * @param initialHolonomicPose The pose to set the odometry to + */ + private fun resetOdometry(initialHolonomicPose: Pose2d?) { + swerveDrive.resetOdometry(initialHolonomicPose) + } + + /** + * + */ + val pose: Pose2d + /** + * Gets the current pose (position and rotation) of the robot, as reported by odometry. + * + * @return The robot's pose + */ + get() = swerveDrive.pose + + /** + * Set chassis speeds with closed-loop velocity control. + * + * @param chassisSpeeds Chassis Speeds to set. + */ + private fun setChassisSpeeds(chassisSpeeds: ChassisSpeeds?) { + swerveDrive.setChassisSpeeds(chassisSpeeds) + } + + /** + * Post the trajectory to the field. + * + * @param trajectory The trajectory to post. + */ + fun postTrajectory(trajectory: Trajectory?) { + swerveDrive.postTrajectory(trajectory) + } + + /** + * Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0. + */ + fun zeroGyro() { + swerveDrive.zeroGyro() + } + + /** + * Sets the drive motors to brake/coast mode. + * + * @param brake True to set motors to brake mode, false for coast. + */ + fun setMotorBrake(brake: Boolean) { + swerveDrive.setMotorIdleMode(brake) + } + + /** + * + */ + val heading: Rotation2d + /** + * Gets the current yaw angle of the robot, as reported by the swerve pose estimator in the underlying drivebase. + * Note, this is not the raw gyro reading, this may be corrected from calls to resetOdometry(). + * + * @return The yaw angle + */ + get() = pose.rotation + + /** + * Get the chassis speeds based on controller input of 2 joysticks. One for speeds in which direction. The other for + * the angle of the robot. + * + * @param xInput X joystick input for the robot to move in the X direction. + * @param yInput Y joystick input for the robot to move in the Y direction. + * @param headingX X joystick which controls the angle of the robot. + * @param headingY Y joystick which controls the angle of the robot. + * @return [ChassisSpeeds] which can be sent to the Swerve Drive. + */ + fun getTargetSpeeds(xInput: Double, yInput: Double, headingX: Double, headingY: Double): ChassisSpeeds { + var xInput = xInput + var yInput = yInput + xInput = xInput.pow(3.0) + yInput = yInput.pow(3.0) + return swerveDrive.swerveController.getTargetSpeeds( + xInput, + yInput, + headingX, + headingY, + heading.radians, + maximumSpeed + ) + } + + /** + * Get the chassis speeds based on controller input of 1 joystick and one angle. Control the robot at an offset of + * 90deg. + * + * @param xInput X joystick input for the robot to move in the X direction. + * @param yInput Y joystick input for the robot to move in the Y direction. + * @param angle The angle in as a [Rotation2d]. + * @return [ChassisSpeeds] which can be sent to the Swerve Drive. + */ + fun getTargetSpeeds(xInput: Double, yInput: Double, angle: Rotation2d): ChassisSpeeds { + var xInput = xInput + var yInput = yInput + xInput = xInput.pow(3.0) + yInput = yInput.pow(3.0) + return swerveDrive.swerveController.getTargetSpeeds( + xInput, + yInput, + angle.radians, + heading.radians, + maximumSpeed + ) + } + + /** + * + */ + val fieldVelocity: ChassisSpeeds + /** + * Gets the current field-relative velocity (x, y and omega) of the robot + * + * @return A ChassisSpeeds object of the current field-relative velocity + */ + get() = swerveDrive.fieldVelocity + + /** + * + */ + val robotVelocity: ChassisSpeeds + /** + * Gets the current velocity (x, y and omega) of the robot + * + * @return A [ChassisSpeeds] object of the current velocity + */ + get() = swerveDrive.robotVelocity + + /** + * + */ + val swerveController: SwerveController + /** + * Get the [SwerveController] in the swerve drive. + * + * @return [SwerveController] from the [SwerveDrive]. + */ + get() = swerveDrive.swerveController + + /** + * + */ + val swerveDriveConfiguration: SwerveDriveConfiguration + /** + * Get the [SwerveDriveConfiguration] object. + * + * @return The [SwerveDriveConfiguration] fpr the current drive. + */ + get() = swerveDrive.swerveDriveConfiguration + + /** + * Lock the swerve drive to prevent it from moving. + */ + fun lock() { + swerveDrive.lockPose() + } -package frc.robot.subsystems; - -import com.kauailabs.navx.frc.AHRS; -import com.pathplanner.lib.auto.AutoBuilder; -import com.pathplanner.lib.commands.PathPlannerAuto; -import com.pathplanner.lib.controllers.PPHolonomicDriveController; -import com.pathplanner.lib.path.PathConstraints; -import com.pathplanner.lib.path.PathPlannerPath; -import com.pathplanner.lib.util.HolonomicPathFollowerConfig; -import com.pathplanner.lib.util.PathPlannerLogging; -import com.pathplanner.lib.util.ReplanningConfig; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.math.kinematics.SwerveDriveKinematics; -import edu.wpi.first.math.trajectory.Trajectory; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.Filesystem; -import edu.wpi.first.wpilibj.Timer; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config; -import frc.robot.util.Constants.AutonomousConstants; -import frc.robot.util.LimelightHelpers; -import swervelib.SwerveController; -import swervelib.SwerveDrive; -import swervelib.SwerveDriveTest; -import swervelib.math.SwerveMath; -import swervelib.parser.SwerveControllerConfiguration; -import swervelib.parser.SwerveDriveConfiguration; -import swervelib.parser.SwerveParser; -import swervelib.telemetry.SwerveDriveTelemetry; -import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity; - -import java.io.File; -import java.util.Optional; -import java.util.function.DoubleSupplier; - -public class SwerveSubsystem extends SubsystemBase { - private boolean lockRotation = false; - - private static final SwerveSubsystem INSTANCE = new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "maxswerve")); - - public static SwerveSubsystem getInstance() { - return INSTANCE; - } - - /** - * Swerve drive object. - */ - private final SwerveDrive swerveDrive; - /** - * Maximum speed of the robot in meters per second, used to limit acceleration. - */ - public double maximumSpeed = Units.feetToMeters(12.5); - - /** - * Initialize {@link SwerveDrive} with the directory provided. - * - * @param directory Directory of swerve drive config files. - */ - public SwerveSubsystem(File directory) { - // Configure the Telemetry before creating the SwerveDrive to avoid unnecessary objects being created. - SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH; - try { - swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed); - // Alternative method if you don't want to supply the conversion factor via JSON files. - // swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed, angleConversionFactor, driveConversionFactor); - } catch (Exception e) { - throw new RuntimeException(e); + /** + * + */ + val pitch: Rotation2d + /** + * Gets the current pitch angle of the robot, as reported by the imu. + * + * @return The heading as a [Rotation2d] angle + */ + get() = swerveDrive.pitch + + + companion object { + /** + * + */ + val instance: SwerveSubsystem = SwerveSubsystem(File(Filesystem.getDeployDirectory(), "maxswerve")) } - swerveDrive.setHeadingCorrection(false); // Heading correction should only be used while controlling the robot via angle. - swerveDrive.setCosineCompensator(!SwerveDriveTelemetry.isSimulation); // Disables cosine compensation for simulations since it causes discrepancies not seen in real life. - setupPathPlanner(); - - AHRS navx = (AHRS) swerveDrive.swerveDriveConfiguration.imu.getIMU(); - } - - /** - * Construct the swerve drive. - * - * @param driveCfg SwerveDriveConfiguration for the swerve. - * @param controllerCfg Swerve Controller. - */ - public SwerveSubsystem(SwerveDriveConfiguration driveCfg, SwerveControllerConfiguration controllerCfg) { - swerveDrive = new SwerveDrive(driveCfg, controllerCfg, maximumSpeed); - } - - /** - * Setup AutoBuilder for PathPlanner. - */ - public void setupPathPlanner() { - AutoBuilder.configureHolonomic( - this::getPose, // Robot pose supplier - this::resetOdometry, // Method to reset odometry (will be called if your auto has a starting pose) - this::getRobotVelocity, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE - this::setChassisSpeeds, // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds - new HolonomicPathFollowerConfig( // HolonomicPathFollowerConfig, this should likely live in your Constants class - AutonomousConstants.TRANSLATION_PID, - // Translation PID constants - AutonomousConstants.ANGLE_PID, - // Rotation PID constants - 4.5, - // Max module speed, in m/s - swerveDrive.swerveDriveConfiguration.getDriveBaseRadiusMeters(), - // Drive base radius in meters. Distance from robot center to furthest module. - new ReplanningConfig(true, true) - // Default path replanning config. See the API for the options here - ), - () -> { - // Boolean supplier that controls when the path will be mirrored for the red alliance - // This will flip the path being followed to the red side of the field. - // THE ORIGIN WILL REMAIN ON THE BLUE SIDE - var alliance = DriverStation.getAlliance(); - return alliance.isPresent() ? alliance.get() == DriverStation.Alliance.Red : false; - }, - this // Reference to this subsystem to set requirements - ); - - } - - /** - * Aim the robot at the target returned by the limelight. - * - * @param camera Name of the Limelight to communicate with. - * @return A {@link Command} which will run the alignment. - */ - public Command aimAtTarget(String camera) { - return run(() -> { - if (LimelightHelpers.getTV(camera)) { - drive(getTargetSpeeds(0, - 0, - Rotation2d.fromDegrees(LimelightHelpers.getTX(camera)))); // Not sure if this will work, more math may be required. - } - }); - } - - /** - * Get the path follower with events. - * - * @param pathName PathPlanner path name. - * @return {@link AutoBuilder#followPath(PathPlannerPath)} path command. - */ - public Command getAutonomousCommand(String pathName) { - // Create a path following command using AutoBuilder. This will also trigger event markers. - return new PathPlannerAuto(pathName); - } - - /** - * Use PathPlanner Path finding to go to a point on the field. - * - * @param pose Target {@link Pose2d} to go to. - * @return PathFinding command - */ - public Command driveToPose(Pose2d pose) { - lockRotation = true; - PathPlannerPath path = PathPlannerPath.fromPathFile("Go to red speaker"); -// Create the constraints to use while pathfinding - PathConstraints constraints = new PathConstraints( - swerveDrive.getMaximumVelocity(), 4.0, - swerveDrive.getMaximumAngularVelocity(), Units.degreesToRadians(720)); - -// Since AutoBuilder is configured, we can use it to build pathfinding commands - return AutoBuilder.pathfindToPose( - pose, - constraints, - 0.0, // Goal end velocity in meters/sec - 0.0 // Rotation delay distance in meters. This is how far the robot should travel before attempting to rotate. - ); - } - - /** - * Command to drive the robot using translative values and heading as a setpoint. - * - * @param translationX Translation in the X direction. Cubed for smoother controls. - * @param translationY Translation in the Y direction. Cubed for smoother controls. - * @param headingX Heading X to calculate angle of the joystick. - * @param headingY Heading Y to calculate angle of the joystick. - * @return Drive command. - */ - public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier headingX, - DoubleSupplier headingY) { - // swerveDrive.setHeadingCorrection(true); // Normally you would want heading correction for this kind of control. - return run(() -> { - double xInput = Math.pow(translationX.getAsDouble(), 3); // Smooth controll out - double yInput = Math.pow(translationY.getAsDouble(), 3); // Smooth controll out - // Make the robot move - driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(xInput, yInput, - headingX.getAsDouble(), - headingY.getAsDouble(), - swerveDrive.getOdometryHeading().getRadians(), - swerveDrive.getMaximumVelocity())); - }); - } - - /** - * Command to drive the robot using translative values and heading as a setpoint. - * - * @param translationX Translation in the X direction. - * @param translationY Translation in the Y direction. - * @param rotation Rotation as a value between [-1, 1] converted to radians. - * @return Drive command. - */ - public Command simDriveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier rotation) { - // swerveDrive.setHeadingCorrection(true); // Normally you would want heading correction for this kind of control. - return run(() -> { - // Make the robot move - driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(translationX.getAsDouble(), - translationY.getAsDouble(), - rotation.getAsDouble() * Math.PI, - swerveDrive.getOdometryHeading().getRadians(), - swerveDrive.getMaximumVelocity())); - }); - } - - /** - * Command to characterize the robot drive motors using SysId - * - * @return SysId Drive Command - */ - public Command sysIdDriveMotorCommand() { - return SwerveDriveTest.generateSysIdCommand( - SwerveDriveTest.setDriveSysIdRoutine( - new Config(), - this, swerveDrive, 12), - 3.0, 5.0, 3.0); - } - - /** - * Command to characterize the robot angle motors using SysId - * - * @return SysId Angle Command - */ - public Command sysIdAngleMotorCommand() { - return SwerveDriveTest.generateSysIdCommand( - SwerveDriveTest.setAngleSysIdRoutine( - new Config(), - this, swerveDrive), - 3.0, 5.0, 3.0); - } - - /** - * Command to drive the robot using translative values and heading as angular velocity. - * - * @param translationX Translation in the X direction. Cubed for smoother controls. - * @param translationY Translation in the Y direction. Cubed for smoother controls. - * @param angularRotationX Angular velocity of the robot to set. Cubed for smoother controls. - * @return Drive command. - */ - public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX) { - return run(() -> { - // Make the robot move - swerveDrive.drive(new Translation2d(Math.pow(translationX.getAsDouble(), 3) * swerveDrive.getMaximumVelocity(), - Math.pow(translationY.getAsDouble(), 3) * swerveDrive.getMaximumVelocity()), - angularRotationX.getAsDouble() * swerveDrive.getMaximumAngularVelocity(), - true, - false); - }); - } - public Command driveCommandNonRel(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX) { - return run(() -> { - // Make the robot move - swerveDrive.drive(new Translation2d(Math.pow(translationX.getAsDouble(), 3) * swerveDrive.getMaximumVelocity(), - Math.pow(translationY.getAsDouble(), 3) * swerveDrive.getMaximumVelocity()), - angularRotationX.getAsDouble() * swerveDrive.getMaximumAngularVelocity(), - false, - false); - }); - } - - /** - * The primary method for controlling the drivebase. Takes a {@link Translation2d} and a rotation rate, and - * calculates and commands module states accordingly. Can use either open-loop or closed-loop velocity control for - * the wheel velocities. Also has field- and robot-relative modes, which affect how the translation vector is used. - * - * @param translation {@link Translation2d} that is the commanded linear velocity of the robot, in meters per - * second. In robot-relative mode, positive x is torwards the bow (front) and positive y is - * torwards port (left). In field-relative mode, positive x is away from the alliance wall - * (field North) and positive y is torwards the left wall when looking through the driver station - * glass (field West). - * @param rotation Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot - * relativity. - * @param fieldRelative Drive mode. True for field-relative, false for robot-relative. - */ - public void drive(Translation2d translation, double rotation, boolean fieldRelative) { - swerveDrive.drive(translation, - rotation, - fieldRelative, - false); // Open loop is disabled since it shouldn't be used most of the time. - } - - /** - * Drive the robot given a chassis field oriented velocity. - * - * @param velocity Velocity according to the field. - */ - public void driveFieldOriented(ChassisSpeeds velocity) { - swerveDrive.driveFieldOriented(velocity); - } - - /** - * Drive according to the chassis robot oriented velocity. - * - * @param velocity Robot oriented {@link ChassisSpeeds} - */ - public void drive(ChassisSpeeds velocity) { - swerveDrive.drive(velocity); - } - - @Override - public void periodic() { - if (LimelightHelpers.getTV("limelight-back")) - swerveDrive.addVisionMeasurement(LimelightHelpers.getBotPose2d_wpiRed("limelight-back"), Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture("limelight-back")) / 1000.0); - - // PathPlannerLogging.logCurrentPose(getPose()); - swerveDrive.updateOdometry(); - - getPose(); - } - - @Override - public void simulationPeriodic() { - } - - /** - * Get the swerve drive kinematics object. - * - * @return {@link SwerveDriveKinematics} of the swerve drive. - */ - public SwerveDriveKinematics getKinematics() { - return swerveDrive.kinematics; - } - - /** - * Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this - * method. However, if either gyro angle or module position is reset, this must be called in order for odometry to - * keep working. - * - * @param initialHolonomicPose The pose to set the odometry to - */ - public void resetOdometry(Pose2d initialHolonomicPose) { - swerveDrive.resetOdometry(initialHolonomicPose); - } - - /** - * Gets the current pose (position and rotation) of the robot, as reported by odometry. - * - * @return The robot's pose - */ - public Pose2d getPose() { - return swerveDrive.getPose(); - } - - /** - * Set chassis speeds with closed-loop velocity control. - * - * @param chassisSpeeds Chassis Speeds to set. - */ - public void setChassisSpeeds(ChassisSpeeds chassisSpeeds) { - swerveDrive.setChassisSpeeds(chassisSpeeds); - } - - /** - * Post the trajectory to the field. - * - * @param trajectory The trajectory to post. - */ - public void postTrajectory(Trajectory trajectory) { - swerveDrive.postTrajectory(trajectory); - } - - /** - * Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0. - */ - public void zeroGyro() { - swerveDrive.zeroGyro(); - } - - /** - * Sets the drive motors to brake/coast mode. - * - * @param brake True to set motors to brake mode, false for coast. - */ - public void setMotorBrake(boolean brake) { - swerveDrive.setMotorIdleMode(brake); - } - - /** - * Gets the current yaw angle of the robot, as reported by the swerve pose estimator in the underlying drivebase. - * Note, this is not the raw gyro reading, this may be corrected from calls to resetOdometry(). - * - * @return The yaw angle - */ - public Rotation2d getHeading() { - return getPose().getRotation(); - } - - /** - * Get the chassis speeds based on controller input of 2 joysticks. One for speeds in which direction. The other for - * the angle of the robot. - * - * @param xInput X joystick input for the robot to move in the X direction. - * @param yInput Y joystick input for the robot to move in the Y direction. - * @param headingX X joystick which controls the angle of the robot. - * @param headingY Y joystick which controls the angle of the robot. - * @return {@link ChassisSpeeds} which can be sent to the Swerve Drive. - */ - public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, double headingX, double headingY) { - xInput = Math.pow(xInput, 3); - yInput = Math.pow(yInput, 3); - return swerveDrive.swerveController.getTargetSpeeds(xInput, - yInput, - headingX, - headingY, - getHeading().getRadians(), - maximumSpeed); - } - - /** - * Get the chassis speeds based on controller input of 1 joystick and one angle. Control the robot at an offset of - * 90deg. - * - * @param xInput X joystick input for the robot to move in the X direction. - * @param yInput Y joystick input for the robot to move in the Y direction. - * @param angle The angle in as a {@link Rotation2d}. - * @return {@link ChassisSpeeds} which can be sent to the Swerve Drive. - */ - public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, Rotation2d angle) { - xInput = Math.pow(xInput, 3); - yInput = Math.pow(yInput, 3); - return swerveDrive.swerveController.getTargetSpeeds(xInput, - yInput, - angle.getRadians(), - getHeading().getRadians(), - maximumSpeed); - } - - /** - * Gets the current field-relative velocity (x, y and omega) of the robot - * - * @return A ChassisSpeeds object of the current field-relative velocity - */ - public ChassisSpeeds getFieldVelocity() { - return swerveDrive.getFieldVelocity(); - } - - /** - * Gets the current velocity (x, y and omega) of the robot - * - * @return A {@link ChassisSpeeds} object of the current velocity - */ - public ChassisSpeeds getRobotVelocity() { - return swerveDrive.getRobotVelocity(); - } - - /** - * Get the {@link SwerveController} in the swerve drive. - * - * @return {@link SwerveController} from the {@link SwerveDrive}. - */ - public SwerveController getSwerveController() { - return swerveDrive.swerveController; - } - - /** - * Get the {@link SwerveDriveConfiguration} object. - * - * @return The {@link SwerveDriveConfiguration} fpr the current drive. - */ - public SwerveDriveConfiguration getSwerveDriveConfiguration() { - return swerveDrive.swerveDriveConfiguration; - } - - /** - * Lock the swerve drive to prevent it from moving. - */ - public void lock() { - swerveDrive.lockPose(); - } - - /** - * Gets the current pitch angle of the robot, as reported by the imu. - * - * @return The heading as a {@link Rotation2d} angle - */ - public Rotation2d getPitch() { - return swerveDrive.getPitch(); - } - - - - - /** - * Get the swerve drive object. - * - * @return {@link SwerveDrive} object. - */ - public SwerveDrive getSwerveDrive() { - return swerveDrive; - } } diff --git a/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt b/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt index ba8bc7a..7286a49 100644 --- a/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt +++ b/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt @@ -1,40 +1,21 @@ -package frc.robot.subsystems; +package frc.robot.subsystems -import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.SubsystemBase -public class TelemetrySubsystem extends SubsystemBase { - - // With eager singleton initialization, any static variables/fields used in the - // constructor must appear before the "INSTANCE" variable so that they are initialized - // before the constructor is called when the "INSTANCE" variable initializes. - - /** - * The Singleton instance of this TelemetrySubsystem. Code should use the {@link #getInstance()} - * method to get the single instance (rather than trying to construct an instance of this class.) - */ - private static final TelemetrySubsystem INSTANCE = new TelemetrySubsystem(); - - /** - * Returns the Singleton instance of this TelemetrySubsystem. This static method should be used, - * rather than the constructor, to get the single instance of this class. For example: {@code - * TelemetrySubsystem.getInstance();} - */ - @SuppressWarnings("WeakerAccess") - public static TelemetrySubsystem getInstance() { - return INSTANCE; - } - - /** - * Creates a new instance of this TelemetrySubsystem. This constructor is private since this class - * is a Singleton. Code should use the {@link #getInstance()} method to get the singleton - * instance. - */ - private TelemetrySubsystem() { - // TODO: Set the default command, if any, for this subsystem by calling - // setDefaultCommand(command) - // in the constructor or in the robot coordination class, such as RobotContainer. - // Also, you can call addChild(name, sendableChild) to associate sendables with the - // subsystem - // such as SpeedControllers, Encoders, DigitalInputs, etc. - } +/** + * + */ +object TelemetrySubsystem : SubsystemBase() { + // With eager singleton initialization, any static variables/fields used in the + // constructor must appear before the "INSTANCE" variable so that they are initialized + // before the constructor is called when the "INSTANCE" variable initializes. + /** + * Returns the Singleton instance of this TelemetrySubsystem. This static method should be used, + * rather than the constructor, to get the single instance of this class. For example: `TelemetrySubsystem.getInstance();` + */ + /** + * The Singleton instance of this TelemetrySubsystem. Code should use the [.getInstance] + * method to get the single instance (rather than trying to construct an instance of this class.) + */ + val instance: TelemetrySubsystem = TelemetrySubsystem } diff --git a/src/main/java/frc/robot/subsystems/VisionSubsystem.kt b/src/main/java/frc/robot/subsystems/VisionSubsystem.kt index d73db77..1aa7f74 100644 --- a/src/main/java/frc/robot/subsystems/VisionSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/VisionSubsystem.kt @@ -1,107 +1,101 @@ -package frc.robot.subsystems; - -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.util.LimelightHelpers; -import org.littletonrobotics.junction.Logger; - - -public class VisionSubsystem extends SubsystemBase { - - // With eager singleton initialization, any static variables/fields used in the - // constructor must appear before the "INSTANCE" variable so that they are initialized - // before the constructor is called when the "INSTANCE" variable initializes. - - /** - * The Singleton instance of this VisionSubsystem. Code should use the {@link #getInstance()} - * method to get the single instance (rather than trying to construct an instance of this class.) - */ - private static final VisionSubsystem INSTANCE = new VisionSubsystem(); - - /** - * Returns the Singleton instance of this VisionSubsystem. This static method should be used, - * rather than the constructor, to get the single instance of this class. For example: {@code - * VisionSubsystem.getInstance();} - */ - @SuppressWarnings("WeakerAccess") - public static VisionSubsystem getInstance() { - return INSTANCE; - } - - /** - * Creates a new instance of this VisionSubsystem. This constructor is private since this class is - * a Singleton. Code should use the {@link #getInstance()} method to get the singleton instance. - */ - private VisionSubsystem() { - // TODO: Set the default command, if any, for this subsystem by calling - // setDefaultCommand(command) - // in the constructor or in the robot coordination class, such as RobotContainer. - // Also, you can call addChild(name, sendableChild) to associate sendables with the - // subsystem - // such as SpeedControllers, Encoders, DigitalInputs, etc. - } - - @Override - public void periodic() { - // This method will be called once per scheduler run - - - Logger.recordOutput("Targets", LimelightHelpers.getTargetPose3d_RobotSpace("limelight-back")); - - } - - // simple proportional turning control with Limelight. - // "proportional control" is a control algorithm in which the output is proportional to the error. - // in this case, we are going to return an angular velocity that is proportional to the - // "tx" value from the Limelight. - public double limelight_aim_proportional_front() { - // kP (constant of proportionality) - // this is a hand-tuned number that determines the aggressiveness of our proportional control loop - // if it is too high, the robot will oscillate. - // if it is too low, the robot will never reach its target - // if the robot never turns in the correct direction, kP should be inverted. - double kP = .035; - - // tx ranges from (-hfov/2) to (hfov/2) in degrees. If your target is on the rightmost edge of - // your limelight 3 feed, tx should return roughly 31 degrees. - double targetingAngularVelocity = LimelightHelpers.getTX("limelight-front") * kP; - - // convert to radians per second for our drive method - targetingAngularVelocity *= SwerveSubsystem.getInstance().getSwerveDrive().getMaximumAngularVelocity(); - - //invert since tx is positive when the target is to the right of the crosshair - targetingAngularVelocity *= -1.0; - - return targetingAngularVelocity; - } - - public double limelight_aim_proportional_back() { - // kP (constant of proportionality) - // this is a hand-tuned number that determines the aggressiveness of our proportional control loop - // if it is too high, the robot will oscillate. - // if it is too low, the robot will never reach its target - // if the robot never turns in the correct direction, kP should be inverted. - double kP = .035; - - // tx ranges from (-hfov/2) to (hfov/2) in degrees. If your target is on the rightmost edge of - // your limelight 3 feed, tx should return roughly 31 degrees. - double targetingAngularVelocity = LimelightHelpers.getTX("limelight-back") * kP; - - // convert to radians per second for our drive method - targetingAngularVelocity *= SwerveSubsystem.getInstance().getSwerveDrive().getMaximumAngularVelocity(); - - //invert since tx is positive when the target is to the right of the crosshair - targetingAngularVelocity *= 1.0; - - return targetingAngularVelocity; - } - // simple proportional ranging control with Limelight's "ty" value - // this works best if your Limelight's mount height and target mount height are different. - // if your limelight and target are mounted at the same or similar heights, use "ta" (area) for target ranging rather than "ty" - public double limelight_range_proportional() { - double kP = .1; - double targetingForwardSpeed = LimelightHelpers.getTY("limelight-front") * kP; - targetingForwardSpeed *= SwerveSubsystem.getInstance().getSwerveDrive().getMaximumVelocity(); - targetingForwardSpeed *= -1.0; - return targetingForwardSpeed; - } +package frc.robot.subsystems + +import edu.wpi.first.wpilibj2.command.SubsystemBase +import frc.robot.util.LimelightHelpers +import org.littletonrobotics.junction.* + +class VisionSubsystem +/** + * Creates a new instance of this VisionSubsystem. This constructor is private since this class is + * a Singleton. Code should use the [.getInstance] method to get the singleton instance. + */ +private constructor() : SubsystemBase() { + /** + * + */ + override fun periodic() { + // This method will be called once per scheduler run + + + Logger.recordOutput("Targets", LimelightHelpers.getTargetPose3d_RobotSpace("limelight-back")) + } + + /** + * + */// simple proportional turning control with Limelight. + // "proportional control" is a control algorithm in which the output is proportional to the error. + // in this case, we are going to return an angular velocity that is proportional to the + // "tx" value from the Limelight. + fun limelightAimProportionalFront(): Double { + // kP (constant of proportionality) + // this is a hand-tuned number that determines the aggressiveness of our proportional control loop + // if it is too high, the robot will oscillate. + // if it is too low, the robot will never reach its target + // if the robot never turns in the correct direction, kP should be inverted. + val kP = .035 + + // tx ranges from (-hfov/2) to (hfov/2) in degrees. If your target is on the rightmost edge of + // your limelight 3 feed, tx should return roughly 31 degrees. + var targetingAngularVelocity = LimelightHelpers.getTX("limelight-front") * kP + + // convert to radians per second for our drive method + targetingAngularVelocity *= SwerveSubsystem.instance.swerveDrive.maximumAngularVelocity + + //invert since tx is positive when the target is to the right of the crosshair + targetingAngularVelocity *= -1.0 + + return targetingAngularVelocity + } + + /** + * + */ + fun limelightAimProportionalBack(): Double { + // kP (constant of proportionality) + // this is a hand-tuned number that determines the aggressiveness of our proportional control loop + // if it is too high, the robot will oscillate. + // if it is too low, the robot will never reach its target + // if the robot never turns in the correct direction, kP should be inverted. + val kP = .035 + + // tx ranges from (-hfov/2) to (hfov/2) in degrees. If your target is on the rightmost edge of + // your limelight 3 feed, tx should return roughly 31 degrees. + var targetingAngularVelocity = LimelightHelpers.getTX("limelight-back") * kP + + // convert to radians per second for our drive method + targetingAngularVelocity *= SwerveSubsystem.instance.swerveDrive.maximumAngularVelocity + + //invert since tx is positive when the target is to the right of the crosshair + targetingAngularVelocity *= 1.0 + + return targetingAngularVelocity + } + + /** + * + */// simple proportional ranging control with Limelight's "ty" value + // this works best if your Limelight's mount height and target mount height are different. + // if your limelight and target are mounted at the same or similar heights, use "ta" (area) for target ranging rather than "ty" + fun limelightRangeProportional(): Double { + val kP = .1 + var targetingForwardSpeed = LimelightHelpers.getTY("limelight-front") * kP + targetingForwardSpeed *= SwerveSubsystem.instance.swerveDrive.maximumVelocity + targetingForwardSpeed *= -1.0 + return targetingForwardSpeed + } + + companion object { + // With eager singleton initialization, any static variables/fields used in the + // constructor must appear before the "INSTANCE" variable so that they are initialized + // before the constructor is called when the "INSTANCE" variable initializes. + /** + * Returns the Singleton instance of this VisionSubsystem. This static method should be used, + * rather than the constructor, to get the single instance of this class. For example: `VisionSubsystem.getInstance();` + */ + /** + * The Singleton instance of this VisionSubsystem. Code should use the [.getInstance] + * method to get the single instance (rather than trying to construct an instance of this class.) + */ + val instance: VisionSubsystem = VisionSubsystem() + } } diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.kt b/src/main/java/frc/robot/subsystems/intake/Intake.kt index 43093ff..f0fba56 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.kt +++ b/src/main/java/frc/robot/subsystems/intake/Intake.kt @@ -1,152 +1,150 @@ -package frc.robot.subsystems.intake; - -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import frc.robot.subsystems.SwerveSubsystem; -import frc.robot.util.Constants; -import org.littletonrobotics.junction.Logger; - -import java.util.function.DoubleSupplier; - -import static edu.wpi.first.units.Units.Volts; +package frc.robot.subsystems.intake + +import edu.wpi.first.math.util.Units +import edu.wpi.first.units.Measure +import edu.wpi.first.units.Voltage +import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog +import edu.wpi.first.wpilibj2.command.* +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Mechanism +import frc.robot.subsystems.SwerveSubsystem +import frc.robot.util.Constants.IntakeConstants +import org.littletonrobotics.junction.* +import java.util.function.DoubleSupplier +import kotlin.math.abs // Not doing the sim because I would like to retain what little sanity I have left -public class Intake extends SubsystemBase { - public final IntakeIO io; - public final IntakeIOInputsAutoLogged inputs = new IntakeIOInputsAutoLogged(); - private boolean runIntake = true; - - public Intake(IntakeIO io) { - this.io = io; - setDefaultCommand( - run( - () -> io.set(0.0, 0.0))); - } - - @Override - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Intake", inputs); - - - } - - /** Returns a command that intakes a note. */ - public Command intakeCommandSpeedMatch() { - return runEnd(() -> { - // get swerve velocity in x - double speed = Units.metersToInches(Math.abs(SwerveSubsystem.getInstance().getRobotVelocity().vxMetersPerSecond)); // "grr I HATE metric!" - every American ever - // if the robot is moving, we'll want to match the speed of the robot, - // so we first calculate the number of rotations per second we need to intake - // luckily we already have the circumference from the Constants file - double intakeRps = speed / Constants.IntakeConstants.CIRCUMFERENCE; - // ...convert to RPM... - double intakeRpm = intakeRps * 60; - // ...and set the intake and cerealizer to that speed - io.setVelocity(-intakeRpm, -intakeRpm); - }, () -> { - io.set(0.0, 0.0); - }); - } - - /** Returns a command that intakes a note. Now with speed-agnostic output. */ - public Command intakeCommand() { - return runEnd(() -> { - io.setVelocity(Constants.IntakeConstants.INTAKE_SPEED, Constants.IntakeConstants.CEREALIZER_SPEED); - }, () -> { - io.set(0.0, 0.0); - }); - } - - public void setVelocity(double intakeRpm, double cerealizerRpm) { - io.setVelocity(intakeRpm, cerealizerRpm); - } - - public void set(double intakePercent, double cerealizerPercent) { - io.set(intakePercent, cerealizerPercent); - } - - public void setIntakeVelocity(double intakeRpm) { - io.setIntakeVelocity(intakeRpm); - } - - public void setCerealizerVelocity(double cerealizerRpm) { - io.setCerealizerVelocity(cerealizerRpm); - } - public void setCerealizer(double cerealizer) { io.setCerealizer(cerealizer);} - public void setIntake(double a) { io.setIntake(a);} - - public void setRunIntake(boolean runIntake) { - this.runIntake = runIntake; - } - - SysIdRoutine intakeSysId = new SysIdRoutine( - new SysIdRoutine.Config( - null, null, null, - (state) -> Logger.recordOutput("SysIdTestState", state.toString()) - ), - new SysIdRoutine.Mechanism((v) -> this.setIntakeVoltage(v.in(Volts)), null, this) - ); - SysIdRoutine cerealizerSysId = new SysIdRoutine( - new SysIdRoutine.Config( - null, null, null, - (state) -> Logger.recordOutput("SysIdTestState", state.toString()) - ), - new SysIdRoutine.Mechanism((v) -> this.setCerealizerVoltage(v.in(Volts)), null, this) - ); - - public static Command generateSysIdCommand(SysIdRoutine sysIdRoutine, double delay, double quasiTimeout, - double dynamicTimeout) { - return sysIdRoutine.quasistatic(SysIdRoutine.Direction.kForward).withTimeout(quasiTimeout) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.quasistatic(SysIdRoutine.Direction.kReverse).withTimeout(quasiTimeout)) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kForward).withTimeout(dynamicTimeout)) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)); - } - - public void setIntakeVoltage(double volts) { - io.setIntakeVoltage(volts); - } - - public void setCerealizerVoltage(double volts) { - io.setCerealizerVoltage(volts); - } - - public SysIdRoutine getIntakeSysId() { - return intakeSysId; - } - - public SysIdRoutine getCerealizerSysId() { - return cerealizerSysId; - } - - - - public DoubleSupplier getColorSensorProximity() { - return io.getColorSensorProximity(); - } - - public DoubleSupplier getColorSensorRed() { - return io.getColorSensorRed(); - } - - public DoubleSupplier getColorSensorGreen() { - return io.getColorSensorGreen(); - } - - public DoubleSupplier getColorSensorBlue() { - return io.getColorSensorBlue(); - } - - public DoubleSupplier getColorSensorIR() { - return io.getColorSensorIR(); - } - - - +@Suppress("ReplaceGetOrSet") +class Intake(val io: IntakeIO) : SubsystemBase() { + val inputs: IntakeIOInputsAutoLogged = IntakeIOInputsAutoLogged() + private var runIntake = true + + override fun periodic() { + io.updateInputs(inputs) + Logger.processInputs("Intake", inputs) + } + + /** Returns a command that intakes a note. */ + fun intakeCommandSpeedMatch(): Command { + return runEnd({ + // get swerve velocity in x + val speed = Units.metersToInches( + abs( + SwerveSubsystem.Companion.instance.robotVelocity.vxMetersPerSecond + ) + ) // "grr I HATE metric!" - every American ever + // if the robot is moving, we'll want to match the speed of the robot, + // so we first calculate the number of rotations per second we need to intake + // luckily we already have the circumference from the Constants file + val intakeRps = speed / IntakeConstants.CIRCUMFERENCE + // ...convert to RPM... + val intakeRpm = intakeRps * 60 + // ...and set the intake and cerealizer to that speed + io.setVelocity(-intakeRpm, -intakeRpm) + }, { + io.set(0.0, 0.0) + }) + } + + /** Returns a command that intakes a note. Now with speed-agnostic output. */ + fun intakeCommand(): Command { + return runEnd({ + io.setVelocity(IntakeConstants.INTAKE_SPEED, IntakeConstants.CEREALIZER_SPEED) + }, { + io[0.0] = 0.0 + }) + } + + fun setVelocity(intakeRpm: Double, cerealizerRpm: Double) { + io.setVelocity(intakeRpm, cerealizerRpm) + } + + operator fun set(intakePercent: Double, cerealizerPercent: Double) { + io[intakePercent] = cerealizerPercent + } + + fun setIntakeVelocity(intakeRpm: Double) { + io.setIntakeVelocity(intakeRpm) + } + + fun setCerealizerVelocity(cerealizerRpm: Double) { + io.setCerealizerVelocity(cerealizerRpm) + } + + fun setCerealizer(cerealizer: Double) { + io.setCerealizer(cerealizer) + } + + fun setIntake(a: Double) { + io.setIntake(a) + } + + fun setRunIntake(runIntake: Boolean) { + this.runIntake = runIntake + } + + var intakeSysId: SysIdRoutine = SysIdRoutine( + SysIdRoutine.Config( + null, null, null + ) { state: SysIdRoutineLog.State -> Logger.recordOutput("SysIdTestState", state.toString()) }, + Mechanism( + { v: Measure -> this.setIntakeVoltage(v.`in`(edu.wpi.first.units.Units.Volts)) }, + null, + this + ) + ) + var cerealizerSysId: SysIdRoutine = SysIdRoutine( + SysIdRoutine.Config( + null, null, null + ) { state: SysIdRoutineLog.State -> Logger.recordOutput("SysIdTestState", state.toString()) }, + Mechanism( + { v: Measure -> this.setCerealizerVoltage(v.`in`(edu.wpi.first.units.Units.Volts)) }, + null, + this + ) + ) + + init { + defaultCommand = run { io[0.0] = 0.0 } + } + + fun setIntakeVoltage(volts: Double) { + io.setIntakeVoltage(volts) + } + + fun setCerealizerVoltage(volts: Double) { + io.setCerealizerVoltage(volts) + } + + + val colorSensorProximity: DoubleSupplier? + get() = io.colorSensorProximity + + val colorSensorRed: DoubleSupplier? + get() = io.colorSensorRed + + val colorSensorGreen: DoubleSupplier? + get() = io.colorSensorGreen + + val colorSensorBlue: DoubleSupplier? + get() = io.colorSensorBlue + + val colorSensorIR: DoubleSupplier? + get() = io.colorSensorIR + + + companion object { + fun generateSysIdCommand( + sysIdRoutine: SysIdRoutine, delay: Double, quasiTimeout: Double, + dynamicTimeout: Double + ): Command { + return sysIdRoutine.quasistatic(SysIdRoutine.Direction.kForward).withTimeout(quasiTimeout) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.quasistatic(SysIdRoutine.Direction.kReverse).withTimeout(quasiTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kForward).withTimeout(dynamicTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)) + } + } } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIO.kt b/src/main/java/frc/robot/subsystems/intake/IntakeIO.kt index cfc3209..57675ec 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIO.kt +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIO.kt @@ -1,57 +1,130 @@ -package frc.robot.subsystems.intake; - -import edu.wpi.first.wpilibj.util.Color; -import org.littletonrobotics.junction.AutoLog; - -import java.util.function.DoubleSupplier; -import java.util.function.Supplier; - -public interface IntakeIO { - // Cerealizer (n.) - 1. A device that dispenses cereal. 2. A typo the robot lead made that stuck. - // fr tho this is hilarious - @AutoLog - public static class IntakeIOInputs { - public double intakePositionDegrees = 0.0; - public double intakeVelocityRpm = 0.0; - public double intakeAppliedVolts = 0.0; - public double[] intakeCurrentAmps = new double[] {}; - - public double cerealizerPositionDegrees = 0.0; - public double cerealizerVelocityRpm = 0.0; - public double cerealizerAppliedVolts = 0.0; - - public double[] cerealizerCurrentAmps = new double[] {}; - - } - - /** Updates the set of loggable inputs. */ - public default void updateInputs(IntakeIOInputs inputs) {} - - /** Run open loop at the specified voltage. */ - public default void set(double intakePercent, double cerealizerPercent) {} - - /** Run closed loop at the specified velocity. */ - public default void setVelocity( - double intakeRpm, double cerealizerRpm) {} - - public default void setIntakeVelocity(double intakeRpm) {} - public default void setCerealizerVelocity(double cerealizerRpm) {} - - public default void setCerealizer(double a) { } - public default void setIntake(double a) {} - - public default void setIntakeVoltage(double volts) {} - public default void setCerealizerVoltage(double volts) {} - - public DoubleSupplier getColorSensorProximity(); - - public DoubleSupplier getColorSensorRed(); - - public DoubleSupplier getColorSensorGreen(); - - public DoubleSupplier getColorSensorBlue(); - - public DoubleSupplier getColorSensorIR(); - - public Supplier getColorSensorColor(); +package frc.robot.subsystems.intake + +import edu.wpi.first.wpilibj.util.Color +import org.littletonrobotics.junction.AutoLog +import java.util.function.DoubleSupplier +import java.util.function.Supplier + +/** + * + */ +interface IntakeIO { + /** + * + */// Cerealizer (n.) - 1. A device that dispenses cereal. 2. A typo the robot lead made that stuck. + // fr tho this is hilarious + @AutoLog + open class IntakeIOInputs { + /** + * + */ + @JvmField + var intakePositionDegrees: Double = 0.0 + /** + * + */ + @JvmField + var intakeVelocityRpm: Double = 0.0 + /** + * + */ + @JvmField + var intakeAppliedVolts: Double = 0.0 + /** + * + */ + @JvmField + var intakeCurrentAmps: DoubleArray = doubleArrayOf() + + /** + * + */ + @JvmField + var cerealizerPositionDegrees: Double = 0.0 + /** + * + */ + @JvmField + var cerealizerVelocityRpm: Double = 0.0 + /** + * + */ + @JvmField + var cerealizerAppliedVolts: Double = 0.0 + + /** + * + */ + @JvmField + var cerealizerCurrentAmps: DoubleArray = doubleArrayOf() + } + + /** Updates the set of loggable inputs. */ + fun updateInputs(inputs: IntakeIOInputs) {} + + /** Run open loop at the specified voltage. */ + operator fun set(intakePercent: Double, cerealizerPercent: Double) {} + + /** Run closed loop at the specified velocity. */ + fun setVelocity( + intakeRpm: Double, cerealizerRpm: Double + ) { + } + + /** + * + */ + fun setIntakeVelocity(intakeRpm: Double) {} + /** + * + */ + fun setCerealizerVelocity(cerealizerRpm: Double) {} + + /** + * + */ + fun setCerealizer(a: Double) {} + /** + * + */ + fun setIntake(a: Double) {} + + /** + * + */ + fun setIntakeVoltage(volts: Double) {} + /** + * + */ + fun setCerealizerVoltage(volts: Double) {} + + /** + * + */ + val colorSensorProximity: DoubleSupplier + + /** + * + */ + val colorSensorRed: DoubleSupplier + + /** + * + */ + val colorSensorGreen: DoubleSupplier + + /** + * + */ + val colorSensorBlue: DoubleSupplier + + /** + * + */ + val colorSensorIR: DoubleSupplier + + /** + * + */ + val colorSensorColor: Supplier } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt b/src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt new file mode 100644 index 0000000..3a96afa --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt @@ -0,0 +1,58 @@ +// +// Source code recreated from a .class file by IntelliJ IDEA +// (powered by FernFlower decompiler) +// +package frc.robot.subsystems.intake + +import frc.robot.subsystems.intake.IntakeIO.IntakeIOInputs +import org.littletonrobotics.junction.LogTable +import org.littletonrobotics.junction.inputs.LoggableInputs + +/** + * + */ +class IntakeIOInputsAutoLogged : IntakeIOInputs(), LoggableInputs, Cloneable { + /** + * + */ + override fun toLog(table: LogTable) { + table.put("IntakePositionDegrees", this.intakePositionDegrees) + table.put("IntakeVelocityRpm", this.intakeVelocityRpm) + table.put("IntakeAppliedVolts", this.intakeAppliedVolts) + table.put("IntakeCurrentAmps", this.intakeCurrentAmps) + table.put("CerealizerPositionDegrees", this.cerealizerPositionDegrees) + table.put("CerealizerVelocityRpm", this.cerealizerVelocityRpm) + table.put("CerealizerAppliedVolts", this.cerealizerAppliedVolts) + table.put("CerealizerCurrentAmps", this.cerealizerCurrentAmps) + } + + /** + * + */ + override fun fromLog(table: LogTable) { + this.intakePositionDegrees = table["IntakePositionDegrees", intakePositionDegrees] + this.intakeVelocityRpm = table["IntakeVelocityRpm", intakeVelocityRpm] + this.intakeAppliedVolts = table["IntakeAppliedVolts", intakeAppliedVolts] + this.intakeCurrentAmps = table["IntakeCurrentAmps", intakeCurrentAmps] + this.cerealizerPositionDegrees = table["CerealizerPositionDegrees", cerealizerPositionDegrees] + this.cerealizerVelocityRpm = table["CerealizerVelocityRpm", cerealizerVelocityRpm] + this.cerealizerAppliedVolts = table["CerealizerAppliedVolts", cerealizerAppliedVolts] + this.cerealizerCurrentAmps = table["CerealizerCurrentAmps", cerealizerCurrentAmps] + } + + /** + * + */ + public override fun clone(): IntakeIOInputsAutoLogged { + val copy = IntakeIOInputsAutoLogged() + copy.intakePositionDegrees = this.intakePositionDegrees + copy.intakeVelocityRpm = this.intakeVelocityRpm + copy.intakeAppliedVolts = this.intakeAppliedVolts + copy.intakeCurrentAmps = intakeCurrentAmps.clone() + copy.cerealizerPositionDegrees = this.cerealizerPositionDegrees + copy.cerealizerVelocityRpm = this.cerealizerVelocityRpm + copy.cerealizerAppliedVolts = this.cerealizerAppliedVolts + copy.cerealizerCurrentAmps = cerealizerCurrentAmps.clone() + return copy + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt index 136fdd5..e53345b 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt @@ -1,171 +1,160 @@ -package frc.robot.subsystems.intake; - -import com.revrobotics.CANSparkBase; -import com.revrobotics.CANSparkLowLevel; -import com.revrobotics.CANSparkMax; -import com.revrobotics.ColorSensorV3; -import edu.wpi.first.math.MathUtil; -import edu.wpi.first.wpilibj.I2C; -import edu.wpi.first.wpilibj.util.Color; -import frc.robot.util.Constants; - -import java.util.function.DoubleSupplier; -import java.util.function.Supplier; +package frc.robot.subsystems.intake + +import com.revrobotics.CANSparkBase +import com.revrobotics.CANSparkBase.IdleMode +import com.revrobotics.CANSparkLowLevel +import com.revrobotics.CANSparkMax +import com.revrobotics.ColorSensorV3 +import edu.wpi.first.math.MathUtil +import edu.wpi.first.wpilibj.I2C +import edu.wpi.first.wpilibj.util.Color +import frc.robot.subsystems.intake.IntakeIO.IntakeIOInputs +import frc.robot.util.Constants.MotorConstants +import java.util.function.DoubleSupplier +import java.util.function.Supplier // apparently staying up late coding leads to deranged comments so that's cool -public class IntakeIOSparkMax implements IntakeIO { - public static final double MAX_RPM = 5700.0; - private final CANSparkMax intakeMotor = new CANSparkMax(Constants.MotorConstants.INTAKE_MOTOR, CANSparkLowLevel.MotorType.kBrushless); - private final CANSparkMax leftRollerMotor = new CANSparkMax(Constants.MotorConstants.LEFT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); - private final CANSparkMax rightRollerMotor = new CANSparkMax(Constants.MotorConstants.RIGHT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); - private final CANSparkMax cerealizerMotor = new CANSparkMax(Constants.MotorConstants.CEREALIZER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); - - private final ColorSensorV3 colorSensor = new ColorSensorV3(I2C.Port.kMXP); - - public IntakeIOSparkMax() { - - intakeMotor.setCANTimeout(250); - leftRollerMotor.setCANTimeout(250); - rightRollerMotor.setCANTimeout(250); - cerealizerMotor.setCANTimeout(250); - - intakeMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); - leftRollerMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); - rightRollerMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); - cerealizerMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); - - intakeMotor.setInverted(true); - leftRollerMotor.setInverted(false); - rightRollerMotor.setInverted(true); - cerealizerMotor.setInverted(false); - - intakeMotor.getPIDController().setFeedbackDevice(intakeMotor.getEncoder()); - leftRollerMotor.getPIDController().setFeedbackDevice(leftRollerMotor.getEncoder()); - rightRollerMotor.getPIDController().setFeedbackDevice(rightRollerMotor.getEncoder()); - cerealizerMotor.getPIDController().setFeedbackDevice(cerealizerMotor.getEncoder()); - - intakeMotor.setSmartCurrentLimit(20); - leftRollerMotor.setSmartCurrentLimit(20); - rightRollerMotor.setSmartCurrentLimit(20); - cerealizerMotor.setSmartCurrentLimit(20); - - intakeMotor.getEncoder().setVelocityConversionFactor(1); // 15:1 gear ratio - leftRollerMotor.getEncoder().setVelocityConversionFactor(1); // 20:1 gear ratio - rightRollerMotor.getEncoder().setVelocityConversionFactor(1); // 20:1 gear ratio - cerealizerMotor.getEncoder().setVelocityConversionFactor(1); // 20:1 gear ratio - - intakeMotor.getPIDController().setP(0.001); - intakeMotor.getPIDController().setI(0); - intakeMotor.getPIDController().setD(0.003); - intakeMotor.getPIDController().setIZone(0); - intakeMotor.getPIDController().setFF(0.001); - intakeMotor.getPIDController().setOutputRange(-1, 1); - intakeMotor.getPIDController().setSmartMotionMaxVelocity(1800, 0); - intakeMotor.getPIDController().setSmartMotionMinOutputVelocity(0, 0); - intakeMotor.getPIDController().setSmartMotionMaxAccel(1000, 0); - - - cerealizerMotor.getPIDController().setP(0.0005); - cerealizerMotor.getPIDController().setI(0); - cerealizerMotor.getPIDController().setD(0.005); - cerealizerMotor.getPIDController().setIZone(0); - cerealizerMotor.getPIDController().setFF(0); - cerealizerMotor.getPIDController().setOutputRange(-1, 1); - cerealizerMotor.getPIDController().setSmartMotionMaxVelocity(5200, 0); - cerealizerMotor.getPIDController().setSmartMotionMaxAccel(2000, 0); - cerealizerMotor.getPIDController().setSmartMotionMinOutputVelocity(0, 0); - - intakeMotor.burnFlash(); - leftRollerMotor.burnFlash(); - rightRollerMotor.burnFlash(); - cerealizerMotor.burnFlash(); - - } - - @Override - public void updateInputs(IntakeIOInputs inputs) { - inputs.intakePositionDegrees = intakeMotor.getEncoder().getPosition(); - inputs.intakeVelocityRpm = intakeMotor.getEncoder().getVelocity(); - inputs.intakeAppliedVolts = intakeMotor.getAppliedOutput() * intakeMotor.getBusVoltage(); - inputs.intakeCurrentAmps = new double[]{intakeMotor.getOutputCurrent()}; - - inputs.cerealizerPositionDegrees = cerealizerMotor.getEncoder().getPosition(); - inputs.cerealizerVelocityRpm = cerealizerMotor.getEncoder().getVelocity(); - inputs.cerealizerAppliedVolts = cerealizerMotor.getAppliedOutput() * cerealizerMotor.getBusVoltage(); - inputs.cerealizerCurrentAmps = new double[]{cerealizerMotor.getOutputCurrent()}; - } - - @Override - public void set(double intakePercent, double cerealizerPercent) { - intakeMotor.set(intakePercent); - leftRollerMotor.set(intakePercent); - rightRollerMotor.set(intakePercent); - cerealizerMotor.set(cerealizerPercent); - } - - @Override - public void setVelocity(double intakeRpm, double cerealizerRpm) { - // clamp the RPM to the max RPM - intakeRpm = MathUtil.clamp(intakeRpm, 0.0, MAX_RPM); - cerealizerRpm = MathUtil.clamp(cerealizerRpm, 0.0, MAX_RPM); - // kid named cambrian explosion - intakeMotor.getPIDController().setReference(intakeRpm, CANSparkBase.ControlType.kSmartVelocity, 0); - cerealizerMotor.getPIDController().setReference(cerealizerRpm, CANSparkBase.ControlType.kSmartVelocity, 0); - } - - @Override - public void setIntakeVelocity(double intakeRpm) { - intakeMotor.getPIDController().setReference(intakeRpm, CANSparkBase.ControlType.kSmartVelocity, 0); - } - - @Override - public void setCerealizerVelocity(double cerealizerRpm) { - cerealizerMotor.getPIDController().setReference(cerealizerRpm, CANSparkBase.ControlType.kSmartVelocity, 0); - } - - @Override - public void setCerealizer(double a) { - cerealizerMotor.set(a); - } - - @Override - public void setIntake(double a) { - intakeMotor.set(a); - } - - - @Override - public void setIntakeVoltage(double volts) { - intakeMotor.setVoltage(volts); - } - - @Override - public void setCerealizerVoltage(double volts) { - cerealizerMotor.setVoltage(volts); - } - - - public DoubleSupplier getColorSensorProximity() { - return colorSensor::getProximity; - } - - public DoubleSupplier getColorSensorRed() { - return colorSensor::getRed; - } - - public DoubleSupplier getColorSensorGreen() { - return colorSensor::getGreen; - } - - public DoubleSupplier getColorSensorBlue() { - return colorSensor::getBlue; - } - - public DoubleSupplier getColorSensorIR() { - return colorSensor::getIR; - } - - public Supplier getColorSensorColor() { - return colorSensor::getColor; - } +class IntakeIOSparkMax : IntakeIO { + private val intakeMotor = CANSparkMax(MotorConstants.INTAKE_MOTOR, CANSparkLowLevel.MotorType.kBrushless) + private val leftRollerMotor = CANSparkMax(MotorConstants.LEFT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless) + private val rightRollerMotor = CANSparkMax(MotorConstants.RIGHT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless) + private val cerealizerMotor = CANSparkMax(MotorConstants.CEREALIZER_MOTOR, CANSparkLowLevel.MotorType.kBrushless) + + private val colorSensor = ColorSensorV3(I2C.Port.kMXP) + + init { + intakeMotor.setCANTimeout(250) + leftRollerMotor.setCANTimeout(250) + rightRollerMotor.setCANTimeout(250) + cerealizerMotor.setCANTimeout(250) + + intakeMotor.setIdleMode(IdleMode.kBrake) + leftRollerMotor.setIdleMode(IdleMode.kBrake) + rightRollerMotor.setIdleMode(IdleMode.kBrake) + cerealizerMotor.setIdleMode(IdleMode.kBrake) + + intakeMotor.inverted = true + leftRollerMotor.inverted = false + rightRollerMotor.inverted = true + cerealizerMotor.inverted = false + + intakeMotor.pidController.setFeedbackDevice(intakeMotor.encoder) + leftRollerMotor.pidController.setFeedbackDevice(leftRollerMotor.encoder) + rightRollerMotor.pidController.setFeedbackDevice(rightRollerMotor.encoder) + cerealizerMotor.pidController.setFeedbackDevice(cerealizerMotor.encoder) + + intakeMotor.setSmartCurrentLimit(20) + leftRollerMotor.setSmartCurrentLimit(20) + rightRollerMotor.setSmartCurrentLimit(20) + cerealizerMotor.setSmartCurrentLimit(20) + + intakeMotor.encoder.setVelocityConversionFactor(1.0) // 15:1 gear ratio + leftRollerMotor.encoder.setVelocityConversionFactor(1.0) // 20:1 gear ratio + rightRollerMotor.encoder.setVelocityConversionFactor(1.0) // 20:1 gear ratio + cerealizerMotor.encoder.setVelocityConversionFactor(1.0) // 20:1 gear ratio + + intakeMotor.pidController.setP(0.001) + intakeMotor.pidController.setI(0.0) + intakeMotor.pidController.setD(0.003) + intakeMotor.pidController.setIZone(0.0) + intakeMotor.pidController.setFF(0.001) + intakeMotor.pidController.setOutputRange(-1.0, 1.0) + intakeMotor.pidController.setSmartMotionMaxVelocity(1800.0, 0) + intakeMotor.pidController.setSmartMotionMinOutputVelocity(0.0, 0) + intakeMotor.pidController.setSmartMotionMaxAccel(1000.0, 0) + + + cerealizerMotor.pidController.setP(0.0005) + cerealizerMotor.pidController.setI(0.0) + cerealizerMotor.pidController.setD(0.005) + cerealizerMotor.pidController.setIZone(0.0) + cerealizerMotor.pidController.setFF(0.0) + cerealizerMotor.pidController.setOutputRange(-1.0, 1.0) + cerealizerMotor.pidController.setSmartMotionMaxVelocity(5200.0, 0) + cerealizerMotor.pidController.setSmartMotionMaxAccel(2000.0, 0) + cerealizerMotor.pidController.setSmartMotionMinOutputVelocity(0.0, 0) + + intakeMotor.burnFlash() + leftRollerMotor.burnFlash() + rightRollerMotor.burnFlash() + cerealizerMotor.burnFlash() + } + + override fun updateInputs(inputs: IntakeIOInputs) { + inputs.intakePositionDegrees = intakeMotor.encoder.position + inputs.intakeVelocityRpm = intakeMotor.encoder.velocity + inputs.intakeAppliedVolts = intakeMotor.appliedOutput * intakeMotor.busVoltage + inputs.intakeCurrentAmps = doubleArrayOf(intakeMotor.outputCurrent) + + inputs.cerealizerPositionDegrees = cerealizerMotor.encoder.position + inputs.cerealizerVelocityRpm = cerealizerMotor.encoder.velocity + inputs.cerealizerAppliedVolts = cerealizerMotor.appliedOutput * cerealizerMotor.busVoltage + inputs.cerealizerCurrentAmps = doubleArrayOf(cerealizerMotor.outputCurrent) + } + + override fun set(intakePercent: Double, cerealizerPercent: Double) { + intakeMotor.set(intakePercent) + leftRollerMotor.set(intakePercent) + rightRollerMotor.set(intakePercent) + cerealizerMotor.set(cerealizerPercent) + } + + override fun setVelocity(intakeRpm: Double, cerealizerRpm: Double) { + // clamp the RPM to the max RPM + var intakeRpm = intakeRpm + var cerealizerRpm = cerealizerRpm + intakeRpm = MathUtil.clamp(intakeRpm, 0.0, MAX_RPM) + cerealizerRpm = MathUtil.clamp(cerealizerRpm, 0.0, MAX_RPM) + // kid named cambrian explosion + intakeMotor.pidController.setReference(intakeRpm, CANSparkBase.ControlType.kSmartVelocity, 0) + cerealizerMotor.pidController.setReference(cerealizerRpm, CANSparkBase.ControlType.kSmartVelocity, 0) + } + + override fun setIntakeVelocity(intakeRpm: Double) { + intakeMotor.pidController.setReference(intakeRpm, CANSparkBase.ControlType.kSmartVelocity, 0) + } + + override fun setCerealizerVelocity(cerealizerRpm: Double) { + cerealizerMotor.pidController.setReference(cerealizerRpm, CANSparkBase.ControlType.kSmartVelocity, 0) + } + + override fun setCerealizer(a: Double) { + cerealizerMotor.set(a) + } + + override fun setIntake(a: Double) { + intakeMotor.set(a) + } + + + override fun setIntakeVoltage(volts: Double) { + intakeMotor.setVoltage(volts) + } + + override fun setCerealizerVoltage(volts: Double) { + cerealizerMotor.setVoltage(volts) + } + + + override val colorSensorProximity: DoubleSupplier + get() = DoubleSupplier { colorSensor.proximity.toDouble() } + + override val colorSensorRed: DoubleSupplier + get() = DoubleSupplier { colorSensor.red.toDouble() } + + override val colorSensorGreen: DoubleSupplier + get() = DoubleSupplier { colorSensor.green.toDouble() } + + override val colorSensorBlue: DoubleSupplier + get() = DoubleSupplier { colorSensor.blue.toDouble() } + + override val colorSensorIR: DoubleSupplier + get() = DoubleSupplier { colorSensor.ir.toDouble() } + + override val colorSensorColor: Supplier + get() = Supplier { colorSensor.color } + + companion object { + const val MAX_RPM: Double = 5700.0 + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.kt b/src/main/java/frc/robot/subsystems/shooter/Shooter.kt index 51f8196..e9ccb73 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.kt +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.kt @@ -1,57 +1,58 @@ -package frc.robot.subsystems.shooter; - -import edu.wpi.first.units.Units; -import edu.wpi.first.units.Voltage; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import frc.robot.util.Constants; -import org.littletonrobotics.junction.Logger; - -import java.util.function.DoubleSupplier; - -public class Shooter extends SubsystemBase { - public static final double launchVelocity = Constants.ShooterConstants.MAX_RPM; - private final ShooterIO io; - private final ShooterIOInputsAutoLogged inputs = new ShooterIOInputsAutoLogged(); - private final double feedforward = Constants.ShooterConstants.FF; - - public Shooter(ShooterIO io) { - this.io = io; - setDefaultCommand( - run( - () -> io.set(0.0, 0.0))); - } - - @Override - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Shooter", inputs); - } - - public void set(double lowerPercent, double upperPercent) { - io.set(lowerPercent, upperPercent); - } - - public void setVelocity(double lowerRpm, double upperRpm) { - io.setVelocity(lowerRpm, upperRpm); - } - - - public SysIdRoutine getSysIdRoutine() { - return new SysIdRoutine(new SysIdRoutine.Config(), new SysIdRoutine.Mechanism((v) -> io.setVoltage(v.in(Units.Volt)), null, this)); - } - - public Command generateSysIdCommand(SysIdRoutine sysIdRoutine, double delay, double quasiTimeout, - double dynamicTimeout) - { - return sysIdRoutine.quasistatic(SysIdRoutine.Direction.kForward).withTimeout(quasiTimeout) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.quasistatic(SysIdRoutine.Direction.kReverse).withTimeout(quasiTimeout)) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kForward).withTimeout(dynamicTimeout)) - .andThen(Commands.waitSeconds(delay)) - .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)); - } +package frc.robot.subsystems.shooter + +import edu.wpi.first.units.Measure +import edu.wpi.first.units.Units +import edu.wpi.first.units.Voltage +import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.Commands +import edu.wpi.first.wpilibj2.command.SubsystemBase +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Mechanism +import frc.robot.util.Constants.ShooterConstants +import org.littletonrobotics.junction.Logger + +class Shooter(private val io: ShooterIO) : SubsystemBase() { + private val inputs = ShooterIOInputsAutoLogged() + private val feedforward = ShooterConstants.FF + + init { + defaultCommand = run { io.set(0.0, 0.0) } + } + + override fun periodic() { + io.updateInputs(inputs) + Logger.processInputs("Shooter", inputs) + } + + operator fun set(lowerPercent: Double, upperPercent: Double) { + io[lowerPercent] = upperPercent + } + + fun setVelocity(lowerRpm: Double, upperRpm: Double) { + io.setVelocity(lowerRpm, upperRpm) + } + + + val sysIdRoutine: SysIdRoutine + get() = SysIdRoutine( + SysIdRoutine.Config(), + Mechanism({ v: Measure -> io.setVoltage(v.`in`(Units.Volt)) }, null, this) + ) + + fun generateSysIdCommand( + sysIdRoutine: SysIdRoutine, delay: Double, quasiTimeout: Double, + dynamicTimeout: Double + ): Command { + return sysIdRoutine.quasistatic(SysIdRoutine.Direction.kForward).withTimeout(quasiTimeout) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.quasistatic(SysIdRoutine.Direction.kReverse).withTimeout(quasiTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kForward).withTimeout(dynamicTimeout)) + .andThen(Commands.waitSeconds(delay)) + .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)) + } + + companion object { + const val launchVelocity: Double = ShooterConstants.MAX_RPM + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.kt b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.kt index e0fab4d..0f77c92 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.kt +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.kt @@ -1,38 +1,103 @@ -package frc.robot.subsystems.shooter; +package frc.robot.subsystems.shooter -import org.littletonrobotics.junction.AutoLog; +import org.littletonrobotics.junction.AutoLog -public interface ShooterIO { - @AutoLog - public static class ShooterIOInputs { - public double lowerPositionDegrees = 0.0; - public double lowerVelocityRpm = 0.0; - public double lowerAppliedVolts = 0.0; - public double lowerRpmSetpoint = 0.0; - public double lowerSurfaceSpeed = 0.0; - public double lowerOutput = 0.0; - public double[] lowerCurrentAmps = new double[] {}; +/** + * + */ +interface ShooterIO { + /** + * + */ + @AutoLog + open class ShooterIOInputs { + /** + * + */ + @JvmField + var lowerPositionDegrees: Double = 0.0 + /** + * + */ + @JvmField + var lowerVelocityRpm: Double = 0.0 + /** + * + */ + @JvmField + var lowerAppliedVolts: Double = 0.0 + /** + * + */ + @JvmField + var lowerRpmSetpoint: Double = 0.0 + /** + * + */ + @JvmField + var lowerSurfaceSpeed: Double = 0.0 + /** + * + */ + @JvmField + var lowerOutput: Double = 0.0 + /** + * + */ + @JvmField + var lowerCurrentAmps: DoubleArray = doubleArrayOf() - public double upperPositionDegrees = 0.0; - public double upperVelocityRpm = 0.0; - public double upperAppliedVolts = 0.0; - public double upperRpmSetpoint = 0.0; - public double upperSurfaceSpeed = 0.0; - public double upperOutput = 0.0; - public double[] upperCurrentAmps = new double[] {}; - } + /** + * + */ + @JvmField + var upperPositionDegrees: Double = 0.0 + /** + * + */ + @JvmField + var upperVelocityRpm: Double = 0.0 + /** + * + */ + @JvmField + var upperAppliedVolts: Double = 0.0 + /** + * + */ + @JvmField + var upperRpmSetpoint: Double = 0.0 + /** + * + */ + @JvmField + var upperSurfaceSpeed: Double = 0.0 + /** + * + */ + @JvmField + var upperOutput: Double = 0.0 + /** + * + */ + @JvmField + var upperCurrentAmps: DoubleArray = doubleArrayOf() + } - /** Updates the set of loggable inputs. */ - public default void updateInputs(ShooterIOInputs inputs) {} + /** Updates the set of loggable inputs. */ + fun updateInputs(inputs: ShooterIOInputs) {} - /** Run open loop at the specified voltage. */ - public default void set(double lowerPercent, double upperPercent) {} - - /** Run closed loop at the specified velocity. */ - public default void setVelocity( - double lowerRpm, double upperRpm) {} - - public default void setVoltage(double volts) {} + /** Run open loop at the specified voltage. */ + operator fun set(lowerPercent: Double, upperPercent: Double) {} + /** Run closed loop at the specified velocity. */ + fun setVelocity( + lowerRpm: Double, upperRpm: Double + ) { + } + /** + * + */ + fun setVoltage(volts: Double) {} } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOInputsAutoLogged.kt b/src/main/java/frc/robot/subsystems/shooter/ShooterIOInputsAutoLogged.kt new file mode 100644 index 0000000..1cf78e4 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOInputsAutoLogged.kt @@ -0,0 +1,76 @@ +// +// Source code recreated from a .class file by IntelliJ IDEA +// (powered by FernFlower decompiler) +// +package frc.robot.subsystems.shooter + +import frc.robot.subsystems.shooter.ShooterIO.ShooterIOInputs +import org.littletonrobotics.junction.LogTable +import org.littletonrobotics.junction.inputs.LoggableInputs + +/** + * + */ +class ShooterIOInputsAutoLogged : ShooterIOInputs(), LoggableInputs, Cloneable { + /** + * + */ + override fun toLog(table: LogTable) { + table.put("LowerPositionDegrees", this.lowerPositionDegrees) + table.put("LowerVelocityRpm", this.lowerVelocityRpm) + table.put("LowerAppliedVolts", this.lowerAppliedVolts) + table.put("LowerRpmSetpoint", this.lowerRpmSetpoint) + table.put("LowerSurfaceSpeed", this.lowerSurfaceSpeed) + table.put("LowerOutput", this.lowerOutput) + table.put("LowerCurrentAmps", this.lowerCurrentAmps) + table.put("UpperPositionDegrees", this.upperPositionDegrees) + table.put("UpperVelocityRpm", this.upperVelocityRpm) + table.put("UpperAppliedVolts", this.upperAppliedVolts) + table.put("UpperRpmSetpoint", this.upperRpmSetpoint) + table.put("UpperSurfaceSpeed", this.upperSurfaceSpeed) + table.put("UpperOutput", this.upperOutput) + table.put("UpperCurrentAmps", this.upperCurrentAmps) + } + + /** + * + */ + override fun fromLog(table: LogTable) { + this.lowerPositionDegrees = table["LowerPositionDegrees", lowerPositionDegrees] + this.lowerVelocityRpm = table["LowerVelocityRpm", lowerVelocityRpm] + this.lowerAppliedVolts = table["LowerAppliedVolts", lowerAppliedVolts] + this.lowerRpmSetpoint = table["LowerRpmSetpoint", lowerRpmSetpoint] + this.lowerSurfaceSpeed = table["LowerSurfaceSpeed", lowerSurfaceSpeed] + this.lowerOutput = table["LowerOutput", lowerOutput] + this.lowerCurrentAmps = table["LowerCurrentAmps", lowerCurrentAmps] + this.upperPositionDegrees = table["UpperPositionDegrees", upperPositionDegrees] + this.upperVelocityRpm = table["UpperVelocityRpm", upperVelocityRpm] + this.upperAppliedVolts = table["UpperAppliedVolts", upperAppliedVolts] + this.upperRpmSetpoint = table["UpperRpmSetpoint", upperRpmSetpoint] + this.upperSurfaceSpeed = table["UpperSurfaceSpeed", upperSurfaceSpeed] + this.upperOutput = table["UpperOutput", upperOutput] + this.upperCurrentAmps = table["UpperCurrentAmps", upperCurrentAmps] + } + + /** + * + */ + public override fun clone(): ShooterIOInputsAutoLogged { + val copy = ShooterIOInputsAutoLogged() + copy.lowerPositionDegrees = this.lowerPositionDegrees + copy.lowerVelocityRpm = this.lowerVelocityRpm + copy.lowerAppliedVolts = this.lowerAppliedVolts + copy.lowerRpmSetpoint = this.lowerRpmSetpoint + copy.lowerSurfaceSpeed = this.lowerSurfaceSpeed + copy.lowerOutput = this.lowerOutput + copy.lowerCurrentAmps = lowerCurrentAmps.clone() + copy.upperPositionDegrees = this.upperPositionDegrees + copy.upperVelocityRpm = this.upperVelocityRpm + copy.upperAppliedVolts = this.upperAppliedVolts + copy.upperRpmSetpoint = this.upperRpmSetpoint + copy.upperSurfaceSpeed = this.upperSurfaceSpeed + copy.upperOutput = this.upperOutput + copy.upperCurrentAmps = upperCurrentAmps.clone() + return copy + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.kt b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.kt index fbec00b..e4b1e87 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.kt +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.kt @@ -1,57 +1,53 @@ -package frc.robot.subsystems.shooter; - -import com.revrobotics.CANSparkLowLevel; -import com.revrobotics.CANSparkMax; -import com.revrobotics.REVPhysicsSim; -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.system.LinearSystem; -import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.simulation.DCMotorSim; -import edu.wpi.first.wpilibj.simulation.EncoderSim; -import frc.robot.util.Constants; - -public class ShooterIOSim implements ShooterIO { - private DCMotorSim lowerMotorSim = new DCMotorSim(DCMotor.getNEO(1), 1, 0.0001); - private DCMotorSim upperMotorSim = new DCMotorSim(DCMotor.getNEO(1), 1, 0.0001); - private EncoderSim lowerEncoderSim = new EncoderSim(new Encoder(0, 1)); - private EncoderSim upperEncoderSim = new EncoderSim(new Encoder(2, 3)); - - private PIDController lowerController = new PIDController(Constants.ShooterConstants.P, Constants.ShooterConstants.I, Constants.ShooterConstants.D); - private PIDController upperController = new PIDController(Constants.ShooterConstants.P, Constants.ShooterConstants.I, Constants.ShooterConstants.D); - - private double lowerAppliedVolts = 0.0; - private double upperAppliedVolts = 0.0; - - @Override - public void updateInputs(ShooterIOInputs inputs) { - lowerMotorSim.update(0.02); - upperMotorSim.update(0.02); - - inputs.lowerPositionDegrees = Units.radiansToDegrees(lowerMotorSim.getAngularPositionRad()); - inputs.lowerVelocityRpm = Units.radiansPerSecondToRotationsPerMinute(lowerMotorSim.getAngularVelocityRadPerSec()); - inputs.lowerAppliedVolts = lowerAppliedVolts; - inputs.lowerCurrentAmps = new double[] {lowerMotorSim.getCurrentDrawAmps()}; - - inputs.upperPositionDegrees = Units.radiansToDegrees(upperMotorSim.getAngularPositionRad()); - inputs.upperVelocityRpm = Units.radiansPerSecondToRotationsPerMinute(upperMotorSim.getAngularVelocityRadPerSec()); - inputs.upperAppliedVolts = upperAppliedVolts; - inputs.upperCurrentAmps = new double[] {upperMotorSim.getCurrentDrawAmps()}; - } - - @Override - public void set(double lowerPercent, double upperPercent) { - lowerMotorSim.setInputVoltage(lowerPercent * 12); - upperMotorSim.setInputVoltage(upperPercent * 12); - } - - @Override - public void setVelocity(double lowerRpm, double upperRpm) { - lowerController.setSetpoint(lowerRpm); - upperController.setSetpoint(upperRpm); - lowerMotorSim.setInputVoltage(lowerController.calculate(lowerMotorSim.getAngularVelocityRadPerSec(), lowerRpm)); - upperMotorSim.setInputVoltage(upperController.calculate(upperMotorSim.getAngularVelocityRadPerSec(), upperRpm)); - } - +package frc.robot.subsystems.shooter + +import edu.wpi.first.math.controller.PIDController +import edu.wpi.first.math.system.plant.DCMotor +import edu.wpi.first.math.util.Units +import edu.wpi.first.wpilibj.Encoder +import edu.wpi.first.wpilibj.simulation.DCMotorSim +import edu.wpi.first.wpilibj.simulation.EncoderSim +import frc.robot.subsystems.shooter.ShooterIO.ShooterIOInputs +import frc.robot.util.Constants.ShooterConstants + +/** + * + */ +class ShooterIOSim : ShooterIO { + private val lowerMotorSim = DCMotorSim(DCMotor.getNEO(1), 1.0, 0.0001) + private val upperMotorSim = DCMotorSim(DCMotor.getNEO(1), 1.0, 0.0001) + private val lowerEncoderSim = EncoderSim(Encoder(0, 1)) + private val upperEncoderSim = EncoderSim(Encoder(2, 3)) + + private val lowerController = PIDController(ShooterConstants.P, ShooterConstants.I, ShooterConstants.D) + private val upperController = PIDController(ShooterConstants.P, ShooterConstants.I, ShooterConstants.D) + + private val lowerAppliedVolts = 0.0 + private val upperAppliedVolts = 0.0 + + override fun updateInputs(inputs: ShooterIOInputs) { + lowerMotorSim.update(0.02) + upperMotorSim.update(0.02) + + inputs.lowerPositionDegrees = Units.radiansToDegrees(lowerMotorSim.angularPositionRad) + inputs.lowerVelocityRpm = Units.radiansPerSecondToRotationsPerMinute(lowerMotorSim.angularVelocityRadPerSec) + inputs.lowerAppliedVolts = lowerAppliedVolts + inputs.lowerCurrentAmps = doubleArrayOf(lowerMotorSim.currentDrawAmps) + + inputs.upperPositionDegrees = Units.radiansToDegrees(upperMotorSim.angularPositionRad) + inputs.upperVelocityRpm = Units.radiansPerSecondToRotationsPerMinute(upperMotorSim.angularVelocityRadPerSec) + inputs.upperAppliedVolts = upperAppliedVolts + inputs.upperCurrentAmps = doubleArrayOf(upperMotorSim.currentDrawAmps) + } + + override fun set(lowerPercent: Double, upperPercent: Double) { + lowerMotorSim.setInputVoltage(lowerPercent * 12) + upperMotorSim.setInputVoltage(upperPercent * 12) + } + + override fun setVelocity(lowerRpm: Double, upperRpm: Double) { + lowerController.setpoint = lowerRpm + upperController.setpoint = upperRpm + lowerMotorSim.setInputVoltage(lowerController.calculate(lowerMotorSim.angularVelocityRadPerSec, lowerRpm)) + upperMotorSim.setInputVoltage(upperController.calculate(upperMotorSim.angularVelocityRadPerSec, upperRpm)) + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt index 3393ecc..c248013 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt @@ -1,123 +1,123 @@ -package frc.robot.subsystems.shooter; - -import com.revrobotics.*; -import edu.wpi.first.math.controller.SimpleMotorFeedforward; -import edu.wpi.first.math.geometry.Translation3d; -import edu.wpi.first.math.util.Units; -import frc.robot.util.Constants; -import frc.robot.FieldConstants; - -public class ShooterIOSparkFlex implements ShooterIO { - // Calculated constants from Recalc (https://www.reca.lc/flywheel?currentLimit=%7B%22s%22%3A40%2C%22u%22%3A%22A%22%7D&efficiency=100&flywheelMomentOfInertia=%7B%22s%22%3A555625%2C%22u%22%3A%22mm2%2Ag%22%7D&flywheelRadius=%7B%22s%22%3A50%2C%22u%22%3A%22mm%22%7D&flywheelRatio=%7B%22magnitude%22%3A1%2C%22ratioType%22%3A%22Reduction%22%7D&flywheelWeight=%7B%22s%22%3A444.5%2C%22u%22%3A%22g%22%7D&motor=%7B%22quantity%22%3A1%2C%22name%22%3A%22NEO%20Vortex%2A%22%7D&motorRatio=%7B%22magnitude%22%3A1%2C%22ratioType%22%3A%22Step-up%22%7D&projectileRadius=%7B%22s%22%3A2%2C%22u%22%3A%22in%22%7D&projectileWeight=%7B%22s%22%3A8.3%2C%22u%22%3A%22oz%22%7D&shooterMomentOfInertia=%7B%22s%22%3A1.614%2C%22u%22%3A%22in2%2Albs%22%7D&shooterRadius=%7B%22s%22%3A2%2C%22u%22%3A%22in%22%7D&shooterTargetSpeed=%7B%22s%22%3A6783%2C%22u%22%3A%22rpm%22%7D&shooterWeight=%7B%22s%22%3A0.807%2C%22u%22%3A%22lbs%22%7D&useCustomFlywheelMoi=0&useCustomShooterMoi=0): - // using: - // current limit: 40 A - // efficiency: 100% - // ratio: 1:1 - // target shooter rpm: 6783 (out of the max 6784) - // projectile weight: 8.3 oz (from https://www.andymark.com/products/frc-2024-am-4999) - // shooter radius: 2 in - // shooter weight: 17.216 oz (4x 4.304 oz. 4 in. diameter wheels; durometer doesn't matter here https://www.andymark.com/products/4-in-compliant-wheels-options) - // flywheel: { - // hex shaft: 6.043 oz (17.5 in; 0.345... oz/in) - // neo vortex: 444.5 g - // total: 615.8161682 g - // diameter: 50 mm - // ratio: 1:1 - // } - // - // this gives an estimated projectile speed of 45.40 ft/s - - // distance from shooter axle to center of shooting area: 12 1/8 in - // distance from shooter axle to ground: 22 1/4 in - - private final CANSparkFlex lowerMotor = new CANSparkFlex(Constants.MotorConstants.LOWER_SHOOTER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); - private final CANSparkFlex upperMotor = new CANSparkFlex(Constants.MotorConstants.UPPER_SHOOTER_MOTOR, CANSparkLowLevel.MotorType.kBrushless); - private final RelativeEncoder lowerEncoder = lowerMotor.getEncoder(); - private final RelativeEncoder upperEncoder = upperMotor.getEncoder(); - private final SparkPIDController lowerPID = lowerMotor.getPIDController(); - private final SparkPIDController upperPID = upperMotor.getPIDController(); - public static final double P = Constants.ShooterConstants.P; - public static final double I = Constants.ShooterConstants.I; - public static final double D = Constants.ShooterConstants.D; - - - public ShooterIOSparkFlex() { - lowerEncoder.setPositionConversionFactor(1); - lowerEncoder.setVelocityConversionFactor(1); - upperEncoder.setPositionConversionFactor(1); - upperEncoder.setVelocityConversionFactor(1); - - - - var i = new SimpleMotorFeedforward(0.028196, 0.0017838, 0.00020814); - // use that to set the feed forward for the lower motor - lowerPID.setFF(i.calculate(0)); - - lowerPID.setP(1.0167e-7); - lowerPID.setI(0); - lowerPID.setD(0); - - upperMotor.follow(lowerMotor, true); - } - - @Override - public void updateInputs(ShooterIOInputs inputs) { - inputs.lowerPositionDegrees = lowerEncoder.getPosition(); - inputs.lowerVelocityRpm = lowerEncoder.getVelocity(); - inputs.lowerAppliedVolts = lowerMotor.getAppliedOutput() * lowerMotor.getBusVoltage(); - // Theoretically, - // I could implement a method to set surface speed and have that be the value the motors try to get to, - // but I don't know if we would actually use that. - // TODO: determine if we want to use surface speed - inputs.lowerSurfaceSpeed = lowerEncoder.getVelocity() * Constants.ShooterConstants.WHEEL_DIAMETER * Math.PI / 60.0 / 12.0; // feet per second - inputs.lowerOutput = lowerMotor.get(); - inputs.lowerCurrentAmps = new double[] {lowerMotor.getOutputCurrent()}; - - inputs.upperPositionDegrees = upperEncoder.getPosition(); - inputs.upperVelocityRpm = upperEncoder.getVelocity(); - inputs.upperAppliedVolts = upperMotor.getAppliedOutput() * upperMotor.getBusVoltage(); - inputs.upperSurfaceSpeed = upperEncoder.getVelocity() * Constants.ShooterConstants.WHEEL_DIAMETER * Math.PI / 60.0 / 12.0; // feet per second - inputs.upperOutput = upperMotor.get(); - inputs.upperCurrentAmps = new double[] {upperMotor.getOutputCurrent()}; - } - - @Override - public void set(double lowerPercent, double upperPercent) { - lowerMotor.set(lowerPercent); - upperMotor.set(upperPercent); - } - - @Override - public void setVelocity(double lowerRpm, double upperRpm) { - lowerPID.setReference(lowerRpm, CANSparkBase.ControlType.kSmartVelocity, 0); - upperPID.setReference(upperRpm, CANSparkBase.ControlType.kSmartVelocity, 0); - } - - @Override - public void setVoltage(double volts) { - lowerMotor.setVoltage(volts); - upperMotor.setVoltage(volts); - } - - - // now for the calculation of the angle and velocity we'll need to shoot to make it into the speaker -// public static double calculateAngle(Translation3d position) { -// // we will use feet for this calculation -// double x = Units.metersToFeet(position.getX()); -// double y = Units.metersToFeet(position.getY()); -// -// // from that, there is the problem of -// -// } -// -// public Translation3d calculateShooterDistanceFromGround(double angle) { -// // this can be calculated using pretty basic trigonometry -// double hypotenuse = 12.125; // inches -// double opposite = Math.sin(angle) * hypotenuse; -// double adjacent = Math.cos(angle) * hypotenuse; -// -// // the center of the robot is 5.5 inches from the axle -// double x = 5.5 - opposite; -// double y = 22.25 - adjacent; -// } +package frc.robot.subsystems.shooter + +import com.revrobotics.* +import edu.wpi.first.math.controller.SimpleMotorFeedforward +import frc.robot.subsystems.shooter.ShooterIO.ShooterIOInputs +import frc.robot.util.Constants.MotorConstants +import frc.robot.util.Constants.ShooterConstants + +class ShooterIOSparkFlex : ShooterIO { + // Calculated constants from Recalc (https://www.reca.lc/flywheel?currentLimit=%7B%22s%22%3A40%2C%22u%22%3A%22A%22%7D&efficiency=100&flywheelMomentOfInertia=%7B%22s%22%3A555625%2C%22u%22%3A%22mm2%2Ag%22%7D&flywheelRadius=%7B%22s%22%3A50%2C%22u%22%3A%22mm%22%7D&flywheelRatio=%7B%22magnitude%22%3A1%2C%22ratioType%22%3A%22Reduction%22%7D&flywheelWeight=%7B%22s%22%3A444.5%2C%22u%22%3A%22g%22%7D&motor=%7B%22quantity%22%3A1%2C%22name%22%3A%22NEO%20Vortex%2A%22%7D&motorRatio=%7B%22magnitude%22%3A1%2C%22ratioType%22%3A%22Step-up%22%7D&projectileRadius=%7B%22s%22%3A2%2C%22u%22%3A%22in%22%7D&projectileWeight=%7B%22s%22%3A8.3%2C%22u%22%3A%22oz%22%7D&shooterMomentOfInertia=%7B%22s%22%3A1.614%2C%22u%22%3A%22in2%2Albs%22%7D&shooterRadius=%7B%22s%22%3A2%2C%22u%22%3A%22in%22%7D&shooterTargetSpeed=%7B%22s%22%3A6783%2C%22u%22%3A%22rpm%22%7D&shooterWeight=%7B%22s%22%3A0.807%2C%22u%22%3A%22lbs%22%7D&useCustomFlywheelMoi=0&useCustomShooterMoi=0): + // using: + // current limit: 40 A + // efficiency: 100% + // ratio: 1:1 + // target shooter rpm: 6783 (out of the max 6784) + // projectile weight: 8.3 oz (from https://www.andymark.com/products/frc-2024-am-4999) + // shooter radius: 2 in + // shooter weight: 17.216 oz (4x 4.304 oz. 4 in. diameter wheels; durometer doesn't matter here https://www.andymark.com/products/4-in-compliant-wheels-options) + // flywheel: { + // hex shaft: 6.043 oz (17.5 in; 0.345... oz/in) + // neo vortex: 444.5 g + // total: 615.8161682 g + // diameter: 50 mm + // ratio: 1:1 + // } + // + // this gives an estimated projectile speed of 45.40 ft/s + // distance from shooter axle to center of shooting area: 12 1/8 in + // distance from shooter axle to ground: 22 1/4 in + private val lowerMotor = CANSparkFlex(MotorConstants.LOWER_SHOOTER_MOTOR, CANSparkLowLevel.MotorType.kBrushless) + private val upperMotor = CANSparkFlex(MotorConstants.UPPER_SHOOTER_MOTOR, CANSparkLowLevel.MotorType.kBrushless) + private val lowerEncoder: RelativeEncoder = lowerMotor.encoder + private val upperEncoder: RelativeEncoder = upperMotor.encoder + private val lowerPID: SparkPIDController = lowerMotor.pidController + private val upperPID: SparkPIDController = upperMotor.pidController + + init { + lowerEncoder.setPositionConversionFactor(1.0) + lowerEncoder.setVelocityConversionFactor(1.0) + upperEncoder.setPositionConversionFactor(1.0) + upperEncoder.setVelocityConversionFactor(1.0) + + lowerPID.setFeedbackDevice(lowerEncoder) + upperPID.setFeedbackDevice(upperEncoder) + + + val i = SimpleMotorFeedforward(0.028196, 0.0017838, 0.00020814) + // use that to set the feed forward for the lower motor + lowerPID.setFF(i.calculate(3750.0)) + upperPID.setFF(i.calculate(3750.0)) + + lowerPID.setP(0.0005) + lowerPID.setI(0.0) + lowerPID.setD(0.0) + + upperPID.setP(0.0005) + upperPID.setI(0.0) + upperPID.setD(0.0) + } + + override fun updateInputs(inputs: ShooterIOInputs) { + inputs.lowerPositionDegrees = lowerEncoder.position + inputs.lowerVelocityRpm = lowerEncoder.velocity + inputs.lowerAppliedVolts = lowerMotor.appliedOutput * lowerMotor.busVoltage + // Theoretically, + // I could implement a method to set surface speed and have that be the value the motors try to get to, + // but I don't know if we would actually use that. + // TODO: determine if we want to use surface speed + inputs.lowerSurfaceSpeed = + lowerEncoder.velocity * ShooterConstants.WHEEL_DIAMETER * Math.PI / 60.0 / 12.0 // feet per second + inputs.lowerOutput = lowerMotor.get() + inputs.lowerCurrentAmps = doubleArrayOf(lowerMotor.outputCurrent) + + inputs.upperPositionDegrees = upperEncoder.position + inputs.upperVelocityRpm = upperEncoder.velocity + inputs.upperAppliedVolts = upperMotor.appliedOutput * upperMotor.busVoltage + inputs.upperSurfaceSpeed = + upperEncoder.velocity * ShooterConstants.WHEEL_DIAMETER * Math.PI / 60.0 / 12.0 // feet per second + inputs.upperOutput = upperMotor.get() + inputs.upperCurrentAmps = doubleArrayOf(upperMotor.outputCurrent) + } + + override fun set(lowerPercent: Double, upperPercent: Double) { + lowerMotor.set(lowerPercent) + upperMotor.set(upperPercent) + } + + override fun setVelocity(lowerRpm: Double, upperRpm: Double) { + lowerPID.setReference(lowerRpm, CANSparkBase.ControlType.kSmartVelocity, 0) + upperPID.setReference(upperRpm, CANSparkBase.ControlType.kSmartVelocity, 0) + } + + override fun setVoltage(volts: Double) { + lowerMotor.setVoltage(volts) + upperMotor.setVoltage(volts) + } // now for the calculation of the angle and velocity we'll need to shoot to make it into the speaker + // public static double calculateAngle(Translation3d position) { + // // we will use feet for this calculation + // double x = Units.metersToFeet(position.getX()); + // double y = Units.metersToFeet(position.getY()); + // + // // from that, there is the problem of + // + // } + // + // public Translation3d calculateShooterDistanceFromGround(double angle) { + // // this can be calculated using pretty basic trigonometry + // double hypotenuse = 12.125; // inches + // double opposite = Math.sin(angle) * hypotenuse; + // double adjacent = Math.cos(angle) * hypotenuse; + // + // // the center of the robot is 5.5 inches from the axle + // double x = 5.5 - opposite; + // double y = 22.25 - adjacent; + // } + + + companion object { + const val P: Double = ShooterConstants.P + const val I: Double = ShooterConstants.I + const val D: Double = ShooterConstants.D + } } diff --git a/src/main/java/frc/robot/util/Alert.java b/src/main/java/frc/robot/util/Alert.java deleted file mode 100644 index 83d19cc..0000000 --- a/src/main/java/frc/robot/util/Alert.java +++ /dev/null @@ -1,193 +0,0 @@ -// Copyright (c) 2023 FRC 6328 -// http://github.com/Mechanical-Advantage -// -// Use of this source code is governed by an MIT-style -// license that can be found below. - -// MIT License -// -// Copyright (c) 2023 FRC 6328 -// -// Permission is hereby granted, free of charge, to any person obtaining a copy -// of this software and associated documentation files (the "Software"), to deal -// in the Software without restriction, including without limitation the rights -// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -// copies of the Software, and to permit persons to whom the Software is -// furnished to do so, subject to the following conditions: -// -// The above copyright notice and this permission notice shall be included in all -// copies or substantial portions of the Software. -// -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -// SOFTWARE. - -package frc.robot.util; - -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; -import java.util.HashMap; -import java.util.List; -import java.util.Map; -import java.util.function.Predicate; - -/** Class for managing persistent alerts to be sent over NetworkTables. */ -public class Alert { - private static final Map groups = new HashMap(); - - private final AlertType type; - private boolean active = false; - private double activeStartTime = 0.0; - private String text; - - /** - * Creates a new Alert in the default group - "Alerts". If this is the first to be instantiated, - * the appropriate entries will be added to NetworkTables. - * - * @param text Text to be displayed when the alert is active. - * @param type Alert level specifying urgency. - */ - public Alert(String text, AlertType type) { - this("Alerts", text, type); - } - - /** - * Creates a new Alert. If this is the first to be instantiated in its group, the appropriate - * entries will be added to NetworkTables. - * - * @param group Group identifier, also used as NetworkTables title - * @param text Text to be displayed when the alert is active. - * @param type Alert level specifying urgency. - */ - public Alert(String group, String text, AlertType type) { - if (!groups.containsKey(group)) { - groups.put(group, new SendableAlerts()); - SmartDashboard.putData(group, groups.get(group)); - } - - this.text = text; - this.type = type; - groups.get(group).alerts.add(this); - } - - /** - * Sets whether the alert should currently be displayed. When activated, the alert text will also - * be sent to the console. - */ - public void set(boolean active) { - if (active && !this.active) { - activeStartTime = Timer.getFPGATimestamp(); - switch (type) { - case ERROR: - DriverStation.reportError(text, false); - break; - case ERROR_TRACE: - DriverStation.reportError(text, true); - break; - case WARNING: - DriverStation.reportWarning(text, false); - break; - case WARNING_TRACE: - DriverStation.reportWarning(text, true); - break; - case INFO: - System.out.println(text); - break; - } - } - this.active = active; - } - - /** Updates current alert text. */ - public void setText(String text) { - if (active && !text.equals(this.text)) { - switch (type) { - case ERROR: - DriverStation.reportError(text, false); - break; - case ERROR_TRACE: - DriverStation.reportError(text, true); - break; - case WARNING: - DriverStation.reportWarning(text, false); - break; - case WARNING_TRACE: - DriverStation.reportWarning(text, true); - break; - case INFO: - System.out.println(text); - break; - } - } - this.text = text; - } - - private static class SendableAlerts implements Sendable { - public final List alerts = new ArrayList<>(); - - public String[] getStrings(AlertType type) { - Predicate activeFilter = (Alert x) -> x.type == type && x.active; - Comparator timeSorter = - (Alert a1, Alert a2) -> (int) (a2.activeStartTime - a1.activeStartTime); - return alerts.stream() - .filter(activeFilter) - .sorted(timeSorter) - .map((Alert a) -> a.text) - .toArray(String[]::new); - } - - @Override - public void initSendable(SendableBuilder builder) { - builder.setSmartDashboardType("Alerts"); - builder.addStringArrayProperty("errors", () -> getStrings(AlertType.ERROR), null); - builder.addStringArrayProperty("errors", () -> getStrings(AlertType.ERROR_TRACE), null); - builder.addStringArrayProperty("warnings", () -> getStrings(AlertType.WARNING), null); - builder.addStringArrayProperty("warnings", () -> getStrings(AlertType.WARNING_TRACE), null); - builder.addStringArrayProperty("infos", () -> getStrings(AlertType.INFO), null); - } - } - - /** Represents an alert's level of urgency. */ - public static enum AlertType { - /** - * High priority alert - displayed first on the dashboard with a red "X" symbol. Use this type - * for problems which will seriously affect the robot's functionality and thus require immediate - * attention. - */ - ERROR, - /** - * High priority alert - displayed first on the dashboard with a red "X" symbol. Use this type - * for problems which will seriously affect the robot's functionality and thus require immediate - * attention. Trace printed to driver station console. - */ - ERROR_TRACE, - - /** - * Medium priority alert - displayed second on the dashboard with a yellow "!" symbol. Use this - * type for problems which could affect the robot's functionality but do not necessarily require - * immediate attention. - */ - WARNING, - /** - * Medium priority alert - displayed second on the dashboard with a yellow "!" symbol. Use this - * type for problems which could affect the robot's functionality but do not necessarily require - * immediate attention. Trace printed to driver station console. - */ - WARNING_TRACE, - /** - * Low priority alert - displayed last on the dashboard with a green "i" symbol. Use this type - * for problems which are unlikely to affect the robot's functionality, or any other alerts - * which do not fall under "ERROR" or "WARNING". - */ - INFO - } -} diff --git a/src/main/java/frc/robot/util/Alert1.kt b/src/main/java/frc/robot/util/Alert1.kt new file mode 100644 index 0000000..b60c8f2 --- /dev/null +++ b/src/main/java/frc/robot/util/Alert1.kt @@ -0,0 +1,184 @@ +// Copyright (c) 2023 FRC 6328 +// http://github.com/Mechanical-Advantage +// +// Use of this source code is governed by an MIT-style +// license that can be found below. +// MIT License +// +// Copyright (c) 2023 FRC 6328 +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in all +// copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +package frc.robot.util + +import edu.wpi.first.util.sendable.Sendable +import edu.wpi.first.util.sendable.SendableBuilder +import edu.wpi.first.wpilibj.* +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard +import java.util.function.Predicate + +/** Class for managing persistent alerts to be sent over NetworkTables. */ +class Alert(group: String, text: String, type: AlertType?) { + private val type: AlertType? + private var active = false + private var activeStartTime = 0.0 + private var text: String + + /** + * Creates a new Alert in the default group - "Alerts". If this is the first to be instantiated, + * the appropriate entries will be added to NetworkTables. + * + * @param text Text to be displayed when the alert is active. + * @param type Alert level specifying urgency. + */ + constructor(text: String, type: AlertType?) : this("Alerts", text, type) + + /** + * Creates a new Alert. If this is the first to be instantiated in its group, the appropriate + * entries will be added to NetworkTables. + * + * @param group Group identifier, also used as NetworkTables title + * @param text Text to be displayed when the alert is active. + * @param type Alert level specifying urgency. + */ + init { + if (!groups.containsKey(group)) { + // java: groups.put(group, SendableAlerts()) + groups[group] = SendableAlerts() + SmartDashboard.putData(group, groups[group]) + } + + this.text = text + this.type = type + groups[group]!!.alerts + } + + /** + * Sets whether the alert should currently be displayed. When activated, the alert text will also + * be sent to the console. + */ + fun set(active: Boolean) { + if (active && !this.active) { + activeStartTime = Timer.getFPGATimestamp() + when (type) { + AlertType.ERROR -> { + DriverStation.reportError(text, false) + } + AlertType.ERROR_TRACE -> { + DriverStation.reportError(text, true) + } + AlertType.WARNING -> { + DriverStation.reportWarning(text, false) + } + AlertType.WARNING_TRACE -> { + DriverStation.reportWarning(text, true) + } + AlertType.INFO -> { + println(text) + } + null -> { + TODO() + } + else -> {} + } + } + this.active = active + } + + /** Updates current alert text. */ + fun setText(text: String) { + if (active && text != this.text) { + when (type) { + AlertType.ERROR -> DriverStation.reportError(text, false) + AlertType.ERROR_TRACE -> DriverStation.reportError(text, true) + AlertType.WARNING -> DriverStation.reportWarning(text, false) + AlertType.WARNING_TRACE -> DriverStation.reportWarning(text, true) + AlertType.INFO -> println(text) + null -> TODO() + else -> {} + } + } + this.text = text + } + + class SendableAlerts : Sendable { + val alerts: List = ArrayList() + + fun getStrings(type: AlertType): Array { + val activeFilter = Predicate { x: Alert -> x.type == type && x.active } + val timeSorter = + java.util.Comparator { a1: Alert, a2: Alert -> (a2.activeStartTime - a1.activeStartTime).toInt() } + return alerts.stream() + .filter(activeFilter) + .sorted(timeSorter) + .map { a: Alert -> a.text } + .toArray { length: Int -> arrayOfNulls(length) } + } + + override fun initSendable(builder: SendableBuilder) { + builder.setSmartDashboardType("Alerts") + builder.addStringArrayProperty("errors", { getStrings(AlertType.ERROR) }, null) + builder.addStringArrayProperty("errors", { getStrings(AlertType.ERROR_TRACE) }, null) + builder.addStringArrayProperty("warnings", { getStrings(AlertType.WARNING) }, null) + builder.addStringArrayProperty("warnings", { getStrings(AlertType.WARNING_TRACE) }, null) + builder.addStringArrayProperty("infos", { getStrings(AlertType.INFO) }, null) + } + } + + /** Represents an alert's level of urgency. */ + enum class AlertType { + /** + * High priority alert - displayed first on the dashboard with a red "X" symbol. Use this type + * for problems which will seriously affect the robot's functionality and thus require immediate + * attention. + */ + ERROR, + + /** + * High priority alert - displayed first on the dashboard with a red "X" symbol. Use this type + * for problems which will seriously affect the robot's functionality and thus require immediate + * attention. Trace printed to driver station console. + */ + ERROR_TRACE, + + /** + * Medium priority alert - displayed second on the dashboard with a yellow "!" symbol. Use this + * type for problems which could affect the robot's functionality but do not necessarily require + * immediate attention. + */ + WARNING, + + /** + * Medium priority alert - displayed second on the dashboard with a yellow "!" symbol. Use this + * type for problems which could affect the robot's functionality but do not necessarily require + * immediate attention. Trace printed to driver station console. + */ + WARNING_TRACE, + + /** + * Low priority alert - displayed last on the dashboard with a green "i" symbol. Use this type + * for problems which are unlikely to affect the robot's functionality, or any other alerts + * which do not fall under "ERROR" or "WARNING". + */ + INFO + } + + companion object { + private val groups: java.util.HashMap = HashMap() + } +} diff --git a/src/main/java/frc/robot/util/Constants.java b/src/main/java/frc/robot/util/Constants.java deleted file mode 100644 index 0d2a6fc..0000000 --- a/src/main/java/frc/robot/util/Constants.java +++ /dev/null @@ -1,119 +0,0 @@ -package frc.robot.util; - -import com.pathplanner.lib.util.PIDConstants; -import edu.wpi.first.math.geometry.Pose3d; -import edu.wpi.first.math.geometry.Rotation3d; -import edu.wpi.first.math.geometry.Translation3d; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import swervelib.math.Matter; - -public final class Constants { - - public static final double ROBOT_MASS = 39.97; // 32lbs * kg per pound - public static final Matter CHASSIS = new Matter(new Translation3d(0, 0, Units.inchesToMeters(8)), ROBOT_MASS); - public static final double LOOP_TIME = 0.13; //s, 20ms + 110ms sprk max velocity lag - - public static final boolean TUNING_MODE = false; - - public static final class ShooterConstants { - - public static final double P = 5e-5; - public static final double I = 1e-6; - public static final double D = 0; - public static final double Iz = 0; - public static final double FF = 0.000156; - public static final double MAX_OUTPUT = 1; - public static final double MIN_OUTPUT = -1; - public static final double MAX_RPM = 5700; - public static final double MAX_VELOCITY = 2000; - public static final double MAX_ACCELERATION = 1500; - - - public static final double WHEEL_DIAMETER = 4; // inches - - } - - public static final Mode CURRENT_MODE = Mode.REAL; - - public static enum Mode { - /** - * Running on a real robot. - */ - REAL, - - /** - * Running a physics simulator. - */ - SIM, - - /** - * Replaying from a log file. - */ - REPLAY - } - - public static final class PositionConstants { - public static final Pose3d ORIGIN_TO_BACK_LIMELIGHT = new Pose3d(Units.inchesToMeters(-0.25), Units.inchesToMeters(0.25), Units.inchesToMeters(18.1171875), new Rotation3d(0, 0, Math.PI)); - - public static final Translation3d ORIGIN_TO_NAVX = new Translation3d(Units.inchesToMeters(-7), Units.inchesToMeters(0), Units.inchesToMeters(6.5)); - } - public static final class IntakeConstants { - public static final double HEIGHT_FROM_GROUND = 4.0; // inches - public static final double CIRCUMFERENCE = HEIGHT_FROM_GROUND * 2 * Math.PI; // inches - public static final double P = 5e-5; - public static final double I = 1e-6; - public static final double D = 0; - public static final double Iz = 0; - public static final double FF = 0.000156; - public static final double MAX_OUTPUT = 1; - public static final double MIN_OUTPUT = -1; - public static final double MAX_RPM = 240; // 4 rotations per second is the max. Notes are expensive enough as it is. - public static final double MAX_VELOCITY = 240; // I don't know what these do but fuck it we ball - public static final double MAX_ACCELERATION = 120; - public static final double INTAKE_SPEED = 5; - public static final double CEREALIZER_SPEED = 5; - } - - public static final class AutonomousConstants { - - public static final PIDConstants TRANSLATION_PID = new PIDConstants(0.7, 0, 0); - public static final PIDConstants ANGLE_PID = new PIDConstants(0.04, 0, 0.075); - } - - public static final class DrivebaseConstants { - - // Hold time on motor brakes when disabled - public static final double WHEEL_LOCK_TIME = 10; // seconds - } - - public static class OperatorConstants { - - // Joystick Deadband - public static final double JOYSTICK_X_DEADBAND = 0.1; - public static final double JOYSTICK_Y_DEADBAND = 0.1; - public static final double JOYSTICK_TWIST_DEADBAND = 0.1; - - public static final double TURN_CONSTANT = 6; - public static final double LEFT_Y_DEADBAND = 0.1; - public static final double LEFT_X_DEADBAND = 0.1; - public static final double RIGHT_X_DEADBAND = 0.1; - } - - public static class MotorConstants { - - // Shooter Motor Constants - public static final int LOWER_SHOOTER_MOTOR = 23; - public static final int UPPER_SHOOTER_MOTOR = 24; - public static final double SHOOTER_SPEED = 0.70; - // Arm Motor Constants - public static final int LEFT_ARM_MOTOR = 21; // Currently the ids are arbitrary. - public static final int RIGHT_ARM_MOTOR = 20; // They will need to be adjusted to reflect the actual connected ports - // Intake Constants - public static final int INTAKE_MOTOR = 12; - public static final int CEREALIZER_MOTOR = 22; - public static final double INTAKE_SPEED = 0.45; - public static final int LEFT_ROLLER_MOTOR = 11; - public static final int RIGHT_ROLLER_MOTOR = 10; - } -} \ No newline at end of file diff --git a/src/main/java/frc/robot/util/Constants1.kt b/src/main/java/frc/robot/util/Constants1.kt new file mode 100644 index 0000000..f8a44df --- /dev/null +++ b/src/main/java/frc/robot/util/Constants1.kt @@ -0,0 +1,299 @@ +package frc.robot.util + +import com.pathplanner.lib.util.PIDConstants +import edu.wpi.first.math.geometry.Pose3d +import edu.wpi.first.math.geometry.Rotation3d +import edu.wpi.first.math.geometry.Translation3d +import edu.wpi.first.math.util.Units +import swervelib.math.Matter + +/** + * + */ +object Constants { + /** + * + */ + const val ROBOT_MASS: Double = 39.97 // 32lbs * kg per pound + /** + * + */ + @JvmField + val CHASSIS: Matter = Matter(Translation3d(0.0, 0.0, Units.inchesToMeters(8.0)), ROBOT_MASS) + /** + * + */ + const val LOOP_TIME: Double = 0.13 //s, 20ms + 110ms sprk max velocity lag + + /** + * + */ + const val TUNING_MODE: Boolean = false + + /** + * + */ + val CURRENT_MODE: Mode = Mode.REAL + + /** + * + */ + object ShooterConstants { + /** + * + */ + const val P: Double = 5e-5 + /** + * + */ + const val I: Double = 1e-6 + /** + * + */ + const val D: Double = 0.0 + /** + * + */ + const val Iz: Double = 0.0 + /** + * + */ + const val FF: Double = 0.000156 + /** + * + */ + const val MAX_OUTPUT: Double = 1.0 + /** + * + */ + const val MIN_OUTPUT: Double = -1.0 + /** + * + */ + const val MAX_RPM: Double = 5700.0 + /** + * + */ + const val MAX_VELOCITY: Double = 2000.0 + /** + * + */ + const val MAX_ACCELERATION: Double = 1500.0 + + + /** + * + */ + const val WHEEL_DIAMETER: Double = 4.0 // inches + } + + /** + * + */ + enum class Mode { + /** + * Running on a real robot. + */ + REAL, + + /** + * Running a physics simulator. + */ + SIM, + + /** + * Replaying from a log file. + */ + REPLAY + } + + /** + * + */ + object PositionConstants { + /** + * + */ + val ORIGIN_TO_BACK_LIMELIGHT: Pose3d = Pose3d( + Units.inchesToMeters(-0.25), + Units.inchesToMeters(0.25), + Units.inchesToMeters(18.1171875), + Rotation3d(0.0, 0.0, Math.PI) + ) + + /** + * + */ + val ORIGIN_TO_NAVX: Translation3d = + Translation3d(Units.inchesToMeters(-7.0), Units.inchesToMeters(0.0), Units.inchesToMeters(6.5)) + } + + /** + * + */ + object IntakeConstants { + /** + * + */ + private const val HEIGHT_FROM_GROUND: Double = 4.0 // inches + /** + * + */ + const val CIRCUMFERENCE: Double = HEIGHT_FROM_GROUND * 2 * Math.PI // inches + /** + * + */ + const val P: Double = 5e-5 + /** + * + */ + const val I: Double = 1e-6 + /** + * + */ + const val D: Double = 0.0 + /** + * + */ + const val Iz: Double = 0.0 + /** + * + */ + const val FF: Double = 0.000156 + /** + * + */ + const val MAX_OUTPUT: Double = 1.0 + /** + * + */ + const val MIN_OUTPUT: Double = -1.0 + /** + * + */ + const val MAX_RPM: Double = 240.0 // 4 rotations per second is the max. Notes are expensive enough as it is. + /** + * + */ + const val MAX_VELOCITY: Double = 240.0 // I don't know what these do but fuck it we ball + /** + * + */ + const val MAX_ACCELERATION: Double = 120.0 + /** + * + */ + const val INTAKE_SPEED: Double = 5.0 + /** + * + */ + const val CEREALIZER_SPEED: Double = 5.0 + } + + /** + * + */ + object AutonomousConstants { + /** + * + */ + val TRANSLATION_PID: PIDConstants = PIDConstants(0.7, 0.0, 0.0) + /** + * + */ + val ANGLE_PID: PIDConstants = PIDConstants(0.04, 0.0, 0.075) + } + + /** + * + */ + object DrivebaseConstants { + /** + * + */// Hold time on motor brakes when disabled + const val WHEEL_LOCK_TIME: Double = 10.0 // seconds + } + + /** + * + */ + object OperatorConstants { + /** + * + */// Joystick Deadband + const val JOYSTICK_X_DEADBAND: Double = 0.1 + /** + * + */ + const val JOYSTICK_Y_DEADBAND: Double = 0.1 + /** + * + */ + const val JOYSTICK_TWIST_DEADBAND: Double = 0.1 + + /** + * + */ + const val TURN_CONSTANT: Double = 6.0 + /** + * + */ + const val LEFT_Y_DEADBAND: Double = 0.1 + /** + * + */ + const val LEFT_X_DEADBAND: Double = 0.1 + /** + * + */ + const val RIGHT_X_DEADBAND: Double = 0.1 + } + + /** + * + */ + object MotorConstants { + /** + * + */// Shooter Motor Constants + const val LOWER_SHOOTER_MOTOR: Int = 23 + /** + * + */ + const val UPPER_SHOOTER_MOTOR: Int = 24 + /** + * + */ + const val SHOOTER_SPEED: Double = 0.70 + + /** + * + */// Arm Motor Constants + const val LEFT_ARM_MOTOR: Int = 21 // Currently the ids are arbitrary. + /** + * + */ + const val RIGHT_ARM_MOTOR: Int = 20 // They will need to be adjusted to reflect the actual connected ports + + /** + * + */// Intake Constants + const val INTAKE_MOTOR: Int = 12 + /** + * + */ + const val CEREALIZER_MOTOR: Int = 22 + /** + * + */ + const val INTAKE_SPEED: Double = 0.45 + /** + * + */ + const val LEFT_ROLLER_MOTOR: Int = 11 + /** + * + */ + const val RIGHT_ROLLER_MOTOR: Int = 10 + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/util/LimelightHelpers.java b/src/main/java/frc/robot/util/LimelightHelpers.java deleted file mode 100644 index a6b6be0..0000000 --- a/src/main/java/frc/robot/util/LimelightHelpers.java +++ /dev/null @@ -1,780 +0,0 @@ -//LimelightHelpers v1.2.1 (March 1, 2023) - -package frc.robot.util; - -import edu.wpi.first.networktables.NetworkTable; -import edu.wpi.first.networktables.NetworkTableEntry; -import edu.wpi.first.networktables.NetworkTableInstance; -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.Translation3d; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.math.geometry.Rotation3d; -import edu.wpi.first.math.geometry.Translation2d; - -import java.io.IOException; -import java.net.HttpURLConnection; -import java.net.MalformedURLException; -import java.net.URL; -import java.util.concurrent.CompletableFuture; - -import com.fasterxml.jackson.annotation.JsonFormat; -import com.fasterxml.jackson.annotation.JsonFormat.Shape; -import com.fasterxml.jackson.annotation.JsonProperty; -import com.fasterxml.jackson.core.JsonProcessingException; -import com.fasterxml.jackson.databind.DeserializationFeature; -import com.fasterxml.jackson.databind.ObjectMapper; - -public class LimelightHelpers { - - public static class LimelightTarget_Retro { - - @JsonProperty("t6c_ts") - private double[] cameraPose_TargetSpace; - - @JsonProperty("t6r_fs") - private double[] robotPose_FieldSpace; - - @JsonProperty("t6r_ts") - private double[] robotPose_TargetSpace; - - @JsonProperty("t6t_cs") - private double[] targetPose_CameraSpace; - - @JsonProperty("t6t_rs") - private double[] targetPose_RobotSpace; - - public Pose3d getCameraPose_TargetSpace() - { - return toPose3D(cameraPose_TargetSpace); - } - public Pose3d getRobotPose_FieldSpace() - { - return toPose3D(robotPose_FieldSpace); - } - public Pose3d getRobotPose_TargetSpace() - { - return toPose3D(robotPose_TargetSpace); - } - public Pose3d getTargetPose_CameraSpace() - { - return toPose3D(targetPose_CameraSpace); - } - public Pose3d getTargetPose_RobotSpace() - { - return toPose3D(targetPose_RobotSpace); - } - - public Pose2d getCameraPose_TargetSpace2D() - { - return toPose2D(cameraPose_TargetSpace); - } - public Pose2d getRobotPose_FieldSpace2D() - { - return toPose2D(robotPose_FieldSpace); - } - public Pose2d getRobotPose_TargetSpace2D() - { - return toPose2D(robotPose_TargetSpace); - } - public Pose2d getTargetPose_CameraSpace2D() - { - return toPose2D(targetPose_CameraSpace); - } - public Pose2d getTargetPose_RobotSpace2D() - { - return toPose2D(targetPose_RobotSpace); - } - - @JsonProperty("ta") - public double ta; - - @JsonProperty("tx") - public double tx; - - @JsonProperty("txp") - public double tx_pixels; - - @JsonProperty("ty") - public double ty; - - @JsonProperty("typ") - public double ty_pixels; - - @JsonProperty("ts") - public double ts; - - public LimelightTarget_Retro() { - cameraPose_TargetSpace = new double[6]; - robotPose_FieldSpace = new double[6]; - robotPose_TargetSpace = new double[6]; - targetPose_CameraSpace = new double[6]; - targetPose_RobotSpace = new double[6]; - } - - } - - public static class LimelightTarget_Fiducial { - - @JsonProperty("fID") - public double fiducialID; - - @JsonProperty("fam") - public String fiducialFamily; - - @JsonProperty("t6c_ts") - private double[] cameraPose_TargetSpace; - - @JsonProperty("t6r_fs") - private double[] robotPose_FieldSpace; - - @JsonProperty("t6r_ts") - private double[] robotPose_TargetSpace; - - @JsonProperty("t6t_cs") - private double[] targetPose_CameraSpace; - - @JsonProperty("t6t_rs") - private double[] targetPose_RobotSpace; - - public Pose3d getCameraPose_TargetSpace() - { - return toPose3D(cameraPose_TargetSpace); - } - public Pose3d getRobotPose_FieldSpace() - { - return toPose3D(robotPose_FieldSpace); - } - public Pose3d getRobotPose_TargetSpace() - { - return toPose3D(robotPose_TargetSpace); - } - public Pose3d getTargetPose_CameraSpace() - { - return toPose3D(targetPose_CameraSpace); - } - public Pose3d getTargetPose_RobotSpace() - { - return toPose3D(targetPose_RobotSpace); - } - - public Pose2d getCameraPose_TargetSpace2D() - { - return toPose2D(cameraPose_TargetSpace); - } - public Pose2d getRobotPose_FieldSpace2D() - { - return toPose2D(robotPose_FieldSpace); - } - public Pose2d getRobotPose_TargetSpace2D() - { - return toPose2D(robotPose_TargetSpace); - } - public Pose2d getTargetPose_CameraSpace2D() - { - return toPose2D(targetPose_CameraSpace); - } - public Pose2d getTargetPose_RobotSpace2D() - { - return toPose2D(targetPose_RobotSpace); - } - - @JsonProperty("ta") - public double ta; - - @JsonProperty("tx") - public double tx; - - @JsonProperty("txp") - public double tx_pixels; - - @JsonProperty("ty") - public double ty; - - @JsonProperty("typ") - public double ty_pixels; - - @JsonProperty("ts") - public double ts; - - public LimelightTarget_Fiducial() { - cameraPose_TargetSpace = new double[6]; - robotPose_FieldSpace = new double[6]; - robotPose_TargetSpace = new double[6]; - targetPose_CameraSpace = new double[6]; - targetPose_RobotSpace = new double[6]; - } - } - - public static class LimelightTarget_Barcode { - - } - - public static class LimelightTarget_Classifier { - - @JsonProperty("class") - public String className; - - @JsonProperty("classID") - public double classID; - - @JsonProperty("conf") - public double confidence; - - @JsonProperty("zone") - public double zone; - - @JsonProperty("tx") - public double tx; - - @JsonProperty("txp") - public double tx_pixels; - - @JsonProperty("ty") - public double ty; - - @JsonProperty("typ") - public double ty_pixels; - - public LimelightTarget_Classifier() { - } - } - - public static class LimelightTarget_Detector { - - @JsonProperty("class") - public String className; - - @JsonProperty("classID") - public double classID; - - @JsonProperty("conf") - public double confidence; - - @JsonProperty("ta") - public double ta; - - @JsonProperty("tx") - public double tx; - - @JsonProperty("txp") - public double tx_pixels; - - @JsonProperty("ty") - public double ty; - - @JsonProperty("typ") - public double ty_pixels; - - public LimelightTarget_Detector() { - } - } - - public static class Results { - - @JsonProperty("pID") - public double pipelineID; - - @JsonProperty("tl") - public double latency_pipeline; - - @JsonProperty("cl") - public double latency_capture; - - public double latency_jsonParse; - - @JsonProperty("ts") - public double timestamp_LIMELIGHT_publish; - - @JsonProperty("ts_rio") - public double timestamp_RIOFPGA_capture; - - @JsonProperty("v") - @JsonFormat(shape = Shape.NUMBER) - public boolean valid; - - @JsonProperty("botpose") - public double[] botpose; - - @JsonProperty("botpose_wpired") - public double[] botpose_wpired; - - @JsonProperty("botpose_wpiblue") - public double[] botpose_wpiblue; - - @JsonProperty("t6c_rs") - public double[] camerapose_robotspace; - - public Pose3d getBotPose3d() { - return toPose3D(botpose); - } - - public Pose3d getBotPose3d_wpiRed() { - return toPose3D(botpose_wpired); - } - - public Pose3d getBotPose3d_wpiBlue() { - return toPose3D(botpose_wpiblue); - } - - public Pose2d getBotPose2d() { - return toPose2D(botpose); - } - - public Pose2d getBotPose2d_wpiRed() { - return toPose2D(botpose_wpired); - } - - public Pose2d getBotPose2d_wpiBlue() { - return toPose2D(botpose_wpiblue); - } - - @JsonProperty("Retro") - public LimelightTarget_Retro[] targets_Retro; - - @JsonProperty("Fiducial") - public LimelightTarget_Fiducial[] targets_Fiducials; - - @JsonProperty("Classifier") - public LimelightTarget_Classifier[] targets_Classifier; - - @JsonProperty("Detector") - public LimelightTarget_Detector[] targets_Detector; - - @JsonProperty("Barcode") - public LimelightTarget_Barcode[] targets_Barcode; - - public Results() { - botpose = new double[6]; - botpose_wpired = new double[6]; - botpose_wpiblue = new double[6]; - camerapose_robotspace = new double[6]; - targets_Retro = new LimelightTarget_Retro[0]; - targets_Fiducials = new LimelightTarget_Fiducial[0]; - targets_Classifier = new LimelightTarget_Classifier[0]; - targets_Detector = new LimelightTarget_Detector[0]; - targets_Barcode = new LimelightTarget_Barcode[0]; - - } - } - - public static class LimelightResults { - @JsonProperty("Results") - public Results targetingResults; - - public LimelightResults() { - targetingResults = new Results(); - } - } - - private static ObjectMapper mapper; - - /** - * Print JSON Parse time to the console in milliseconds - */ - static boolean profileJSON = false; - - static final String sanitizeName(String name) { - if (name == "" || name == null) { - return "limelight"; - } - return name; - } - - private static Pose3d toPose3D(double[] inData){ - if(inData.length < 6) - { - System.err.println("Bad LL 3D Pose Data!"); - return new Pose3d(); - } - return new Pose3d( - new Translation3d(inData[0], inData[1], inData[2]), - new Rotation3d(Units.degreesToRadians(inData[3]), Units.degreesToRadians(inData[4]), - Units.degreesToRadians(inData[5]))); - } - - private static Pose2d toPose2D(double[] inData){ - if(inData.length < 6) - { - System.err.println("Bad LL 2D Pose Data!"); - return new Pose2d(); - } - Translation2d tran2d = new Translation2d(inData[0], inData[1]); - Rotation2d r2d = new Rotation2d(Units.degreesToRadians(inData[5])); - return new Pose2d(tran2d, r2d); - } - - public static NetworkTable getLimelightNTTable(String tableName) { - return NetworkTableInstance.getDefault().getTable(sanitizeName(tableName)); - } - - public static NetworkTableEntry getLimelightNTTableEntry(String tableName, String entryName) { - return getLimelightNTTable(tableName).getEntry(entryName); - } - - public static double getLimelightNTDouble(String tableName, String entryName) { - return getLimelightNTTableEntry(tableName, entryName).getDouble(0.0); - } - - public static void setLimelightNTDouble(String tableName, String entryName, double val) { - getLimelightNTTableEntry(tableName, entryName).setDouble(val); - } - - public static void setLimelightNTDoubleArray(String tableName, String entryName, double[] val) { - getLimelightNTTableEntry(tableName, entryName).setDoubleArray(val); - } - - public static double[] getLimelightNTDoubleArray(String tableName, String entryName) { - return getLimelightNTTableEntry(tableName, entryName).getDoubleArray(new double[0]); - } - - public static String getLimelightNTString(String tableName, String entryName) { - return getLimelightNTTableEntry(tableName, entryName).getString(""); - } - - public static URL getLimelightURLString(String tableName, String request) { - String urlString = "http://" + sanitizeName(tableName) + ".local:5807/" + request; - URL url; - try { - url = new URL(urlString); - return url; - } catch (MalformedURLException e) { - System.err.println("bad LL URL"); - } - return null; - } - ///// - ///// - - public static double getTX(String limelightName) { - return getLimelightNTDouble(limelightName, "tx"); - } - - public static double getTY(String limelightName) { - return getLimelightNTDouble(limelightName, "ty"); - } - - public static double getTA(String limelightName) { - return getLimelightNTDouble(limelightName, "ta"); - } - - public static double getLatency_Pipeline(String limelightName) { - return getLimelightNTDouble(limelightName, "tl"); - } - - public static double getLatency_Capture(String limelightName) { - return getLimelightNTDouble(limelightName, "cl"); - } - - public static double getCurrentPipelineIndex(String limelightName) { - return getLimelightNTDouble(limelightName, "getpipe"); - } - - public static String getJSONDump(String limelightName) { - return getLimelightNTString(limelightName, "json"); - } - - /** - * Switch to getBotPose - * - * @param limelightName - * @return - */ - @Deprecated - public static double[] getBotpose(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "botpose"); - } - - /** - * Switch to getBotPose_wpiRed - * - * @param limelightName - * @return - */ - @Deprecated - public static double[] getBotpose_wpiRed(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "botpose_wpired"); - } - - /** - * Switch to getBotPose_wpiBlue - * - * @param limelightName - * @return - */ - @Deprecated - public static double[] getBotpose_wpiBlue(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "botpose_wpiblue"); - } - - public static double[] getBotPose(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "botpose"); - } - - public static double[] getBotPose_wpiRed(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "botpose_wpired"); - } - - public static double[] getBotPose_wpiBlue(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "botpose_wpiblue"); - } - - public static double[] getBotPose_TargetSpace(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "botpose_targetspace"); - } - - public static double[] getCameraPose_TargetSpace(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "camerapose_targetspace"); - } - - public static double[] getTargetPose_CameraSpace(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "targetpose_cameraspace"); - } - - public static double[] getTargetPose_RobotSpace(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "targetpose_robotspace"); - } - - public static double[] getTargetColor(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "tc"); - } - - public static double getFiducialID(String limelightName) { - return getLimelightNTDouble(limelightName, "tid"); - } - - public static double getNeuralClassID(String limelightName) { - return getLimelightNTDouble(limelightName, "tclass"); - } - - ///// - ///// - - public static Pose3d getBotPose3d(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "botpose"); - return toPose3D(poseArray); - } - - public static Pose3d getBotPose3d_wpiRed(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "botpose_wpired"); - return toPose3D(poseArray); - } - - public static Pose3d getBotPose3d_wpiBlue(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "botpose_wpiblue"); - return toPose3D(poseArray); - } - - public static Pose3d getBotPose3d_TargetSpace(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "botpose_targetspace"); - return toPose3D(poseArray); - } - - public static Pose3d getCameraPose3d_TargetSpace(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "camerapose_targetspace"); - return toPose3D(poseArray); - } - - public static Pose3d getTargetPose3d_CameraSpace(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "targetpose_cameraspace"); - return toPose3D(poseArray); - } - - public static Pose3d getTargetPose3d_RobotSpace(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "targetpose_robotspace"); - return toPose3D(poseArray); - } - - public static Pose3d getCameraPose3d_RobotSpace(String limelightName) { - double[] poseArray = getLimelightNTDoubleArray(limelightName, "camerapose_robotspace"); - return toPose3D(poseArray); - } - - /** - * Gets the Pose2d for easy use with Odometry vision pose estimator - * (addVisionMeasurement) - * - * @param limelightName - * @return - */ - public static Pose2d getBotPose2d_wpiBlue(String limelightName) { - - double[] result = getBotPose_wpiBlue(limelightName); - return toPose2D(result); - } - - /** - * Gets the Pose2d for easy use with Odometry vision pose estimator - * (addVisionMeasurement) - * - * @param limelightName - * @return - */ - public static Pose2d getBotPose2d_wpiRed(String limelightName) { - - double[] result = getBotPose_wpiRed(limelightName); - return toPose2D(result); - - } - - /** - * Gets the Pose2d for easy use with Odometry vision pose estimator - * (addVisionMeasurement) - * - * @param limelightName - * @return - */ - public static Pose2d getBotPose2d(String limelightName) { - - double[] result = getBotPose(limelightName); - return toPose2D(result); - - } - - public static boolean getTV(String limelightName) { - return 1.0 == getLimelightNTDouble(limelightName, "tv"); - } - - ///// - ///// - - public static void setPipelineIndex(String limelightName, int pipelineIndex) { - setLimelightNTDouble(limelightName, "pipeline", pipelineIndex); - } - - /** - * The LEDs will be controlled by Limelight pipeline settings, and not by robot - * code. - */ - public static void setLEDMode_PipelineControl(String limelightName) { - setLimelightNTDouble(limelightName, "ledMode", 0); - } - - public static void setLEDMode_ForceOff(String limelightName) { - setLimelightNTDouble(limelightName, "ledMode", 1); - } - - public static void setLEDMode_ForceBlink(String limelightName) { - setLimelightNTDouble(limelightName, "ledMode", 2); - } - - public static void setLEDMode_ForceOn(String limelightName) { - setLimelightNTDouble(limelightName, "ledMode", 3); - } - - public static void setStreamMode_Standard(String limelightName) { - setLimelightNTDouble(limelightName, "stream", 0); - } - - public static void setStreamMode_PiPMain(String limelightName) { - setLimelightNTDouble(limelightName, "stream", 1); - } - - public static void setStreamMode_PiPSecondary(String limelightName) { - setLimelightNTDouble(limelightName, "stream", 2); - } - - public static void setCameraMode_Processor(String limelightName) { - setLimelightNTDouble(limelightName, "camMode", 0); - } - public static void setCameraMode_Driver(String limelightName) { - setLimelightNTDouble(limelightName, "camMode", 1); - } - - - /** - * Sets the crop window. The crop window in the UI must be completely open for - * dynamic cropping to work. - */ - public static void setCropWindow(String limelightName, double cropXMin, double cropXMax, double cropYMin, double cropYMax) { - double[] entries = new double[4]; - entries[0] = cropXMin; - entries[1] = cropXMax; - entries[2] = cropYMin; - entries[3] = cropYMax; - setLimelightNTDoubleArray(limelightName, "crop", entries); - } - - public static void setCameraPose_RobotSpace(String limelightName, double forward, double side, double up, double roll, double pitch, double yaw) { - double[] entries = new double[6]; - entries[0] = forward; - entries[1] = side; - entries[2] = up; - entries[3] = roll; - entries[4] = pitch; - entries[5] = yaw; - setLimelightNTDoubleArray(limelightName, "camerapose_robotspace_set", entries); - } - - ///// - ///// - - public static void setPythonScriptData(String limelightName, double[] outgoingPythonData) { - setLimelightNTDoubleArray(limelightName, "llrobot", outgoingPythonData); - } - - public static double[] getPythonScriptData(String limelightName) { - return getLimelightNTDoubleArray(limelightName, "llpython"); - } - - ///// - ///// - - /** - * Asynchronously take snapshot. - */ - public static CompletableFuture takeSnapshot(String tableName, String snapshotName) { - return CompletableFuture.supplyAsync(() -> { - return SYNCH_TAKESNAPSHOT(tableName, snapshotName); - }); - } - - private static boolean SYNCH_TAKESNAPSHOT(String tableName, String snapshotName) { - URL url = getLimelightURLString(tableName, "capturesnapshot"); - try { - HttpURLConnection connection = (HttpURLConnection) url.openConnection(); - connection.setRequestMethod("GET"); - if (snapshotName != null && snapshotName != "") { - connection.setRequestProperty("snapname", snapshotName); - } - - int responseCode = connection.getResponseCode(); - if (responseCode == 200) { - return true; - } else { - System.err.println("Bad LL Request"); - } - } catch (IOException e) { - System.err.println(e.getMessage()); - } - return false; - } - - /** - * Parses Limelight's JSON results dump into a LimelightResults Object - */ - public static LimelightResults getLatestResults(String limelightName) { - - long start = System.nanoTime(); - LimelightHelpers.LimelightResults results = new LimelightHelpers.LimelightResults(); - if (mapper == null) { - mapper = new ObjectMapper().configure(DeserializationFeature.FAIL_ON_UNKNOWN_PROPERTIES, false); - } - - try { - results = mapper.readValue(getJSONDump(limelightName), LimelightResults.class); - } catch (JsonProcessingException e) { - System.err.println("lljson error: " + e.getMessage()); - } - - long end = System.nanoTime(); - double millis = (end - start) * .000001; - results.targetingResults.latency_jsonParse = millis; - if (profileJSON) { - System.out.printf("lljson: %.2f\r\n", millis); - } - - return results; - } -} \ No newline at end of file diff --git a/src/main/java/frc/robot/util/LimelightHelpers1.kt b/src/main/java/frc/robot/util/LimelightHelpers1.kt new file mode 100644 index 0000000..d46bf22 --- /dev/null +++ b/src/main/java/frc/robot/util/LimelightHelpers1.kt @@ -0,0 +1,698 @@ +//LimelightHelpers v1.2.1 (March 1, 2023) +package frc.robot.util + +import com.fasterxml.jackson.annotation.JsonFormat +import com.fasterxml.jackson.annotation.JsonProperty +import com.fasterxml.jackson.core.JsonProcessingException +import com.fasterxml.jackson.databind.DeserializationFeature +import com.fasterxml.jackson.databind.ObjectMapper +import edu.wpi.first.math.geometry.* +import edu.wpi.first.math.util.Units +import edu.wpi.first.networktables.NetworkTable +import edu.wpi.first.networktables.NetworkTableEntry +import edu.wpi.first.networktables.NetworkTableInstance +import java.io.IOException +import java.net.HttpURLConnection +import java.net.MalformedURLException +import java.net.URL +import java.util.concurrent.CompletableFuture + +object LimelightHelpers { + private var mapper: ObjectMapper? = null + + /** + * Print JSON Parse time to the console in milliseconds + */ + var profileJSON: Boolean = false + + fun sanitizeName(name: String?): String { + if (name === "" || name == null) { + return "limelight" + } + return name + } + + private fun toPose3D(inData: DoubleArray): Pose3d { + if (inData.size < 6) { + System.err.println("Bad LL 3D Pose Data!") + return Pose3d() + } + return Pose3d( + Translation3d(inData[0], inData[1], inData[2]), + Rotation3d( + Units.degreesToRadians(inData[3]), Units.degreesToRadians( + inData[4] + ), + Units.degreesToRadians(inData[5]) + ) + ) + } + + private fun toPose2D(inData: DoubleArray): Pose2d { + if (inData.size < 6) { + System.err.println("Bad LL 2D Pose Data!") + return Pose2d() + } + val tran2d = Translation2d(inData[0], inData[1]) + val r2d = Rotation2d(Units.degreesToRadians(inData[5])) + return Pose2d(tran2d, r2d) + } + + fun getLimelightNTTable(tableName: String?): NetworkTable { + return NetworkTableInstance.getDefault().getTable(sanitizeName(tableName)) + } + + fun getLimelightNTTableEntry(tableName: String?, entryName: String?): NetworkTableEntry { + return getLimelightNTTable(tableName).getEntry(entryName) + } + + fun getLimelightNTDouble(tableName: String?, entryName: String?): Double { + return getLimelightNTTableEntry(tableName, entryName).getDouble(0.0) + } + + fun setLimelightNTDouble(tableName: String?, entryName: String?, `val`: Double) { + getLimelightNTTableEntry(tableName, entryName).setDouble(`val`) + } + + fun setLimelightNTDoubleArray(tableName: String?, entryName: String?, `val`: DoubleArray?) { + getLimelightNTTableEntry(tableName, entryName).setDoubleArray(`val`) + } + + fun getLimelightNTDoubleArray(tableName: String?, entryName: String?): DoubleArray { + return getLimelightNTTableEntry(tableName, entryName).getDoubleArray(DoubleArray(0)) + } + + fun getLimelightNTString(tableName: String?, entryName: String?): String { + return getLimelightNTTableEntry(tableName, entryName).getString("") + } + + fun getLimelightURLString(tableName: String?, request: String): URL? { + val urlString = "http://" + sanitizeName(tableName) + ".local:5807/" + request + val url: URL + try { + url = URL(urlString) + return url + } catch (e: MalformedURLException) { + System.err.println("bad LL URL") + } + return null + } + + ///// + ///// + @JvmStatic + fun getTX(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "tx") + } + + fun getTY(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "ty") + } + + fun getTA(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "ta") + } + + fun getLatency_Pipeline(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "tl") + } + + fun getLatency_Capture(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "cl") + } + + fun getCurrentPipelineIndex(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "getpipe") + } + + fun getJSONDump(limelightName: String?): String { + return getLimelightNTString(limelightName, "json") + } + + /** + * Switch to getBotPose + * + * @param limelightName + * @return + */ + @Deprecated("") + fun getBotpose(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "botpose") + } + + /** + * Switch to getBotPose_wpiRed + * + * @param limelightName + * @return + */ + @Deprecated("") + fun getBotpose_wpiRed(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "botpose_wpired") + } + + /** + * Switch to getBotPose_wpiBlue + * + * @param limelightName + * @return + */ + @Deprecated("") + fun getBotpose_wpiBlue(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "botpose_wpiblue") + } + + fun getBotPose(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "botpose") + } + + fun getBotPose_wpiRed(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "botpose_wpired") + } + + fun getBotPose_wpiBlue(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "botpose_wpiblue") + } + + fun getBotPose_TargetSpace(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "botpose_targetspace") + } + + fun getCameraPose_TargetSpace(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "camerapose_targetspace") + } + + fun getTargetPose_CameraSpace(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "targetpose_cameraspace") + } + + fun getTargetPose_RobotSpace(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "targetpose_robotspace") + } + + fun getTargetColor(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "tc") + } + + fun getFiducialID(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "tid") + } + + fun getNeuralClassID(limelightName: String?): Double { + return getLimelightNTDouble(limelightName, "tclass") + } + + ///// + ///// + fun getBotPose3d(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "botpose") + return toPose3D(poseArray) + } + + fun getBotPose3d_wpiRed(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "botpose_wpired") + return toPose3D(poseArray) + } + + fun getBotPose3d_wpiBlue(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "botpose_wpiblue") + return toPose3D(poseArray) + } + + fun getBotPose3d_TargetSpace(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "botpose_targetspace") + return toPose3D(poseArray) + } + + fun getCameraPose3d_TargetSpace(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "camerapose_targetspace") + return toPose3D(poseArray) + } + + fun getTargetPose3d_CameraSpace(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "targetpose_cameraspace") + return toPose3D(poseArray) + } + + fun getTargetPose3d_RobotSpace(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "targetpose_robotspace") + return toPose3D(poseArray) + } + + fun getCameraPose3d_RobotSpace(limelightName: String?): Pose3d { + val poseArray = getLimelightNTDoubleArray(limelightName, "camerapose_robotspace") + return toPose3D(poseArray) + } + + /** + * Gets the Pose2d for easy use with Odometry vision pose estimator + * (addVisionMeasurement) + * + * @param limelightName + * @return + */ + fun getBotPose2d_wpiBlue(limelightName: String?): Pose2d { + val result = getBotPose_wpiBlue(limelightName) + return toPose2D(result) + } + + /** + * Gets the Pose2d for easy use with Odometry vision pose estimator + * (addVisionMeasurement) + * + * @param limelightName + * @return + */ + fun getBotPose2d_wpiRed(limelightName: String?): Pose2d { + val result = getBotPose_wpiRed(limelightName) + return toPose2D(result) + } + + /** + * Gets the Pose2d for easy use with Odometry vision pose estimator + * (addVisionMeasurement) + * + * @param limelightName + * @return + */ + fun getBotPose2d(limelightName: String?): Pose2d { + val result = getBotPose(limelightName) + return toPose2D(result) + } + + @JvmStatic + fun getTV(limelightName: String?): Boolean { + return 1.0 == getLimelightNTDouble(limelightName, "tv") + } + + ///// + ///// + @JvmStatic + fun setPipelineIndex(limelightName: String?, pipelineIndex: Int) { + setLimelightNTDouble(limelightName, "pipeline", pipelineIndex.toDouble()) + } + + /** + * The LEDs will be controlled by Limelight pipeline settings, and not by robot + * code. + */ + fun setLEDMode_PipelineControl(limelightName: String?) { + setLimelightNTDouble(limelightName, "ledMode", 0.0) + } + + fun setLEDMode_ForceOff(limelightName: String?) { + setLimelightNTDouble(limelightName, "ledMode", 1.0) + } + + fun setLEDMode_ForceBlink(limelightName: String?) { + setLimelightNTDouble(limelightName, "ledMode", 2.0) + } + + fun setLEDMode_ForceOn(limelightName: String?) { + setLimelightNTDouble(limelightName, "ledMode", 3.0) + } + + fun setStreamMode_Standard(limelightName: String?) { + setLimelightNTDouble(limelightName, "stream", 0.0) + } + + fun setStreamMode_PiPMain(limelightName: String?) { + setLimelightNTDouble(limelightName, "stream", 1.0) + } + + fun setStreamMode_PiPSecondary(limelightName: String?) { + setLimelightNTDouble(limelightName, "stream", 2.0) + } + + fun setCameraMode_Processor(limelightName: String?) { + setLimelightNTDouble(limelightName, "camMode", 0.0) + } + + fun setCameraMode_Driver(limelightName: String?) { + setLimelightNTDouble(limelightName, "camMode", 1.0) + } + + + /** + * Sets the crop window. The crop window in the UI must be completely open for + * dynamic cropping to work. + */ + fun setCropWindow(limelightName: String?, cropXMin: Double, cropXMax: Double, cropYMin: Double, cropYMax: Double) { + val entries = DoubleArray(4) + entries[0] = cropXMin + entries[1] = cropXMax + entries[2] = cropYMin + entries[3] = cropYMax + setLimelightNTDoubleArray(limelightName, "crop", entries) + } + + fun setCameraPose_RobotSpace( + limelightName: String?, + forward: Double, + side: Double, + up: Double, + roll: Double, + pitch: Double, + yaw: Double + ) { + val entries = DoubleArray(6) + entries[0] = forward + entries[1] = side + entries[2] = up + entries[3] = roll + entries[4] = pitch + entries[5] = yaw + setLimelightNTDoubleArray(limelightName, "camerapose_robotspace_set", entries) + } + + ///// + ///// + fun setPythonScriptData(limelightName: String?, outgoingPythonData: DoubleArray?) { + setLimelightNTDoubleArray(limelightName, "llrobot", outgoingPythonData) + } + + fun getPythonScriptData(limelightName: String?): DoubleArray { + return getLimelightNTDoubleArray(limelightName, "llpython") + } + + ///// + ///// + /** + * Asynchronously take snapshot. + */ + fun takeSnapshot(tableName: String, snapshotName: String?): CompletableFuture { + return CompletableFuture.supplyAsync { SYNCH_TAKESNAPSHOT(tableName, snapshotName) } + } + + private fun SYNCH_TAKESNAPSHOT(tableName: String, snapshotName: String?): Boolean { + val url = getLimelightURLString(tableName, "capturesnapshot") + try { + val connection = url!!.openConnection() as HttpURLConnection + connection.requestMethod = "GET" + if (snapshotName != null && snapshotName !== "") { + connection.setRequestProperty("snapname", snapshotName) + } + + val responseCode = connection.responseCode + if (responseCode == 200) { + return true + } else { + System.err.println("Bad LL Request") + } + } catch (e: IOException) { + System.err.println(e.message) + } + return false + } + + /** + * Parses Limelight's JSON results dump into a LimelightResults Object + */ + fun getLatestResults(limelightName: String?): LimelightResults { + val start = System.nanoTime() + var results = LimelightResults() + if (mapper == null) { + mapper = ObjectMapper().configure(DeserializationFeature.FAIL_ON_UNKNOWN_PROPERTIES, false) + } + + try { + results = mapper!!.readValue(getJSONDump(limelightName), LimelightResults::class.java) + } catch (e: JsonProcessingException) { + System.err.println("lljson error: " + e.message) + } + + val end = System.nanoTime() + val millis = (end - start) * .000001 + results.targetingResults.latency_jsonParse = millis + if (profileJSON) { + System.out.printf("lljson: %.2f\r\n", millis) + } + + return results + } + + class LimelightTarget_Retro { + @JsonProperty("t6c_ts") + private val cameraPose_TargetSpace = DoubleArray(6) + + @JsonProperty("t6r_fs") + private val robotPose_FieldSpace = DoubleArray(6) + + @JsonProperty("t6r_ts") + private val robotPose_TargetSpace = DoubleArray(6) + + @JsonProperty("t6t_cs") + private val targetPose_CameraSpace = DoubleArray(6) + + @JsonProperty("t6t_rs") + private val targetPose_RobotSpace = DoubleArray(6) + + fun getCameraPose_TargetSpace(): Pose3d { + return toPose3D(cameraPose_TargetSpace) + } + + fun getRobotPose_FieldSpace(): Pose3d { + return toPose3D(robotPose_FieldSpace) + } + + fun getRobotPose_TargetSpace(): Pose3d { + return toPose3D(robotPose_TargetSpace) + } + + fun getTargetPose_CameraSpace(): Pose3d { + return toPose3D(targetPose_CameraSpace) + } + + fun getTargetPose_RobotSpace(): Pose3d { + return toPose3D(targetPose_RobotSpace) + } + + val cameraPose_TargetSpace2D: Pose2d + get() = toPose2D(cameraPose_TargetSpace) + val robotPose_FieldSpace2D: Pose2d + get() = toPose2D(robotPose_FieldSpace) + val robotPose_TargetSpace2D: Pose2d + get() = toPose2D(robotPose_TargetSpace) + val targetPose_CameraSpace2D: Pose2d + get() = toPose2D(targetPose_CameraSpace) + val targetPose_RobotSpace2D: Pose2d + get() = toPose2D(targetPose_RobotSpace) + + @JsonProperty("ta") + var ta: Double = 0.0 + + @JsonProperty("tx") + var tx: Double = 0.0 + + @JsonProperty("txp") + var tx_pixels: Double = 0.0 + + @JsonProperty("ty") + var ty: Double = 0.0 + + @JsonProperty("typ") + var ty_pixels: Double = 0.0 + + @JsonProperty("ts") + var ts: Double = 0.0 + } + + class LimelightTarget_Fiducial { + @JsonProperty("fID") + var fiducialID: Double = 0.0 + + @JsonProperty("fam") + var fiducialFamily: String? = null + + @JsonProperty("t6c_ts") + private val cameraPose_TargetSpace = DoubleArray(6) + + @JsonProperty("t6r_fs") + private val robotPose_FieldSpace = DoubleArray(6) + + @JsonProperty("t6r_ts") + private val robotPose_TargetSpace = DoubleArray(6) + + @JsonProperty("t6t_cs") + private val targetPose_CameraSpace = DoubleArray(6) + + @JsonProperty("t6t_rs") + private val targetPose_RobotSpace = DoubleArray(6) + + fun getCameraPose_TargetSpace(): Pose3d { + return toPose3D(cameraPose_TargetSpace) + } + + fun getRobotPose_FieldSpace(): Pose3d { + return toPose3D(robotPose_FieldSpace) + } + + fun getRobotPose_TargetSpace(): Pose3d { + return toPose3D(robotPose_TargetSpace) + } + + fun getTargetPose_CameraSpace(): Pose3d { + return toPose3D(targetPose_CameraSpace) + } + + fun getTargetPose_RobotSpace(): Pose3d { + return toPose3D(targetPose_RobotSpace) + } + + val cameraPose_TargetSpace2D: Pose2d + get() = toPose2D(cameraPose_TargetSpace) + val robotPose_FieldSpace2D: Pose2d + get() = toPose2D(robotPose_FieldSpace) + val robotPose_TargetSpace2D: Pose2d + get() = toPose2D(robotPose_TargetSpace) + val targetPose_CameraSpace2D: Pose2d + get() = toPose2D(targetPose_CameraSpace) + val targetPose_RobotSpace2D: Pose2d + get() = toPose2D(targetPose_RobotSpace) + + @JsonProperty("ta") + var ta: Double = 0.0 + + @JsonProperty("tx") + var tx: Double = 0.0 + + @JsonProperty("txp") + var tx_pixels: Double = 0.0 + + @JsonProperty("ty") + var ty: Double = 0.0 + + @JsonProperty("typ") + var ty_pixels: Double = 0.0 + + @JsonProperty("ts") + var ts: Double = 0.0 + } + + class LimelightTarget_Barcode + + class LimelightTarget_Classifier { + @JsonProperty("class") + var className: String? = null + + @JsonProperty("classID") + var classID: Double = 0.0 + + @JsonProperty("conf") + var confidence: Double = 0.0 + + @JsonProperty("zone") + var zone: Double = 0.0 + + @JsonProperty("tx") + var tx: Double = 0.0 + + @JsonProperty("txp") + var tx_pixels: Double = 0.0 + + @JsonProperty("ty") + var ty: Double = 0.0 + + @JsonProperty("typ") + var ty_pixels: Double = 0.0 + } + + class LimelightTarget_Detector { + @JsonProperty("class") + var className: String? = null + + @JsonProperty("classID") + var classID: Double = 0.0 + + @JsonProperty("conf") + var confidence: Double = 0.0 + + @JsonProperty("ta") + var ta: Double = 0.0 + + @JsonProperty("tx") + var tx: Double = 0.0 + + @JsonProperty("txp") + var tx_pixels: Double = 0.0 + + @JsonProperty("ty") + var ty: Double = 0.0 + + @JsonProperty("typ") + var ty_pixels: Double = 0.0 + } + + class Results { + @JsonProperty("pID") + var pipelineID: Double = 0.0 + + @JsonProperty("tl") + var latency_pipeline: Double = 0.0 + + @JsonProperty("cl") + var latency_capture: Double = 0.0 + + var latency_jsonParse: Double = 0.0 + + @JsonProperty("ts") + var timestamp_LIMELIGHT_publish: Double = 0.0 + + @JsonProperty("ts_rio") + var timestamp_RIOFPGA_capture: Double = 0.0 + + @JsonProperty("v") + @JsonFormat(shape = JsonFormat.Shape.NUMBER) + var valid: Boolean = false + + @JsonProperty("botpose") + var botpose: DoubleArray = DoubleArray(6) + + @JsonProperty("botpose_wpired") + var botpose_wpired: DoubleArray = DoubleArray(6) + + @JsonProperty("botpose_wpiblue") + var botpose_wpiblue: DoubleArray = DoubleArray(6) + + @JsonProperty("t6c_rs") + var camerapose_robotspace: DoubleArray = DoubleArray(6) + + val botPose3d: Pose3d + get() = toPose3D(botpose) + + val botPose3d_wpiRed: Pose3d + get() = toPose3D(botpose_wpired) + + val botPose3d_wpiBlue: Pose3d + get() = toPose3D(botpose_wpiblue) + + val botPose2d: Pose2d + get() = toPose2D(botpose) + + val botPose2d_wpiRed: Pose2d + get() = toPose2D(botpose_wpired) + + val botPose2d_wpiBlue: Pose2d + get() = toPose2D(botpose_wpiblue) + + @JsonProperty("Retro") + var targets_Retro: Array = arrayOfNulls(0) + + @JsonProperty("Fiducial") + var targets_Fiducials: Array = arrayOfNulls(0) + + @JsonProperty("Classifier") + var targets_Classifier: Array = arrayOfNulls(0) + + @JsonProperty("Detector") + var targets_Detector: Array = arrayOfNulls(0) + + @JsonProperty("Barcode") + var targets_Barcode: Array = arrayOfNulls(0) + } + + class LimelightResults { + @JsonProperty("Results") + var targetingResults: Results = Results() + } +} \ No newline at end of file diff --git a/vendordeps/yagsl.json b/vendordeps/yagsl.json new file mode 100644 index 0000000..e0169c8 --- /dev/null +++ b/vendordeps/yagsl.json @@ -0,0 +1,22 @@ +{ + "fileName": "yagsl.json", + "name": "YAGSL", + "version": "2024.4.8.6", + "frcYear": "2024", + "uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400", + "mavenUrls": [ + "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/repos" + ], + "jsonUrl": "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json", + "javaDependencies": [ + { + "groupId": "swervelib", + "artifactId": "YAGSL-java", + "version": "2024.4.8.6" + } + ], + "jniDependencies": [ + ], + "cppDependencies": [ + ] +} From 4c45ccd6eb9a6b57a6983f3519c3921f3851b737 Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Tue, 19 Mar 2024 01:53:01 -0400 Subject: [PATCH 07/13] it is 1:52 am right now --- YAGSL | 2 +- src/main/java/frc/robot/RobotContainer.kt | 79 +++++++++--------- .../java/frc/robot/commands/HomeArmCommand.kt | 57 +++++++++++++ .../java/frc/robot/commands/IntakeCommand.kt | 4 +- .../java/frc/robot/commands/MoveArmCommand.kt | 3 +- ...akeCommand2.kt => ReverseIntakeCommand.kt} | 2 +- .../java/frc/robot/subsystems/ArmSubsystem.kt | 31 ++++--- .../frc/robot/subsystems/SwerveSubsystem.kt | 83 +++++++------------ .../robot/subsystems/TelemetrySubsystem.kt | 18 +++- .../frc/robot/subsystems/VisionSubsystem.kt | 2 +- .../subsystems/shooter/ShooterIOSparkFlex.kt | 8 +- .../frc/robot/util/{Alert1.kt => Alert.kt} | 0 .../util/{Constants1.kt => Constants.kt} | 0 ...melightHelpers1.kt => LimelightHelpers.kt} | 0 14 files changed, 174 insertions(+), 115 deletions(-) create mode 100644 src/main/java/frc/robot/commands/HomeArmCommand.kt rename src/main/java/frc/robot/commands/{IntakeCommand2.kt => ReverseIntakeCommand.kt} (88%) rename src/main/java/frc/robot/util/{Alert1.kt => Alert.kt} (100%) rename src/main/java/frc/robot/util/{Constants1.kt => Constants.kt} (100%) rename src/main/java/frc/robot/util/{LimelightHelpers1.kt => LimelightHelpers.kt} (100%) diff --git a/YAGSL b/YAGSL index 1e6352d..1e21f8e 160000 --- a/YAGSL +++ b/YAGSL @@ -1 +1 @@ -Subproject commit 1e6352d216df661a2a84ff985facefd9ca3ada1b +Subproject commit 1e21f8edbf0a03881a490670fc8bb46c58a05343 diff --git a/src/main/java/frc/robot/RobotContainer.kt b/src/main/java/frc/robot/RobotContainer.kt index 8fd64d1..aaea852 100644 --- a/src/main/java/frc/robot/RobotContainer.kt +++ b/src/main/java/frc/robot/RobotContainer.kt @@ -11,6 +11,7 @@ import edu.wpi.first.wpilibj.DriverStation import edu.wpi.first.wpilibj.DriverStation.Alliance import edu.wpi.first.wpilibj.RobotBase import edu.wpi.first.wpilibj.XboxController +import edu.wpi.first.wpilibj.XboxController.Button import edu.wpi.first.wpilibj2.command.Command import edu.wpi.first.wpilibj2.command.InstantCommand import edu.wpi.first.wpilibj2.command.button.JoystickButton @@ -26,7 +27,6 @@ import frc.robot.subsystems.intake.IntakeIOSparkMax import frc.robot.subsystems.shooter.Shooter import frc.robot.subsystems.shooter.ShooterIOSparkFlex import frc.robot.util.Constants.OperatorConstants -import java.util.function.DoubleSupplier /** * This class is where the bulk of the robot should be declared. Since Command-based is a "declarative" paradigm, very @@ -47,7 +47,8 @@ class RobotContainer { private val aimAndPickUpNoteCommand: Command private val armSysIdCommand: Command private val moveArmCommand: Command - private val intakeCommand2: Command + private val reverseIntakeCommand: Command + private val homeArmCommand: Command private val absoluteFieldDrive: Command @@ -55,6 +56,7 @@ class RobotContainer { * */ private var driverXbox: XboxController = XboxController(0) + /** * */ @@ -72,8 +74,7 @@ class RobotContainer { drivebase.driveToPose( Pose2d( Translation2d( - 2.720, - 2.579 + 2.720, 2.579 ), Rotation2d.fromDegrees(180.0) ) ).andThen(drivebase.driveToPose(Pose2d(Translation2d(2.720, 2.579), Rotation2d.fromDegrees(180.0)))) @@ -83,11 +84,11 @@ class RobotContainer { aimAndPickUpNoteCommand = AimAndPickUpNoteCommand(drivebase, VisionSubsystem.instance, intake) armSysIdCommand = ArmSubsystem.generateSysIdCommand(armSubsystem.sysId, 2.0, 3.5, 1.5) moveArmCommand = MoveArmCommand { MathUtil.applyDeadband(shooterXbox.rightY, 0.1) } - intakeCommand2 = IntakeCommand2(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } + reverseIntakeCommand = ReverseIntakeCommand(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } + homeArmCommand = HomeArmCommand(armSubsystem) val invert = invert - absoluteFieldDrive = AbsoluteFieldDrive( - drivebase, + absoluteFieldDrive = AbsoluteFieldDrive(drivebase, { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, { driverXbox.rightX * invert }) @@ -96,13 +97,16 @@ class RobotContainer { // controls are front-left positive // left stick controls translation // right stick controls the desired angle NOT angular rotation - val driveFieldOrientedDirectAngle = drivebase.driveCommand( - { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, + val driveFieldOrientedDirectAngle = drivebase.driveCommand({ + MathUtil.applyDeadband( + driverXbox.leftY, + OperatorConstants.LEFT_Y_DEADBAND + ) * invert + }, { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, { driverXbox.rightX * invert }, { driverXbox.rightY * invert }) - val closedAbsoluteDriveAdv = AbsoluteDriveAdv( - drivebase, + val closedAbsoluteDriveAdv = AbsoluteDriveAdv(drivebase, { MathUtil.applyDeadband(driverXbox.leftY * invert, OperatorConstants.LEFT_Y_DEADBAND) }, { MathUtil.applyDeadband(driverXbox.leftX * invert, OperatorConstants.LEFT_X_DEADBAND) }, { MathUtil.applyDeadband(driverXbox.rightX * invert, OperatorConstants.RIGHT_X_DEADBAND) }, @@ -116,24 +120,32 @@ class RobotContainer { // controls are front-left positive // left stick controls translation // right stick controls the angular velocity of the robot - val driveFieldOrientedAnglularVelocity = drivebase.driveCommand( - { -MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, + val driveFieldOrientedAnglularVelocity = drivebase.driveCommand({ + -MathUtil.applyDeadband( + driverXbox.leftY, + OperatorConstants.LEFT_Y_DEADBAND + ) * invert + }, { -MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, { driverXbox.getRawAxis(4) * invert }) - val driveFieldOrientedDirectAngleSim = drivebase.simDriveCommand( - { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) * invert }, + val driveFieldOrientedDirectAngleSim = drivebase.simDriveCommand({ + MathUtil.applyDeadband( + driverXbox.leftY, + OperatorConstants.LEFT_Y_DEADBAND + ) * invert + }, { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, { driverXbox.getRawAxis(2) * invert }) val sysIdForDrive = drivebase.sysIdDriveMotorCommand() val sysIdForAngle = drivebase.sysIdAngleMotorCommand() - val driveFieldOrientedDirectAngleForTesting = drivebase.driveCommand( - { MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) }, - { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) }, - { driverXbox.rightX }, - { driverXbox.rightY }) + val driveFieldOrientedDirectAngleForTesting = + drivebase.driveCommand({ MathUtil.applyDeadband(driverXbox.leftY, OperatorConstants.LEFT_Y_DEADBAND) }, + { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) }, + { driverXbox.rightX }, + { driverXbox.rightY }) drivebase.defaultCommand = if (!RobotBase.isSimulation()) driveFieldOrientedAnglularVelocity else driveFieldOrientedDirectAngleSim @@ -165,26 +177,17 @@ class RobotContainer { private fun configureBindings() { // Schedule `ExampleCommand` when `exampleCondition` changes to `true` - JoystickButton(driverXbox, 1).onTrue((InstantCommand({ drivebase.zeroGyro() }))) - JoystickButton(driverXbox, XboxController.Button.kX.value).whileTrue(aimAtLimelightCommand) - JoystickButton(driverXbox, 2).whileTrue(driveToPoseCommand) - JoystickButton(driverXbox, XboxController.Button.kY.value).whileTrue(rotateCommand) - - - JoystickButton( - shooterXbox, - XboxController.Button.kLeftBumper.value - ).whileTrue(intakeCommand) // independent of speed - JoystickButton(driverXbox, XboxController.Button.kLeftBumper.value).whileTrue(intakeCommand) - JoystickButton(driverXbox, XboxController.Button.kY.value).whileTrue(aimAndPickUpNoteCommand) + JoystickButton(driverXbox, Button.kA.value).onTrue((InstantCommand({ drivebase.zeroGyro() }))) + JoystickButton(driverXbox, Button.kX.value).whileTrue(aimAtLimelightCommand) + JoystickButton(driverXbox, Button.kB.value).whileTrue(driveToPoseCommand) + JoystickButton(driverXbox, Button.kY.value).whileTrue(rotateCommand) + JoystickButton(driverXbox, Button.kLeftBumper.value).whileTrue(intakeCommand) + JoystickButton(driverXbox, Button.kY.value).whileTrue(aimAndPickUpNoteCommand) - JoystickButton(shooterXbox, XboxController.Button.kA.value).whileTrue(moveArmCommand) - JoystickButton( - shooterXbox, - XboxController.Button.kB.value - ).whileTrue(shooter.generateSysIdCommand(shooter.sysIdRoutine, 2.0, 10.0, 10.0)) - JoystickButton(shooterXbox, XboxController.Button.kRightBumper.value).whileTrue(intakeCommand2) + JoystickButton(shooterXbox, Button.kLeftBumper.value).whileTrue(intakeCommand) // independent of speed + JoystickButton(shooterXbox, Button.kRightBumper.value).whileTrue(reverseIntakeCommand) + JoystickButton(shooterXbox, Button.kA.value).onTrue(homeArmCommand) diff --git a/src/main/java/frc/robot/commands/HomeArmCommand.kt b/src/main/java/frc/robot/commands/HomeArmCommand.kt new file mode 100644 index 0000000..7a9d25e --- /dev/null +++ b/src/main/java/frc/robot/commands/HomeArmCommand.kt @@ -0,0 +1,57 @@ +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.ArmSubsystem + +class HomeArmCommand(private val arm: ArmSubsystem) : Command() { + private val armSubsystem = arm + private var hasHitLimit = false + + + init { + // each subsystem used by the command must be passed into the addRequirements() method + addRequirements(armSubsystem) + } + + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() { + } + + /** + * The main body of a command. Called repeatedly while the command is scheduled. + * (That is, it is called repeatedly until [isFinished] returns true.) + */ + override fun execute() { + armSubsystem.moveArm(-0.5) + hasHitLimit = armSubsystem.hasHitLowerLimit + } + + /** + * Returns whether this command has finished. Once a command finishes -- indicated by + * this method returning true -- the scheduler will call its [end] method. + * + * Returning false will result in the command never ending automatically. It may still be + * cancelled manually or interrupted by another command. Hard coding this command to always + * return true will result in the command executing once and finishing immediately. It is + * recommended to use [InstantCommand][edu.wpi.first.wpilibj2.command.InstantCommand] + * for such an operation. + * + * @return whether this command has finished. + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return 37 < armSubsystem.angle && armSubsystem.angle < 43 + } + + /** + * The action to take when the command ends. Called when either the command + * finishes normally -- that is, it is called when [isFinished] returns + * true -- or when it is interrupted/canceled. This is where you may want to + * wrap up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + override fun end(interrupted: Boolean) {} +} diff --git a/src/main/java/frc/robot/commands/IntakeCommand.kt b/src/main/java/frc/robot/commands/IntakeCommand.kt index c54df7f..f9ddea9 100644 --- a/src/main/java/frc/robot/commands/IntakeCommand.kt +++ b/src/main/java/frc/robot/commands/IntakeCommand.kt @@ -24,7 +24,7 @@ class IntakeCommand(private val intake: Intake, private val speed: DoubleSupplie * */ override fun execute() { - intake[0.25] = -0.25 + intake.set(0.25, -0.25) } /** @@ -39,6 +39,6 @@ class IntakeCommand(private val intake: Intake, private val speed: DoubleSupplie * */ override fun end(interrupted: Boolean) { - intake[0.0] = 0.0 + intake.set(0.0, 0.0) } } diff --git a/src/main/java/frc/robot/commands/MoveArmCommand.kt b/src/main/java/frc/robot/commands/MoveArmCommand.kt index 0f4d15e..e8b47d1 100644 --- a/src/main/java/frc/robot/commands/MoveArmCommand.kt +++ b/src/main/java/frc/robot/commands/MoveArmCommand.kt @@ -1,5 +1,6 @@ package frc.robot.commands +import edu.wpi.first.wpilibj.DriverStation import edu.wpi.first.wpilibj2.command.Command import frc.robot.subsystems.ArmSubsystem import java.util.function.DoubleSupplier @@ -38,7 +39,7 @@ class MoveArmCommand( override fun execute() { //armSubsystem.moveArmButWithVelocity(speed.getAsDouble() * 144); angle += speed.asDouble - if (speed.asDouble != -1.0) armSubsystem.moveArmToAngle(angle) + armSubsystem.moveArmToAngle(angle) } /** diff --git a/src/main/java/frc/robot/commands/IntakeCommand2.kt b/src/main/java/frc/robot/commands/ReverseIntakeCommand.kt similarity index 88% rename from src/main/java/frc/robot/commands/IntakeCommand2.kt rename to src/main/java/frc/robot/commands/ReverseIntakeCommand.kt index 8c98f68..6e831ba 100644 --- a/src/main/java/frc/robot/commands/IntakeCommand2.kt +++ b/src/main/java/frc/robot/commands/ReverseIntakeCommand.kt @@ -7,7 +7,7 @@ import java.util.function.DoubleSupplier /** * */ -class IntakeCommand2(private val intake: Intake, private val speed: DoubleSupplier) : Command() { +class ReverseIntakeCommand(private val intake: Intake, private val speed: DoubleSupplier) : Command() { init { // each subsystem used by the command must be passed into the // addRequirements() method (which takes a vararg of Subsystem) diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt index db5bba8..8d6601f 100644 --- a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt @@ -18,6 +18,9 @@ import org.littletonrobotics.junction.* import kotlin.math.atan2 class ArmSubsystem private constructor() : SubsystemBase() { + var hasHitLowerLimit: Boolean = false + get() = reverseLimitSwitch.isPressed + // With eager singleton initialization, any static variables/fields used in the // constructor must appear before the "INSTANCE" variable so that they are initialized // before the constructor is called when the "INSTANCE" variable initializes. @@ -35,7 +38,7 @@ class ArmSubsystem private constructor() : SubsystemBase() { private val reverseLimitSwitch: SparkLimitSwitch private val pidController: SparkPIDController - private val encoder: SparkAbsoluteEncoder = rightMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle) + private val encoder: SparkAbsoluteEncoder = leftMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle) private var maxRange = 0.0 // amount of revolutions (or other unit) it takes to move the arm from min to max private val setpoint: Double @@ -82,9 +85,7 @@ class ArmSubsystem private constructor() : SubsystemBase() { // Takes a double 0 to 1 as a parameter, where 0 is the arm at its lower limit // and 1 at its upper limit. fun moveArm(p: Double) { - val distanceFromMin = p * maxRange - val distanceFromFinal = distanceFromMin - encoder.position // Final - inital = delta position. - rotate(distanceFromFinal) + leftMotor.set(p) } @@ -95,6 +96,8 @@ class ArmSubsystem private constructor() : SubsystemBase() { Mechanism({ v: Measure -> this.setVoltage(v.`in`(Units.Volts)) }, null, this) ) + + /** * Creates a new instance of this ArmSubsystem. This constructor is private since this class * is a Singleton. Code should use the [.getInstance] method to get the singleton @@ -116,27 +119,28 @@ class ArmSubsystem private constructor() : SubsystemBase() { rightMotor.setSmartCurrentLimit(40) rightMotor.burnFlash() - pidController = rightMotor.pidController + pidController = leftMotor.pidController - forwardLimitSwitch = rightMotor.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen) - reverseLimitSwitch = rightMotor.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen) + forwardLimitSwitch = leftMotor.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen) + reverseLimitSwitch = leftMotor.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen) forwardLimitSwitch.enableLimitSwitch(true) reverseLimitSwitch.enableLimitSwitch(true) pidController.setFeedbackDevice(encoder) - pidController.setP(0.01) + pidController.setP(0.016) pidController.setI(0.0) - pidController.setD(0.0) - pidController.setPositionPIDWrappingMinInput(-0.75) - pidController.setPositionPIDWrappingMaxInput(0.75) + pidController.setD(0.016) + pidController.setFF(0.001) + setpoint = encoder.position SmartDashboard.putNumber("Arm Setpoint", setpoint) + pidController.setOutputRange(-0.75, 0.75) encoder.setPositionConversionFactor(360.0) // 1 rotation = 360 degrees @@ -149,7 +153,6 @@ class ArmSubsystem private constructor() : SubsystemBase() { // pidController.setD(kD); // pidController.setIZone(kIz); // pidController.setFF(kFF); -// pidController.setOutputRange(kMinOutput, kMaxOutput); pidController.setFeedbackDevice(encoder) } @@ -174,7 +177,9 @@ class ArmSubsystem private constructor() : SubsystemBase() { //pidController.setReference(SmartDashboard.getNumber("Arm Setpoint", setpoint), CANSparkMax.ControlType.kPosition); } - + fun homeArm() { + moveArmToAngle(40.0) + } fun getArmAngleForShooting(robotPose: Pose3d): Double { val alliance = DriverStation.getAlliance().get() diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt index f83e03c..f9a60d4 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt @@ -24,6 +24,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine import frc.robot.util.Constants.AutonomousConstants import frc.robot.util.LimelightHelpers +import org.littletonrobotics.junction.Logger import swervelib.SwerveController import swervelib.SwerveDrive import swervelib.SwerveDriveTest @@ -104,15 +105,13 @@ class SwerveSubsystem : SubsystemBase { 4.5, // Max module speed, in m/s swerveDrive.swerveDriveConfiguration.driveBaseRadiusMeters, // Drive base radius in meters. Distance from robot center to furthest module. ReplanningConfig(true, true) // Default path replanning config. See the API for the options here - ), - { + ), { // Boolean supplier that controls when the path will be mirrored for the red alliance // This will flip the path being followed to the red side of the field. // THE ORIGIN WILL REMAIN ON THE BLUE SIDE val alliance = DriverStation.getAlliance() if (alliance.isPresent) alliance.get() == Alliance.Red else false - }, - this // Reference to this subsystem to set requirements + }, this // Reference to this subsystem to set requirements ) } @@ -127,9 +126,7 @@ class SwerveSubsystem : SubsystemBase { if (LimelightHelpers.getTV(camera)) { drive( getTargetSpeeds( - 0.0, - 0.0, - Rotation2d.fromDegrees(LimelightHelpers.getTX(camera)) + 0.0, 0.0, Rotation2d.fromDegrees(LimelightHelpers.getTX(camera)) ) ) // Not sure if this will work, more math may be required. } @@ -158,15 +155,12 @@ class SwerveSubsystem : SubsystemBase { val path = PathPlannerPath.fromPathFile("Go to red speaker") // Create the constraints to use while pathfinding val constraints = PathConstraints( - swerveDrive.maximumVelocity, 4.0, - swerveDrive.maximumAngularVelocity, Units.degreesToRadians(720.0) + swerveDrive.maximumVelocity, 4.0, swerveDrive.maximumAngularVelocity, Units.degreesToRadians(720.0) ) // Since AutoBuilder is configured, we can use it to build pathfinding commands return AutoBuilder.pathfindToPose( - pose, - constraints, - 0.0, // Goal end velocity in meters/sec + pose, constraints, 0.0, // Goal end velocity in meters/sec 0.0 // Rotation delay distance in meters. This is how far the robot should travel before attempting to rotate. ) } @@ -182,7 +176,7 @@ class SwerveSubsystem : SubsystemBase { */ fun driveCommand( translationX: DoubleSupplier, translationY: DoubleSupplier, headingX: DoubleSupplier, - headingY: DoubleSupplier + headingY: DoubleSupplier, ): Command { // swerveDrive.setHeadingCorrection(true); // Normally you would want heading correction for this kind of control. return run { @@ -191,7 +185,8 @@ class SwerveSubsystem : SubsystemBase { // Make the robot move driveFieldOriented( swerveDrive.swerveController.getTargetSpeeds( - xInput, yInput, + xInput, + yInput, headingX.asDouble, headingY.asDouble, swerveDrive.odometryHeading.radians, @@ -233,10 +228,8 @@ class SwerveSubsystem : SubsystemBase { fun sysIdDriveMotorCommand(): Command { return SwerveDriveTest.generateSysIdCommand( SwerveDriveTest.setDriveSysIdRoutine( - SysIdRoutine.Config(), - this, swerveDrive, 12.0 - ), - 3.0, 5.0, 3.0 + SysIdRoutine.Config(), this, swerveDrive, 12.0 + ), 3.0, 5.0, 3.0 ) } @@ -248,10 +241,8 @@ class SwerveSubsystem : SubsystemBase { fun sysIdAngleMotorCommand(): Command { return SwerveDriveTest.generateSysIdCommand( SwerveDriveTest.setAngleSysIdRoutine( - SysIdRoutine.Config(), - this, swerveDrive - ), - 3.0, 5.0, 3.0 + SysIdRoutine.Config(), this, swerveDrive + ), 3.0, 5.0, 3.0 ) } @@ -266,7 +257,7 @@ class SwerveSubsystem : SubsystemBase { fun driveCommand( translationX: DoubleSupplier, translationY: DoubleSupplier, - angularRotationX: DoubleSupplier + angularRotationX: DoubleSupplier, ): Command { return run { // Make the robot move @@ -274,10 +265,7 @@ class SwerveSubsystem : SubsystemBase { Translation2d( translationX.asDouble.pow(3.0) * swerveDrive.maximumVelocity, translationY.asDouble.pow(3.0) * swerveDrive.maximumVelocity - ), - angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, - true, - false + ), angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, true, false ) } } @@ -288,7 +276,7 @@ class SwerveSubsystem : SubsystemBase { fun driveCommandNonRel( translationX: DoubleSupplier, translationY: DoubleSupplier, - angularRotationX: DoubleSupplier + angularRotationX: DoubleSupplier, ): Command { return run { // Make the robot move @@ -296,10 +284,7 @@ class SwerveSubsystem : SubsystemBase { Translation2d( translationX.asDouble.pow(3.0) * swerveDrive.maximumVelocity, translationY.asDouble.pow(3.0) * swerveDrive.maximumVelocity - ), - angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, - false, - false + ), angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, false, false ) } } @@ -320,10 +305,7 @@ class SwerveSubsystem : SubsystemBase { */ fun drive(translation: Translation2d?, rotation: Double, fieldRelative: Boolean) { swerveDrive.drive( - translation, - rotation, - fieldRelative, - false + translation, rotation, fieldRelative, false ) // Open loop is disabled since it shouldn't be used most of the time. } @@ -349,15 +331,21 @@ class SwerveSubsystem : SubsystemBase { * */ override fun periodic() { - if (LimelightHelpers.getTV("limelight-back")) swerveDrive.addVisionMeasurement( +// if (LimelightHelpers.getTV("limelight-back")) swerveDrive.addVisionMeasurement( +// LimelightHelpers.getBotPose2d_wpiRed( +// "limelight-back" +// ), +// Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture( +// "limelight-back" +// )) / 1000.0 +// ) + Logger.recordOutput( + "Limelight Pose", LimelightHelpers.getBotPose2d_wpiRed( "limelight-back" ), - Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture( - "limelight-back" - )) / 1000.0 ) - + Logger.recordOutput("Pose", pose) // PathPlannerLogging.logCurrentPose(getPose()); swerveDrive.updateOdometry() @@ -465,12 +453,7 @@ class SwerveSubsystem : SubsystemBase { xInput = xInput.pow(3.0) yInput = yInput.pow(3.0) return swerveDrive.swerveController.getTargetSpeeds( - xInput, - yInput, - headingX, - headingY, - heading.radians, - maximumSpeed + xInput, yInput, headingX, headingY, heading.radians, maximumSpeed ) } @@ -489,11 +472,7 @@ class SwerveSubsystem : SubsystemBase { xInput = xInput.pow(3.0) yInput = yInput.pow(3.0) return swerveDrive.swerveController.getTargetSpeeds( - xInput, - yInput, - angle.radians, - heading.radians, - maximumSpeed + xInput, yInput, angle.radians, heading.radians, maximumSpeed ) } diff --git a/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt b/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt index 7286a49..4434c52 100644 --- a/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt +++ b/src/main/java/frc/robot/subsystems/TelemetrySubsystem.kt @@ -1,11 +1,16 @@ package frc.robot.subsystems +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard +import edu.wpi.first.wpilibj2.command.Subsystem import edu.wpi.first.wpilibj2.command.SubsystemBase +import java.util.function.BooleanSupplier /** * */ -object TelemetrySubsystem : SubsystemBase() { +class TelemetrySubsystem +private constructor() : Subsystem { + var hasNote: BooleanSupplier? = null // With eager singleton initialization, any static variables/fields used in the // constructor must appear before the "INSTANCE" variable so that they are initialized // before the constructor is called when the "INSTANCE" variable initializes. @@ -17,5 +22,14 @@ object TelemetrySubsystem : SubsystemBase() { * The Singleton instance of this TelemetrySubsystem. Code should use the [.getInstance] * method to get the single instance (rather than trying to construct an instance of this class.) */ - val instance: TelemetrySubsystem = TelemetrySubsystem + companion object { val instance: TelemetrySubsystem = TelemetrySubsystem() } + + init { + Shuffleboard.getTab("Main") + .addBoolean("Has Note", hasNote).withSize(58, 2).withPosition(1, 0).withProperties(mapOf(Pair("Colors/Color when true", "#FF6A23FF"), Pair("Colors/Color when false", "#000000FF"))) + } + + fun setNoteSupplier(supplier: BooleanSupplier) { + hasNote = supplier; + } } diff --git a/src/main/java/frc/robot/subsystems/VisionSubsystem.kt b/src/main/java/frc/robot/subsystems/VisionSubsystem.kt index 1aa7f74..7a928ad 100644 --- a/src/main/java/frc/robot/subsystems/VisionSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/VisionSubsystem.kt @@ -78,7 +78,7 @@ private constructor() : SubsystemBase() { // if your limelight and target are mounted at the same or similar heights, use "ta" (area) for target ranging rather than "ty" fun limelightRangeProportional(): Double { val kP = .1 - var targetingForwardSpeed = LimelightHelpers.getTY("limelight-front") * kP + var targetingForwardSpeed = (LimelightHelpers.getTY("limelight-front") + 28.1) * kP targetingForwardSpeed *= SwerveSubsystem.instance.swerveDrive.maximumVelocity targetingForwardSpeed *= -1.0 return targetingForwardSpeed diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt index c248013..a188020 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt @@ -46,14 +46,14 @@ class ShooterIOSparkFlex : ShooterIO { val i = SimpleMotorFeedforward(0.028196, 0.0017838, 0.00020814) // use that to set the feed forward for the lower motor - lowerPID.setFF(i.calculate(3750.0)) - upperPID.setFF(i.calculate(3750.0)) + lowerPID.setP(0.0003) + upperPID.setP(0.0003) - lowerPID.setP(0.0005) + lowerPID.setFF(0.0002) lowerPID.setI(0.0) lowerPID.setD(0.0) - upperPID.setP(0.0005) + upperPID.setFF(0.0002) upperPID.setI(0.0) upperPID.setD(0.0) } diff --git a/src/main/java/frc/robot/util/Alert1.kt b/src/main/java/frc/robot/util/Alert.kt similarity index 100% rename from src/main/java/frc/robot/util/Alert1.kt rename to src/main/java/frc/robot/util/Alert.kt diff --git a/src/main/java/frc/robot/util/Constants1.kt b/src/main/java/frc/robot/util/Constants.kt similarity index 100% rename from src/main/java/frc/robot/util/Constants1.kt rename to src/main/java/frc/robot/util/Constants.kt diff --git a/src/main/java/frc/robot/util/LimelightHelpers1.kt b/src/main/java/frc/robot/util/LimelightHelpers.kt similarity index 100% rename from src/main/java/frc/robot/util/LimelightHelpers1.kt rename to src/main/java/frc/robot/util/LimelightHelpers.kt From 6fc573f6010329d13894a10165648c2f3a531ad8 Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Tue, 19 Mar 2024 10:29:12 -0400 Subject: [PATCH 08/13] feat(swerve, shooter): further advance our plan --- YAGSL | 2 +- simgui-ds.json | 5 ++ simgui-window.json | 31 +++++----- simgui.json | 33 ++++++++++- .../deploy/maxswerve/modules/backright.json | 2 +- .../deploy/swerve/controllerproperties.json | 8 --- src/main/deploy/swerve/modules/backleft.json | 23 -------- src/main/deploy/swerve/modules/backright.json | 23 -------- src/main/deploy/swerve/modules/frontleft.json | 23 -------- .../deploy/swerve/modules/frontright.json | 23 -------- .../swerve/modules/physicalproperties.json | 16 ------ .../deploy/swerve/modules/pidfproperties.json | 16 ------ src/main/deploy/swerve/swervedrive.json | 14 ----- src/main/java/frc/robot/RobotContainer.kt | 16 +++++- .../robot/commands/FrostedFlakesCommand.kt | 56 +++++++++++++++++++ .../java/frc/robot/commands/IntakeCommand.kt | 5 +- .../java/frc/robot/commands/ShootCommand.kt | 11 +++- .../frc/robot/subsystems/SwerveSubsystem.kt | 18 +++--- .../frc/robot/subsystems/intake/Intake.kt | 7 +++ .../intake/IntakeIOInputsAutoLogged.kt | 1 + .../subsystems/intake/IntakeIOSparkMax.kt | 24 +++++--- .../frc/robot/subsystems/shooter/Shooter.kt | 2 + vendordeps/yagsl.json | 22 -------- 23 files changed, 174 insertions(+), 207 deletions(-) delete mode 100644 src/main/deploy/swerve/controllerproperties.json delete mode 100644 src/main/deploy/swerve/modules/backleft.json delete mode 100644 src/main/deploy/swerve/modules/backright.json delete mode 100644 src/main/deploy/swerve/modules/frontleft.json delete mode 100644 src/main/deploy/swerve/modules/frontright.json delete mode 100644 src/main/deploy/swerve/modules/physicalproperties.json delete mode 100644 src/main/deploy/swerve/modules/pidfproperties.json delete mode 100644 src/main/deploy/swerve/swervedrive.json create mode 100644 src/main/java/frc/robot/commands/FrostedFlakesCommand.kt delete mode 100644 vendordeps/yagsl.json diff --git a/YAGSL b/YAGSL index 1e21f8e..b1bc574 160000 --- a/YAGSL +++ b/YAGSL @@ -1 +1 @@ -Subproject commit 1e21f8edbf0a03881a490670fc8bb46c58a05343 +Subproject commit b1bc574fa246b0f9f70a604b86cd704366723b98 diff --git a/simgui-ds.json b/simgui-ds.json index 73cc713..69b1a3c 100644 --- a/simgui-ds.json +++ b/simgui-ds.json @@ -88,5 +88,10 @@ "buttonCount": 0, "povCount": 0 } + ], + "robotJoysticks": [ + { + "guid": "Keyboard0" + } ] } diff --git a/simgui-window.json b/simgui-window.json index 46ef9c3..50c8e8f 100644 --- a/simgui-window.json +++ b/simgui-window.json @@ -5,39 +5,44 @@ "MainWindow": { "GLOBAL": { "fps": "120", - "height": "720", + "height": "970", "maximized": "0", "style": "0", "userScale": "2", - "width": "1280", - "xpos": "-1", - "ypos": "-1" + "width": "956", + "xpos": "964", + "ypos": "66" } }, "Window": { + "###/SmartDashboard/Field": { + "Collapsed": "0", + "Pos": "246,435", + "Size": "595,340" + }, "###FMS": { "Collapsed": "0", "Pos": "5,540", - "Size": "283,146" + "Size": "169,184" }, "###Joysticks": { "Collapsed": "0", - "Pos": "250,465", - "Size": "796,73" + "Pos": "217,767", + "Size": "796,155" }, "###NetworkTables": { "Collapsed": "0", - "Pos": "250,277", - "Size": "750,185" + "Pos": "235,165", + "Size": "750,254" }, "###NetworkTables Info": { "Collapsed": "0", - "Pos": "250,130", + "Pos": "243,35", "Size": "750,145" }, "###Other Devices": { "Collapsed": "0", - "Pos": "1025,20", + "Pos": "937,14", "Size": "250,695" }, "###System Joysticks": { @@ -48,7 +53,7 @@ "###Timing": { "Collapsed": "0", "Pos": "5,150", - "Size": "135,150" + "Size": "141,173" }, "Debug##Default": { "Collapsed": "0", @@ -58,7 +63,7 @@ "Robot State": { "Collapsed": "0", "Pos": "5,20", - "Size": "92,99" + "Size": "92,116" } } } diff --git a/simgui.json b/simgui.json index 5f9d275..284c55f 100644 --- a/simgui.json +++ b/simgui.json @@ -1,7 +1,38 @@ { "NTProvider": { "types": { - "/FMSInfo": "FMSInfo" + "/FMSInfo": "FMSInfo", + "/SmartDashboard/Field": "Field2d", + "/SmartDashboard/navX-Sensor[4]": "Gyro" + }, + "windows": { + "/SmartDashboard/Field": { + "bottom": 1476, + "height": 8.210550308227539, + "left": 150, + "right": 2961, + "top": 79, + "width": 16.541748046875, + "window": { + "visible": true + } + } + } + }, + "NetworkTables": { + "transitory": { + "SmartDashboard": { + "Field": { + "double[]##v_/SmartDashboard/Field/Robot": { + "open": true + }, + "double[]##v_/SmartDashboard/Field/XModules": { + "open": true + }, + "open": true + }, + "open": true + } } }, "NetworkTables Info": { diff --git a/src/main/deploy/maxswerve/modules/backright.json b/src/main/deploy/maxswerve/modules/backright.json index d65d30f..2b63dc5 100644 --- a/src/main/deploy/maxswerve/modules/backright.json +++ b/src/main/deploy/maxswerve/modules/backright.json @@ -1,4 +1,4 @@ -{ + { "drive": { "type": "sparkflex", "id": 4 diff --git a/src/main/deploy/swerve/controllerproperties.json b/src/main/deploy/swerve/controllerproperties.json deleted file mode 100644 index 6d17bfd..0000000 --- a/src/main/deploy/swerve/controllerproperties.json +++ /dev/null @@ -1,8 +0,0 @@ -{ - "angleJoystickRadiusDeadband": 0.5, - "heading": { - "p": 1.1, - "i": 0, - "d": 0.125 - } -} \ No newline at end of file diff --git a/src/main/deploy/swerve/modules/backleft.json b/src/main/deploy/swerve/modules/backleft.json deleted file mode 100644 index c64503f..0000000 --- a/src/main/deploy/swerve/modules/backleft.json +++ /dev/null @@ -1,23 +0,0 @@ -{ - "drive": { - "type": "sparkmax", - "id": 4 - }, - "angle": { - "type": "sparkmax", - "id": 3 - }, - "encoder": { - "type": "cancoder", - "id": 20 - }, - "inverted": { - "drive": false, - "angle": true - }, - "absoluteEncoderOffset": 107.842, - "location": { - "x": -12.3125, - "y": 12.3125 - } -} diff --git a/src/main/deploy/swerve/modules/backright.json b/src/main/deploy/swerve/modules/backright.json deleted file mode 100644 index eb3172d..0000000 --- a/src/main/deploy/swerve/modules/backright.json +++ /dev/null @@ -1,23 +0,0 @@ -{ - "drive": { - "type": "sparkmax", - "id": 6 - }, - "angle": { - "type": "sparkmax", - "id": 5 - }, - "encoder": { - "type": "cancoder", - "id": 22 - }, - "inverted": { - "drive": false, - "angle": true - }, - "absoluteEncoderOffset": 178.330, - "location": { - "x": -12.3125, - "y": -12.3125 - } -} diff --git a/src/main/deploy/swerve/modules/frontleft.json b/src/main/deploy/swerve/modules/frontleft.json deleted file mode 100644 index 7ba9774..0000000 --- a/src/main/deploy/swerve/modules/frontleft.json +++ /dev/null @@ -1,23 +0,0 @@ -{ - "drive": { - "type": "sparkmax", - "id": 2 - }, - "angle": { - "type": "sparkmax", - "id": 9 - }, - "encoder": { - "type": "cancoder", - "id": 21 - }, - "inverted": { - "drive": false, - "angle": true - }, - "absoluteEncoderOffset": 250.049, - "location": { - "x": 12.3125, - "y": 12.3125 - } -} diff --git a/src/main/deploy/swerve/modules/frontright.json b/src/main/deploy/swerve/modules/frontright.json deleted file mode 100644 index a815e97..0000000 --- a/src/main/deploy/swerve/modules/frontright.json +++ /dev/null @@ -1,23 +0,0 @@ -{ - "drive": { - "type": "sparkmax", - "id": 8 - }, - "angle": { - "type": "sparkmax", - "id": 7 - }, - "encoder": { - "type": "cancoder", - "id": 23 - }, - "inverted": { - "drive": false, - "angle": true - }, - "absoluteEncoderOffset": 254.092, - "location": { - "x": 12.3125, - "y": -12.3125 - } -} diff --git a/src/main/deploy/swerve/modules/physicalproperties.json b/src/main/deploy/swerve/modules/physicalproperties.json deleted file mode 100644 index 9be10f3..0000000 --- a/src/main/deploy/swerve/modules/physicalproperties.json +++ /dev/null @@ -1,16 +0,0 @@ -{ - "optimalVoltage": 12, - "wheelGripCoefficientOfFriction": 1.19, - "currentLimit": { - "drive": 40, - "angle": 20 - }, - "conversionFactor": { - "angle": 16.8, - "drive": 0.047286787200699704 - }, - "rampRate": { - "drive": 0.25, - "angle": 0.25 - } -} \ No newline at end of file diff --git a/src/main/deploy/swerve/modules/pidfproperties.json b/src/main/deploy/swerve/modules/pidfproperties.json deleted file mode 100644 index 99664bb..0000000 --- a/src/main/deploy/swerve/modules/pidfproperties.json +++ /dev/null @@ -1,16 +0,0 @@ -{ - "drive": { - "p": 0.0020645, - "i": 0, - "d": 0, - "f": 0, - "iz": 0 - }, - "angle": { - "p": 0.01, - "i": 0, - "d": 0, - "f": 0, - "iz": 0 - } -} \ No newline at end of file diff --git a/src/main/deploy/swerve/swervedrive.json b/src/main/deploy/swerve/swervedrive.json deleted file mode 100644 index 1264966..0000000 --- a/src/main/deploy/swerve/swervedrive.json +++ /dev/null @@ -1,14 +0,0 @@ -{ - "imu": { - "type": "navx_usb", - "id": 0, - "canbus": null - }, - "invertedIMU": true, - "modules": [ - "frontleft.json", - "frontright.json", - "backleft.json", - "backright.json" - ] -} \ No newline at end of file diff --git a/src/main/java/frc/robot/RobotContainer.kt b/src/main/java/frc/robot/RobotContainer.kt index aaea852..ba32103 100644 --- a/src/main/java/frc/robot/RobotContainer.kt +++ b/src/main/java/frc/robot/RobotContainer.kt @@ -13,6 +13,7 @@ import edu.wpi.first.wpilibj.RobotBase import edu.wpi.first.wpilibj.XboxController import edu.wpi.first.wpilibj.XboxController.Button import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.Commands import edu.wpi.first.wpilibj2.command.InstantCommand import edu.wpi.first.wpilibj2.command.button.JoystickButton import frc.robot.commands.* @@ -49,9 +50,14 @@ class RobotContainer { private val moveArmCommand: Command private val reverseIntakeCommand: Command private val homeArmCommand: Command + private val frostedFlakesCommand: Command private val absoluteFieldDrive: Command + private var shooterRunning: Boolean = false + private var hasNote: Boolean = false + + /** * */ @@ -67,10 +73,12 @@ class RobotContainer { */ init { intakeCommand = IntakeCommand(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } - shootCommand = ShootCommand(shooter) { MathUtil.applyDeadband(shooterXbox.rightTriggerAxis, 0.1) * 5700 } + shootCommand = ShootCommand(shooter, {MathUtil.applyDeadband(shooterXbox.rightTriggerAxis, 0.1)}, + { shooterRunning = true }, { shooterRunning = false }) aimAtLimelightCommand = AimAtLimelightCommand(drivebase, VisionSubsystem.instance) rotateCommand = RotateCommand(drivebase) - driveToPoseCommand = ShootCommand(shooter, { 4000.0 }).alongWith( + driveToPoseCommand = ShootCommand(shooter, { 4000.0 }, + { shooterRunning = true }, { shooterRunning = false }).alongWith( drivebase.driveToPose( Pose2d( Translation2d( @@ -86,6 +94,7 @@ class RobotContainer { moveArmCommand = MoveArmCommand { MathUtil.applyDeadband(shooterXbox.rightY, 0.1) } reverseIntakeCommand = ReverseIntakeCommand(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } homeArmCommand = HomeArmCommand(armSubsystem) + frostedFlakesCommand = FrostedFlakesCommand(intake) val invert = invert absoluteFieldDrive = AbsoluteFieldDrive(drivebase, @@ -185,7 +194,8 @@ class RobotContainer { JoystickButton(driverXbox, Button.kY.value).whileTrue(aimAndPickUpNoteCommand) - JoystickButton(shooterXbox, Button.kLeftBumper.value).whileTrue(intakeCommand) // independent of speed + // for the intake command, if the shooter is running, execute the frosted flakes command, and otherwise, execute the intake command + JoystickButton(shooterXbox, Button.kLeftBumper.value).whileTrue(Commands.either(frostedFlakesCommand, intakeCommand) { shooterRunning }) JoystickButton(shooterXbox, Button.kRightBumper.value).whileTrue(reverseIntakeCommand) JoystickButton(shooterXbox, Button.kA.value).onTrue(homeArmCommand) diff --git a/src/main/java/frc/robot/commands/FrostedFlakesCommand.kt b/src/main/java/frc/robot/commands/FrostedFlakesCommand.kt new file mode 100644 index 0000000..3617a71 --- /dev/null +++ b/src/main/java/frc/robot/commands/FrostedFlakesCommand.kt @@ -0,0 +1,56 @@ +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.intake.Intake +import frc.robot.subsystems.intake.IntakeIOSparkMax + +class FrostedFlakesCommand(private val intake: Intake) : Command() { + + + init { + // each subsystem used by the command must be passed into the addRequirements() method + addRequirements(intake) + } + + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() {} + + /** + * The main body of a command. Called repeatedly while the command is scheduled. + * (That is, it is called repeatedly until [isFinished] returns true.) + */ + override fun execute() { + intake.set(0.0, -1.0) + } + + /** + * Returns whether this command has finished. Once a command finishes -- indicated by + * this method returning true -- the scheduler will call its [end] method. + * + * Returning false will result in the command never ending automatically. It may still be + * cancelled manually or interrupted by another command. Hard coding this command to always + * return true will result in the command executing once and finishing immediately. It is + * recommended to use [InstantCommand][edu.wpi.first.wpilibj2.command.InstantCommand] + * for such an operation. + * + * @return whether this command has finished. + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return IntakeIOSparkMax.colorSensor.proximity <= 150 + } + + /** + * The action to take when the command ends. Called when either the command + * finishes normally -- that is, it is called when [isFinished] returns + * true -- or when it is interrupted/canceled. This is where you may want to + * wrap up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + override fun end(interrupted: Boolean) { + intake.set(0.0, 0.0) + } +} diff --git a/src/main/java/frc/robot/commands/IntakeCommand.kt b/src/main/java/frc/robot/commands/IntakeCommand.kt index f9ddea9..374394d 100644 --- a/src/main/java/frc/robot/commands/IntakeCommand.kt +++ b/src/main/java/frc/robot/commands/IntakeCommand.kt @@ -2,6 +2,7 @@ package frc.robot.commands import edu.wpi.first.wpilibj2.command.Command import frc.robot.subsystems.intake.Intake +import org.littletonrobotics.junction.Logger import java.util.function.DoubleSupplier /** @@ -25,6 +26,7 @@ class IntakeCommand(private val intake: Intake, private val speed: DoubleSupplie */ override fun execute() { intake.set(0.25, -0.25) + Logger.recordOutput("Proximity", (intake.colorSensorProximity ?: return).asDouble) } /** @@ -32,7 +34,7 @@ class IntakeCommand(private val intake: Intake, private val speed: DoubleSupplie */ override fun isFinished(): Boolean { // TODO: Make this return true when this Command no longer needs to run execute() - return false + return intake.colorSensorProximity!!.asDouble > 150 } /** @@ -40,5 +42,6 @@ class IntakeCommand(private val intake: Intake, private val speed: DoubleSupplie */ override fun end(interrupted: Boolean) { intake.set(0.0, 0.0) + } } diff --git a/src/main/java/frc/robot/commands/ShootCommand.kt b/src/main/java/frc/robot/commands/ShootCommand.kt index f411dca..9f80bbb 100644 --- a/src/main/java/frc/robot/commands/ShootCommand.kt +++ b/src/main/java/frc/robot/commands/ShootCommand.kt @@ -7,7 +7,9 @@ import java.util.function.DoubleSupplier /** * */ -class ShootCommand(private val shooter: Shooter, private val speed: DoubleSupplier) : Command() { +class ShootCommand(private val shooter: Shooter, private val speed: DoubleSupplier, private val shooterIsRunning: () -> Unit, private val shooterIsNotRunning: () -> Unit) : Command() { + + val maxRpm = 5700.0 init { // each subsystem used by the command must be passed into the // addRequirements() method (which takes a vararg of Subsystem) @@ -24,7 +26,12 @@ class ShootCommand(private val shooter: Shooter, private val speed: DoubleSuppli * */ override fun execute() { - shooter.setVelocity(speed.asDouble, speed.asDouble) + shooter.setVelocity(speed.asDouble * maxRpm, speed.asDouble * maxRpm) + if(speed.asDouble > 0.15) { + shooterIsRunning() + } else { + shooterIsNotRunning() + } } /** diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt index f9a60d4..bcd4bb2 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt @@ -331,14 +331,14 @@ class SwerveSubsystem : SubsystemBase { * */ override fun periodic() { -// if (LimelightHelpers.getTV("limelight-back")) swerveDrive.addVisionMeasurement( -// LimelightHelpers.getBotPose2d_wpiRed( -// "limelight-back" -// ), -// Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture( -// "limelight-back" -// )) / 1000.0 -// ) + if (LimelightHelpers.getTV("limelight-back")) swerveDrive.addVisionMeasurement( + LimelightHelpers.getBotPose2d_wpiRed( + "limelight-back" + ), + Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture( + "limelight-back" + )) / 1000.0 + ) Logger.recordOutput( "Limelight Pose", LimelightHelpers.getBotPose2d_wpiRed( @@ -347,9 +347,7 @@ class SwerveSubsystem : SubsystemBase { ) Logger.recordOutput("Pose", pose) // PathPlannerLogging.logCurrentPose(getPose()); - swerveDrive.updateOdometry() - pose } /** diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.kt b/src/main/java/frc/robot/subsystems/intake/Intake.kt index f0fba56..dfb2316 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.kt +++ b/src/main/java/frc/robot/subsystems/intake/Intake.kt @@ -11,6 +11,7 @@ import frc.robot.subsystems.SwerveSubsystem import frc.robot.util.Constants.IntakeConstants import org.littletonrobotics.junction.* import java.util.function.DoubleSupplier +import java.util.function.IntSupplier import kotlin.math.abs // Not doing the sim because I would like to retain what little sanity I have left @@ -146,5 +147,11 @@ class Intake(val io: IntakeIO) : SubsystemBase() { .andThen(Commands.waitSeconds(delay)) .andThen(sysIdRoutine.dynamic(SysIdRoutine.Direction.kReverse).withTimeout(dynamicTimeout)) } + + + } + + fun getColorSensorProximity() : DoubleSupplier { + return io::colorSensorProximity.get() } } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt b/src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt index 3a96afa..491a9a5 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIOInputsAutoLogged.kt @@ -12,6 +12,7 @@ import org.littletonrobotics.junction.inputs.LoggableInputs * */ class IntakeIOInputsAutoLogged : IntakeIOInputs(), LoggableInputs, Cloneable { + /** * */ diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt index e53345b..3165b05 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt @@ -5,8 +5,10 @@ import com.revrobotics.CANSparkBase.IdleMode import com.revrobotics.CANSparkLowLevel import com.revrobotics.CANSparkMax import com.revrobotics.ColorSensorV3 +import com.revrobotics.REVLibError import edu.wpi.first.math.MathUtil import edu.wpi.first.wpilibj.I2C +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard import edu.wpi.first.wpilibj.util.Color import frc.robot.subsystems.intake.IntakeIO.IntakeIOInputs import frc.robot.util.Constants.MotorConstants @@ -20,7 +22,10 @@ class IntakeIOSparkMax : IntakeIO { private val rightRollerMotor = CANSparkMax(MotorConstants.RIGHT_ROLLER_MOTOR, CANSparkLowLevel.MotorType.kBrushless) private val cerealizerMotor = CANSparkMax(MotorConstants.CEREALIZER_MOTOR, CANSparkLowLevel.MotorType.kBrushless) - private val colorSensor = ColorSensorV3(I2C.Port.kMXP) + private var intakeError: REVLibError? = null + private var leftRollerError: REVLibError? = null + private var rightRollerError: REVLibError? = null + private var cerealizerError: REVLibError? = null init { intakeMotor.setCANTimeout(250) @@ -90,6 +95,8 @@ class IntakeIOSparkMax : IntakeIO { inputs.cerealizerVelocityRpm = cerealizerMotor.encoder.velocity inputs.cerealizerAppliedVolts = cerealizerMotor.appliedOutput * cerealizerMotor.busVoltage inputs.cerealizerCurrentAmps = doubleArrayOf(cerealizerMotor.outputCurrent) + + SmartDashboard.putNumber("Color Sensor Proximity", Companion.colorSensor.proximity.toDouble()) } override fun set(intakePercent: Double, cerealizerPercent: Double) { @@ -110,6 +117,8 @@ class IntakeIOSparkMax : IntakeIO { cerealizerMotor.pidController.setReference(cerealizerRpm, CANSparkBase.ControlType.kSmartVelocity, 0) } + + override fun setIntakeVelocity(intakeRpm: Double) { intakeMotor.pidController.setReference(intakeRpm, CANSparkBase.ControlType.kSmartVelocity, 0) } @@ -137,24 +146,25 @@ class IntakeIOSparkMax : IntakeIO { override val colorSensorProximity: DoubleSupplier - get() = DoubleSupplier { colorSensor.proximity.toDouble() } + get() = DoubleSupplier { Companion.colorSensor.proximity.toDouble() } override val colorSensorRed: DoubleSupplier - get() = DoubleSupplier { colorSensor.red.toDouble() } + get() = DoubleSupplier { Companion.colorSensor.red.toDouble() } override val colorSensorGreen: DoubleSupplier - get() = DoubleSupplier { colorSensor.green.toDouble() } + get() = DoubleSupplier { Companion.colorSensor.green.toDouble() } override val colorSensorBlue: DoubleSupplier - get() = DoubleSupplier { colorSensor.blue.toDouble() } + get() = DoubleSupplier { Companion.colorSensor.blue.toDouble() } override val colorSensorIR: DoubleSupplier - get() = DoubleSupplier { colorSensor.ir.toDouble() } + get() = DoubleSupplier { Companion.colorSensor.ir.toDouble() } override val colorSensorColor: Supplier - get() = Supplier { colorSensor.color } + get() = Supplier { Companion.colorSensor.color } companion object { const val MAX_RPM: Double = 5700.0 + val colorSensor = ColorSensorV3(I2C.Port.kMXP) } } diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.kt b/src/main/java/frc/robot/subsystems/shooter/Shooter.kt index e9ccb73..3b95be7 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.kt +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.kt @@ -15,6 +15,8 @@ class Shooter(private val io: ShooterIO) : SubsystemBase() { private val inputs = ShooterIOInputsAutoLogged() private val feedforward = ShooterConstants.FF + var triggerIsBeingHeldDown: Boolean = false + init { defaultCommand = run { io.set(0.0, 0.0) } } diff --git a/vendordeps/yagsl.json b/vendordeps/yagsl.json deleted file mode 100644 index e0169c8..0000000 --- a/vendordeps/yagsl.json +++ /dev/null @@ -1,22 +0,0 @@ -{ - "fileName": "yagsl.json", - "name": "YAGSL", - "version": "2024.4.8.6", - "frcYear": "2024", - "uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400", - "mavenUrls": [ - "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/repos" - ], - "jsonUrl": "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json", - "javaDependencies": [ - { - "groupId": "swervelib", - "artifactId": "YAGSL-java", - "version": "2024.4.8.6" - } - ], - "jniDependencies": [ - ], - "cppDependencies": [ - ] -} From 1cb7f2cbd7ab436536562facce0d137eba3ca944 Mon Sep 17 00:00:00 2001 From: gaming <48131223+TheGamer1002@users.noreply.github.com> Date: Tue, 19 Mar 2024 11:19:21 -0400 Subject: [PATCH 09/13] calibrate more commmands --- src/main/java/frc/robot/RobotContainer.kt | 2 +- src/main/java/frc/robot/commands/HomeArmCommand.kt | 13 +++++++------ src/main/java/frc/robot/subsystems/intake/Intake.kt | 6 +++--- .../frc/robot/subsystems/intake/IntakeIOSparkMax.kt | 4 ++-- 4 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.kt b/src/main/java/frc/robot/RobotContainer.kt index ba32103..b16fe6f 100644 --- a/src/main/java/frc/robot/RobotContainer.kt +++ b/src/main/java/frc/robot/RobotContainer.kt @@ -93,7 +93,7 @@ class RobotContainer { armSysIdCommand = ArmSubsystem.generateSysIdCommand(armSubsystem.sysId, 2.0, 3.5, 1.5) moveArmCommand = MoveArmCommand { MathUtil.applyDeadband(shooterXbox.rightY, 0.1) } reverseIntakeCommand = ReverseIntakeCommand(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } - homeArmCommand = HomeArmCommand(armSubsystem) + homeArmCommand = HomeArmCommand() frostedFlakesCommand = FrostedFlakesCommand(intake) val invert = invert diff --git a/src/main/java/frc/robot/commands/HomeArmCommand.kt b/src/main/java/frc/robot/commands/HomeArmCommand.kt index 7a9d25e..ba58eed 100644 --- a/src/main/java/frc/robot/commands/HomeArmCommand.kt +++ b/src/main/java/frc/robot/commands/HomeArmCommand.kt @@ -3,14 +3,14 @@ package frc.robot.commands import edu.wpi.first.wpilibj2.command.Command import frc.robot.subsystems.ArmSubsystem -class HomeArmCommand(private val arm: ArmSubsystem) : Command() { - private val armSubsystem = arm +class HomeArmCommand() : Command() { + private val armSubsystem: ArmSubsystem = ArmSubsystem.instance private var hasHitLimit = false init { // each subsystem used by the command must be passed into the addRequirements() method - addRequirements(armSubsystem) + addRequirements(this.armSubsystem) } /** @@ -24,10 +24,11 @@ class HomeArmCommand(private val arm: ArmSubsystem) : Command() { * (That is, it is called repeatedly until [isFinished] returns true.) */ override fun execute() { - armSubsystem.moveArm(-0.5) - hasHitLimit = armSubsystem.hasHitLowerLimit + hasHitLimit = armSubsystem.hasHitLowerLimit || hasHitLimit + armSubsystem.moveArm(-0.375) } + /** * Returns whether this command has finished. Once a command finishes -- indicated by * this method returning true -- the scheduler will call its [end] method. @@ -42,7 +43,7 @@ class HomeArmCommand(private val arm: ArmSubsystem) : Command() { */ override fun isFinished(): Boolean { // TODO: Make this return true when this Command no longer needs to run execute() - return 37 < armSubsystem.angle && armSubsystem.angle < 43 + return hasHitLimit } /** diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.kt b/src/main/java/frc/robot/subsystems/intake/Intake.kt index dfb2316..7190cd3 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.kt +++ b/src/main/java/frc/robot/subsystems/intake/Intake.kt @@ -151,7 +151,7 @@ class Intake(val io: IntakeIO) : SubsystemBase() { } - fun getColorSensorProximity() : DoubleSupplier { - return io::colorSensorProximity.get() - } +// fun getColorSensorProximity() : DoubleSupplier { +// return io::colorSensorProximity.get() +// } } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt index 3165b05..6d27b2c 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt +++ b/src/main/java/frc/robot/subsystems/intake/IntakeIOSparkMax.kt @@ -39,8 +39,8 @@ class IntakeIOSparkMax : IntakeIO { cerealizerMotor.setIdleMode(IdleMode.kBrake) intakeMotor.inverted = true - leftRollerMotor.inverted = false - rightRollerMotor.inverted = true + leftRollerMotor.inverted = true + rightRollerMotor.inverted = false cerealizerMotor.inverted = false intakeMotor.pidController.setFeedbackDevice(intakeMotor.encoder) From 9cd2dceca222471ec79eab02893fa104df571cc1 Mon Sep 17 00:00:00 2001 From: gaming <48131223+TheGamer1002@users.noreply.github.com> Date: Tue, 19 Mar 2024 11:19:51 -0400 Subject: [PATCH 10/13] update submodule --- YAGSL | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/YAGSL b/YAGSL index b1bc574..0e3050e 160000 --- a/YAGSL +++ b/YAGSL @@ -1 +1 @@ -Subproject commit b1bc574fa246b0f9f70a604b86cd704366723b98 +Subproject commit 0e3050e0fb6b0e5b75f30fab29531801d932973f From f0fa052a969dc54bf5aa1cd5c318bffd65aa1357 Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Tue, 19 Mar 2024 21:30:39 -0400 Subject: [PATCH 11/13] WOOHOO!!! YAY!!! YIPPEE!!!!! --- YAGSL | 1 - .../controllerproperties.json | 0 .../{maxswerve => c}/modules/backleft.json | 4 +- .../{maxswerve => c}/modules/backright.json | 2 +- .../{maxswerve => c}/modules/frontleft.json | 2 +- .../{maxswerve => c}/modules/frontright.json | 2 +- .../modules/physicalproperties.json | 0 .../modules/pidfproperties.json | 0 .../deploy/{maxswerve => c}/swervedrive.json | 2 +- src/main/java/frc/robot/Robot.kt | 14 ++++ src/main/java/frc/robot/RobotContainer.kt | 67 +++++++++++++---- .../robot/commands/FrostedFlakesCommand.kt | 4 +- .../java/frc/robot/commands/HomeArmCommand.kt | 6 +- .../java/frc/robot/commands/IntakeCommand.kt | 5 ++ .../frc/robot/commands/MoveArmToAmpCommand.kt | 63 ++++++++++++++++ .../java/frc/robot/commands/ShootCommand.kt | 6 +- .../java/frc/robot/subsystems/ArmSubsystem.kt | 5 +- .../frc/robot/subsystems/SwerveSubsystem.kt | 74 ++++++++++++++----- .../frc/robot/subsystems/VisionSubsystem.kt | 6 +- .../frc/robot/subsystems/intake/Intake.kt | 23 +----- .../subsystems/shooter/ShooterIOSparkFlex.kt | 14 ++++ src/main/java/swervelib | 1 - vendordeps/yagsl.json | 22 ++++++ 23 files changed, 252 insertions(+), 71 deletions(-) delete mode 160000 YAGSL rename src/main/deploy/{maxswerve => c}/controllerproperties.json (100%) rename src/main/deploy/{maxswerve => c}/modules/backleft.json (88%) rename src/main/deploy/{maxswerve => c}/modules/backright.json (93%) rename src/main/deploy/{maxswerve => c}/modules/frontleft.json (93%) rename src/main/deploy/{maxswerve => c}/modules/frontright.json (93%) rename src/main/deploy/{maxswerve => c}/modules/physicalproperties.json (100%) rename src/main/deploy/{maxswerve => c}/modules/pidfproperties.json (100%) rename src/main/deploy/{maxswerve => c}/swervedrive.json (88%) create mode 100644 src/main/java/frc/robot/commands/MoveArmToAmpCommand.kt delete mode 120000 src/main/java/swervelib create mode 100644 vendordeps/yagsl.json diff --git a/YAGSL b/YAGSL deleted file mode 160000 index 0e3050e..0000000 --- a/YAGSL +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 0e3050e0fb6b0e5b75f30fab29531801d932973f diff --git a/src/main/deploy/maxswerve/controllerproperties.json b/src/main/deploy/c/controllerproperties.json similarity index 100% rename from src/main/deploy/maxswerve/controllerproperties.json rename to src/main/deploy/c/controllerproperties.json diff --git a/src/main/deploy/maxswerve/modules/backleft.json b/src/main/deploy/c/modules/backleft.json similarity index 88% rename from src/main/deploy/maxswerve/modules/backleft.json rename to src/main/deploy/c/modules/backleft.json index e9ca036..d528f79 100644 --- a/src/main/deploy/maxswerve/modules/backleft.json +++ b/src/main/deploy/c/modules/backleft.json @@ -12,12 +12,12 @@ "id": 0 }, "inverted": { - "drive": false, + "drive": true, "angle": false }, "absoluteEncoderInverted": true, "location": { - "x": -13, + "x": -9.25, "y": 13.25 } } diff --git a/src/main/deploy/maxswerve/modules/backright.json b/src/main/deploy/c/modules/backright.json similarity index 93% rename from src/main/deploy/maxswerve/modules/backright.json rename to src/main/deploy/c/modules/backright.json index 2b63dc5..d9f17d2 100644 --- a/src/main/deploy/maxswerve/modules/backright.json +++ b/src/main/deploy/c/modules/backright.json @@ -12,7 +12,7 @@ "id": 0 }, "inverted": { - "drive": false, + "drive": true, "angle": false }, "absoluteEncoderInverted": true, diff --git a/src/main/deploy/maxswerve/modules/frontleft.json b/src/main/deploy/c/modules/frontleft.json similarity index 93% rename from src/main/deploy/maxswerve/modules/frontleft.json rename to src/main/deploy/c/modules/frontleft.json index 04df04e..50af3ee 100644 --- a/src/main/deploy/maxswerve/modules/frontleft.json +++ b/src/main/deploy/c/modules/frontleft.json @@ -12,7 +12,7 @@ "id": 0 }, "inverted": { - "drive": false, + "drive": true, "angle": false }, "absoluteEncoderInverted": true, diff --git a/src/main/deploy/maxswerve/modules/frontright.json b/src/main/deploy/c/modules/frontright.json similarity index 93% rename from src/main/deploy/maxswerve/modules/frontright.json rename to src/main/deploy/c/modules/frontright.json index 81cbcf4..a0111f3 100644 --- a/src/main/deploy/maxswerve/modules/frontright.json +++ b/src/main/deploy/c/modules/frontright.json @@ -12,7 +12,7 @@ "id": 0 }, "inverted": { - "drive": false, + "drive": true, "angle": false }, "absoluteEncoderInverted": true, diff --git a/src/main/deploy/maxswerve/modules/physicalproperties.json b/src/main/deploy/c/modules/physicalproperties.json similarity index 100% rename from src/main/deploy/maxswerve/modules/physicalproperties.json rename to src/main/deploy/c/modules/physicalproperties.json diff --git a/src/main/deploy/maxswerve/modules/pidfproperties.json b/src/main/deploy/c/modules/pidfproperties.json similarity index 100% rename from src/main/deploy/maxswerve/modules/pidfproperties.json rename to src/main/deploy/c/modules/pidfproperties.json diff --git a/src/main/deploy/maxswerve/swervedrive.json b/src/main/deploy/c/swervedrive.json similarity index 88% rename from src/main/deploy/maxswerve/swervedrive.json rename to src/main/deploy/c/swervedrive.json index dce981d..da97274 100644 --- a/src/main/deploy/maxswerve/swervedrive.json +++ b/src/main/deploy/c/swervedrive.json @@ -4,7 +4,7 @@ "id": 0, "canbus": null }, - "invertedIMU": true, + "invertedIMU": false, "modules": [ "frontleft.json", "frontright.json", diff --git a/src/main/java/frc/robot/Robot.kt b/src/main/java/frc/robot/Robot.kt index dd5aecb..cb5049b 100644 --- a/src/main/java/frc/robot/Robot.kt +++ b/src/main/java/frc/robot/Robot.kt @@ -5,6 +5,7 @@ package frc.robot import com.pathplanner.lib.pathfinding.Pathfinding import edu.wpi.first.wpilibj.DataLogManager +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard import edu.wpi.first.wpilibj2.command.Command import edu.wpi.first.wpilibj2.command.CommandScheduler import frc.robot.util.Constants @@ -26,6 +27,9 @@ class Robot : LoggedRobot() { private var autonomousCommand: Command? = null private var robotContainer: RobotContainer? = null + init { + instance = this + } /** * @@ -88,6 +92,8 @@ class Robot : LoggedRobot() { // 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() + + robotContainer?.let { SmartDashboard.putBoolean("Note", it.hasNote) } } /** This function is called once each time the robot enters Disabled mode. */ @@ -106,6 +112,7 @@ class Robot : LoggedRobot() { if (autonomousCommand != null) { (autonomousCommand ?: return).schedule() } + } /** This function is called periodically during autonomous. */ @@ -122,6 +129,8 @@ class Robot : LoggedRobot() { if (autonomousCommand != null) { (autonomousCommand ?: return).cancel() } + robotContainer!!.setDriveMode() + robotContainer!!.setMotorBrake(true) } /** This function is called periodically during operator control. */ @@ -137,4 +146,9 @@ class Robot : LoggedRobot() { /** This function is called periodically during test mode. */ override fun testPeriodic() {} + + companion object { + lateinit var instance: Robot + private set + } } diff --git a/src/main/java/frc/robot/RobotContainer.kt b/src/main/java/frc/robot/RobotContainer.kt index b16fe6f..20900c6 100644 --- a/src/main/java/frc/robot/RobotContainer.kt +++ b/src/main/java/frc/robot/RobotContainer.kt @@ -7,12 +7,12 @@ import edu.wpi.first.math.MathUtil import edu.wpi.first.math.geometry.Pose2d import edu.wpi.first.math.geometry.Rotation2d import edu.wpi.first.math.geometry.Translation2d -import edu.wpi.first.wpilibj.DriverStation +import edu.wpi.first.wpilibj.* import edu.wpi.first.wpilibj.DriverStation.Alliance -import edu.wpi.first.wpilibj.RobotBase -import edu.wpi.first.wpilibj.XboxController +import edu.wpi.first.wpilibj.GenericHID.RumbleType import edu.wpi.first.wpilibj.XboxController.Button import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.CommandScheduler import edu.wpi.first.wpilibj2.command.Commands import edu.wpi.first.wpilibj2.command.InstantCommand import edu.wpi.first.wpilibj2.command.button.JoystickButton @@ -28,6 +28,7 @@ import frc.robot.subsystems.intake.IntakeIOSparkMax import frc.robot.subsystems.shooter.Shooter import frc.robot.subsystems.shooter.ShooterIOSparkFlex import frc.robot.util.Constants.OperatorConstants +import java.io.File /** * This class is where the bulk of the robot should be declared. Since Command-based is a "declarative" paradigm, very @@ -36,7 +37,7 @@ import frc.robot.util.Constants.OperatorConstants */ class RobotContainer { // The robot's subsystems and commands are defined here... - private val drivebase: SwerveSubsystem = SwerveSubsystem.instance + val drivebase = SwerveSubsystem(File(Filesystem.getDeployDirectory(), "c")) private val intake = Intake(IntakeIOSparkMax()) private val shooter = Shooter(ShooterIOSparkFlex()) private val armSubsystem: ArmSubsystem = ArmSubsystem.instance @@ -51,22 +52,23 @@ class RobotContainer { private val reverseIntakeCommand: Command private val homeArmCommand: Command private val frostedFlakesCommand: Command + private val moveArmToAmpCommand: Command + private val overrideShootCommand: Command + val driveBotOrientedAngularVelocity: Command private val absoluteFieldDrive: Command private var shooterRunning: Boolean = false - private var hasNote: Boolean = false + var hasNote: Boolean = false + + - /** - * - */ - private var driverXbox: XboxController = XboxController(0) /** * */ - private var shooterXbox: XboxController = XboxController(1) + /** * The container for the robot. Contains subsystems, OI devices, and commands. @@ -94,7 +96,10 @@ class RobotContainer { moveArmCommand = MoveArmCommand { MathUtil.applyDeadband(shooterXbox.rightY, 0.1) } reverseIntakeCommand = ReverseIntakeCommand(intake) { MathUtil.applyDeadband(shooterXbox.leftTriggerAxis, 0.1) } homeArmCommand = HomeArmCommand() - frostedFlakesCommand = FrostedFlakesCommand(intake) + frostedFlakesCommand = FrostedFlakesCommand(intake, false) + overrideShootCommand = FrostedFlakesCommand(intake, true) + + moveArmToAmpCommand = MoveArmToAmpCommand(armSubsystem) val invert = invert absoluteFieldDrive = AbsoluteFieldDrive(drivebase, @@ -136,7 +141,17 @@ class RobotContainer { ) * invert }, { -MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, - { driverXbox.getRawAxis(4) * invert }) + { driverXbox.rightX * 2 * invert }) + + + driveBotOrientedAngularVelocity = drivebase.botDriveCommand({ + MathUtil.applyDeadband( + driverXbox.leftY, + OperatorConstants.LEFT_Y_DEADBAND + ) * invert + }, + { MathUtil.applyDeadband(driverXbox.leftX, OperatorConstants.LEFT_X_DEADBAND) * invert }, + { driverXbox.rightX * 2.0 * invert }) val driveFieldOrientedDirectAngleSim = drivebase.simDriveCommand({ MathUtil.applyDeadband( @@ -190,7 +205,7 @@ class RobotContainer { JoystickButton(driverXbox, Button.kX.value).whileTrue(aimAtLimelightCommand) JoystickButton(driverXbox, Button.kB.value).whileTrue(driveToPoseCommand) JoystickButton(driverXbox, Button.kY.value).whileTrue(rotateCommand) - JoystickButton(driverXbox, Button.kLeftBumper.value).whileTrue(intakeCommand) + JoystickButton(driverXbox, Button.kLeftBumper.value).whileTrue(driveBotOrientedAngularVelocity) JoystickButton(driverXbox, Button.kY.value).whileTrue(aimAndPickUpNoteCommand) @@ -198,6 +213,9 @@ class RobotContainer { JoystickButton(shooterXbox, Button.kLeftBumper.value).whileTrue(Commands.either(frostedFlakesCommand, intakeCommand) { shooterRunning }) JoystickButton(shooterXbox, Button.kRightBumper.value).whileTrue(reverseIntakeCommand) JoystickButton(shooterXbox, Button.kA.value).onTrue(homeArmCommand) + JoystickButton(shooterXbox, Button.kB.value).whileTrue(overrideShootCommand) + JoystickButton(shooterXbox, Button.kY.value).onTrue(moveArmToAmpCommand) + JoystickButton(shooterXbox, Button.kX.value).onTrue( Commands.runOnce({ CommandScheduler.getInstance().cancel(homeArmCommand, moveArmToAmpCommand, moveArmCommand) })) @@ -230,4 +248,27 @@ class RobotContainer { fun setMotorBrake(brake: Boolean) { drivebase.setMotorBrake(brake) } + + companion object { + var driverXbox: XboxController = XboxController(0) + + /** + * + */ + var shooterXbox: XboxController = XboxController(1) + + + val rumbleShooterControllerTwiceNotifier = Notifier { + shooterXbox.setRumble(RumbleType.kBothRumble, 0.5) + Thread.sleep(125) + shooterXbox.setRumble(RumbleType.kBothRumble, 0.0) + // wait 0.25 seconds + Thread.sleep(250) + shooterXbox.setRumble(RumbleType.kBothRumble, 0.5) + Thread.sleep(125) + shooterXbox.setRumble(RumbleType.kBothRumble, 0.0) + + } + } + } \ No newline at end of file diff --git a/src/main/java/frc/robot/commands/FrostedFlakesCommand.kt b/src/main/java/frc/robot/commands/FrostedFlakesCommand.kt index 3617a71..649bc63 100644 --- a/src/main/java/frc/robot/commands/FrostedFlakesCommand.kt +++ b/src/main/java/frc/robot/commands/FrostedFlakesCommand.kt @@ -4,7 +4,7 @@ import edu.wpi.first.wpilibj2.command.Command import frc.robot.subsystems.intake.Intake import frc.robot.subsystems.intake.IntakeIOSparkMax -class FrostedFlakesCommand(private val intake: Intake) : Command() { +class FrostedFlakesCommand(private val intake: Intake, private val keepGoing: Boolean) : Command() { init { @@ -39,7 +39,7 @@ class FrostedFlakesCommand(private val intake: Intake) : Command() { */ override fun isFinished(): Boolean { // TODO: Make this return true when this Command no longer needs to run execute() - return IntakeIOSparkMax.colorSensor.proximity <= 150 + return IntakeIOSparkMax.colorSensor.proximity <= 150 && !keepGoing } /** diff --git a/src/main/java/frc/robot/commands/HomeArmCommand.kt b/src/main/java/frc/robot/commands/HomeArmCommand.kt index ba58eed..69780cc 100644 --- a/src/main/java/frc/robot/commands/HomeArmCommand.kt +++ b/src/main/java/frc/robot/commands/HomeArmCommand.kt @@ -24,7 +24,7 @@ class HomeArmCommand() : Command() { * (That is, it is called repeatedly until [isFinished] returns true.) */ override fun execute() { - hasHitLimit = armSubsystem.hasHitLowerLimit || hasHitLimit + hasHitLimit = armSubsystem.hasHitLowerLimit || hasHitLimit || armSubsystem.angle < 40 armSubsystem.moveArm(-0.375) } @@ -54,5 +54,7 @@ class HomeArmCommand() : Command() { * * @param interrupted whether the command was interrupted/canceled */ - override fun end(interrupted: Boolean) {} + override fun end(interrupted: Boolean) { + armSubsystem.moveArm(0.0) + } } diff --git a/src/main/java/frc/robot/commands/IntakeCommand.kt b/src/main/java/frc/robot/commands/IntakeCommand.kt index 374394d..60b240e 100644 --- a/src/main/java/frc/robot/commands/IntakeCommand.kt +++ b/src/main/java/frc/robot/commands/IntakeCommand.kt @@ -1,6 +1,9 @@ package frc.robot.commands +import edu.wpi.first.wpilibj.GenericHID +import edu.wpi.first.wpilibj.Notifier import edu.wpi.first.wpilibj2.command.Command +import frc.robot.RobotContainer import frc.robot.subsystems.intake.Intake import org.littletonrobotics.junction.Logger import java.util.function.DoubleSupplier @@ -43,5 +46,7 @@ class IntakeCommand(private val intake: Intake, private val speed: DoubleSupplie override fun end(interrupted: Boolean) { intake.set(0.0, 0.0) + RobotContainer.rumbleShooterControllerTwiceNotifier.startSingle(0.0) + } } diff --git a/src/main/java/frc/robot/commands/MoveArmToAmpCommand.kt b/src/main/java/frc/robot/commands/MoveArmToAmpCommand.kt new file mode 100644 index 0000000..ac46491 --- /dev/null +++ b/src/main/java/frc/robot/commands/MoveArmToAmpCommand.kt @@ -0,0 +1,63 @@ +package frc.robot.commands + +import edu.wpi.first.wpilibj2.command.Command +import frc.robot.subsystems.ArmSubsystem + +class MoveArmToAmpCommand(armSubsystem: ArmSubsystem) : Command() { + private val armSubsystem: ArmSubsystem + private var numTimesAtPos = 0 + + init { + // each subsystem used by the command must be passed into the addRequirements() method + this.armSubsystem = armSubsystem + addRequirements(this.armSubsystem) + } + + /** + * The initial subroutine of a command. Called once when the command is initially scheduled. + */ + override fun initialize() {} + + /** + * The main body of a command. Called repeatedly while the command is scheduled. + * (That is, it is called repeatedly until [isFinished] returns true.) + */ + override fun execute() { + armSubsystem.moveArmToAngle(208.067) + + if (armSubsystem.angle < 208.067 + 0.5 && armSubsystem.angle > 208.067 - 0.5) { + numTimesAtPos++ + } else { + numTimesAtPos = 0 + } + } + + /** + * Returns whether this command has finished. Once a command finishes -- indicated by + * this method returning true -- the scheduler will call its [end] method. + * + * Returning false will result in the command never ending automatically. It may still be + * cancelled manually or interrupted by another command. Hard coding this command to always + * return true will result in the command executing once and finishing immediately. It is + * recommended to use [InstantCommand][edu.wpi.first.wpilibj2.command.InstantCommand] + * for such an operation. + * + * @return whether this command has finished. + */ + override fun isFinished(): Boolean { + // TODO: Make this return true when this Command no longer needs to run execute() + return numTimesAtPos > 10 + } + + /** + * The action to take when the command ends. Called when either the command + * finishes normally -- that is, it is called when [isFinished] returns + * true -- or when it is interrupted/canceled. This is where you may want to + * wrap up loose ends, like shutting off a motor that was being used in the command. + * + * @param interrupted whether the command was interrupted/canceled + */ + override fun end(interrupted: Boolean) { + armSubsystem.moveArm(0.0) + } +} diff --git a/src/main/java/frc/robot/commands/ShootCommand.kt b/src/main/java/frc/robot/commands/ShootCommand.kt index 9f80bbb..b5cd94c 100644 --- a/src/main/java/frc/robot/commands/ShootCommand.kt +++ b/src/main/java/frc/robot/commands/ShootCommand.kt @@ -9,7 +9,7 @@ import java.util.function.DoubleSupplier */ class ShootCommand(private val shooter: Shooter, private val speed: DoubleSupplier, private val shooterIsRunning: () -> Unit, private val shooterIsNotRunning: () -> Unit) : Command() { - val maxRpm = 5700.0 + val maxRpm = 3500.0 init { // each subsystem used by the command must be passed into the // addRequirements() method (which takes a vararg of Subsystem) @@ -26,8 +26,8 @@ class ShootCommand(private val shooter: Shooter, private val speed: DoubleSuppli * */ override fun execute() { - shooter.setVelocity(speed.asDouble * maxRpm, speed.asDouble * maxRpm) - if(speed.asDouble > 0.15) { + shooter.setVelocity(Math.pow(speed.asDouble, 3.00) * maxRpm, Math.pow(speed.asDouble, 3.00) * maxRpm) + if(speed.asDouble > 0.05) { shooterIsRunning() } else { shooterIsNotRunning() diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt index 8d6601f..cca228d 100644 --- a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt @@ -134,6 +134,9 @@ class ArmSubsystem private constructor() : SubsystemBase() { pidController.setD(0.016) pidController.setFF(0.001) + leftMotor.encoder.setPositionConversionFactor((1 / (5 * 4 * 3 * 4)) * 360.0) + leftMotor.encoder.position = encoder.position + setpoint = encoder.position @@ -168,7 +171,7 @@ class ArmSubsystem private constructor() : SubsystemBase() { // If the forward limit switch is pressed, we're at 243 degrees if (forwardLimitSwitch.isPressed) { - encoder.setZeroOffset(242.88780212402344) + encoder.setZeroOffset(228.65) } // If the reverse limit switch is pressed, we're at 40 degrees if (reverseLimitSwitch.isPressed) { diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt index bcd4bb2..a800bea 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.kt @@ -17,8 +17,10 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds import edu.wpi.first.math.kinematics.SwerveDriveKinematics import edu.wpi.first.math.trajectory.Trajectory import edu.wpi.first.math.util.Units -import edu.wpi.first.wpilibj.* +import edu.wpi.first.wpilibj.DriverStation import edu.wpi.first.wpilibj.DriverStation.Alliance +import edu.wpi.first.wpilibj.Filesystem +import edu.wpi.first.wpilibj.Timer import edu.wpi.first.wpilibj2.command.Command import edu.wpi.first.wpilibj2.command.SubsystemBase import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine @@ -28,14 +30,17 @@ import org.littletonrobotics.junction.Logger import swervelib.SwerveController import swervelib.SwerveDrive import swervelib.SwerveDriveTest +import swervelib.math.SwerveMath import swervelib.parser.SwerveControllerConfiguration import swervelib.parser.SwerveDriveConfiguration import swervelib.parser.SwerveParser import swervelib.telemetry.SwerveDriveTelemetry +import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity import java.io.File import java.util.function.DoubleSupplier import kotlin.math.pow + /** * */ @@ -56,7 +61,7 @@ class SwerveSubsystem : SubsystemBase { /** * Maximum speed of the robot in meters per second, used to limit acceleration. */ - private var maximumSpeed: Double = Units.feetToMeters(12.5) + private var maximumSpeed: Double = Units.feetToMeters(120.5) /** * Initialize [SwerveDrive] with the directory provided. @@ -64,8 +69,27 @@ class SwerveSubsystem : SubsystemBase { * @param directory Directory of swerve drive config files. */ constructor(directory: File?) { + + + // Angle conversion factor is 360 / (GEAR RATIO * ENCODER RESOLUTION) + // In this case the gear ratio is 12.8 motor revolutions per wheel rotation. + // The encoder resolution per motor revolution is 1 per motor revolution. + val angleConversionFactor = SwerveMath.calculateDegreesPerSteeringRotation(12.8) + + + // Motor conversion factor is (PI * WHEEL DIAMETER IN METERS) / (GEAR RATIO * ENCODER RESOLUTION). + // In this case the wheel diameter is 4 inches, which must be converted to meters to get meters/second. + // The gear ratio is 6.75 motor revolutions per wheel rotation. + // The encoder resolution per motor revolution is 1 per motor revolution. + val driveConversionFactor = SwerveMath.calculateMetersPerRotation(Units.inchesToMeters(4.0), 6.75) + println("\"conversionFactor\": {") + println("\t\"angle\": $angleConversionFactor,") + println("\t\"drive\": $driveConversionFactor") + println("}") + + // Configure the Telemetry before creating the SwerveDrive to avoid unnecessary objects being created. - SwerveDriveTelemetry.verbosity = SwerveDriveTelemetry.TelemetryVerbosity.HIGH + SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH try { swerveDrive = SwerveParser(directory).createSwerveDrive(maximumSpeed) // Alternative method if you don't want to supply the conversion factor via JSON files. @@ -77,7 +101,9 @@ class SwerveSubsystem : SubsystemBase { swerveDrive.setCosineCompensator(!SwerveDriveTelemetry.isSimulation) // Disables cosine compensation for simulations since it causes discrepancies not seen in real life. setupPathPlanner() - val navx = swerveDrive.swerveDriveConfiguration.imu.imu as AHRS + + swerveController.setMaximumAngularVelocity(Math.PI) + } /** @@ -93,7 +119,7 @@ class SwerveSubsystem : SubsystemBase { /** * Setup AutoBuilder for PathPlanner. */ - private fun setupPathPlanner() { + fun setupPathPlanner() { AutoBuilder.configureHolonomic( { this.pose }, // Robot pose supplier { initialHolonomicPose: Pose2d? -> this.resetOdometry(initialHolonomicPose) }, // Method to reset odometry (will be called if your auto has a starting pose) @@ -265,15 +291,14 @@ class SwerveSubsystem : SubsystemBase { Translation2d( translationX.asDouble.pow(3.0) * swerveDrive.maximumVelocity, translationY.asDouble.pow(3.0) * swerveDrive.maximumVelocity - ), angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, true, false + ), + angularRotationX.asDouble.pow(3.0) * swerveDrive.maximumAngularVelocity, + true, + false ) } } - - /** - * - */ - fun driveCommandNonRel( + fun botDriveCommand( translationX: DoubleSupplier, translationY: DoubleSupplier, angularRotationX: DoubleSupplier, @@ -284,7 +309,10 @@ class SwerveSubsystem : SubsystemBase { Translation2d( translationX.asDouble.pow(3.0) * swerveDrive.maximumVelocity, translationY.asDouble.pow(3.0) * swerveDrive.maximumVelocity - ), angularRotationX.asDouble * swerveDrive.maximumAngularVelocity, false, false + ), + angularRotationX.asDouble.pow(3.0) * swerveDrive.maximumAngularVelocity, + false, + false ) } } @@ -332,7 +360,7 @@ class SwerveSubsystem : SubsystemBase { */ override fun periodic() { if (LimelightHelpers.getTV("limelight-back")) swerveDrive.addVisionMeasurement( - LimelightHelpers.getBotPose2d_wpiRed( + LimelightHelpers.getBotPose2d( "limelight-back" ), Timer.getFPGATimestamp() - (LimelightHelpers.getLatency_Pipeline("limelight-back") + LimelightHelpers.getLatency_Capture( @@ -341,13 +369,15 @@ class SwerveSubsystem : SubsystemBase { ) Logger.recordOutput( "Limelight Pose", - LimelightHelpers.getBotPose2d_wpiRed( + LimelightHelpers.getBotPose2d( "limelight-back" ), ) Logger.recordOutput("Pose", pose) // PathPlannerLogging.logCurrentPose(getPose()); + swerveDrive.updateOdometry() + } /** @@ -374,7 +404,7 @@ class SwerveSubsystem : SubsystemBase { * * @param initialHolonomicPose The pose to set the odometry to */ - private fun resetOdometry(initialHolonomicPose: Pose2d?) { + fun resetOdometry(initialHolonomicPose: Pose2d?) { swerveDrive.resetOdometry(initialHolonomicPose) } @@ -394,7 +424,7 @@ class SwerveSubsystem : SubsystemBase { * * @param chassisSpeeds Chassis Speeds to set. */ - private fun setChassisSpeeds(chassisSpeeds: ChassisSpeeds?) { + fun setChassisSpeeds(chassisSpeeds: ChassisSpeeds?) { swerveDrive.setChassisSpeeds(chassisSpeeds) } @@ -537,10 +567,16 @@ class SwerveSubsystem : SubsystemBase { get() = swerveDrive.pitch - companion object { /** - * + * Add a fake vision reading for testing purposes. */ - val instance: SwerveSubsystem = SwerveSubsystem(File(Filesystem.getDeployDirectory(), "maxswerve")) + fun addFakeVisionReading() { + swerveDrive.addVisionMeasurement(Pose2d(3.0, 3.0, Rotation2d.fromDegrees(65.0)), Timer.getFPGATimestamp()) + } + + companion object { + fun maximumVelocity(): Double { + return Units.feetToMeters(12.5) + } } } diff --git a/src/main/java/frc/robot/subsystems/VisionSubsystem.kt b/src/main/java/frc/robot/subsystems/VisionSubsystem.kt index 7a928ad..1a7db63 100644 --- a/src/main/java/frc/robot/subsystems/VisionSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/VisionSubsystem.kt @@ -39,7 +39,7 @@ private constructor() : SubsystemBase() { var targetingAngularVelocity = LimelightHelpers.getTX("limelight-front") * kP // convert to radians per second for our drive method - targetingAngularVelocity *= SwerveSubsystem.instance.swerveDrive.maximumAngularVelocity + targetingAngularVelocity *= 1 //invert since tx is positive when the target is to the right of the crosshair targetingAngularVelocity *= -1.0 @@ -63,7 +63,7 @@ private constructor() : SubsystemBase() { var targetingAngularVelocity = LimelightHelpers.getTX("limelight-back") * kP // convert to radians per second for our drive method - targetingAngularVelocity *= SwerveSubsystem.instance.swerveDrive.maximumAngularVelocity + targetingAngularVelocity *= 1 //invert since tx is positive when the target is to the right of the crosshair targetingAngularVelocity *= 1.0 @@ -79,7 +79,7 @@ private constructor() : SubsystemBase() { fun limelightRangeProportional(): Double { val kP = .1 var targetingForwardSpeed = (LimelightHelpers.getTY("limelight-front") + 28.1) * kP - targetingForwardSpeed *= SwerveSubsystem.instance.swerveDrive.maximumVelocity + targetingForwardSpeed *= 1 targetingForwardSpeed *= -1.0 return targetingForwardSpeed } diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.kt b/src/main/java/frc/robot/subsystems/intake/Intake.kt index 7190cd3..33334c9 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.kt +++ b/src/main/java/frc/robot/subsystems/intake/Intake.kt @@ -7,6 +7,8 @@ import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog import edu.wpi.first.wpilibj2.command.* import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Mechanism +import frc.robot.Robot +import frc.robot.RobotContainer import frc.robot.subsystems.SwerveSubsystem import frc.robot.util.Constants.IntakeConstants import org.littletonrobotics.junction.* @@ -26,26 +28,7 @@ class Intake(val io: IntakeIO) : SubsystemBase() { } /** Returns a command that intakes a note. */ - fun intakeCommandSpeedMatch(): Command { - return runEnd({ - // get swerve velocity in x - val speed = Units.metersToInches( - abs( - SwerveSubsystem.Companion.instance.robotVelocity.vxMetersPerSecond - ) - ) // "grr I HATE metric!" - every American ever - // if the robot is moving, we'll want to match the speed of the robot, - // so we first calculate the number of rotations per second we need to intake - // luckily we already have the circumference from the Constants file - val intakeRps = speed / IntakeConstants.CIRCUMFERENCE - // ...convert to RPM... - val intakeRpm = intakeRps * 60 - // ...and set the intake and cerealizer to that speed - io.setVelocity(-intakeRpm, -intakeRpm) - }, { - io.set(0.0, 0.0) - }) - } + /** Returns a command that intakes a note. Now with speed-agnostic output. */ fun intakeCommand(): Command { diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt index a188020..2de84fb 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkFlex.kt @@ -56,6 +56,20 @@ class ShooterIOSparkFlex : ShooterIO { upperPID.setFF(0.0002) upperPID.setI(0.0) upperPID.setD(0.0) + + for (pid in arrayOf(lowerPID, upperPID)) { + pid.setSmartMotionMaxVelocity(6000.0, 0) + pid.setSmartMotionMinOutputVelocity(0.0, 0) + pid.setSmartMotionMaxAccel(2500.0, 0) + pid.setSmartMotionAllowedClosedLoopError(0.0, 0) + } + + + + upperMotor.inverted = true + + lowerMotor.burnFlash() + upperMotor.burnFlash() } override fun updateInputs(inputs: ShooterIOInputs) { diff --git a/src/main/java/swervelib b/src/main/java/swervelib deleted file mode 120000 index 964cc4c..0000000 --- a/src/main/java/swervelib +++ /dev/null @@ -1 +0,0 @@ -../../../YAGSL/swervelib \ No newline at end of file diff --git a/vendordeps/yagsl.json b/vendordeps/yagsl.json new file mode 100644 index 0000000..e0169c8 --- /dev/null +++ b/vendordeps/yagsl.json @@ -0,0 +1,22 @@ +{ + "fileName": "yagsl.json", + "name": "YAGSL", + "version": "2024.4.8.6", + "frcYear": "2024", + "uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400", + "mavenUrls": [ + "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/repos" + ], + "jsonUrl": "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json", + "javaDependencies": [ + { + "groupId": "swervelib", + "artifactId": "YAGSL-java", + "version": "2024.4.8.6" + } + ], + "jniDependencies": [ + ], + "cppDependencies": [ + ] +} From 7a85facefda1384015667cbd92d8cce316356264 Mon Sep 17 00:00:00 2001 From: TheGamer1002 <48131223+TheGamer1002@users.noreply.github.com> Date: Thu, 21 Mar 2024 09:05:56 -0400 Subject: [PATCH 12/13] everything --- .pathplanner/settings.json | 4 +- logs/FRC_20240319_075956.wpilog | Bin 0 -> 4964738 bytes logs/Log_24-03-19_03-59-44.wpilog | Bin 0 -> 2959915 bytes .../pathplanner/autos/Shoot from Middle.auto | 17 ++- .../pathplanner/paths/Go To Note 4.path | 34 ++++-- .../pathplanner/paths/Retrieve 1st Note.path | 74 +++++++++++++ .../pathplanner/paths/Retrieve 4th Note.path | 102 ++++++++++++++++++ .../pathplanner/paths/Retrieve 5th Note.path | 102 ++++++++++++++++++ .../pathplanner/paths/Start near Bottom.path | 68 ++++++++++++ ...ample Path.path => Start near Middle.path} | 32 ++++-- .../pathplanner/paths/Start near Top.path | 74 +++++++++++++ src/main/java/frc/robot/RobotContainer.kt | 2 +- .../robot/commands/ReverseIntakeCommand.kt | 7 +- .../frc/robot/commands/ShootAfterCommand.kt | 51 +++++++++ 14 files changed, 543 insertions(+), 24 deletions(-) create mode 100644 logs/FRC_20240319_075956.wpilog create mode 100644 logs/Log_24-03-19_03-59-44.wpilog create mode 100644 src/main/deploy/pathplanner/paths/Retrieve 1st Note.path create mode 100644 src/main/deploy/pathplanner/paths/Retrieve 4th Note.path create mode 100644 src/main/deploy/pathplanner/paths/Retrieve 5th Note.path create mode 100644 src/main/deploy/pathplanner/paths/Start near Bottom.path rename src/main/deploy/pathplanner/paths/{Example Path.path => Start near Middle.path} (56%) create mode 100644 src/main/deploy/pathplanner/paths/Start near Top.path create mode 100644 src/main/java/frc/robot/commands/ShootAfterCommand.kt diff --git a/.pathplanner/settings.json b/.pathplanner/settings.json index 2aaab01..2af994c 100644 --- a/.pathplanner/settings.json +++ b/.pathplanner/settings.json @@ -1,6 +1,6 @@ { - "robotWidth": 0.9, - "robotLength": 0.9, + "robotWidth": 0.93, + "robotLength": 0.91, "holonomicMode": true, "pathFolders": [], "autoFolders": [], diff --git a/logs/FRC_20240319_075956.wpilog b/logs/FRC_20240319_075956.wpilog new file mode 100644 index 0000000000000000000000000000000000000000..c9a2280afa8094e6ba9d9823726e463f0f5e64f5 GIT binary patch literal 4964738 zcmdR%2Y3`!_x~3}x$@dp5et^37li_3z!M zUoTG$4}N@}b5C1coA(VcH(XelF)mzq4E76)3bOOY$w9-r;Gmk=Z-9S&2PY-;$(|e@ zmYtWCKP91cVNpg=abZHAVZPM7j4?UktlBteOn!b&I3w>|>|Wk*QbGQta6wUaxUgZ; z=$*)g?`YFgWV z-sc%YXC~1UP)cU!%)M}}gC>PDv&UvwFxnsfwlq}hKMIGB8NoG0L6tJWN;^m=2misz4~z>77>s0%>GJ<$ZqaA&PiH?4XFubB%kNz{ zFr1Z=larm1ml=*RvmaOE(H6C9_&j~-#hBVP|<66V4ddaKjr<}o|Et?$~J{l3yZ?JgR^t@Cu18qp;Hl(fIj)- zLK%6eehYBAv0O92RS`Zls%TVkA!4W<9O=z7d0ned|KE@n#a*Z3{ z!RHw?7r#z{ld})yDE7MSlw%gwHz_%2XbOFvp`9BTPhB`T=MYZ91qJy9g;XC&V|U5O zBdHub!)G)xTvC09IQNu{f;_Y)v7dd&rl!VI4`)79c(Re{Vm@`J#aIX<97(y8Ol zW`iR*ImP7=v56~}omuN@oEbm9`tIIY?%wG&?r2H5Y~VvUh(dM<_i<#hvyXb9r9oVL zp3zH})ZxP40#2&QW2t$W`B~wD!he;~&Z)5)UVNTmpW_#$QiH=ei#@lUd(78M>NwTf z#k<*`$J6jIj^fO6BWf5gzF34;QMqGM}&3DL6fTd=1>ahVI@u zH5xCiQv=E6$3Zm8INUYFkpml<1eRdCZ3ZhVJS6lVs!_%58CVs(%VZbihM{f0e? z^Eb!&4;`eqGGEhLPvGSE@ilYzn!9_AYb;$!nQzD{97L7Up|2p0tk>e06)WpVfP9{@ zeYV%(acBZuRg>}ZGA0jiH7J}{m|t*7`;q@D1GcO&7`}X-k>l};dddgM>j%1wJtLl1 zYvT4gy`~oA!`aGRbv)-Ev9qBWImJA<%*roD*Og*_xOs{5%~iWOIdQDV*RsY_yD9lb zF2NsL;V(xhGWL#As}tt$t`i+ApC{{;M;m!s!!5b4COHR92^UNb`+62&V&-2ZX6qUs zz!Umtf8rPAor4Sqq8-MblnKX}#~L}!+NG@@YviFJ5!EY)Qx|8=GCB)B+T#3F`VZ$L z?)qiqZSc|#9*!hzan&+yYCQlK`0=%M_u9F8t!u1)tWgal-!C{Q@d&RYj=CoCxSfwR z(s=+Sqvf7Pp7wBgkVH(&4(DJV?_Z1{+t+9h7e3G6m+`9uJRM|kXFbK9DLd3&yr&U= zx?L8=khTA4(M%_Os5eGNIL7i~ap>@Vy z#dJE__lM}jwCjIrH}-UflLq)#O}UU@4iDvL73YL`%o&T&&ZBGBZalEr?CW3LT+!`) z&u2A{yY(Kj81~@jg#}03!VOJpHRigk1e4V+$~S zkrN(UG}1RPV~Q_jOksXbaZwl(*E|?F1|L51_Q7vb;go+?bo6<0Mu3ullw*$k67t67 z#OXiDTrB<{+H=%m_#X?pAXfj}V8o~Y0uy%hQ)jR!AJhf@FFaEHDOnSWF)^0)FVmrm z$%@MSQu-Mp{tppuVnDOAd1F8iZ5kB8mnHEF(tN~ zccHmQ`?=^55EUw_QL4##Zk*$C*3Hb;&L%wzN`@oK>eV>YC9NQP-1z@VQA;+@=xfMb z07`*>svBdthWN``ikUALP}7r~u%oA5hz{;>VXTOWIwV9xVhlp z)p|Y5+xkMLtOxbPMNo1a;f4IKid#>!PG3siHc%=qgBr7gU&@$_%!&W2CLq;p(N{2W zCnycxsc&+`R}g=$Ofx&!{cOpV6Ze36#pwQD_7P^t|xQafcnJh|6gRuJ|;oyFX{ve!T+KABufAPC{Kn=M|~ZW zyMp@SI+F44&_%;$h5uQm>}$H{E4idEs2{H4Amh_Qo<~T?<=%de{Ng-bop9ux;(jLN zxH~Bsv+!d<{o(E)gKq0?%J^_Nr%!$+-!YDPjL|I~Hh<|fnl^13hd+C1$9o%j${T&FeJCr`*Fo7kh`B*&SZaIt&^T@# zyj~2C2br38GN`R+dW_E~EX*$C%o=muc=72U+VH~Pfj_uQuoc!z@OPS8K6n6ZJ@T)v z2Kxqmo#ab0eVBYTs2kxouZiu9p|JT)qdI(Khv7`O2@SZI=?|gY z5lq?t;UllV6qIVpga&r~^Fo|uhtLzF+4iRpMaY+Kx*x}%n|8(Zuj0t3g?eY=$Ye7w z%GUOHJ~AAJEy=VOs-Ov(WYbm1vS)j;ojz58~`oU~gR9A?vCDoj%DBYZ^$ZraT z7Ek2QO;fg16H%0Iu2JMSp9-zZ<)79rv%?w59W~LCQd(hk{gU+ z_9zOPy+ZcN0w?iRwC>^&e@|#^k^FHLyc}`~U9M4p9 zjG}aNoFcy&EmXA*pYxk#Lf>v+YI_Qw<>*aJcL+83gz3DxZ0q_NDAo9dY)QRM=%O#! zcE1o`i{Jb#RQx5MCHqu9%WYpXEf#uyE0d|mw#sinLE{&)dEzRemnnxNnX83(0yf#) zB4o?^t;&{a?ohTgbEmSUn|p;mp>qb!eL`*2aKEAybE^=aCC%KfC}{3hlw{skjv`HxEHKr4r@sTs%VCpCI_)?~bPb2mrJo5olccEo#naYGVuV;EeXx~Rn zn}p8znCa-2e3lNMG7S_O@Hx|Tq1??(bA+z{ifNtD6I+=65~|q7)Z#oo=cnH?4G`M< zJyVI$sXsE!7HYeb=^dfaZl)bV**`PYJD<;a&96*dg&x_%6c&2pccxo~HvY-9Q0SMx zm}<7-v%LK17o1;&-g}&Bu+aBUGF>ZF`x&NJgc?1|v_+`f^Gy9)^Eoe>%d|*n$~>ms zLU+8(bXEc%Id?u&KnKk$56g+9LwzRQlB#;&wlcW9_MdSPDWME-;LBiy4j=`T}xsU1Tf8v#mJ(uEB zwAS;$6K3aSWM&o@WMsxTFz^gI6K5TTGtx581J8;x7T~dn{`rOBm@ju=W1M(2PFmgN zW?;-TIZP3W{k&ap-i(8swzS5)0P>pY zf7ix_OF&oMZ|?n?ZP#2pumYdEU+C$aO-a5k=20PT2$Id?LYzNR%o9TGm;IdN>tUW$ zN2Z#m)RAcp@sR=Zv^p}~Jfn^bI>bkY%p7&3XH@MijXh&<$p=}E+9N+FzW`aE)?@kl z7vz^@=f*tD9Al1x6Z_-yOvndi0-d`NQ4b67Bx`|vNFyOVACD+xXHION(7m{*C_j&v zOBEiC4gNkoLla4wDCF zWalId&Cj97C}OK~!uy@p#kf9v2AqzCLuXunP^Udo`gX@7b3=-UMWMd>KTu=#FV(>$l;eZdEqb-4#ywNVRY7t?-8c)(F(J= z!C^KWI?Lap6h=GTpO^dh8(K)$%z6087UpDoAQTfrVfdSXk2(`WQT}xPNt~P*e+HUB zD#!9q9b}*h1@Jl%UTNXhKXPsLDmx^klw=o5c_po5bMiBaj!f%B(VBG+yyoDeF~qh* zLL9NpvHl*1zg+mMwwUzK#~p~C*)*9qrkEbVN*F{H)6}$#;+&$`YNXugJT!4G{N};0 zb2IFqX=;n-;DU_2LR7=4^q3Ie3yG=B6}6R2I_)~e~0fP_@x&8kiPLKB9^hm_T+5iqLXUC zomyq=OV5~`;mgS$Q;<ijFGKbX%FgW>o}8T-_GK1?aqlY&%SPQbit>GJTDS3K z6^CiJnv=E0I_uio8heTn@)&Y-hlJr{@=K`ljp3>HVv0Z7?n_UD!^!xp(=j|~twe42 zKqNrSjrZi}ifBSZc$@-{)%FXc>IUhi;DPus#tU&)gHsOhem=aHzo2&CChMTB=IOdy`{k-1U~{A(X1Dj_^Jeo?}Sfw(-;;Q*8y=6aJ>bU$y;+ z=oURSH;my^Ugp$6MfsCr%uUm5Zp!Wtf0x5wwKZ0>Kc}B0JqRkIv38a&w<5!EIz6_a zwu_?`m@e){OoF>B;I7(+ROjEp;f&lko+W*4u7TaS8cz68t$l8z~)%w-gsMr zQu06kw(Zlqb$Fp0^6WM6e`RdpZ4*zGbfr@z-3o`1BMC57NitxJF~3HvtBn7`)eN{g z>^QCCzZj>@*q@-MqY}9EX*j*=Nc43tKw}loLi)z2?eEiob^dgmv*WvVPICbu!M>Q$Yl>pwMkWy5XffpOZ`r4MO zo!qh#-mZbSY6qXu-efEYk+F4+uGyb{G~CTz3y;^rV+@sC8y+UbQ^{Q`wNBROaC#k_ z#?W#k##0KfvvD209S&z6EEWGbOp0p;V`g+@$L@j8>*150lln*Fth1{vjy+_GGLFI7 z_0gU)kNT#u=Z1rY_n&G9V?|94|2ej-bVIb;v3240#v>7I=ZWGMd}FldF%97Prh^HN zE;dd}-6nxDa7=^Hn-1_=0IxU4<~1>PuQx|~&71+Rx4`RRYeC6kR1IQABRkeA=@u$F zHBdp^41c%6U$xozpP32kS}=IYv1x1Y!B}n$+*%H=5#{{%OHKqb_TeROX^Wpb)_>G}jZyS4oxINnI=%w&_2fS80=!=eZ z&v+Z?J8VOexeCtij7?&PIJ)O|N<%s76S%tz?v9}M5%2rC?urg)#x}UT`(Q40=CQSS z3f};Wu}^omtzEKyg138Oi)Y(-dII;@1k9@WZDY^9a9C~GICymybJ@6;!g@L!(GM0G z{|A2mi`{B-Y1E7*?pRI0>`&}7d;g_-d6;Qx*QQ;2pC|KFc)SlDVgne} zffUksAu;X&!^0Brj4U{v4X1}4+D3OR zW6N8!qx067TsVCMPGcxQ?P71v9*OpveK)*58e4qZ#U0;ACBB*S;PkQBq$b8uS3G8u zb1B?Cek92mJv53fIUkP>Y{qIhed0)*cF!m(3KvX`tA2VS+Udn#!ReE5+6e#tF$j$A zoD9Yb2V-nTpR}#o=-=VyDY&S%b%}P9f=T?m{M`Ivo}r9kmi;NG2|f9{#-69)%vt9i zH6`-TCX|PlsaPvCF2)r-Pe;e{(x&kH4E!F!Me+Q5Jx6n>bizM^w0Lf zbvbrp2ynZ2dM)LWpxI~s(AZM}f7NEAe{@IfP4gjzVJx)Eig}es1&K{RuI72y@hXpu z3*h`sI6rKc$xbHs8#^}k^?h$fM|ezcIDIR&2zQ9Rjd?5DYd8~L--g#V`1gWJqM#veGuN?f#+%$Ek*YXo!+o>ZzT4N^-gr8 zM=yl)6>xs|#+BE#$2C>9!q$ruSHoE)oK@RPtR_Fv(EMMlb*Ut+zn4yUz37hd7)EA) z3HK{w3$!!rh&|9NqXRu*H=Mr<=hfC(2TSF+mtVgtIeWy>+Z%gU!E3cSTQ>>=2lb(6 z7GnM0g;h?{df})lhNQI%OXHm(sG{gj{kCaa^W1Yt+RXZJzZ&kVoq~yuuJfHFBsbPa z6;?+lYIYLbz6ZB46kX>jnAmgFdj~l04d-iObMB0KVt2kK+WDA~aQ;4=AGV9*^fuzE zIo_x2RRcYYX>j)e+*O;t|LmAkrz%{4uZ}8+aW&8f(K08@gx?S0H-=IxllyUXSUByyUx(-g8;a|0lz1s+OFV4=%ioF?JcVIJ^nAE|a z)V_^v23NuVdiai^EIH3~#h#tlN2hc4W;ovvn{#LWB6jB+qMZB9d;93Vna4gS`=QY0 zwRj*g*?cNwpOgJeh>pf{vYVAH&3x(D@CW22Lx^FC@}jV7Lt zuv>i(V0?Z)=Kd3gOhS2bUQjb|QZ5azk9?@|5xFFH^n;abk?X$NM8d!OuLgW)sgR@LBC( ztv9~#X<|5`N4Nk>kMX9b_|yE8D7U#pw8n^j@Bqr$xQI`&OS$47mCYcX>16$LZ29fe zDBqsU=J56zJRM51C`aOEQ?H<>ycH`px1UA39h(TZpTljnsoPq<@GHUQssY95eBoQ2 z^7D?vC*+TE#JS+Zy>#mHMhLHzN8gkS>`sZZGu7Fd<}0L2Y%${2H-Blqs++Iqc2GGUA^RrsF zZtd%br)~gOgF4;u;^RJjeC>L2iSp6clDU6O)PMAq&{g&wbJB4CD@P@xiW-1G zet|F?vWntjf~qOLNBqBtPP_0(xZDhvhsrYhONqVrlaf0r=9g$~j&__`1jk<<%yCr7 z_*Z%L%V@XbX29)Na2sQl%!|qg#a2wd+V7gGq+`K!wXT`;+P0hmcuup|Dvwh9+ixq(X-+7 zM>uVOfB)#^>9Y1Oy4XJ+x{Ez#A+BKu{5P%c8V*PVx{Ua0w;ipJ0Q^k9^oA0%d`0wx zzt9Cv>f+DN>srwhUye)LiOZ_CkKvRoF310>soxouDvv~GjL{$AB6i^-4qvrMMJ}p0c_t!1^ zhZMdFx~7}&$ve5M9Iq63E9!bZqZ;4}f58d< zuZl?Cq+EoaR(3~R&aXHu#(>3F7yNoAoF8Hg<{6cO%b~{VkkR2LHSY1uZ&A_lj2;M= zd*Jer#hmM!_>1|TXrCD);dAf7WJY!G{zaR!H_B;}+0mHpb$Irz$Mji>`BjKt9_Kf6 z6WC_o=QU5L-U7VOE7{B!vTyKOAjEImN;M0WEzK-awsf;t*@EU(W%HWi)=jX{<#>D> ziFlW&kf<5%UYvFD+Zczp0L3yq#^HMgef7lsZ-3Fv_f^!1ONqLV-m<3Q$CcfDWkh$L znlIh`TgyQ&cI_V3FIsazKkC4K(}C<9-^TWroPOB7p~TB-#=ulA-}_t$pA>)h)1;RLYrtmg=wv61Iln+e%@*5*Q-ZBk83WlJ*& z%9d{0DqGOBQ??{?S|R)E@G(62&C)BFZ04&FI=6~5-!dVa`IZaW%=eD6rI{7VmToGQ zE$9$`&TC$q-UJ)xIA1Oi^^)lanGf{CfJNtA^L<4(OtygTIK9@;6IyNR<|`%QnU@vI zDgS^z$+Y=rCXt*2tHEw9cS-*CfAN3c9MU8=5^tj11gbl3EK5NX2U_NPv0(gdRo&3S zD80yAAh(6_o4|b>8JoBI2o3m@^VT3Co41At*}OGe+0x9#%9d^}RkolRrEE#2u!8;N ze$II-p^C}ot&T!TUvu8-E@bmo48)((CZudZ(^uKN=H-=5ut}5(iMTkP zxq)&Mi0-(bUTZhyCQzsAQ&1lvZSUtvTon%AhYj zNags+Z*;8Z3SGaMW4%xK8X0n7h9n#GNWeb{#%H}m2PH&3Mi8XdF_`DzbU5HW% z+3@v4vy(nUIb3_d+(-KPwyFwXSUGrbZ_|Cw~s_S{LHaC7GK>vhCAt z9P1}0GTB(aAT+l*$9jp7jrCF?o3EECTbg-C+0xA_Web`rW%HU^*hjxzvWo_g>0<52-#StDqETfC|kN2plm@iSlN=y@z1fpQ-9!CKe$N8 z`U#0-B3fWk{u54*$iL#}ex0Eet-c~lRIdy(hY)-7PTW7;#le*UVoMH{S zuHMGgzYY40Vhy7H%-+&3Db}D454f=gseBERn;Sn+P6nx*-10*m-9(|bKXP;DSbSU)IaWBsJErI|U( zmTq2FwxC&{Y)NK*K%)CI$NHSXI@V2vn&ok+l z_E8<{JfXB}IM!DP*;rpGWMh4`vZa}8lr7!dplm^Nqq2ET;ls_aIkCnr-6UKwc|FA% zBt2Ko*Py%6GH&~0BgGnY`?YSYLGHMqf^1iG>u~9-y>UCLl1SCiAXSH4{f3V9%|aW0 z=U6`=WMe&B$j169WlJ;9DjV{(vIWh2WlJ(EzGi>F{K>H{*r{VZO=!Xc9P8_ZY^-Mr z*;wDKY-#2eWyAMvC|l6np=@4r^Y&)goLFP`zW>q>;#opAd5hT3l&?WkmOOlB!l#_C zLC>#sV+~UI8YHRmE#+j8^k#0ST4U3H=t)Lr9n2OX@82BV--K**{}8g#t#urKj%{hi z2(c~Qc$E$Bi&wTJGa!*a*Q&;sG(LOmLMB^7&k_2#Gi-l}-UlX#?EmyWQ^QN+; zn|G8gXjUkj*UZ15IW{M{*p;3f_n|=&7mhB7X9}`Drko5~->|@`H9)F{1|b_`z>8i< zB^{}1XpqXuO)g^BPG3W)_fd#MvS}q`W8GTF#=4ENrJ1(MmTnT2Eoj;+Tax)9!v4ZX zbF5e2pkw{M(9JD4*6W3AtTzbRSZ`FeG_y(B(#^-p7IcU|=QV4uZ;s80HFjmh_d4Zd zP%#gGKc$=ulJUx$6l>6rliXN?Bvr1W))2%M`x75htU;>Q0J(YIZ`M4eW4&HzMs1Gu z=R!8tn}uwww<=qj`9|5&&30uAnje)d$$Y<>{XKXr$9l|09qVyIOOiR(`9e0qL&{T|zdV_Xyc|KBR2;_8VnOH%}{D(9BUb%#uxHf5)H9@qDnD$;R_h zp@e*n=Nus$&u4{fJYP_@G&5J((#U$BTzl3bkFZi0` z36i=Mu`VMTbcv1U93s`90Li!!tzi|}RBj!0yN>QSp%!&Hx@T$*NB7ycbaY=7%Dy0fF$c> ziZeOZS9zIiPQF%X{(~Irn}lqvZx*t#zE#=Mj3pcE+mtPc?@D72Z1bASPil#cgMk@d z>`LqO8s%irTfa2NvOjL)K`E^)Fmc zy_s`_Y^=`}vaxQcY-y&EvZb3Q$`&+DmCbABUD^_x6Km}9@ZmVFH9$0DynQ<7YY=Da zRGv)-tx7F&`febJC(nO^cmiYtdU=)PflrVBkgq}REQjB`F`aET*2{(7_i?P(3fWk1 z5VEoUOxe=RW@Sq^-zZzqe5Y&}g*?Xowm0NhU-SZ#jrAy@**9>kvxRJ|CkWYC=PFy8 z$y2s;bD6RQ9kTiQrRQ2=b7GBMswGkvaDM_s5wIzJ#3$)=5H`bsB zP_H9lsP6`P9CJ+@9{Yk~4O00U{7O%`AON5%+b5qUz27W>p_3&SYIUc%Of1?3?UoqF+w)hVP#7*W0fu4WGh?HAsg%W zes77*i8Xe4P}dlFx5R*?7UtFv#B;b$add~LGufPcsZjsL z9Nn;xjqX?>8{KSWOEVLcE#2fQThJjJ-PwWjusPAit{cG;1ETws^)_N&zm!Ps@2;Wf zf?iK3c4`ffsx?3jxVquK21xSmeN-pU8LOlFlF-yv9NpK2Y;>0h+33EdY-whhvZb4q z$`&-Mlnvjacr*KZbi@W4Pk(to6Gt$~d?!TWQ77+HwiM%efRD7%JywW6mu8Mrwsdov zvIWf<%H}m)?l}*e6J6{|e_}J`T~JScpU@u^T@bH;AAuUWjOgN0H@YB|cR?~+v5V>n zkVKyElYpc=+)1(ic|N=5cqW;@glg^O@4D--fNj5B)AB+rN$4zOW8H=6i(AIL;m3FN zc2l-=(~~JOtpB!m@C})%%H}tXzu|M*=$v<#`mb_h22%YqkUIxaMMp|J@1`hiu6aH=vr+m+ zh@+HZb_sD@(##%3LGz~~zxk{KpT%n5DrB|q5whBAcH|?Of~Jll+)cW9#!NuO=g^r&C!lscU5`` z*<=QU@85!C41~Cpk*&vgS35|hJ4pIHJof}rZ7N7cM2}M>dOxfqF+j*hA}nMhk)tSR zrYZ89mGA3Fyf0)U@wt$V#8yQ?^MfL{5&F2MMuiK>3>Ok%66?iAY`=<5VG2bDhirQ6#31yK3d5pUq^|1rb1Tx zD?(QL>xzQrEk$1Q?AfibIoh!+V}y029VD$2*O;Im@r@CezRGjypcS>II3)n2aslX3 zx@Ec+wMG@4MRLJx(mv_}c4kX|SjcM65wh9~6$Q=Ziu|TkuGZdG$ZGcsS?ygF1x<<~ zuep0-D{PK->^@1u{sPQIm5{AJuWZD9-%=tz%)@OlXwg7dJJJ68WA5kBtE{5Wxiy2| zr{?%64 zoJe3-7Ikt70LjV@zIz3d`zyHHQbwOU?-4f=AXNfDQiuFV?IuWaND;*aB(2Q7lqYW7 zpyP6zkd4c|LN+cBC<>Z~75U9Ob?8YRr#w^%*|=;HvT@n0C}_4R3Yi~-Jf7Jd5tmfc z8k-Xr>`DoEpKAuwx)Ch}c%AD=*yMgHuWc~d0CO)EFZ2Tu}a8BVxy3a#OI3egs>v7891~xHb*;l>4Cu! zw{o5U<adVK-W}bBLt8Pp1(ksE}`vVWzv1NVSF_DGzs2B+Q#S5+?}RNSq>MBXNeJpgCKS z-`w)6j>KI;HWE(>*+|S)g!|}&Gm}B=9APV23e#~7|(vhl;1ab9JbO+^-376`)6bP}t6mx};jZ2v#v>l54=9F1F z67_^^B+eGHkvLaT&@@!!HEV83z~)2(yHYdo%oj-NI-Vf_srhoy_r-1`K#~h0R8~Mz zRxmqRNurb6g;ORF+~H8<1<25?GhoYcA27}S*gft-f!6ko1+%H?kejNvZ;PD z=!IUJr`3G{ce2aKw!=HkDFGmN9`|5#Db ze5uH97EaUJUlp?2D}=1}w-p7=az$PfnA!%LqaC|^%k4Lwfdt8{EzkCXXtmTi*YK6JPX zeT8f!h6~w9j8ud*ZHf?yciLccBk_*CPV|gR$R?4%sHc?3?K6}SWxcRJ67RH8_tD)W zaW4{)aL(DE@&rhg{svogBw7gBNF)l`Nca^6O;<&Jv-UK4?93?-n}lp6z7?{O*rh0F z_9*h2%T8^J&4~ndW#uhL0wl9{+#-M^zi^8Hy5&zd5+F5p0?D|MTLh45DM4;M;Wy0^ z*|jYlt%PhOItbZFbX9~gkRr?>W$Q?^60(u#A!H*FQWP{p6nRZiW?O7dB(N)e2Hb-# zA)DNv#v@{-L{d*6hm;ZBnSQxbGl0}c3M8ciXEjC9xc11hSIfCAy#ge1~JVpT3-{xuuNiLs7JpquL zL#l{WKRNqszG|E2FB7ubrwdu_Ws0yaR*~N%5765C2wCk}LRR}EML`o$YVA{mtoAE~ ztoExFVJ(0nzq$Egt^FP$tG!CdYTu+NXuekDHT527ht1KBU3X5PglvD&4gR*Q9pv88 zEF)XzGFLlD<#~|IKq9|X(vi|j7*CM^sb@bnF4mFQB4i`6OUOpzH$_3SPZ4IKw(CfY z7qXFv2-!&7q$p_aQsg!M@7iH=B7t4E=U+lL871=yc97JA+$REE^1d4hkSYNnenH6R ze8<7H@f`<{st1?UrkBz=qow6SHWI6aY$Vny3Yw1;`OPyI@LBBm=oKLwiB&>25*ri+ z&1OYjlhHX5n-dA_%Dn=N4NJ%-ePNzU2T9w=MFv$Geybfly~`ae22443N1a{TxT97<<#`6UrwRQ_MVU`;SkUI-dLFbh55oXq_ zh}=Gd-`uoZYo8_L)CEFT`(28H=59rPGkcHL{>UNj&|(I z^NqOIQ$jX*CKUO)l*nBpUq*D_XRdaTTiz?kCQ(9-Sw*Dk!GWiCBxkk+3=^{2FBP)d zGZkS4m?GR^4DeZO+rLoAYOfNq+BYZ)n$Hz^O>SyOY>sy9%E*TMgCMCDxdecu{o^(O zbnE#Mrv!l17y%@+s3-wd-?GGsmn#UDk)&CZ)eWsAr{;-hM{;Z;)c}0=etl!)bo1-1OT=8w@IRTLLjQ3KW z2My%vjmH6?-&VNVL8|5hUB*)jJT?TWnhzu`C9f-)@VAacfsl>FG$9*_h@zmmT9Mzp zl-P*`*b?xDkd4GoLN*fh+Vhc2LDN8y*X&E^gw2TrcBRhZUJyuDt@0QFBvInK#~|Nn zGn^6ta!Ysxom1B0Aoo-fxw)W3Be6)xMq-Jgpm|e~-!z?}Bat9v zBhgdHMk1sLy-GzPlP_df8+0h`gw2TycGavANS+S*g>ndpUt_bEXN^EZ!){zaZmnNI zM@j^FwE;-w5Re*0K6k&4%gaJGF0TvOxKt>@{QyONGkCR*%Sa)POBeH$kS95uj1kye zp%&K{RQP(BmzW~Mw*Aq`7cj4h?INO(sSw*pBHUYgw-YueO4yZJpL-A>Y3;cm36du- zdF%u_bwKvqJlcHA%lDSyqvq~bBUqJ3%8oxQOGhc`;M~Oll39Le# zptbK2vf4cp**3icYd=;fLKHA3Fh#B=3YmIhyN<|fvd4GE=4i*R^r2T!p8+KE4BU2r zWKQ5c>N$e0>*s0*x#Ne$WK(an0ZF^b{Ya3?1t66R_Fbd3*S?m?YJXrclTG(0g{<~@ zLLZJ`?XNOLJ|YU33bB1k6f*CM?F%CGmlkx!=4i*R`{o_=mlkxUm%r?IinW8J6-B#( z{?dZZ_de)q2Z_F$X#4<@nOSZ(L2gR>P03oVuT;qD`|21!U5M59y^z)SGgG9vjP?B~ zwrNBGQ?oXIu9PTb>Ilss!mLp(KQ>1ncHMizm^G^9m)Q}d3Raxe@=L9c`DDx*)$%X= z-qi;Z4YNoeNaohKOuIHN(;(GDI;SDKwmG?pkX5^Sh*rBv$g15cw0#b%-6ixBQNZkF zitHf@nOZ~XERjEnyym@uer%3f?DCSK5cdQ?@>CJ`06}usgnNLXo&GYX6oXVx03<7O zIPZeo)WmZI1N|~HG?(s^beN>ob`i2_(;m}m`w3aK!(C$@q`+E~x%YS1m~8U6A|s8Qcq*?N?*G8<%K(cM4g3 zzwFZbYV2mR`i^6Yc=ocs)5LZRQNWxlw*L@?OiQ5?iM-~oAN|-Ieb|-$3*YYmjpZLs zO^~c$;C>yb!FpF8NcHDI@-7TcO_1u%fFx~aQ)3wQl*qg`s`d2fkqX$`ao)g0+Ra{eD4~h z$|gw7RW5y6t6eT+)%N{Fs~sw2)s7N6FOSuZV~QjY1x&6`B2ma(F4U38YYH|dVRO`C zSFLgeN&U&~3P|b~?umo$EO*s{RJ{w59w*PqfmGjns3o zDp%+-BCol%_yTN>TI{O1bddB8`JNj{jjKTOM!0H0YWx5a?W`80@-9fFZN?p1?N}kJ z_Oaz!?Q=p_?JGhh;k?prRu3C^PsUTUOg&M4ij+C^$mujMZo3*}SLRR0Cb-U1o*t|PW$m)BIDKfmy zUsTh+Ei{q{`sBzlL?N?QY+)j-tMqok=IFz&Tbp8CrMHXB7IN7HslGnw?>(+QkjlFt z>1$v#SVd=1x%JWnc4l*Ho{-hIHbd+CRLJVv!W8+j4eR?sXg5*7?2;pYB?_56V%tN6 z`vIf6U~}|gSMHVb8bOdeal~r`K{Ct1Z)*UZ*y~!SY=YeWdLi>#z0RoMhdT<)a2yXIZ3cD;~Q z`}AL0?K~l?b}>_A_?4{oO`#D)0kcAm%peMxH9}cLST+7<7i^AN?7A!euxk9zE^;4_ z`+Oj`_ls5Ie|EX}D_1Q@^%C48(XL?CxMRb;kShM%{&xkwb4FKkZFBN!A**(1AGX<& zI!ef@9nTa=c#_pl5?gzsfSD}RnJ8qg5W0ZKYbK?4#pbBRu6pkXNZxqHIT<9E$!QCk z)%H3kCxcW?1d>q?=VXvdTaY{RCiHADeZU+8+GkZB-v zGZCHv*xD7FqaC|y91fB``)(@5Ah~bBy+hFaDpxy5joe(~d<{}54N^07r`5WUT-$to zmXK9@RwuUEeBD^csy$!m_WFNQ3)EidZlZum61tBlWO@iaNaQuk+FyvxQHx!b(jb|2 z=TZ!EM?GcqxvlkQI{6x;@-;~2ZFp1;QYj5m{fUHuT5U%mtMYG_cK39ed@ zD4Ioc5FlCMhCES8q|z3o<{)Ow)@pAQvT9eX)oMQwvT8pO%AUY#w+Q7C17llmkC*Y)0iTQ zK4X1XiR}%dfSD;&K@>8xgx)6dnr^Rk!{+G2uDt&YZE6YGB=Q)qloGk?4$Fu}KkDiO zsahB$eH0#}gH*i)Qggp&Zq#be6S8X0J1&_n%jVsVLRM`zrpWO}c{-yO?#onuB2mB$ z5!)$5Av208`BWmWdF0q+Y;;$otDVFYIfE!*O6171h(czD&^bh2v-F8%Y|zSTvFkoF zSwc3cg*i1rYE%dM;wD!uNR>^H>Yk1NEp~0yb`!E{7yrsOtM+XntM)yi zd0koUW~TC&i2`ODQ}QCBkl87=#YA57?oY|spq15PSIxhGr0)5d@-E1I=BJElldBds zRZ>B2kGhhMR3+6VZe>P#Q^>Pbn)f0NePjxRO8tukbDmb&+CIuZ*ilOlR>JL0m<`}n32F3 z&#`eU1CpHl1dZ`#jM8dn3OQ+eyH@*_kX5^ysrdiQ+0Esk0sU+-CrdTIT8lsgeqk@gL8Pf<=eP1(0 z7Tn1Cc8hH>QNZjG+v`Lj^S9WR5aBuY^Sfhn^kLV1BW4NNwrYK?g{;1Qr}v-> zvAK1akkvPesr=OCtZ$sqX+!~&BXkB)$P~)w>Jxd*$Mt$(bM#?XMib?v4+d zxo@_tq$5?o0Hn(1kgK%X5kgk&1+QqeDMD6lFQ(*^wzJy4OyyppfVr3{atcw%j25a# zK2tDnoK|T0qnUbF&3YZs|%I6S;%*#xXXNkNfRHG+0N3F9< zE4)j{CcPj$;af`N&VrW_<$vR<1*!WoAosm0cq-)_KE2JY_X=4>llp5#g+f+QF;n?j zby-mfQ}WqF0W(#OJckJP4aLUfHCOcOiOo@j-4E&I7yegB5lHHnk4X_oO4Sm|t)K@w z-s0p|keezMWaDKl%Ri*j2y*-LezPb?>w8Ve>ig*Cl^sq=iOJe+A1Nd_Pg)3+8>0h+U-JrB(d5ZOvy|Evy-Wu2_rB$@=rR_ zYbJc(6Pu$JyHcAzM`}TGr*I{y1xZifWl{^e<^xwPNJ?CUdU7CH*&X@}&6pxgUUQE>6`P|7yRypU8Bzq2 zcd_A~ekqakFMx{y_Lh0w#rtmsOnWTt?LFqJc5BrHeHrX#TmcwH(sM-g_V z)n-K?sTnxef!z9~j6T=k4ObCJ)rugu-Nd@zbv8;+>o-Gw()xxAS$#J)PNNI4dGID7 ztM3+}M%S~xTbUwE0W*uKoGD~(mm?d~kzVs%qcm)eKI~pkU-j1TSxPaGBY-4_49VRIO2z!p>|Nn;cio6k&osrgEl` zxlN9IoQ}ktYC#${M;~_Gu_)$L3)1At1-xw-bE*Ytl17{(L2WK_^?}@azJiXFb)0A$ zF^gJ|Cb^u`?}1yjzK4XYzKhGXz7axJ-=#vQy~z4TF-4dHW;9bdQ^<^wBTuIzz2?KE zY1kZn*j4!xBt0u0KY*k~c#%pR==&#KeIU^=o=O}@=Cinu0#ZFPklUN_o7+CsYVQ=X zYImH_i!RIN)?GqY?N3a}ufN4=e`YFY3Yfp-$T!FqGM*FZERm%|UUTUQy|9Ve5+b?7 z!TA#;EjrhcpsRjy^?^jgEYb&Z^JgUypAi2cH9;!3R-MN-n_J%#vikOpV4KzVhmh5` zkE#5^4Xp2PrsQr!0pl4-pDSkynVL+VWU}EN?TB93L|-A1Dvcm_2Dy}M^5&hFC^djX86AVRQ6h*In^hLN<5(ODU1eJuN1EpbfXV`ar711Ie7#a?%Il)8jv+ zCPA$>6YC&5+ch!Pa-UZ1_DOM0w(vfazRuQSP*}YzXT-&^xCS=u4 z?8P>lck_g-+RK@b&`zR|S zg!kfn8NlY~!>+WHD2*j#Q{SorlIuikSVp$@DqVdbxBTI~I9~>2cJd2KP4{!CiSU-3 zF9U81i*?|h-sIZm-Is){+UMG_&F0;CLRRf7Ov%snVYLgy_B>I*EM$r>h0Lo=zK{k2g?nk5#Bq@yl@CLd>2u`Tp~x_O%yVh%8^X?PNk~e*c^S>l{-xs?Us+8a zdCm3N>DU~7*p<6%7?qchO?qpXtuG}K?YQ$=M)Z7tS06|;+)L#TB;^m~wu;D2Tfgac zoz|BsWc8&l()vO|R$o7+51*8w; zzKOAvNZz0I8tDVw`jD#+Bx#HJmkP4E>lG`B`1JS>YC&!*>NmsJX|#@8FMGn-p0gdBZ?qx1<`eeW}sC$3|C>zI<;69vqA zp$AK!zQKkDr!C6zD%d*3L%@GwI0*yd5n-vPs0?c_=eN7j@aHL3Yh7e;IT}e z8AJhdyx6WH3Yk-c%80zivolB={h-Fdt~}i z`U{;*gg10v*asWABz@SG^;GDC;tib__K`U)ZXZE1+E_z56m(~kyPftQB(>2^)P8`Z zCkuU*M3T~@DK$ZI&bz2Q_8g(r28FEJ<8RSw>k3)5X9``@h}E9U6uFitU>Y%%Uq^&_ zaiN(+Ui0`(eXu!dvFpxgmyk`KLcp4-QX;tb`ElBltK=O`nyvMDQjuf?A z`?yEmO==V7XtkY$tlF6$Yqd8ES+%p6lE3Q6YVQ!+*F*tx7gIS?$lN1GZXp}qHnOP? zHb*UX)mvsj(s$+71SIzamXcb~M-{GGkX!yL$mZTXs3LOnHNJggkJi^#$m(0tB19Kr z^X^+hR^M`_@=58eZzWUYGNOQ4B~(C!r!3@ig+zElsCfvRqYt~X_JV6ykgW5>N(H=m zy?IF97r}SoK!2ThkCS&nZcS7{N4jrh!V^NxL#nqkD2<)jvN=@9>YFk}>$_aY>MLa` z|7;}do52+MoG4(fVoLskC}ge{8Z>4f z$CZ^td_w$(9NFtmt!R*tRrJO(t*BhcDtc3B(q*jZZKeoQz$_EnWn>GP6->!YUekD4 z2%Dn_yDG&%?z5()bflW419g4QO)-$9*d(fLK+?ivOkGK&${)z>*W%5dUuv}(LRRgb zx_#-gZ2tU9$f~V%D%m34u3@#uGI>&n&~`8-cP9#&lZAQ^c}?3>`eJj`V%JTF60)i9 zbOWin6*TyFS1m~0;Q`5am+_hnZ9{6dWoI^j_7k%Do*JX|JuhVSz08#S?7ggSAyfHt zL;>@L(DOtg^QIg*m&j{IWc0=6=)(C2a};4$ z>JaqFO2{VlAkSui)HfJ_?z-D5nnOpb8U^IO-=~sne0uzc))3^5MDUFzRa))ILRM}2 zzqQ&fLRM`Lq4$=u+TKj%Yls3S#FYF25$>r9eMp46#QXYUbJSv2^sOMZAXzz%_29Tm zysxiYHp_?>f9<9pNOCf_e;`%Pb-&|O~A33x6v!{^N*D%C3TmD)IS$%DolG8tA zeI3QthX~K_FhxQ{A(JfBm&j}Kg8i^L`mn3|HX!*j4%P>9M-XN7xm(-)*J&R>ZW>jP zO5w*jfX&Gc-owoJ&XoqoSod$o{Nd!x|it*rJort&X|(AqO4e@zrJ_X%ww z@|sou?T5`#i(OH~sR@$Sp4Eax1MY5>(dTwVT(uyTcR})mEZ?tlZQQp3N!^M$Nxyk` zp;r5pkX1YPTdj71kX5^cDU$m;t9@H2p9oJ_%8{25h0JQ90wS+@YFj^Sj#}(W9fH1T z3E4#7ca(QQGKxk^Sw^&SwN+a|b##9^z0Ixn3Ry*`b!MB*tqp{%qLxg_ z=7d_*6HjD{)FDD{Why_82v3`d?F1rx=U~VF*c?UJmAg3n8~{kZCl#xp@tuPm`@3(( z!gmgK?BC(+`<&bgQay2y%#iSN03elHLF(z}mj-FIi-oM(qHDFzI-sZoq11 zF_k|;6fpP5k&hFF%p+oZg2-zcUfmy?qZYez-<#79Bx_Q5^)1Nl>6Fpux=*xfD~ROD zXpB&*h(zCP%8@@jq80rlWED+Xs})TZvWg;1$>(%nMKi_bBMO+Cg&Got%$;&%BO=r` zAN0rOD8jCL2f2i7l43tn`hn!096xmgx_PmiejwG`2FcrSu=25rJ|{NJLi)|79a`V# zLRQ~Z4F}ML*!+3DkkvPfDf!U=>$_WQj}ryVgG`Yph_J#|j(m#9Yp(STz~<<~uKO%X z3EAYzejt4y_c@0$qQ`3A@8nOAJ7TCHn|wPqdI?xF+?7vnOWdzQR#EvRt!Sl?RkW5V z(ryGR`c!Nkhyvz&rsPgUSmDl8o^Kq`GE}5Qg-Yi1eO=dU zt>wBukKgB?-|_gI&*y%uNB4SK@4feVUDukYx9a_?A%C9j}yHAcWH= zvoApi`VftM%$%f|9qu4{Me9h=nkT%z3VD*V$e86wy5m2!8XA$jhHGjylOOZBt}V%H zxQ*1Rpc;BArLGdf7)YsjjZoG-sFZIlgi{tfHA4s*5H+O=#4)=1D3baJ)Nn)e5y-UR zAntxwAAwA*(c>`vF`oy^NM2u$E3LjfDU>SG@<&wPNYd9rX*W(OwMr=KCNgcc5Z#GJ3XE{{^i1jsAF0sb>bhFk2 zq6QFGL)9xF)-U5l(WE!5qGw57(Uf1TqL)ZsQBkS5?p0M(V%m>FY4@H|YJ(8YPB85! zp@h3~Q!|912vOdyu8Ke$nQoH04#XV?>J?DW&!Zv`Yla`C_Kq}06n(sFbNPCo&%Pje zMbDh0X}%o2K=O)SBXwM)ismcjI|-%TyGq5|gs`%}w5~!4cjH;j5rQH_xx%W7KwN|0 zD2hO)_6FT^#G@gffq141^?XU5WUb#;^npxW_f>1FZ!O8|TRqh3+d%UA{!q&Q`L*iX zW|%x#{7We9c2=rUbEWFrgS53!!aXp!IYQ8fsPPzxYBdjnxT8YzAZSX?>noRUF=K5I z@8&>1vLtDy_XOg|M$cw7de*8B(Ju)Qhvyly%)n zqlB;H+1bsa(MTq)(UdnlfMKXFp0#AczZUvcJ z;6WR&|65XB0s?({>ZWoq(lF5rRHM%-l|dtb(xA@vx@l(_yU>eu@mIf&#HwQXw^-A3|? z?o>+c-%1tTt&~4dDDCbi)f2*QZ9aLhP{Lhw^JNG@5u)6Or6mr;6)N=@$c#QgowARG z_5s9t7k$M_`A*g^V zm5MWjaJSzJmmvg2h;lv>a~?TK<6OG>2xNQ&8ZtU60&z}2eFS1Zd4ec~YzO7eRPW6FI9z3C*{+Q2$jY(eLpypQJD3aIrq*8v>Fx59r zDfO)o_R8_ewL)1}R4T3$O1S5nUXBp-AsSn*oTQo4@}PJQwIFF9G#VFbeUPa&K-?9g zts2PmDv!L?>N}p~^}Rjb>idx7^(|9M-9AzEeWO(DA%qjvq&tMN?iZzePoad{F!pkU zpbyb_8){C{I1>IzS~XCds9byNuFd{Q^}vF%(nW@AbEZLez5um zlf1rBN~y13QGHJ+XpXAjJRZ3mI zP}PoBD&8oRc8`;87RtJ3l=5wb67J|zu0RNC5sfp*IZ0!#Q?(#7MgU!O@c2+;f;i8x zM)ZN`Kg=g5UH=wV(O{BSbjbr&Q7e*HbfZ%Kqpws^N2V~C zN3AhIm%Qc`mCKW+Mgehl8FQ+Yl4kB`c zo%EBpSE^AI!V05Ou|f#DQ~2cTLgC5ulDwCR_z@mul6pb)PV=6+B~VQ z5axpTWIZ9=y{wd1O1S1-TOb6rh;po^t8*ZFbGfJm@vWjbxls`6)GDe4u@31cy=GAC zUsnpnw4{4?kkz-C3uI%DTst@;3?L3`<1| zgrE=6crqGiSSng@PwlUw55!rKB}0sc6BKa~&hp zSZ393L-K0ZCtAv%<@4?zB(HYcT_vqpcDAamt(58`ly-Y4|guK(Gq#e2ecX~|rm{g+5OYjn)f`t?44 zHY9mPzh7$=ZPQxGE2>4R*+LcVrIgxQDD4hVDsC&3b@iFHy->ofySgPpP=u(t8yv*- z9Ib6YtRvqSMW9;eJP}GG$dpD9$En(*25~J!`=8mKR$nuc*LUPptM4R|*LS*7{-O4& zFRfG@D3o>=^T{DXS=WMTLxu3}vdJwGf<8p!F5#S{@r}mnF_5{{6m;0os1Ib?cM$Kc zSO05lGWFf+mr`6YvI1R1(OEyx#a~8!AXEN8W`zo5T8p`RwUQt6`SWd(*EjG2P4gx0 zF_PC;u2g(_i0XSmDPJy>b}#eEDMDHII@6{K;f-tQRtP~KqGp8=#4(WeSU~3HQc#Cu zCxrY7GX4W`Hbz@}kn!K=H(7lvNnYQa5msM`RZaR6NS=lrBc3;5Y}_} zWKsxc93N?g5cDC+9*d4)L0sKYeIRpRCuqoBQ6DJo=dY0ORxl2A5P~8^xdNbyKSvU+?qaR$D1~Mg31u@_BGD$txPElscqR6^$d+7fQP) z`Q%|jSvQ$!hYKa#;WSpZe2)(_}lcCoP;vLFp|4Nc( z`Y4ff&8>D*t8aIb*Vm+A^_@fV`YuvREn2SnS}5f|5K6mi`Q%4JS=Uyn__0vJeU!fv zA?QQY)FB|Q`)VEpagIgn5YTUJyuNbz7M7#I(nkSt_lAxUKyi#vDQRX5)M%_#+l1uR z9N7aAodkCe}dv! zl!AP2-xs4dLEI0mV_1+GZ3D@|5s}SUCWp^~9T+2eQGAG0p0PSCcxT;VoEjp;h zHcy2b6BK)u6_Um^6s+l&gp4;qZ2Lz^ZF5;;{b^q|Tamol-8*QSSGyOU%0(0Y~#M19zISSC->E4rT+bV0MI7R1`7 zm*ia#XELzbQW7#H6%>0qNq2KUtM(R>SNqp2t9GlGm4a`T^7&&_ty4<%5lXuq`Q+U~ zSyzisDka?aGp|AjY7sRjr$GEWbuNyplDxhvNPC>A`mR(eDy7}kq&+1KcT6dz_7cK-*SEhKA?QQYoXiB# zx7fv2CQnX$GlK@dD0vsu>-(q=WV{J7Cl^7nCy;bA4$&X;x%Fj|*Z0vCR^M`x*Y_Ri z*UMDjPfGdUh0^X%rfn9=x@}wNw`>u@J?xiVjS%!98p|KjNp6+2^JOkySNuSxCW=pL-+QmFR&8C9S3CVlt9BO2tF2H<-Fl0v zEs;74p(jADHXd4CEUwTT#XRaBFfvZ7D!D5qCOp4#I*Oto1oA7N421sBP%2= z?(r-MF-^yY^10v2P$YDH^S7c^yP4$GuH0zVt|NK1o0L+2^is8(Nt=c6KD3|YbEz#t zcpsWlzQ$ducG>!?5rSGoODd%v9HjcrAPo>oyK_l{gmCIcDL+^!;kHR#gAnu~ zYF4X3ELG}FkeNFK)jxD%$h#m@_kfmNEHegJA1lc(n7j)z^EOvpZPm6W1+{~$+J+>r zwuw@4=LxFz9H#9egfps2sf1A0wNlFOE|hTl47dg%s6~|X8k%=O>=UV4kQo<)8s8q( zf=u28(JneJ2ARE#9iOrKx{$oSla^Y2DU#QBzE68e^)*vU4G~JamP+|yLbxf1X^#j& z-{;pLM17xMV{$7JIDXff2xMj%LCM$u*7v#h`v9qlkj7lD<0_DuMSbr#tM5aS*SG6Y z*UBH_bL;*jukYWa?cY{?M=Pav5K6m-q@9Ga?i8is&O%tXIQ&|Kpbt^j8ah)0;%JHM z7KdMJ{D-vN5|cu11)1Cm;&@u`^#z%_2V`>VJLl<7`?C2S$*XT96q< zg4omfRLUlZYMV+;6lsw35>9%=s%=d2YTtd!s{MrI)qX`fX@ja=qm(~c2yY=$DmE6% zy5E#iO@tC|%$wID1ht69Gw?Y{Gi5W9wkx37Q=(c>>_+dApbpGsOFly>JRr4|Zdyh2(elyIfpTO-KVN`D?v z{?)oB3^FTJ@?>`@fx1fwwDymv78Fl4RLHmRt|1+rflR#%Vz2Tk@$E&&>reZfd@0GR z{pdzb^JeqWk=a9Uj_BF4QU-pW6ki4QkO2w;Fs^|fwRBNHM8^W~fg|cpp zQvODvggb0YYXtdP$*qX8R>TN1C&aUJ8$}<;^l(9$RZ$yxL=x@}=gg_GG2v+d^q~I-h)3DC^E++Crg(OJ=V_2x<{E z>j5Cvw0iyl#2uK6#G9a2Cp;5!E6C(l5YN2oo*|H_dj__%`i7CbzE+P~eK(N2z79&o z7Hw4D?M%B;DD8SGrLGprx&oiPMkwJrjJ^&b=tGqA-X-xSh&!ZIUrbYdpaFMBeIV0{ zf_SISD)A=Bltz%*>o8@eRXd&J)ec@`)s7~4wNEM)SKX;Ad`1NW*)4x-SzU* zKJUIu@@k7oP4gvn0m-ZVKq=p4fU5mmsn|^j_vP}*9zt376Q8_ODB%i?u15%J5jF2B z1hKWyc`y)5v9>FqCl8z)@-E2u7Gzd_Kql}0d8yU6^<_$4-!u1FeJ_x_zS*R8<5k}q zq#uORZUJe%P}VI{%5M-#xaobbM+o{5<<1UmH$hxk)*dd1y~7WrY=Rbbi26XLrUh{v zpkr;2$-9ws4)^dUtlCpZUhP94TD1?8yxOr!sheh~+9#FrZG^Cog=x14W!-e9wG&FX zcR#ouA*e;vyw48Aeyh&82A`38ib7E$9(5PLztNGl35D-NIwuZU_v zChvmSuAucT$>*rAsrVLT`V6-`WYu;ed9~lov1&JvyxQND@_+uIYHJqd$^2hJX}7&n zs>YA1wzg8SrVwuKe(eT?pcYY%BDK#KNoP(#rcVUw_+(TIGQI_wQ-q*cQj>1fXI9^1 zB(LwUS~toc;`8oywUxZS+DiF8Tkjw}_&rDkp|m?lDb-gf>kcFJ6T%HiJKu;9^dZXk z)y|i^3*xMp>I0b_FQ6tHqdt%+n;`bm(Td^*sGV;#x%K}t)(1&Q$kdrjdd1%=Lac8QwB%m2* zObuldWcqv{s@1s!keS(Qk+b@)BYAy~mRo&Klf1s?l!}v%P<^wN@{@(q?hQWqtWegy zLz*sxcQjAD5rO(T3dy}u@;~%&L0r+)9xjNbQF{p>v(Fzib)Z+-*z_$!6f(CTB zXQ6!WR{lSayLNBo{Mg;~KC1@jf4gOSq|Lm6|2=&Ay~VuOYO6D+d?o+wkkPlCEcad& zYvlKo=fnL~|MlLgaG%vbc;6LN#QJ8IC~UiUh{{1f2*kdz_G&@wKj}1FRlsZ-@>lP>#8we%b%%5*WPy@n)i1Lm(of`si z-;RzkLF|ueuNL(27v6&di=e9dZ1h>x?lY(`wF-!*IxteM6w8(Ko;;bFBZPa%NEJfZC#Y1ME0l0wo_!NS@Dif&rr(^T z@tqr5&Om(Mh_?8k9gljJwaUOEsH$GN@|&8nf|>scQBS=(rif{6#b+Qhdvn$G z)@Rp~yw8pwW_^|FK0i&QmqscT z4-rbcu}Z1>LRmLKDSxO?!fo~T%?P3NAj-c}N0=a%CA6jmd9vPf(J!E?`sImiHT$JP zG_kco+fymT`eCH34}7uOdSVsHd*Yh?+K9<~J$5t6d!mz4e#x8ai5^PD&xF$MF47l5 zxF1j{wM+!r6z-b;&>id{ZcFMYwZ+lBBpa-~!cp{!fWCv!sR z$F*sL5WIva_gU*~8;I{w)xI~#jB!CfUKG6qs;ZYhYg)}-LeH&Do7itfU#(3W&Yn(` z(z9n@>z4yb-Y?T%vVNIG@_s2QrM_RMewoj-ABEDcQmMFJDC<7plN*Jwt6@ePgy0uM z{Q|10U-~qwX1|n+CNp0I;+aI9s|K-TjTJBD zKd@f9kL0~nxoul9r?2A{lf0KcBi&weN15;YN~zdgDD5^X<#R&VpTM+ULU=FeHf<4t zmk>4k-ax#=PrU@yP{9Y*G>NabO5WIwFe4lVm z(s(-pW>?FE_*XBG9s;OI^109wfvW1I*DtGfFF}PF_kg&!Psget_8yvw&p`C2-VWWT zll9qsB=570h1!s`=@j+ZmrBK-h0<=7QtDSB^d*$?zX>JW#oxC@2tGs9?C1f-zIT~C z$-fhG=>?&VA4Z>ns_L_ST2{Nypu&_h5bGT6mxIhL!ZUZeMNH;v!`DdOORY}RG~Z@j zPx4-Br<5OYv3lt?(kP*{>#mdL`|CoiuX~J$&)`mEnDxk z%>oVo*Ylw^1Xa~brB>DMC8#j{a!@?`QYq@qo`zK|t(U$hc`x1cp!HG*lJ`^<+y54X;3Y(P21)nhfH=a|-D99%o6CI_I(h=lzAbtQ zR8=o^x~kf}1Qne3=`VA2p!gQHN+H&NfKDh-UcnMLSHr3e%P`qiPOrDJUt_wn?Inhg?s(Pu` zN8_t|O%N(fD+S`-FYW(UVQQ>A>5nJw4;S^mcM>Ggy1Da<8ALa%U{18OP0<=fa0wpILlwZ-4C^12sIw4 zs$P2j<7)R3RG6{^V%?$pNkOK@Ykanv%(qKtki3_k>u$X?i{!mjR7y>KRK4^j)20cf z-P=m}=|b4WrBr-QDB*tZ)((MQ$_cTJ#OSFYwBJ?H6QHVkqUDlm_XJd!T`VB()5fT_ zBzj{{Jn60)Vm)yK$$Mhc>(&#$k-R7VR7(9dO+B%NXK2KKov&I7#?AC_agR@CEA-h4wU&d`V3T6pAG)J+Il_O8Jw7vhFKB*+>W@q-)zF z1TP`VS&`SpOCU270gCstV1#sS`wr*M2rUt)s$M!{X|;O^D$J@mD6X1Uie9sF@m4SE zrFTi*OTSFDUiypVy|m4A;cJ zOZ7?KOGhi^&#$juIzcIw5lXuxpUetn-RVrbNC>Nd!#f}ZFCiM=g^k@@!#i-7FUAPi z%{9D3d{;Yma}DqCLs|3^sH$FC@^!U)2`b_U39Ep^JD3^OmNTqht|fWDobZkH%c&&q zmvfa;3zO=XiAkAj{Q?ziZSqojKx}#O?x#v2v*%>`)*Z!UzK)wk@?Pq4f~NU8t~<$l z=}x8m0a^7@Z_h75~A_l&UjN2<(zScc`m7_#`|OqX ztj}H}d7o7%<&W*AK6^tc)j%li-sF?V31wZ0Pbwwc5$|w65B{1QjeHZKeJL#r|%kQ1l@7ZK-1sf&ct?leAmu@K%j$tRT(?v4((A_OlX%2UqIiI+f}d%%dHOo%J$uZfpHBbrAq zfvW1ISHG`zFF{4D$148Tixa~oAyealm}7@ZE46)p>$9Cm-e+B2u|B(<_LVO1!=8_6RcZ`od z169>$H~d)bK7)!_dMZR=yuZIvD6Zos-5(!YFKr=tFAdwFlbF-jf5S=MOQV#EH_cTq zjaACuEQGhDk=h91-GlsGTOr(x?K&X@FCl8~vIBAUNM|BIab$&?v0bP4eu!QIRn<$o zZK!rHL4}!#0L6L*H+s8HW-N6=eKnb{|4t@(FEzNrdg*wQ_tFVU`FB24FEwIXrBK?P ztW;FWy2eaa5U8fvW1ISsSa} zOHjc&uCugKAl@5=ab-zJjf8*DO9#bO-K1;Q&HC(elK0t5PgQVy|nBn>!sBs@1+f-#+%hke<U68Hgw3pOl`(&viPB0ex-w7s>nVgEKYFw^?71yw6rDrCzGDv&_r>K$<0# zcAJ!nuLxz`W~RL=gu8>!=!_72hA4Nw>rDk9&VcDDv+!6A-CqQ{^01dfZ3wEW&u08u z?LLEw*n7YY$U!}JuHXjbGdi2zAjsTwxWl#9XLU&4XX!!KXBU#Z&n_YDc8L1yGNsh+ zLTPs;X%C^SYpqn=QwS>_13M!GpCM}c86d84d?CF-5N{6Ac_vU<_vkZFReg5T@73-z zs9-tENec#w_u*m1V_;{tS-Nw%!4&JIhNR%7rT^h2l6t9*J8x;{E9ZHuHE|a+ZD=F) zS#zbLQrcZk8YXF3*Fq`(uu#Hv`=T>K@EM{kXWHuk#T9@udD85q01bU3`V3T6pY8Ey zwfhVz*f)God+8l!k}qfPE2SD{)MrbS z@+Sykm7ZxQ31!_HQX`>+8+PPv2*GEFvfV{l%1IjULc>0tGNIVk6@;GK^_5UJf~xAX zS2kC>&!8gq|0+Zwdy0BfD9F@}AhWaLnDf&-@itE)=DY0 zSSamUGwmZGyxD-C`$Q<=rrmKHLhu=)T(iJy)=!~u8VqU7O8_!+Raf)-71uI z^OcI7gz#qB`L`hiFCoesSaer2h~sZSc^K3?7XWuYRjGvfWf z!4|qp3B-~$PWpy3R$4C=N#0BI_v#|%^!49+B=4n9NI&&eFMUb+St#wkQA+(PlyyHS z6@L>-xK(>}K?q(#l<)VzNFyg{Tn$+-WeF7Df>{vSW^?ossH$G7*s9vS1Qn+K1I2fN zREl1fvkBs*Q4Q5(zQ%i;hgTtxEz-0>yr&)rGhp9hfUO;LZ=S4zznO1q<#@+G0H zJCSK`3!$g@To(lXon3`^rvg^@b3%L%;2%=zK=EX0L1@Ux=s{3h@1ZMZe61d8&@VAe z?i+Le<^O|s|7*JZ_Z~Y;IU}SmJL=0eXPmO?g#XTiDgS%_-Th)A{lDHzHqC!7~3UjX4DL6rb}xYbxy-$lN2laiR6uCX)Br?OSyfMZTu&MOw?- z8w;ezit4igO2u(PX*WzM|AbK1jpCC}3gIoQHM%0Gq3U%M3N}L-1W|+bK|oxu!<~#} zl4i~GTncEQR9jF%db?RXx@6XW}TYo-D^8TEvl=}7q_2&$w{2C#=gN|wIgm6-r zY2OQB=jTOT5$MmZLUCR+C&W8mbiWNK-qeYmpBHt#^~6_Mi(;4LMO}FgXsP5-keT)V zv%OWcbq6J{=+Q^5q6s9gsGM}mH>zm5QofxK&b}z6ItXRmY*I&|gu8uASA?JlQJ(j} zENM>C;;pY`LU9hLAT+oT6@mDE&(FnUAk*&$nG$%=%T`}~lGnFojn%i^S|zWqwo<<4 zAF6Lp($+$0w?AoHA-olepW9w2;hy@gD?-qRC~t(-9n~Q2DAcpvAik9iz0HDrZr&oV zuUyFVm_h9EU}dc&X(oSyI2s%;ZT?i(O@7+v&lx1I_PeB}`TAx($*cWUDb=fXEt$3Z zi)m#-X}4`-`CPuYP}c3FlPwMo3*ik2e6o&E)@7KM5W@TE z?(K#U^dZW30qV#b#Ph_e4;1f{DahwGbd35yvF^e9>F({u_Y$f;5a(Q;5dXb0!RmXR zi`>9$`e0O9) z(k|F>PROkw(*p!so zSIRG#@x~7WtiIn#Uf;(>t8W>}>szf$dR8Q-$!xwmG*W z1bv7aZ-TfN3pZ=wjcs#o|1c+~#NLs-3(7y`^;HO&*$9xSO_N_(MQ4z_qCaYPm!J0e zbDLe1yrNp9ih?TIQz`Yj5ZVr<{5+woJA_Zp7fQI^wYnn&MTo|=`JAN1_f?e%nc4<4 z`lskIkg07zJb8uMrX-(Z{?xuI$nsTa&u3aw zA-o@1Db-8}dx`mEbD@NL{K`o-Oe#uE1NA+47LFNq>pcl?8hSCT!yD&i1u4+N1 zG=j|iq{rQ1)ixq|wOyaFYVRa@wSAQGOUqSlKc&=ip|pF5Pktqobwio9LMY+hoYWm5 zs6{l+`Q;?d;xe8D_)LDE(XifTcorUh}_g&q4PdD8e6WO{k!^R3$HB(JvoH>-9A z$*Y~Cl7!)0y_25YBUx)(R!uPUrSO2x<}KEoIoRnv*n^RGsSunVJ@K_|X-imkz3{7nG*&jYHqx>Q;#>}9b_(*jbWg9ST*$N?AoeFzUrf`vs`b;YzTZh+-=q~* z-*Y6dZ?;l??XRkD9@Bmh!r5-6)Ow+;`%tO4K`7x)`Kkv((1$3?k@nI-=4Kd>xq%7P zvJ~}!O#TG%7CqGmGHw6KHFEM}zHU8>jYyIm;Z@(pqbK_8+V5ox~_#C)dXMi6V-lK2nw*j{r(-3l`P192A;R&-19 zq^WJ<$vptwu9AZdl0qFRt?H$gn_uje^Hrk8&87_09_lGpc1rPa5bmk`#H-pL^ZeTc@LML9|1K673F1H~IZu$J^r?w#ko zz6v4U(x>OUKxTDpCi@&0$nPy77Yg5(voChd8iD!P@lw@})3Rm$%tly!G1 z755iPxUcrT10g6vlyjhSrN#vDE>86r$jobi{;K(Us4+oo5p-Sy#917@d2iOq`t`oV z%^`V3{n}YYLr7lH7^VD#R;uVJradi$_ogsyl2F#YsFZp}DB)_}atA_Cgeb=d+6I95 z_A#w7L3}@m)|jArO}(OW`4%&_0I>~6jZ%^{)8c_l-}|+Dt=f4cuXeypt9Cfat9?wV z`0ra)?bD<~g`k#nxDeDTrH&NBJ3L>y10kqIG@j7NNgCg3pnY!;YYiP+fKDD8)q+g@ z0%9*+`)(jpzkp2no4weoeVgRfKDgbT@@Iwio#fR%s+4-NkE(r&^t4dgO;*ZJ62d!i z__=3<67HC7??eb{5siE3bCSk)#^@{nD88+=AZZt_jcP%rwE(eA)w~Nbb5^zfr9bBL z?(QV7@0UxhzO61(^7?jG%BLPyeS0$PETObJfNAFlW!<4lsq=&q?xN;*A_RSinzd@s ziCSgqNHM1A-YZat#&3ky0%W`iqCOoLgG}B9F_%9jeVc=CvuY0~d9}MeVbvZ$@@fxN zO3k0BY8xmOOG0Vah)=#FgmVW>s}#a0Yy6!EK`o-Dw+7<-k#)@%#2Q6QDrjuKs1{^O zDv0kCKrM_>*7!T)oJZ27=2(4ak-WZI>#e@MNM2t(rQ$iWRo@XzOADplaZ33Mgs`tz zDRrSx!u9*%PK2NjQMUFv%K_qfKdp&C?6GLs1Wo+N>#LA&;oesDAISI*WOfP;uhmn2 z%;(neB(HD#(>2YP#$8EX-+oH@Hx{bCLzIed3Z>nVe6l2zbtf=wfe=nNp4t;3=tGpf zO4SGAeR0~`2AR4CG~$uKmJ)2btWwl!VQ0X@^hiA>&>(;gc9zXB|Q;>B1D;c z)MFs_y3}JJb5lKN+lr_N#PtsCUxTazC1t`4P)90p|l%CS}Bxuk1OR@ z2_@X|-FqPfMTp7`e)Xnlj|{|GLwjT()5d`=x!Nl#mv1p`0Eqn;j2J2<&6KLz!>qo& zNM7Hhc~;+ZB(LukrF@6uRNp+M;;lj$@hPQl6Uw^9OzR?)aOb?y3nA!3G~U3GleG9Y zzA~YBLa-oo!!uDI$kZAj?ifTJSt(C)Rd}N0$d+GOeb)te! zaqk*Ry4t(nC4aKdyL*$oCF+rC)VMBH?+kaCQvUsx%_@+Sk1}cJy5mh++MQ(5GOn>n z%eqrdTEY$5^)7^9Gepe{D~R=ywj>}kuK{}Yw`env$rB*XYO2jZrd~Rwf&Q4!^JkH~ z%`Q?3HoMGF#$9O$=NPZEHv5L8Hao*@RHBv6b$=MjxUH_2&oK?Xgw}T<1nr2jOur!` z6cG1ZY7Z9_-vVBcv`5dIA6glZ$uA&tyD=#CaB+6I%xdpS^4jlG3fc>XGOnMYq`PdI z)!v%qwcn}~w0Ad@ad#QQTgs;1g%GqO8pq5zNi%!#LFP@^ppPE*+AHMAc;j|S$n+pU zrY@NAj@AAe$!jku1?>wBW!z_mlJ1bdtoEZxUi&FZLHk*TGVTIH3HS1!cOeArh??FZ zh&fqnc97XK0s44F^gD=Zbwv!s+=G!#rTl`aCyM))$&dLwzkuYmf20(&e_<%&Rv1dU z?1lO*zMi<8|=6R55r$IH3e=Fp9kje9) zc=J)E{DPSkThZ2PUqkZRe^v_GHyg^h?QW6JF)iuZkFwgkk-YXkN8&j zq6{HuN7S?rAhTZ=#J&C6>jLea_u4DuTR0D`o(3_$=&aaRFIu(Vk-XZCN7A*e+Z8_+O~G+$~r5Iv^z^Psp=QINE= z-i>NO%;jH8z6P0mo!qv!e7(=tXOg_y3zdS}W`;8E3PVZv>q+`8K3{LuNXe_+MJcG= z+fc^UHI#78Pwb5l)FNtp3u12lPF5p8?6IhCLAUK+3cWQDN5UB6Rmzj52D_)ZRXc#> z)s9pOYR4JMxF-#v6!*1iTadikHcCNlXG0m+!w}vjUg(Vw)FR5i`fc$ohS>T!#lLR6)!u>Rwf9g8+RF@O+&zYH2k!?~du@`}zOPcy zez2j8JIoNqzKePz1nr2Lbqf&ZZM60VnXx_SshLqb$kbpUv!)1&t#+mSp2-FO{=r(} z7?QWd$x6Wzry0t)vkWEOhX>_FfY0;GNZu0PD+NpZY$)UYGL&$|x_JcoBH4e7Xk1gw z3GvN2KS(YBaR&KgSpfho+ipRq%Rwd=fa2?M(W}K=&?Mwe0lDEVHrC^B< z4Q1R)LrHgAC;b+0iJl~HiT+B#5c%DAHpCEdiG`pDnt)lMgQwR4n$+WCesb~1$b zw(r;nLB2>z0HS7A6T}^LYor8#OdAI}Y<=`Q$dmvOSB10<02xm&J5+znYhO+B+BYZ# z?Y|nzxXp&3z2$#sCwc9!DFy9s8p^nL4B-tkE&3n??TDKBc@X>T+TwxCY6R%C)87s) z9%wt=lmWF#cVKs`?=X_r*H9_wYiuav&M=g8FFbAay-M=>7AOUM?;FavC5962)TjC& z1bv8_IZhDkGp*e~rbP#}ddTZ5mv1rkJczX$dblM?GqoFttE7{}5@)_)Epa}{TcVj# zu*8*yGOo3uq+7koT4DpqTVjh+u*CL1%af#xt7QngpnmFu5G;YH>9d23r$J_31JwJo z=xGqwS2SOP%&7c~UGJ8!_xbvKl2_YYDX48}DC4d%lysxd)^G7;`U#R(J5?#Decn*U zy<{limY;byLQson+*6v9G~U3cWjYd02^A!5t0UeCts01R)`L=)gIE`+c91zy{ZwnK zeHzJYpRE+MziuewN`{i|jKNm>`6REssZ!A1+)&0{ZYY7X*LNcX?TFGxFG{}-#9kiO zcFTmgpJy)u*skZI#U+-yA$jdzD+TRq3}xJULrK@Pm(|{a3kX3wqGoS4 zh%GZ_84L2{dDlm^AokY!N$Cf1Wb=ur1)2GYaU-nSr%7JzG^L>SB|{lE+fdS#EwF0u zC3&@jl!Dra4Q1RYLkX8E6%c}2L`U2zHGPHTc@RsndKwh_bp=Vgc3RX9GQC(3_dKho zL2L~lm-7DmDyzNbH%eanj!Hp$9YYznhas$e?tPE^$v&5#L-N|QNYu)4Y^|oY3%(D7E4@l zqJF2(^VgERCE6wMEa2*DDFa_=N= zFU(0A=OgvbJP`XmdS?`9(1q`Y@(wb&02KQLCHWT927pW((7s?T(Us&aQKl3uagU*l zyWbFIIbN`qXioB$XsHw|ah0KryVg*`J@NcK2*DDFvj3u%0CB!`vE&I5?;C$b@&st^ zsAvh0srf*04{}MKWM0xd0b=PGB6*_YB5R2rByWj=Qm{mSLzr_klyr->>MOtCOUEZ9 zZ;3CJf+bcO%D8V0;kLJ$eG!5sLR3mXPSWDsMVU}sE5~hbHTy1J?JZFu#5{rAQxak> z(Do0+k~2!Qzg$;;%$JAPNnZQAN(SK+g3qpUKv@nzhkSPx!(CwIj!4in_RKp8m2@uD4 zS~Gxn8X31X79=gvH(CNjwRve9L2++yNl3pQ|DcWpnewpW6>Ev_NZt|~l!7IGF_dwC z7{V^+wbl}IN!}7~DFsU`FqCnXh7zvc+P(bqMk0gAWGR|?TegCrN!+3{ZaF<&0`B6;m~m4fy|3}NQd5JrQI^;>*hu#V)lZ&V7} ze>RkHzZt?Re&c%)f_6krtq5YzSaSi$klvu?N-#JvY*KT38 z?@sdC_frbm>l(_qe;G=;&-+>J%Sc}P*GfVA216P5lc9ub)$d+}pdC@pXH5~mgSgWI z^I2s=to2bk3PN2wMeU$CmscTaT+?_iPm{d%OO%54%M76hZz$>Z`Pgbd zkmR-hODSltZwR@^P{Q5%(Y**kJEGkC^PFf0arH`DLlEENgF3PxX@g&l+CgSq42ol? zN_mp=o!{LKa#xmpOk|3pABW)uZEKDmqYH8KiTK`-$-8jA4);{pN24FW+>tA zKjc1ypdC^Eol`|Si2WC=Y?TQyU%x2YK@)dc6!JXC^aMc61v8~J1erDf6#J1$_x&0A z)4ud?AbCsttQ0KqtD%hh-4M!AS8It~N!}8BD+NpJXDH(iG=z7Xbh!^9SOQV*6Q3rQ z0CDw0a{(yo!@Eto-1kt+XbBM2c9xnC#8&hjDFGl_@Da%cV+UF76G&eBWTl{enxTw) z!BEn|A(Q|^3HMgeh0<( z>Xn43UHgL|mNDIFKjtX?XQQwrJ# z7|OW8h7#`K^X^9o+7YD&^l5XF#@P{^Vk#4g=fDa=&mHqYX#YT_zYF5Z0s4xS@+7}= zq-fuAqt(9EO-f$-c1l6}4u&#rM?*<>=p$D95hSnu7^R^7ctaU?f}w;fJbXVw(2giQ zrY#=?TecImz@jC~J_Fm6h?R`jIdq1V1{Xs(+H^5NR z&HdVHFOj_Vg-SvD2Zl24LqiGo?27vlf_6krT?b+fwp_G>;=K+9p?4NU?I7yY77s-2 zm`y9mlT6cEA7tA86KeLCpY|o73CUaHJf&cXOAKY)WrmV&>GAq4z65+t@|O5PDOh5Y zA&hzqCETpz`XdBOAj-WCItu_|i>K`$$kh6vrF$<9B>)tAxE1o9d=e`vB_Ucu>jDs4 zN}UDhf3da1Fp{^#M5SPf>4q}6_eVa*G_3IVv6i@wvr2A<92joxo z)Svb>!x)mc#CWA(i6;zY+yp~OH@}^=!~&AH#6qQD ziA9Do?gK*!w|~0_5P~HTHE-1dv1ZWu5D-^QFybr7=NerSEdgQ<=_Wm65OGOPop1&1>RmQ2TY!(;zeR z1>z_YvqqKjq?z&j_aXXYK9?U(^4gD43fdbO%DCeVC0&EdtoD;gUi&FZLHntOGVXLk z3D@h=2N8mHM9r)pDDLhnlP7sjQP)C1!%z7rly{IB|AFEgNGj!XECIu$p1-<_)qWkx zYj3Xvy53J%?RS&B_Is6r_I`#kuD>DNtMd4R2thld^q9`}f~e>d@jEE? zjB&5Z;}3p)f7A{#yMv?I#3Yh42av1ZraFUa^EwEE+y9mIORv(#>&iUs4(d2wT< zXa}(zJuKSC)_zES%;)(DB(Ht4QqVrl5ccpGO1haT{T5%|UnhC(A1Vdy%M4}QH-@nK zfBHiRK|7*mPdA9`9lFB}WOj9e&a3}1^ZdXf=)b$$vY)>VbezBAvQFc6C(Avu;lDR% zLhkIJd+6;Qn%aA2{|E23gbFiv31VJGkGCXtGW|6W^T9LX&stYof9^^0{yan}`15E( zsKX2;UA=+UpGT0qKbt58f1Yb7<1R9kaF;yv5JK=LqGo3oi0629Zz_nT8trdEKG&sN z^e5=Q^XLDeyGo-%-Jt@Cz15QFrTVr~K0&P0bYJ4-&scx9CV78$QVRa;VF z&#ga4lDt2kQVRZ@Y$)TNGlV+@K6?lu_!H6ip4ptFnHy+8agC)QX&vTzf0hfGdKtuW zjXM)cl4f#tq;Zn7FZ#_|;&PI=#Pv$S5*-ZTJd~lNyYh$uBEZ*Ftx4VzZIyy0IvUEj z&V~~1mcs`i1WO`DT?>-dug)i-bq1L-4&t5-^xsPIBrT!6agcq# z`nmekzRq4t@|M`36fCjHP{#dYDCyqGSxYP-c}uKP3YJ)F2>ZSaC0zd=0}z5G5anN8 zls+1W^N!e6UM9qy$2vz3nsQCF1SpO+D&$GdN$Pwh$m9u-x#Q;khpi=slDs9xDFsVB zWhmn&8^Vmmo7NJmNZt|~m4YRHHH1b?yfAZ#9~(R)EaDz2XY1eLl%+e@`iBUu-DjJ~5PZm+mo8{$yVs zt|EEuH!B70?G2$k7)rP=cN>Thv?FTHV}yhnsvTrb+JS2R5w(L@4{99=Vjm4X{F3~F zDGwl%3sxMbKkduI8j`ofFG|4@n+;{$*2l}|n3i-G++Z!yjN~nGl~S-oYeN}#lOf!` zdfh;TUj;NWv1jTy3OrE47 zU8w<`H#}+wnOp#39f>v0l6=n81@TFpvs+ndE%6=6TVlOZu*A=XFz;w6=}zBbEpZ;n zTcW8_u*9W?GOneeglq8EK!jikM9nG=h>Dg=tq3yvw?NsI(Gnn27l7jUz9gSB# zhN!6(LG1US_gf}uv2+xK-aO#5Py#@#6?0+<5by24Oh8G<)CC~3viIzz))F&G-V$?_ zf+b3ZkdqDJ3}9bti5mARc}wh|6f9B8P{!3UlyI-zGZ-OQ0#V-gkM=JoX*_+YE4rZg z)~14_ecnD=0%Ym}5L-i7qEenTZR7WkTkSuQy!OpXL3_<7H-kY3+ak3$n5Cd zYrX!MF9CH)Ui%SBLHn_WGA?N->25lBi2TW3`>iCeJ*O13-(@J{`WV8^vj+`92-*>4 zNu4Wx2T`rI0U(Z~^hAr0`#h8Ykm(nIn9H?y2r~Tw5bH>74PQJ>f7)AO4#`{MZKYs| z_YGy-$A*&b{La=A%}Cx7S1AQcTxSTqLqiF7RHq>b!4in_jA~IV0XkQYwrdFh(bKxS z1C+TuS^{KB0EnXrUEc-8x*+L}f5>W2lDzgam4f!Pp^UrGP|}_Kn$>;*$!l+>6trJv zDC1ff!d}i-had#)h?>|i_FrCc@nVRqV&#d-# zB(J@zQqX>fp^PgtlyrS|9x8vbF9G+Hy!N3=LHj5}88_BY!rigcP=ufzQR8_9dV_$y?%frC^CW4P{(!Lud_K zSxY=a@|Ji(DOh5rA)K5tgd5^p4n?3PmI!II#*e3?Z3LNBeh}Z+u=@0REB=0R{}ftE zq{WkA1)=9tUxa!BL`&qQrHu5ow3Lx_Rt02MzRG%7EA=ILD?O+btTf0_#tk!+bbC#* zRyv5}t<*p%Sm|U#Sp6}Sa3h}{iV&<6qF`7F6nhCdA(jWsi?0x(J@I6jkZDChGY5Dp z4J?AftZLIox88kwe5~`L~$@_YzUnDK~dN)HEw~ry*4Y_G3g1QafMU?X+I%5EeZ)hu%w0I`I zAoTg?G1r4k-2md;0_v2KJQ>>r+#9)Rs5$vMW4B@Q)4pz~AbCqHQVN#%)DZ5fGL&@N zoTK03YssBR-V%E%1xp-Y2)jfKCEPY=4?_r+K$QD5W=rb`;^2`({I!hx<}K$Fzi7wrm(e(2i(a<;+PM z=RkDS4C2kc=t&kN?aw!(cA-h@-_KsJtpJEE%coKvVw$!BATzgK^Dk?O9ZB92yD9}s z>}@FH4lsmMPscti0(^OxNAi|fs1z*mp`ncX)KJ3Rd(6WK!4inZJq|fZsfJ}J+nLP2Y3-zac&2SXSTjE5eV2RTWW!%|@lJ3d7tR<$B zyd_>%3YMragu8MKCEWGB9!3b3K-A2wgW~&A%j8LO5&+cuhG+?p$rGShjw}xd-N*|bMhMyw<;=J42nVqz zi9S-9JQ?qVDG0qV-D|H9;^+`1r&5TP7$-H~Evv2C&Lpq4hf+{`mm!Su3?*HYeIJoO z(&zbeNnY)xN6OZx}nmHKiQ!7Y5+e;|+-O4yx9f~Y5P~HT zr3S2s=OoRXdIH6rQ3XjmYD}~Q$jq66Sbx4Nxd22<3=-`X?_2F}ki7Q!NEP zlysA}9xi{fF9FYxy!L5ILHl!tGH$LRoORuLI6}~lD9dfR_#G5?{1t>w`Od4Y5Q@9{ zN<#V-_y=l1=6u`6dYb0*{Ldt>_BW-V_76iiqh|;+?ai#({YhSJeWjrG7(?jk7)rSP zE*Xvx)FR5iQ}=m;xFW8tJt)qf7vyt|PX02KcM!d)tv!fV($+qvwHCjFOrNh-Cu@m4 zNZt|$DFsU$Y6y3m8A`ftirx|jR7Uw|9gv>4NpbrlIDwF__@jHm?N!r?jSVuk~em}6K)qXh1Yd>BoXm4Z) zx0V=6x<&o1_9Y~*{cEM5eT|`v`_T|)gYF-JK)n$`-n*wM1@E3^2<6dG(zRJ)z1xN4y?eJ(@NR!Y=+78RxQ!o=KnUJNR0W8Ju99YE zu|S*+{#LvT;(2zQODG5>=0xv;W?pdiLU}`Z@b1p~3pHvKCvf*>P0!nH#mJ}o{rZ)} zCiMTdf#k0r{e0I5zYFxG6Ssd`zVCl5e^gr2Mk4#ZDr5U!SfNe0`1~v;&3`?%?_( z5#)=+yNH_gEf8R`-9MKcT|Rpny2zhIzD-=%qg~+QLmL-A0;Ogr$S6KffV) zf38;w{`|#I#{Fps@6wuQ{dpA0`|}i~;LkG+p?n%jxC7^oLMNCuw|#{jXB{ zf_R1sw=EVlZBq0n(&~)fPHW42ucOmao7Qm^|4}~mC-6@{U#o6)(EmDrLWSukf;h^+ z3Q9@z(w`U?Rtm*E&bZHfx%FpllK1D{O2MB88p2KhLl|c#Mv0AlefuuS`}0$!;LqiT zaF4bj+@Dux6oMMNUPmE~;vdw$ptyqoZ_BJRierb3;$2WPo#fNf3hMid_in$xzvZx0 zy@5rfh41{o`v3LHMN=%hv;J17EiKZxH~UBNJjm3{Ahx@@x3JSOY71X8cPDwz_f`s? zFBrJLJaf{y*Kvf(p~e0+~J*h;=wxu+o31uM{%t0k`y0%XrV< zO7foXt`t0fry<;BVW_d|^~B%bl5)dHHEK*d32%9NBoOlCIc`KCq@C+V2142eZge1| zW!#uRNK3j!lmGT$W4G8)6Sv$`>ZTOlBelw;rQK>nS+~{@_HIrdg&rPTXetPG8S3-az#`}$%T51&yt;A|RK$LGg(!@*D0ZMu9u?b@Chqe; z{`N$|z4H4ggkVEN%?<|;*Ko973^FTupe0{M8-o5Z8}9i;b=eRqVu`E}%a|QpAXEE- z;*3SYy`3J75NwDjpF};DlQhS3J4a8MIwHnB*8-b1~i&g{uV^;g6+N=f@Cg*|JLVr1Qg|*n>~FeOHb~2sT8N|o}ZVSgC1REmCUWwLuAl@;q`({A#jkN^_ z8unteA?P2oVUtPKW5Wv3bl;xRlhxafK&HHc;y!uYwRFIv2*GNIa%~yAYI2gsxn|4; zlnHUBKxbw_OSkzZlvmI{X0@ZstH)~PqL6E3xETUBMjh~|**O4;dk7QmgZ7Ui1gjy+ zQ3Gz_$VnROHC?%sC$m!PY1;tW)GS&J^p9Ds?laY8HK>R?2`WUrnehavk?;@7E6C)$ zO|u?F2sT7C-d~(^Aof_)h9J{B2JJpR+7R@Q*)TD=x@-s)re_D@O1Q3JgG}iK#T6gy z7jR<{f(;QhbsmU&0<_KpnRWw|`XSm7^pDwa>nYV`L#W^=t)G-$5JwSuZWd&E$A?`$ z79m&-(Ri{f=Rka;qV6*SnR_-t=bgGb)OnzP%xd?{t}d%Vg~@p!b0ZpvIZu0br%o7) z5Uhr%Im-qz{b7(f!vVVLfoL_*KW4S=uU41Upu&tPKwb5Kv-VLyY9#!FIuB&Z>%kkw zA_N;E8t-4tIS@}q>Z}ULoQwpWvLxCN^pDwa16RwdVU7+en7cabO4)|7aaIK@Wg)Gp zjBP=&WGCEJsmBn44H4xiSoh3>*b-}<2a0bvFUaS59{O!4y`X>0hJLlO8f++L|GqJNRI`?U9|s?x%YsYq^jDsr$C{|G$06)K?xFuoRln4 zf`Et-NdgMYz%xoK(jqO0f($`WBuEYqamZnSX>tP%)yN0p6y!S|Ni>F zt{7~liDZZiXNuNgyllWW5VY4pwxSTUfVYGpj7)p{*E@D z@9x)-U7mkXhhk>BRWEn*i8%9Sb`~?WV9>i;YJY{z??5TE&^ONubtv`RAWsLY#UKx@ zl|U$^?L)Jjge&TpX^anTYE9;&ifhQfNX&SmD|+vPP={P$KjmG>cQX_AfhczBwd$pJ zI0;wuFw^&nPL}8v3u($C*g`ZW~$#H-&4__7iN7`KV<$lWYU{E2-P5f5KdzE}daXxVQ%T zLa98iy7DQw5{H;+-!9}k_pJ7T(!O12oB3WUIR^4Kc(XIVUqdO)pi~}LKJXM=(Zft> z2Kkd5eC4%ML-BTruIO94H+sXO)K)^?XQPhp%P)l%^7fED=X{&??o)6@9n<};P|FGV zUPNY-JEHiCUsv>AIpIX27?k1kB&L&K0MiWXc)NTu&it|`&*O;Cz z)+#{hy=c(yrg_z3qD?dTr_p&hn z6yF2n>xZLH{q?t+cw%qE=uA;>Mz1+Fo;TpV-P50jD|(pT8@WuOg}kj{jNTEY z(gV%)>``&&xOOH z)bE6RzpA}I7V}7 zQIVn$mc70wyIx45!!($jiB~^>~vgF$MhbDtuH`neE~{OWI{*Z66#QD zg`jx%MZbnp*n>_~KD&15GjK&6)AQLGHhx?B3}4aZn@&6_zVsQMTdmwe56}KuX>+02 zf6LS0OP>*?s#QO`?-{tFfa(453#0(W*Ht^B=z(`dQ}5I$42x1;g1pzu?DycG{CL{$ zwli==57S%q6Ql>lTQWL!=9kp(`FZ6Xq>ueVB1pUY2>C&z6pP-^3cPdp1()G^~e+ja5qH;zJSe>&9vZKy*j*F#I% z!{fGI07Z(m>Ze{l3s>|o(+C-gRl<(W^lMVzbwyL&6M9hOke>X!b+$Ghvdi-iaUEx# zteWbxUmeC3bxcn`dj=fxd$IWdD7`-jT4>=nOI$-Kv{0IjfKpsTDeQ|LJd7*qnBE?f zCs->vcsSm<(h>R0kIfrG>+RL3^HuhPhrK6D?D7ut=7Jtt$aBvr3hkTs4daR)W(qBo zLJOrQA)(nOL};OC+4%15eT{;tLn*XS+HLluMb5?*b<8x22zejdMz&CT0v-CzjBk~= zhEiNZ9!t!`3~DHa_Nw@eE_9hP)NBHz-5>?}Z)|bwN*OrkNkeF3&&2 z?j6^kjVpSX(Ichze|-)g6!Y=){;xm#<>5w;Zwg%Bgu%)Rlw$DC);YMMfEn$0yN1## z5tR1pK`*}>A%ap2LOy?M=?6vnQ8u?d2Uqkkqfg(KpXU%O9gx3q)M60&%=&M8icuQ3 zJtsT{03wfdg>b+or^1Ri0LgSU%hD8kbm*&8O0&weQrjNd~aZ*bN5{4olCYP7x-QtU!rs*jZV@bc&3iaKVR5r=%- zXC(rPK4DkCyX6b-me_?-sfIkCGbc3AnV#-PNblMG&%+fx%v7qO)CxeU7J;VzaiiDM zRiY+j^s)bWzU%8WDNLAn9MKi8Cmb2PpPow(9A3KOa{VFyl+mZTWfH(&}_X@jP`` zwCGl$0L8edCqGXW8~sCedHx}d;!NHd(yG6F)%m!hj+s`0pjbKU=*%>a4{dOAs6(FX zY$gfvG_vv@em3&~rFo@;rnvxD)G<>IfztPZA&)cblR;;`8tPCg4^YgQ3~DHqfaAV( z0j}s_rgjbT*27X0N~3@1s@2~wsR^a}1zN}?tY-kl7?iJIpLPMR=wW&;U_OJdV4rq@ zulHF`1WG*v=&VCR4~p;&^t&9QH!e8tjZnZ$tsLZ~%0u)X37PSw*eMs zP^yKYy>AS4D8(7%xz&0%P^yLFOsi2AT;f7pQO8U*3gk7B#UQlStRI#bgj~<^8I(e_ z!!Itxm1|B1*XRZ#F-f25tge!WO>8Sz8=L}gb>gvoJH~y&93{a{WAdd+~hpqa~3opWz zYhrp2)W%>?>f=J*^RV6F(96d(3O!xL=XEU?Kq(i@P+g2G3dQuY3B|k8IyIE?HMHcj zp#XV0kds^WnwwpWE7!zKV+|;+5<)Q}($(*NxZ=kpUZ7M`q1dA^(3vTvH$47gT+zc! zdm^9|2FSy1H3PKEZ$b}BWfO{V!Jv-c9i{MX^1{V9*K3QS?&*qlo77yhCrbTD$Wz+Z z5B6B)5?r|orq5Sc%?_mz3-pKiKPmA7rThYUKiTR?D9xIG{kNCkO1xmEo(|;owdp~A zP0KydPxff^dNmaL@CTxld&d3!5?oQhj5jm3Ybf4m(GjIlGc;*@gb0fEy{9wdd-Vg6 zmrd&(-nY=DxT1#{UxIGekiRpMJlGL=JuyKg4tjgq5f6Pl>r^9nIv7fI7UZJ|)_7X= zM|)n1D+-vYZv*)g)}{bOX{6=a^U}G#9STsYr6AWsp|3OT^8BM#ZO=D6PzoRPl`}#eN;w(wR6%`ELlM`ldes>(!xcTuh|iAv{5~xPp>Mqv3Q&qc zD6PsterJa%J~#Z{Ww@e%=_8`c)tiA*d_vKt@@4z)UAFT&RY@@@;*)RL7ovCAsz(i9 zhARq~erL>}wdEII8|a9vVhUD2V3hXR!142pE`>r9UcOEJjnCH9~2w$67i!xeQ* zzt0n;4#nzdN8~YYYZ=gKkAymu;uDHhmcD-H*R;McSwQaIj*QQMAX z`O3t4mwSt6&+0I$Mkt4OIyhMM3!62 zX=+!xHT2v*p$2eTJ%+xxdK=8Fw;}KP>e7;HI&v^p>KVD$`ZR!ie1R_JmKr>cPVXyEVR#c zuD}&_%xK?PCF@+_ts$c&R>?Y7cw5ElJ*#A$D_TDabtvkWp8Pyd*xWN@m**ey(l&!D za77Q(N0H-|mmq%!8FffUly-4IdtV%SP>NkBW=974U5ed3zHlY3=wbSd>jlz-qOZ{r z`93bz^1Gr#rua;WT_}|t$mbv~R$T|h__kFax$Bj%Ep%hxkdlyz#AXm5C z^XO-f>XjvMbvCi&K^Ogi=i#XOfx&oteV7&mrS+ zMGrIDBjz{{8Sk-VdQe*BgZ?zs=rPB6$oR-FywUi9@wjqL%vft~%g<*WEJs4In}s(T zKQR8{UUSX9D3viNdNVWEqZYfmJM+{Y+E#t_qF3XJ9%k%~Xv@!M@2T}Wq7-M)12Z*O z>B%p?p53Z{^|PyS<(il&-64Nsh%sJAXQtl?4e6?IIH2`kf3d>g7$Ly=-#(Zc6Mh#;Tuxl`#5rEX*0;Y$7dY7kE zX1&H^(DqP4UjD3>g4TRL!Uv^%4Mp#e=R0P-CZ!(~>DQ_^+U^=$QO8WPnvmytQ-`8w z)z$BI-JmYH9Exl9Lm4t|6bvV9eYRc@0f#(G~sl=+J{w zEd@pU&U4D;nl?l5tBp2Lagy`A7NX zqifR2!I~Riiz|AVKC^I%QWJ{xhmI&_D;S4weC_v_ou{Aa>jsDCH$6dOC~^kGVEtp6^IJdo8Z$ zVW!xHJPg)5gnYzqsR=D~XQMZE0`%{%rI~2_bLL-Wv$r0V|M4k29YiRiHs@;?&tB^@ zMbxeXQ7Qw^t}p>-x61P*m?@7y-Yc?N8S>u7RZ1o3GxJRAd1S0E@$bjl|HHeZKD`x4 zLXmPh-PDL(J&EwQI;nwKmTJrQQJajh{4eIIJ^M&l2)> zm3f`M{8BlCJav!O7;u?M6L6tEX+pG}s85>U^OctGp|sBy+VqOa>XRCU{j>uJKX19& znK=;oo&8yQ)6U<+6+KL^sjROB#e7#sXL@`xhUkhGpL)7dt3WBVkdN1_ZwIAX?3g`z zxT1%d+9b$p0BaSXSPSab&}H8Yy*Sh6aUq{!W<1lX|2)2jD+-t?M9}Uw*kQ!f(V3p^ zS1Lr%C8vY}cVU>u^OK(_0#gPsl@S{S+uhpwyGo zUiY`xLLEva9`X^4~bvRdVi~P;urUyj}+?C((8q=5bgHpW=`JAii zK`FHP%vSyK>DS>(XfZt|n3ZVD&&QnBDnLHQrM>FPZ@NQ69ZDq?@_v}bHIzaNrO?j) z)^)g|jv4z1+BM|;c6Nz$L~&3)?u$~`Ay;oJpDnu1^|+#rnerKw z_Rc{mrJ)TLpP|G&6d_`N)jHSvY$-W;Ac{L{)z#tG!a2o zGOTWg=4po>l;RrlFDqGpD*S9+_^?N=#}z%y6h0`P80plI-?fz^=-it^4@%_-^6?>Q zJJ9bU?2IUuya8AAFjL8a{7iBr-$+^VhSbA{E}d=05}#1Y$x!TDX0);74Jj`{slRc_ zJ~!ZsI;O`GbBlcWeV-d*M`K46<2AngzRwMJZXfE9tB+B=3!U)F88>ab5<52gBD*~Q zkb7?F-+(K6m_FNWPme(H6^M?`jF{+(p1C0OpcGmt<_KH$h|k|Br$71vnBLQ~9vkF6 zL@S$6>ajude-a8%s)^!vw=4ailzzAGbR(|lVW#I{AYYl~cbyuF5q($m!q;ai=?A3{ zK`|3I(3vU4mbv&wT+zeyw7ozn2KkJW)$@>lPv|n$JvsrI}0YLa8)D@sv_uzq8Bp4`~afR{Pi!Zo(CH%y^!uT|;Rs2c@t>mmkom z_jIP`0&*QYcV4^+SFVYf=CmMB70aJc%Ae4qcSVSx6rYf{Ipnjx6jFRbe$7Lq{=lj? z33l1zH}TJ)IdNn7+s^$Unp&lxpwy4!Rjv^e{bkZS5EG z@vrrJAb(cZR_~zMM>l%IHI&j1^1i9Hl;O9z$|jWZ?o#*Oj4SGxF$2ra#Cva!@dP^) z@4Y!@LD-pi@6DTB6Y5ZkYbc&2VHe-MO^6Ox?2i26Ex4kG>GyJi$|mF`hw)lR6g6L0 zwAu8tl-vrXx&Vq?(ASxEdHx}^aVGU{tKNL*7FK$%|~y2ZyttQj-EHgrq0 zqRg)i-7@Msje1Yyvo-Wsm{A+L#Y>g7{fqQ&!4(C}X#bd@?A;Rk5<8;kPcTE-yJfvI zBYaSbPbl`M^>t>-yHKk6&X}o>E9#hOln14}1jW36w}x(fJJg}LW>0=zis^aWQb84g z=0A~zr>{QxKL2yZdfp%O7cgyNzExlN{XVYT3#Q-o1jRMv?a^C`YshPT8>d5))}7T; z`T+U)C11UE{v#`>Vqus6MD$$f|Fft6>G|airAj{K4pCL^Y{b?FU(p}&J~%(erdzGL z^p?ACx7V0;w;S4J`%&BNwd2xTjM{$Gn5}o(ZPX6Cj`{gioHI0LuU+@pc|NRt7973T zsL?y^HD=eHh8A3PpM95DaA?#|_u65n1y@~g)2$ZVcmDUkvgZ~3b#~cqXlU1=El2OP z(~d)nZrxsW{*g25oH_eXn;+GEUaJN;!q{!kG~Ing!u9t|Ce;hA>V7)op z3yi4hKWFh>$3Ye1|8tI0!2kDYzCcyg=lzrVmCzLbj{5&5>{C?rbsLu)TRTWR{C2vJYh^o3xi-3Fp)xLWnPN8gGodYEb82KiNNx(@Pbsf#rXfOgoo z(d&u4%V!&wA-f>|5TY%gycJgzFk>pAEkAF3Ek2>>GIZs)*KMHy`6QLaAe3S-$YOBM zWpBe3Jxq_mlhmX_zWt5?dq?CGdvtBOqOo&+uEZb|vDA}a>Zn2yzJdHarFmSiRUfh6 zZMdS2nTBzYcln->Iuwg=UD3HahdLD9rJnqJ%c;dKl)@flVZZW@+i*o4Gd2LUYsg>e z_ng$B=tg!$4_^}MP;`EK^7Bp*xu7pfVTYn~$Y+b^z8zQ8F=K+2&lb;pyLV<@k~)+& z6+jB>s)cW$MrGNTXpIIuIOQ=?LUxj4tQ01Q2HD&^uw1!4|2UD6xWb--jNQ(iZZKJ65AWc6t6m9f~1Wt3Khi0j{WHrbh%If4PN) z7VY%VPZ+cleOR^q>?zC}O@<|LqTV;EEom*NRuD#)P~aS-FMMq5|~Fm_~0{XQsRh zd59=+1NlYFGwuE09k`;0nc6tWm+q~kLTTy=n)dq8gS_?JQMUi)Th5h1p z;)))oryq}g^9uXL@ARoyYk?q7BNq92h5h1puF{&bQ`$w)}hv#q^*w-2;7V+t7nz{MOU&eEGq0D`c1FA4x1fE_4L!)?%<5gpU+HA=8Gf59v{2kxtNz(+6LCcy)2HMvQ0zkK<-1U9ed@~Z z=nq02ifi`d=lA)j^q{yi7O1wLh%0)Skz#H6`D8D32n$r(PfXi!pi4KLtE46rDb~}O zJ|$;0EtE>f27QeIF28yuLihev1SHg$s z6A~9HJ|W*e!c}NRKb{yRwJZAYsZbZ4_1dIOw)a-_%z}+E94Km@IsDOz1VYq!fc>y60WFY#*$)Ne%^9f%>a4t@H(kO?Rn=eH9O?f^YjM? z@=Lv-y$+a!D+-uVzqD(}dkNMLfzpH$G#j+- zqK=vRV37B{EqqWcO?36Uo39LYDCH%{dr#B_yi&2bJQ{=@O1+XR7q|;o)G<@+Lf%KQ z2go6>BQ0&Ad+T{hPKHw0AusRr+3EcjKMOnL<<_Bj-@N)RTv5l2iOaV9e9Ua=4y6r0&}^rL zIutcgU%zt&3oYdBv`tYjI{n?aqKBD!WYE5rxTXjBRVFAWL+iZ}dQb{2sy}z ziqURIXU1|sS9HMG(1X16Gwt1zpSOQ(itLM0?8cb~N&Po(-;FEkn5m6}JnYs(f>NCf zo%D}Thg`wh0LZ7=two0-b_de)GY^ycN$dU{SJW}nCKJd*OHJF+nQ6HLn(*cMN?b#! z6hpo&gLTUPniXLXlJ&@1vSUm{ENQ#ZCx81Yrg`o$f&_X`;CC~SDrd^(Y z$V>aqc`vT$VaBXjTYf3GLMeREaU&M+*zM^|e*qqK2#=lbd@rtC6EhwH;<59c@AcN# z${*x4n6=Z;S(`T39M+jB&LD5cm`mWX$xH6V6$Q+c2O$r;wN;SkUCV>ePmT)(DAk{k zmld0>fFe}}(sQyLdES)w;fgwDJnGi2A@46)_@ESL&~49$I+RKPxdYGwnKq)?< z)B-^#UK@H)N<(D8U9Y=iW0bEhXj8SX5hP>Zup@mZW09`P{!lk~3QfMK+ zinUIVU7mjkJCsVtEn^Pp_4U43N(bckd9(5- zK;DC}S$-(mqizjt_{T-^O+TSXsSA0`SZxla+zUmC=LJm@|AF&Z8xp0l2IRTdMygPHi2=0HWlbFR z^gCB4b=naV%pHK^r-Am$yqHMHlJjl!@f{V*jqpy4zSM)Gr^Lbl- zzAc{Lbwn}G(G?wfQiKTd6&;&9f$W0(LkvQxJRV*@f-8EMsYeKTO<{Ua>JdWcy%OPr z{F?h|v<>-6iOraY-{wj`DAhiDZv6SCo-L#d{K zqW9LS??3esTv5REm_JYBUC46?^?pYbY0Cr8r#|xD!Hq&s@2=4qNriYdwl9 zdYGOL7f28Ce!@Q#J}6p`u4t)67cVggrThtbIbu^VW6W|*OFt;;f>yoc*hg_i9W&bW zw*0(qw?`MD6k2GbpM^S&OLtkzJmDh-)ZvR;%9a%a7rTI%WzjT+zey)MPfjEkB=sH9aWy=J1l^pFcMKhoJ|h&_ezK z2Oh1VZBBlz`jVR;!xcSDzt1zJ2YFes)P%gvqu<4&1UEl6>AcW`Qffl6Nw-zs^SQ@y zMFG>paJCd6ZxO6CLa|l5E5A2B3A^f=JkdK~-iH<0x z7&P<7OOzCYqJ;N!rjJ7=NiY0J%~n0jg^%Nk9%k%QXv;4i_UedyX5$>iAhi53jb2aW zE8Di2ABxcOnB9mca76*rM`Wid2BCNvWJi?J2>RwT5h5sRVIH#^@kDIH=P|nxPel5) z>hEm&1g_{|rWk}gUhY#2Lb0{KD;l%Hk|hQq&x7>gd-C&#Tkckz{p`3Wa76*r=SmqD zu!?!y6R8e?{3^B&3Oc+S3Q#IlPzn*0TJ$5Ie*#zZFw^`pttU_+R&UFri3g35rKP28x-K^FF@&NnD9F%v4uEJ~LpoALMNy{f2H0 z%{9J>wP8`zKRr==u7v#^3q6G^3YdP)(^Yn%RKG&0c7RrycIi?(K#|t$?^x(54+HgU zUzAE#5dF+nz2crv;fgwDY9ApV1={ORpm@}vtKV(4O{hZ=XFd6O4PcKPLy=!w^*675 z3Rm+ z%?QOxN>{(TaP5&LHKAxfdh+wWEAi47dDyLY1x35cV^wE8jVtPykz#H6dAnn)7f`IR zcIEfzVWAF1iuL5@^Q?>^c&zHI9QJ%>tDgAI)3~CJ>FuM96Cj^CwwQ-vOxD%!UU@jw zp_G%Mcm>ZuXGXlV>es&Z46f*5djHMF2~fN$ucI^lcUCr`){@JVxP~GIdpgtOdZ5rk zDXyW&6RrBXBcH()bxil8FVdEu*Qb=fjwn6E2|f0UP=``z%}@Q7Th%XuqCI8}`SE9P zMGrGZl8nQ4cc3#<8^7boXK_UjGwlO|e0*WE zgph}QylOt^H*+lOvD*`Q-_>5A52cb5zdJ-FXVK2HxT1#{>)?E(qVsGTmq31%3DSes z->K0X7Nz)vybdvS$S%)6Dyg?Wiz|AVUh`e8^n-lGj`^96$mghoqb_)ZPVlc?+@^^Q6 z4p-DMV?4v&q+Oo#yu|zrdy{r~?$?ta5{Evwd8k9Kz%_e1(`yattiH%D&p+fBDDo1Y zIJxXOTv5l265f_y?D^@67CIsHpp;^e??z%w*4LRSv_Tfy37>f$SM)GbZ3Cs39z&@Q z3O)Ejs6$c4sOy>wdb<*2p@sZj4pU06u;uf(qK=tDD?ck%Ryv@_SzY~Z>s6O8DGjB% z2l6mjD+8slLlH}@djFH2#}#$V80WR+7oS_`h+-F0SM=9|LLG|wtS3L89kwwb6uF>P z|KyeDaYYX^>a(`|(uWeD^inqHpnF0Oifi`tJ73Env;$EJ-!Wf(0q1({8q@bwSla=` z1DCuSfgbrMeDU?fanzr4)mr+zxaVzn3GVxBLw+;))(- znzw>tpIb*~rg_@Acw$jM`^;DfQ%_ zU%VH3P}Gr(+Glym=Pwv%4MY*wt@_tLd|2 zO8dMaA5mYf(g?k=%*r0SJyBZagi`uVbkk@teF?%}Ga|mr*UzGA^(0&U0PyhA`&ehwZSl#N1 zj=DS)pvc!f`T4kt^y`Z}v=%-nrRFK~y^1U0!%TB%kk2#NND+$Gsar$WO|@#tkx;5J zp(qc$wr}@WaYX^sdlx6DhK4*f|EBbVViuX#QSJWf#H|{IVNu*QuXNx2Rc{S%SNNb5 zgZa!>ecn~C;)*(^*Ast{I^=D*jgNwuuk6Zi;>n>7MV-}?pRd>1=nP7+3;BIAKgv@& z)4YZ&>X;EeUQRX5YaRyDs3VHHfR|HE^V&48g*xQwZRH*)=I;lhRQjje<~3Z=!%Q=j zQ2dTnm2F;&x{gngZu8orYphnv3KZ$bs>(L6#Vfp6RVjW}n?jzNhbpvdo&FlGsAHyC zD#%w7t?h@RpWM~&w*5n>Ln$Xi{`yPW{=UvkaSi!>T2ElJH($dQbSol*M1#W^e}ydVo!WQzPHmxZcy3}1pR5TuavlkQfQ$l zw}U$Swdy|}_ByWUVWyTDichw5bY|*#Ko{;EdQgO+r!&*Y6pC`hDDvUgajwU>@!{9K z^|iVHN-NgT{WpdJlu9b(b+V15AiE&{P|xQxTlHZ}yn!p>!%Q;^kgvDWgWzRfOT3Zx z$3Yj&`qdJjP>N5;cO!7uyzDFawd(Kh^9HWyVR|3MM#+%RU0B(K(kvD9%k4uCN}+{( zmdfTFp@{2NyA7!yVIMvqKBE<#^N!;Vi5BCBzC(s zw9nU9FDVA4@gL-)9{Q$zooScnA3_U7z0|7rzUWO{QO8XE0w`93yE^m8zchM1k(Y2& zfKvFNsA+kXVf7ZSC}5_x1M+7qZ&Z$iqORk`hSgic&qny5ltUm7(FBDr$ifGup2vlo zy@f04m|jxPP|F3yj#OT2v)Nl7h6@zC(4-aDD6tDg4&l``o4w^P=|!Da*OcE`{rTbX zZ{dm_rsvO7qzCy7osATsw8j9yYw8R2ymiUC?nmze> zI@k&Tl=4#0erg+6I_Pa&QOArJhr%84)5V#USM4 z2b;HnQi|O@0Z|%81 zC_XRNsUZ)8^$Vb@Zw);tu1QIK;=R~?)EC+1`G>THBHj6f(K7GjiaKU0sZgvV@Cl=3 z-j5zqS9Htg*DbLNrJ5Fs4=eJ~qGjHXm~YjO{_1^P(Zh_9OeaqNt_#Fv_pq z|KvxZ7ia!PbsgmOlIioDyZ z=bZZkT+zc!bphlprPV}GYCE8nruFG}J2;pHFTiUMZLA+>AB=a;NzhvI4IuKa%e*9ae! zax3KPaW=yPMfh6vo>P5@D|(o*o06TfQ+*gKp}bpZst?l|19bRH5hBQ+H?tWtC}Ou& zpSjhCxT1jR&y?Am6%?&@M`y+^;jZZB)z&L121PFK*)@5M@bA{Lo(_H~2Cq2zLtN3r zOuY-p`-2vPP#W1l_x&#Pph)*#4aFSUKoowg@W1*YuIOQ=7=*lEZX<6fr5N;_iuIOP#oz<3~_ib!W6^j0KSAMN8tzY63N;L`;dn5-sGsYIJ z`U`*f2`0UV^HeNK&y-i1t@YsPrvg!vpfjd1^I{YK@s*=z14#s;Y#>0Q~LnL z6JH&j=~rR=z|QywKN@pgs6%nhp8R5$$v_mPgEfuCKE@S2%rq+o`5MYysxhG`jqF5R z?Bid|yn)9js~C%Y?7d%R;aJ63?Bmqp?Z5ZOxT1jRe#dDn1ErZL$V7odk=1qUijHO-|07gj4OJWF&b>wkoPWVnL8rS1vXZLZagRSpcI3Uw^huI z4)i;ZLFNGYi2AIb;EEn*+C>NXy9q1?q3B)k5%pO=x%K^sLC9-io5zGwnSOD*PjE#6 z)9>Xh#UK;&jv-4}S`S7$l#zw{{`LJ_5Mo z9Y?Yzj!#)A8rd=Q-p@5_jAT_D-z%5f$TGvoVZ#!xk*tg3>)G~!HAW5$OKC&*M}HYn z>1cFimR1a1p;z<&SOZ;QS^Gp+c)+hiR~T3BnXgZ!+$&xArttpw*%6hFMpvfa^OBB(p3fBP8_N=1~a=%kn=$ z!i(qGxJ0Zlg3vSHGKYrlKl$?7x!+Wkjz(8zsqWDgmUa+bVVNjIS9s`8LRVNSED}^$ zdXXb}8WJoO3b!GQRA|-DO{yv#&27jm?Hacs^sV`iEBM0lbT+pkoaV~74PnYxLf>>p zzT*44^G{LfXoO^zE(k(G?~^|zAz}G4IYPp@>#vu17N+nDJrh2*2H_P-M1O?$pH6Po zvyYmh(qXZR?5tDo_1oVx(_v^TWq`zO2)8{oZbMj_TvA`?bM1B;LW$^)*bv4&x9W|j zo3hejzC(tko#!^>Fh zm04OxbcKGh6*{5ktIL%N!eiImq+|wR3cj#RE2Arvi2jK7BhQ$!(qTAcSo+B5%Ez}- zJgo2v{Zdy-S9sx}p(~7-#qEW4&jZehxG6W94nrK8c6S*AbH6_$O?=nBj955X6{xcH_e+J!0F zg`PLab@bc8$P8@FJ^VA3jz(8znPf&+=yORADcXf)b1AyQ8GjzS!niUUbU{xt8Ul9c zf)ddmw;@cypZ?L$R65LesFvxz7phGW`gcJs*9lXh6Mp&TxD8=SePJ2clD~ouycowGg6?zZQO1ChwS*xDrm!GY4G`cb)1>5H9?SchR zzNsw}F1kbL3L}66`)weN*R7webTmRTQ*T7*9ZV`@8ZR)~6dEt^kZ~a-Oc_a7Cf-O; zp+xjYf(j!xTJ;&9pQ_SfzC(s~CfiAfXZd&vTALy)%az2l@TO1VHiQvCzJUOG#1dEi zgqy4U{^&1cFimN5pp!ZMwMuCUDGp(|Wz6-;U?Vha7Z@ZI z6=T=%l+huilf7urQSX^=dB~B7m2c#nLBjoX8)x5JS2~*8kQrH}ZNA>JTenueo+#s$ zzQS9tiQ5pSk|Ok;Ih};Qoh%Xkk z316Rn%aWgkUdfoQFa=-eJ+~v*7&&u&!I=PvweGYqQlF{pbNDSs zBP6qIJVHoV-mOHT6M7JCRBjg@dSoLsY?w;7e7z<#U71CE}q($R!hW^}09=9|JR-?BbTvF-@vM_m_I~xr=_(!OJ5#Wzl!0enZu&|`BP2787lh?glL!gRb`6At%gnWPiCAF-p=Z86TS+T9Fig$jI=`O2 z($VP3^oiU{)UOjRZ5uV7Q6nNu^@ec!T|!qFA!2k4diRpd&^JsONxmt4zj5dEm5$~% zWTrv7(5I}eyCp2EZUkRA`qJh$dWJE$=o{*)`Xk2<%`-!#!*IyaN{)qBKHmGXdQzBL zE8!8J`BteYgg$>|&4e%lNVn%FGgLYnA(<)13O$W1L_+VzTh0;gxJ4sGw+BomROo{^ z>$nOfqCWyS>53UD9fm`OQRTJ`ecQ6t3_3B*G6`QhF?59~L4}_B=<<>&FtQnM$C!G? zN=KtBGlrJD9|QCtSi}m;9tu)W_{PhjJNe}O)f*9d9m~vT-!S5tcV^(5GSW%koUzi; z+=k554G@-{IOJzx%m#D~uldS0r5wpORZv0~BDq`j9H-7$=`f+Tp_eiXpnOu!5w3J_ zTv-_R+_T?$7tyY~!|O9vI+`oXEbm+7o`q$@0#PU2@BX;5Fx|7zi!<$S-%i$5^+yWI z*KhJTg=mX4XR36V?~tJnAD9bj8~ST0D9&BOJs0_Qi7WjsWffsrb45s)vdX@P&Q$4W zgk+|^iqLbcH6p@P=LnDgY3K@5ObS!mElgSEpH5~!)k8B?I-1*%nX-z|e`_UFSa#tM zeBt=(o7-Tk23Vd(C7y-4s{V-B^A?}E(qTAcn8GWcvaf{n6-GtDrhM@B)^|!g3sY4f zEW7y76-Ibl_3dqb%VD~0!{`I^1z3Du*fy>#OerW#dGei`X0CKJL6DicwZ&(|2#YJB zk0q~FRuRsAUL({qjJc6k{iV;fDjm(0Wu~5+(6@P810*cFu(`7EYahmyg}y_8oHH=r zlCt|wgoM7Y;ci8p(1U-0goLk63?X64 zIYRHNOjM4Y?8`8mM`>1?wbIe(%1nL2;xmH%=I9Dz+|A=O;B@nSzvNh9L>&**faQ5e zbcKJ4JSaJo+I|0xYrm1^7dH2v2rtk{=&EeLC5Jv6Ysu#a|)=EdC zE3<3>C!U2K{QDGMp?C7fDV~KJT@|{*xN^^Yy}xmn;#t0)M*AtAcUf?@N=KtBGtE#5 zV{xrxC&xlY*YJR8e&F#uc7jg+k1fa7`^`2r_w@hwtBzQ=Rxmu-$cR0|vhA8?M!u<; zIeGMKm5wI*WTu{<&^Lq71?kkn)bkVez7^3Y{EtQ7ayzfQ#@?Sw^eGroo_ZE$pD}t+ zx$mERTlMMJ%vR}WqEBY(h6q!?QWyi!uKo7L)0*h(8OE{_8)!H=3IR_gPXD<|hY9f@ zB4!%A3RAyBIPs0Rvd}lcSQquV?|iP((cH7lSiEH^8}ypkdT_$j9WY#bTQ4y^J2`a~ z~yDO=}xz`Xkzf(H-Co zb+^q?=`dejQHPm!9tqPFzOd||7fF8IE+X%l_JhLJE#x!~(v`de+v1(b;X$UX8+x#!_a zK40lD-=SKj?@u^OsVMX*aa)HHrj<3}d&k9X2qU~b`>o#Mwvfnh33Q-5a8 zN=I`WGX1yKOBeds&=&ZFWeX>nSh&awaT~&viG@B$vEHN5Z{sl4Sx0O!XQiXjm6@jE zh2=>%QbCv|+=LgcvO}pmgsBV*qX6{nw-V7GsUY8!3J;t(XQjh@hiaLr8zJ>{x zY2r)x{%_+p3_F@&K1fxV(5o;u^|k65UzxMg(Fn=(xVluyE%cdcYm$ZK!>YuyaM^o8 zNa$BSTtY%!)kZXZ!<5|e^?Y@VZsWkO%vI^o>Fm;!nObO}2aqmT$9!X%rfYb{LOYgd z*U2f`h2F=qKSb+kAbJ(0bYOEl&Xu?ZOwY4P9Ys8il^vOY_#ZlO>`*ZbQCN zGq4?HkuOv_%y-DpeQA@}ONmeHO=3F=m}XIgV`to{M7uB|mc5jqkF%(+*p33G)EB1Q z{=t|pR63g5kePPV31f+e?bBfDGz;hXUfhN-rM}P~4rPJ9Z@-m@{)i3vrbJoz`Y%*E z%y+1k85^0}hCVxIbHehC`I)Zyt}`6BA>R}m!sv6f>g`)|S2`LYncfq+UC}P|1T_=Hy&1NN@rAO9G- z^7Sj*SXSumAdxe$ljE+K6aHZCN=KtBGbY=4$`AM{^r8(;S-6A3(Of-@?=b6K?mbxDBBTF{#4xA6Q;BPB{`vM1RDFFty#Y zK0QyR!+e=y!t{j#$`gsw0JU+8Ichsv)o1z(t|k;Rvvx6)y{L$ypl znd+JuC(yq>Xu%hz@rH1tFYMx}z!VecyHc6T>l^B-`XjvZP0@br{_|Ek%y+1k>7Dh{ zq$`Z+mX4vfk~Y&N->Y_QbcfA1)f@8lhJeO;V7@85yG@+8($VP3^i;S|x)8cD`B%&h%=8NEmU&mjXafU&;}m3IIJpk5B+-|JMAKjz&nP z--Zp;g{iYGj5Qth_Jb>~{^OFM!c=~RG55{~?7(Q9SuHwk{z^xqD>Lol6Z&Y=I{Cub zMZjtixZWY5D@@@PmRAQ8USZr7@0odH{z^xqD>IE$g|Wqg*C2xB>3XVb;U*7+uF#Wv zwCYKrZ|k!9YO?RnsvK&7L(4Vful3DcuG!jyr9Pc8bB679lNj)dN_lY#rS zP$K%{HiUl9Hevqc*aa#b<~vl&jG<-Q&}Zdn**k{OXXqM!X79KS{Whh7u)NNMZ1&ne z7N~SILNe2efUvxa1R-JE1``C}EH{RbFcOr3Hkdlw!W7TzEwNywqtTU_vY9aUyRv5$ zjLs)}R>56n-Ob~9>;&PzIx#U~?f=dP^jHy4Frpl?^%nGTEWM~!{ncMASm|iuOQsJ# zZR{=d-*R%tPWBP6!3}F?ke7#a0s5}T$eYe>y3syQBU74PzO;_l{ z59>w<%S++W6^=STbcHD+3Vpo|Ek2sk7r+~(qVVS z6LgqqZ?VvSdx3&4Jn*Bqjmf^&ixQScA-N5quBty`Ll}9wRgc|qp-PAO4jHCOSw22y zU^1m+zA-`2H9T+Q-AnDDljF)g^Yu4%-l1Cwgg6aYrxwOt zbq)V^Oz6rtuG}+UAICBeH86~5Z`HpXv2dlM(UqAxuR@;!u+$g&mFeqr?YDn=CUoVS za-Gn(Nm;I&{9Eh0zp?4Um5xSNW+W(&$AjK|F)H@fZh!uLo9-`W8uit*L($U<8%xKQr=Ie_RR*vKw%bi{GJz|gM zHhPAs8Yx$`D-X;!<>!_E{>4g1qboBFdWGJ}uqOwEsTLJ(F+PGX^vD^bPKMCmvO&j) zRR}O5r&Vvc(3dJ5jjl}Z`JJFqfzX>|+ma%TY}Pg3-KHH~qFugzWm{zumM`B?eF;;v z3*#n<_C3E;=_t{TnHGQKNmP2fbs&>Q>)SSJfZs`@ywes&p6* z8K!zeKAvQj&4j7^3Kuvd!YlMzg>Eqqu7lB8XSN88%-^bKn{km!N24p#>sXsQ6nZCv z9$3dtPJ>?guJBgqPX6tI(w+QU(r93q(s$wSEmG-dbY-T_tI$Vo)H$76m?{e4I_vCN z(pTt7_8aL6V>-KUn9^6i(TK1|e|V8fM{^r8Q}!07#Y|zURm}JB<~DkEDbIvAD1GIt ztLl&73sdm-e|M2ehxrcGGE=k*VV_$;9sxmOL*&&dzE+=M$OPO-*~>gZnfYxt$d`_N;>*&pq9SaHe0zZ3rU;d*UP8Gt z&m)1}4R}(zLa&f1p*)WSp56~#VG6!5-hIFWNT8?DNeb_KBNwZ5G`cc<5O}S0h2;f9 z=n8#K$EMPRb9{cNM7uC`KZLP(GqB&fuf=ogSBq6T8eN$&ZPBiU_}zA3yy-DBw(*r&&}(3e=i$$Oxzf?-%1pJ2 z(C1`r?o5~-5Eb71V(1D}HWPZ)cb~#5jD9;0)NT3YN=KtB(|=3V#{+eskLp=A=om(W z+ckV+)t{F1)yXNmLhnGbeP&=MM~{N3rIWv0>1cFirrpv)e_N6*?3EKos6u9H3Evfd z7rMfzpLuOW{FaU@uZ;jDqCaj!=pnN8#f4t|a;3w3hiaM8-D(^9@(c?w9YYU-^+k2^ zTKC3n2ve;h^qD5|c$Jb8_(FPV<)HnvwZ*B3teH#Il|a3Jh0!oF1;_>-$j?KbTqm$y&G`3qE6@? z3@a(ZxD@R#c>7FymmDih;T3x1SdAo14eo6}Te8y8=*skny;{1$^h}`8muKu@JmGWS z4_#rzWY2yZ+h_WQp4^NFTlModELrJjbY*(IVI@?U_UQ`C3zR7-!s*TlU14;YdghxN zKKaG~kXgA|ma23#x-#QoTDI+gUiDdvBlHxsnqN5M`=KjL;T5K5K7|s|A0?ShNe5+Mr#MTbPnt=rcuDF$z<1uXaB7%+ct|Oi%0! zy+XD%QDN$D2)})F=n7Ntg^}EYdb01yO75*bTB_2~=*o-@n{D$=+d1XyZzr+v3WuHy zU118ZFl`4Hrg;9<#!FW^8eN$wxrJVisLUzOU|Oma9>46*ON}J-dc!(4!pP4QXE2s4 zTJ@#Ja4C*PS7ub3e0>&7*;|+zAmQEnHM+xga*Aj9`oaK>2p?|+C89sFnJ~t`t@?^* zmacS|?~tMQMr;XOK3*YPHWPZ&X1#jh{ddG|2vcn)Oxa8r10o*eTVZ6SqtTV=9cHV| zgys8;M7uD(xkmWP+`lN0EC#TexZz^T8Pa0Y2Xl_HMx4+k@QWg5df>km?Uz)Ys5Uy}V za~rh#VEI;y+I>)0)t}mZ&=ci!1%LVZm#K7^?~tKCm2IO5`S>;?E8W6Wxe2$JdY=;Q z!j$WTu`a^W4w#aAmpzuLbTqm$Q>`NOUXbYuQz;W3@XgQ_rsNjJh>zX-;cJtM!c^D~ z9KTGZqqz;4ekn_Rq1QPU?LyCl7VW~*PKnzPrqmb4D@FRXP$K#x6@)1jPMUVvN{9Il z)iTqVPUz*=>KtK;4dJz~#cc>vYzTe!!^-|-UyBW4ijAGNS+>&A+=k4Q357mDu-g#& zh|gL&;cwRXWyuV}6dOVxm$B(;Pzyb)SXKY))0eGuG`cd&=Tyl2LZ4-_R1l`2wD5#K zgsw0JUzj#~2_>RGZbKLgimm#kHR_`8$$nPvISo_?L*CN^z66g z{l}C+`TAX1v?2 ztbO=$m5xSNrvH{DgLWx5K z@@Frj%vAP;Udk++3DZzoxaUowD@@5P^jv3q`-BqFAGaY)!QW@ey&60rra*{*$>O@!c@wR+-Lbphw1VxB4#|s$+L)Hs$+#0Zr=#; z@FAG;voP{is~+E9zS7ZzNM_2wLjQIm8MtdF-+w^_LB1&_g}w@48%>0|s{V*cVamX_ z&9OqI!+eKonW<|kjPY;Bd{fs{zR!Iew;@a!Sm-sd#iTIia(QBKrxhw4jjqhtameSl zz!b4UAD3C}Eu4OnUwI1hh#**A08apgDS)kuSEzI}LNfg^UFMLP`vQGA>1p)|g+5`$ z%rE{FNzItaLQGG9weV&DV!`)=J8^yzLiV;kTa) zU13UJq31~=me)mX&dD5&kW8e66een6H;!7Ciuxt3&1Dg06 zHcUBQC;NsV8+%XwEvr+l`tldK6i1^g(`WR?OIPT#+m<1OUf)@rCA{~p&=sbPDD(+U z?s;IBN(JEjRadHXG`ccVT`Bb2u%=O%27$uC0>3VGr7(q8m>!4|rV@U~K`T`{8eN%b z->A?N4bHwZFpUZ>S$O42M{^r8W6Mvw7RDyTj$upybq(*FZvPVP zI@yIrEBHd+{75&VZzvJ{k^1uWD(rCOx-Sl`T~{grUAJ2@gD{mrVJtZH?c@|2@=aC2 z#b>Wl>1b|4W;|`su7zo=BJ>h!jjr(SBjPrMDK>Oc>rn2z4qgSnTG`Ar$O@|4+DzKVRm}(^9^83bZ2vf8Ry+)#? z>(@ew=#O~b;K@}h9fm`Osl}0x_jIl17naXylKF)@-`42%3|-ecbMo~Sh_jTS>o2=n zrK1s&=?#H3sY0(eY&0T_~>_C7$K$H^~N$1t9d;0wL@9=>zvPCogU(iQq#|J`a*g|Py`8%pk2tYwG)80+t5-&%1g(;pVpUkAyz#yiln$^~k?gxi1RwLZ8lNhb7>D7Y;FU0|9zv|GmK#mn^W;k`FS$Zuj85e*S=cmXmn-z zJu{%&pEc6P3SM$XBS=HPL_!N$Y%2O3i)W=#@`=Yz0zU6Lx%B0X4}x$>TCe1 z6I1gfeDk`v4PnY=!gwdvz%CU5WN~h>H7XsAuFUjEqA)Fj3R5jAoU!#gPld4)g#YTm zb>f2mr32StixJN*`>7F9sM0PEVVZ`Ysl7&}qlrG5DcOWRGxxAEu`oKmUBe}|ZKAJd z=yQ$C3iJ(AuGMcn*V;ICshifQbTqm$qs!HQ;0xnz)dTZQt?cOS z*Q|6jLNdJoT%uY@7%N2`!&rmr8Xmmi?@MK&lf9I-mA=Aw`n7MEqFuhJ5jyOGH7gy> zZOBZ0EMZJN@DXk>)`Gf*XaA|Wjh>-r6w}e?7b6 z+Lew*NM@>bh3OkZ!k91U*22%udq~O8!c<=gy>nx0=97IlSLa5Us;~7ASi92E+=fgq zp|*k{^bU$W;3@RBpN%Sv8NeNPYi@%<0+=4)73!+`LsytG(kXYXUFk62p;~5Y`-R>_ zu^X;qzNwQT-`r^_L+mIQpd)s_H_1V@zamF{z zLJH5X|4>pv7!@O>8}!U?eQ2RX^rzAd`fVJiTsLmiI+YId9WqQqQ~9K2Lt)wwB%HW) z+=ej4hA>871G{o`B3t!?R})^2MpvfK_uJ4#7;9f0JK1Zbo>E`F@0=RCLKm`;o6r|; zZR93QwdkwUty}46bY+%rLQxzSg0oHj}S!>#(h$!Zh);#ratB9b-z~WXmn+!$zP!-sO=~hrk&2hgTFks6f0qFtU<3R$X7Jh zphWaXu@ZV_I8nvw{3E_r=`i0RLtl`v^p#Kg){ih1E8(3#kJ}KY(k=AaPrD6as$_&7 zSGG8R-J@TtbTqdiGxd>#DYpyL2wC{(&2byTRJw&81RG!oC89rKLzt@iHyaU6S0%+A!-?m<*qY;uB?<{JYua|ujlCM`#3{82V6S(k&5kO(8 zRfPUHqv;A$ExP=i>sLA&U768JwrgRkMucf1Rk+27!%M^pQz;XA#b^;LOiL_V?96XD z8eN%bURCH*(w3mYl%T>cdDN5}R5}`6nW^>`dXky0Fl{ywUi5sU z+pC4~_9xz?1bX&9UDe3=Z){NMXoO^@KA|vGBf?l>VUGZK|H?;r`i`9-{Ev;0Ke>07 zPvv#5%&!oPcyU1AP?4iQiluyGhOAZJ_ty<79p*b^7;gz_8~VhgWmBCP4*+(}_w55C z`sDi`i@s0mb+0`ORlMS^Z{O($Pep%+!_&(=J|N+Sw+Y`tMEj4cEd{ zs|mfsZVTnYm_lgPH?Fo}rK8c6nYM-qy`N=kcEYr5A$(%NBTKC&OvPI0uhyg{?wgQA z^hfTIZ)!bO`u&EL4)YzVWkw&oZRo3?)`gL;Pqe-0Tg;GZ5=CNiVb0^;3mzyaiycV z4VkH%DfBhUCzUsZX*Ztm)pz1HgsG$my|5FLd_e_F?b16x*tpWs=*o-$wrinJK3QfE z`fQV}stadd@2HX)gefx!{aH0D8bXQakJ}KY_J7%PH~v4|op-ckWznzaHEtA;BcPyy zm_gh#sbv7YB~;5WjylN$Zt_U@1yl4vPb)QyV4BRW@zb9dr20io zbrAFwU-<=7!w7D>z#*ROV+|PVg#%$KW>`~pZ*u6*3sU`}`T~PZ$L&jEh8_hKGcca} zvM-4l?$-;yVA`(-)41}0zx})*)e))(<2)RJK26l@4NRZz1kapS9gXT{kI@b+wPN*& zuQC+$DTodvO#S-O1*v{f(<%t)dpb&3FqVjHjnnY{PaN7NEa(TIHGl>ARW2(?ptne8 z(wgnIgH6CuzDV8mJFr>eDO_77o_?{ zP4hy~%azg@OiO^^-RFg0Fr_o-{gGBd#;sZf0n-3uWX@j{qy_^ucBt)WrlB{gDp#O) zn(ErXuf6}Uwiy9a*9Ll1pymrq#cYWUeo>I>7d7pifN`qL-c@esVZM@11YBqN>epUQ zZWv3g10lc4W!a52Ev2t^(Ju-jYo|d??FQ(%uVMzK=^D7raS>n8JFnd--k_gAPh^(y|2+c7$p90ZW`& z@5!2;z`?rm7S++Dso;NXezm|M@7DB`Xn6Thy91_fX0iL1El5o-)YROA-oUB32fe3M za}Tb5RiqdAA4{)yYd$*K5RFui!PI$zsW}1D;@2|sELV`4ny6{@2TYIMfoVnpZurq7 z+U5jI)eDS~qwNP9rqR$hwpy+r)h}v#n*``lP_G51Lxtck*Q$Q)jf#d|V{C{z5b~>B z)_Y)0OWXTiyIetJ?KG&~FX@mSm`;0vF*dZ*B8I1(QT zl{2&G(_U}A^Ugc(1>UXFGp1O1ZPS#ESf%0udM+MCFL3*;zbptrwgbtisZ|8yeIoXm zbi=e34!-iQC@x^?1;BKC08E3NgV+9LL8@QWG=B$uWa5j3hQ1G`Wdy8eFLh*FOu^Lo zf`0PKCeF5YXqZ+}o;&N81*v{f<3vEW0ps9kPnaePSf~F}_ytpZK@YR0s31uf<7xzlMkjQAKbPde!-LrU~GNZ49*ZIT$T%98Uk(k^zsFfwbP)cp$O=OUn4-! z+dIuz!GmszV1OwXKzF2E7`JM`52k_lF^JWtb*7XY9H{L8>FvwDSYTGN66O(lCAd8l1Labu=n#%5JP_f&=1&%Yp%> z5#Y4j?Was+?KG$<*}?R*B$(f+-3Ha8pso>&I@p)>yDNtytnTOl zCOBYv#t-zAv|~6kHM36rRhj#w`nMy^k1qdJL27(a)A?jDJ>doV5~9Xg;MylfFu;`T zU^IP0IZ7jgU(B##L8@QWG|vKkBS^IjOuN3|A72f>V5((ceCoko8)ujrw|!Pyu^`ni zYFZQpqnqe8p#Snz8aME?A0FH0FPP#B#$!qY-Ha11EA3d**@}HnS+O9p+5p8=AHG~b zTL=0SRc#&UJ8V}F4Di(bA{byA7lK}YHN6E>4}0btD;A{sMfLS$o3PuL-VJ>YuK67p z&wuu1o%TTZ#hQ{Gj90eXm);FiYj)ETD;1>rMU4#YHlVjE@(cQr7JHXaU)Ja6J+4i5 ztSQ++UvklsIGAcTn4=jI@{o z;)Kgul^;H`QbB|rM>Q)K;unjzgvxF(GQ}Q2H(YBFe!&!dFm-KUiawZ{`mZjqazSb^ zP(2El5Dd`QloSjwjvV%7{rSfyx4D2dHEy8K8MOC4jwjKmuGm|-Ak{BwTFe2xz0$x2 zOsfiDXPxSIOg|ORoDYQjDwjFhXxhpJ5!z>XO--BaptquGRlqdg0QWhkI+`>U{NIlI z_gnJ6_6^@e!<*e*=^H?=;nq3~gsHe-O|z(dKCwzcYHFgU#UL&_bfcGsEe!)~sLGNa4&0(OMal&P7 zG}csG?m2Ijg2>uwP~+hZdvwRpPcPfzwLQ9H7(2eUCS~~gQ4tIhH7ON*~OkMiIoklP~FN8YU4f^(>ZN~Iv-Qvy&2G&$2!5GU9b+h+p2NM1DzqeXJkRk zY`WDG#u-I>>%3Wa{`{ZYbOt>oHzT`2Uq!Wv+(@(6UaJ+P#t1d7k$^E(>*?m$Z|Dn0 zH?58)P37i)zpb2aNj~J;UQe9)qeohuf8T}gBNL6(NP+2*1F#LCRSz(o+dK1~)e6EL zwq$~uiYXXJ(rqMVc*E34KJed9zW=f%rcuQzRWD){hkR{7Xy~PWGNtd9FRfmXnqH{! z?2CPU-7wx%XkTA9Oe=KYi!+|+#eC9K@ZV3qHY@$#lMkQe2CdxH|NSnMKBAFIAL!-F zT2%XpyrDPUda&r3%~vl-O+Hj_tftT$f#+Vgg$-_OG}aTwA=19^{lAXntaWmxvpBhAT_;Ep6b5A$NVS&DInK#2PH>dIe`k2WgXrGui^d9Iq{I0py zuL~l-8ww{(_&h}Gge6Tk!L*ADrs*cw`^iadZ3F+O;vzrkKRayeZT&-c9B@6gY_9t6 zFDIX{O#3nS3GbUQ;oH-F@*wO}Uwr2X{=K>WyI8${!d@F~_U87pU(^0{dw*;HfB$Yu z{kzux#H0Op7r3ydi2soFjl{}_Z(1S)Q)9LJ8NV(Fw=b|^gW4|dTWW%-tp|PG(k7(# zN_4~YlpFZxgCjM;|0y-w(Ek_DGKfZuZ!c7wmp$semZO$lV?y5{u%>JvOam?cHtjte z^RHhQM1R|9P<>3UXPrQQU8pUg_GIP8`l4v8mpxh&cU0C?W5)m1#!iFuw-(5uFpc+q zyVM#5;kPZ1QN2zm7@(gWv}u%mn$s{AEA7*qhP|(y+z!J)uc=*zVW5{S3x<7~(=aUz z-G0~_1*v{fEFec>zHhhMBI`d}RE8R+Je3s_V1UwM3ug4AH3 zrs#uy8d60ZjO|4G7!G)21Otq+F(zy3*T${K(r$h9n`;)N`bAB-55^gSzHXlHQ>V1) zj5Vb*7>@%CbThxoWyy{;wU_hs*DQ#vodz`x??F#VYaM#Bx+7by>kEIfegtFuZ?`48 z$8j2^4ot}ornf~bb<3Isslhqtg)!iFrEGe5Bj=BwM+Q$dIi0WVm zc>N0Xmq>TFSucotRC)N1B^1wosYWD4?c2OEB%>fnEr0-P2YW4WFGHj=KXK=wE-y6XIQ?&x)k@lf}Ds46_|HI!Fr20io(FfBe2bexC0ZyFzw6y}_FuJ&d9*4yD1 zYiw^1WKHqK>J@fRI)Y`^`CUP(UsTV1n;6*}c?^ABOMb!V=Uh40j7=*jFTU> z1!9;|15By0U0J6fH5jO|jL>aBufKLsxF?JQ8GYfAPu5_J38S|f2>Demi#|W)X=SHu z?R`DVtWywKZG+R)7;f1Hr=iElj!pE0-Z0wog>7(}_4I|#Y;yrjbr6h0WcGp{L+^jJ zUV6n*>lCE=MUA!eZUe@?V^0`mvM+pK=kUwTX&3;;VB4PCjbB!&yW^R43R3-|dYEl| zWiJLY^bwQ|0(-(3*7k+3-Wq<#|8{3e9T;PkfiPt^R&N;&AlYYLWZi<)V4$Y#2IG+@ z`vSXRlu7#nyWxVLnbP(+U_1melr`n=hjw4LAk`77FMFIqe8G6atta#-oJ0O%oqOYO z1jcA{AS=JhW#tNMD$n!Wxo$yZwSl^+9(`L?>}9qj}6ofe|l;71wAEgG-4z3 zz-5`2fu8%eNnzFb^S>`h^@|!?MO|6_Y=`m}tCx1YZwuV&!)LYS8H^a&j;3L1RY06@ zncw|4{e3}%9bt?%?fX<_@wXnS{(`9lLK>MfIg#d+MXxfIdXDRW5rj%g_s%#m@aX0D7Q&GoCV zSCAS7R8O2Ei2|6)BdFL5gcir8C|a+)h}u~xdo<| zf`RG49M~KXe!(=r0Mm;jz%;C#`%R02N%f2B`{;KP-*J4NECXXBsV`jeq40|}l}XSm ztPK%uIBgiM%1HCIpZuX9)i0`t*`_UBS$&mT<2tPA@Cvx>SI=o1H=zo&O&$mOTYig78bNWRFFb2F4bHi3^*gGYQ`NwF;t^NPHDyx;158B} z^g|UoMe+GZ|4@(`4AgLBkMJ9&&qsjq=E1(KKfFGIfi-0}=%r4<0CB=)sR4SaJCT-f zkFTv?5Lr9I81#09`a?d6&=dO7vUWoGyOU=-w=L~pl;<(s9B+FV3O$hO+Roa3{eo1# zsBu=I+kjr_)B=OCo7tE3rgg(F))aj(7Q6?#IpqRY$Nh-@gTwU;QiFl&YxdUEcV+dX zW1r~U}5qjCX^USp(r{F8qyNDT&R>W@I50@&H;o^JLD z;1t>%tnYj8UpyBkO$GnAYtR$kGyN3pll`}ya358yQl=8C7_JRu^;}$wmIZ5+Jo|?4 z`hP4)O-TR+5-)gZAJb90rnxneeI|VJpV@-=lV5*CtXSq$;Mw-)J+@K&e7^vR5 zXs`kLX;-bGf!@xm(+97=D}pipw>wc6K_8gu`D)My?Z@Kx#_w-fkm?sTI?%4HK3UMt z3)Zv+06zPL^V>lV=ttrVa&*HyBsZp@4A+&0ckA z_`%Jp-%(+zJXoU>9Lnmbg@RAryJ119U(^_EbQ{nYt}S7E!Zc&Wy2usb7fd|>=z+9X zS`78KshBM?_eKS&eo@nwIGEBIj1fY=0au#of_4}KdO_NO`~}mwp>gZ71Otp2+(@&| zmKznM1_L!3ny#$r^$=Lo8B4IgMg#*)(FfyoNdx^9PPi->SY!BPuZOyNqk_oV5qb`4 z;|WWgDYuWw8>Z8J;G(BRFhI}WE~x?f7~VQh8%!Fe=sz>_#s#T?>{wIu&-=~B1*yS6jRQ0GQA$Ja|5e$+7^e1Ry=}=0 z+roe~6$UVliP~2v4bw{X&1Y_0km?uJm*Z?1u-ky?JUSQ)1$|jxI3)aHP06&ee(mcQwaE^q=z|^wo6*>AuVJ(*c9!+CQPYw* z=ueu;FX%s|wjEr0$M6fL_=2g_fvMDiF%GwHo(Oiu%Yd(Cli+r@zC@dJ=w<+5Z4y(u_((FGQ6 zHeSK4TW`0=MTS4yM)=Uvi!XbXb$om7yh%ayw;iF!XexC9i?_gP3cwhX_GLZsk2O@2 zregiyj-rme_(RA3m(FO2MjF0=vFkHboV{@zW!&)Ct(z32CLd}Hxw^9Y4vI1rt8W2n zn+GfxMW%wj3Zvx!Fco4j6{Z{J+O#0mFRIs4ZFqy;Wb3>R7)vMp27Ka!m$Y>lOg#ta z>%w+W#y*p6h!ZX=TVU)c*yn3D+O#0Dc7)#fT}PW# zTkO&{f5AK}Fia2XVfE(E8jF!;>ytVKseVzTDe1}@oq-)mF>8!h`ohEat$yuDidlU= zYZLaN(DPRdItRbjDM)pMnqIFA`evJ6@B^lV1<$@OA_%601-)Ul&Tr6wsUCseLuMxi!t-)CP>o?#nU%9MJXVBAXcSc~KH=S0l211;0S!!T)NA`H=Nb}eI zH!Fy&9bxRvbcKFKL46W8da~QBpfBqi-3SKORJ_4hCLZeMRJ`AQaI=C`zo_wGL$?8a z$fc7{VC)C?Wu5cd@QXD?AN2BUv!J1F_E1eGz90YU<^`#KQPVR{ptppNG4ugr=d~|f zXx7WyWXGC@AYl47E|_v3Os)4L+iYHt8VuBEWV#KQ_U*t_+Vyv9M=-#Y>|k04)6ICX z%TfbOlcJXgn-@e@8wi@}!8n4}42;5W13|+${9(^W8h+@k2nOi!U5i2pMnM_~Q)*z1 z)vA$Zm)W)`NDT&R{B2iOUk6hm#OnF0who;9P6PvVM>`M<&|gKV@#y&99#3Ida@{Qo zQvIT)hmt|BDe6SPXoBn`V20~1J+&Wa z0A}$bs)uDk|7H8ckbMo(@VO%*7+`90!FXKCmH-UXc=U$%Y*~=%7d7V3-3Clwg9OvF z@8FY9gaTU>VbzovOwpftxh)G)gMsSf4L$J%dNZPjbis6H9-RN%V{I;g zX+#00Z?}Lr;j&x+)6{f^W40`ateplmEyRFc>a-98dI26I7r?o9t-%-*`r|BWg0RNg ziai|s+?EBYj!;tv1p16Z9T1pSBEU6okNAQq*+I{Jm3A;iaQW|a3sU`}dWk)o$`1NT zAiZG%^p=kV~kN@pX)G}H1q^(xCz%*jqZjWw3s$bN27mFQ9F^u7s9Z4~a z+_xhshKElKzhH_l7^iCNgi2Ud%s~ICgQ@I?-qkHg4F;-bsGU*h%9?r{te!Ym5Pk5x z%OV(HYWYELHnr{s;)KhJ8JIRT&-=nw1(CJWpvLJITY50`GlDAZU^;pW-a7r2Z7zUm z_yPKkua5kJsnl)P*{UGbFKX-vSS}cP!rBzTa>3Bo3NIu2;9;wVU(ln!8MzPo-0WsL zTreGQ|NGch1*v{f{g=-m*}-^ae@_@&+I`{2P6@xqi=g}L*49X+wddJ=Vscv zAk{Cbr-n*97?1DwbaRR?*2UilzhG)q!FU9BpuhE`vr=bk4Qp&&km?sToo@i+eMt7) ztf7|;odW}xTH>lUf5DW_V0;LBpufclmqj0ITHamrw557&iay>E;-2^@Zoof3+w3m@tOoLtzACq`B&l zZ3SZ?-ZN9$9DvU;gIgb3dK*fs^JeoVq`BqH;h9k_TqEHD9^)$`w@(n7TmTVH5jN~>Fjh% zS60tZo5J^mF=_1!Xa2-BZ94O}ei*_Q+6J=nt6Ua+tUgjb9KW;fxNSjX?Fjt{yQ(vm zScdD#>iKJ{0rvVFvo5e+^*bs|)e37IIkNA>8m8!jQIJNOAK$cXL258i(*iD-CXZlj zW%c#9Yo8avz?xcbFy7uj)XizOxbz&`6{Pw_O-qMhdSCYYKHa9J?}y_V^)%Y`586-3rfgX+zu zf&r%0EimoIfp-Sko97^yz~&^+Vkpz2w5pc89x99fMoAdE^9PyF~jzL!^cZHEnc*zK*03Bk1eM z8WMwF+$%x_rnV0B605Na7_FJT1LEagL8@O=&m-jm7%%nc>E^UJfOUy`!Y`N#A?T;X zG%^Q0%*RpqzrWb_1*v{f)6=`4C%XzEm`2Fps$Uwkxd5g@2>M=*{DLX>*VuRaf>gh# zUNtVF@Po0j*Au2z1#55f@C&A~3g~+(+KmHKI)D7W?F&-YA{e!TL*d`DHvc{LIMDN)R=>5j`O*-cPvQti|TdZ63P{rUg!g+brtXjOWn}sFBl0sroZ*7p|wq{ zIN`F!4NTGh*;zXlMAmMD>aUSjdj-aE;l8YYJS_ZTP4x)$FstZ)+RfcvKve%X+WHCS+awvw14M_oeCmrr$J49C>TppJz2e$X`KPj0GLK_t4`dxAT{|=BZ0b&tg6V` zy#&(($lz8h)#Mx1&8Z2*8c9EtHI59AG@DN#dK0MjMT z!9Y#3H_&Uj2F_rbD1f*9;HI|C1JeKp^udwUmO%sJgv;7IFjik|GxOwK3L>jj9#hk} z67)HTf&r$Lb?_gPA{bz5dck<5iEU;Y`r@(nk=}ZJmx5HksA;?ddLdM)1Jmpr{Nw}S z7fiVT#$0FEfN6m9=_Ph8NcD>v^TKWe`WQ_ESTK#Vz(wc1xlML3#TWFWXc||7sfYjW zfx8x@`bA9x4bTgrN*$QSJK$sg6+7fichrgK`9>)d+Cn zbrC@@b?IOnt{F67D&Am<@5K3cD@Y9ns{hmljAy}Ayuma-11Ej#mNuQil)s?INQ)C7 zPPnXigK55U&UU*MMAlA&8Yj!U!qlZ>P1z0J{JRJSm}(j53s-h{a;Tq*o!*h=+8cH& zNcD@FrY~UHGY8}3a9@A>=-J^HYw8QZ_~6PwH>X^{nsVWp*>^8U4F+l|bzpq4&)$J% z7>kQ`cGPgXa%-ClU}|GQZ;@=2J=D!KG(=QW# z!Ib-;uL)^31LB0sf&r$w@R{>=FNmz22Gxh;cF4sZ7BNgKWS~dz3MO;l_l}BSfGHQi zSQHuP=9CLqJ?(ZVI_SuD()q5x}`Iz24#?N!LZ{7MI z&j&VBXL?s2QWaTDbY?p`LVgWpAzHgzd`S*2nHq5dPkVnW$;A z8%*oiV0vE+c<64CxZwW>!%U))nglQ{B!Q_;fT>RG@%$bIsi`Ua0f%sG`@tTOG)sEv z5ttfg@RU1hYL4pW)DL5g-En(F(lCwwuK4br1*v{fWB1fveqiV=vHE{7&GEp8KX-fE zB7&)90%OJ5UVdPh&gu>K+_NCnFKV3f>^5Nf$TOH`+Tb&rgkLZvI~XnTKtF{OE^867 zrcvhy?%A^-vUVEOw7doSi(WK30MoM+;OD2-V2tT+y@*>&JQSu5aJDb)RS-GqHmJUv zsL3S;mmJ=D{JK4jC{!GoLaRgfAZ)Ko3OIAPXnz|^>c|6DEn zf~k!MV;V8g-=^}6HQJ7mW{oTNDo70mYT7#o{cNH|!PcV<{in2o18z4O!2naa0{zu- z_7J0eip4OkS!_14cR{LO)U4z_CHk^H zdr);WDoiZ{H~Wml7Lx2-@;~=3Nd0BhG!+2T6D?q>3*h6Agd;GOSkMm?+Eid5M^SP{ znh!3uPeJ6jEA+Dvb0{K-gOG(gw>d(Y?#>4Dp6InaL z$ltCo)^>YBA03=c!t!_XZXdw_QxgQn=zgf1y%6fXFN;3DPeH0*)M${q4d{7fJFh)q zdUO`+uZPv|n5@xU4~1S~_a=g?ePiE(R7a@3rmS-_U^J>d-5i6XzHqBg-rW{aZjRzT zl+|-kJNjGiv~NMGBUEoyY@5dpUK@IEWtn0JuMOj;?BKQGL4T-@MuncCo3ROm)gOG+ z)+3lssGM-~z6Gg%QPT;2(6d`@ESTybc;)%w7fb~S^afdNEa(ZVHum&6Cl#dnMNKsY z^d?um2AH0P0jItHo;G2@m_!a6&^M6uKCo*ym{gGJ2sJ$_0QwnUMG#D#2>AH&;RuXj zfX$N(qYe&*X}Q@eg&z1QR5}4-3Ih#M1DcfP>mVD z-rm*ksBTUz5?0@c)$|mMHfN++@0I-uQvITOFKOLzSJsr>Sba^%&fN56-Q}<07pq5b z2kI}FJ{=3D;(gQ)_Af~Fi<;sKrU#I~wDbsG`sI7ujsQ%>42;q~Y`_%Xt0(PWkm?sT z^`W3QxtflHsiy-U+ammesa%2S)3IR6-`nrszaZ5wYO2nlZ+NRZgI*Vu&fu$8gxdsD9=PPnXigHdrtny2PDpdhk#gdRxEHL#>-8Nu|}9N5f!Uz_Y;iar?4=0Lxk zN;}qg@rk{EvPC7N-wc3w94*ntJ9j!@HS0MP589D!-A5!~ag za0I4$1g3ffrU*{_-GK$Eeo=juS}6&pu_&185jg2*_qQ1erVIsRpl+*)hN&R!dG>(? zseVz@lQ5u1Q0*0%>JfPIpTaK~2|Lz+@$!*@5GPz#p0TE7t@9@wR1jG^4Qfhu(4T@; zbq0N$qmymm9Z%F?jOlOVD-uItO6PljaZo|3Bh=I_f~h+OQ~M15{hJT8=?td)1tWh4 z&A4@0x+gF-BTpZBP(f-iP-8&VZNR8Fec^|84!>Aay8)&O3-YU6<`+!O^{mevR1jJ1 z0HvvErwH_3<1vPLV5&#pg11I6z!ZJZ*BNYI#ST!0RnZ4isr%l-2N$FU12rw;f*wJY zIxzKC;OcWd*yh6c&AZZDfiXB43RCn~-RTs^2kLQ#XN?U*)pw22(NH|8s{FL{@u`psA@^ zf&O5OwPt-;&-&0qZNg$r#SBc{F_c3Usbc|f4>1ATsi!L zDPcjM4%-ZOsGDQDWY3FUen>&8UsMm3noZDO!lQX8m|mp-9&%#%1wG5Unzk5vTW9^z zK#o#B$j#~K-k~!bT96tHRKIx&qc6}`d+cGYo-n=k73+DgMliq>eJ~EW+G8Y!zB+y& z)59;WerQ3eU({&py0Ut?vel2C&?i%WA=$Zk(ZwHbvm5jo8h^!r9l#Q;?Z?>Q631iEmFZ|X15e$ANl{zq%4u-nft%u-u;@=M~NcD>v z=j?4q&M=<(>j|Sw_Jxxk48Po*k{wLvWkDaD9E0E9j}I$|{C0(2VKqC(62}etvK}?x zBc9Gg#kd8U%u!7VWp{B=^Ko6B=Xukn3-6nn+jF%kSr!5Rqm`{J?u!7WI zMvZfv-3E+v=RKj99DAU>FPt_AN8B8bpxA`h&`Zv-B+e5H{HY+-5vm76ul5AJ39_xu zo^Fo$LSOiS*&c1vikqVY8pxXJAl9@N^i=Op1*v{f(@`fd%?Lmroao>e*sL3VL7%p0 zss%XO<=t-yJ!l3`MZIbt8-DKJDi#1g`FeV5?-R!N|;ly{-^A9gb^^2Mg z$AhtK*wf81uImf;IXe7ua~i3Fmu$w5X*n8973ZM$A5oC%7d0)xf&OfsolLQ3iVRbB zgJ(Zm{n|4{hJK7?8u<&R@(iZ@J$?Bj3R3-|##6giLk(jHVKvn7hDH9?Rvgf4nFohVXq@Hd|~(McT|`%6l;{{k>=GGjwncV zgz5v=^XVl)Z=bEh?Fs!{@)eXEtTW#g5d=L{mXfyUWa!J4#}T7hzJFvvsw31`__Y^1 zR?CD5wtm$U#!`vB*wL(C{lepI)c{is1$~|0x^jE5qhZQHFtteY?R{iHYA{gKDLyck zm3j^6KV>U6ec@7_2*$WoYcimZf~=MebTdx4EH$ut@t#a-tohd?3nHsM1ZZmNox%9B zhdl&n=uNIFEZ7^1V1OxqL0@vT=gsUPKtr$W8Wn8w<)aEx{i4P%cN@?%#a7jN!t|me ztcQQ(iMBk0zQk(r9qQ(EB4+XyM-`+xLX81Nw*kF&>tR|jJxBmv{_E;!R5yFM+Lo3O zt3MBHg?}jYmQargopsew1*v{fW1ZjLO=}qQ-<~iIjM%$r%{n|a{DPizUHpRa(1pF5 z)-V+_FzuJ!{n4WfQiFl&(-u`LFhw6s=aRrT-i%;?DSyXN(FfDHvuD;ix**jrYBcrs zH9|uVr1BR`M>D_=E%{`dzo4%Ms62!GDwicYn8rvmo_TaZWVKBnQ&Ten`iMf=4SJ?r zNwos!JtX{sDSyFKf4}|K(FLiFP-9TkZ9p#!nx%q1FVk8sxYA?c2=uLF8&M4Ow<$xh zMwJ|CR`}U51*v{fV~o_5)rYn6i`Anqzu=||KGil~VCw0>w1y0(4esurjwwj>i<;^Y zm-Ae}*{WvS5HQbQx*hyye(} z$l4Lc%(^S|+}F`6ZcGn8fwNs0!2nZsgE0mk>Zelio^Gz=3R3-|rhWnRB}dg?@Y5PY z*fZPx2K@2|pK03-Fg;KQ#{74r`RPW-6{I>sb?ZgsFX%^`AEE;S(^tsAb$?YIjmqj3 zR{gK63Z>2XhO(yoop6cyMC`I-Rj6K&g0mR+G$X|VLXRmfN?^@J_2Ky-dqE|c5eg& zOw9tA`U%>~etPV+&~SH;zN zfjHr^)Bsba%(egV1(CJWpn8mK;%VR9HS~pUTP3z{?i!}X9QLfnHRuqg4Tyy(avEp3eI*7z1OVZl8!TOiQdQ&38gU zs$bM}SPM)mkYGBj1$Jh6zD;&8bzY$7;N8R*^s1o~xRbXzp&->SYO3sDI`s#7QBh|N zUjEzg3#P^m^znuoH!!91nS&DwQvIUFVrI7i)94FKjVgHKl<*6t$__?jKG094(vCH? zv6p=O&jqQ$K=osOYGXlvp^WN2n8rxpy>CY_z*OnL4K?#r(+A>&%W?sXzQ!38U%j3%~SKbu=c78U0Y`W6}L_ zwBWKQ7Nj~t^{CHq^_(!J+vuLPngbb zar42qRY#+;di2#GWA$9HG5=83l#)j+a#BI6U(~eh07mWZHDGiTec{EQdC609(p0Sf zu~Xd>pZ>_Za%6r~u}U?ZSb6K9WjHW3G+L^ zw!xGdV2oG?a)c8uOAV}PtTcVce#%7FPJf7fcBY`VxYT4y@@ljQ((>IquX`3Q{A8nx@oXTDbxJO~|%-+SlJ+ zc0l;Wnj#3sw*OE!M|UyOoc`u11*v{f({KRvo=1ajFuu%ZTL*^I9tyu;iZAE`E3Ke_ zY323hpNtly`bCZP6?=26VT?NM&9R2wO`S!2!I|cNwM}O*#TSfugS|P{5GP!g?4XZ^ zbR7HjgGUP@Yo|d?TSH*lk^RT+6~v>-JY zsNtw9t9QJb_hU^{5b&!vL@>aV8lXR0qp1LxTC<-ncxpkaUsR96$y6&aK6PyC9EP61 z=aLKHdb7XQ=EAsjXQn=2jHCuaoN!q#U`+$7b#^$lAhLEE)L5mqkD3^IjBMSmC-miT z+ZOH%cm90@WBlfw2nHDEg6%6NhLJ~ByKg+TAk{BwT5bV-*;2_4rgbdvz`ulFFbx#I zH1P#f?t^Jae(a}CD@Y9nst03~Tmb!4snsKU2;VU3Z(lg}-q+h)z#0)8lhq#(wT5CK z#0i(>0yldPdnkqQ%Jokxh^!r<|CDA1SiF1E>Kd39pTI|!i(r7MDFD4O*KPoq=E2)s zU^kmozo=>P81zAc{DNsQ20Zkb@C$mFyW~FT&4^|~U@H8_f8g|jRKKXPKiO?SFFESU z!SvKUIQ6;k3#R!un2vOTDZ4LQ!G6l5`bACedH}t4`{I*f>dUbH^*e8Pc8@h+JY8YS zONJ?eiywb_L8>FvsFK|V^nO9>I$%002mW@?>S$Cqrwqj!uM``|nu<5p)Q7I}(&+`M z!9YzTH!zLdK+k<`N`PD49l-!oEd%4(sbK@A!AWP)GYV4uqNbr5=s%^}4W>pFJm8Ce zZ>trUq7VAaPh%tyCtOyoK%WL^#Q3*;&M1hiodz}S6@Y%TiW!(rmw@lvyar=Tf9rK$ z>nm8(Cd@hao>7qM2sQ2IfqrC9D+-{uz*^S(w8iW!)S*;`wlS&$kG)YN=|X%7mF0Y<+8 zKe1*619V3_(2RhwDKQY@gv*-ES*|&=Ai|E&8`bk^y|MTSFEw9a+C&8xI6eG=DcQkz z*{>ZLFig=0J%ZL*+jI4^OeshW25KxY*hh8^eK$a*9rUELMG^bRuHldW8NmQk^ud@B z*hh8^QzNtDZ>JQb`bCWn*FJP@=qs;w2GhPGN8`bABxDCi?|wW46^t-u2g4ZmQDFBt1sHc&T=?s%j*?CmK9seV!Ymu*ng zmDRg8#TTm&T*pXf@Z7(JUod4i81WtGW}I+YtAf>=dYvG+;OA!*MAlA&>QR_VFu*io z1k;O(z`MTw&o;}`TCc(5-Ql2`iAk{Bws%7J-c^Q~$H#pbL;TKHt1=CCZ!Boq@)X2>7t+NYKgMpe( z--Es+rU@^YRw2Oe%=xc2*@Zekqme2Y`x}D>#0i(>KA1LOm)hm*g2>uwP*ax*`iTiu zb})6R;2$=KV1Ow#z!eA7o_?{OXkpU-O6n?=p zPXW`bOu&>2pg(P3Pp^(NTYTo6g4AH3dTGCm!Vmg!Fa-ll&oF@pH*dAM0H)}JK2)=_ zCqw;IivBShpHqu5t4v)zi)oLJ2xxmfd=oFje@;HPAk`6S1k&DiYv>R0 zsMLYp;o8j0-gayF%}LeKs4(R|*0fIudOfmz;E`tO*Uv48{C0)Dj3!4|(kTz{kM~E6 zz*Mckl%Zf6ss8RqejLdSYtyzg?l{uXaDM#%$4^L@_*bs~U_kp-)gh#F`MYh8eeJc31fKK7oK@-M4!KnnldJ9G(iI)PPi=k+#L0Hq`C8}=M_ZO zj?jlaXH&be_|mR=STKEB6?|#d3HQG}^9Lp@Fshr=00V0r*c{55R^*1;o>!3S7d7^; z?4>M*KCZLX%bqX_e_#0Q+ToX*Q|^PY*Jp2GF-%8p-@g95f>gh#(bU_QybS&0P1Z2> zgt1#|U-B~Rr_T<*U`lq-n?76jwl8@Zdb@En**)9r=NF{;3odTv(9m7uAO@8Y6+elAz`bOlO+FSw8pPHetcke1U!tNu3Co8gtMC zIa#%P&kM_JCN&tS(WP4LHjD)vtKEj4`!;*(3%{{R1OsbIcF<>V9R zwYx7Yh^(CkHKhiaPI!UdP-wOY{`~S9j4}PKS9Y5Y4}>ZDQlf}_`wBNi(r7MmVs%g2Bx;|m@6(SNcD^ANv9Qc(8p$4Q3qq`zy|7u7oQS-!Bhyr zSSPfBx?#!%Ftv4;&vbD?YA{e!BLl|rPOkw|lMCMSMg#+NM-ypeKo6CkVi~up?oV6e z;(}DasNPW6?5W#;K2K4ygWgMCOyLKgTH^g}?t|`k2mFFj_Xk3pa9QqS_2rJ^$o*GO zySN~-c7)N^*;6}aNl!U|F^RLMb__pqPy_=^brAH$0UHF`Lp+A5(vAG{;(}DasHxO} z>1iP_=CJ(+od1#V3#O(I^c+;(2UG5YDf;vM^pb+qV4y}v&~3nYR@)xpF^nfr?I9k+ zpD*x%HW$ED2f^5=vZr1h>z`nnm4nxO;)9;f_A)lZC>!=NHbZ`u%i;^B#_iM{FD;0yodz{M zD+c<2S*rnH8mNOetXKVx>Tf+$cBPiddfXBe4L+6 zAJ*D3%Rp9sm5b_Z)|dj=r@J<|tRS-5neoKqWti#_ z=<&6F-`+eCxGb#-=$WED`uQ%ptROWQsA=gB^l7-3{=l@41ODu|2nLv170?fCS}s_1 zHjH-CrvJ_51*v{f(-|8uuLc;#`M$pXcKsK^FE^*$2jhK31Ko@hE(-?MlnWcIczHo& z?KG&-S=)#C41J|n(FfDPCvflYP1m+&U@GmPXNny%8R(}{A;g-t8xA?)@`BW0pvKd> z-3IhS7uswB(@UJezw8yk08?QA(`FNh6D~^)Fr~)nFJE2|Svw7Cw1oCdyrCzoE&bUO zw}!EfWXEO>6tlnAgOWnU=v8e^Aj!@Id5YSH?E52a#DSiFz(_i{f zTj{XI!oGb}*D$3s7|R_a&9nPXElBl?>MK+hqpqy(=n*1_)eEo=n1R!6QT>j}no1qk zIFB@t6(?Ml&R8R@>@`vMPc4Y7_R?xoQ=0?&DJexCOr;K7?5YR`n6evmN4B>()Gw#D zZk~C@3R3-|#=2;?0n?cT(BGYX6@3}F)JH$uCOeppV}of!VU?}M3Q`@R##&If0b{?c zCyYS$h26En5jV$Hlqdq#XqC>VHKrz|@R@@fIcfFrQ%z zdPkbm*1n=3)h}w=F#&xF@DSx0Osyz*{ZiAn%@>$jZ!o6PL;Y>4N1L2=MM0`xRF9D@ zId&T`o^9<3V+p-4+~ctD%gvs!YcWUweHLR6E)0Y?;j;3KH8mq|zjH-FWbHJlu_<7S zY=*HzWQ%Nuaqim|*$hARL<9qjdSt6=h8`nr3e5P6D+^K`p~k$-UU3nqh7pX)Zjaa+ z&il<7+H?j}I)ky*IMRIO$SVs{9ie(5Jc@(`W8JJLj83F4T(Vys4TWj^yz{i1q|>=;S60pr24p3n<} z4PE-eQ$Iapn{?b9zdRk!CBHB0ofn5+tezS>P&L5R z6o9EpzVO+r3sU`}#^O)60X@q!k^$3ETX4n?eWXoiFvS=2-dO`VFy{Ls&5IMSE=cu@ z8Z)o1tX^T&rD9Ee893w0;TKF*1B~^Yfqp8rz*wUojWnOS{OW?#V4%8RZJvVuQ%}(n zf}V8h*}?Ce7{LHj^ubA2y!PeQCs`B*`dhD7+tR~g^)Zqyu#Yr9o8g**)L@{d)Bt_* zsM!RV1{mP_uSPJyXpzSB%dv($5aNW(g2Bx(JsfF%z1lSek+ma?Rfw+8*JP9_+~^0c z^z0+J?GI=2!Z4r(9Ez>IgLr z6%4HD_zJk#$3NQU0vOS^@w1^9Dymj z!BpzTt;%jNW%tU{t}93l25M|4bsNyzXJt1SZ$Y!J+;EF?A{bywb}&BWY+ZR+Z8>YC z+36F5f>gh#X|fEab24B$c?%v}W^P**&~wn%>WBJePmL)!+Hbud1{lQs>%U`l5&b^vYG zW*8e)Bh7O6+)$9}7d7?WVEQf)7!Mrv^|uqJhF`3yvV(DQexRFi!e!CNnkERRd}&%i zWbHJl>A`)_R}wT(2h)QR;59RTtW9<>B|Dgk8JLP0n1&GdY(A|ZH5jNd|LrzldT<|1 z&(nghuO7hw-I3-CU|RYEal&P(0j3q3cdndP5Lr77YRVKab>*PfK^+4F=R7rn0j5j= zV^?~pUydajdt>WIhXtvAQPYk#=yP^kM71}z8b(iNZ)`PO{LSzSrs#v|eEYanT`CxB zn+rFGE}|gJb?VHETxC_`n`;dVqEOug8j9+R8uvYgiEdZAa)8{zysy7H^|%-?}G^xk_KS=cAG3+?+-R zU^H+8-Ha11tEE_@eAu*SsT&I-s~sXVH9BlNL}=)PNE_Mrgt1j=hX~Dj%GYLVOCIQj zX+0JfKrb#=(p7-bppP`?9Cl+ts$bN!ECu>F*d{hT-Ry0L4VwGH;r7+K8R))Ronb&e$}*CyZ{jFMR)v5nui`QgTdIZ)hyO10hbhEc)CW zc{I{I_l=thB5Ow&Pbk^9F3s`E-mU5s9XET|XeX6N zn%Vm|6{I>sjm3qotR4lmhFIfi>b|VsTE99P6-Ew@34QdYhpfhbS;c#iTW%^y^^59% zYvcZI1A1!MT(l>QzM(H%?Sk;j&Cy8N1Mr4v?-`8jwv+dtzPTXPFKQ&6y*t;?!z{mG z42Mx_lVBID*hUw{3Fea{jSx=u_f7xa-W{t-$Z6;$FDQPnq z!_;2=VY*uiQvIUFdE#yZdIO~i73hC!y-r`&-Cm4@#hMBd7zd^Yx)~>2matf(Ww6J$ zR=%YmvUY@V0Ky*MGK;SW=r#CYetgStsYO58<}X%na_u;XeI?b<*OIJk*yCG1);5aG`r67+@;iU=;76Zce3c!5`jQkm?uJ6Gv;`V0zIX z7;AR+?jWplf69}6(p2z2*7p-0yShita>MtxoG{_r(|uAOo1OaNJ4e7b*MAqg!#_$p zVXuugdvp8QukpVczrVHrzkfHS{$2ag+KET|@7kGhqLB(Q7>_0lWNn>T=~;chTMNSf zvTQ?5#|%LqgWHl=PuA2bVcllSNIvjCmVEEl&}meWOqGCG#lGr5)>H|wI_^hZ-28!C z3sO@PHKspZS)(BLglXf6oABZp+8WgehEy+$iWp4k6?f?L><%L#sac^7{sjJ zGW>$65Q4s_qQU^;gv*lsi_6?m5Mf7{ zhCf(*yrVTVFdf$if4tDA+hhk*d_g~EZ0j@D4;!Xr2UG5!c+?#Qslh-^XBxp+uIV+P zR}DLX&=+2_a}CCrFrCpIzggq=^Pah*Ak`6Stm}3g(1&|Ejsiv@?8|!Vtr1_WshEN3 zfI5g1E-UThH><6?Y2iByB5SunO>c|_Q)LIAnQN{#oxzm9U}|K*RIXmy?aqS8QKvzT zWrVIU)o!e@!q%5{hK<87))ZgR_bBZ^!az5t{KcB4O*7wlXF+N(P*WQVdZ?_e>o?#6 zmxf<3#TQI3g#c4yKHul>DoAyN>cP+ne9%{_bp#!ZF2)W&8!q|b&$Q_bdZW4-tr_U^ zB+Uy!FYP*|`KwLuDoFK<>SK;m=|sTzSWRCzag}g{H8q={KNevNK?B{)uX0&I!kY4T zo2eE^6InYAYHByY)Omra;(&*p6u|&fI)mv=^I+;VE}HS~f>gh#X+j423{34L7~636 zEU@8UUkkrrYB#{N%M7M+1*YbD%IbF)qy_^ul`GI^6&k;TY0LoLy!dB5yT=+ZUUD)J z@~d2y>{vY*$I@FpJ9>9PWbFvk*%d6_PRcLnQ?5%X-r)2HRKIpi(a>|>)(pplUiY>0 zf;GkWJ#XG!km?sTWjC0rGnld){Om*F7fi_x`rfEj=V1eSWmkLk@t@pNkm?sT#TWFU zi(Z2O#(t1JgKYS%uYRsgXE2?^1XKQksdz7O@I3{oeo@o>3`{#*VC(P4(B5S8X^*lO^>I}x~X?sEsvrTRL!mX~ae(j^U@wZyW1LGjm zK-Ls}tkK4fH2tsrwIDSZsPULjS62TiYbbg`|EVbigPV_^?elGG2Bz!=V@^pv!vslM>+bt4#9Q==co6UKa@FPw3? z@XO69zF<6^G1Sd5Ul?iTyx`t~RKKWhJpsStXamTeFxuF@@Y~0PUvBm=??h_`dJVNA zIuxe-{ox1hD@gT=8WZ(y1A4VmI)ia$wJ+;$o(sQNQ+&a+1_q{D2Bz#TE8JI*8Vpol zJl0D-Tg!wA>dQcHMy67{!8yM3#WuUasJ~;frUQXk(^zHR$@dkc`bCZIsoQ{Qdl&Rf zxeCAF&-VzwV2b|u&9)9b(9JmEvRuIGUCg2MWrx3bUqNK;2&1#^3VjLChVeb2x4_!n z=I<`Ns|I6C)^yY#Yf5&|qkkNJ*ZKba1*v{fqyE~_EW`AO0hr!I4(|MgFSUINnBE=( zru^M?@B0f<9ijRvrp;ly4VcC%ptrHgU+~YJ>S$CqN5vTvrtNHQ#tE0DGw3%TM0_9r z>-`0hwIhsP(zZ&>;tO6nH36nqo`UbcB7y;?>;~hprjcf*xgRJq%m)in{i4P>ANwGfp=XM=@4(dZgEt>i{n{763_XHZ(&m8t zDwov-&`Zt^)P=!Y4;Dn$jxb_mYi?$VB@0_~GmQS%*4zxAdMx4#rn&(7RLgovTXPGm zdf115_E15pU)1!D7tqJ;>S4hc<@Ou>-Pga;Rt?YtY2|q+YXrmI^Kke>1*wiuQ^JCW zEY8T?)u+Oawsl{J#i-t%BqKLKb*I|j+REWyAUtt zdM~NXc`V*~+c~|StlnNB7#h(6Yo3ln#KxFFRps&`)Y zvI6_uuA!%uvKx#utM<8F!vp>pe!-X!jma9PyzCqGW=+*<-&-FpNcD^A&B%%P1-+Nl zDFD#t`<5y8N*}}1FATq6#K>OhW9Wm=%ZV=-vdwurme?#8}pGG=^ zu}R(+-ul6L+jPbnF&dLKPL~aY(GiR^FK_fnL8@O=Pf6?OZ4KGbn_L?N+8VN9It2jE zuwwWHBSyA{Y#2?StsxuYgv+82Mwzrve_Z-VL1gU+Q>%g{jyc(ix@B@n~ZdVlo8j~1l*MU7>pZUcHpubm4pEuw-8yc~YPlK5OC$#uM2#3^1JXm9Mtl1n9-=ZrVvO zDvk{U3{%2hvHxQQsS!l=GpiaCf?f!quDBrVse`HQ^VGU7n%-*3(&8_SSrVD@b*On)dm}Q4s{wfC`*r*7@5a z3Z^0odX{O91Ez!>w`%PDt!@8SkQxlsXo9*8=u;1^*MXl=k-dZl8C-Gg2nLusAkeGx zo#Zcw6D~`3Fjj2r`+nE|tst^?gx=QKK+fKKZx%z!4DVK2HjjDv{w zW_!cb@4xc##|u&&p?VFqQBb!5<0x5A=vg+I_+p*@oro{!3A+|Ede9wRMhyj{T8%WH zTlevTRKKX{uqYVM1NL-tOtkyLA1=K>o88=;(ix01AokL{b005Ab%g3krx691dsxF5 z=2;JGc={35k#(ttk&+|LCGUBnAoZ6~Js4Va0)05GArqMDK6u|#5d|=nSTG%|15=3w zJqml%*4@7B69uWkK=mfb@~A7T7hrX%Sfl0d%lhiKzSgEB*3_4Q@jaA*ZjSsN3R6LP z_2?%GQiFl&gI+BSfxe2UV1Qm2&ZZ!Nv+Nqd08?s!@sb347l$EExGeggcd27EZGfH?!UA9lLe`MQ9YftWC5ln3(%MDEk^wY zoMU461*3+J$r@+Q?Xb65z2!fKQa9IKPZp&5MNMbjL0`^N#|Qc&x?}hS7riX}f+^WS zFIQ?OL7Z?|^ug2*F7}0|3Lv zEY>l=4d`iQ6Yak6gp;e^F`>suj>d1+F@v{0@^nF}Bh<8?0_K<18%9%aFRM5F)Ef~& zFtsXRY@OT7>J4$iW$^_)7c?rEVU4E?B5S8XO)qZ;eW6?3F&OKjece3I65nX^7i-F2 zFuLQRZcgQDzSEvANcD@Fq7SA+CZI2{+f>VThYgoLF#Lik`k)^bwBl_~8UN$yf>cMS zsS^QxbgdZy7%PE&{p}wf4o6s11VIm^9Bs4YGX;?&`$oN~{vj~^GMGj(;9>KBvrRhC zi;A^%_SF)@*rc{k)*GfQ+wYKP3Q}W)nhuJ9spNnu>A*9#3%_8B5$GwYmH~_^X~$*_ zeXZ|s684P8?59j>Fi^e8J)dq7^gUda957C^_GO)RLk-55FqPQ$SM|$7SyRc`Wx;0) zQvIT)5)1lzj?E^lh8m^}1y7iLp*GpURB}My*RT=AP=A~H-@othY(c7DRByhHAiiKc z!r2qXDpOxL^LpWzo4pWjMs|a7zTRG!Y8aVfPwU_GY(c7D)HI_9)6OFp%SwIy?RU=$ zzgSaz!RWi~@qEJ+-^J#5t{~MfYTEJx(}7$twG7}I@B3Dp&S1o7tO4U3qqV?>DStQn z<8uX(U;E&islNMQ^{6jA@R#w+SX0{$df`_A22%kBQ$5=1!siN7BZ!(>1~5*t_Z#rA zW2@gWVJflh&*-OyvZfgQ?1Rr2q&h;4*+jPi({V~LRao8peE0=DHEcCtre>uT?Wex? zZBJ(#F#qcLf>cMSaay@6t4|&uqH17`^}4?BzVFtb8WpCZ!p%NXwO!hQtdX$ximKzE zFG%%^npz| zFpbQ?bW#FL$^P&@FBGKuMU7`%x=m}TyQQE9LqkMaHxIvHN_NmU^p)MZ883EO%fIq{ zFBC-B5&9U|Ch7J}y;;(b7>qZe*)#QqTV5G{!IbQvKdGQDb^WirSdi)nH8nw?FYc*_ z1yd6Q?lH1Ro3LPtAn2z0Dyf@K55J(VPHQ{~rb4*&EH4$LIzo*#)oufN*-*C#dLT7V0T2FX zq!s9CrS1t#r{F-Ga9LddeFfuqMg_nX+^zK+qE*Psl_I#`13Xg|hFx3SxzFT3>w;HBm2BzF!bLp20QiFjSp9t(Wptnem z(DH-n-~`zF#&EE55_sveK7vkK9OJ;xo@jIhG*;) zjzF)@x6`M9{3@6E1=BL=o=?485LvqoYI?US=yP^!g8H(aa&tJsnugP0O1cZb^-4kN zFQcZ%sKKbP_SPxGJLmjfTSP%G3_CH913gsMI}d~@%dn;x-MGsu1(DxQgPKY#=*3%& z8yMxPubW@kAcBE4^%`JwngiX86D~_wtf>G$ciSrkk=35pG}Q~g7TG`_s%f18Oce*5 z{^AG*m#!px#w@$=PSQ(~dpZBw`7Nq(`jk8 z_N=ENzshC((U~XP%_hRG(0d%))#?dT?dHber25OFvZi##>aDjHtiTk(aomr7@UGWi zD~SAdgt07aUr95IujVNj?(-};2D=&`bACs(Ku>k4yNrwaOthXFBtv) zpaJ<+E{iXiiue2vn_m-II}NH&!_TL9gMN@t#T!ihAh`5(<9-d(`W4o+`mx6RZxp0D zLQO+c(5HurAedTjaJ!HFpl!auRLsCM)dEvGgDIUi-0qEn)L@{d{cg~!q~Z&v{cdot z-_>A@HDEe12=c33md;>G=RIgM$V}V{J^++HXZ^rKHZ>LT8p{MhtsaXI0=Sy)sew}={KaSh}pLgN$T%zFxLc?Ov zPYwPb=H5G6va;ygp1DQbN{|Kw0Z{}M$wQJPiUcL+q#z2YNEB#7BSQ-`lEVN)kerc2 zaL6Dav|?zrNdlr65VJ%@Q54~;tLol$e((3syPmaNkMCZq*3>n%&#pV?z1znelh!Ti zbU`UDkMHr1sR+Thw{=k^+dx^<0cFt{e0lRsP4Iu7n*Wb|=)`^?%c3Ej7?=~#kz3oW zw$#Kbm0*tB{xKD)sfj9$4HyGS@6tip8UmNOu%_m)0j1J|Qt83)>vODSW_x8SQvISz z=LyE&x?fNhp21C?Nxxtoz8E#2#21W~X(oNz3R}N26{&tvv$k2|Y8W$4_X|eJ^C>2{ z=^E>`Z5}9v7?fn6w0a>1BahA|7+YWR%2cEV12rZ$H_*m|@_iXFTSWU1hT#FnWiUW# zdchooj{Igx4XoKvb()i&e`P9CgMk_`x`beW(Zk!>z`mob%VNFxu?z;7T4B^Y?bve+M?Uz)Do2gLwRTRwpu`u9!r+|&D9woftu;@Z*`rKqFi@o#0pnbQS7%Umn8BSUG8mv_HyGnApZS3?$*@D0b_BKa>QtoqMU84@ zM-}V^O~a_pK6C=*1#9r2f23bfq7TYvUqGC2S?di-UwG`NUY&}#wcDUZ6nrMsTI%X4 zm=$N>H(&M9kG8o#`L}*_4veI;g}Ra7EV+PHM(CGc|LRnv1_M=c0gTrgyzqmvh7Epe zW(~%$0rTbTkt0v#vgl)tB6=>laMQnDor<`%>ljCG{96lHqHXtq6_}?F27dFyPiOS8 zN-lu$9X?yv8T-wW?7!UT-&2w57d20^_Zl$1!0LX%IOSn401e#w?`a=vlO1a|$V0cr zDNFZ@Rnqy@bN)RQseVzV)VcMVKR>eBZeH3!Sx*8N{Zje`^WCXo14bZiZFS@**^O1! zDHr*jp-Bw}s&rmpq=qlkg3`usgv)XPYlO8P&RMfx@Yxk>y&2AVm5M=WXCGWe(*!DO+~6-)F`pH(B^_)h-q zF(f+}3rJS#?87RCIN`GBgHre}eCO*^5w~_5)aVy{^%Tr=qkXqZkAwB=Z``O&b}-_5 zB*6f406CT?`(cyY_j!FPQvIUFw8{N~;m8X=D2sgHhsFK~Fyrl%njw|@~7t=2& zJv$hkwO4jfN*yTCUwnrt1*yS6mFRgYMfG|#rP`i_}a1INuz&S3Dj(&m8C^m%0m( z^@|#5HH%6IF6i<16>d;wo8T!wO}~?W>!lrxX4Aqv@<&N7V2xa`mrFX$`5&2DkQxls zaOCp^FdB1TiUV`-Iq<)|Qv>f>P-~sqB;1nZ)<*pHD4F^@}Qv3>bcWF9?*i8Stm~r(aM?9T*LxWtp7a$c(>i#0%Gc>8eK$V^jl+$6LtV4rqd@X|k zN-lu15DVgj%W?sXqT+>N+5&GVh+Df2YBbkA%mZUR*ykFcw7}pN|IT25k_({hi-HkI zZ*%tj%o_?){h~@PfDzwc)8>GY&i66Q15e&$v&em0m^93@t|PhGlYR1UFQM=sanlYD+I`@EEcyO>Ulk-8Qu)B>YJ4vWB(1otFoMzs z{OW?)3gXsogPPNEJ11lq;|^b`0&|dJui6@xV`^$nILc@UYmCBdrE26>$yBV_e0G{w z|72)VgMk`V)5rc`tW$bZ1j@W0Tl z1*yS6l`am9D(%4lbKl+0aT=camMz;h9*j|m4d^<}%mZdGNPRM@L=cpfIZz@9-n3(V z@`OK1I!~#cMqU=#+=K~Q$rz^AXuU`*cZOGIGg zzQxzx2{e?1eR!@n6{Pw_jp?|*6A0#%tKWd~P9XT)U(+urBUUgz4dCqtDESLY0iI{) zHx;A?16BG`P~JEK<54!cA2i?!>uuFm98f9_n7?l{_M5X+u{Vw;-c*q47gd&sz<77s zD=e6Aq}UrrhO3{RenH87P=-z*PPi-=z=*;O3gJrscvC^#+I5VP<1OSq7TN9qWgHD| z^~($fD76ffz7UjL0HqLa{?Vo&H5jPbKKB|h=c9c`nM7jUce$Zr#n}XC}pvp=W z7-wI6eH4_D6!@J{1_P8_0C{R%qz7evbYj|@3xeGi=}~2&4wMx#FdBC|XE5-azq8;r zZQ;i%br6iDbeq16{AQeRSuS9e+<&W5)=U&l~1j z|FgONDir+_hc_azf>TG_TO?O+}p88@Kh@8)~Hr6AQ2s!UJ8XjE+p->Q{i zr1Nd$FSys1)zO5bQ737T{ znzJBo?KY@VuE6N6{8vc8Jh@=sX);{mz1z3B07~@12$gN@kNxH>44r1Zljkf*^@}QV z4N$&&0%q+V_}}i#I1H7%T$>#gR<5LMrFT?=!3U>GW~+`r94oo)p_^NRgmfkRk~wPzV{Ex z4hDGpwbju?17^vwFV-1GQSm9jz4Ojpkm?9k>Ms~M=qo5-MDQEL2>it>=?KiCGIXn) zdBG|f3d(u+?|*vkf_N}`4Qf;z?|?v=dVqiU*p6+*0i_^;QA2&q4@$!R?S{DvQsax7 z=T@x4HI(>*GS>j-JG=U|9@a1?2-d?IO3Od*zvnJUb%ZLXJizG7d~^*;0|l=9n~WeB zp*o(P9n8t&*fFB-Rb#zP-dd3A7geUiU<~6uLqQo%gS)Nt@it*WNmwvSyY-URG8jg? zaW=#FIll7Nf>gh#(bU^{nVwrCyZtl`*2okali0Q{d)~qqCDGB+&<-Ln7Lq|@-$rIfs8L0>D(io!I=Nr_pe8eQh@z$ z-Fza^ziQQa3Q~iCDwA|DT7DltgR%<&e)}DtXpH4aG>p=I zH`xvT@s5lym>D{BYpjkxLb79(WS_)KNcO+It5c8~4AkuDtU4P;{q>Fjlw=3zd(%#B zvV-C1NFP5N<^fr&-G-9R3+&e^NcD><(FgOVRr?JnO9$Y}+f~0qx61AoR+%2Ia(Aa7 z)e));FhF_X3OwN>#MpZraO=x6f}oTuFxNTuviD_5Xo_nvQ=w;*oqHmGuz3XBPn z7jIBHT=4imXD~n+Z-DV;wGH#^$D0f#yFuxH57}|vg4AH3MniEPr4Ed*IQeJwz*su) zkEDQSet73LyFtlrFnU-U_Kf^dIN`F?z?w;Czj=4nyajQq{pOviQ8w%|DE6CohSB7D zn*(N-YQK4BIO~)Q2AEGCx>Y{rh*b*1*Zw+hL8@O=85Mxh$oOs#D3uO;;K}ND*nn{q z)T+kFQIZ{NglZ^JMqSCHx#RSF>}8|+}V-UI*JH!S_hHrcUC?t}7j8i*4vOLkDY zwy({YuOM#iHmI4u_Rfi6z7=NgoEXYhC-|d7GZz4F%ljsXp z@A&0>1*yS6l|dkw?-KVLP_+n{DKvo~)I>{IFhJ>X zKsn?BO5s0s!M7Ep`bCvW2g>mZP?q1p>t3sV?ZaD!xm40=?)dE63R0hpDvc_5gqH?S zSWwmqz{fWIRGXoov}RxoYi)mF?2aOT&!js4_~y42r20jbu?i>|3P$brJ_Y>ydFdCF z32|jP;z0bXBQ|)^^2O;UIRvNW&L2^F~V$T zitQVkX5Ifs=@*n{1kA#3KW=T9dDLl6TXVsJRKKV)PzNIz*7WuL=D?fqi}i+g?;6QI zbc`}-pJ^UBN_KN|q=tW2?u_FXEJ*c>8g=1jI%_cIDL&H#GYa-;OT$@TsDAAW*M=FR zp<^!X+LtcPiW4r&Zcv($iN_Z#h+A!;+f->rK>0ceC^LHSd-r58z(^e5mIWh^tnl0Z z?|a@}km?9kx+gHE|2`xJWvB)&GUsk>@dhP-!5CoJc~#s0HI!rrrIC5&z_%Bq1_M<_ z=AeA46_myeeDf!2FiyJ<{EwY2*nW`*`C-TZ^`jXR4bhNn1M_wHky}YCE-O7)rS!}_ ze0xFM+HFvCRMB&cCqGT)!5S@^EgcRVm;Gv{Cf5I0YEGH*-$~7($10c7M~+e$iKHBo zTji|_6{IE~Y7WVJ4JhY?Kso3FZu4>`ANU_jzW?4q7os6m8D}-#tIJa6zhH z)Uetrnf*kvVKf-tbc3>X2cEF}XWA|jl+W{x&sw-3^~tERE(FSncu*<;`0VuhIhYe3Ml6>L0KUO=lMZ80wv4b>LVoU=IlGXW|b^^^Gb^p#QpXf zRQcWnC}{;Qwa{nVG6_l^fibAF6^XGwN}7^S9=S+CY6MZGDFNlo3@9sX;PgGJ-(dsB zpw9Z!vEVuM7WEm(gFo8JXvS3W!>~sHp z-|>!uxV77$W>4L7jI{E)k5%3p1W$a!=h}1zB||6C(%Hs`d%dF|)e)*BEGWZrP=@8; z4O^unP~r>9upEqF*zCU3+K9e|K`gh#vQPj@ zd_h?#0RJ-2o^3jVQbR$R!hqQn*f*&Sr9A)m(03KYgJEBjF*U57&Y;8>{M#D|64q(|%7g{O>L)G1*eDyf|BfDJlPwl17BOLAk{BwEPa^YK?BbCZ8`#_1qNlm{;W;kT@Zg%w?UPr0L)eW zzFVUixd%sBZ(VusHYGvHK`=IPe0C4wgv(MAlnlM*ymuGGt=$GyntD(&6qKeO{N7O+ z3{Wx@%p=Mpf3hU(oJeA9$ zk5w9|KYU>Eg1EKYpl0Iq9Ak{+NByw|PLK=Wo8Gxk>fC9L`oae?+#=zcAg0e;m{@^d^ z7nFnrV}Hck$w{k^y&wGedkRwhqDuV*<0OxFxS&j?z~|T5ugy?U3KE#_ZjKrdCtOyZ zCvWzF>mROuPeI&j)!Eb>QCM|0j8|8D{0v50XDj4Zoei7QYA~!i8_H=7Q1W+)m)}#6 z>IhZx7tBQo`?VND*?9p!^7D)@DESLYe+1%$%i;@4J^JAK?=6U1yA7(;BQRP*Z#LT- z>v$5}d6_S?$qq`ggHbiCsEqu{8U3+i-0aD|&XsECjx%qunYz$ zwG7P7&`|^8gv(N6@@DTuPJHUU1#xS)L6v<~P#RS*n)=(xeemks)5yKq0+5U*(4R71O%@j~l1I%9quxb_Zp0$|7~WOy?tZW3{|Ij?)&d6 zNOgo7<@queyTJH?0YA$zY4!aeaITv&zMvFBFh4kGUqnr-m%3NqzGOkFU(`Gj)@#7{ zj<)xqU@mtI+`90T1KM=PDs>Qy9ot9AUoevHEc%oOKeuE-s$WzYGJz2cFYTbbVgNqB zS^5PtC5QgxJcwv*omr*Qfijm|<<=z&QiFji14uBE&VvEwqSK%Ox4j^P0ZOuiay}50 z=pX%t_ZOu4MU^fFluwd?QLgTzmVuZ5DgA;ncLt-K^wSFZkFukZ)Lgi2hY8~Ak{Bw6cv9l9hCE9p!DqEbB|_x!94nI z=kyFC`j6ApgE--`WCtVJy^Vczt)&X$)^39;9UmA+N_@l!%7_tsY4L8G?4T5WFb6g^ zg*S{)d1YVn#H9*S{h~@~2W8zG%zl5+fFC;`{eqI+V661|bP1GP044ehKCx6mYA{fx z)Pa%gUg|)pbl?Z>&0v5MeNbN30CB=)xd2KXT=RWP7sRdI237WCK{?6-%3(rq$GHxQ zTp0S_X7tC7lI)*9Xz7AfN2t=qf>B}pi!5L+R}LERxSi4wm?y->Zq2Dyrx|>6>4H>8 zsFJW?Y;$D6KL8}5@eob{W;VAiwHP3O`D)Bta6r?&rmHG?Dn86A|-*1*)1M8!I zPe-8SAeir)jQww;Ao*15wq2GfNcD><5d`J!NKg)6fsbu)aGPbIoU{a`#DcO?^waB> zDM*SeF01^;no^*iAxy(HEs48FYrMqxOgc5?22EmM%{7gc&m zP(Gvq%K8Sl?9&-vP!1!362bX5TDBn75vmkXP|hcSvQY)DGVPGIMFOQi0%JJsQyvf} zTvjDPDZn2(XW4?dwcDUdl>~D*-FK@@X|e9q&tQO(&Y+A&z*r5qoOIspx62l!`bCw7 z5tOMkDCG(~>WAqUl=2MbO2XJ3Nq;n0dAWjAzo^n5f%0iw@Px_p%-|&pAKE567zOx9 zRxrS*8&(I$j*`yj9JO3Q+;6WzjXApy^IA)t0!Zz-q>p!3NZY7&kjmM0ZO0p%-+ivr20k8MWgh# zk?b}T={2BiMu0Me0JnP~{en_cz}$@JG&^s?&2u90rEj`;Bb^VzFBlE-w~63A z>r5+1b%dIM?720{hDQ)%r zyDzeVGW7uGyFY^gN=pdlBAdMAH zZFvSI`k;JX1H=iJl`Bvh#x)OHu^?`>L9eM%L;VA3VD2pU-5QPgZ3F}B4xi3ofYNS& zF>tkxVB|MTE?||^`0RIAEJzIoYSevyX9SE_&i(X0n6u+S10Hol1_O*JOs9B*a*7_r z373`j{ol4yK^(h|k-z?49u|o{C_{1Zv{%zFD9sm`+l6C)vNR(X?7mV#s$W!jQy7eH z(OWZ6nrrZ$jiXDyyzw^eG3Q~iCDvc@_J47A~FvcoA zjs+h-H-iC6;RoYoIu8bj6D})+p!AZzdVQsWxYfQ5Woksh3n7^A1@zr2udZNy?RPa8 zL$}7;3jSRStP=f6^t%7o%~mc*^@}Q{4z!oWEV--z_Zu+Z>#<+6Hhk-A~7r6~aObLpLC zoa(=XPH!qBZTrS*@DVU=MD5)q=RS>lhKV zjn|%IgvxWD8)IN|3yA|h{^l>WnF30tfN>7Wet&)JH%ANXuNXYI|EdM4eo-SOJ^EnG z+N`s-j@~f)LF?!Z|GY!`1tn9!TyM91E5i&`r}^_Y>~Bq~U(_5F_1v1L(fW=OUv8f3 zs`Lv=p91Drr^f!b(xomu*9Qtx{h~%L%p#q^XjQyX1!ZvnT=TE#7nHd(n1dqwRFt7K z=3DRdfr3=OsM%iGPf{34V-CvX5j=3+BisB1GbM-qx3R8b71qAuV%DhpGbvYFUt@kv zTEC`BI%A0`fK8YBesjJbXFr8u*8OHo`ZbhR6l;ufZL~S^o2AlWm1O_&-#<{08Vpov z+`xEa$lDw+C!Y4B>4um6B7*^D#j)Q|H;h_lZO+IMCtQ{qSS1&3-(ayfKU|^L6jeoANdO_UUZBR42dycYajWt`*fm;_|@aQ%dux2_B-I{A7 zBS$Hd+$;l|`TMIEqy__3)~`T$iw(?k6oUp_^|KiaP?`cTmpev&GfucHHLywzUHXTs z7sRbLz%Vt(&ppTJQhk2`tE_&28{VA30Hp&0qdePc-q;@{(cgLDH40MwqDu5Z8RdfV z-CuC})IpmIpyUD=J7P8{vPrt3)WIV@zeYi-UsPF+2IZg#C@@8&afVXN9@u)#f>gh#Ia2L4pnP5f zl+{}BxiyYyvm2D`24x=y#0i(>KA3fXo@RXMn&p?r*GF}lHy9#*bI&nW#k~o_B3sGe z;_cr~_|1|FSik(tR+fq01c8zZVARla$%Xk|ShFDRx9cd~F&6n46etZcxZ>lP8lW`D zpnSXzlw82@cV_ItW}We7ghFvK>2wG zQ1(Q?Q|?Q@pu`u9N@sg9BX@)oF7rEc$qyF9vFj+69m{Usw|Qj;qhY+2jvkyf_pxm{ zgEH&^b0}`#gEfrYpFw?G)NDT(6j5k1eeFK!0eDI$W84OTr85k{tC7qo$HN***l{)|1KC4h(%l_6`yC810 z5B!^&iv#wF8^btt;FTSW^^N<;1#rGsG8mxbJ{YSmHc+?aJ40z>-}~vc3sU`}Migwi z)N4SAJ{Y}*Z>@qGeC)V3_d#jvz=(oJACz1GrHB3C4Qm&q1_M=^dN77t-qeFq_`#je zs=*jGpmgP6HmaRw&sWzjNOgoN11c~oo$pzL(x-qY{5lgV%p)G8l&8$Y$k3|6BRR;?_w`4N!978^8NdL258i<59Cn z4KR0z`i`<*hxO;<3Dj?o7CE8K z1u)tiTO6=AK@6qTfzpT0JNU5Gh4hOmZ5=54uwXpu9%?r@ZLjnTM(wr@LHjP8VGPFn z0McR)f4Cquf~ZowK{yFYn_6)U;AYYQ>F6)Wl#j3cUd|DC7r=I?`;Lxei8zCf7~fPeVVNp1dulCWTW4avHvQ3K+H%hDN?{QcvVA1R1iyA7(u7nJ4;lvz30 zoKk}^^uLwYW3fgqcshg9UcK_tM+#E?qDs5bTI%<2K}l!u?N6p(Fj@v5j7|Qn#kbQe zuJ8Zx>ZRiJMKuK6Ih7eYAI?a~9Shpb6FKR9w^xPU{!_TN=%`d+V+`8Yl z(=XP1v&oKs8|DzA)10#GdIhPDP;-*rb8AeceSC#A^4B8>UO(R{ZNh@mLq7e8+imnez8hH0%L@1t?1Zqmht2t7g)a_)h}x1Laza3 z$pVxGEAUOPRlin44fBZ6$dRXVnP03iD)E`td;*RWx3`~`p0?HZ`C<91vtMjVg3IAKkP^>wGu#Z1a z-Jl>fMyL@CADn|W=4IWL=cow5P0e_=@*m;f|-M3dDK~yjSHUH zpdi&Rs*J8eRbI|4j_4>3g*hEy&(CXj}@do88s$izhRsM#)Q{i%(OQm4VRwd^tQ5t(G=LA zXyjI@>{xR|(P=h0@M8sWM_or*`@#}Q=i^CG-Xj3_`grv_;eRV72WzfDjogY8E=x(Q zQ5S4SyVLA=-^U8#)~=&uD3(|a@aTj2PR+n?KJ@C0KGyu+pndt=FzZ66IezX93sN1S z#=zCiU-jG?)!APQ!kRCX4cvP5-_jA*99@syDl6M(@4R6_sw33sM0^hyj6AYa2mJ=j znqr?=H@tPdGujLV!5n%B}v6 z9C5;Bsev^eb((j7Y@>p>wd)v;t{^qAL;-$?WCvwU6{KT)-N`Egw#Uk_(_z=hc6`Q9)`j zP;+6S*MM<=!3RZ?R&N-=?Z2PF0Ht9BW3FLCh_OE^yVOpz&59cr#QpXhV`0G$<6((M zeUtVIJmBp!+u{w%IrH{0{wQ0!Hmi*Kx?kG3AT@%hlFncZ1KckdOZV;gh# zvc3Vz`UaTo*83cl_ zZCQh1Kjmncqdxm7M?;>|*w zZd#BU3{;6eD7gDL1J}9|xs)F|)puZV`-=x7GpK_dX5f93!~gJmc)O^ zMBk6Dz2(r&3sN1S#+1k21?V+kv{!zZ2b9C`;L^KPM-zUtlpL&im}lfxoN!q%u;$J7 zyF%Z#Fq^p5K89>+#;E6*U3uRzCJ1+sgWSCFbr}p$>#t!n1vY{j`OQ**xmgCEyUw>o zL258iQD!KG|B+3$EJ*c>nzQm=1IC!&4g>TZb3!z5d~v1o+GOWuDRp3G*~o9k z36~}NYhT&2AdX$fNIHKp1WOEheasJLUpDZY7dk5aVvYD7M5hTxvfKP<( zS!T;DBfl9ZT$UPGW6W?Wsd4XqTNlKwT}LT|Sfa%Gp;l1N)`Gv-E`tF|Ap~PV!|MW= zsnKa3y?g6|RKKV(UGl>`V18Ag?>9@2gY~7$tKXqpV|U4aJ*0hVjV~x8)o0(bO+l(( z)F`6f@_76*>aUoyT}Gxx`Cm0~vM$G0g+b%Yuv)_x7A*MQQvfzr5v%dB%@ zo4=qWESQa(eH_eC8r2V8y-h)?UsP$#!6-=9AP*XF=Tp-WDAgH^lLNL0W1kN)l#;XE z-?k}8b%Yu%uq`a~8ZciB={x4WI}vP%6BNhlh!Q>1}L3ZcfD;3 zQiFjijX4-ga2DTw1LkYF1III#zNk&-$-h08V1TbZ+Oz6l3!x)NoN!q%utqIAk$QCU z>Dv~>tv$zB8S`|;a$T=F8oD*gq$R8!xccR`1@XVN_a;o0eh|!q6MeTv1id4``q+0e z3ZN7fF!m+=tr<{q@F&Y{SCHx#Rf-CjLx@2GzC8cMZCZhmWj->Pb>Sd2aJ_KKgb8ZW%mpQDE&Sd8=!v31e6YUsqb%Bkm?sT zrk1x*VnLZLwl~&y(!mXHOuwL{^W@*!D$~dxg%d6-Dp+OCzTVrnFNj;a4Qj5|_8emu zz}JGX$}SJM+v_zLL%&&8x3EUp@I{F&Kev5Bsv}gHmw_@X2Xh0|I$Xp3HoK(FZcx%0 z%mIdVxQ3G5po}-Zbc;DMslhIgOa?p_1N;(#YCC`Y-#Z~rml3rhZiIR>^L0W`!3m*p>*ZBD28=9W7Y#I5!TFHpe$^PI)I~1e_12tD%?e%9vDea&f$pD}K zas~sG)Bq#CUfMyNa9L`A(&4`N><$HSYqvqo=|j&^KKG4PQUjdp(F_JCZ4Q`>0$L z3jZQ&?O2fN7d6L|{RWJd@Ei1l;984c)+Rd`kMfQH%u+YA>aN00F2<)4upfn@kf!|2K zU=AT{IBgiu^36mLCtQ}lpj5hP@BMf|+}dqWrFMgI@&}CJhiwTB{N^p@yu3|ztP*`t z&QF4o?4M>B0OokZrqbPy7sP|nbCiW{EV9rI-t~#}3rZ~mbD`Vj&W1dd%lv{;%pM$m zydZA1YGrCPU!L8dG&11xUroQD#23sD=GX`N-uj7x_>;SiIrg>>^qD0(YtLUW_u2+- zo$K%E2&HQvISvAib9aV?olJFHq_c_`VIUhzuPzU=F9p zj#7XZzwQ$Ssg6*k9|YywXkdO+&^}OLxc-^d(S)NEV653r+7}57rNplI&rcMj`bCw7 z5sa45y9qGX-0r2sf?NJ7{eqH%pqx4Yv!Sr*u%S$cx7~23g4AH3O1lBdmH{YB_uzpm zT-jC}Pzvzm%{G-DH6Tv7EW1G|zz3hbQ$gI?ZBS(ieG)x2K-ozL&psl90Y*9>&-fY4 zZ_kb$CHJrX%}xcWeo-a*V9dO{n1ND%!SDVc{en`w-MR^9LVf8Tlw1I%m%MMKoeNTf zff^%5Kl%d3POH~4FdpU27x=4%u4;1ul<0%FjCUexzo(G=qC$O z9id7}f>FD@VFdHo+ra;Jnc1#xQxdC`=gFJBy#l2=|7NdG7Nq(`l~Fwy6TqjK0D{s^ zg0pR%enE*Km@|=)|1D0qtR7*Fw7QV!f8x$h7R0SxN14Q7i9;8@WdLR_4E*N9F3DhE zl~x6eO#y3y>~}fUYClf#rd67J+m;Q7?uutnYsM36aF@E-r0F-tT+^aLu7H?3Z z59X1%kv|zHT$bHfrL-T=`*cCv+HFuJyTSOj!_%~8pzPs-r+q4e0ZOR@Bg|GqNB*~& z3!Ub??|ix-)i0_fJ1EmMP-YY0o!6&dP-+<%eYe+cP?G&y^Y2=a>K9ew3(EUtpkz1r zn}4NWFtdByOx}Dk&DRfi+qEFo5vt5nz(`4NzCh`oz-KqQw#{Eq@)yi%HF8Hd;j;Y2 zD*5~DEPIrRTe}Tvb_6{~>5j2V{(^5lH-iCY{*L@_Ged1T+N`qZwA$;t7Nq(`mEsM? zFy4oGpo})b?S5DN4jV9X-=>H5BTa^qp=)fmTS2NLRM|=fcPofv*HH#kSmZrEP)7CO5l2_QL;qWO0|l!jEGX^OVSn7s zW>3{`uR)at3Y2ydJolk=1jY)ppOFJSI>cz~kCGg`YPH=9QX_~eB?pwFO`zl;`0aOI z-*yCGE-ct`mZ3xtloEUWmv=8n^^2NYQN0Gtmk#=llA&0CxKH{8Bh0=(2u2}1lN$Q) zk9IFeb%ZJ-88CV}|B4Y9VV*_F0bl%jIs#)G%g!;5+{#nAEMc+A(*5)A{!BsK+HFvC zI^1)NhQeO`=sV^H*}!qGH{Z}EEPtDCuZ-QAHMG-A+y65Ksg6*iAo-RM7)J$s%MX<8 zesHTDs-p>iRJL{YYL8jtBgVE>VQV9XS#dher@rx-f>gh#vd$0YI)C49&T=(yJp9V^ z%gvEE)0yId@##+6dK)`RhQ49W&laTmMa@IJ_MHU7_==#P3j!lkEXxLNefLZ07i*^E z(5(>+pW$N70^Dhi`NU@nQvISvYWNBU7zNm81YiWiU+n>}_{i7VCJ2;t2BS6eAq1F( z!Coo)>Sqg5{i0?{+ABqdGN%J&2m#)3TKWa0iveY+6O&u@li2JplP&73%)aP`Q zcsB_P{^;lF2$X~ca}8?bH}h03tD%pq|G9!Vb{(VF@Rtp-$QLI-*|Y^;SY}q6u%Hwq zP`>5|W`>U4k#sRr&a@yPgsR)1N?!&_9|}rW4lee^3D=0>AoP zLEPGHP-R2`=E!{D)>Xcjez8ijgHaf4j5P9_CHh#UBiMF@Jql9&qUI)buK}f}17*Ss z9<;!XZ7zUPyg^y`1#!Y<(FY@tKH=T(h&>A8)^39;^93+Rn|-%RE?_WvKe;FO!%TmZ8_8v5Vn!qLc4qR-7z7;f3)^98BFK$W@x zW+Ci1piB?JM>o%4fRYPf4r}dey0==GO{ybQ8DD|%2~8hBf-=4WpT8g-f!RIT*K`e| zKeF*;rD ziz>T^pd8`_WqbuLv&PMBhJsSNL1|P$oN!q%K*`V#T(W0D+}dqWWg-U3JhZ*BF0+8! z9hboXC7mb#*0*)QELS#2cz(}OJ z|2m=%#?96*^c{0?-p)>&^?`dc7@(APFrr{bP{w|<9GiLMeR~(A`bCvaq_xx+=Ruk8 zgMXRp);8HeX*a+eBiY$YL!59~FhD8o|2Syxg1EKYpk@Snj?o?ai$7SSY~06423&aO z3V9nO3uh{mR!Ipg<;8W?Ol)>4AdBk-$*Wi@nkQApnT5_++ZSu0ZQEmV^rWL zQb5^#*tD}xL8@O=X>&l?!~|s%1l;={=@*pB4o1uGt1e(vjdN*ZxBb*U1*v{fWn>P@ z<_mbjjMF_qvVtElBl?DsyKrKRVa zY23i53x3`V#0i%bGcZCmgIxH~D*F}0t@a}?rb-tB#-PX!58IEt7)BuPAosyt7P+I% z1yG6^nD3;I{pLtXKU=%%(fbvo`bEu_zt@1VWniZq`;HMoYxxI`+wYlvxmj`n%<XMc|X%#pdh!fg1^ zrRf*U92~ke*7@xSx4qTa>|c=T2sL-6dTxz{1s^0}&Bkru*79OH!YUC2qeb#T!vA5l z4_t4*e?h8WR5`H^=3z_wz_np6-47h+`q0K9cOtiW7F>^Gn!EV%T^=@*PF^RXEi<16z!^1sCimjwfBw6SN9?5n=Ce?i>Zb(FK> zSR%V^SK8{YVN~bay#5+)_0tRnR%yP#SR3(V2ci@V1SYf&mDGPLELHwy-ba|;Hzq&{bIsK za~3%3r6E+U0c5arI>*`Y;sSV-IITNEUg(Bp|a8D$Pp)8mKs>4 zaogmkZb95?pDr;q3WL8}3dU5+V$^r5G;Ub;`bq`^%yb_5&2gT=zu%5k&YSHw<)DI8 zzo_wKJKkU)`7z9S%E0l|-=`z2Qm()l$@u6Clw_a88MLC8ZGKQes$Wzo-e4~L_WkBa zNgsV-{no1AXpCo%s^1C!TPasqW%(VH_^$NW!3C*)QFBeE*MRa34KPCG-_QWJx;y=XlFnc@ zK_h=u__Z-Zrzzg1TUt54di7yy+!Sff)_>TR_ zVfDFW?|?%JQiFk-pYiE6U=(0qfCY16GH~nJJ7zGjO7y`@_OahAz4Mv(+M`UWU(}qY z^%^jayt-d7!u$(GL@wcDUZI$uKb1;$j` z#v8WKZJ1rT{XU)Hqkqj{fYOYBF;KU`w*B6OVUCb(&ugbc3sU`}N-YB=`k=hM0{(g3 zVVnD)L?6sAmfOmhq13Y3Ck`!0^@}P~cu?LF0_9)~_`cKAFDRuBl;c=nmOAUK|8ZzR zs$bOX2YYV)@#Xv5H)DL$7OT{5aM~}^FDUVyL~CR^%?Cc(D@b*ODiH+Z$$lUQ%#qB% z|91Q3zS$-$R*4`e>+K*;xGaA`=@z%2*(-=!yA7(u7nDtEQ1TZ%0UvqBUD-H1fvdmd_mc^15X~MBQVd^cbbc*9afO~WK@X)DBmUpWpxX@cfoJ9 z9RV0Gg;^er{mD`$ukRmL5O-voT&Bjv#5V;%NgVKj&(pj{uZHIR4>b z)*xq$P^Hp=^2!(}g%Eu9=JX3nAq3^jCrE6#tW3VL@D~f>*mab?8;cZvP{s`4+splJ znFOUwg3)Yx!h%vZ=GoI8Wm5g3YL{v#T{%{XFSx>%=@*pvg82oNQ3GZ=j~yj{SGxU+ z1@T~5mujlKg8<5DG;phns^6jCoYSRFv+ElVFG!6Ms^lP;UvBC9%@QN5UwSrU1WIoO z%2)-&373^vP!jggZ4NJpTe}TvWXf&y8en9KFZ_bi$be_9`R%r9fLS$0{JRSHHF-Whna^VD3JQ+=>$}i$2!O{Z4cL z3x^lPtv$ym!0s1I&i4my{oUgkU#z(zH*%}Q7i(7MPV>;((+lE`x{i?=R})_>@~gFA zo|G84^~Lvmr>!_xrQ(1wuCsaQ*l(8J`QIl^FG%%^Dor04E6m>7Cz1?qWyuj{*A~4!3o0r*lFAbL+re82qa_H8a5ZT-P zX3aO&JI(U%KcXP+sOu;V6c*Wq2jwt4xanKJ+om%p@db0WXY5aoCdgjr?=%M0{q(GZf6aZ=c05j3J_pt~<@|Z|E1KIzp8i3g$N@`hN3nUK*^O95~K(b~@tb zjDmgW(lELSJ78vCwltI)`s}Oyf>gh#F;cZt*>>RBFjjl)>y-Av4a4}`>+lQC`J40$ zO2UHK654@hwRV~xZ2YByRKKXP-QdeCU>q^>)h#ejDG&T_pILF#w)|K#f+M$POW0|a z`ifaisw310_J%r%O>WAvfd6G5yS9hr{6Y$)uz0fyno7gDzT{g(<-9ihq$2#m(u z-!K9tM&JPtR7VpHC~XcHJFWhWvj4+sb$`_(3sU`}$}RvHZH{lBfwDdc&V0xB+ad~P z*%K8Ritbdvn%oWJK-<5M7xq1>Ak{Bw z{Ox%ZU@*Ue(sztx_k_hd&vxk-lyU{;EN1L~o4IcZd)H9~X%p5|DbHBsjX6+e^x%V+ zrC%_L%Kog!f>NGA*_YhoEk_rm`bCYQsV{_rv65hGx%~#rqaXvvlm483u|{f~ieHeY zddD|*%v|U+d+ca_O|aXsRaA*D7=iTj?VuE3@VF2Eu+3jk3NV<*qRg*aJ5BehqYF~~ zqUJtM&#f^b@-sGA<&Aal%u}jg`y`HGj0ycv4VW#VeGMh+Df2s&oXPY_EXPJ=q@6 zz;AwVsd1a^SS8uP{J9NV2R4-KeqzR;Ak{BwZlLrUP);d>*_RF6`u9WAFII^@7)uA% zvyc5|88W^6i$OuEUsRb(g7U**pp0a|w|%Gj9X4PNA;yl`GIW}Smpi5)?#O<3*wh$Z z`w9jq>kQx;^FI(NIrN()3Rq>yarwiKDM*b1s{E`cC|||{<=70k$!^urL<2?<_5EKk zOOB0l4YRZEG`o$CDMmz>NOLpDf8fd9!caygv2Vg4AH3W>e5>z2L5xGXimsNJ?WU~5oY99s~#+8UIpk}05kwF#87dEmmUJ=A6j zD5(MFy6D)SEZyP~7ad!W>K8Rabqm7)FxqD?b)YObgX@2}`W^bsF&MM78armYF;BD7 zbH|nq9<4WbnvI`5wjk9nYEF22Zq1)X=sU`kmYetfQThd=AG8Hnd(+lXvKx#T*~ra) zyJ5}a3R3-|%K9@X2d({PkHfuGcCh#Ehud@pCA+~W-oCa8;)Kgm1I*OuG>062TtVF0 zb(C%bON84OTnxL~}GVR=jQwV5+`jdm;|o&#qGmVIYrt5AaKB)zGx*90_?tN%X_Fn4 zHV2d+&ITp-K^YZ1e&F#1slh;ve!)vSD7_>ogA?%Ok7qDI$$c|3R3-|O7ub5(*$!E zKWM-`UQWNDAZoB@E+S~`FaRX!E z>OCwdxevzF;{xjb#@C)ukQxkB8DM}BDnIWH%GeCt`-~clp+72m$!K%T%2T;4ySZ6< zx|3fyp&)MUHmK6mfl}%~Idu@{hL34oY@|kvJZG5GPy~eNbiuH=kvXGI49SL6uSm%IYO3mCkRTp1}a6 z(t+~M6qu>eX`cM`i3O>CQKM1ylI(8vboWmUgPH7Oapdb)n?G<;L258i zBPDIcwby`A>MTZm#~k(y9QVC7gTc*G2*KDqwQgeMH{*oMQUhyF((Og3cbr@hxAq*P z$MN+mELk?}^=HGQ-tc&v3!t<)pd7dYBl;fSi}pIXAnvH!pvG|PO5zJfd*$cNz(|do zNOth?!neLcr8e_ztxN;Z^Y21e5P za@H@mJ*6Nue^K+7Ecy)?G4hpd@U^vm+~zMR=?q32Yh}`Y^Tkm5?l)b2N+fO(d{$!WxXu?tQ7i+%GFm`J$gLj%IzI|Fjs$W!DpaWw#?d>y|V+LC&GyLau z=@*Q`a3bvn7;B8S-)#$JhEkrNnQulxs$bLy)uohYFlM-Z5Eqn$1?Tuz`UNFJC(-w; zL5c60yUi#_^@}P67?ii7z+9~zG~iAf{j{w|prkVx^I!kmHzvf9uDv z!8{n#Z@^r18aRIHob-!TDh?PE1S^DNzgZR*KJl6b!=(B}&6MmlU@XA;;1kSwsC^mF z@bKTJUr^!;W?I>o@eC!tM{Ig}L8@QWD6zhA1Il@CQ2KrF{FR?<(;1X@63pGwaRW;K zJ8|CW1*v{fqhYiyzg`2zqr4u0u~c$9^$7g_QRx?y_=3{!gHnHQ{KM%5seVzV{(|}P zyS++mDD?<@_`&oGN_ht3YxcG$Vq2>pIHMrd5o+9g6%hoZJbMJeTvxHJRl`3n`m;7+ zK}lFJmJWP82}(x*h9mC?UO48Ag4AH3#!Pb-!2qMv^pz7ZrqZ@aJ#gz>`_y0z9ixG= zFxy6z-7HHMi~Z<~f>cMS(&2*n(bs+h%EBPH&et=(pd>7qKNB$Wzr_ic1p{l0k$f1x z{JYOAh+FOKhpAz`nfQWopdFN147f$}^ETN*DOX@rcALeF{85tZlQ;V^>E>TJvmiAX zsB#npj4s9($=e(2Q4nyS?K2pl5Rcml8aOC}%qKTp0(=GNr;_v^2}{szLb@*b;`%>RYtBN{UH2Xo#q@&uAPfi)_S z*NOW+KC>V-HBs{vK(7I#3G`(=Fj^Pi!2q9H=NC~mPrDENpQq+jJm>Y*^P=#z|M6c) zO`;)%5tP^DLFuV~aP`cB5MC>cs8Sd~*#ZD%c?$f)shND>|2+BrpDT<+BZ}LR3}nGP zTswA@()Z%uW)`F-AF7l-P`=Cy%3>}!&(CY}O*Ein8<=l~jNICmDQi-&=7_n|EV%wz z1*yS6jYru`yXV#jmLC?!8l!yQJq1@^=9g{%1WNw|#>(L1bPS->MNpQQ*FNK{g4AH3 z<^o5r0i#-b{{+e+Be>IH84NJn%%T5n4EubE8LOlQ7!w9N+16M#{&P)wI4(yOYWVXA}`K)$?Tq9L&qq6zG}_Q(wv+*{p^DH&D{ny&)oJM zWh{X8rrm4uO}I5Pb?7K(U%6Rw@$T=RU6ASsRfce&9PS0B*94!uvHBf0U^b8=M`cMS5vogY1m@~u-!TGt2ad2VxOqAPV_(?X%aL1oDwp}inrAZYNb0TU6vVAv$7~?& zNUB-lr(yi4Bp3;M1Af5`FQ|Se95Y5kM|V2qK7zr`lFne>+-dfH!?^{i!9dN|9C~ie zLy3LI-1;0ip7^H>27fE%3e3VV@|z=6o*G!Q_vkdA-0Iwd)L@`WYJfSX?)%L-xf?hh zvHH_(c5`!{jvKpGR_gY>_}qe2N2oc-=`~s+e zQ^S@bpF6i8)i0{75P}jxP|_Kk^=SG9^T|Vha-OKSl}WQkcF&-TyJ4-b6r}n^m3jo` z=1AXf&SkEF;{%KTx=mPa&Xet9w`MTx$0ASoNLHP!Ldt;s3f^*(m9ZfV~w!lM2`KBdSsW_lCjPH8i zc?GG#K$ZRsjKbj42~cMG;M#NjrcGE-8b*+(a#_0p$_Q@tgU&06Te}Ua3?#wGP(R=Y z%0Lp_ai{8c!v8jNaOfE6?7P+6EYY7tYZyDt=e~JfL258i!>_HS_uMLP|6z?sS&KAq z>#^5l^s&k*2vE}b=y}dBNOgo7mCn|*dkrWnDxeI?z)Sz0@tyqJV;Hc55lD-#{dUGK z=NF_pLX`{!Wr71r4-4M1!Ef6P1?63Jkf(B)qnoZfzaWl1$DDZ%93MV2AH|KiXEAbX zW=f}d;GgFg#2?jll)``|wzvE|7?=(6z;Ax;SJlykqZ9^i&SRw`x8j7$qVSguFDQs( z*HO|6i)0EYX$8(R?RSw@6aKeS2eIadl16UL_>LWAeQEA?hz2XY=p8 z`)mf3H_O0f`!yItzd2e_U)RFQQ@N}Tf>|clXl{Mdt&80~-l+c$_z zm9`zs-}kg{5E#$@uF>vekpRbN495V_-$LJ<}RkMAn zKY8rdO!iK5>Vp>+q{bIDm&bc;PnKgnp+?MeLqdNQO8kE83jf-AXkQzZ$`GGu8 z8guZG+5XU$XD|mg!v>57+Rqt+lCYqZ=NIBfl9ZTvoiXN;?1L&Wj4-R;%5nO0@!`czbq(TDuMBxio`;Rcp7Q zbTL>ZH9$#?Wt)o&QiFjiQx7msFMBXR$!>6y7cv;2qy{MKh9FM3tU52dz4^kO| zpPpm1?cvvMl*6w4-DYe5u`LXs6b3NgXB_#XB>Iy#`+DWxS6p0>8Vppa-JqPf1||C7 z2`6PRK*7zE<5=*;Z)JQz z$=}Jp^~Md9*8AT}Us{mr7geei7&X)fkYIkqa?pT_&ihQ8&Y+|-DC??~bUv9IrQ(1&3L5*(l7s7g_tJvYC!ZA7q|HAM}C;y_$YOiQweTHvH%`NA7-EL8>EEDI1`S zML}6?2QS+A**1?ri6AI*4G=J)g)FDr|~?&0Viw zR*?E+RB6pXY0bb~NE!Iw{^WQ0WULY+P|60FU#{ykFK>2vL8@O=i4iD`IViOoTwvAb z+LQz{M)u;Bp=_6cQYM$Z;PQf0zo;@+0VB)2mVq)h1GgKbUoet=Ces!$np~f@EcK_$ z3sN1S$`k;Ui5Mu=8QkdMbOcHSL3tGgl-_x%)vqW>>(^8%qFCPRztiB&7bs&waKm>! z-zF?5-2|9B-JPa?>=gy6j!}yomB9cdoxw;eYp$&hE`DV}sv}gXDPZhE{L0Ug8EPFgyz$L1M8eux zGQ&7bW#@M6ESaHnxa0k=EJ$^PDme(sx7t9dlHdzFR7VpH7-hrHbb(n!M{dOlmjwfB zt}%9+$G&l8LEPGPlmd(;CMI4}z&LX3jVk!^l^G0B@)yjuZtPE%e(gh#lA&N! zI!{VlA1SgjLbDPefydMNghJrF+ zzU|Db3sU`}N{Z2HXq%)Z1YV1~t?=!!;x*+b?4nvwMO+6?P1m_&3 zBT#Azm`%O?IM)haEl7&E-`r70)L5=JncU4Keku5<5u&qh4^1M zDnT@4%mGS01W79{tB0V}hYOGRYC+uEZBS)C3Fa`O?^c=EV7>h_nVR5#EH(do$9RZF z)TjL!(SULO-HybL9Hq8l&EZd{S>=acEl5pGRH<#C^uwUEYT&jv*VLTwM@enNnrl&G zw@PhWW#MZI()u-3S~V>4H7QVrA>g)CUus(yFi#_n8jz=QS?K{~n)s>DUsDjbb{kY_ z#XY%Cmf+cgELj!+|0uBFn0@veYPQ2K&*u=s>^ z=7s49l-31|(SdFLjQnQFU#xQC`;^%x3Q~iC8cn{R%mwq5NxuQ*3oDM#WH7*RbR@+L z%n!Pc9C5;B$&NJ&gY7VPntQgMD2Q9TjEc`xj$wWb_UsTC%P*?N~rH#k>+;Qm_l+F{3p4P_>pyUE5ll7OM zpD0KT2C6K^fU?U3N-YEDe>{T$O7ub5WCL-+WznB|?Q09-*macXWBK)!=ik5BEPrnX zl(rIF{yl$dlO2@W4aRW5*JeP8{^ZS``_oRkwjebasPdT~Fzau>0p)l&xcPw@3{avE zM(y@v_+UiPj}PztlWPl7{i4dO5tJc07*X)CFnHp9=@*pT2XjPYYkv8+K2)5(?T{(sEv9}GwS^^7{(Bvc;M1tg;qaXq|8B8FDBN#xWQCh_<(nu2ICJG3M zh|1ZLCC7WK2n{q*g5)HqAVGpC>8-13cJ1Hujqi{58GXj+ca2eF)U|8vo^#gBbImoE zzjgr16AUnyJ-Q8e&TMZD+z!fA0L&e(J-?YixUAA)jgi!kDf}mW^TG;oYuhoBa0QhP zOPsFcxew+qcisBi&y{FQIL3U%US;b$N?Z59?=P&75)f+Sk+1oIGBgI|xf%H8cm@RO zB*QS;tFuYbL#>M{qy&T-walN2gIO2G{AMXgSl@U%9Scf90wedmAc4|LR(oAkAthYY zXehk-0%LcHJ(L)0z#QLo9T)xNzXlnKH3ITh6wG%b`+l>m3aoSSMHN!QMUDTxlpF+O znCX*OFyAb?&^$96R~H9l9qlKS|ejjO;#%g7kya zFRqXhE~>mZ0>-MmEg_8g%~^4}j^}+p!{uh_oxx}s{KY;nvTO6?N1+mNrjYXpvFw-GDG! zfYnzr8lYs#B;Lc22_z6M^9C5j`$RHju6r-35Vy7+^9gguQN}9VD94k4t6h`P0HrQ~ z`9g5te@g1${EJ>%AthYYTzTy@V06|t&KYx*x`1`<8UGWxFyYob;;ZK;~Kp?zwXbcid5WE3DDsT0QEyl|Z=6?N}xGyIy~3g}BvD zB{x-uh+yn^^48y z8cI_SUi4~41C%NW#!uO+)jj`T0^u@mV2wEY5aQRnT~;A(Z8xa$Mms2P@_{+9>H5vL zZuriiN@A5l2u8WGH`{uCvy=_2((zsT%gZXHL<2Qj!cGImtj)^?D2q?vUB_iKK*>z7rCTiXq)%u>N{tgV4{-TKBO87|g{vu{%Z^BccCzd4iNYG&T_ z@(L*dp+=>iA9Sv|%2@sGbda62e&2jgTHFN7e0a9Mi6NB=!$S!^dVwwk4; zUS1(?Z97U!h()$$fKnyFO%KUvfHKYjWqbvSpQk)=d4-g4QDs&R#$uaqfC6Qn0v>Qn z33s9av$^g&%CvO*6@FVGB_LEOS73BNzNiVxHZ<_-bG0DiZ@|poegjI6 zbNF|DTOlPHs8X)LD9@f=Q1&K(KmTGz1C(M0#=$lgjeY}0F4)N*t>&k<{kB3%xTw(* z+VtNJb~TI|`V>t)C@X^Cb(fTIC)_HZ)W9kkdgHuTR7eR3HHXAD?>3CDf7_O>uH)nH zWs0zhW5LL7oACDiW*I^}yw4RCQUXHFEw^^`qoI680E`81??k}2wt0V$p`eslPE#NPW)ocRuNe(c$`u$RbKd|35(t-h1C&~}()L$Yh+EqYs#Iq% zYMD zDj>hgWeEhO{(k?(D=WmU?FKb^XP@DMzG3kd-?0duegHFmd!L}|H=lc733uF4vYVTu zrkJ1mZk6`={B^FXkP}ISv?EW^J7v{ArlQ+YbITT;R=2J{aZdU?!fRylntV{(kp!cC$$d7gYxNpzIC< zWx@-dzF8IdJKlid*uw}H%q^&`=A!XyDx?I2n$sowjE|x0Wd`LbF?i>R84xHH2MkYo z%K%D--um`66;i@Qm6jijWi&6qpi~_2FHdH;pd=8Crq4T|NvqFdKv`FLV9RSOq(lQ% z$`vR(aKWf4zV#J+W5s&lXHb$4$_M&D0^zb^21X0)&DXz9xwb;w+HO##839k*jD>Lb z1}Mw#;M|91G(hnN7y}IRhP@4DDDCq?&t6+0C0tag-JsNNFnTLbKDh4f87?Tv2V-pJ zwHuV$4dyhh)vU70brn*gfhw&Tn1^?c`OQ&~d_e>2cJqH|kPD#9CBZ!NsptPoAYA5+ z$(zrj6Zzuzud5KZwjE>3z?F0&Sn}*r`!JEA47S0;zm(AcrL6_AG*G2s1f^<#`Becs)64LZb21vBR1Gk?C#xFv z=A5Ba$$!moLxq%ZQ6tNIl?jxd9Tc~N^ZcWPd%`sEf949@e0-$=-d0eUAJzq-i%RdPnd@Ff6aZP+x0*)qzwS` zQFhCJ>BgBkn#>Hs^u698=sk(SWkB0Y($(GyAbuZ>W$G z5UTV%U{uZL7+8VXZgm~ceW(O9?idxAe&`gYllZwZ!(CyGSWLfjK1ay7gb*7)W9m_&lP#M^Tu5H8E^$(xU+4&HUfv%m^k zz{q`zm3^Js@WQ(?Tu_n^MnUp$K?32jVg|%uy6a$ zx^7+XqaPmR0#<2)z+7(W`_18vsf7E5BPJ@Ogo~ODW5=!0wcUf;u}1FOf?3yb?5ic* z39(vHX*CDlH&G$wmr)~DzSssvtbDl?l%X+r;Ad>0{Jug;xTtyTY^MR`Aq*G|qc0MGFTIv-2cIDib3xhL^t73PwG;k@5`AwehTj+y|x9fzcq_BS(AN z-!Nvnep=Ujzy5uNlyFgH1O>)3#;2%9U_`@{53c#+3>TE<3zQ`yP;vo`QfG&xx0;HRtr-VE1DEZ6HlD}Yf1g+-hPyV4oO1P*|L~WkZajT3*u;waA*R9k3nBiiT{GGh{ zX8a6hn`2vjSG=V{O1P+z`#v-UW%~>mo#u7;8GL;1*$3r$(&{rHP&Ofg5$J?t#|kOoqDl^e zaWJFLVZj`#*;gtJkNjzd3rdLvyCZw zrCTec1cWN<-(d7*o^R0+L2F~{>9EFt*|6)l=n``d{ESun4CV~C?>EOwadT|E@;c48cK0yPJ#4G>IoD>v zV{WSukH()JQKy^k)s1XL4@-87_GwAO>|&mko9&m!9CKZz>$v8DC6XshBJ->+Sx-lTKU>=!3@)RB&{jI8XIhUHytQ74GahQ+WW>2-Bux_Y~?>U z1J$wZm`ixJUSK!I<9l1ifA;^pdCW0K6}Eg}H}82b87fnEUi>`M@xK+2^s~ z-!`9nklkRkN*#JxFd9b>7nE_~bQfBf2;OKnsIg?}<1;XB_GhwSc*B2x>P>W&I2;iAg42b4hu7zvz4c7tD7X`X@GLFo*@EGo9!*^ofEEcu`m{_3GQ zXKhwldYJf1ze36{qek+5;0wn8K1I_9%0Li&VuuWO@@8)ez!hCYx@=A*0y6vSk)ohyi0L{|6ike(l_h1}KgNbF+8fZ_bXs)yy!{T@_No zMa?;3$E{J2Jo#ATyUMm!*bVE;87@|-gJ4YZAEW~UB^N-cDL>lft_ms9K+P}PcN#EW zxAACzvY8MZUw{5V?t_wiFnTK=orBTCo{ig2|HWMuQo==zB-rDbj$5UMVwENcy!O}( z7nF(v=7A-B|0zlD-ml$NAthYYV+NmV>olM|LIYz1l|MoQ4|_Pn1+%nI`2Xgcr1r^i zvl0lGl{!#n1ut!McZImM-Jr(8gcp8L_Ky0^JJ5|xko({)A6sD1K!MRtdUk`7-Jm4@ z{p0VhkPWvf4!hhBI6f7^SOfW{rA)NykjE7Ef- zfpD4Iu}Z1?@gMK05Vy7)RLOl%o?CK=qD(KCy++@EN*sIE-1k<92h?d$rCfos zdIH|?P9_k{k*clc8^)->S5H7m(N%ljTOlPysNo!6X9T0v-AN|`=2}wM@!_o(8Z=*6 zBMCmq2V=*BHTAYd*)RrjKc)b`f9bsyQo==*k^{!gzULf_S=%(~FSy9*87`>x$WU5u ztWto%sFFV;8ZW+oZ-ta-pvtHK%wze+{AT&SG1i%%&uD;BuD~2$_56Pcgv-2vRjTu> z+um0pZf!TH`P{4HC?DIvD&7D;vHHS;TmUl{dj7wX{7I{?B`x>U`zoY_i<*P{P6NhX z8ULanm|aZQtvei^;bP5c>4aP38IsMN`;Ibe`_SL+tB?{ds-zc`b38yvFSyh_87?Tf z4@Oh)AmM^pt>$R1TkHO+zsN_!SFL7oL!?9lRgRbiV-)0t5R``~;6{U=8uy=)+{YUE zYn86&Rs!L&SYeeqc+L;+uMoG|cXv(AB5L2=HOz0=jyXovxR|X#WVD7gSe5^VI<_kbk#*Z#-@6;i@Q&9#wE1InI6 zP|jBdcY8g<1tq;;yqIPK*Pj2B{``at7nHgW<{?%+4~RgxEW1yA z>wyY!Y&*&pLo70c0K;|O@qt%9p5cO$UNFj}wK?_<#pVxINC^m4b}WN(tOqD#74VMb z7YoNu_)p0Y0;?=Z-G9=96;c91jpBVJ%?S80-|X%)ATWkZJ|h5M|8@yz+;5h#DAp*k z-k5_?_kH5|tEV2UkPn#(+h4o@8W|J3rfWS<+%tb6$g|8yw3LwO-eLS#qFS+@CVA1X>gBy zG8&*1Bru1>t!By{4^>DB2sPJ`J8qSUHdgU7c;MwFAbYLYFrQrZ9Qjo)E3u0&@Nk7V zwjJ|uhK^&DST9K2sNJ#QM$;`Za4c5IP%xLlt^YNY0({244_8PD7d8IZ$G~8$Bl(Ur zFp^-W$JjX@hSzMD;ewK(U>?e3?-UrOpY0gnD<7_q5-zGtrNJw1`<9JBya0pont&H1 z@X@m}Trhum!hboZ@I6N+`(~f_x5Vy7+`hZ@Bb2OAc}$l-viS3G%@hDBb|2S}k+# zpDUz9167($P+r~#rC$KII4Yw7iZ?)c$8GtS&CeztP^Uqa-PK^0oUU89dLVxpYb4{F2BoHnuSD=jRPJZ~23URA_9nMtg z=)nm0F~)VEO!2_WZ_a3dl6)|q^7QNj3MtV*jqJ7oWTzQe%5mvn zlsd2M;0v=Z9l0>!H|O$f-%+}!w-0`_LP|iWl3p;D9eknNZ{CRoX&+#Ki+!#HG~R%b z-cu-MV5Yb4C<&bL_m5Uc2^UqG5ilJ4EPe*1n1M@=XSksF8H}dDTEf2nujKE_t;Z^) zgo`TUb}+`Vp1+_}Sa8bQ87?Tr43ugG5(t+?0~EJ!zvp8W;?{P98cFbREGQfDK$+5l z-`H}QK`jHrvA&Q3X6M!OUzTEqRhET!zUZ+EDbYZU+0$hdGceYHeHH`e(8cC-hV4@_ z8ldC?C}*94;j7aaZ65T_V--@uMGfm!gbPN6^{F%{yKli$p2=`QNj{i|_4WLx2!zXW z0juP~8CySIA#SzT15J(6?qg9fT<1dwP`Xs`+Lb>x$OTXe0~p=0PijEP1u#F3XD|N$ z|q!3W1mG$#D!@Rdy-dyf1nmnEN@B^Unmm&Yr_t?dR? z>OL4NW1b6x8_Q%0{O6sSd{Fw($^Z4CIGAe`t!Ay&pQw-$E~>1?gYqx}ls#DBZVN3t za62e&2c!O4-`)3sq_i(}_!AXU!bO!WN}#-u4n}o$KZBcoIl~2|w1cvl50tiU)q9?( zkPnfFBrAViy0{C1*cq{;ez64FyBw>`AFL17UdeF5$lt^0VZn&Ak5nhEz6S%8MbyW3wVyI6 z(Lj|-2g>*gj9jplz-|M+x509Q+y|p-*ovHOnKg_P2K>n*sFm)QPgP5qlyFgH;RuxE zgEC(LH$N`J1*O!1xoxi3fCR#2r4E$jFZcRW72?)*gBtnkJsl|hJ}9U3fZIHh(Eug) zK^f#tm!dTP2`zw@TxNHMXtWCX=39rIEoZ={@rCrz@mH169UXVC0~u7tE*d z-3I*CA2J$~Hy=qc1La8#NFZF6-JtAtn7aHk72?)*gBl|!-}nS>>H|C9_yp$Y+TMIO zymZbL2BjU8>;_|P(>FeW;*H6hPxn=|Z$DFAWKyDm8m+hY?4ZmhKwVWcylbx#4O>++ zlvO5Ba{vBYpQ(@%5UO-BV4Tz9jT-&X*}%85VG2Ic4#aE~)G8lY4e;dG|~GY4&wZkQdty%lMAMK{9*rFMh4AJ``8hT?WGT3~-FJ@NPF zDx^dMHMgyH8c-ezfHI2#pSib0W5REa8J~CMSou{hb2})7|EabAQXy__H>k4c1WMr_ z+*ro#;QNcNG;lj8rEcv`Jv%6G&VbUkgP)&eU{s zDuc2CO4R@#UyA3YJ{SYj8?ENa|9PQ8O1P-9k^ssE6;M_$!4IZpxS*6tP&TN51j1#> z2covMaFZ?nS|KGG zsIqGalvO5Bo_T?Luej@%0tar*^E5xns232}1Fvic;@{hSS z>u=X_*Y9RDxH+QHVMq+-mYcp~47UA6m_45PYlW0>QKg#zB^N-M@_>i*GF(vV0vHMO zu^A|1(Suh0TZNQxQDv$H#xk03cL(Lk1$feYs}0-^O74R)69F^#Tg_2p_RA(ET-4k- z&~a-#eXw_k#vH}Z+VsSWr9lRxQMI)ZdroIaAYA4RPzwKtzH9-RxV7D&=JU{wV}3K% zhNfoCw<2w5YPi&tj0Px$0gO1`$shrgAY0c8p>(@rl|NC_7; z2fdvJjK_9=q40w;5d)W5ca1@IgOXk__vQBdf2Gu6mAe0(pTAfkB^szP{P-264$Q;r z#vHR{=sKQybVh@lBN_+O)`8(?e+LjG5H8DoFnZXNn3(+fl@}|-t#+cmshLL|$Jp=f z$EIMFT~gq!4`wt#DRp3W6Mg@w%%fIw?FKJZNC_8JHXegf+Mgm9K$#JM4=%OlAQ!;! zvkyPO7=GB0*iO4htFQHenLzt=&W~QIkP;2lXw7`V8I;3KK-sJXzIjka1C+u5M)Exx zAc1gME`U-d-~01R72?)*gBq>qFDMLP>{9jy8O$+~eJ#xk0X%*XuZY-78Q$NoE0H2J^wUTV*+{3@6E3aez< z#e2P6A#QCqs1eE2$ucmH9k$m+4Wl))#XWmn)Uf}_wFg-SN&%j{c^bXOr1cbv$}Jba zTp=Y~)R@sLnPfF19bI=RcJh+IN)c!@cjmTp=YI zsM3jmu~zR7sloUuOHsE0UwgJhW5Q9Mh+&PQ;yb$k`Kebbqy&U2y#|;)&R7FV)c{+o zt~2m6D1HW`hT5>U=l@F}T;_JHQZ*Jj^w6ETaKR zc?Kgz9*xQW^=1D-}|rff`+#zncciYa^gM4hHMHG8&*X6rgNv0ttl6O5Gl7 zyjmfSZO0s%b{w;z7;}_d;Qzk8@VbLs0HwDAr5ORG)Pd4>f1~?qg_LNZN;?V0NY!%z zl*uDF^(z^T$^Siqz8lOHIeRc?C~iON-d8K6go~O(VtbjzFp7$Y3&xniAIyQ*U6bL0 z;&w2mJpOttD2ul@E&5u8lyFgH`3{twPGIhh?>69LGp-kIpKz1}VwLXrh5cWvkP;B8 z*^ZtwfeX|)ei&hpO+DdD2Z15i*t;tk4P7jUK5GF(tU!_9^uY7d5MuErc4z6W-hCoxv>pUB?w4 z&2X{CFZ=R4n2#!K<#ty(x#{Z_QqqeWEs}pB5sW(Mt6ShPgI7Mg4S3DRHyE^6 zpp<7YT<5D>ptM($)}PW@-#hj73MtV*m0kms?Hq#}%gQJC&qFdAU^>=1&HP_~#y9!D zUadgstRH*g^$ID`K#f6>54ORaJ&iSBq}QhK_F&!cgIh8hVEWk}tQ+Rhu6ELmVJ>L2 zn%7r&qe4o!sB)ACC~JM7^cvutb8k4v1yD*ID32OJSyfy5yKhuT2^Te*v#S{+f#DpV zS%dN&7I3q@Gh9%bYfxV41ts@Et=+vhs&!3DG*Gizbs8`_KJPU^88d*pUs|Fu;Wx*C z$_EKp`Bg4!ML}86*mb@)E5xn#={i%RgW`5jI%`mp4`%Id zHHZH9n-x-`fhv6pC~ts*GT#T!{`5wJ+y|xbgHeyXtpmmFC;!$`WKzOKl@(?%7TJ8i zC@A|U!OPFga6zg2U^J@!>w<^S~?FKb_tBzyLQ~dcpR(ae2-u~B& z1}Mn~<3knxxB--00CQom)jYBNTNP5Gfhu1B0c9r}D7gT>yXMA&TmYpmfU#`oxd2KX zeDmzLDx`#qDs>->qT($u7_ReOCE(mY%y2=;1u!zynm$`mHw@?4%*%S5m+XH{O1P+! zUNBY?JX}zQh~Vn?XSiS%e(PckrI>wg-G5a`2?#YJc?Go$j1?O%W?(#B@);0#=;E7% zV<-G(dBF-Rzsh9^1Z51o`_ccZ5Vy7)RH;^Aj3<5V8kFJ<9`f}PuI-{R6vu+`Q`WUv z{e93PX;K10jbdhV*p6Fs8b0PI8&tUY>>D#6Pzo>@O}!t8H2KRmZP{4j_ z%&k$KtxL5}UYhlmJu(`gR2(p$iP$GE4W<5q5$DtJ#v{|-u86F@L-_D9&Dv?}0sCuKB1$puhG6d-|cS*Cze_jmjEzbnM8 zwjtKknA3Ug4=g43!9$+PaKVVAul7v-ujPKL`RXVCQz8D#ZATfYVv(5$7)`y;aKYm~ zvH8Hypky}~Ya?FFz<)IlaR!JZj8@+6o zMbB@RT832|d&RT=sgM#4RB6n?7`eHhL21mvKi!_u044dL?7akKUiPn5-l>ohE~*R> zL0QiMWnlrFZ-FfaZU-g#pp22gXg6$SyVbn={dX#)go`Qw40L4yRG|Xkgo+E*9 zS;fIB`TOcZ?^cLgZDGMwslTACB7(BT7o4x&GWd!Jn#j#)% z{-0BTuiE*&3Mm1hO1B8gre!cjjP6+Qf%QH)$WTxkC@}nNCm*(&2hOvbO-ewhQM-LI z1Kz^0WoU`rm?^lRp+cD$Zaa_?KE_yS*I4rt9p;6hmpBues%e3Mt{DN)Cb%XHOs~vkCB_3ro2D29)yr;#||!Ncm+{ zDTJU5T|gPegCBk;T?b0p0HsWV1j1!4KPU;DZf~<9SnYgKQ**7a<0ucBu|{X@YhU0Z zTYqYhgP;uK!F-L;4iq(v1fEa3@rO&Ms}T>k;}{9_0W+2;b>7o~&zx2Qn(&)*V|mX} za*&&4puYb5)73~xAgc7RVEnI#3&uds_nLyA{Yxeg6hDJG$LTj!al082CQw>$P+D*Bp^tug(0YSeQ*8g0q14c)j;LzH1L`!WvUC8-nhf~< zSIaMt`_1XP2}cj8C`?2A_o!(mz5k) z(mVg+b&a^S-JnWa2S&T$Z5=2r61Y~g?VtdIQh>o66!rXl*QBbQ)Bd zT!7NXg4^v{!nN<78_K92lmza2V_hR9fv7U7A6WdA{B8q&^Zfi}FnUQFPqv!xe)vN* zQho|mY8fbT2J;zE*Z=p-f2OanN>Kr&djbiB%d!lVx^T`OAF2_z+DT%jN{S}YJ9<#Y zNZ?HyZ#T#?Q0gEUd-8o44@#DS;@FFR{h=E1XxR6fO^w|5q5?{mfp`2k!v!Vzpd=sU zSGg?tpmbgjz4@UUacjFljc~7^DF9^{4@!vz-+Zh@W5RFFd1%iu)7xs^-fV^%DFLBo zQ{QoGRJwbZhGUH+STwqh3ogI?z|UA^o&w6Q5|BW+EWKc?B%Da8yZ*!(YQ(K=$C&@x z(QqBdeAqPRC=C?<_fRLJ0fr|JWwr>$oX(P92gn#k^7mrx3(Q?Kt!AUAW~h-84OH15 z3&u*m@38^1Om_W$_qsKsfmPZoFkc$#`OTRNeMj-eZl9R3MoKhLWor`{qiZX`V+|Nt zW)Hc#j-7d?3^E0)WC|F~wQWr8`OO5vW!}IV={=Q9+5gZPYs9T>$E=|p$7sxbry@5- z9rV+Lz~lZaqXCLHz^piZ|EaXvaVxjaSR*A|)NDoVxD~^Ais#{i;mJ!$KKR6C87>%w z!JZCJxHU_T9k-JI>q~!N`l{7jG5<_8;?d|h#uF3Y6Nn{y=dN2H_#nf@nm;w+)?DA{ zJIa%qyT3G3jg<7F=JS+J1IoF1U@k{@-TLabI}EZLYkG3Rt+{`)=SU!2mfhT(k!&?@ zTrpFPxV7yV0sV|Rh$UX`@Iw^AaO{P+9i08Fj0PCd=-_rRw?y_GBNzNtwR!5MMoPG- z(QMkNuhW1rM6?n+<|x^Xb)~;&xL~xC2NNzBy|ax)`;L)iCsVvv+o7qE5-w_V6Tc!{ zFkT6?RpK#6$!@IMt-a&G?VzL=jF)I`CtOgf)y_X_YNUjV8s6}>4vg{SgM7{e%6 z@mS}fnd?VPO1P-G!MoFdvAw~c9)ghsZ`;AQZ_02%8DN0X0^3;!t>(?8XQ`1A5NbHb z_ltu0EOpFp&S75HagJGc9yoULf4w?`(E(XgV9#L07{PFm9wUg7}Kdya{HL&}zQALlvr!yd|v4(9+Q+>Beb8`1q zAE}WN5NagfM+aaWsbx*VSOdyiJK!rT?K*HB7>%n31V#d<(r&$Un*Fay2?#Zh1n9Um zUZ-%^VU0-oObGnQSP5v{Z9LPmpkGnmUBJ-70!T;^x2Sr}~9_N%kih+Er^vEc7pBeBTh zBA6+%jlhP7?O4LKjlhO7?f~V4El`pVX3x=T`q$1@BPANBSz+yC$A)<{-I!x;3g|li z{oITOH%9_}bO1)UHdM5)8yiY7dv&JSYovsWnyaU_!Q3zg?9bqKF!I-4h_MakhI77> z;et}y!5Hq@hQ6NPOdwnq4XpB*bdFtTuMxMl8`NA-={U+7Hdc9l1+KKg9)n5;Mh!iJ z{s@#UPN3uhD1~tC^JlM-5)IT`$rx)uS=9q~`%wwkzHV%oBRKoIv0+x&Rl@EeBW`UssIu@3 z$|DOfa={;2fG2$HGXp<^TGpZ!;iBenzSB(NV-#;t9#?`V{yxJ6#qD4|N$C0iO1Z)+ zjs*HD9HB!Pwjg=}J*w~g^!#u@* z%rWA81GO9Lt$Sv;U?k9|)L=x?TNN-DMOw|Wx3+4ego~Q9x(m7 zFvnLD{=d=m+44i*QPR80Jag7a2^Uo+&7d5r1j<+i-0|HK?nDFTE0{e;ewE9@#VW1n z{{LmaY~og15j0ggFECcfd~OHI!X$Y7r#?66yuf_R-sm(5utB_PxY$ofJ1 zq=R8R%XPv{zVj zrfU0T)}FgYN;FWVn1NC0e9t&2=Olq^Ec%6k+d-+nZuPH!S~2T+Km@{Nxqwwh1z$XJ z?iz7xyFrcQ+fsVRF|y2aAFJd(c-a0K4N$xR#`%|?`=BfVe&tVd*GLH$ReCEhT5s<) zKsgNsJm&fm?nDD-`)sdJ8;aXOX}-R>#5^@p!bO$08^L&D&=XWnz* zc2H_J$glbqW1Aft=4{dSoE~WZYl7VtHBhD0fzcg%X$R#14Dia`O1KmLzmbDh%=(Tp z3i|C$^VEn3)M-$ojrH~l%%>k+x8D29Oc7S8N1*J70{K-g3m26B_qC7ATO)35H>kOi z&~c1`x<#YwIOiJ~E;ma72BRtPc5)JbN;~<^XXdSu5)f((Ty2Kiacey6@*Kn}?IgI+ zrh5%K0x%c6`~JVuAkY3k^VUcS2sKBlod%Qxdq8n4xZ>0j(74|$j>Q_8;x!bM5(`QV z-SJ=Z)<}s4s?-!P#<5;g1~-=N*xNFli`AqzlSk-1Y@bhp7!(|#m{fuF@KGea8aX&y^_if%4>yS z{FJ{U0M7f{3>TF2f;pG8uLK)PsRQ#tsGXIv-~u&LqJb)I2jvuDFp^*`lAV=exa#!( zHE=s9g&&lr03;AD^9Cs1_|$$2)QDT#4Ql+9tps))V~O=ShKN{Y8yfi4?K2vnlsYhy zZ_Q@k|5y5yuUxf2jg)Xvqh;{NhF~mM*~1?@@5C^cE3YB>;L&GixS&)zFrW2V-)$(l z07jPi%=-8bEm$KZ8mQ6)fw5}pg&&Nj;Ci9~{^rGu1}KFPj8VNe$RL4mnKwYG3#ab5 zV2!xdx^h#crvoF)9>*JC6qVl*4e-i!_8AlgP|75jTe_@gH_Xi!t>*G`7p##IE^5wk zI&O{f?BQa~SJk_2z3-?J?u27F$9q_Ama)q7FE3alB_LEOW?*EukC4G!aqTwXOb=!P zK`CZnq}OL6U``%e&CDAtR3jx^R2hqcaXgh5GcbA_pNW9WEcM?5$AXf-pnP@%l&)>n zA1zcPC0x|VL4O_##&V^H3(E6YaL0o(Tu?F;l;RCa@dm>={y2L5KQB}xB^s!)iRmh8 zHz-3yP}~lFVOmB5j9%k7+E`H9I*>rPtayXsjr~5haE-XN-Jr^P4j2jakt!G|nnv*k zkD2XDgIoY*yaDE1veg{^&4p{E1cVyiuy&*4);M(5iy78jE9koQ{LhtuCLE(9@F6ib zOY`-M-!EJvB_LEO&tUl3Qv}LV3HZD5Owr{3`pPF5J)M>3UIR-0f-=#bXnnLsN;FU< zf5F%*=L0!V`ZDmTw==zmCG^|lni}r&yUuKTiXq4IL97jbR1=25Ni|_@4UeO zY`O0sLqTc1!5DpcGXhF)HS@(Et&tKgYF3<114{maxm~F1){mc>;bN6)1?ITD)y(?t zM{A@6geqe~Fyid}0w`lbzxmk=X!7R6sW@Q1ui1B$vFN&=TBJrwxTsRDz*ze80u0Iv zUf^d|*>B)jP!b46+iq=6uK}f8fl{sxK7ElIDbYZcm;S+M+dcW9j0wS$zMs(mC4a$O z`0X_yfpA$d1ErXq@%$n+;#T`=kg3_WcO2y*7uFm=+6Mp)uj^+tKb)W%AK` z7OjyIE~>nx1jfpzmq}2bwSn(ko#BE~Cc*q(T)zP$7wl=c9WA-YVl`62MU5ir>quZE z(Ar6RbKOuLu7S7D@RdO>fYNz^xeRV^t{V~vmlZ-#`q0_-U#v#lYTq9=RoXi6oL7GR z$8FZ~c?u|X0sO?y84Xa956S@;pcDpBhKOrlzgUfwXrRha4U9tQYZRb#<=`IYWi&wP zL&1DZX^+4Rr775D=EZBIgo_&Oqz@rLUl&~7b03s020Y}|67EC;O4kPRt6b)GP@4Lq zcU!zh+}dtXqipz^Ik=@i^m4a@(#3!mZ1~kd?t|iXFvib5Ed|BT=lpW<8Y$tTN*4o0 zFX?^;Wi=1H`M3-h6hDK}JA2O#N_K-%=`MMF@fs=7K$Q*%jA(ez4n~&U%#aDZ>yeBG zD3u+I(U&hufCR#2xd2KF{HINps1di?hs#Wr6UD$NIiCAqbQ3;Vc3k#rgIoY57belX z(Q2BhOVmgS2sLi@Vg}|X-@AVEGKb_ZW0fuj%m+7i^uiNM)JXYd)Nq}xBiY$qhLK($ zs)6Age|QS6c1s2XiYGytTY-_G=aQmLS6H$}O1P-eX?g($Geu*5vozOO|7))O2d)F9 z^8)j|y1xIfl$<@kvt*5wa8YG_1B`PTJiVX{A;7UOX1JiF7tAqIzX7Gf9(>!9HB!Pw zmHqW#Oox5LHJGhvw*gPRB*O(IyY}%XQ>(~;i5*Ye8V*uYskL89?T`yuK(}fwmBg3 z*FGF-R@qPwMw$FE0X=&8QZ?cMbsTfzIp&y?sjlN&XOv$acMMPZURQob-rE@bs{gX} zzh;$|@V)7lu91>J)SS`Vp~8l-*VP^+k2&U&g&itv)`kC?(Ez0&fw5!3cBI&$!iM5! zFh@bHX7=ruu8|TA)ZFH0YvzXem4-3Ld@r`^xbm7`AJijmmIfJoYgvx4v0ZRIznMU| ztR=)M!+>4RUb;ry+HO!~EDFX#nR^3_^x867*Ka=Lh!PF!2hAFtroHpgbCl#`4Nsm- z?tk&crE8>wiz>woj9TX5f;lGa`u`q!UnU=`zN zP-75yKCLJiqafd34`!Rwb?Z+SJ8+N-SfzG@F>7;gfZ`2M%H#=0EmI>U8mMyWIhfkNF!yRit z>FB|$PRwvYse@oXTJ8J)N1(QBexP-%0i)tvOM1bJpUiN<@Z@2* z9gL2^N^IXT!aWB+_qY6bjg)Xvv!}C7o`w-;UnB=*tq**0#rD9@VED?{g1{&$J`@L~ z)PdRIwwgOn`FM?#XrQKJJ8q397d|1vD)UhA@82!anDCn;8a4y!Ir6JqmV9o`g4Ake zeD>ot;?}mKjIXfdm~hOkvYi9#GPh^)LCJ0~50JC(hZ{;|pKF!nYNUjV8dh)Xz{n#n zW?*KDJs>k&asGn`ZU?27fzf$cEwd+LhB0Y9k?dac`^(ix2^Up5dQf(-gEFoIclc5X zcfx-v{@1tYV~twoi}QQ-m#dKy5NhQ9rPNg8*sgo~QJm3>;!Fg720?FOTk`3x6)`kV|GlvWgsV&=6Ql-do-Ki-vtb%x;dQu(K%bukN%$jg)XvWt{<(<844$ zX8>nk?^}`kcA}V}oMZ;_t6UZ?C_{)P&s(8J+}dtX(;FSfctB=j!ZF8uINo*K?3fbn zxT9n@Kb5<8`eOCj;;OH%P$MN=)a(|m?>5ZSjK&;gQ4#A-4`sNZWH*?v6kBI)D6{fi zHe9hrO1P-9dP@pzn~N|P^uLu zefOoyexgQ7G*GkMur+hT81?yL2q?81ym$7_!0n)9Hz=nHfznyO@U2hONC_8Jk`Ky* zIZ)nE0B8C_h6_saL0NPHr8-Z4%O`5Y!|gPvvYQ2zCt~0d7iK`9BoK^Z=IsWUbB$KB z-droyNJ${7lq*mY2uiyFe&#;RxOnCmGVZfZ+mf)j%nI ze_Ugg8Y%8W&84YM1IDAyR~VImx!%xqd~xCLMkP358rEUmcl3Gpj@o@BBg)rF3?{)C z5j{^E0!Cfli?JmbV;+BfZ22QrsgdGM)SRPr8Za`(8%a=hc!FDfHN6QA>&?Ta|5JE# zbZ_004C!OQ=qA070i|UGWgfo5eXG<+@g}N_n86LaX|zLH#u_kJ$?er*!%ttE-UNsB z=7D=XIBIW_4C!aUSP`+wSFMQoM7>?vC+ooA6O$} zY-(=H`GyD2bm*X_gF}1s=7&e^O_CuEC7AWmrWJ;=NOHgdtJX+yA8O>puNanqITadn z%t>X}@q}H{ecU{(`_5hD(NVjPWXR|l%&pR`=C~VHt&!p{R9U$OWz7`KN5x(L-{1Tq z{e^W{f4%*^$4Biik|C8BjFG#o$=SKsv#eGl#b2l~IQ6w&Fy_a;(htVc;MG)5@S)ez zU*NF*n)>*YqxKickYOO0DzrbPr_4bjMjMiUvxR)hEUS0=f z&U@gKmS&UUFH~7^0cFcM7z+y4O?Mmc#6PCLz+wG0^@Ynu>#uQ7l?>%bRh~uDcWWM{ zWh1*4*Qk-=K2)imV0hD4n8Do1W+OYp-^~5}LG=WOb>F4uT|R2}kqqfuL3vXMl#vP; z)$@G%)+fHZMvWA2qUIZS9k<3WyEn1MqNEo_@cq5ho8YkCyyo-29j!O*W!6ljcMf2< z?_B)#d~b~!DgHv0lYu~4E(K#A=4TIpGhdee0*Ce299#ZywEh}*kL1vI!ZE)|*mumQ z`K{)a`PQtF;y%>))|S5u48|iKfA|Z^)(&vC57K?$u!U{PK9V6r6EHvV&~ty` zD=r%tW0jH0{9jtLM%-#2CNMSku5}!9hBxMzQ@XC>TH78rXbSn?VZC`xbL?onIpL{_ zNt?Yfh3RSci4rJ$L+g z)b1l0S)e97k#P!!y{~Rh_{^FuW2+gPvQ~{0_o3#ZQ^&2chZSp#vF)viu3LY$)(-}? z73;9>J9otsN9(=`PgOo1?>pwBk5+TWIcwEO@fWIWdIiIMw&iNfZ_b{?UPd(Ql|M{> zfy4T1_rH$VU*n#tC{Ty;Y=~6FB8t7@VeeELMq#x5sIBI@m)5G0;y%=#D942HkF zs|8~di$5_3|9pSC4;%Mz-IepabBN;MF1LN7Fozv5E7f4r&RhFb)J=z>(QoM;OueE`( z1I3?Ag7R7$ILCqMO>kIm9ysmHQG1hQNY??zXv3dOg7}Kdsy3KIlU6h5Lsl3~+-eJa zrpl%RFy4{$1C&5naRFDoDZL2}>&;h}ID6FIBpEV}0cCj^l(Gp**<5Ssb!wz|6E#{8jBR-tbCh8X)?Gi+9n^GiSZ|*G!=H`Xn7dkfP`VxP;LoHt!C}4m>Puf7tvBuMGfPHz(-#y#DSgLItWzV!U#Rk^ z2$Z)+L75SQ7hI730*Ch3_WO+1U*iqQkkw`|Pn_wwHS2P#nL7KrHB#J%DyxBDoOj^s zSD@_s1TT3j-3JcqzH_hq(x}}>GNkf?`?x#pwQu_lgQ4^!SAKro8Y%8Wm3KbCY(~c# zFw17w@xINE7_@y@hjrhp^M85N?jspdz7AuI4aStt#@Ibae8pwn#2Rg%zhH9zZ`Q35 zx3(M9e5GQ{QKl$Z-#97V2M+7L{SN)=sNF|0vNxFUG)H&oQxvSxP5Zk6v;1e>8Y%ul zmA(RugSVch=LMr&`{FaW+|%hka9H=v@znmKb)UVRX~~H9#qI4MdmYnI_V+Em)p|8j z{Dm4G@hROT`Y0NdcN)M=SNh?gwt~a@>+LfS7_Gm?8-0R<4j@FwKo~k^9wC^a3sh1zN zevK4=q2{p04$?G?kE-~0a6ox!6ufue^cOg+zovbD>rwlQWaK=*?=DD>*w;w!TE9k$ zzfhy5`~Fcdo*eo9K2Q!a03Wht zZcrn|o2W950pk&}v!lVpSoPGQyo<_4mkBfjFYt^=z) zQ(yYp4Qj-#od#8Qz<@7IzOn^wac;T~9M*jszqaG3-A6K{FoN;rI(t*L=N^&5h&4wl zt!9InHmnhMU)wP!xgAFt26Ceu$qerKa(WXS)|<;-xYMY;Niw8m1anJ5-#sE5i1ylL z!x|~>LzUfsV2m04siUvXJo z2E*6>(C&y|Y*-_1Z8xYgCjrBKPcb6~b5z)M{Kc{9O{~LubH8UkKU!~2c&g$fLf)~E zDyhq$Opt&6+J-e!+=nV13mE?L2{IUE(_dx(Q)H>#21FVs9*&yGJdl#>-eIlmKJ`1k2Aa9Dpmb?C=N>#qq< zvka<9m9%}JOi`9wZsQs$?n9Mv3>c3A{7DEXgKBV_*0F=y3J&YODbIdkNQSIM zgR(Ofl=C%K>TFyi#eJyq(hL~h^f?JAGdys+J=1;QuzKeI!F_D;Vv)?@$2o z6_<4#V7zPYhfB5pX#O&Bt8EoDHEQ~0eu{=+Ob2}&gEhaVYg+{kPrfL<>DE7;bUUX) z-1^cwQ#Rssh#TfTMNf%1?9dgr;_v5PKg+rP_v!zCjzzfi6QlMf$&kVb#%?1!ZOpa` zCi)w1Kbd=z8Y%8W&G&gb4H$2KdCv>VI}YI0@1*;{VGHBw^Q|&!_mK?gdBNQM*K?0Z z%ZOFRF~{${NsYKSJB_1#53oDU=Okb(wc1DvXjof`CL#A|K zv|lzSv5zAe%F6z|mu^xcrSzf7$0#Pz&&dPxwe@ZTzWS4NA2_W0);@mKQI|fFAx)tt zl1~sEV*{6-rx{;y**NBv_cy5#$F^hCbZ`5x#JLe(`oP!?awDY=ob~y1A2_W0rp+?L zsNF|0qI@0B>J}K=etkv^O63J*f6Q##ZdxP7o2arw0Ss^YE?_XHDBT8JVfEt%br~Gi zo4X%0(`dap;i-zRSlGjjzGIY4TRLnt)6U$qMvA{sW68h|xddZ5%VyJKesfF*{R3-Q zAOAu63mn#8^FK24X#F+riH!2)J31ykau1ak#8+JAO;F}=8~n}6mx)_#anRK0E4(g) z^0_)NHU-~AT?W5!PkIv^)|=C9`jJt4lVr#^28;z!ugjp+Wl-w!c57``BgLDjvTqfP zpYoOwl(j-||3!`;)Map3Z_Y73+o-)sGNfYxNc+S_-o8YkCoHA!?)ZQc+GDrkt&TB^&+v_EUGRiso{>^HnxDPev zB;HVhavCrwuj7E%UzhF!hjrg#{gJzmWJos+%7@cHsmoU^zIlxl_o2!R4~%xeSGPd< z_&0c8^W#BX28VUut4GZ_+R|rFkS!Tef~;e)C&-EC(l0;y_04Of_zN}qnG2Z_gYg21 zjVSFKBZl!X+7H+P-`O?&1rF=4{q~)IwEnVBrC2hgwu1SQ4*NEWp$u!LziIOtDegnf zrqGUEHH_(vAI1jekh|;FC4ZUj!#b?{rrfjOsNF|0azo67Co<2{?K?&VoJ#4N?;~5( zNO2#kls+&|3>fp9GAj zhKvfqoaFXA%~Ce8=3D=*=HR!ssFC7L)ZBR4ack`8_jkjv%2O2Z)W_4C;IQ6&_1n*l z+M6UpYC4!7u(FSv8OpHcyv?_)k>Wno=x6-n3}76iZfoFU4VdqHcO8GX{M13!#yYI~ zE_n9&QM-?1NH-0}2{Hac1cavxy-6~pp#*aj-E)uND=sUWSY>Hv`jtLeBW`UssNs5_|AF#&9+brhaEWT1`%u%lod%50$M^#eJxMLFEO9b>GAPb<1eoH_?!c7*zXSBv2N+4%&CC8Y%ulmBlVF_t=d!pzK8gPuwp3 z1rF=4Ywo&rwEi0RL`v5&=>lIX1hYA7HRoTsRgDz)p+-@?fSwnWwbiB-bxt0%eOQO}=2mmuJ!)@~44I;UQG)E)#h#}bUvZf?vC6^v|Nhz5HR9HG zgBrfJ<1uYeZ5R(#?qq8%0zbRtDTBHU4(q<%UmLOeCK{3vQw85!14cvXP2nW^LzUf* z{Zx$<_n~I_>NKF7bPmR##|GqGw|?sz={~H(y6>s)KQ`*pM>1qs1Lnu;dY)!{#bt$Y z(j)H8LmvKAjkvYlpvoW-j48@PG=-o%5d}}VIlT!E>&-b{dScYxBpK38gK;{8&xj|j z?!J?k*``K{`%v>CRHp&sr+gh7jPaB2_XjVV_0&OK28VUuQ@?t0)b1l0QW(Mfrfg3< z;#C`~bSzIFyiJW1Z=y!&vnQgR28;odf0qu-L%OQM-?1NMQt{udt>3 zegj7J^t$}U9G|X{;yzUQk{TG#4E${XFc!Ui-xoON+vz@VSodvp^d+NqAIXr-Az-Wq zTIuUGAim-5sZGuI~Fh|eEyCoc+@lLO>o%4`0(9VjoO&>ZKTr+BKk__pl!Ti=x-#rrL%ioi_=`Y*XNO2#k47tI0^WIxVP~KDl zpS&~O2M+7L&fVQnyN_hZGd%Ekf7i*kXM@phddmpP-iJ3=+pb26H&JEK1IpX;pgdFo z=UwRZLDdF__2z*a964%lk_>4XLHV#Yh_AS;YJ>8$ex}2>s}Z-h8`OM;*Kv$*8NbG$ z2Wzw;-p_!`emT7f4(rX+e{=Mxy-6~pY=UvH>&py!KzW07x_iuZ2+nOcsQFZ&;}|;@ zeFTm*Tz@l5JK!Q$r~ANR-8Xf?AC205Btu$8FkVTvLvH$>X4!eO(IVT|NO2#k)MYSw z5`RDn%8(n}bA~epbr~GieTyA){HWbWGGzJ;#<1C2Mo?NtFcuWfqnqCSYundI@g}M) z(}FP<@@^W;uUd5de-GIyy@_>LZ%+Hy38VHV$&kVb$~q&6uehvif-;2s&UM?@h+EqY zYCcryI7Z9pL&(96W&136`p?sw;IQ7Ddim5*dy{0y5E9G}-S^xhQZ^@V_Of|FGo?m~ zH&NpOgT2z%X~6hEna^jy$TmMj7rgbA^d>m0H}~5A#8G>5GLb&H2IbrbFuduL>#KI1 zQX|EEsPYyS7_F+!g~l2%MwHjl&wvkXaOR+)1c!Cs%AeSKwC{7CNO?zfjX79k^&>ZtuiGGgZ7N1lN=hs&xbC<_WZJ-$PYxV7D& zW_#apjLyM3Q><|?qV0_6y7ilXNcUkK)_q%j?tsy{Z`@NQlQvQ%>oK5=?4~ZiV~rH| zp~?&1psZAb;d>dO>-22mIT+=}mB0Z|=TFXSCj&Xh=ppHFx)cIETyX zGAJGKy!-4_BW`Uss4+-9ooN{u=djqWurbFRMcexkW?gfevjFzB zN}57am1}nPeuQDTZz@gU?3eFUBgK8FvEJt|g@XC;e#~#qPX%-xS2!cx$IZjKZ;ti8 zH){8h4B2rF-m(}^dTpO?-_tDn3Rj(O=Nc*QLzUe#pbP`S=#+f%8JzM$x(^)Ieal|> z{ZYG*WXKW=7+r^V#GtI*e|fu|YoxdjRh|)p(Tw`yGZ;^uye9#VUE`cVM`pe#tNQCO1a8 zz7%hQcP#p|LDdHT-+J@XhYq^*|KG`^N3Xl>sJ%%tq+bSeV{hNnob$g{^Wc%Y)c+50 z=N)xrb?s}+QuAtTpA}0KI~t9sQLz(^N~~C-*ohSjifq)a!7aKi*ujb&J8TuPAt)-J z1=;FW?AWmdj14s!Oe}XjbG~~r&mH%UbIw?Qtaprgvz{^c$GP+8>J=;HBWVMes(5Yg zt0rixPIbXK157^tHdVepckY&3KEg18IweS(6o?O@M6atELCtQL(#t7c`%Az|HA%Xf z5!7Cx-17>$JDbHj$)$F&z9=X*d3@fdjB9JxHO+mEci$$9sTV>Z#bYFGvfQh#v z=vr+&_LOQ}yuBA3)h^3;Q|0UadUp8;!ec1%tLN3LAyK)~N>p}zVN1NOA2Vp-eF9d>N77Yxpu3p{)OvF=EiX9YpC%ue zD&K^Cy62XUFkEQ`?OxoL#O%f-ckI7Uz)JZ@x^5t-^2KXeY6a*f6u>Fl+|;h@z*PB0 zHrLKAA7QxJEl@L*9Qy=a%L`hcv7@+e%sv4t)g)p#X4*Azq?zSz_fq&w05&cF5vn0PA%Nq3?fw2L=u;?-+% zWz`(-Pw$z0V5)qx9$YW4d<_ZGRfR;QH+aNJftGl+t&oZS@3!k3uu?vfD(-Cz=|H=k zy(VaDo^`<`*S)!2mick2d?SzVky}2(a3f;S9`I~R%&sisRjuP>YDY2ivc3T;)g)>A zeB+jch`L@X^9!I(g*`*V0xs}3Qxi;8v)@|l=T?(2tg`ErAZ_A0Zb^t#2_6?YLD+NjS>Jz9xmM#3Ctr^ti#}6HD^5IRDZ|ZlO=asJ^QMq0rQE7G)H9=Pu zf^G}{i0AhWSg9sS*T)9k!!e-#canL3@ZS4PO)yo>IsLcFt7d0G7}lw73L*|)%#3(< zT!^cd$Iy~YT5i99iMJx?_AlVke@ZeV=+->Jx97RFU6#RA`6jQjb#D0xW2QVGE4dGJ zxev7MYaPX>{r3x4DIZB!mO(w-BpZ7{o3*XW-~PIf$%i*pz6sTkSH6Zs<+?RQWj(u= zcwOP0J$}D{mGY5vxet8fmVxm;5ZSZe{$aT<8eH@SlMhUlum9)s<(7{yTtf`11kw;$*_+~fmOr7uzS=)vrF8!o%Pk*axP}lMwpz8*L zt{?N}n+F7}%zY%?X*tlXD}nBc0C3J^Qxi;8bNHd3bY#8Izq23=w`U)8mEB!y9vHAv zFOs%u9=9Y!blqmq?b!#PUF42-X$6z@nm#kHUJZ%al~$tC31k_BfM~@R>psw}ll<*>^a4}$DxUm2uU_#gu}mPg4lpeu1_^gAeEWtJi7240}*h*cyPePTPaBDe~EY?wJPXd z?8K}2TGRx;T7OKtXoIP0j-K{oZZ+phAcxCA*O-E?W}H3p;DD9#k<^7G>5G6`E$ED1 zME&n1)A4v09cuD{sq)R){+GP+brytSElE?*RfTxn+R&0S4-Qx9?x>(4Ok83(k9s$%i*pzJV7`%Pk*axT+A;Sxi|x1Fa=#i3GagO0M<% zY=J`pR;o$T9pndfP9+WpYX#^I@`DR~ZEAw4YWCUwrMzl(N|1UHWqhHzCFr)3F5CBz zfR%cYv=MQ&0A14ox~2pC!`64T>pn15uaTX%CItQuh&+H62YswBn0u;?r~gpJLqkb4{xe`qwXD@SH4b(s`2&9 zyBxBZ=tWen@Gig2p#dxPB57-B)dJL8KIKX)(7gl+ZoJmr?ZOMD>NRVvJM-$*keFTJ zB`Vb`-V@XmuWLH+y25+i@IwPus!37@x$!)2wE%59R!z{YeB*ueWK$DNRkQEScjs1< zFjUQ96kgC}Mo^3Pbrjx*-#av5rFJup+2Kx_iiOc=SkM?DW(G-Fw$~zh7c(yYPakdQEsWvtA7e z(v3QZYJe2Ec+W=DdF9R=ylx2m-KmEKtW=Yv^$O#;j)-=BbUfD)(Kg!0a~%;EKg84o zQ`PMM#|LxgKElw`R8f^O9Dm*!ysEA=87FDHse2xZg(>Z-Zyk^;4{W~WGS*9tTMau+92X=`v5ZAJa?!vj|8Mbed4P{+J+?yDw0*1wJC zI_iR>cD|=w_wnOYy}I8$DX(4)iOSV|MD<$Kk(*jOg=DGzR7Dmo>#ukLZaG^d%fbm#Fn7FjnYwEG0zbJEA=AjdUoKt(ixFS z0niTP*X3{Tn`L_8P1URa(`V$>t07UjVHr^=#qZ^pcRM0rrJ5wQc*-Cb z9C;iIztYhI^=}`f@PaRIJg!}M!BjQ-Y<*U4H3`Et9iW|IZc5B(#TVhM$qcMrU>LRBVJb(&i?F(fR$>J)PBsJ z^rAt{j8YYXwk4r1-i2Q=HSwmZIcmf6@~Rovd1DybS&KO+uJcAj9KKjHg03O%y4jHd z6K|y;>B=&w^LnnUj#o>$FI ziArCkmZ^NAa%TW9TCIP;O1((B2?bCunV3$e8gvZ{*!azT?XnD}>ec)35qb4$NRX~! zAu4wTH0UOuuOHMuV5NK{H8V;}0;=?JA7-rpwOWud2{>tAlMhUlZ`wzP=9Z5zTvZ5a zg(Y**pqo&5Z*u>DmGY5vPi2BLm zP$yI4;zmdD$|6Svtdx(W+k*h=<%lwa0BXLLMRf3+?@T^0Rlfdj_0KIIVYsFP)VoDw z5gl~9C2v3AsDPF7k<`B(Pd5-eUH0zEbQb7F#NgB0-ruhKz*PC>{NectxC*;+uQ=+n` zYg>Z04Wpwt@rt7ZCW=%9-N_(4I)5dbnL&NgTK0m2R}C?}z*N0@?Q~*Zy&58cwt#Xe zHc_4Z+3sf-QEj}{IU?Jwj-4rLg6@DgIQCgn6HHZe z)H5gNR+BJXQw!P=-FT~WM6}|Ir4@8}^WpW637B{*1xYQ-agLxWsLhV3iP!BE2jA-Y zV7n}XscLrr)2X@DoGXExQvmG%Z%Y($JH_8P{g{B2@{x2WP(fWam-#EuUEBhGcZA6Y zrph;c@{ru}5r%6zKs$ljDnMKIU91@U!ZG2A2TKV$isd6>rJ5vN(FV2BkZvHT8Cf3n z1~+g2Q|TABn&qQ0c{Q{ZitEKDoRiVlD(8ump?XOrJ5vdVWe7sdLNyf zE(CR|Ro-F%XZ~t@yJ&-{YL1)w$J}ZXhU-*=wous;McjPMwnrZuFp;lXkko=NhZ;b4 z_XBv??xq)*s@II|{*+rU!f?3{)U}Q{jBPnZZlD*v$An|!l$2#RlGbWh#cLh%nxM@u z)CEtv(d6TA|EKaz>$b$G|JVBfQ=i;Ew|sLY7|#AH&^CWJ1<6}{QBAyVmG0E}2Lw#K z@u}aKw9TgRso#iu%bo0UIU?vr#Nahwn3`a!ntlHG=iF)%hU?{k+L*?39r3B(h^{IG z?F>yvF>^zd$R`wOuUtXq?;=Qbz)H_`azc&!C&4mHNj*xAMTS|O~P;&gn_pC zs3`)uqK(&0H~f36;{sNyDOh8&FwVs($yeq6RpaTva}(f(gH1j#RlZ^0ubNlB zMlm-?sTn~V|23Ugwz1Cr@hJL0yS#l|z)Ceqy0dhkop+mYMbRj{P89}t-i|q{PTJ6(LK0aXLtrjG;)s7vey5RK(nO=BP^%^$lce(W< z442(NeIhSb|4oV6wIp~|-0LX3w?7?!98L792)a%p9{0=&=q^A3pS;V|1e4YLdfnV= z5{By}f?5FMB6?heis;76?<_GeV5NK{t*NaRpu6`JoGA;+vVsi$=ieqDm@416fjx4| zM;IFPevZlJBnk8QtyUGRq954Y<+ew->_ zb?x(PA7;Y*I)J5T_W=FBn&L;${)QhCPT@kkzRmE$sl-2~@Yz;r&Yr{v{ zg%?cKtJeve<<^TZ+*B*5`_*DY+!6^~%X{!OCj_jNkEEOI0^O~4Rq5ppsk{G6xCTL1gw;gr0v{Cd-aPZAKp~?`kkJli4l2_x^TLyYPak z@>L(6FRy$J3DUK^M5P1Oco?kdyfOsF>&o)6XAKHisU}Hnc_&a6f;v|ynGw`!T3N#b zFFMB51XIN1{Ar@e2d2t5{E-E7 z%SRZl7Y%B5i@oTMV)2zL0W0+)=`IQc-ENTf56h=Nz#he;?ZOMD>eX+Hg>&mg7;b7B zR0(8n4Tx5Ju_^?0hk{gvJ04#Nn0PA%N!JjAD!nYggKh~FJZ5iG6HHaJ@1u+6R+BJX z;RW5}3!s~E+2YYkz)JZ@y37c=ZZqf#FL=PMCLfq8Uv;a+^UBv*5QaY67W>I9K|7$- zQSA4d!2v7vB58}lRq^T$bs1*hbsOWrzkOqRfvI}+nv-2G!mv?VOC)fcwU*y^aKK8v zNNP!!jjEtN{TQ{b6`)>!Kau%9aN}N&z4!AH^LObH_s2v`)oaw{A1#*keSmmjObkPd zXO;O;P}_4p^xsNjJy^U1u~S_a{ATUP+eMonr)I`E z%YK$yKEiPQ7*P8$@ty9L#HB;CO8N1Pb2Qa+My?jF=uTRJYFn?V4VI>qDzQ|0S= z-50s#BMg`OK)X7zDSEk@5wGh8cAIfxz)Ceqx_%7kZr=u7%?SSS8B-HXRkPoUvvaFS z7_Mdnbumb`%YeGpAtxX<{ryP+E9E0;*Dh8IQ0Et9?^gSV<(LHAcd5zkvJ9rm*L`|+ z`3S@HqCs1VY>Fai#TSbiV+G$AFjLYx04q@=cihb8h(v z!%ZlF?xrZv)r_E>rRyl}>Uwg(N;OHU*3tt9bx0>87Eq@SB{PE0|6*!_scH^A^_RSA zc8VhIRScp+9KKkVLAS0n;fRw1Cf-Ux(#>vxs+UX-f?5yAmUQrqT{_z}BbX{*m*$gs z9#P7YWpA4$!sWfoz%SRZR zgJiE8C~tbdDNF2gy)w}cx>cthyH^8Ns!7tODyjvjn?vFTkD8$Mf$D<0_k5yVmick2 zn*H{CF1MP5;W~++&7Q_H$Pv+sFXm0qxK*<<+YpQCWHH6x4x)oOL2dw@P>Ud8Y)dl#isF>;j+JiPs+GXdS4TQL-C& z-$0WOOqFlwb+_b}k1$+m1y7W@eCfx4);M$&6W%x_V5NK{bv{P=F`!O6N@)dk%~LjO zfv-Pi@`0)H&FXf0Uimsj5$i?AeqW5rWw#erKQ&;bUL;+11NDUn*%#gZVL71ye!kFC z?a~US>Q%jMbZ))o#w=S=K{prubLG^4m3ooXvxkzuKzCjVbocp!%kOV`fvI}+T>H+v zdNm5da2-8~Y7jjNx!xCa{p4kyI5l9Ud?ekoq@WxJw4QLa099N$JO{e@EAXIynVMj#nmzt7 zF1MP5;RbD>c5dZrC{VSQ`KvM-5a@}n~MgAZufM%?gLZhoAX6> z`3S>hMo?!EWLr6?;>x!2bMN|Fz)JZ@x~3M4cYN=5(N&WBKzqEZUVyh=X7Yil@=ZJ9 z!Q8ozFkDp#9w0NwvbhaJE50~N1KpjLxBdHX0TXYfAnAq~pgXz=YA<>c-DYsg2c{;N zs%F2>AIhyJVYqHHsQGIeH6!S1M$iq~UgJwqH>HDd|On->f&KU9`be zHM*r~1;;G)l)USO(TMeXt2dJ%@J3PF`G z>eZB(5r;2Ug?Qb0rBydPEnwoU6oN7+k&B~1*DizFC6cLpaNFgcX%}8FRn2a#vvaFS z7_M6b+CJZ=2;{0lyzcPa24|cWuu@HuI$pk?=|9k2PyxD~aNr*OO-(RW&5?T!%dIA1 zxP}FEEAF7GIf_NjynV5NK{-S!XAJ%+gs=7mX9!8W&~9c z=_G=#Dy;ps7O+x2l5U6s>e-#?%m#usS6COkcHXJ&vWz!XzUlog$}JyZxSA1k+gL%@ zkGcMsTEI&ANVUXoir!f*{SsPhZ53m9};-=3LR z3s@;1Nw>iRw1&7=fNs+{_{k`f4@{MB@^P2um9JBRR0*P9O+m!riw!YB>IJ@IsQW(n z_2~f+Iwj_@aV2XnH&V&m<0U!OOp>wm2X)0%ks+CkeFTJB`S9xCg>Vs&}GKo z?R|Q{N;OH^hV^OzYFU;o)}U<}u8Vj3Et~DC5O1oQy(b=;TTQ~yhFG>(gZiGjyr==9 z6<^Gope})4L*88L*3$zf-in~+zPreqc(hw1yIMh;XRM2Ny9-QBys2tV>vcqKH3>sU zc!Sxn4(cug+0_bat9>Q%{o$L_16ImM(h7c6yl%fgUc2A1F5cbWH2LtR$~Sas|J?Es zhAY~j=FO>8lyki@5esVJy$UrK=ruH8rJ5w&PB`#^sVBvSfp|SiO@8dIy2ZQJn$Nb2 zHkhhr-#*9WR+BJXClOpy%C=0zg05y<<>H|ME9E1pXWZr8Fi^)NapI>|fHr`s3vPL$ z$%i*pzJAjO?@7}OZ>nCy z`wh&iSEod!3vY5dr>%x463>&wAYIe(;@W2ftkjF7YdS!;h6lQ{PT*G^&$UY{m?~f2 zeU!x!lx4j6oiR+HywdxrGEA=Aj+6quFa*ORuO@3?_RMZ9kd9dllk5l!UTsbkf zUWDN$Q$fU$b@7(O>}K}Ao^nRO@b{<`Bz09&deNZXNGOd1=z7uMqGL@yFjc<3Kc1Xh zKEiNgIB-|#p2Zp}p1WS^%z%}8k<={-x6rc#bzwwW1JLGU>f+t#N7D;$s$Mb?3lx%DCp z*EoP@$g?3b4g=kWm`ir42dvC)B;9@@P}e%*Zjf35YEFHat{iyJA6o6w3Z}|8b?l#V z%SRY)GO)aP! z`r@#xB{92U{}Sh%6|ho1l6D@hT7Y^IAubu$1l22BUhr->z~lo{K+^DnOt7iqQl#is2^GDN926b<93;DoR+l%OR!CfCQ`S7O7*JJo@x#c4a z*US$bX7rZ zqhtnwAG*nU@Xp&zO)yo>Zj-v_RkKrKb~m07m75TKXrXfgR_aAk=VN3D403|zlWEeh zfbPL&@QrUxFECZF-n;!SuU?IUFsxze6x8({d2Jo9mF14&^Zm{VSScS#*DC~d%S+tv zQI{VtxXrY7-G?_-ul{eXn_Dl!a5GfkZ)LqFHl|I98FBbxX~paIY%DnDoPde9Qjl~L zFrdCxEc>ECw=Wu8bGWGqrm8vN@E*Cf78;C$1lSthMx&vL{F7KI|V5*u!S6V-}nuMWK#22C_XkC+*pn9*P>DYX`a|2e& zNAkYwzq(_}P7l#^fcjrTE{p-SXg@{K1`k;0rFPKtZoo?UNZQhEwE%UQT%G^|wa%4?8^GaHO+GMHzHWcnDzAK<60=nI*LZCJp>TM=}*50AUv3Dhen9;faDUpdUw1XI=Q-3WQr?3Adq z!irtr_cV4H6&(N z*%6gHGy}TH)PF8}Ucf}YYC+QFFHrkHa>xi=VxCvpr4>xotM8LVZoLS@l~&NE@LHmX zo4;DP|9Jr`vl~erX2ivfY5}@q9-z(T)Wy5bZYCezRQbB~`AuH=IwdMSmnL`r5tU{c zIf=04`11l*>P6B<4%GtGp0IS~K)onJF4h1KxZd;vQ}tTx-Gy`OMHp*JfsB2(rbuAJ z*p{G8;dKJ`QR%=wp1x>_S9`)2)3#nX>imF}@{x2qL_wV+khT?cZ3Wmk*W?3JFL*(nmZgB(QVa^GB(hWN+xqc>V9A4!+{Kpo-9qyXsp$>0iuOg=DGzJ5J^n_E7@ zaMSUi%WjLmc|pKRy-3=Gd)&|$(e;x-&B!u|0 zDArx`!hn@}k#ubZI8%W7JICbX$EoslJ@<#a@--wXomM)Z6$zrU73kJ~^>!3@ zAAC{3O8H1yTTvCSHl}glRTH%RkafWqwtu5tyYaWF^37W6$K3J}hFg&U^^(Gg3?xA9 z`i`LRw(h8F`3S>`XQ#xh zm7VPR!Rxwmpq;wyC_eqqMFA_-Bx$QZRq@)L&o#ltwI!x1L~X3`^5n(J;ejfFjM6~s z*>x26PrD>wrCucU4G9^>g6_#m@Rf&5FEBN`^_w~^w_b$dvKwgGttA4vr=G4|ad^PW z(n`|KAy*6Vc^@ydem>ZDim9vrR8BRj-~4znxnz!q5s!)*eB`;fsYAbXDO#`-}*f zcq;`-8;4Z|b(ALZ;nh}1wvmA+Z}oP&Dg;yI>vhAsdF5+J%+`{$1T{lRM{n?LBLY_H zMbZ^dP>)+kWe3^_uU>$cU1)lNsd^QC-^;BRVYr?OXf1D3Vz$bzquAlw5dkaZBWY83 zRq@)jXLZ5D-!i@UajIU^I^NH#SEoc}*Tl61U3t9!kCz6l6o{nlimer(Ydyi2yT8*e zfMBXXBlj4SSD=Oj>G~o><(6MT#Nmt88R+^VA6#;2z{DG`)r(12JV8C4BE=Kbvr?0p zbOL`l$)$IN8ow?N{3|Blst)XNu0BFUtB@(#4$an8v8n9ALlCEt9U1bNlya_J# zw5bWEs@eUdvANYG3~L-Z3($7qH3iX%FHQ<9zRqO<6O5~|G3gfnLDx8d8!Yi|yDWpL zdi5yo&8-(L3wZd?KCpiM4l1>MbW;QW6zHNjLh z`(1N?ZZ!$R)r_D!AOO0maOtU+1+0{hq}v(*x@}RQZb+6*dEg)JG5Nq$`6jG0KCgV8 z1!3rR8#zz`+MNO&#fYUZ4_K)eN!N6MZXf}=tta69Kbc-&s$N6?o>{MkDB{*0iE3Rr z;Uwb<5Uu!PLkzm61xeS@1NCNRDZK3;mNR{Gs6o{lsFpi~LP)~%*25wL{=RQKe51fCN2?Qn!H1BzN z1!_oCuHQ#gc3)3ZylBN23ol-GvhnL(uLziUFf_AL0CTMHw@y(6+<3%=p zzg>92R5ceHbwO@52}8@Htfhf=b5cjK`t?@?tkjF7j#%y`_kp)x`&74agXF3tu=ClQ zwj2MgtUZF;oMn1}se1L_@Z!9BbxO?NcjxSEyoRDB=&G}IKD#1drCucMl8R~pYBMd3 z1L#I+;EpewUSO(Tv!)EstruZvg(Z4{ZdcjSn_d~PQZJHP_r?0FT7bImLTWeAz55ED z-)%;_Jc6lujT<^5uU-v_*^R@9O3PzhuV{%^w?o{<;_RSvuMAizA4zvm8`KBbWsVcn zo{B8@fR`O-@`0)H4efPEZutnq^+iA(48)#YOZ0M6QfIz)Wxz`LNa`f;edIn+bFS2G zpdHnyi+9u{lMipQe6JpsTRy^YZ7XOuS2iVP*OkNT>b{3py((a(nj~FU4s<)*LH%3l z%7N1t{GeTy!BjOz_dhbPnwl>!c_qiZ>1oqld00wg7Zt) zPVTG#wOW`&M-TkXz9t`-D&L$RkIE}wL!xq3AyH{ZPg)YtHZgV-i%z~OV5NK{UCRsV zZNXBOLGAa+qc`C1?=bnmRQakSj?FC}VYoRJ(B=r5qL(Ync-=mgwH6r}uu@Huu4V+a z4K)byyuGL0#g?I19$bgmdk#rNHpx)vr{TR^A zP=P0pF!{h#`39agIJbO+;rcP4ow{umpmt40(G9$0&d7k3@{x484|K2ffrVTi|2Rzt zIQD&$4@{MBDwSq9zZ zQDFadKWdj{FjdW2cbt-2O~PE7hY{i;ysNW#hf131WddYLAS7r$GyA> zx=mBy(p^7p7hW(`zBw13o>#txNZ<-DQMt7a&=p?L%`Yr*`ZWP7)g0O!{trTE=+EUK$bT=(TdINf>T=2Gr(KDm&1X);+O-07cRzr)b((x&s(jPl z_S;NV*{%==NWMZZ{kF;(;a~ zn3@^8E%=Ar@)3q+x1n5v1L|~^Jp2c`sp)?_bwj{P`AE8VCPBLqtX6=U%^zl>A6)1z zlMhUluiwoZ=az47kaCL<=-wLw(TXp2Yrb3j#()V{1ho-wFa*Y<(#JkfP0$9&b-^Y7 zZSwKsRQaZDwrOtp2*Y)2Kt06}b6-655z$qJpiOpdTKuhtC^>YiA2xd`io5P#Zw#1- z`=%htE?s7C9Um~p=j6|hoGlDg7=5A7SMi-mER5HA^w=z3S+vqMcy zFjdXT6aSrCO~SB(A1@hBlRTwWBjOb>_r_3A`uu?vfwz60)K%GXD?g6O(a-4Ik zi}#}!Og_A+@^#@2%tC54=JD-5w2z%C-1J zWv^4T#OrFtRnNL9VEo^V{U?%|-Q=NGP~YNAE$b<~}LBpsV}9L4Ps5z*N2FtomYZ zy$D0ITa|7NxVJp={R}M$h*o@2z5$bN4wzs?(Cy{Mqwj;q{XjMGzO;(eoHQMH&%edw z15@Se_t;Chx-0%FE$;Zo3ec6_FDob-bz8zy4+Pk+Zj<4v}NwP;I|i< zn*435n$w5BnOjZ5aQzt27Vle5AbA34neT21SScS#8}L;NQ18izTgYmHdfF}Sg{%v1 z_KwNNk5lEF_Pcj-%SRY4GlDjM)smQX5E9?Hjs3oDZw*)}A4xY`1M0bq*b2pdUqsu5 z67QPk$7_GtF3Vu5e6y##ms>ukZ#qGD}RkKr~(w^`XdeKCMID9cPg035Q+uv>rn0PA%Nv%d@ z@e6cohoIJs@t8(ke*DZKCLi8Z`DXobOkVjKPJ;6plMt02#E>xwXqmC2nAp56V5NK{ zb%WVmOlN_*`}j3-AE-+%vh)hRJvSe#$`H6&)&bP$#9V~Sa(C0=)+blxLw4_GN5 zN$obr{h!qWbdNsF^~!N(aJ5}#w<|j^Rlbo+-W1o!r9$x}yW&CfAyLV5)rM`aGUjzJ^HPT3(`ZkMDu5@b>)G z9RVxlBk2y5g1X2l=UCc5Ebll2`+jQjfvNKKf4QDpKEiO_W>6)Fi$To-w6>xp=*|ip z)8~$Wm1>gIZjD?s0_s%0WJXX+x|C(`f=#||mt`%7eZL@T~n zv_TbD_A^#*xFcZVtrR3}iM=YQvs=??i1E7TaKJ0iHZ{RiHG3~~UT!rB!%b&_H^)o3 zetI?bgqtFP%bR#@0;Z$5;`2KKR;o$TUGxCD_clO%C`^uygZIB;YKr%Ny`S;F?iHzy zxgf8aouY`l$(5)Ohc9ME(B0%ZZnMz=6K|y;X;b-CL3e#2UU%FSoVM~e?V=5)X2xmT zUz}IIhQw?|yCvwlHD3)I9k5a_lD0v%T7WvCAPo!XPF{eE4K%&LRK5CqJUq8vgyGs{ z@S>}Zi$mAA<)tNx=#-S)_x1VfqXSmTN780oss*U|OIi|83;txraNvTEnS5ZXd|huC zkz2mGLCV4is8iE%X{{+SySi`gkEJE)y84)aiJH}dq^c<=2|)LRHP~~ZZ`-96OqFl= zidW~Bk1(vXc8UaAf5k0AEkQRMxM^ifz{=c5(iL7%XI$c;y?O!eyPxR=ChIln+Pr#o zN>pypMpSx)`zB_ncIg}wuu>qBZqxy4Ntdn(XuA&U^0!BiHofqs>NRb@8}jPakf^i( zO7SEry-7cIO>Q9m+t5WD0W0Mrsku)EZJ@h!3Ut?^gQLDT`M^~9MlN|{Zutnq z6;IISI9mm%rS(>F--QP@0#?dL(hb@`H_QNCR}Q@EPycM!ZsJYs%1wCT(7f_>iXwU{ zTUrC6LL9!B`#?A59e-ydVB)P5Bwg(`7o~9kUE=`0da20=rslqW1CGcmUqd8t;|ij( zV`fe9y0#Uss|tVmp%JiBO_H{-TP;Ah=>XK7mhsxxx_FoSz|_Q>s%DRcj>@ZMr$i;! zZoMC0S#Alsw)MLm?hII|7fJKRqbU*H4lB@R1LM(@h>NZFUAypt$$H&+OkTYj5|uWW zvSWy-+*${SR(w%S&@C0MdF7n}6K|y;X*<%Yf|`+~EaTNnPURjJ!P87lFjdW7J06!? zO~P=)3{dx7#QCe1DB>opcK-OzfR*x*bSG{>UB;BTd(h3@g9Dy3`M^~9hJQLRuYB={ zNDM=-QjQ(tctj+ktNTFPDc(^mvB6ydE9E0;7YA3x>mK36t4(}d!>fyT{bj#zmu0-E z^7XytguL=KBr4aE5S8t>ZHgDI_+n!u8c9@Jmw@Z>pLzzV4G-O~P=Q5!B0BWwr)%?Q+k*j15>R zA4%K3RxLnx*CFVha|ZX_Votke1XJak^U|KVxYe1L#KvxwW|Ml2_mGY5vH_CYX_ND0l@70)#|A$gY-)n3YIfWEpuB3vPGSthmgQQ4TGA!=efjo10W0+) z=_am0T?KxNst{E9WVQxeIt06(Us*tGc8J><}rM1TetkjF77H!F2 zpu0o~bYl{5tB!xSODmYF*YKCt$gLM)xY7#hk-+Dv`#@LsfjSj7k}=7;)o}qU)gzLm9dt4SEH8wk2vhC#IAi*+C9=KXh>GA>}^trR5PVMEa6 zP0)?-z+>(o(imp~)B0rG)M-W#w|K9aiINVW=s`r4=T z3PCp}0f+p@-W&_bIV5+=h4B zC#Dyes#mWs=gF-XVYm@7r~?V01(NLyFYSC^z{DHxkBLb)*#+vqEWJX| z%`bqnH~g_(c)?UPyNsAOx0;0E3NL6|_?se-s|xWd%3incuemQ^rJ5vl#Bx9L*x;4h z($Yv(*#2R;qaR%QOj8p~Rde=+zs{{DVYn4hP$h_aMdIY(r}qU+^r{N#L2D5RkJ~*1 zZZORR5^v%sUf?99N zwsLT{6@O|MUNAMg^*(i>+-eerE4*NQLpnYr9h;7hV%M|p4_K)eNmo2UZFZ!x1Ko5M zIN(^*3ry8(+;11nt5>HeGV?!UzJ7TZX(6V{u zYe>wlpG;IX+uRbbE4;IR^I*VA`AE99LcDXQmqFLIf{T1>@`0)HP2GQm-0~5I8oGfx~!B} zzD|kC?yzbJ+AS{~#df0~3|OfbNt<-4idR?KWd9XjJp>}V*}x+%F}=W4z2;2JtXD%~ zc1|sZKNzr5O_Hwgf;yy=jvnaNhQO2FH8sIhHK*IzYG52D%x&OD-KBuu?vfF86`j<(AwBy4(lebBf6arph<nCi&;B~MUWDNaAgEa;R{u?j8Ljx@Fcz=dwzBYZ4+TuT)q%&sqj*Y0gztoUNt38Bk8ztRHO zQLGga6E!P>Zq5#mJ3k1zvJCd_QvOqyOa@cMox1f?dByD%33TE}raXxXark0p1l_P~ zuOlY}OuUtXq9&)CZUz)|Goaul*O`1^s(i(T&D`=4hAY~jn-B$E?z=rq3|J{2NtgRT9pS}> zrCxwj{$YB7se1L_;Q8Eo5r)fdpiQDQC1zI@;&nZ{gLj`8Fp;lXkkmn&EcdiMWzP;g zt!HR=T)0@1w|s=*Ixe6}AnRf8-#9T~W&R>*8G+v2CUSJq#J30ZlndejX4X*gOsR^d$ z&DqPnpI6OJiP@Ttrl8A=1gR5N@#5i*V$C%k30Nr~N!@Qd0r^1dxYPvgZMnMO4hzrM zF53J!RlXkI-jr9qhD7BW7NW9lb5p!%#TPRpURP0WH~5i&iMLXa)DiI`s0r%uSr#`y zml?ss_BS=bR5fQ@b8Buj3By&CpkB!*ThKt4H$ffM-bmg&^od6TR;o$TRg|Ec-2&Z+ z7(8Q)sR^d4Ic=Lea;r%guA&5OcB?6Rp%q`un|R&Q$2p5l3Yd5+1xYu*0J`}Fu%GM^ zl50@GTmEHgg2`(BV@zH(J4FK9bJh}c4aUCXTH@7`emRAAnY$+itdx(WdgJcW_;N}_ zT^Nx!%fMBoY{$*H@#U0=Juf%;z*PBqZGKN~`3S?UTY^^o$Cpzg>ay?E$hY->CIzgN zkEBW;k8D-N`{KX$jBRneG@&NApj4}p`}px;ADVn%s(hnAx>x1f=W+Sp49_5`l3Q%u?jgvPu`LQiC)dlx?-sI!Q$?`3GVQ%>dLuwxHH_mu0V5NK{UB?)F?8fEdN~S!}2)e=xe%IgR15@Q&?AQ^x*#^H67n2t>L6P2#mor0%=rE>j|WV=m4c*uDH+s~9*560@!I~Yy5N8IFg5vc zs+v8Iy*js=grP-yFhv{GIhCkpOVAzQ-Rt4U16ImM(mhfJS~sv(fLfNv)3AU8Z!-D7 zRQY-=eO+$(2*b6@puHgHPi&PXiHUy_pvP(Y*&R~s(jr} zy)n0ZgyC8e(2YqzSNHY1b#lN;`AE7O!9blOkX|9^S`u)`1tuSuD&LGHj?66|VYo2~ zxcdCmesZw}=(;ta>m;7~&E$ZUYLZl~$B-F8y92Z)=vorISH5X#f~jf_ee9^bYIaJH zF82|Y8v!8&kQd z6GSV%*pC5SKW6iHI|C-(NDKOwK0aY7-6q4!-# z-3Pk557exBC7JQS-#rnqQa+OQj89d(2gq`Lyb8W1Xt%u71y5Ogp>|p3Z&T$Pcl6-A z@-;Ln>G%zy7fn>lNREnIgqnhA#TPRpUhVW;j+%o`c_Luqtq8haAs$;Gji){$x^4}4 zSwB+~OjWag*OPOrNf@RSu!K&iZp}faZ?a+_+n-xNX<}}QIVos^v~as-fD5^I)Nw6H2J_(`6ev2M{fBD!_8EKh{G2PFX(!O+wA&Oz{FcANb2mCY}Nu# zla^Tax`BEcQ_kOjhi5~eRQB5w62Tygu2OxH&wpL$L*6_KEiPOi9mPY26SZ^bXDQ8|9C23rJ5vNSq61} zK{f@0?!*Xq;Y+3_n5yQm<@d|2CSkai1aya4K~+<3;kc^j(*Y~xBkA^3gL?i(&h>+C za~n8*rA6Ci8BCS0I`x3u@)3rcY6bhqVY=ybTqd9MbihizNa~Ltpzwma8$?b(fbOYZ z@cjX%7nrKojFS(}t5>JQY>y(f1Z`Z=QGD|1(*Y~>B5C7_s(9TS@_1EiIS&WUH_7w@ zQ}vp<)+%}RYDmnkcoLNzP-=htW7hG_$cJTyL zNa=mrwt)7x~kYd0`ezTp?Ims>u< zaE$|KL(!Hf;u?pW$2=1-(W_FB)MGI+kO18{40I1cflm%M`M^~9dThNxZutnqj_I#@o?`KLu85tL@T~nmO<_MUQa*yx$UL~OuQ9A*Kxt4|FX;xfUe&Mezwly z?V=5)s@eUzO>(PA7_Ml8I<$(5XH5~vcy21-? zx7yO}!VCWI@%AE; znsa4G2dH}xq+JHjU7GzM(k_D&2bp}}|6aaF7LmeQ%C*>kzQ~*V8cu>?bP|cmo~&#M zy25+ko6iTVl#irabpqWUg!T{1YXrfUCYyXt6@vCESzUg7-6G4hODo<~y?P(`ZEn2?LlqfHcAFb>Jh|TzbQcnRbz&=E zrCubpEXzzas5{|gOai)@YH;BLO+GMHzM|v%-0~5I>-T}y?`svH+rIY1ldXW2@{x2~ z5`g!5Iyc4@{MB_!D#T$``lp#xP#1vMpam9U$WH#oPzF`IwCse<5JvtrR5f z*h1BzY)QbY`C2AZ!F_%(`M^~9dJXg>3ZV& zu4se0r&{(efbK;zaN8?PT=2gWw;jy1ZcB_pq%QOP*M7{5_kYfvHwnY$7bc1#U4J!d ze$lH_&^_wSk2Sl=1r?y3SL!G(`|*W<$=_B4T{DeGZ_AW|54w62eBdJ!7fcm*^wq!Q z7MC#G2oKbZEL&|rwBn077gTYj({tyJF9uA!m4c)mh<})kgrHvcAzf}z?<bB9efR*x*)Vw*4!VBu8x7;cS>fk39?Yek- zt*~6X@ZwFCZ|dZ?bIV5<*3NWFka|~7oF8opq7`4P3i+{WJ(5QJR&eYqxRcd66`KR?RU1&p7^4mn9zQGz$FIiAoD#9M3eJBGTn1 zNS7HOdgP^mmGY5vN5w#QdIHq{PO=dPeEnvV4@{MB)WKu&%GW3e!*vqDnRDL<2kjhj zNAcDIF9)oYkEGj#2Yw*{Ibhk$<~4x0;0E3NNT9$Ku|tmPp{H z8@BuB%K8Z<)S6u72?V^o0Rn2~%P0Xz(VQAr%B^S`G z8O-&{Y|RP7UkO+#A4$8iv08vSSd>kOpk75I4KaAx$tE9|Dqk^bQf~PO!}YO2JM!KX zMO@8@*Udg$_FhyZTB#;U9XrMgFymD;5p_eJ%+|<{-| z%SRZlEQ8t_#FHv5iCMi;mR~vb)qs`qwUg5Cs}`WveKNuW-HurBpMN#^z*PB$K6zGd z`3S@1K2QfCF$c9o5gk|DOiMCn>Z<`OFs!zZNi&uUe4QyeZv4&~5(*58ZjCc4Y^q>ecn*3v=s57%sbkI%t!< zBB1VDl~awo-2Ym@%Irqc&TLl;aLKVd#EqIV(GOPoGgmFsS>Q3(n0#QWd^4`TB)5Eo z;ij`dEr4=*0(9AJ<#}EYSScS#yKA~yfNonRsM5|JiM=*W%7Zk@=aUk z@Z9ndhU@5ox@s;f?sL5|nK~Dx-#7iU*8^6nNz!eb16@l3s@9LuZ3e%8+0+D6)$H}r zk-62J8}pegGl4ca*b;PA;jcG)BVeU`Bwfb^)K*(ME}&at2fMGla=R>psq)RZ`sm#9 z5r!+vpdNXU%m|_tU#uBHH@Dht*c$;8Z>1pVX7)kt$H-14(A~QQZgae;38tz!y3c^z zY7&O)27WR7KBMi4`6Liym<0i)-qm_D*RDte6FHoBf$!?%#Rhhp6r`=(CfvI{;Uay*0uZG0z zhIB+_N1x)=DiK}NF=>%E16ImM(j8O;b?Q*&qCvN=1it&7$p@y&*LUWrx#c4a*ARoc z-(Rl%0j=riDBe5Z&488ik#yZa&@BpsZUP4UY1>uXl^vKWU)LK?%Pk*axMexett)|O z#TV;7P_t@$0=A==_s%y1Cf9eL6f18}$PTV!GUJZ##8B;s+MYS7)14nEm+^>*O}Q`H>!``vS^Nf>T`45|dO z$O*cs!>Omg9k5b9k~)TyF$t(GNxbu>R)97yTNj*lgvp0DRldG6_slIHVYp5r=$=pn z-H7;w*4qIqxYe2nSG`@q?DnP9Y zWvX?~^6vz!l#is{TT?ASyR5G!XuI3%g3E+8+J%=Nr{=zX2dgZ4=2SHc&fg9{@@`0)HON3*=deNX>(kxfefZDB*MLV$1jV2$MDqr7eYvz@&Au+qAgQ&Fbi`9Qq zylBN2%Q9Xq={M65?>_�TXXU&~|B71$9$!>=MQxi;8v-|mL=T);) zqSCE`Q>puiN+q}&y()Xfn4^haar!SN?b+>`ppIw8BM{yzH(#?|*@3A7b@|hJc?D`n zRJwR}G5x-_8nVNxCFrhWIPd0n16JlQlCG@)bvst{S67Phoir1D+YJ##C@P&tvj~`$EhRFw}$~R-f zd2`E07;cUL)Xlk5kZ-Q{O5~fd)q4RemX9!8;{YBZUzD$-=yFli3X5MH)sl3@6V#=mxaL_CuiX?}7wk6J^y0^ zKyJMV!G$ znp#jdf6MF6AX@Q7`HnpK{eTHp1l@@wJi7Z&CIvvZOb*r$GWoz%`3An(ky}2((AIMZ z@_{z0Z3?=~h}U)WPI)^1ZM0HNlDfz#Q!Jo1#4<_)ZR2IV07u?sYJ#b1&bo5R+-eer z8{~re(0v>mv?OM?3Vh`fGXhr1N76McpcZY(jG#(Ck$w#L(7#PSFjcIcv_VLGV{)et0#?dL(rx<%pZuKn>M$j&fs>|QLyTR|; zWf^a(d~>$@aLKG!DaSV^V;DNe8LPth#$-e{UAoFO9|Ww_i=;a#4C?)%GD8KrULm;6 z8KxJQs#o`4eUewNMnM>^w1Qeg#UWi&ylBN2)x_&YEc?v*AYkH+HxkCAU8ztNbdSH_ zb=#!DlV3D7!BjPeJ~lJAnuOunWl-;Ci>p6PQN*<*cy)SNu0=n0;|~K?s!37~*laYG zmITz3!ZLgY-AV{J`nT(}%QBd%X3zRR@~YV>F>7{%r<9z7_d?=l5X7+ zv_snU0zBjx69`NdXx7$W$XcPn3@^;P53T%W+V)k8Ry0v&$c#25m)!k^~#+S z|2XcWfR$>JbQ@Jc6<3aKf^MTKxZvKVCYY+`=o9DURWm+b9K*1_NK+7T_+njoiD zO!_Eb;;j@U?dG$reg0A*h^=n5~WJv-Uh zyYs#u2dq?+q`UD1)T`S54{>J#uI04;|E>4IgQQJ}V~ArYl*&*@WsXFHA(?WJ3{hUg zd&o9yoQ!48RGG6)$rQ?NJBD7o${Y?dhoUITQ2+J0@8?9gK7*Q|hPlKhXzor1C;!W<35Ke<=oh1F1-~tM`LKq{H){R&W6Osd zre*~F8(S*kv!9EuPT%Yf;eb%EzMn3Z?D?zn1GUrCkQMT)Sglc)?Kl zX592~T>0um0@ISdC5c%-R1S6=;j*OQ#YW;PAl*va{SNNW#W&~TvwrPVQ3<}KVHTJgAG1WhnrHstF9Nvy?`tQii1=8{3sylWPm z*r!uoQG%gr4!-gJ*lOa2>E(dBGu6eW+h*v{oHBml@vjS{Og^$E7(v}sC=^zelWItxM4=qpm|jVUC?)Kft2Y*RvRU^Yq}&>ZCGUL5bM}eX-O{K7D!?(resYY8`Ms2%?_ItrkTUtmnrWhrUN`-)9v!Y z3x>+qy7e=$<--lrbb$WVR+SVqvs=S1`=&t3zjeal;&_I&S~0x6S^tZ6zxT_AO{Teb4#qn`76VGY%*8r(W3#3dhvZl0xGk+Q2c3Del1^sKWYUSU4JIL#WHB_%9 zS6>@jFWfMt6*NO&(3jSV%6G?Ju0fC?@c4#r3#3dF9xGlm?nXF4*H2uNN4q*Wl{0arLT8al_1C zf!emZ4GR^qnmy>B9Qj>=l*va{*VG?lm;vgG?qxC+)J~5~rh23}?QqL-6;Z^@o*wq#cLh==A6ZlPfx0Lx{bW!BS$Zm9={heT7%JbSD{qZ0 zA8wfF1I;L{(JG6=BYyp^K+5DJs|!iD5PhIu`lu1~yMSv2um04_$CpFpEA4$-Z253Q z8wWYf1p4WC_fipuXvO1#5j6W&FYh(4KoV;)C2MvLf_k*hO?K6Y)vr3$3f67AV_uf| za;TbZt8S02CT^Hu1oci!cTlk`KAVQP@yoIg^Sc}86-b$yWVPTwLu`V2Y)ZN{pibV% z3}q30H5TPBD&JT4ePGd;7~h4Tv}u@+OZrf7qD zN23&N&;%pcZm5?J43)3vwFN2Q=+6h*mtVDs23+1mopTe_tSp)%6)&*349cI-Z#$eMX0-CBa%Z!K(>| zsyXn^GvfwhgGiv)pt{qAu9N7zGG!Umf-kc*kF5Mdft1NdR!1yP&`AWfO_!DgG_w!j ztna;iV5odm7uUp06>_}*sOJ{l zY494cYDMYR3~B|pec!9emqXQT{n6gB)x-@Go1lMXZdrUbv58eDZ?2}K@7Z%fft0C9 zR;}ZxH$gM;1Nw=KTCon1ESTyS0(5ObNeza37c)^)oO}-qeX2;|AkF6$dn87uu8~o+6QP7;8 zKjU8u3ZzUvvVP93l!9h!5@=2XfY<-i%Lj(aH@4k@vE{=J(};t9qgO=~F<18Axz)k~ zDU*+^fA@1K1+^OelIR0{MOiEOeDyAQS;iVFU)%5d#g(r?ywb}W+yqQn&{TyuX(l7? zFD)#PGWp1A(SDSw5Y+yYG}E9tzYM-~w3kn;f#;XgCpV2NU!C}@ddVC(UTIY*gKH42 zcwAKonyHHSURqcniM5!LHJu(%7qCQ4&}>`+mptUv1Ve*y?m3&sRueZ&SqA+%sp|Bn zRzDUmS(8MOFSCPui z4*iz@SRiF;lGPtInRW)$UZK>CpxM?0p8l0r6AV>z;KdzctBD(?W(3V;eW01?DfaoP zK+5DJt5!F{b9Y=j)Yz0@1kFYX!R>d=i#8Z4Uz_gR#+DB^%=iy9bKoFa@wlQ5noEI3 z-}+O5B-Ua|R`rr#1kDTZK;5xe&uAKa_#&?+7^>!^_B+K^6E`%Vq}c(@>lZ;&v_UPr zvK;ugZ+DC7i}<9zPV3#k1Zc=m|z6`v|~ji&@~o! z;d*tt_>x5hQYIf+9q`EXFT7x=e6!bBIj(#SDQ;ZyT|YNxC6yg$rW^VU zUtAz%dXd$;G^MnHW_LTNn|MSoaM+<C7l`44AJzh;PRLv>3H;=6*ZkWj%(Dw=}B9K}qAm263 ze=d+R`N*0v38)L%GA04F9*{kD;H00te1d^S`vlFU!{EPm>zP-DU}!K-+Nfo0HF3iPBRKAd`(EnZ zMbre*ipLdgP#5iFY5#+XKNm=1Ev96(8kKojP(xK>6VzWM6(zW2v{w@hRkJiZx|)qX zU&PE9=$H0guh5}smw*4+DdJKlA6fGTH_%+m37TL8*Z#p!t z#Htmgl-6&r{iQ(4Ugjvi>* zij!YmQXpk&lGXT<_wImtwn9oPsBcM@*;DYc$zDw`RL$WZE{?4xZkQPtP$Nh>dLUZy zxTXU%b>Ca-EiI75T1?6MSCEwib@p@)`xmfkqa?cy!Jn%3$jdSqs%F<4evYkXqm!4? z(F66i6t^R`BB;|dZtGih`oIZG3#3dwvU(Cqnhwxc3pMg(v*M2RwFA6-V5oep5Bw#z ze7Iqn4p669+?-umBrruAtD=mEUw&d~ft0C9R@Y1A-Ik#5a@VAwpQ)}D{Q5SpCe~0j z)6HIpttM`mZeXL&a)u8?D;^h{pg9q_WAbZ(B-Ua|)<V4)JHZ$s4_IRB;CYT|~8%|;Y8K@*#x>U9ex{crt$Es!!b$@=x>l2~xm;J-535Kd!y5P0gYT|~8P0(!G1WiRb`TJiBq)a}tetp@! z?#-c}>2a@nbLi(~YXx6_$IFK`RK8yO&5SJ{Zm4|vx;KaV;$wNs3|6z}b!xZY3ZzUv zvi=}ODFyXV)w|S;pzjjZ3V!g{z4Ee*HB`Qq$*kD&;f9Gm(7Z!R7e6-Z(&resYY2-LY8+0G7Xz3J9VYvs#pPxoqK4OMf(*>A*-P24cC32Ni;8Xa=b ztVwOP+ZPnHHgnFe6&4cCham_ znX(LOyX@X=S)Cqw=I;ekCLdX|iUR6s0I3;4e~oFa{M*tIUOud$^7U$YUu^ks!@PzS zL>wL$eV|!i?*Gr<3nZ}?Q?llDZ=hcE;D(YlVl}UO!+Khsmk$h;ujPmL$Ca;6oHSJ- zUg>;{1S4pI5j0)yv#S3nkTNyNnuZ1RJL79oP)ADAYL90x8prtj3os+9k2-n<-?7f>nD+Zjqo?tPOkblh=J%L-lGq;*r>T z;f9GmP&>vlL;=x?$CYK!T-q}2p+5>Fu@+OZ{v2LO(9APp)n7CfHNg+A_iBQnYA)Dn zQfxJG!$cqG$Gm0n*_36hre=Kaw?7J`Oii*n`yhK>LH|DCniMo$Zt$1SyqaLBnp3`r zt|o4nsU6Ul$FfL(Ry-~?vFg^h8z||^_FYyWiM1%`mjg?Je(+Nx=(VmD+^AEpyrlDE zLe(5P?$Nlh*&tq-1Gso)g0T_DAm3_Zmla5vd}LK1w_H;at9Hm=pe$qE`h2e!7^+vB zanoY!g&Y1AWbV!zhbF$Z|7ux*lnF%E%rAgCyXBSvYEsZodb=C29UfHidV!&O%{uhC z*m~iH&iA?b(Xu#+I6SU+V$~(8>xi%Z+b=JW#Ok_%E~|~hZNwMoUq$b_fe!TzrEYIc zt>Ec@**7nqSVQHzpt?S`e7K=Clq*veanj5No_Epm0x8prtRK>qQcz#};Rbv)f_^Vj zt>Cy5yco4OME3eg9ej^2YCRVAcMKC*s9TuMQm?2>LX zXjYxT87uCWmsT)TzS7JqV#|jcrrQka*)ZuggQjh5L|Mao_mrxHl&MM9tdoGcb;PYr z*QB7|fL$y2(*Um~)=)Kj-F$UiH5G8c_krtVw%OjSb4^df6k=|G*DmaT7~ znePMFzSHXk2J3a~HL>-=4ZSqo&2d&z&}{$s>nbZGq)aceW{?Z|1Ku?$sMV-zwQB|U zSm5=-8md>{O|OlsSDkoe1`>GXd;evzq7{!*6RW>$raIl?&=nGrSc`&Mv}H35md9tD z_1yUN-J1hy#A-IGV(rzvcV72_p=!2$Kf0Q@p#@N`q5)N}*9k^Y`?_*?ZooY&B&19} zvgQH-P-k3Zn>1)nK!78z^zwnB@>PwwE_N{DhK{9Vn>6^fyn)iSp5+uYO$TV^2rl|* zg@lx;N!G7hmQv7M1_GKx+Ter_yqaLBnsZMd8duE*@!1^5!7Ie!alr_heVCW+*37jP z&2st3Y9B}rX@mNsWMdqteW2;ojNrt!`{!jD43%%nt|!NpuTH!&-9WtZosY6uO)z3L z!PqdmSwa%6iz!)Cv_bu{s0o^dB=EDdyqaLBnv>E~W2=c9W=sNVKSs70f)bd-W_9}M zN6ivaCLdXI#vRnt03sh~F7^SJzu@H)YvAFgS#J%GEgx=}ni2HDSP{Li|Z{)^s@HE-6Am?JiRoCj1mt`y#+9!j#SI<9NlOBn!VBtj)_shK zTb@%$NSS(U*U*s!FOtu){H4J}^|iB?q4oTRzOH8r;yOt}%G4z5_Xd{4s%M>KO9ED{7UYTmaLYfunqa7!)BhP= zP24bjY*3fhX3`=uGGaLlXh1j48RnX5BR;N8CCkZK2ldKNCWji})x{#nb z2?ZW`vsV)gRkQ6s&X27oZkSdZ)OU_arw2qU9v7;OUzT$}PgJd#ki=R{$!ZfXYo4I? zC}nB~)Gm<}eDM9Ry_#UCnpG$78Cy-<(9yKJ2)98L(W8iRYznJ(*X2~>HwUbkkTUtm zYON}lHGrmQgXUr%aJ3x|%=h_>=Ro)+%WYf=&x2Or=Tg?pqV#Yc-x8zDN~cI z+1Ul^_2RO#3p6{s!0L;=nqa7!EtCCXtBD(?q6E!M52$L&wDyc|S4>Emd}Q_Cy4^;l z6x1auX=gyw&Vb*%;pGEE<(oZg|Jd^3hUpT4Iz*BFIfzy~u4V*H2lLaeDftg9Jo#oDY*-@Ghi4V7=k?FYt{uR*->r5ZQ$_Xh`ldQS&3^bQcfo6yT zF1pvN35KdU^zsg|)x-@mL;=l`3y4-cE;d0^GtOH*O-N!bresY+3~EIwMLYjuHcbhq=SENF^0R#Q>#SeGWGOii+8$ptjG8G`2R z-{8U5cs0RLH770FF}9kxVcHo`3$N>AS5nY4(}yle6H+E0S#vQ4s59iUmJgZ{9(d*_ zUOq5XzEKZ!i7g*)n3@qZ^Nb)`@i;X>GhW_w?^P0#Slz^;%bHdj)VFgs0cx8{cdewY?XwR$wyWL%54fRrJ%k@Tvn_= zovL__0W$b$*~s>L&!!*qcE?o{QYIf+9nUuGl;w zWonYu_>!I-XkPvTn)xem$~>u{iM5|bU*psyKg<;xRBc{Q7xuIL5M+3e7~c!HsN&0S}HY`t*9Pg|Bn0@UDfPHUM=^baaNJwHW3YxVcELsmpFB&u_Ai#zry_#TXFisz~B(9nbB7t8fFAJKo zjFVh4~S#3HVrz!-^@g;D^170sMRIgq=ev7RaZkU^>LDb-J;Rc$PWY(H% zBqXsGQ?h0!FQ{`+GU48cvPlD6u++;3hRV03<+8Z)l|=#*UwGxOsjN;H4PGN5iC!f^ zjXvr6V$p5C&r`dBt$H1n*KS~_K(k(sEKq}Z<;$bH3eb7wC)%phH6B?bA!P!QH4y}w zeJWsw8@)has6Z2ImdA~tI+4JPwD3yjgk}8@G!@oozps&yvI0ot6S2 zf}v_oS@F%-YT||oM$jLnu82S;7$4oCIw6UCrIf5WTmWiCDUB)k<_3r7g%=FfYs~Do zW9x+*Ci+0LpBprN5l~wacVT;VdSPvKLdv3#tXkc*#3ixn`_4Y4D#U6goxt%Yc{RaM zHHVIVC$^fnVVVvwkxO9SV-5;LD;`&tL9@m2+c&Bcl30r=S&dv-%m(#GNzDlAjnFbB z1+Mb6R}&0XbKu_Z##R$IOj!nXGmgvxfc|>A>a=y6H4{=MA6c^#1=Ix!=_iBwcaowF z?zr+1dC>+#@<>doI zAQ@b>g#WYVk_@ zy0V-InvM%-<~Zx_T`M7F@{!d|W+ESG-o*#La+Q}443)3f;K{M&!woY<+~~8&2O1j0bg%-R9<+&P`#E^qU(hlCi*~ssef7YGKCkbDsm^Ijt#D9 zm5?$u$(ji((7Zq$H1mDnE+wxf7^-I9Kc>cxKHM-(E$An#%Ayxq@wl>#)wH}lKWUYa z#9BSU^Hngab?PK{V~*N@Dy}(et#$J9)Y`t(phgNcNC)i#ZS2}Z^zGxf!*rWL6MdkW;A_=v-Gn51l~S@gA0vY{&|I?%ZugDX3k=n3?8W2bhFgR9 z>~BM?2%64Ehra73q%5GwnvOAOc5H*@;wkWeF304>6AaaB!P7(I>Q$HGhAEz)e-~Co ztfnVCaNN2HDU*+^HpFh{PALV=J;b2ti-2cc;^hNF zTQ?zP@{u){Z-V{h@S@x)0Ge~i;G=JO`M^;5CJi|?wtTo@YBx}aqH?DIXf|+PwR7u) zl*vcdyulJ|c;$}0p8Uxzebl6&?#ggm9BTz1*yL|{;l&y%U*BCv#Fei>yqbCjx4XGJ z*vo>5!{dgrjRK9QWBll-)(J_hML~ah%q{FXi}rFP`oNZ|F7kn|pXTKQL*;AT>WsMZ z)rnWy`H(9a@apHbyb)BQ4>S{^i{EXXkTUtmntPi;b94$cO)a?gb6!3$RK5kTM3)aY z%(wzH7wLkgX9t?apn03Emyj|w$(oh~G_wHm<$hF+G7A8%+WgqOEQ6tH&baW**ujV! zrYZ!rFCvHHL9-CvzPMgO%H$)f-9R~c25R(4Sq61_MpkmcK7+h`V5od!>(7rZA8wd_ z3~25w1WilQtzo@{l*va{dpVQo$ACKdEc*yRtqJR?3c({LdilUm`NrJ3dtCV%)GO)u z$uDJ827iwxR8GYA2%-1E4+?gK;ROMCZB#N z&dVks&|JFy>eBTSQYIf+e;+|91$9@3T)GFE`&z+ybG&?DsC;dI>l0VL2Ju-}7iB^e zuMmgF)qS9uVwt(mUlNj7iz!(>$2Wg!YPw7SDRjY^haeFOfOahv^4>Xs`{m{{I^{Pv8!!#YB?x>YLL7*wT+jZU`A!YIjN+ZsuVeox=oi8(g60JM>922)kVL*xO4e-I12uAGkPBY>gx3oU)oaXo+r-uj zH_Rvv^fNAHQ3P>#T-}G&MBlg#HcUujEv976pba$hSD_Dz?OH`A=}1Q z6E{rV2b!C|LErLLr_)c`Fd=2~ku^;RX!?DixvU2Kyq}j33=PJv9XrRC4>z>8A@AG( z{p+ABqL*np-kRd{aw(IKtcolBKG5`3K+{tJ7moMxfuZuX{W`jQxM89X^c|OS3ZfN{ zE6bp%3V&H?ql6^ZVoFv^`lB?&pt<@d|6+E#GPut7UQIAm&8l(R#STW?FbhebUr4G> zn;*PULdx_aJ5+W9N@VhojNSSg$>MdOw4_f^DdO6&74wn<2t zd}MXi=^47sVDn}aP`Q#1)LKu?}i@wi|F&C1br%Qi_!VlAd* z&2$#1jkvTVpjku*AN$g)35KfK_rfo#qh21|AQG6#XS_0X-_ZRxO-Q0wDJ5&VCZIXb z3y#|El)SWpp#lv&^6S_F;fCKDUKR;V&km~|M7x_o?z^{anvk;iB5O9Ag3{8yE-RCu zULO1$Z3VdKLN6Z}D&MG`zKttiop@z>DtM)hgY1?BwJgiYjg`LHG$Cd3ku|#|K^@h~ zj0%q-udHKW|I9We;?fJ3g!wu6`fZDT@)8rsp@wmzkRIO!;P^&I~O-N!brexJB z`_(|L`=sdr&2~Sq^G3t+vJ8d>e@#f4 znqO+yEw+5PVQNOuY*+x% zipK>bXu6PJt+shW5^FIf>${LOf_jPNRLU~eRe$pGfuZtUu*S^T^5KSAVh8>9qO$mG znrWVGxBdk)$BO`jo519h6zSc z=L+5Rhh^~@t$188V%2TGH=yQL6E{ytVl4`KtxJL%%IMm)Q8j{oZ%wUW@6ldOeoUyE z3+{R|wwkzM7VSX)cKgcz6sS7g>*viAQYIf+KdoI7>z(f8;U90iu~3bmjt<>%oLa#l zA9?xsx1sV)8uV6N`5MG4-DU1B9!PD6U?0;K)c@_}Y%A6$8z5qW6^ zL*<*X<|nb`!wnOCpuc0NB8uoHjR$C3-y6AQLdv3#tWFuor~^DxCck7t0W@>b;F4p# zd|;@2b4K19TRz+{Z7b;Cu2T`cbW9>st-rqFzU)#aA6Zj)LG3fjTw(sjY%?JEm&sl} zFjT%Jhu3QK5 zYv5FCn_V7^D_>oT8)nQ4nq@iAw7k2W&^94u@{!eg^A^_BLH~y58bRMK*9snUfR~Ri zheqG<^&g2XA8wes57dP>*PE?~&pKsr4Rv3iC)y^YOg^$^#s$=6Oqp>3H5g@UC3x~} zUOq5XzFA8jjV&K;nCU;zk9pnfsYA1u@{B^ege3BnQnK2%ie8}Usespi>-7Rd^_nP}S*+qOg^$^CogF3a{^7r1^nt#FCQ2x-;#g(r? z6!E3CEQmNfPClG8bN6q~Z$bQ z-RgAdE?Xs}Odzsav>&By1$Bl>ZfpY0+7P(jU(d*kCm1SF)erxOD^Q*IY$`jv()%>s z;zmWRT0G^(rnN8MDj{X^ku_K4g8H@?S@s3@l<b-nmsC=y_T@_cpI#I-QjPc66 z$p}O%9v6(D*>H8#7F#DIu@+OZD!r`pid6zzHpGBth6+4?^)vIb42G&XXUv$`YT|}z zYC$u>2Wm-|4Ke4Qv2{Yqh${Ow@yfznqi%pjqbyAHCnJ2?ndV?cZXni5seyteS)V zEO15iGBYkuwcI8lW%7|VH6y53X3Ok6sM5=x4eGBwHih22sLYNI6W3}|8#Y0um0#mf{ z%CFT{#H#Tn>u}xnZJ&@b`N*1@5!Br?GNAyPUDM#<9na3oG8h_tGj19lTRz+{eMZm^ zkloFI4pm%v-Q_ViwNFTyd}PfT2heO(1+~?dGY;T|HC{e2RK5uZjEF5CZkVbN)OAZa z;{ckfu<^^%XB_!u`-GIKN!Dzw1hwvyW*XG{kEgNe037$4R}&0XbLgdK#a0tHOj!o? zmSSn9LA2s=H6y5cNzHiAb{!IuSc@rHjce(FH=>NDL30TJ_|p2Nyl8`=YR(?|_t=x0hlC_*mQu31dqzgnpw^o*83DdM)XN8k$~UU_$k_7XhAG;h zKfY8EMNGHmgP9!?QWkw=HNIpr0@Rr?Ij0V4qa-yW_}i0SJ}^|iULDSlEgx=}=mWKA zySBBGg1S9Y_Ux~-(Y6UGlaH) z=hQ*7qhs%9woOQxUSw5Gw**>BL34NxG-oxzA$NGaz)-#B{IXA6z3Rkg(+$Kc^Da>k zt$1AF1FCW%W`AUcNi!C2+n7R-22d&HEv*{;eH654P zJv$|&Oii-p(gaXjZ3#xuOelcAYa}U+{Wi4b^LK+pXg2RVQAVaRpwPVHs%dG}(UZ&Iu`tFS4e1f_h3u z#ucC$mVt+?IWjMvV5ocxnzxTFA8u&eSXFDe8SsR^cTPxR zEv976MrcsyzGRL7G%F$CC4;@1V5piC7j7F{P24aYJ<#tXFN;9FELW$0f7wazQYIf+ zm0o73Ks`z=*E@mc)ePXx4}1B*Q28#H*fF+zxM9jNsN+@%Mi8xdTrh%W40r3=+a)Bi z7E`k3Fe~V<#j6pkneW5;%PplgJxL{{9&w@PppB5m&xCk-*f9c%@sNWk?5Ve8~}!rOUTV zNSSJ}mv7-++bn)zJniL4CoQbelo54IjK? z0VLqZa3DJ830xun|+YV^r` zANbucFCQ2xU)NV!#g-2@%-RsBThQD_`?4tF8wYo5iL;uX%8a*nNJt`IF(qqO+CZI5 zmBI^}jvhGoS+6D-s%Faz*N&|wZkW0c)B-3y70|4-{jlkd2`Q70tm&zMW=BWSj~@a0tpdilUm`Nm$bVO;s@#7Q#*#;axS{eoL`nt__2mgT{$nuDe+Z&JTw zLdw)6Ylgs}-f%1%h(NPV8ti$mR}&0Xb9k4HVylT8reOhf>BHT7Q%*s&;&Ez%reW!~ zdY6PG)?!Ll2W_&21JrJ_jNw2ty9E{(c{RaMHG6#@T}|9D?F=Z|aYsj41TyVRRBfG!83QiFs~@VP&M1!vvKU$#0{Ns8OfLg)V;c{ zq*nxW&~^tWAWpr%OG3)zBWo6gL3sz~!?H~p)O~WYg&(|PjF%4#m2diGKevo}|8bot zqTwbdAn?lHPg@qN#-#* z5liE$*^uJK)HB$gD_bi;Q0w6E7NM@l^=DK#cF~Pt2s~d!F62|Ql=(ZZI|Vw9jI@om!b`t;UM_i zIbKaLRLzdNEsw1xZkTok^taWOQ_#dFXqExmeAYD~WonYuFN>O>=>vgg<`vwn?9~)& z;LPic9iNY@WhI_{K^GWp1w1ya!L-2zRg2kfr zMr<{4!wjxLKe1R&K@*#x9}ZThhrYH`LJ~DctV*``@qho@X~&#?T$_&W8aO`i??o&L zYQys_w>0MevZ~5$oU0W)`>{;kOItTu^WWe2{~fQCZ@0=m={R~i-wyp_^jh#r+&{)` z&6_&iu}&QI4cSA2%d^MzQTYdc<8@ik1V2_qcL3vEvF3kG*Ml9t{>}+W{(410T|#uV zQb};!5BI&)yUUmSvG}5&0jw1qy~4$L&4M*l{w42L;>uqqUYVK&uY4!IEY>^*-FN`2 z*(i1U(47-frY6~q<2Ji9uTFe6 z6*FF$6Vad##_DuIvP(kBUTHg1V)6s8?!EN|ccw?=1AR+Uoo;l;E(s}N3E@ zYI>pIkaxX&V5odE`h5~xKHM-jhL8S9A6F3rm_7^>#Lp7+F76E{>%*+L5H0+3sBt%%P$^>!Uq;R#oC zOGue~WcA;=bAKhV>N%q_@?q7<4|fo&R`4IEd-<@2%Gb8-#MtuThG}^l6`4v|22EKW z`F^*Al*vcdzv`%zg8n6zHG*18xE-bLjJUJjINi$!hRWBbzbAPT{s1d8qFuR{zEBH~1f8=GEFNdnxbIC)o z)x-@AnKMum^eYKvK_86neXGu@k$WRW`(J17nvgOz$(nsYpx?4qBVRV#&anP*gjW*` zRddvwNwL+$4L_Q05TEs3V{VjI7DOu^7n^)pWAjeb+~|c}6Oveqf~KTn(f!O)QG&il zSu0=e@_<(pYp9xSZg@1dnz&&~I;e}eZe6A#KASFg^_txiQYIf+zip$Gg1P}vwGg8}uhfE8?>*e#`q~It=cfkTUtm>Ols#m|IFg?PI$= zF*SmIcX+Mf0sD-~Yev2tD&MR-E{!c8ZkT2oGy^_Rrwp#4@SgQ>_k@(mN7h_e2WsIJ z`9QM@0p4_jmrtyLs}SjRm&KM3H_Vz2sB_> z+_v1%L^~oQ2B-*KRUL2xM2z}=$9QT;RqQ2eW2fKQ7hKw8(f|jUaX;dwVe`KuR8I{^rG=f_aw^( zQxL6qoSKb_JVaHvL2b{3B-Wy!-(*!1)Vfd9l^mPVstS4b`jT(%a+e zRVQAVrlZkkS3{M>YU)0$+8R7S^!43%w}h0bNmlzY?iH#fv1-AWQnQab+2+X-Q5Swp&6HYcVD3Ur1XLG~F7k`e%Cy zHNmS7@@j&iY7YL}_}FUVhFJyx_04V4E`ugEL30Y}if0|Vl&MM9U#(k8L345e)cFNb z6MW!KuO=9(X3uAb#8wkGOi2fIOyWvh4~S^sXMQVN=0A*kyl zGNAzO-|nisEQ6u){o~jcpYflPKc(ARz1scks;aK5{N;N7fBJ&uxAOn9vj6Y-&b6<= zRacyP#?tfGdnx~S`S){s(|CbihSiY##Ot44v&&J*KVN05ode(_;RRxvt|`zM;~tJ&S9zhKvVaf`|%zL zN%ShEWc5ueQanK!bbKRiD|pL`ULY`3po!D=jVn-{_-uN1c%`$aPOs{8)HZu2q%5Gw z`c=A;Sasn|ZUMvUc6Ydgl%f|najmQK@(2d&b^rdc^}-F)IDmd!Q4vM7ry@&h51+GV zLdxVLYuZ-OyukxpNe-h)c?4%3ZqN$m#etyU6@;D(dDnqa7!Z7%8`TTR?B!3g>pm$C@to7(F1_jUG4 zNSSLewva>3@}E~#wcxwRYBq>hdJx{t=v4&$Lb!V^-tBuQq)ace ze(PIFtmf_(tmg6&aPq}oFECWEQ4@}i8+{Gpv%lD@ENBWZPMU7uyc<*O4X&5RyinM?XWbB5;ao%TscnS5lm znRa`1ODU+~CWjkAv#lKbsm(QcX$3>&>-j^w*z)0qulp(@ftdmQ{U7@zq)acedZ0@V zfq=RtL2g6;ra> z19uzxN`hu7605$ELV^*z?LMz27^>#LO}CG&CT{qaq(LOm*p%r~tfnFE*J9s8zv14Xu5&mh{aw$FjT%#Yp)zzKHMXNtpUv|6~L`JT%VU^FjT(jZ>$+tzPc1Qd`nUhG+V0L-mqUn%Jd>@#w6f|@@<*B z2TjWh?mN=!1%~Q1@Y1zn>xCO;HW1YMOD14Ivo5~>=ldn3Og^&ygkUKJ&7L68)P3M7 zuXy>uQ2Azm-#WH@xMAu((7dJ+G_$9tcIuswGWp1w$_~`6;SznInLz-rYJEdqTES5H zCVc#t*z)0qFRcwJsIOa-4SgV5@wlb~Gz%kR&hMR Bpzd*TJ<1wE z{Y$uA=Cy)9HoGw|+I%@wzA+Ddy+-8wN^!#kBdC{I%dLDMTJgA|4VrGvA1Cggki_bi z*j-k~e~+OisAbumC#ezC(T-ezf_3A5UQIAm&8l(V##R$I%!UO}cci(cwd%Bb%Kix{ z(~GQ`*$4gA&F-|X!;a&>^OnkX$8- zODU++f3lwlH17Zf2hR8MfuZsZJbyuK`EbK@13^ClQx-)`(}7iswoGT8dr+T*l&MKp zLsc#p1NGuNSri6UYuVrd-nPq4dEEzws@Ze+PqEd+4O3b{zpz_LL4W;nb$arheG*b8 zA6e~zOJxV@07jY)P}dBkvI9q5=H&xJ<(s|PqS*4`hKAb(w7j4{^j8toQO88;z6lHZ zB&19}vf7e}e4rW9fu`jJr@!ar14HE-{(f}%aKp5`px%`zuSWsVipSNApc$e((*1yh zB-Ua|)(lZVeUZ1!t%CkkcCCDQ=H_GbvWzuU%`xk|96K0s!_Q$HGhAGRSKZ#xutG|i9I_=Qz zz=V{^N7n360QF75G8+h*!V4bI^5(qof}!%w_-P}|l! zXjryA`@n=G)}o*ZMl5EP4)hn&*2A?V*gHyLqL zCP8(2|08`9Ql=(ZU(!or)uFeW4XhFL_u$nEzH*~ilYbkkX5Y4-#8tCFywc8xyK1s5 zh&Vj1CBaD@K3_{q^7$Wq6Oveqg4(9bk}(!-IwTn7%lB|Muq<+d&A#;VfuZuvs=qg` ze03s$nXSRA_Hyy5>lK#8Y8n=-rk7K-f4@W$S{GBY=B;m_uA;cnPK{Xgtmbpnj953{ z?$*3$gQ059nS6h2HE~1r8pC)QG}rrrL>`ZeO;9Hz#uJ+x+|n;0iPc>gzhr3?r)dWM;Y<=&8vDL&4Q&EEEO;MnaP1og~+buNv+AnJvDL&4Q&EEY+7LH@sfZ$a*ibHiy6ocq z2`Q70teHs!^o3<*jd^FUyq_RITqO z7_Wb`e?rRCBx?pRpe{GdiYRC<^Z=iD+N%kMs@d`9$ZERNCe96i6In%2<(q_FueBMF zkTSiB6^u!t?!;XAR%S) zkyWi_1sT)@_;+bZK!0ksR`8dDy?kQ*50AEJetubO`EbJ&UeLVE7DOu^rzU77 zZ+@FPAR&phn3B~WCEFQ5ZFZ#ag4)59?F`@scY8I#&|nvAh`FBULY`3pe3)4jw?`|_-v+H@k)CeGQR+tnf*Nv zJ18M#@kQ2@R#0DQGn>*1nx+;!w&%FKvI9fqn>hX2*z)0qsq8?%L!lxPXmcq`#>d}x zP(sS&BWv0UP-g=r`arEHrK1O4awF@2kLx`i@tISnw|=%Q(G)JmZ>!6B1u{^D$)il#26FHfw>p*+E7fpua7pR;*u@yqZ`;)l3JBkF6$dnCJuj zJCZ8mv)PMO{^a0pZZ-0dgp{dC)&wKycaqe|m;IfVwSxN|>(%7Tp=!1~ z`=q#PHi%c|RdcyGB2Y!Fs ziZ*E8;|ET?)vF1Hs@e6m=xXAIiA~VIHMlH#p%ssdO{}{2;WpHKt=YhYB-Wy!f1y%I z&>Z3Bi`t`AwDu)7 zL9imlMtauB(oQF0al#nv{$eQQ_{o6}wFty@+Eb$BzD=qoo2N=TV}WX;Yl(BD*0BVRV{GS;~hy?kJ( ze6622I<|bcVcKQTzZ}g?EIL$iWiQgtYaE`CGWp1A!JowN8Ps-0c6NdO-MqD8ZS{+n z4{NA=Z6|LUTRz+{O$X?=8CJw+Q+PKy>hOe=$w$_#3V^2N1@&pn14 zz6o`k$CeK_%FdCynI+g zyT?plNvr{pu8PDU*+^_Eg+!>Pji7Lln2TS|g}`7`Hj3R`Bdk zy?lH*RKE1Ktz*lF8>Zs|>im^EF;W(v)hfMctg6?ov?S;BIwB#7nk7NMTf0WkypNbK z-mvYxdEo^^<*T}(Lu~nQLt~^w%M1Edfr_9R!`*e`5eX@aKC)W0<#o=WY$$$rot`fG zz;{Zl^*gK;tUu4ohc#5bvHNZtTRz+{(Ff{fqwYnTW$_uUcwAM8RhEpOUAt$;ozf#8 z7bWLR>EG=I7mSm>aEiDjUw&Uu{$bUE9&Ys+i%v>DNl6E_opEO#KQ~`)h4ff;*N&S` zuN9p6s+S(?|6TfD{>PQ-RZHiu8~Gj<-0+>Ar^U&(#}(v1$^|l3zt5y1s9%=#tdBY$ znUFHA^Q>So1^p~{Nzfn9{ajH0Fz%09BWO19@NfTE@4md207JDN{^Nq!TH}V95(l-1 zB*$7nQ^|sU7V_6!kGuHDWRIc86pJSo2Mj;{_~VLg4=L^3rhUf_ojbJ|wrz2nHi!Iu z=QbTXbnK{f;IQLQI41kx^ka_Ow%D%YZ|USqj!e#J_3+nUtov$x$KTT_4o|)Rx8_gX zynJfMKhn>vby@m_wJuMW8f&Mj71H00xzh?Oq$^(9__I4TTOnQ9vH#)KX>#F_2`P&W zvgT4&P@CtUX>mbwS{B@Fs1F7(G#FaW`zdZP+}0d7P~(=H*LzM>X%N5l0PRoo`S^xk zlIuG7+i^!GZ%(-Gpm~Qh^mwD{<7TT|{!Wiv;U=Hg=bwMQ^~_$!obXP4)9*L=+<(90 zj;;T2zvkDOWA3I(8kL%s(>O;P<Ze~RWNpZnz_Djl?!`s-lZ{`yAIxAqoe-xU$NO^2e0-0 z_sgd?{jbPBZ}QuE{4bx^=byX(iv8TLY5HGr`>=~{Z0K{t)Q;WLBb?b|k94rb0qL0* zf9-zn#z+18hM?;XjSYco7yiF3!EE@-<>^9Wr6u^uajOx}E!uDQ->1?N{ATU0CHTYGT?eiEhDRkNDMuwi9c+C|!NFqs zT;Ng3#JnE>h8CO)R{Aw|!NHBD;gDBM9dB!n8FY2OwhVP5iJ0F#t zwc#oK2k$=3m!;ni+^p*kHC5A^d|sb_{^O$aj_UFJyS`<3^_xl+}j^b{IjC@=S`IBG3|=gw|{HipB2qNcZ#-lzox08?GFC@o0a?BL%p!GGkffj z?rL#B+SlT*-P;ZOxAj7&4%>JA&+CQb-4AKqyQbgV$A6(-80zrjM@H6+_)L0;r(5f? z^ek&#p4J#E^}+>?CoY-Uv2K~x3!|*v)eDy!yQ>%WIr*rBB=tg3&|EErMHfk3V^Skl zUH6ps73+}xzM23-tBEOV{1LmFz>TKS@%X4C&ieY*E>m4Kff=!e4*4ptCiut?<{CsL zU2=1G>s17G_;D|_#)g+2m3-U%i?*X5e!|xpdwluj$0PTyn%3m=`uy`7=Y2A9yZdJQ zTBGk;8xQY%{~uGEd|sb_?qYm<_iN7Fc*@&%wR^Ds`{yPd^wgQhcJo2quje7ooQGH* zc}+QwqTJq;U9BinPA8rQlXvPJ#CjehvP zYPzd6Zge=RXWu=$t|PsP@z%O5y~|pcrw?Sd zd+n#AXYNC-ff=!Gy?MQQ5v@)%G}97%Lnmsa)&RBZ;qFuHI(V=5j!G6)5175?L-+Vv zj3tLiaTx-m|hn;fxTdSWob@MS_u6)PKRl7Px2c$>;NzpkYpB-}M zYkyWW|GbHEJx&^b=Y;Dv`iggV9=Rgu zHy3vue8lER*|zhEou7U#pXW(ezoNA4=oO|l`Mf^={DWSP)qk|+$G$}FGv&i`-@J0^ z)Fz+T=byXyIotbEo2L16TMf1;{qL;Z}(^SzzhrF}rPILc7 ziG0|ZJ@!Z^TO5$SXz|zX=N@|Wznc~4+@Z_=VOHQC_e1Ij{?|1l7^Jk7c z_qJus4?k+H%hD&Ub$L3?Sg8Z*9iLxw^Jyn-^{uqyFIu~+6J9oUS0_Av@X-k=s}snY zE4M+ta$D*I(DeSnx4PY*PZEHkbwby-UWr{N;6~Hv*n8olXY4cfRN8UOh}EpBr?%s6 zzmNM!&r-UVeU}CK29K*Xu$uX|3yVi5BOkfx?ycHC=xc$U9y|NJJ-=%+{cDjNjybO{cY9>ipZh8TD5^HFo5O_nhC&2X()m zQ=K^vu{`pcavnvwy(zm|FKPR%(rTj`!$r(#>O= ze<`)bkJj#LjYY=pYK@t99i5OQ#EXJvRSAo3!jf78G#B-Q3oiGy1{hjvRDD#5U2EV* z)97e@Q?JWgZhir^24=)MambLo_s>UWY7x}^26O0Zfc|7j*TLf&TwiU4Rd+o7l=}KN zvo)x$XC8jUg6Ykst&@E|OFysAKi}`UK2^W|{F(p$2V326;L_T~Q}fUB@8_Sp7=Ob3 zn(wdc|K_4sXVqW1(w(ChzI{nIAJqMNe&oz~h~<&jl=CRc?M>O$8lU_(e$1fO^WBfh zf6E3RwqH7=?K9nGkEl9fpHr*p{Vz1;m3ALE@5@{7ocd1pmUSo0+JIW)(I5Y;=(P0* zC%=zP{-kLBd9Gak7x?1LapPNVzw}Rv=AS!7Uv|HysiGH8d-I-AhtH?h_`#Vy_DFxU zI3Qi|Cu9A!`&5VjW+{5R4xRoFGmT%nA2PDl!%qzvvI@1vcMh-axpLzzU-p*N8mZ&_XEXj-&DdS7@x#KS6H-=dkTv5EP$$jY z+0&v)vB# zuLZ4$X#V24u7jUmV{mfAkq^!K`ky7{2)*Yg)=&O~ES-&%XZ&x9TssWmD+|E%bUC3BapIq%Pk=AY-v<+aA!g}=Ua+?tF3q-g%RQ}lE9 zYnm#0@T6B>tzXkEuXj%uJF~|g=~9aW(&oDv>#yBEbog&-jm{l**#1B7YplHc;N;VD zT0Q?=zl2(2RfpqVzwUveOfaSN{707Z063?y$vE^Uw3|=byWv{@(qX=T6#v`&&1dUBCLu%aR$* z#&q*h+^^@FM>WP&9%^}v<(!Aj|HiJGSo^>6V+OU}#Qm83x4hJQ_5r7lf2iAQBNz4m zp?V9di7kxz)-z5V{ripgOr7_`?EgpHcR)qWd~fsWs!_4GwYS&au(KLi>|MdNt_`~) z%?ftxT~O>@>{zj3Sp=-0px7%GM6n`v1%&V3Np2Xk{y%^3fpg%TXrB9IXEHbUxtUCo zN!@5;5lj<;x4B34&*n!Dd8aY+DA~z#lqQ~Am#W((ccPg`$qpVZ4b`YU`sDM}eD3GJ zV4AQ3T7i0@J`W8-YaS*GHGLd4WvX2DY;+AIogy^mAd1!wutms8$JLKwL_D>(<1mQS zZmFXN7beoN3@T5)don1UrPu`lZpeLz9--rSMY9Ogt6BRTcQaeF*bMctiP?53ul1K@ zCM$pD5^n6D`QSxVg@-@cNFzdS%%J2xM@`2%y#`))zM%+idY;NHZ??-8)LFKZ;K+V; zrM1&7{VQerGgX?OX}j;GiR`pJ*&&?jK{el+SKYY>ZW(l6KJzZeiQt&y0 z<^X3VzQ6x{0wj!ILI;2_kBP*l2%UL0Rp`$B7E^)|@aShGe9VPMUCAtM97U9)J}BNw0sih^aZ-*bW(YL{N33S zgR%#aow5MgFS}TLc;WFnm|}c=n?ZT4YTq@Honm~2Y=;@F-ENi6yqaD_}Qg%@{OOcS@bWk)wXmW z_S~u`M-LpoGk;jk-KHv+w?7XGu83Kqb&Y{$9=*{cqFsPSF!Lzc$#dk0y?+lV zq@VZM{cjzh)Zij#4P51B`$i}|xXmsG5GpU9&0@b@U0^R=3?Q4{tg*XP zbY^D_Y=$~I9CsZw)~&Q2vj);q)`*~|lhDNVH4sWO4zrO)gvw-c){gdV2WrmjT7Efc z${i(Z?9kPX>%BW?P>5`&tg&6T=eTiu)9W^Gl&s-4X2bUbA7ey8wo}%aD%&B(he0(X zP7lg=%jHS%yrhuG*DfnWC8!j8 z_JoGbS-(Q;yvJ`qpmRYR=xc1^=o+so&ucQo&y-NOlv|qx|6*$y6^1J$TKI=b&#hYBxQ)>s3y0`9Ov+*sxzYxsH&)Zij#4O~@bQS)T18yk6KSp!*V9P%Q*Ziev403~Z6 zOmEh3e46Q51Dm0a4*!Rik%ov(m^F|_XIWTyQPw~c*VjNOJ^TP!Bb<3j`T@JiiLCS@ z5zKsS?Ko)FK+V73Tq87{?kY*dr+v|vU6XPLRhI3PM9ALc=ee@+2h)fJ%b^;zM{AdfZui6)ZYtUe+ksY~ zUf9J$gK&z6iMAud{*NR=Z%E*qbAP*F$rCV+#jGzd?4m?YdUI!N;(@i9sE1;AQGKh2UQ`<`P_ zvfp^RfN-_&APp`o`o=P-OkU;5p!A(3cIL(nxtEs_en?Uzi!i-sZl7UKGF!6P4E3Rz zTuT{+=nxk8~8_-8&~wNH%L?A(bdbmTq%hDmF*-~vg_V`F2kRu zDY%-*c9JU>TxX%0mmb&V;c0qYJtLE=5={9Y40)q5AU~c9y&c3*aiaFPz@VX6=Tu*2Bi*=&yNXXAwTI1GLD zkAntjaFG>{tID(`o{W_w&ff1uR_eN6z`i=d0`2$F6+XiBDn2a7vCLLHHbZ@MC%Vi} z3jDMIPtr)Ev*-_!0GhZfe1y_`)G(MD&RAvRNCuU@x`SQS8ENvPgGlltO!A|{Nb(~L z^3!ERF-C1`D5kYb<)>#1{$fNzXP1UH4Rr(UC)_B1=#&oR*A{4Mit_*DMH5HYV-NMb z2{4!6r%_Y-=l*FfKeDUkS9hRYUmy2xX7ba?c935RRHHsX4L1*M?)!{gYUe*ZNTWc# zP>6>Hp(+oP1e+s+G$#zXi&Ql2M(woYVXDv-;I8Mx#3dGon0AaD2JPg59l-@%0Ucai z<=(iTCyF-GkuD5mp*do%V|-zA1T4vu-bv5u~5*R(beIQE?eYjBYR2Un$w$3UDE3ZXQ@!~zE)_hb)3w+8#^RF5#d zfupT*CUXPFpS79GN7yRqqsH(UKsaN$e1xnrGf@G-W&L0cF0waqRSGhgF3*#((x(rY zH<6XD3(jN53E|?IiZ>Ca*PEWNGufM=tX0xYWcCyVwn`bCC?KqVJy?T_>@QrErr2Vi z7egq$>jeWFv)IO`qZ9`rn_dSc>i|SY;pxM$drd9`Z-{xXb}kE5h`;PY7O+x$c9(FKC7|H8k@VLgjut z3|-6_qQOP>7p`)THzSmK-4I{X*v8yMMaafGEB->5UVm9#UYyzf!e&VCG(5uiLdeBe z)>}g~xXAv(RqlZhgwi|XEPo;79tc5L@wDPEgz5FyiQC?p>o0!+o5A%H5K3xg=?ozk zZuu(=)!-t#4_CRtZG?^4)U+&}A*_@0An6fddi`bpYK)dp{!NX zm%Er+u~kwq!u$h?VvdlZe;g+I57QtvgCfRD(;({MhHxu@8z*#LQ=xb<8@LAP0&qI9 zDS`vQmBgkBy}94w4dK3kpC*Tflt?Zcgu}>#xL@N9;UR!;$vpHtyPO%S!9_mWxXKMO zA(SSmXSoI;cP>NdxV1zgqNB*KFSkQ5j5eu$u@p1r5a#g$YFu#Rc&c2gJkW z(BzCL#;BbS#mLhj>a8c9zx(|BSh3Ud;K&MD;BApU+JzkLR4Ov)hs#7!xg1Iq8{{4K zM@jJ$%B79N{&8l};ZQ`FG@l$w${Apzaupjt+nNm}H6Gw)Vp9YUfDMUF6{d5)MM=#7 z-1X_17T^5hOem@O+^d;k20XA47Eh%oTq&R=(L+*r+TPP>|aK{V?D-PKH!)0xn0IeN+_A&S9A;*W??nHky^XLKDuJ-8X zDwQT2S)awsqn~6uc+?51QG3+%#Od#o& zGe$xY@?2XiX8`;$w~}Ac@MIhc9M7{b#SG7;3NtwtbH;4Ig+-X&oZ(eyb7toZY=$~ExSWAB zIt%8Sqnv>zuG5Q9n#Gha;K8i?i=p?8oObCV39i+234F;q*R=tEcAhOQKc9jcmr=HqghLc%%v z$h+v+t_Qb^iO1~EHqx>wYj*B2_h{gX)y;LI9+-KQ>}rqp{2APNpwB%skCGicdK#)x zd-U?w=?-mcf5Yc9B7jz)UbxCbgYb-p$-)c&VVZva!}dMy{au7Ny%IQxlKug>W!r#P z>p#J39U$SXd($vT_~`Co8eC)v<0^OEgitzzv0F|E8(f@VR|L( z*kw>=OBkD>J~ow|f7T4_54UUK<4{0zZ)_u!zNy1*IU!We@i18oK;;_W+HwBHVH&aL z(-O_9q`ml6bAkJTp(hWEwz8e{O7@F;l3QDrex*E&T`yux>%r0Crc1J&^h$P!t_@Jl zOQ%BvifbPRuUdM<=TnfcsDzV)-C3Y1U`Q!yOc6u88iQWXXGAeZ?R6-IYKdMM-F9Ha zI?<`=_a`577DBz=;^==$oc`=-<0qb;x}@8K^KV7?YDL6*DRcwsCNzPW$REnk!s1XP zt5!lZ58Dfmd1&oe;k)_K7&WD8r>EbpnjHWLm7SO)BJZvx2|x-W>{Fu$1%^D?E>5aUb#Hb<{5ldF`Tiu zA^yQ|0kYC1o-cMa_7onjso34)rPcGam&zZFu>IgV)L*P5+bQ_TKH5 zz2{Jn_c;^UX?wDRSPnroP0!>$;Xddd%rn1bZA8Fy@6NL`e@H_ z^pMjf^=}^R6m161-gIgFdrW&fn@WC|*bw{xFS4~VKR9*)_Qz7f&YB$@veQ9OGFeN% zM^0Y*%?{24*$xM%15~3vIPo6KTIBuu5i?mQpz+}JD*e6*bYi*yR9L-W&qIUIjfaWi z8i0RFPW-fce@RX|pa^-^F-%T70q!aim$JL_XG~7Jc{WAZ!?Q4ZF2`bW+6VY)=WQbk zbbiZ{(*d4`$bLr*uMgua1}dZ{ViB`PnSBNm1+TCbHA^WQPdf2h|u4 zb@0|j-wN(`#DDFZ!^=e_hIPUrpz#>@YYeh;usa2iLX09$jVX$VS7XR18B&Z<8v=Vn zwM-bA@44&ZEuwHV*V|%6>taUX>Em0TMl3J7S9}mU=lG(fFng{}xVAuQS~DHXC~tku z{oN*d^Ch2(H_ZG^cJeD_lnmgELr>XP4yP%}Fr`=m^h~&QwDZ+> zm{JPzY>H5rXH$g|9E&NX6yT(99aq`rmWEc!^E{-KiX0Cqr92z}T(J4@C?KwK!?6gZ zJF)Bz2SRQ_ZiLMyDG3K*dJ|5sv7<6O;b1e=+U&4CHuh`Y6_{|4MrXm4e3Wp|#PxR& zIhIk&r*h?Ys6oe;#hs3 zSTo1AT>W;%p_sqim712*hGm$fXTvpNDu2J9{I*ncr&}V~$$w-gzfy*IGhw{t=EMhP z{w6#4+cL)7-!tnC*ja0B4DM6`pwZvXPg#bk2~c6->Wha4!G?#4HVFX#lwqv72|WIm zVG2GUE|31@#SBvnVCBZ^>J51N2s2D+o=p+T@@%S5iDNOtQ~`W_(9`yBBcu#dljkAB z)aH1|FsYpo$i|1 z83vo7)@H@nn}Myp*t}dwqqE?pTFNkJ;s$RKj%QzCipD#x2&MUz{jd-7EoHby5Cd|q z-myc;Fs43j8~j)jVj??5JlS6@t5W^K;HS#=%`2aK?C{THk?gcR+3}p3I$YCjf@Q~| z9WDh2Tyk*oo3cz)Vj3bIXl%oKTb5y}0HlbMT9VgJjVY*zS7XR9)iRBXac8TT?0ycHbe+xY9DZ|FA+qAm&_^N3f<{w__P5rOpU5 ze`hl`=(_08K~e2*vXfsa!yNjsDxgl;7iRt@JNP@V)d(|xzu0RC>-6;=W|*Qtqra1z z#p6{`8Gs6_7s~U{AXxD*S&LN9aw{U2;EC*5Wl>uMUblF^?ax5F#t;1mu zczb9+E?7GV99N~YA$zVHp>%!E9*IFHd7eE`if}~H!*tDpFuelzTs%6n1&+;7OT*~* zU|ze6vvFt_X>Mp2q4XFDJU|o9Sac=+fw+<7=H|@PX@sUimegXU?YHVFcxL!E9?;4Zu^KN{uOih*x6}w@pSAW7M{XVyKowM+@fu5ZFy@6j#xAK>>Dw z(vhQ`ii}=a!FGdquiVN3KW}G6akm;LHEnH6Chn%w%>A9mYQJOUCsCr>-()Ah((&nV za*)R{>libClO6os393>1`)uI(X*cd1Kyh~i8vX4S^#R503Q%G7!e|~Egc&?c7Cfhq z(CCWR%u-^931{f@;vkB90br}UTeiN6eZj=-&0!GtxTzyFxM1xdZd~P_=0)hi9-W5k zgISDSF+@=_vguXxkJPD|t!8Y7`q)_C>>d2}>10$h(p>MKHG0elm^XyoSVhPUHz4FL z1{$v)p?PfCaMRG5CPmG8beFa?6E2#_PU}#ZjGi#^)xPV+QO$kNN=+NsmZ{k} z!rb43KW}biJa|D=`pxrE5Mig*0ge9N z|B9*E51_*8h3z~v2uFCBXzLO=;;$D2=96RmHr|jdctatttWLWv_IiRTVGRc{C2R&9 ze6;S6Rqr3Ol(2)tkP;4D8KJ=in*b>RSGh?$5lYWvv-3Sd>CPm3f(zl*!%BugnBEK# z6*?`mGXyq6eZ1WltWM~tbHMKbAuYXq4Bd5W$BwT@X!0JqcD&z%ON!{b4i4E>H}$fK z>?C5cxBE9>_3lb(cXLyFXSZnO@k%5+ZBKRx!v0WALWMI&kH+lMpBv*}FSeSGsDznL z7!EWZ!B*{==%)arkRZ9KF~tP&Y7D3FX&F(BQM(w5p<4d=((7!D>lRbhE%}QXTCh|2 zQjU(if35tF1&d4r$E~!=yR9sW-aY?F*0gFJndqmM7-{D3vG)Ua+*lSOs{KuN@+*mc zO@qTZ&+Y$c=5Mltzn4HYYJXo}+Tq!$*ykwvRY0S^f3$v$r|?Yx6;>~7;h{k|$irk| zR>_f?VOxxL7Q5e~UKer@^|}o3o${+{H=7p4^tz72px2YdM{01v+Ci_l%Dp~^kh=g! z$UU--@V>YpP_uUSOPR2Uzm~}?-*^@A*hdH|7<<_Sc6!0@Obhxt0zitIo^VNn!2aNV)Ahy|B;>iN@{*`^xNJot3I3go9y84)liMv-#2>sg_MhrM>QV? z8vVUxH&gQ|fC{S@OguCQmwA{hY#2FG(`@d_de>jUgBkFFO%9@(_W?dv^`>apvz@8= zFo!|SSB8(&;DWV-nsHScY-U&62pwPGgwXK*&NRky!)eIA?X0L7VS3f<71}Yg)r`$h zAF6>1=XdtAo{MTmn(Lnd+IRDwu$+MetXZ2nNq(oXf9Do+U4@A3Otpp&n+ zsDzVFI07{8U)Oe^00+A;fD}I@D>bG7B3_L_+?O+=7^C(+6hpN{9om)fd>ATdsU z`4I3&nFsCXfVyzOodfOTD);UlLg}eVrhSCmtD*=iZ&b98FumGOxY{MNwU5nEAIVn- z2bObay$rRFv=p4P@lgPTb=fEP;7vbk$FQ3tH9b7{KQFiRfuintm$nRiS>~3hmux4s zE|u+JW&2J(T4|r6?#QDP!z{#4BH3wsvO~1phiVQCiQd$9<8}RThw3}~=3gu-@uU-; z0*wc>L?@>1F90ckNLLgx6iE~^#8Ze6593?PGV5$<`a5M5 zQ}=s-3ab}B@X#PwWaHRmA$xWwjZc%@`dW=Gfzo4zPX@mT(EYKFRpTLE+gb#V?bDuor>5%Il^jh75O4euYBh}>YCZ|#b&4v)z`g0 zZCWl~jq*jBJ9Q)EzIBI?y{cScFRD3j1t*Q?{&?q0&QBCIcgZ!Tw9o82CbE+{d&qY8 zf_*loZd$3Q=<3`1;JOMUzKA}*+k^Yac8IPDP|dZqWvYIdd`DkC$IsS1D=Ze3_|XY9 zfyUz-W6#vw0w4tp356nt)JhRUJVgxgpypN?QH)XB4T>Q(4_JQoOoZvIDIhX2@7!Sm zs<{Wyv=dDoD%8@nI%O)peMU^L!PQaCscogEUF^!#e59+nzl&6~cKUevftkNc$#%8B ztKXd3W?_%dX8x`w+ri%^s7CGYKF;$iZaNL~-|B>5pwZtaBbl1d0#sPNaE^xt;R+9v zg~sSqHC$`L})vUI3~2AnutQi{hROcv;)ho=3lbV(01w+~({(M~(-v+d^Hq z;Ld^AaaDTX<{;koMmQD+iS_U}|1<`bnWkqkI6!xluDWsK^orf;P4~AS?sVHKF^bqbd~^NP=~0l$LAI0F z$!^y!vd*gb6N=cYdGFi5Gv7n8?eF$rvP19{aCg%DXd<54-tVFQZuY(BX2K`xl)(xuy$(Q%CkiArrU)WljX~^nGol!y)((oHS}Z2Fy_Zra#N-=Yy77L$s(6pP zEl0oYnfrcwzf-18n(2p&Ooz{4>V#&irKTtGT}i54ie1XYfTcf0JG9?_8zJ zH)>eru9?5d4*o6))u{b_%X`O#8KFN=>=l7Ve~+yLJ7p`>0I0Bfp(YOvg2=;U!N$)? zv#Y9WtNJUTW1b?khicKHql?_nY(O<5&E4ZhID}#LOdLXGQVnaznrECe zDgOj6tGhZ@QM0&YL2|JgL8esMPHHB5uYCTF#Ts8!)SSBOktvVc1F`S#_F%F@blE{Q z)nNwQ3uT__n|5||_u8;TRN_Y`v;i8A@0eap&3yqtpAm?DOFH3l{J&xm4-S|=!m zYPoWxNAjg&A*P!v_1dWEOwBGF?R~KR*L53CnnKt7$YWQGsoCm<)U+N(rsk#}%>A9! zquafHA3{X6zsaul_lRwUyM=0BnE9LR;O{O_joRPy13fLu9!^FzcLy5%UGNE0b3cFz zs}~0F&>*<+5XR6FoHYCV+Riz70XpKpglzzo?ox`d3*Z5nMR6Yh{J<$VaD(`gow|>5 zo1@r|1AZj)AodCIP8wWr=RoYZ%DrxkP@3_Jy{m{&x(L6Bx4;puysd~GVS2@W?_}@H z7CSaWeI&n+9$hp4uJtH(q^00wm)QuVD;f5#B0}yKI6`SmG62uy_LieGmy!-H9G4?b z(SEbWgR0sOy=e-Q?WBEs**@jll9m;JTvN1PGRxZSQNABVuix##C1g9q;!vpO^T#$L z1n(Gqxe5=~b6@QOgh`F?KxA;N&f`&ZNa93Uj;PnM0{wF!|pXE(`BvU!^u`u+Ckj7%01A6P$Wq^tcW;@z zWIL((jBGz(efjpKhqn|p@92MWf8*z$#6!Q^gSW|ch_0GY&0e3JGoPo#>bs}xt^Kpy z5>bgCozMViJib{RnVQ=Hq<|rzP{fd0DPoAHh#?--+#w^1F=~55F{I}F&Am=`S$WZv zb?4TYRrBEavp(8BK+{f?+Vnzmx=V=ZcDuJH+?=bTnn%u%n)Y%aQ?v6TbAOw*Hh6v0 z=AN0qFUxkdzX!eSqTQI&+~1C}9sKPL)u{db>U>mS-t(z=CSL4ihabUe=}R`*bMcN z+>?Z?cXw>`?opcfc~z!=ihHYwy?H?Sj%&u9H+_)p zBzCedF4SmIo}l}R*bmH4(fBWj5tsgM4<>l=!pTDqJ_u2*l(In#j&n!qA;+0$!> zIl5FtYSzhvLrfPZH=gMCqZo>P$2F;G2Zl1SZ@h2r?-_|dpL!j;Z02vWtNq=7Lf8|x zpHI#FO?L425vWG(@6gi?cYI7rL9w3%8vR```wJ9%2tb9^3uk#~5U%quS(yC*T2Rrs z=cEuee!iH4sP2`3Z%=RQck%vLcIsZwVNmmnd!sbCVC|r0T;(pp5stROCtKK%8ba>& z7eY;lqGp8YRr8O1RWe)6*bMcdTC}N2qllobsAi;oO7moUE5gquE^AUlcQrD!(5`j2AftsGfYa}#MFGKv@>hkgpo|mTdFvl z`TJKu(YzsDFNkV?lU?oaCE|`!mfPN$`J3$E@54}y+TVG-JN4RGB#RBG`2^7D@3`Si z&A|W_RxgC|&>%$dFj?@b>Z~bp?pU2d_2D|?moOKg(p`e5)BqNhSrqp&z@hD~)%s8a z`sFZB;A(DjJaw-Dd`{*;>~AVNYjDAx1F_>Ocdr|v^i~8DJ3{HpCG6CVFlXN5)K5p4 zUa?1=uAbRq$7ZOH_~I{bcE7{4TwFQ`43%*e{j_u*wR_^a_58&7DEyg zu{Yk*?DVj=_e^9bvA34(+palAuQ>Be5qr~#M~Zh}`AyvZyFIvxY=__rgKECFm@{rg zmv{OH3kJZY>>^PKFP#ttH13db6cc+aK#C`l8AT8U7DW*86fwku*k5KuF-GlYD2Dp! zBinVnQexRfQ`jPXrR$qnKm9Avv=d9*KgBIe4K+o?xetC+zZRaluaADwwkdS>O)oEb9C4K z_2JVhq0B?l&22U*HEzv~p&^vSy$8q8t}J)f+-q_Az~~Jh6*c$SoUdcQ>kmx#Wjm>P zq->}GCx*kI{(Nps_^$3aA7xmHv{G7T-RN_Y` z!~u=Rw}Kl}b22~*7!nFa45^hOhIon?;z7+R8BvT;Yw4S&<}HEciuryEGkqD=W`t`` zxa{ns%?mW`M8DlrChXgB-gK^Wh3>sw>Y$oaPfAV8KANdH?wq;5D;d_uX}(39`MbVs zSNnTP)7(3k&;D-a@5!8R)_92>@$BcFH43X21RffM zqC89%LID=|SgOaoBzEe)1dy5!;*Q{06!%TQyY&t)+{z`hQ}=ytb3AoF;CK+b73>%; zxN{(OT;(27MJUbB38(H^jCJr=)QxO<)xGAvRc5Ojo1s2*qc=V=oi4l!)s3`YE4+(v z4}0PWrEiL`&mbp0b=I^VH$-o^^+}QQ=?6vj4jp>MM0S!h*@rlZ7n*E-smQtI)!gt( z`73eg@AhD_LwH#}bJp~Av#MQsO@e;s%W|C__Fg0^0i+WO0gXrS%@`)C{)y# zVuW}#207Qrh+^OcZYYLosn@EB%?R5t(}uOrrw8qpUf|~F+!57#RF64ts(saV`N%xw zP|o=T7uK|^$S>QZv~XF0(u5lJB*m=B+s=-N-$kFqS_BVWIpEo_tf2+~`FYI+Mn;ufrR(Uctw{$f3_wj%n zD~5)g5!L=CyV~E0yGQ+eb?~E^zsU~%HbOOOf9IVOR{hGV?5O5}K%>7~-HgMN^GJXS zs~1M`&>&3aVX~kb=%T5!Yi#zQ8t{J@PZyiY2)d2s znJso~hWbceKe>Krn`TVxNORZK2$do6aOOXBCH{f-k(DlNcB1y{Pj%50`}n@XgO*rJA5)?g=#Q#FtVL4KJ>{XiBbg_*kvWR(K}wx?O5o|0zuS z#slX5URG^sQ0BVQiiv|~LKcp92l^)w@kRo~7#f2CXCCD>-G~0sXl!n_ptq-|fNvvK?Z)0#s9@ z^OqMD>U_~Z?rc%gKXIX`L@_+)4m9p|^Jy%nv;asUMv+HBMX^RvL_9?e@sLwmWkfOX zoI4b=L5}bj*WVO7Y=6a6*7NxOYgP^~q-bz9!qj-#wukwZF#~v0ptjUcj8< z2sHZpX7y*-pBMp9VfDgD9vXy+JWRAL^6O7IrCx1aqyLaobWljvjg2f`9nFC`r71wy zLUThK{DSY>{}NjAY>LpDXH$ia9E&-nGvIF_ZIYZH|6)1C!1It(x^q0_6t^T74KCPz z$SJrgeM0gKK1z>J`2y!O2BkAF%PGh%jZtz6!t~~pUhDLk-DSaMsDs64$Ji>r>hHsx zf;2iSBBCSBAcrRDJjyOv5K1>p9^fSlE029AaT|79rWAM8e3`IiwSB+uN{R{paL{4m zgnK5kQ;H#bh}+Te4Ff(XDdx+_UiJH@d=^80w+E9QLf!|e$u-7#Zi(_=^$FTNUA?|6 z6qTTc7r%kVR^*z=Qp|pU6mb-YYD_^zyc$D_IhYZ}7_~uA4ApYTrjFOs{TEG^kxPz_ zt6c$~t`Fwu_DLJ!Dt$g@+P22W>D3DM+N-af)U^0nEX8=YH}`jR*&zLqxCdtbCcE0- zA4=a2%s0r~-(&}WZ-Hvm{vPADw72aRmST1S&7x*8OECukDy&{O$U}n=#KUA^Vh2~v z_u;K<^Y4OmkRr_BAPRmVV4FK0E`26|;6dO%90q|$v~$(qg0+LdaaHPZvriHulqTJ0 z_xccWPuC-SYjuLINf4%2;7?<6XSTqx8R|pTK_ zaHytseuuql3xCspx;U}k-4_c*C4O|m4WRM(-k8JG{0bli4CzRXDPo9MV^H&(j3~ya zO@v~o7W+4oE-l=C-qg}|Pg2(MOwGw0ef?pfM$L|%GgV$5QN6+dre>$5QqzvlV`|>J zCe7bBEgomdx$w5W<*{HV+alqLzv*i#WLNoBpEK*}W~GmPGxImu!QZE#8nwT-Ij`+$ zDv}F34CjDGe_x4bYQ6?gVfDgw9vXzFJWRB8U+emZi;#M?>(~De9fnm<$f&FvbGdBE zf*po60GEA>u>Ms%KXw?l031ndir@!uIkBn2F7CIOKlT9LTjp2w#zH*nFdXE5jrrsd z;Da&``6Pa|s|FWrKjaf!Rqi%UV~~3?2-&>Tl>~w?y$R&rr@Wb+K(HC==ty{`q=NDp9NxUIC4*Shs-Xlw^PuVib84R1|9zMZ{Co5Dz&eB_oP4YI7fV)i}u!UO0K{ zhIdQPnH*oGIE9t1fp;A9aCEbleqNQThnPMeU-oaK)wS^=S|6kO$A3PQ*xmT1amy+bJVw$I}|PK0$Ll@x<8y(uPt)`FRxVz3$NU^#a1M#B;n z_hX7d8l9D#no3^^M$^qs_!t+Pdxy4QE{$Yf;>J1dWp&eR8}RE+`*mq4rg^Szc7r`W znYPPz3i;Nu-Md`l#1%z8DJdo?U$Aa*$y_!*zuSY!4k7;*syS&4zfidUcYO!L?i2l* zE)tcXhS}tS#{C<#gr%5V8aE~4C=e;eDD)_(h^HVT9#V{DMigVzmVjcm$N@jS>dB@F z?N6HaUJqSAJ%15QF(o?W+^5w zK!w!{`FUs%%J4AJc0a&Br5LOKGR|=w3US?X(>6Xn0aMH!fW2q<$6d&t4^zw|fX>9G z2#*2wBQ{lt<$lXj4B-C7S3AAF_l0#^-g3Xj6!Q-7K$(XWQy-21F4%rZF}SL9TRa)O zQ0@>+Ez2&0kbS;m{rPf-*dvb!yOlgimq7^An_}Dx70K)rgUwKjbJ^HW;~$3}z!ZZt zI;(d5BlMY5G;w!p5K7mM>?ufu+=UWCu2U20;HKHPbWhnVAAc$rN{w1N4@lkq(nNMr zKug)arpxo@9i7uMPLoSHj#Y^HC93SfjbuA0;0{!CcER|(5l6r4S7$3~8Ix;~sKhwT z2Lv=Ws`@gPalQhi0HnC2kfTVX7$cryig?I4-!q~Zqc(e2H;s!N|4W6cOB1>uHi?4^ zzn_1y1ZJEZ9DQ`y%;+rc`%Pb7PJX|zK6?VX$V91W&ralP4#P}2W|{kY@}Yw5eq?=P z=I;fvUFBDO(Pa(ncGgQa^LHWH4*o6*)u{d5E$wZh}NcZY#Yf94Wy)DpLr zUMyy6Mu@({KN!SB$i0f#V2hh(Sox`=4z@{D)cj*x*;0uWKbpu+YEG5yU1N?f{dqP` z&2C|imkw>pZlkgXlO3X~EmSk5R6FCu+&}bVf7y4NP;Zf_#E(ws0yOU5-l`B?4t9e9 zQoxW}DPl;i6fwk8#1Ic^9-0xw7`0=d7*g}FGtJjJojGLsHSu!Eln$j(&Eq)wTCMUO zBCGB*jR@Q{;rLnq;1FU{g+bhJF@FpJ zoG|N6gMuzOZSdafNbc9ze;5V$o6JK#86D-O!3En7{RdoKw-*1{b6g0yNlFkFyMOh& z;W_(EIzpd7CA}a_Z+hACBGc0gHbWgOj`x36>OF*wf*_5~IvdfEE>X}Vy;uTsb%!$_ zavcU_rQ6x;LCqHNn3G!_=jIGI1j3+>fI0{6H zF$z5jD&i@Kh=&w2DIHzA ztTfGv?la}WhccLA`WA6#P3u{krI_|*-Oc=cCdsF?N4&<&-&+TRne)v-VIq?nn% zr^t5jwS4o$mb8 zs4#XITmZ((5CuO0@Q0xzJfHW?Zi51!0{F9xLEye++%>ph?I3Vm;{fq*a|+bOz0K$u>Edkrm<+5HD>hWb#M`WH(Gs^^dW2c)@Kh!C>LEDOWj1>uZE zSK=S^ACTp~&0#OPYo<# z+8!}NTj*ZEa~6Z8rj@P7#O>x{?(ZXSpG~nYnbpkSCfTm`_b;J9x4UM4Otf?td76Nc%J&KD%XA zyPo{nzAi39hYzHOxs*?Vo`5nu3m=G!Ep`RF52pdb09tD5^d5H5eK?=S21EL|2rxxr zL#$GTNPyGj-(oho#{C$(4|me|V9YM}_@5UL_Bp$2aKYw7cEQz8H*mC$bsrE)S10T- zaD?2g36{n`&D7Kt-nJcK#@d6;O^ z-}Jvo-@2i6A@OJFFN89}>a2>0E%p|rzXTu#gDm~kX)H>A9l(EZZ@qe;^tS-KEdLgz z@5lWZrGF-kXVMShe_lYie#%{g3l<2{$5n3R5ur49DeG7uAQ{uKXc zd*aojKG*i{481bq!OaraLV zO2f768=VNH#IPHmu-bhuP5NUV_eyyZdxzbJg~Mq_(zmKOI7huYw}P>JJj^8h(W>o9 z`gK*?L&Te)8fr!12m1rv_OH|{F|8BM1C51WY0RYm6d*+$1tP_mjDv}%U?X0}DE;Rd zQH)Xh4T^alU-X~gy8dF69NH(_6%McW9|t?g`YGF#i&47DoOXEkkT za~NLu*kFnDh+!{zZKFxLj#!S*Mj(_jAdK-uGRRG&a;x%a<-(!P?E8<#U%qFi?Xgp1 zs%~g^BUqM?9cjC^YJ1Z5IMw!`?UzsuwIaU6qie&m`sU$sC*?`S(5(_l8q}dUs?RNkbRxiZ!5a#>u#j%Mt z%K)0+QT)9}U$1sud3^BCr}g7dM&;mMWj@4PU>81!hpEB^4x*SNI1E?(mau!cU;{wB zxGKFj%$|%yC~29A7a{k_0E9JcPtz4Y!t{!Fe$n@tEnaMfI_y7}{JQJxxE&~7q}Q)4 zE(s2u=FgnQ-9%soXf-|Z)?yDfA>>ZXug9f{*V5{X>B97fX5y{2&3oCJs@KfKn@hDl ziMNhwdk}9jR70(JW9s$l)15%Q5|uh3+j!}a_t7))mIO%Rq)@_$K=Bg(8xP_woe{+t zwKbubJR4?h`jB!|tS$$3)85m3_Qb($fj-*W98EiCIcr96!4^!snhjFZ^v$4Y){e0| z{%?QN=t~Cp`#V&l_P0fNo&&~PYy!hyK%+lBiaf^if3}?fiPZ}^cnDJ|@Gx0;hYcQSHad*6Ea)D*bMcts9(gx zklLNie1f#}f;l`S6v-UMO?8rdHZ5MxKQ35K2h)(EYtj1@FQ!&quLJ~zo9XkMYJ1Y> z8P)cn&jRPt_VMNEkxd+XgzA-u&gA-olvl>X>*zj%4XFw;G;JJvo|owq4u3(~qvoj$L8BwbZn0ZJAnao0~i0 z#Fc!#4aM1~uQ~#a4SnOy)Y=W8!s>+{JTwTyc$jGOPm3{sRcrm)_2s8||J)U>31#&D zv?%9`V!2VR4S1L;*l-Zl+JeKN)(OqVXmG&>z=;%Bxd{OgO0N>Lt}sIBMPqjJ3*pMD zCh7_!Os|%sk}_S(*bH^pf4(qz$G}=JarXvGq(=@L#%mc(Tvr$&H^~@6Wq3N0d6;`T z&S5~BmfHoc3Ed$)H`B6R$LhIC9W=mwY-6&X=nAW zU;CEy_y@H-bgtC2)g7T}){c6g|J~ozWEw{Jo4;v$@OKxeM(yuaa}x)-7X5~^{dNNy zw?47^9`=m;0#sPN(4U6}!I_7N;tzm-JHgklO*0$FDT7^HE4RanFB_x0$qgB!A`erA zY8+(ecMe0wnD0GCgA49IWDH#8Mzs-2cd+2z%q+(4nxLczWYe1>?9QIg?9)9qLw$6I zy^0PlRRzAewZRf;ns|VDDU|s^x*ldzli?QJ*w)1TX+f!N*Q`=__ZNB^!=mnY$fG`2 zBAO*l$=;VJvG}m2S|q zM%qm^$C^39^7N}}JFk33E$;&wTiVHmY56EXh1Cnkc?eqOVFBT8jjj=5I!w`Ng7(`uggz1%%Mcn1gmJ&8Y9d*MtMHbjFgnhskY3|w?A^Sps z4SQ`LA=lqV$UVQlzuj2n+Bsp$+H*C_zc$lN^3#Xe%A7Qr=|;Uh=|;Uhgi8oiLoLYv zv)gR@6OZ&tKUpz(0$?g7DN)V={&zx%kjXNd>@6shkxnj-bP+oUXw{BmHVo^zK9 z`_Pj`>V!$=RUfpr3y61)$4H$9G*-Rs8jI9f02Nj*%;up%Si-|Z@eRPgbv@JGXa8f@ z(_->i<^5ea>15+!s*sa|c+$zsVL0i0m^fC03+_KC1y`jhYYyO)H3+3a;Jf&hDTL41 z9B8MoCyFrNKt(AC)2oyIO!mi=HT3bC!M&}Y2x{|d0PJIo8BlQp?=efDKi`0b2zVvibSH`p6u%F zK|CLz8fsKYec3W!4?oc>F{%?j0*(83vo|~GB+3v^I`n2Z(*Fg+Nhd>!F=|s`Z{}bA zxo1t=?V_9fp1O3>NybUCEY^(GERbp1*_lNBX=^-d(gl!HgQbw3wDcf0I&ul4U zGt^N(Y+9|N)lz&=%FGAyOW(|C{>%@OIv3;f6S&3Eun90;cMWgxAmqO7{Pabdc3mCj z1d2!BnrU}T^NlyI?hZ54u6ldYu6ldW?mMW4T9M76Xd~+nPxVSrf_8z%y5XI?l`yS#N)Q)~9qVYWEV*xC`r6FzrSFR9L+b$wPy1mxqZqO^S{C z>uI=dZF)cZ&li7Pp$vLS4aD1%hp9q;4x)Gmau~#0ANB_qYygNCSEaXm_M>p?Hy|*QuG){FxuP zPAqOAP1A4##fy*|Ao^Z^oYHH(dgRo&Ndw<0BBc}Wrz>MFUFdg35jBZay*=60+k<#D z4boaM^hk%#<2O9hD^aNvasiEdKX@P$Z*du->L`?u{x2BBTQVbxF={J8F+E4$z44*J zJaM%AE;TnmR2k@AGEF<1e^Qp&_3HmHfgDTpk($<4x3k9wg1dEUi+V7q-H%L zZQZ~3L+m0702Nj*9@NtUs-Z?*zi`U3DSS*^2~wTV4rtuJ&m-7br>6|@EJKln^nbx{ z*6EcI#Td1NpqQe)0%EpybQ6clFXT#Rop*S-H<+VoXQu~Uv3;g_fLd%{Xl&?}(@e{*02Nj*xbx5;OyOao&1Zmr*Rqv79r~ZOTsX^k zn5CyeWcTe|M9^|c9;ONv0rnfXCC_BfZX#;A8izs40T$ymxL^a|w1=zG9f2d*Wke`F zod$Oer*V)yGlcB*I7Q0{)2rnWV{~R~8JnRF`-p}WwS~9NL@gstufQ><`7^h0LpQjE z^l%0wz(~eQ*USg?5G@1CNX|a(%w#iNhA0y{h*<2OFdatX34?5AXGAeZ?Q$r_`Ngac zlfK1Td!HTU-{OvgxTRX&z8kFPp=?%AEo={@e`2Rj8`8q<9LmPEmDIG&u1q#tyO=xj z%#6kPqc=Z9+3W+F6>*En<`_VQh1+aAgrRvJCJBD_<260BZ5w~_orWQQh=-{{AV9ao zisxH|&0-;chQko@_dAc*;DVJy$m1$Ew;jUlGgiXLK6^$LAvd=j!k-O;si%i9y&>;a z>Tza=JT}8DsZdLkXbwZpWhRq!u8t8r; zLw-Be!Z~29S6J2Wmp)<0FY%R{Hhc^V`5qh19eKLoi$#?-u#oQ$G?ruij)nYSfC{S@ zhValJxbiSbxCOA>`O@cXKhDCCzt6)|AsS%8o&j~XMJ`|=AH!h?`CA*tYjDBJA>?sY z`p6X<7(gh!SiyR12>wdp(4V;?Ek* zUEJW-mePH6ytqM#uEamc@CZ9L##_W&FvFiZC9$s`-@-|d&dCtNoem)TuT&7L<<52ISx9!UR;jUKhM+jMq0 zzUGv_{$vZ_S;!I7^Gy6Q{Fq?+i2+QK0T^yvVT!sIdCqp+V@zvq{2IfZlJc z4xAm&!rh05slsxAt==qK`lyx^?khM9;r{l`cnvOCIfOf|N`38p*r`D%oseNXb{d1y zjmSU@cVu(lP{JKydc*zI<|mn*;jtO&aPOCFRjA%w7Vb!MJs5<_iy4v3CDJ)?1;+PN zVFL4PKn#oT*D}QTrXz-q{}ZNTMm%AN?>8Ay47@@Q#n^Y*c=B#oab2?If)t;GIbzBD zLnnOpHer0nQ!Q){q<;p-98203_Z`!DXdS6(D`Q!Fuhva4^V)$gxe~G)S$uB<8jJAt zW%0cQpu*~ftvoacdw7^6lx#9V6ViX;ooS6&e3#*2s!$$a{LyTuSV(9okVLE2S6NdPHk`cui zwXdLr zse(H|<9);3CTFDh9?xNj?>bNxE?7ClH?I1!cNh<2{zfRx&BE?uAiQ3IJ$r-kjj)re z65j~Z8{gKo4rX?IV>8t8-MpvvNslEgzLDl`S|F6(2VgfX5Gun*I-%eW$+OMgu=uVd zLyTuSV(9okVLE2S6NdP%ni0hqwRNGG*rh99&h1fLSHzIxYX|Q+;=Ry|2@VBVeAlB| z*d9p#Sl+W=wtFgz?+Ou8(<;4V@%{3)xz`5W&^GB;fW>#gJJQx$dfmbPNpXM*s~1Z0 z&>&RdVUn;5;D;Ik)0X65@x7misls7^H*yD@Zn0U4??4Vid^^B?;ez`Q@r|o3+2myb z7~cr1unss}TTNrIJWhoCp53QI*43oMH^TJBw^y^nnH}HQ40U|>ZRt6F{16u3NK4n3 zUYNfTmYws~;Y69+n7JexC~#diZ4Vm#9kV}bJrOvj9P!Vuq$Gol!H zT@i|@{?Ckh*BcerO-f2UZa;30c<20{z`F6Lv47H%YGHdI{qucKn;p#^S$wxE;lYCD z{RbA`egE|^^V*Ns-?VP;AK(bfNT9KZdZ$@@j{~T%dSL<&;meFXOcJasd1$g4>K!W- z52Iec1Unw43atT_@@r(rBlaKU>{%jyTC}$FRsS7T=So z7Pbe{KXct5TYtA>@og9(HSO4E7T(mcEPmyDLD2)e8n5 z8U#lkCJEmF7T(pX$ktmdzLR;FD*Q9nL(|fsbvDO-QhW;>hWPd#?V-U1D~I^T)hqB2 z{pVjtF@Gb3`4%AJpJ4t*C=HddL34x$dnxgaFum~|=5!*n;~Sfyj_)Z$<0|JW%;Fnq z?)nm;8@ncf{2k6b#El*ztK53m2|c_eN3Z?L!reuN7~XUM@i_bm(;+0DFoe5%MigVz zPJ&{3%t?ON^Rrg>t7_hIaZTok-S>Q6Gj1xMMTa;jX)Mx@@j@Q*po?X}AJs(h0+UuX=kJzMBNqP%HMAj$k)cc7_}Rrm@JxkwRd#9*2Jq?qeB?FtHpok<*)wu z{}Fc`P*EgX6lKH~Bcd|8<{S}>i~>F8tmqgqVZxkq0u(XFHRqh;nga-CS;3rj6?4uR z1^&C$T|Kou?*83{bKsoTzIAJ=yQ<%P6}q|#?Wko$S8Xx#R@!E#E77E#?Vvxe{y2QI zJrmwM!!VY$8sC}l#$_00QxI!=4|ozfmI-ev(a1@G!%TR;64Y2(nk_<$v_pikUPUqv z`v)(0E0p`Y_0r6ghB6oYA=XQ)VTD*5u{J@zE*-6xR^Q6X(6Wyev$YVLh|!&-Khh5~ z;6VOJ+c;GkW98av018C|Gv{F_gC}OCjc2C5CBYj-UB%SMyNY*&40#7U{US^Laj7LtFe% zAD@d^AD_g$k}kt&zv5n7}zB8>HNZu|em z?Cx5o;@^q6B&9*KZnwT@{1IXn627T-tR)>#EQ9P@WkX6GqRyqMXtU( zpWIr)#0>guRFo)Y1ZfpDEnPa?s@@?(KOAT=^|j4R#X7Hw_gQMV$knTT0fJ||;rE$-=r|9{sRy!VmL};i(Riru>}VvmvH7eDVI|y_K>r&|>OG$n$@m&?Q8M{@ zRp0mV>=@4us$~l^d~XXhzu8@-vcJD;$5vp9T%ly`N=nLF1>@RHwgpiw<=`*R@o+}niNp5)} z8+x;M$TMnD)wiS2js|@;DxD%Y6xt?MXu?Q0Vkir`vSu})(31qz1_nL+Zk@7f+27}o zclYCOY_wc#`N5$PgD%@>Ss$NkSs$NF_$gh6XDY5y{jkmn4`t0rP0|~pVF3pWOv~{q zgm$@Qf&Mp`w49I>$Qjg_TP5z?nNB8>HH{p~+!SzK(z zNqYQcm;ncFfz*goWr%`alMZ9hhglYz`3P2d1;tia0!)2ZQzKwv)%bPm^yF3}%cQzF z2RB@YOXu{|R+_h`hnHxvH z)g;D0l=-&!UgbIWtt*3biRt6>aD9A|UixgqHR*LZ+kSb&3Xf&Yrc6>+qH%v?B(hIm zV?}~ZL!-(L%@Oi5W3MF8+}In|zf~jd@l}{_E-xjqE{>F#ho3_&+Z^Ir(D6UbA&>tz zIdq}RaOc8vI40Nnx&B$s;-+#EjZ_}hzKGUsL4q1f+xv--w)YcZtmi3$|8FjG8Q1cE z?y8EK`Yt`EBS}LBLc!)~h+(fCKkW3dE_>jbaNd0168% z0QM|(j5k*S6RW@t$7UtB0+9{<({(7FW>TlegHa!XE?>5+SRW!t7+D3>2IC@G84C3w zSZ$(+hhOE+R+Ak*%s%DdhVN`dStX`%%AO;0? zV1PjLn>~23Zubn`9zczrQa z7okNOEW%jNF9iRecFVfD|9M&dKWjJJyy1pXS+?!-_fG@u<`N+-E-FB1x1@kcyQAlj zDba!Zr^*zk%Az>zvvI%`Ij~3$lQN*PP3;l%JOLMv)T9iUSSeq>H7B{HjBMzw-obuh z#(h!!AZ5@?7Pb!Gj5n7~jB8>H%Oz{7E439tehX3p_mQfOl4Q7a-EqqoGYreLqKKifA%>ppfWH>8wCWj$R{H;hXOXS4(02+ z`N{22kPW>pq-%c1^u9?~I26#NEYYDLNN5`X=3>=HNW zgUWw(obrJ?ln8F%pA)9ON;mbMP1`^ppBuP7J{hz1@#KPK{s6nhBdEf1+Ul zH=LP68AOm<7&ko7a40G^|397_%HX6(#@84?$>b{)HRAJ%-#o{$2`w4Sfia(JI}H39Hz?ngfd{Sqsa`+6LX-Z3|*tRsZAh&KE*S=>v&IM#uMON*_T` zV`XWi2rbfh5ypCbB514hQcTOeOAjoW7d!Qpb^RNu(+4DOBMdlj4VS!r;|^(Ya?26f&|9wGj+PHkEvmpiAR$_)%n@7Zy1XD>oakWL6q>Hclu&NozE@4>m;K1$MFzWY zu##9vc4pq=0&OpS*CX`c@V)n7-m{6ur8{0`=DmoZ#>&zX5n7~eB6N~228=M^!0*X4 zajI-2&)#4HDj)8!$vA*YOO!P|0pE4eOcOA%ra3duvg9^RWJCX)W6M=OKGS(%D2?NQ zR-V{6Or``>X6LbS96%H${>V}RdxQ?6v9EQg7N#z-TI%&TFVcOE{bXaQF?YUYd(iW- zO|_tp&n;CSpDcATU54jiP2X}+0~frNHG?ooD~ZPab^nD~>H&f|oW6$c?YUBCsjQQB zkmzsD%WAYKyF#{h!MiPxnZ+^)v z^#VbSm8DA}q&e{-bdnOHMi_A5_hhL!6{d{=D)YqHh$Eo#9*T`P0_NJSSt?*+E%o}n zWVcjgL;svdmvM~D5E%?h1uZyHKw-oYP-wsa3WFP=&#jg^?n%uNwaR|6u~d(<+uw!U zerjW>`uN;Z_3_D4&(URg4t%=KFr7I6PSy;(&GScSKc4a-A1r2-yOMON(F5SrK zEIJ2o068m5??h;k;zSrH&B!^@+Om(AekI7;RcNa(5@>9#yF}or?QW#RaNz1>=Qvf? zwqVV*^&9VBHIop}Qp6CMmI^;fEd%GsH+BKHVEj2$oWR}rS$=V+Unau8Ww=D>Vo?Fva zF|aSdUlNUiXflY&>=Qwam8CBtv`B^?0_!AIAQlIHPeQ?|;_ldd4M1hxK-P2tY)T*8 zAI}?sPA*_`A5AELi51G%+yj$aD9DE1>b#dm1)iNb3qk=c^k@OKm1UzDE4*|1G2SW^ zm!-MKv|IhnMkwt}?Gtv}tMk{wQk}V3M*Ejpuu$ zFslK)2(B3Y$vvRTc3lm?Oj9Phn*ZWwmiXT^(@b0D_=6(Let~J`+@>V9wkR{rBKvJG zon_Yes&k5cKn+liXk5DKHD;PJL5-EAsv@NCuSMu2wca<jX>_aO5)0G+E@!%AUoiUYdNc_pn`PHnz7hlE)w4llX1*v@6)&#wosJ zV0$7fw4F!AA<1o;$Obn}{+zwHw}1O4&zw+dMuQ$LqZdq5C8HTsmc7~tr=8`B)fQ*J zn(=kUtys#*)tt6IKDR}Ee6qzNbQyk+?R#I}mwxysS$pIr$(3jn z=%nJz7TXi7vdnWp+wNO_W{Vw&et%_Xoz6XWX|~ui>!^U^*R#PEd;d@pYhia96L&H? zjIz0OmkJ(7Q#4}Je6kabOLwbu4y}Z`%m_{ z9H7vi06c;%4L*dy76E6y)NBzjv2Johqv6SIi^zulIeUk*3LA zVg!ZuM5h9ywDyGCiTr`HoPXGu=IP_R;-*^P4r->UkIzk0AD`@F2wjHX@{j60y)*vy zS=KDTB#kB-&$mb~vL;{SVuBs7*d3KK>IWZ~n_LR|;M{xz=kL}`v*m-D9eUhxfob~G zRT4|vhZ6Jf^J@C5?PnXf>u;|_JGF1oBELM}$m}um1olLBxmtkMOjd{D<))PTzO8LXiIxV6$r-l7IftO8ng8?tZzF`o?H~^1*DoWE2S&JG_XejjSZ?%sSsod-r*Nd}Jz%j#-G4sZ2 zFV!NredyzJ1?c0G0>;v1_$_}KH|(hK*%w)}0FyL{XguFHeVGE*6FewYztVos`ky)H zO+@d>`_ZM-@jaRX7Ur1SEAYM%3J6}HBzCDkQ-J5H|DMB=x)S-D95$lM=yOQ#R>k0alfWjwt zfU_oQ3II&30_?^FCbt5R4SivI@4W8+?DKpm0JPAj1XNZ5xsT=vpi+MHNvVh5v~a6^ zd>WhcT*TOT8wE@oyR|`RnDs3XSHNdod~P55_@sd4bQyljM^bi~?w$9WtXTkkqd+vC z@4kUd0VfIm*p@%fgw|_+rhrJI=SCX_HhQ;LQ-I-hna^vUuwLA*$4X+02UB7dj91>; zUfTZPl}tav*at!Ph{mNWaUB>O;sPC z?BxMnhTo&RYx>PITE)tmMVO@LMB{-54khbqY)()iOyIAEKM?)zcpCn&%b=wCchUZD zGQP%il*~7ev~?ZqSN}{n>4}~F0OXVieon+Mja z0aRM8?9B~ewnC?Ps|GN!%BUS!FS(V0Z0N1d`?nlZN`@?gGC&I-ngI%1kM(bDRmPoZ zeGaA?VW+(f=Y7nkzx4UwQ2Mi`7_JO`e69?Ad^BU|GW;GVE-qAV(yZ^Y_Q*}rWTNpv zYmH=1d>z5{{!4zDy?({dY;gn8;qOijs#EWPW{b-l3?b>hvhj{*W0k~8jApj@aH{R4 z7kv%Bu_H|^TG;Q2#-#%uFkAdiP-A5&UWBx-{WO84Z!?I+f!~uY;#8?U*_bt;(#NFQ zGk~#5!L#uWuw@2nwg{M5Tb#I{VRG9dvY~&@-d%Uk&2@G$+83Y|wX(N}fXXmF+w2Pv zMTtLZZU8Ek-exp6K5n#HswHmbh)mg1*jTD}?9PEXyISAba7)$4=a#CEPnPPq$(n-! zBYNy!7WqTg41(4{A{zIXF_2kmMS_0ieC_8gTJkeXtwi+q`Qc-F4?Cz?>f)+3?=StF z6AkX?=as}h1TjnfeAD*Q)AF>=cn5pC0@(bBW~qRQwbbjsHBN3zMK-vl^5^WGXYBK} zS(n06K?~n40Q#{_Fxm3VfI{;k%U7#uo~(S%Bi~M2(=0Hw^jojx*0(O)H1+YhY3k#X zX%?f)@LO*2<*{2tig;PG0NR;=XguF*W0`3-AsBhP%(#<}=l{$!n-U$#JU@JnATKx;th@0eE;{Ek!NCa6vGPjkrQQx0>|W%N1h zdBSc=$EH7^fP6$F@jo^)1r#Nyv9eS`gcivp!dR~@1pmQ=Cf)Arf1bM-MQP9u^Q#}a zq>Z4-ikC&0Al(!oUUq}3nMtPHg!qdojC)UX<9 znFs!N?|G)QsUd!xXy+Ba`3kWQ-M$fw;lfCh+{l}rg*v5AJ%1><#|%EWOe!>oAu&E z^pJXC$7d}&5USpsxn6^#ABLr1vtGP=D|rc?$m*+-Lv0IUWzU_C=ZD8Ztrdwz#)@Y- zgZfG)sIjtCMT8cqp$KEW_7VK4TFa<&i!uGMjBCa6fBI_v&uYC&X|(T}ab?CV4wz|t zonZQn8y1Z8ZwB$+7TI_yMr0GDM*@q9$BzXX+I}wbG@0S0z?0TT4k0_G1KB67<5c*v z0Z{3_|AB@fpz`?*>!biKX{%`+FtJ*HnyY1UYaQ9pi^lugfqQXlmP6~H6B1;3(ZcM9 zS)pxW#UhMFA%?P|A7WUMfc2dpqSE6)iqJV|#i%ifW(@|zybGB4Vi(#)Sd43 zr3G@fti>10izyW$#de;_Y%j<;&?fE6hA9!NOW1``?5RW}?R7Vq?ad*mv9dHz zgcfOy2xGnEEP+3-g*?=HN2!I}%lu6(l61{}yfNe8FGP#K^whzxkQ5k6jL zElvi%Y0?2qtaKJMZkOEBK{oVunCC&yH`xxaL@fk*!NTlR3oYce5Q2oa;(*Eq?zG-U zG%Hf2m$(T-6u-I!8hT`D|1hCotepGRqDN^4+na~054*b>e)-19IvET7ka>9XD+^NB zUGd%~els;(AD`5;fi4r6vBagwr(a}4Dfz_dV|HfErfG=;qVdST%wpBfNrK$sxFK@P zO^@Th;;Gs>ofOIV8m~|?zn7jD_0Z)-_^*Y+_rHE^r&c@c9sM<;fNl^)u^v-94q ztO2^Xg_5;fvzhegcd#vpT-&b5af6uj*Ak6_Nb`Y7e=9+am8ESWv`C>Mq;+39{#5$z zuI1FvVIh4h`uU#9lt#+mk%!M^(!WZOTO2n;epB4^IL|S^32s~@{p(4Q zjIZ%AC6m2gK;x&ozl6VVsW<+~?k}?P>Dv!as`Z};^h1@N_bF^iJ|k;!o?NSBZS{O6 z{hixw3&N-Bp_a>2r$DVAMl=c{I_F9BJ&zOASXnwLLW^`sgt1;Vcl=cPWn6hZ59zzP z@;1OvrQeOx81QOdgj(zOAUOSN{+J@ssNK`gWb%l3V)7hF&yx zOV_Oau>+Gn=s61)dM{p>Jsbr?ZD<4uZD_#GtQEjUe*uLL@wP>g>$o0vszLl$*}p=X zRvj+en`fxci-&jawc73QgC8;vZ@BQw^ZCQyY4NA2@p(9p&%;UjN9Z!cE=}6&a`dxY zf5=vkyaiI2HJdg`r-{bhPguyLf14n;IBtk~%#DikdQ8&4lN8DL8edQ{)Qimh=Cxf! zugKCB9=N=a57cp)pVz5a7)k$?KzC5-?R(xIESWw(8vL(6C|T>dm`VRxoNYl&Sn#EF zgTt)W|3WkhB4-ejzFmBvL1SgfUW69OS%k4(%Lx8t*vUH3q)49+Lj6?w5tPR0$chQ- zu+ve3)$6VItGd7m(myS-@luq?CP)_r7Sg{=*sT5-(!Vb9B>kHLPttdxtm8oTN%}Yy z<~srQW;=YaStEeTd_Y#~1DYOc(g#ee^!-McO>XHU8+y^Se_H3j;Z&

w})LFuQk3 zJ2RI)f`mPG0hMJ(sKFn}iWH@bKWhJjRlde!(@bJ=1R1{e9Bhus`BffOMS7d=4|{Wc z_3`oWnPXSB%lheu%)=j++}^1;eW}Rf*H+{6a2}tBlP7pjm&wqzO6g58pX82Xwwyat zB86Eqag+3oXxv|;rOXqg|0PH>KyH`ZAUWnX_E(rZLB^y=#@CpWlA)1h=N|SB5q|Hd zWWDQhMqd6f-Guqg-QWpw3v_*zKL4ujFwO{(;T_HruB_7V4i|-Aqfc;!uowTilT@Bc3kU9%yaP^! zcff$k24JjV04OvJ0GpQio%aa<6YCv}3o0bHcR)7uLTdkO%K_JSQNv&pDr3+*GU43#Y%SVse_@;YNRh8Iij3o`WhRQFuoBA+#v zF=ge^Hl?~bgmqWLxyzWOhHvhb=FyevueA6f?=uelnB{)xCN-SL4^YFYx~oQ)34ELF z@bl*%G#8^8HSHusG;(ow4RbMV2y%<#hRAJ|awQkWrm`t-A2nQG-mCK6*uA=4j7@njR>P^h^V4PY<(;shNQ>%k3~({Uh(>w4 zZ(=USjiAQLlDh~kl39eY-m3}zq(5U_x96X@m>7J-YP=RKoO$2eHB@9$yS&3@N+b+;;2LN6mv=3+~x}&)t+^Db#T8L3sGBMn%`u zyZBs-Uwqf=@RmWJLT{?!JU$O61*Aze#^BO%-O{zcz1KXBX5-YTAsSg)zkzw2LIk-1 za=X-HZeyI+WAZpfk|G&jV_8auU*%@&*bBRV|21^^{yW}BE3ghtIe{*n|6$aUUr&S{ zZuqT6&7o{mvr|bWYg0BckKK7{l}f?k%hC z`Jk!uRq*ZfG1F6oO;f|UI(hhqk5@k%J3Q6mALu^ve%4FhLf@<5JU$O6>sn5iS-m^1 zW;z<*qw8e#c*DaNzF%-A{k%fMM{QWWsW6->!E3V zLqED+nl$DzQ}bnkzT|u)Ls!%B(7MgGdM>+?8SRHYBb2OJwlOsi9cNqKsqYrt;84_H zQ{FsWU*50sq;u(%D#50_c{r8#1iFmAybFbA4?Ojqby21gjq)yki>Y}wL5-EAxgxYk zD@FK2svR=MFs_8(gXxvVp{{R0aJaH)VFZc0F~RO76&B)dL3md5{uJdZDE)`FLUf3| zJ>l6ZPhyV<9%I0Pn7|#wxCWeVsXWdUhWCt%zu5NOBQ3tq$>2{7vONjyp@#GLb<}V&zPWUnyZfE?xK??qiCr@< zleCOzJl~2tnAmp`=LNvdL!+C@7L4}m{>Ju$}T6jnvo6tqpI6En_J!K8&GwF z7FHVoRJOom?Q%dACH|;g4k&!Jx9-gt!~TQoD-EpiP7|yB{T#x0I2UUQHN4K3 zqlZR}d7#B#7kVIK#q0;6wbgJQf4Le?#H{5`@c)0;_o*NM7N!*u{A{k%feM*LlTb^6;-gS9Z=&LPLi%zKNh>?H?MDv^2 zacNjJW7z4?Ba_O;xSV!JO}-}ESeCU1dziQnE=C~^8P~&r}92Sm(iDZ$-}K0bn<56zCbj}yN%Zo3^raTsIjtiQ-l`ji3op4!}Et&bI0Xni8#dA-;9$DIDby6Mw|=xiiV;7R*VbS)gXInq8( zm0>Hknkt~O?h|Xa1HN5h0NGQD@x@jGX1 zhW0@VeR4o;*e{Z?Ld6bNSWWe$*I0wRxkAjNbZ<2+Uul!2;q{*OVcu#u*D?=pem%y) zFVj6O{*esn%RS!pA+(tq&g1iNvc+3;nT_>REo;B>g{FPY+Dy^|qVc#-?PJ=HCCJT- z+m#-3gW|j%llJ41A{k#}dT*{$8f%jwWj zJ=aMo{Mr2Cd!3c6#oRxNmy9?1*p~P7t+}e_eU#Fsym`33yvyv!lXu9v_crCt!>PQV z(q;7J{V+qPYMb|^M#cVyXq5Mr6-@h|32Lk?eHEcaa_B3tKcpoDOMJNK*WuAURP3t+ z2(fPLhNQDql6T@74gf3~(6 zY2pStl5uAvYVbZDWGzm+ODfK49yx>L#8hR00J38A*-{U9)O zU3B48Hs#I3_2nIt=W^TLIlkJIHxH-sb_%mC@2#Hi;tQ=v12wx44STQ{=%#34JAxWZ z3)_j17Pb>%tk)ufKONI|SGSN=<|w(j{mn-S2PlpEBeFE1ZF}(6FpS{b0rU2po*rI2!C_bY%VAWnFRXEa%~SaG@YSbye5us%-zS%4^AzT& z;i26h`sZ-Fp~a8M+T$qVA5_D6{QGJ+3BYiZnspoJ{hqGa6FD$sFq@~KnK;dvAsQAi z^(k{Wc?fa?1IzaPp=Nwkhw~#dg2^S$WS@!}aBTFR0eZ zpO&{8PUT&WE~78+19x8s+?t*i4yQ5EDDSIXnZxN!P-A7Os|YR9P!Yy@eIfW0hhyE< zPjNUE%KnYR$(1hH(69cAw1)QvIGp?hOZ@(1@AS+iF)6Yr!9JXgmx>cC&DjL0G{L?q z3x`vNa1oV;!>K^HH|NRWmu;8a=HlFf$(REEeO;9FckY&kY& zE}IkyIP#t5Z~znQaNG`MPHu;TZ0K#J&2pz%N0x7a!vRh2553EjEz2Daf`tAGptx+U z#LXdnl9rKP_|{WNsr__+s{oL&@hErvuXPJoM=4qrZ1U?X+)4G$_wDX3oW}rHq8B4eNrI3yW1Kw==8qq22F%>)bRHaBQo~v6DM}((yRlY(0rq|7=<|TslIU6rI5{%|-f|OBU z;Xa&%AH#iQC0tMaHTo6V#GgA!^VS6$a3K5SPH-xG@d&v0LmbWCW$OY0(xaz$KWq#V zaQ8ILod71e ziN9A3*T*LTjG@bvp48!9uHWv*+UZY}wF<`VpKJ?aLi&!a0+d=mjA#@@j~M0&P7~BvS&9^)MY=A+Sg%H( z|H2b+?JJ(Z^mp5Q4xluS`3xJTdV;|OCuVo*xur;bc!JR)8!rVAoXpt-X&k|$>Tlr* zLI_V#X?TLkgpY8ZJi%1)=T1`S$6x~vWS=|%PL;MR8?XdaHb`L&en4SWM!=i5G*1AS zSWj?1Fn4l$0%SuknvTm(G#$O3jWB>d8F!QIoR}IgcVu;V!0rBz_^|5*$9JTYg9IeIY zw&J0N^Y}a+62KI?%>7lzs>R0KlUGN~t3CEPeFbF|z-*#n0b9N>Pq3LFPn6pwPmE)3 zW8C&Q&uxu7!PcZm#@855$rNuhWSNrGXJ@qfjn`c#D-u(Gcc~_&$=*#=|G>-vQq8u^8P>X1k z_o=VU;j|~Hv9i=bgchlf2xGmj5d2Bg!_AeCDZt@a#~Xgy^!Pz(WIeK|g*w8JqWU;P zJ-1Usx5YJq!%0Oj3uoh{)CB8uHbF{D&{<{SaMBAuhQo0Zd2%?;;?JF=X;sG=a3K5i zi8W4@w|T6s0VqsM2HaZgEbqDiCfdVP&6C_72HDUX$Ig0h8|<3D z$|}$EH%V#MjMyZF5{+j( z=sR;M(FFNTaLeO~aa-d&w=T|eOfKbYQY7PRyg|uCm7bUBdEgX=?Z~dYWl>t!^($dXai}O;EDdGLAJaF3hwoh#ETwbS+wmY5fY(D2V6lL($E+ zMo?qrKSPUjQ)FYk>}UOj*7*wyXuYhfySmKEPqm(z(onZs$7rH6LEH|OP$aEq71?+O zH8w$V5m;#5DEt^&&o1($^&A3EuP^3MZg3z)YFyw{nb))gt1AF1n@yg=Xd zXVAC6>?c{l&_6sr=k>qaq5h6tkPU#b_evB@0{0`=g@5 zSfOoV<)FO2=!Sh(5JPD`&}6Vk2KjAKHv_B^c>z4Z$8Af7Nnl%$QNk53jJ$fcEPmprE)d0C& zvMi86{!>hzAW4$(H9FAU%{Ds}L};_FVMy^W?T?WJ7Np1IDb(G|s?App-HQl2KszBNIoE(C-8k zT7`g0k*^+?Y7eG1UbHk|G&jV`)kz>}ifz*PFkEj#H+( zi>*R;qMwX!8NVVlQdBvu!kA8A_lc5~H*VFAX*{O4-t~E5jK4jD6ZZ zokmq*W$8nbUb~En#)HlR33bRdGCg+p>Fq*y>0hpX*2;pLA4?d=Q$=FB}p>A#%6Rkod#A68M}Aa&vXR3Qq<#Pzi;|o z(~;C<#kVU3OF>69B9yEROUHEdDblte&ZoM(q@~iPiYFQcF}K2Dw5jZW4>4%0ETs~m zMan3`Sg-a3|3M{K;qNAg4WTraR5<^sV`MsXr$&k}UK&LZcgH$g2~v>2qD~wqViIzQ z7~M%4OnJkB1W3p@Rm_yN`2e*&M*|qEEcqP@A%mT@LlZJ!Vuf7P{atbk8QIXQVnC7S zXXn*t-6zmx%MKLlNCYW8qG9Mh0V*xy^XNVS3S+Z?%3EUg38>c-tJEh~@AGKrC0nUC zKfZU(r+z7Is!V-+E_Ho;lDZFFhG(kZxXdRiJ_2##K`o{8G=xRj^=8eDK2;jvGoH0k zn`ao$vS!XiS@ZB~X&kRLQS{}*JFNkEYA;O#OOvah`>XQ<*g*HAxeQ#{Ct{%v{D= z6~aYu%L4sxFu9ENNs)}NaStVPsKL9-rUx5B9Tht_v%8^x$Yty$+P_uEV7vOqLe-l! z$9#;Ry*Mpf)VgOIC2LX^);bvIZ(9)KMiqCCRayrDL?i8Ce=sf2C#bQqv`~Z=X{`w3 zCD*RwwN^H*Cs&SON>!Fjcp|2{+e?h@B<<}o-hcyFCn4fgSd0Y_P4J>^*oPp1)ZC;t zCleyz%lhYe{}wQ@LNs@aPwu)K+0fhUfJNm;><^>&s+(8|X)iI3FsL-b=@myLgF;1( zw1jEegMzK9i}OE`uJTD+)kQu|AGN=ey-h`}kIz-7k58%_PnY32c(AVf%Wqj6%$hlw zr0GQCalg#URJU4%qRMzJq*oy~EY5RGs#}v3$Td4cwrE&x_Qqq`CM9dRDq6`=C5Fq<6-D9l<0{JKaJ z8(?C^RS{vF&FoJg;jGADJR$z#M~f|4mkR*9xY;X|m3vG*(=4DE`ppdpL=AsR$FKH3XNdEX2D}z$D&O zbU!$d0jeo+D$GR$RJN*S;sq3@HUk!Trim9YvEn`5KQg(+i)`r4UJx(n9|;NGC@}m{ z<%uBSWd~qG<^ie68qHW?3HI}OCTQKPH5(_*v+rpu-hRa{HX9=uY-&q=d@f#nd=l>i zx(v_7=)Zb!$z#ZYokotWqFJq+o zk@#~bDJx|T2NERd<5a10*w;pYM}A*fWA6vnTLolI<{9j3X~6OoFYrb(U}B|TduCK} zOCQs^TLo!)I5#ccHAotQvutkFeR--KNVr^=T1^-Dj6JjkR*MaDzE1c;w2TJ(t^K_ zmsEgCckejHwgDT4XwnBvtn_`hol9=%BO7|r40s~l56{k|5Bg|SeNp-d5}NFQ%BFNQ z?>L&3k}_wIeQ5apkX8EmFMT|=aeW#taZUQKn|K8msbMgyMxaSwAD>HKAD^Tzg<5kV zIWJt@?X!bfvuTs$L^K|GxgZc!JLTP(;17YjGD_xlcZaU8M{i~oU6$(p>Z_X;R9fJ-<|)EdAITew_FeZW=< zIj*&z6VlvP3i|k53i|jYg(`FzevjqmAKHB~b!xNrjOi6F(RhNFi;}(g8b=a*Kl@zC zDyE+r-)N#o?m4@o;ascnWj@j|Z|oelaEHlVNo;>{W_(R5+g{o&GFO9ZL2Q-Fc0}XS zQPIr!x)9V@`oLX;7HO;qV?8C$i9e}#*k;nbOAjoW7c)|==%+JM%Tp3d#`d#}e6SA7 zYk7$ZqOU*KU@JHQ61PN_MKxG{w zYBNSMR*6cHqZ!2Rhg)*eww)%aWlN>(my~24d>}#Yq4_iA9-3p$^QX#rj>&@$Ns45A zjbkYppUNGsbs03&q-3Gxfy%7{W^R0P;Q)E?5cS@9?(qM_C+B-y%f-G@H3ceJ+gs`o zW^+1BvMtvw<^LE}BZw_EpPpzW&^wS~drO%JYOE|diO?ct7vXoQ6T!IC*ZVsSS_=hq z6=8zZonTpyndu50-OLowTfn4%`4cA^aNy#k0GtZb0sxh9^b2S@0VN(p;y4gcN4mOG0@_XOVWWxVevnzAP}T{;(8J$4=B7|092Yz^I-DL z)+xVVRGOZ2V{?0g+@$$K{+Y>x=K1FT zFTe5W`WW9F=&!VhR_FkC%9=?sTvK4l2L!)Ml?cwS*P&9?-CJR%o+3<;ya|3<)$7QV zio2MZngvW|8hLf10SB&1W{Oj7#_cc$mCt4A0R%9p8F4U!_ro+Z#cva9rZIExB)6F& z8#ZS8){@)r@jAQ#1FaZgKlJ1QmG2=A!$bl310=5us1>J48u3wKJC$(V zFY)F8*u+{{zZQ3s*UC1rTq$4FO@|pFSIXP3DD(;e6`|2LI3{UvRi)^PS7e2Ipt}My zm>4`VP=P5n??zdF9Wcp&LoI8ZDobs$Z-oJ0V}kub)(rs^Ub6wZ_-bVhnCP;;ye7HJ z8rcwf;DE~4i)_PlKt-b)QPxLhDn<9c5-Z#*`xJQ9lR^I@3XIOM2k%tx60{xOu{NxK z+RQFRdu*HX4(QOi^uS`|z7r^oRl#iz6zxq<o~vOsRlZtf>jAY&Z?? zq#;;eVKKauo?xS0AG=kZ`dG&BPDaAB54C()q*6^YhIg`9`EZQvW+gmV;Ugf+2$Cfo zT$XgIG)jI$D;O+b&2p(r_)D1tx5o;@NnxP`iwx^}F5klUG8A>xio;1kH8M^%;J{r| z#fDR52$XI304Pi#0u)}00{VZ}6a<)91r^P_Ik^>tY@jsoM^pB~NI?h^ISQQ+WfI`(^fG|yL3_{<7=#}-kg$K z{CmXHf9L&qB{y_{X?xkwc6OaPZIYauDp~WdPFeHt^J+(?RM)qWef7uk(F>0*<=c_Q zT-oRFvo_T{BK$m0Ru5YCNVZ#af1Yomu@dZ)O4} zR*f6nw8d(3j@NAmnN&UaE)HJGoiZBfIR;BJ0- z_GYPdrOwF>i_|_o^ko|JjZ7s{xPPo>jwqI+VzpMMtGq07!%f$QyRbxPFvk1YXXU6BRUgK0aTARfP^VSLK z#!^DWurXmkVG$$1IlpS^1Wc?tTQ>eJ zdDZ#ah-~OhWnTUK&n|>53#WP$v@%OzGWv*sN=Jq5l>{iXJOQwjVF*Z#uT8**beNxkSYc%GT-GVc*gked^?GHyUBmbt}nOX3!yV!SB~Ns45AjkDF8 zv$OLH#ZB7T%?#~weL(aHmkMU`9`iI>A@Q$9o1_kJm8^ZP$Gk_e*vW>iF$rI*Rd^y# z8{fIYfLUqGr7|T{@fzV3G5SQ=UXzwQlm`}h-Yb>KV7?s{y=iI1(q_k9nZi>1dR|_5 zDAll4sT|D(ek)UF>d~s^mfzmi%pP`94s0`JTluX9v;E0{z+=DFf%h=cW%MR7(&BdG zcIYqg9^ORbKGQ|+gZHRGP-A7OrU)%kQxV2`9U}Ozy$5wxJt|n;$1O@Dtm`uOT>EL& znjg|#g1ok%+WLW&MQ8O9L0)%|`*=psIb+tQZaH4E&gu)oysZZJ@z%<-&gwhDylNr$ zG40!A0}f=L+y_pD-IxHCt(w`l=zzjTih!G9H1`3RSog8Qd1rFF4`f4cEB#h`+#cz( zJDdj8L8Gwnx24uSw8Rml_>3TU6u_Z}m**(`2iu@Y`~kJZ0kwe<55Hb6Q)~oK@-GB% z>n{XQ@Gk_AiVMIbh0tYi$2S`=k20Siw=iya+@@5lwMV#daidW&+9L~-A{k%f8ujLI zgUVm1=h94zdmFd;qCK*~hPJa?%xRMp3+EJ$ z=F=Gu^>_JR)x4pQ{5mrADLHn*$MoIT8_eyyes1nDoOzVJbQ!&sv~2fkPVm?4@F<}~ zBP%WMF^_VBpvKY;Od_;MFGLvY)vL~w|KL%|x|S(p^(enm8n0Zu&5NSmqrtz#3en(S zP4NEOXLaJ5d}R&(O;*f_JH_&^A~&8RiSfCCvKAAwV$0|3aj3GT(#Nd#owP=9*4 zL2ok%zHq(5I{<)*^$|rU98PW@fo$lXz9H*4zp(Fz;Uhq!u<%#3O~%9IBM_vFJx^sX zI0&*u%+|7X62S_s4nX0x^VBX%a;q9M@vbDu#mk>D7q5yn@$#q4pQef--nB`QjIVLK zdUHx{@$X5`;5*rRU3cjU@&0B*+u4ofv`O-rs$^}vg^73IyeWouwU;j%H)7jBO?Cjb9QoFGzZ4gW%Q44XO=9*7gfy% z@lGNd8Cm&_iFYPJjg_TeMQD+hi!jzJ!~FjuURttH5U(qxv7|!bu^}yAp*i4Au%Wd# zVY0H&vP{rW%c)zLAIeZ#4J&3^u0@!;ZmRF2=T0%;K>kR}I4!^y>|{f0fHc_w-+{Bi zX@bf(vq#wAG{G06G%X`?Vzs=YPIz)_8QIVqgU5|~xrd|-gO)*~u<$oBiz~E@AmNJx zKy5E&8oL&LfR|1Lh51*71|vt%@1Ul}lfq z)nGtD^KWED`|IXR>NPre8iwI-AvOWH9F2hY2 zZug)xvX2|O@U=S|;Hz$h=rYtK$UBVWGU^d*Cda+0)leDlvsf|4`!dnZ<3N7MMc`C; z)d@)Mq0zMYkKrN!74v4F?*h7?(Od*zVqL`3ag&nUMIamchkriok7_Gw9fOMijl#m; z*{J$(5eO0n=K+;QKMj&bGgjyWY)LWoADgh(e>Gu~bd)ZGTP)Lx`GhM3xliDx!;M76 znor=?!hM2@;S;VUMKZp|2kOmP-)9~49Dkm)|&Z* zV`Ziq?q~dv{nL`C^0rlNR$ghA#ylpYUE9hrRUJ+x3}D7`Q*fwtLimzH21f3&T-e<%e>{o-l%%#j>uIm56JJ7HEy;rok1j zVkka)QY7PRETY~VEKK>E?0M!}(>l(@N~0A}%!anJ(`b{FZm5#AJMEa_En}t{qJHh| zQ$FsgJhFIfmd;hvnB7OGZdWr?^@z>ABF=Xjd0*aM#=bzkyax00x2=1}U2!%K%%0G- zVWTVZh^~j`<>}&R&N8f-G4f6&bH_z>E;OGXA#dw@e2qi3ROY;g#(TanG=kzg(Pi{D z;GEEU$N0JKP<$_hL|+h zjfHo!jzd9$yrW1Cprn;WqrjD5J#}^j`Gc|q-#GQ0KD^=w<`1e^G5o>sps5BN$R7Cv zoNDXD4P#KI*-v%SvDXY>l_mol0{~pmRr3dciS-BOvon(0A0QigTeyAq)OP#0^Jo-+ zMq%MEUr0|h3J@gBm;$Vuj!jU;oEJc048R(hX7hRYtzT+u;BJ3m;P?Nlft#embQ#?7 zQ9tG}E)(Py#0`tvjEXgn!HtJ|3>Cv;Tuq8(sEwfBoVAT`#B<`TOV@+ES-;_lMk5Ex z-vmyZq%l^S8OBcDx^SMGo`qe{ytJNAvc{wE|B}uVi+7k#C|yzX-X? zJntUcYo#(@_$_^!S0$Op$U&FUTglLu-Rn$##5_hGqH(9q`Y?}CgrLUCQZW%)Bo7hB zdhH$CY*Yd)P%L|l-d@yLohPNLv)Nqxc+AqX3x!YD29^($dx>k?zfZ(>mcP8dC zerF!zxfR1>G(J1kfCJehkAYL=Rl*)jg9EJ3=E1SG4FHw)1?xrt_TQs<48X*CjG}LT zO>U2YZ0K!a#j#RH%xf;eV}M3s;qO515O@p(3A5w?l~v>E)2>LyD$%KgqZ!mj4L$tw zzx?M0-rz3`e8>MYaFgUgm%&X;?#w(!eS+MAxM6XdQL*MRxbbk0p<;N9MoE#3uhCb% zIbKRMdCK!>=IxcU9_WrXMq3-2R$1n>N$To6jb*KmKl2!+a!oVTZ`HJ1&k@gLOXGES zhZIg@KKQxd!P#4CL|lBB-R|C{dvffngooF18O*M~M!45K`&~Zg78H^4`c=7Rv1=b| zk8(7p2+85+x~`(RSDsRS2TB~4U!QP`-8e9nxoM6j^_TegppD^8m(g2Ek@xeu$m#EJchd!!($B1In96r*&~mEQ(-j}Ky4~R zFk=_kU*nw&u!(jNndT+8i$FH?55I7gQbktAF&6o#7%zX*6=6{DpGbBn5X+vR0u7a}nKo zPBX-WpRWBa({uUx!#A_**rhRBT)nnWK2$5h5LY`xzqlCr*s+W|3g$MLece`j)RpWb zF80`WFy-y*a_Cc!9_Qvdn$Ko^KG;05tl4kQ-E2oL9hB#uYB_$>F6xFMB`2$RM>@X$asP+IV(#O32Koo(gG32dKr8DHy2UP!|Ea` zQyNRQq}>$ok9B;1kYUbEIR6t^8TWU6~ia2?lH}P1NkAJfK%a< zS3u#r3&2y@3f7N(@(OsYvF0KG6YC=ST}*Ztfo$j>e$Tzgo0O8cdhLP2}jsT*M55+(mFp;x?mV z%|&qI;VweOa1pbUA{k%fD)r`gDN*;xb8l#g+mWZ)gyao2w4L1^PMf6u+m)=v_hv4_ zcwm|#Z4HaV*1+d-YQO8wzA=({W5R=s4}9xHT-{ow-}$C7@~XLUOI-39%#ZR<%=a`P zTSS?9(Pz9y-IVKuJo&nO9nE+exMcT?I&Nm;zzqSJ7wwlH9!xj3?UPjIGt1n+94kWm zm{l+qr_1QA#9+vpC8D?|TtsQ2ksZgy%tcfrsIju-Awr8(Q-rZzhY9}sRs`+QCb)<@ zl*W?!^55!C#FYBtw41aLNfoM9AAMyt{ zRo1X(t7HHwBMof25?~Q5@Zif*vUVNYI$%}7e{Rtg|EopQ>rA=~Zer6w z<|1AYu~n>NZMe>fJ9`|>bH6t%nx}a&^MV}D3N)C$ zSDv0TUE`ej9nAS}H%#c1(Sjz!5xR`tO4@vzRL&g9T*N7&akmbgx1d)MO;BTH>6{2H z(j5`Tdev_JUtC04>?p6j&g@EQT*wh;?s4=pTtr_h#Out#1f5-qy^0tR$Jz)Ztr$Kb zzUg!W4rG9Q0#5O*PTn1C%Pl~>yhvGswGjY)rp@m|Uo~Oc6JRdS>wKgEFtI*i!IF;2 z?Gum<{nNfb>{oj~pL_5Lpix-(Yc=C2d;)@$hCvYCZ~`jJh_DY1t*j5GH~?yk5tyWb z1C-DPUPnC;R#SrVXq)5isIA6UvCAawZch3zc%U$>Q)D!jj zLL1u7ZXKs-*~3Lj)|wAzVtu}Py5anas2xt07qb1?<(2Z!m&{wUFPw7WV*Q9bLt5E2 zj`>5rn)Sbal;oRl*&^qqWKju}wsbI`Es?JLp$AN?ada8|<4e6HJfz{YDyYxx*C;n-KF!3MmY~MUQaTY@ zq+diB>ot$yzi;2uPORmuVm(A@)H~zTwrK-4|M-LzqCP)GkT>5*yHNzs{3v*}(Y7y4 zyO*pO+RaN@#eoMy+Qq3b1OTWF3kEP&SoI35d9tQmz{F}d=x~?h)-JN4fB2V9oDba@ z!L$n+g@wN{FD^j42omNa0V?ArY_SGFs96aL9i(VUv{gh;o}%Qf$Nb z^(6>$pTJFr8;OcFpTMn!`veukCzMKxWPFX4)SFXE5&xd_469plV$eu`_yjK-n!b_b zG|BI&lC?tilr;~(x$mgBFMj_16hqqhdWE=LzWIX2W4y&k>#>emqWR3%U!oV zUGC*=FyGnHCf{wzJ)%g4ZY%8EW8}y&u{-ZYI-37S+<8Dnt-Ng_}5s z1rmE#1Qi7f>IJc)VnGypuYiIy3l=O`P!zFlu!A7>jv@jopkhaw-}_E>LcaChbMId` zhdn2{KVFz*CeJ*XnM@}6ZC6i^Sz3dWx4Cm#R~gMdx2)A`+#W6NL7y2udKKZJ|4#A< z*p0d@YCc?D`%^shOBBoz2xCSTwmX6s@KbIQ90i=FFWkUs` zV$lz%Qm7xO82w;bStR2m->5n`JV4>I!}`$BTFwiGL*v+4?)zIjo4PR}! zx7~u*nI2+Vqv#kcN0~*l{`>ay+VWD1E1qEB)b9=P zgYU2#bxFAEB_vPX+7tbt5W<)h-k11+CbwB8Mp;H%iVjQ-DdyWO2mIgL2rvdHX(Q}| zH2TOo-S)qogm)4T0;>ET=N=p@iK0D30n+=(U=ODN-8UGUr}Vu??BRR~qdmwVYq(+d zz#i~x{9Jq_58i6&MewR&)GT*DvSa~9g}yGCt%TUz=m~A^BbL@4mQQCjXV7kF>@C4prh#xosQhiX_ zP(`R%^aCml>IW)DKNwXO$-o$(>flPo0C!s(?i_9NeQ-DQgXv-zb0B;g)3AcESRrKX zlrHfDlTDjtnIrnP8Qe05eNdP^?JskNTX=9=U4sBSzIwHU73&v2Wnbkr>etau#*H|Z zH^|DiBfqY5{HK8fUa@a`D9#NAKiKDchHpPUgLNO+a&U8_X!aX7b(>+97U$XL(V7WW z;e7_3KYjGU|9Q|>BJBELKu%!{~PfGJ3ukYGWJq*V8%)@-{uzJ|LzCyY88ne ze1J6C&T!k-x($rX6*8XzssDo?{3wZ{ALIej)*<*oF`)db$HmHtZ;2mN+AK2q!IF)e zWw>GXzz^`NWG)h-@W3uVwLLDniAgA5dvf zKTt9H!J@KA#!0?jb#Nuq2x6?8xef8Uw$2g#V6zy;90;E#G^}98-W9UuQ-%1!+UFqd zNypF5@07!~>UbbGunoiIzfN7)`idR@S+BiWH>;;??H!-;&O6As0l^KQ2j_R>XI*x@ z{MP3c+kflNF)rW-%#4PO8`~XM=E~maFKrObDvG*ITm=i#=PonMSzt^2U>EF0T?765 zz5SBhtrxZr4nP=>w8`iL*k6bS6r(J2N{SB5RVn7%*rfcKA9R$gir@li=(zM=u+SJL z6&Ep+OArVAW&kc)QDySPRc}a*pIgFM=u3{K-AbhfESiyK0`jV{mtWIkD`Zm6@8wJJJ zJ3HsF^Ah_gemh&8cJErT=Id=jc(RM#^(beoD95V^a%X zv33{swZD_7%PB1fkL#%TrL?Hp{jGleX!a`8WOL8j+MH)z${D@Wq{fH9Zqzkk-*Lj` zPv)?SnS$8~VLZ|~aiqpa01ly1me~&|{;~rTEyaAB7Hxh1s0CmmX#wwPM0}F@`sy(G$0L0Q7K&v%9%i91j8|o*&oA;h6yHm&|AH$Ma0f^$PfFx3W zVi!QcMD!L)wslQXGcN$rnn_O}Jyj|eYbHHsv}URpYi3+oB;zDcQXQOz#tc=>JZxR- ziI(oWlknJ{vpiW0qc((34H{N30n>%7>DMMTbDx*5?BYw8$leQb*er*4_LYjYxi0h0 z8s;Az!dve%F5L9=G3#QuZNK(JcupX5`IP7T6#T8JS8KGTf%KKo=jDs*9>5Uc# z@md@YC`MW4rW75R=TgkKai0GtHPZy&)Ggk8TMB9PPE7xP(j6LrMaf~)2wUqmcQ{6OOzQC#ZN%H?1{>Gga1 z-}I|suE1{a06x_rhVTrK8Uob~H3SulhCr1=6{2D^gp{&K#!3EOb#Qoq!sn26AIrAY zwO02>L-_bxSVN;14J(*4=Y_02s7nkX;+n54Ccj$kb^vZug;>i>41d^NTjlOv<~G#vXA9JeLfE`7O_-YVC@y!B6#^ zbN%e7X!cQ5;4jBM+FY;e*V4z$A%<`UcB3wdyt@_|p;5#TEe- zK>MtnHH|i>k|oP#0IN&0Q>lL)mMfaW*_VWzup^2n(x@OM-(np z>tbm7?X_~}OsE13Jbek5z#8xp@rtLY~jKV6wKepe1_ovE|= z&?{}uaM^|R>$=+WkJ{(U{WKr5<2EdsKYzB2OE>VX(it?YIBYyD}cB8I=;8o!U{x*HF0r3;U zc&uwa5WlEU%TFdoS*DT{9T)>C=G&|W{FA{wc=f8-fH(kYSSg=GZ;pkgeIaugkX|3a zFHV$1(JxK{(vBVY#TmfB)-eX&h0xN66;jUuOP4rQmc)r)!~xTb3HU`D$U1JAeeetX zDp^e&QJCyQ2LBLqv0t#3+$%)vQy}^UVrl(?&mC0Weu3Fg*NWpfuf`@@v(YawEV);R zD7jaNC>a?*l&oy<-1NVzJ@X&bZu}2wuT9miVDex$cs`dlCiY=qRw5^=GAbYyi_HzH zB&rYebwFn5z9XqnKpQ#j7!*O?$+JR zhHvm_Lr=pAuh|C+9@Y%F3L^vi@9)iQ){tMp!TPH=quHvbhDCh!(B`UYMGSJ&8-e|g zZ?GG6NvyZ~61(>Wv5x`><8j(J9K!xbg$aH#F$(J&Nzs9+BE@{0$$r< zNaOyqbB>2Y9$^1teFNyRIBO>=N;5W}l$W1*0@ zb0A{b;RiY#h=L*P!n*;V7nfeJvHu|0YE-cB{@^9TLG*1#9H0pxy`WH`PzO-4=m1nI zR1zvi2WVCn$vDYPR0k)N5&nC~dTN?Qoeyha{Xu8B`EOwj4KWNe3ik_HYu|!6fYx!4 zYfk+y4wrM-8!H^%Mqbk9BCFq6apR>u?^QHqOnCE0?4-E?OuH2_uG-ME1+^yG@|lf& ze9TV1X0x6aKDc^GmvfJr=M(hHke6*alQ_TbNp^jr?f0H5w7K2KwZGPLA`Va+cB8I= zqx)kjRq=*nRxk}Aj2YQ?nm9mPz#}xuGVK7xUv^*=Qp~s61^6cpU?o}2NC|0tYnJP^ zwj->nTgY4nqzy(egc~JMY(T^V(&i)h!!5upuPz^cwRlSW;a&;jP@#R4pA0w59{2%% z6<-_ZMeyVeoIOA$2V+#28*>RK2P1lJ6a4_Ow0^)VhLyJ;U^djXpmFuFoo@#C!6A}q z$xtEwwg-6y1ekL?iAov>7!_I*yU`w$Nx!T4&_AfT%0H-i;=idG`WLVpJf8+Fi9Ngn zq;jDuq5@H|Xb)5=)E-of_K;l`$vDY>styhhQ26Y#j^uZFTit`cy|cXNw=hg5qG1Ko z{+p1sZ>@+uRQly7%NbRx@!{J!?0P@>-tMQgxzkBgK1Mck;O`D@Gwc4giBN*6AVZ%2Vf7|OQL8GI{@j$0qkKnVB+!?OU!RRA^nTJz_hc8 zOQ`QJiKAV37yHR@!|Z}x;8&r605`+E2nu6$(9u~$aA^SESA+Ww%L#7F5bXm0wzPI( zGI~UL+XZGrT^pD7zkJtf%X_p73`_bGh{EcJ@Rrsj5*6Orw*&p*X?_3yEa#s8Am`iv zAm?LL&I;x|>;_NZlQzU3@&Tz{sEnvWR4k4^P^nOVP%-*LVOb>OB$qW14z8pFvEO>w zxe*>RAL0*MVikI9OKXe}GFS9ofbnEdvhwZd9bK(92+T00;gj?(c z2maS1qfxTy57`$p=XW#omvMCtzw(>kh2sOAIyR28PG{RSwl=GLL6-}UU7KWIzXjhQ zWNXJC=T5Tst0wh{-KM>_FrJhG#GATR-A4aex9~=?KHG zk~lg*zyN<4ZkQo(0Q@R>;uuj_8;!g)0Z}pniFnHVIqg6omev9CmN=KU17J4P&wjv~ z#&7Pn`G5|9VaaqN#3nfZ@;$WWl1Nn2LYOeQ^n%^{4}v{N1*>2d!*1{dh8q(H@CT$0 zK!rjbK*eGUfl7rsfQr!p0?Hy8CwaK);P3#2&pzwVeLioDbAuc8&hov#h2hQ%4J(-W zenQq(nh*y#6zVS1m!^|9ZlE!v}_F>wbPNx^%IpGd`alYrbzvK^DpIgogss+oq zYcq7R?#6Qbn#M=IulGr3?PA-$e|1KebGg~dIJR0#{``@mr(NKYq`y{W4Zj+r&1pPn zm}T2wBn}~*h25xYV9JNIkHdlNwBpfj)ssN;xEGu z^9P22UnQ#}B1&c(As+g47j9YHz$O7=?o!bZ5KC(av3tjqw;^CQ)WxvnRP~L|Vu>MO zSki+){EQ_sf=oU_#G=Fx_yZ!W=>p3dktIo1#g<;q&i^K71+yJ?g9k9ljQB$oAoT|- zBPtjbi!B7I9O@4$Mt?X_7RfltFQ^W#q=m50dW_FsV`?SAR9cg>MI#`f79YIz;ntQylmcZH&f^xc-2BR4ch*>P{KA zXF~LxnF_L33e+bp>-6!g!<(MZ_OY0E$tTiI$=R!%H#W#yIN_{Xx<~ z=nrZ1sk_L~=KO8+han}1{xB49K*`#NBLSBb{`}^+{{is_CtzuVVN6LJ{UPtIzYI6b zANT`)mAqvMQMe=V9J>sNk`YJ5y0=AtKrF34$S001Z-2mSsEc8^*@)vWdwj$O1BN9t z9uS4Mr;r8%qU8Cct6E$BvwnB~gMJ_Vn|>9{Q`iljK+{gd5Z(b&L!i2$3Q@7xV4zZ= zhM;0Hq)-;gILW`O4h|1c`0TZg4i9oq+|&aN;m2=b4Gl4@V5%7lS*vA53?a&Li)?6* zAQ!{D9M(Hw!O#jTwYlb%7sXwyHI$$H%6wVO!UwFi*MO>{BV=4by}tA2?drF8b@Qb-0AqbzeriVjSw6!UEythW47m!XqnO_F(#Mm>+{9la_L zLs(jZ*kxD)Skbmv+vAk5DAA@8CifhCf$1$KaDcC!w#ab941ojSSIKJ{5tD!5>qE&+ zNJOE*K*ksmYcxusT?WL`I)L5B=H=}Gm<{!_ulIP~$5#o&0Wd6?w16l+krYqLPaI>k zaydS<^nz9Vn_v}8JnRNf;7CddTVo+ z*(W`E_Z!M5Yb}|quzbKauI-T!bXdl9S@FwfjZQbdf3wB$Q`%&(W4h9caOv@SIUQq# zXAsAgFmZqhz|`=;0cybU;f5Ik2f(kwJME9-upwefbDVJd4BG&R!V4BIVjls~e5&XG zh^2La12tNew*z1{)X%_hP-(x3aTya6ShbGgz@xiY{s+=30!LIAe-93I-m+P5VGYJsN^azdvbe7=hXM#i6Q)e-Ka}q@B9YOqoau-6hjz~bJjd!2(tTI zWMY(Mw4~_3RF`7D%`Ct_8Aa?Q=_720G+J+n&H8*L5e*@*1kn(-1Kyp``uLf!yW}?G zo)X4RfH@pIZkPcu0Q@Rk;7+0eAWB}fiYQs95OL^P(Et!jYXGgR+LpHgU^djx_L@d7 z_xp??27qBnCjhY_zM2l+*#R{kF=q(gIS9u$t{3JCCA+pOsfx8fl~hG~#%NVku~-%9 zIipok#aI>Vl|?d6awA9vPkYHH-1rSfT z&n8=Cg;P8%yXd}WTlim%-tVT(6(%gcz2-2q&SUrJS)9JlZoCy_5*RDv4u=c~sC=s% zA3Ei8*5pkY>|d2e6gnT&<$lcS_$Ra-+~qHDDGKbQvIw+0lMZs$v~LG0HM^rRc!4l48EiPQd@YD*pd<$S*@0 zUC+8(-uBAHs+d%Q*j-Nsq@y!XGw%cL$PF^DXD6%}_^gDnW)6W8#SQZVH50!I-Al4M z7@`l0^X*CF98s7K$K$0L(SvzG8|R3nt(mc-jLW-bVm8!k=JE{rn;HVgxR*HVbZp!n+9oC6kO-vj1Jek$);-1+yP^gNHbzC-H=MKzezm z(xDF74-B+Q)M7Y|-p*dN zhYFqmyHS_Lq`RZ_G^Z0!(1$Q)Wgi!T?R5h{G0HO4rRc!OrI>Hy4*0)&0<1bFnI*Uo z(g!ZeLP6rvuX3NlzlJohlYSM0^Vh2b}77?v(MDP*mvAE})~E^d`&^*`5jM8o&& z#GNr7Q_Z!xzK7lvyB{3JHyNH-J#YR!cJ27MXJenpxZWche7*BL~+C|iTtu?k5(?dp8c-ye*d8GUjLx*S7qAVUAw_1mp2XPy(bNA=`;B*>+9EQ z)uf*?ZdgS2&?Wx8c;7FUmOrPyVJ~W`#)6QBtqtG&X!fw=6QtUVWNQE3?83Q1UN4hYZSjJF5G0HN-r3kZjq?m8>9Pod? zpqm(*O8VQsAdQH|tzX;EvMMF-IXRH*@4?15w8SIMMbM9GUq5G4;GBd+``ItF5C9mDH!xjP1CLtP6kW?q1%PI{lWOPkO588Kmw`&l#<# zD#nUBvMiEul223}oQ4LcdOpY7dPL`C^R=$m$BH^h45K!Lk0T8$nErM`*1m<2in_%q zK-Mo!%YR*?_pIZv_V!y|X>t3OyEw;papWu4y?JBnfjew&q{H+t)it@I%2gsa)Q=$*br0-D z{p8%a;`vxR7~Tk^V3Hw>M|!?fI9}Ty0g6$Uc_Kvz=A9JtZN@qONkxS>kD8V|-nSgm zICymToB&Jm=FwGv)R>{7ZYqglMfC-wHVqXu5b&#xvBT?3cmohT-WLQcy_dedBu>WF zcLLMfC{U4ajSP_ChS`UTj9-PRBxkVQj`*hFAWXMO!*)BO@USph?jP|Z_mXzr5ldT< z`4G0eFa4Meb*&8WO}dwn`58O!7{;@0<$qr&634l~mRB2R1Di*s3R83SRDkh!xvPi~B{#12vCD;1%)*(k9o+$oA zUJ3ME3}X(2PcRKDm_s{+tX)44?yxVW>W>;wQ%V1Fr_6p@dx|c1Ry$2|QH{=g;iRc) zO(tAqwG4bTcI{-iWj1$QwUxv|DjfV>7O^k)dVUEf7NP}VJW`KPVj)!l#VE@dNYR05 zCdGW4y@3Dwwcgy=QnL6@Jftx!phknO3E!}LaK8kx^ZpbtzR{goHO&f%NjwLpR}7q^ zpH>nlCXo(IuOMI&pY{jHaKj9ON#Iv;g?}%CE3>L$@+`k2>k4tznAz%UjTep-yGicbOJk6wA#JlgveEIX1!Q0Oj@7Zjhk z`rk#I@DCzB{cj>xFgIW~cue8Di7Pw@q^>~4LtR0|Vh@1Ihsr|5=n5~(A{n>^uR1t9 zK;d)4`swbBO4qMU#)iem-@+OiVpzdE$Pu!(axZa(dEWzMZ~645Zq?tjo2nRY@II@> z)qTaRUR3DFe>1rFx%2betoDxu<4&4ra<8wAsrX}BU;azYyOBxP-mf2b(&zi_xudZMum*Ocu7jRU8^|t3IMpGy%i)5VSOikh7 zG&FowtC3x{&eUVik1r(S{FTKp=0NzQ(=e@Gnx zg+qXoR~}gZ&Hn{4g~Pzorb1Ln98JLrGJ_jt2uuOLN(KTD&(FpejF9Do5I0}?)@syd zGIWSIylpD&KOmOY6xQsiUf!mF*-$_GtGqV)OtT^|K#fS?kEksBhRTz_8@z0iw`_g4_S`Br3Ui zQ1Z*9>+twk>GfOmZ~BE9ZLk|Wfj^HBLy$$47y{J|RfvkkRsxj@H3Su-A!wIHGEVZE zkPIFiOx9Di5`wJHaU-rYNa%uHhdN?d_$B-|mWCC~n}@<*ryL`O(C<~C%q%11W+y&} zWzy?z&*-bgea+4b8q>jvA0cz={Bds*`{m~={fnD4x!~uvMyKx$|On3H=eoD!f3YlRrb)`Wf>j%=x|x^e*a6r(INRf-PG0x9O(`~>`yR)VR-5E`Tf%EBHMzkihiQ)&yDCV+Gd z8vLPUNfiB|HK6M9fHx0}0ec)TOt;ofBR3B$N*MjXH#Ja(8)gsu0KW=@->1oFAo2Xet=;~Hvv(2riu6gB9VFuWl{AcE6X!7EQUdYh95JcVNrD4}nJA`DIg#Cg$J2 z%KoT0?sm*z9d6>vNN3L^QZwtoZq!fC_Lhq$jg2BTvoVA*Gu~TB&1?xMMp>q{6djn( zQp~qG2KXm6Q#upi9;7kLAaRFgJ}jwI$UFq3O*5#OFG`|VGgAR+Lk((XCSY@oyCbrW zrIVVOQ^Hs?`xtMN;fC3Rnu%W}t$9S@ML=XC0HWl!9^#~0uV`x?v9uM{UEZL)D=KC~ zT?_5|&!5`*E2*d$mJIzP3Rh|}Zx2yu>5w=7xDEL4@(uV?`6`%&up2yqYflkB@CBs$ zpt7NgP_gI-R2tL|RE&PGr7V(hlJ8U<93G(XiMGDnYS8@jJ*&_~{MUk-cpQVDMW*0J2vPxrg?D{joLvMJ^od*kNaHTTEqa7U({ zcekq!a}PSnLtr=R8rbYJ;N=Ewcu|;w*#%+D%HTZW2L}MfD9ap_q5~5v#eAC%i~h_H zOeBj5+d~@q&vzZ)GJ*8xN0lHNz!*TxLs;+b(7lI||0yMm25@ZQHW_Z1 zA20y?dZ#H_pb{_5h(dRs+zvz(W~q{qe#GPnq5&Y5)&Np%8<)2MU^diGenX!rZ|XJp zfmdn_OYZ99|DX3}#;Yo>~^X6`GC zWSr#3RR;&1YE>KhuyxMW@hPU~;CWJK`AIR1+7Le3G^}9O#|c^Mc#hP}(>J%tE_pu6 zTf8BMjad58(W;Ra_wMfUtyWc?`K_+w?BsnC*^{*k9M8vSa;pvvZ8&AiVE)s)P!}kpl0qWVXT=i61K^3!~8(a#IM4-PwrylhSHx0w1WEaU|1{Ycc+|CTH7mM7~`OJKk&j zpzuNave~7F`ak}7TZh}!&a`%sX-~dg^3IVfH{D>XFWbDT+DaYn!+}`KEt5!%&xYNo zpLBz-J$$OikQ)C9!kCp+mq?BO2`ENcra+1gOyzo#D7=*u@PBWc!%Dl7vGoW@BRD7K zU4bzS<-$VUfRbMGiION9z)3)r8nD-V1~8>hi_|!GVI5v&38MkX;oxz@?12H`SIIN* zh+m8Dd%ZIv27uUsJP}K7zad&_q|vrHVrdN^$~U9D4FI#Du7&p=b?#bxAO?V8VVVNz zH6uz!(GZ1o{Gn~GVCHlZO7;~`DyknKJ#qAW(o>~kv7*v*Mk}g{v7!c)MKVtEJ*tB% z8Sjp;PF(Qz+FnhvAnrafjM@-BVpzf49xY_;>LpT9=T8ih4Y}DmZkT%xyKuNs!g!e$ z_c3ko`O^W;{K>6*-Yr{ulP##dKiwr+lk4L;H^#!wj%QbR%(1(l&93ZQYlZeT9d6Ht zX`8M@_T;B}ojp5E5zoqW19xcp>2P28>$No3kczqNlUD`2LwxR6hvgk-E0r zj+f>jKrzZPp;B~U4oWfK#?bu_E2?B}Y!67ox95hRFK3X7+82--GjyT{mqf9m4gsV# z4HeZ9u;}&0p_MKQ6?Jq8V@18@79_(Bvj-IwzY6zw$#6HK(4;2!$q|JacI1{AV#YwR zq9T^IqVlKTmUl(PY^ZCY=Fy#vr*V1MhQ_dD^cxYT$-rD0=+DHHC>AAt;C2{B#p!ek zrtwOlpbuUl^|m`8J&*MC(le)GvEI^CNb9YNvEKGAi)5VS&Z>ix*4y3tKOP7ePU`I# zF)ZW`{}sb<^Ey(<+Qw_7-e#Q&l6BiO*1FlS9Cq|eMknEiCU;~=hv8ozIrF<)KMwz8 za+CF6)+IjjnI@-of0*4&e>>i3!0Wj?v~t*0gI=8abVi43Jh|N^8qc6djnx zQp~pr1^kl>th7lT2WbqAu=IGxL6f?WxdKRi8tQFQNfhs8-v{KfCbwPiPFR@o5wP@L z_VbcBR@^p_b=>egK*hzck}E8trxw} z^n9AY)-{;^(c!Ho7m*ALr9HIc5C6sYuA_kWXnr|pH0Fp7H+Eb^n~kS?@yjZ0O6-0< zfvuHN+3n~d9j@v32i89lh-Hj|-KeW%{-(vNpL!9?7!P4Q(vF{qWlRDTqbxH;if|`O ziutzR0sqZ1+QXe}Gs9^eJlh!#p5{7nTxUc0iKS#AntGbSvh7D&y{dQvhOG*j#(>7F zLi+{l!BaX#Obfv1s(mlmole7ReM`XU-*;JeZfS>&@^*kdEsA^0z5~nD!1VeKz`OeX zG+koRmB(JX1@MK@2_sYe?va_Zoq!c)89p;-cjdrRMpg=z;fDDKOTn+=gRfo$g{A=+ zPs6CN68u%{wIh0GiI##`T1#oA^|8Dy1+$?pmhcB@i>BQomV#j{EU=V|s_8NKqmA39 z!xH)Ag?;olNRcLyQWBQ`BX`5~n*__cxetGDTz~^fjeDnMX>vo?>AySEZ36$oAanfg zEAi~?BTHAAf#ln{c(+~JOTlX#H=A_yOE!CV^Mwo6Ao+gg3wPD4F_wR5;b^}rBA%Tw zzj4t9kbG=bUBB)=upDbAxgqQ(>00~5T=Q4#X7l9!`?R$=QPc{i6@>Bl6p6%QYyqj_ zs1T{fsPw3)sMx58sJOslxUxvbNj?aY;nREP#@kO|^DVw*KdJLfxz1wNj-%_z>X&v9 z*2)mVUsd6?G^}8H_Ytzz@D{Nc4SOi>UXPs%-(<6&(?5({^-`1T7Eo|mbKC^};m`es zExhAdt;oISwtvy&_MOhEm}=FTAMY`}VjaUAcDd!4hS$S&xK@2f3_me=Ebp{K-?-tJbPRd&!cB5Y2j(eSLW}PAyV*p_+?}4{=VsD~0pcrKtxfC6k zrc%teoe%i87Nhc%;q$>zUKkHHw%p zz?Igu+SYyxkB}5I+X36eygF6kx&vBFIH1C@L!i&HY+^BcfVY_%+xGh~gjh@j@OG~+ zDM>Z6iNzcM_DcC2QS}H+s4`&Y3<;LuhWQ7J!LP!?E@WjaL}9sjxBxFAQDHz@i57!V zKdaYtTmZ4O78Be4b9q|~WY?y|zO zCI9uovTtW+WwU8MdtS}~jsM8HV)J6iU;GX$`_+y2U1xuEAK7&yXnbM)JtNmOF+or1 z0=pU0zMFFEs#NyF{F+sUf~SZohNt2ojE7y}Hu02UfK*~sc~n$XYg9#4T~swxP2eex zWs!`N{4Yr6^YxgJV`sOqlaAeb^WlB2lAk{_r{E`9K+_Gv6>kV(S5;U^!wP0vppdnU zJH%6bcLmE_eeYFT+A5p1H)yyi_r4}~Z))zP^EF)gB||TtUcdYrJ66G-jw{mSZqyA* zKH9D|pRThzX+cOf+wa%tc`pNXIG;Hc-prWx7r&@;(TlnLZ?MB#F4+~O)Zq?#tlrbO zn3Q(}>_)x3$Dg^sd0P(glqd*ec?V_^Pl*K-qbze)iVjSI6!UHShW~@7SO_Na&z>R~ zOZ0$59F3WZncBotW&zG(Pgf~4B%b08sFiJ1`RH}xDGLFk{B&aK>JLRvSqeC|&G6Ix zlLb#%4qUik#K)J91y5N696Y*9yZMa-Pgw`NKfFQf%XPq#44B}Z5QYu&51xWw;}XJq z#(cSeHyaQi?U`Yt`-nX7gE*YrZMcq}f*89>^c2L>dWy;M;_~(s%!ayH^e*mLdvr8- z${~_z$q)wqwy@eBOrDA-QAxK4qmpiq-GyM8?~DDdYAncNXB4b^9S(AzT-Y-?Udxp? z-dMB${iMsRPqQO>o*?(FHY0C+C@|uyjhOpc|9uwg{_bX?FUUPABv5&7{9k-K&q1@4 z0aw}C1|PnS1G%SO;5+V#Fh+YB54)-Hquq^xCtk98e=VD!3HBliTER?#FrM!Cd&FKA z15&k75mJ3o*-=4Jp-}-*VS&9YD~n{D-yx8sg$YjJ&Y2GrPbuoeHrGOl5(8riJpHn*7#Ht2An4>FX>4^cvXI5eHKGKp4wAt(e%$AV4w7GHz0I zU}j1&-!>WWZ<{QN|7S0-9IslhsFP$x|13!4WtPs$&3T2`WcdIX+o0p}ph*ZZq#6IkZ|HX|m)4o7{~&+i|r6X|fan&%1NF z`P_&fq{&hYJXp){(cCuh=P=9QeXtBS%s-np^?FF-;E*6i_m*;zjk|qm=v9Ky=Xed)pGI*lGXq?CiwU#5t>;~2HQVQU zc7Yo3HaE?+;nn*5oE;7gQ;OcPuXLs_k65q6om#RvIBuvb-{5F|udMVq_H)~Wdi!qZ zaJx2{)tcpOO%rhU+H9y&uB!5J@)x$?IwyY4uzd6Dg+ zaksOnffhHz=!M}hS!3ScYfNyHrr=QNhZ?#s)#1iDO>{gr-IcGB;UBHJ>Jn@5vJL;{ zjt*BVt@c~HF-@?%U&3zG%iAxl=~r$zahyyDV|lMG3c^m3+$KaOM&Tu6QgmS2NHO2` z0N~#_j%i1UD5Mknp(VB|6-_HC~l;kBypXjS++4J#Ps5+Q3gDa2yZ z)`iHpw+-!@o_NE0>QDAEKds5txf_x+>5D6Wa{464jwg<@@_ya=7uD6`ioU$A*{@D* zzTWZ&Uy853Ww{`)pEc*{a1r&kUYmT&m0!`*XimK$XW8`oc8M>Zz*9^{5tWy{tc~UU z4R)hm-d0*plPj(!7E=IWEbmR@gVACttq+ljQI^q^q61S)iutyFfPZH(X6FCTViYRJ zDH-bRD0yn(BqS1k@O4P=ItDG~4B%ti1pNiD&N4J=lzKJe6BFfq1&c`p9`-C$%NAT3EhY&#?91e&W+ULw4VVvW zLu9yN{=s7Kt2ol)MbMJGhKCIGVw5b#yOH#n5cOt?7K2z?i^=s(C~u3wY^aN+>d7Rt zK?eCa4ufGVtmMQ2)MD^QlII=}g;{On?h&Hcjk0oCygx+NZc_WG7l|3{^&Pi=c*9)6 zHBGCZzgWSIUlP?;d5K%WPJMPDp$ABQ@as{Pf~vT2TCxm>bE%o^*48h*M!{UdYTjEy z_1}WU1oz0!9~i+}xt;EB1d^}4ykYv(YHl1zJ_L5NKKI19w{Z{I(+%GQ*@DH0qE;{w z5XM|Ic}XnhG9XnP6(ZFbl^zup6&n>16&F~{wX#UYN&Xm;so>e_W8SnRwrgxxqln$w z{19XJPY-0oVxHl#tHNDWVS5^eSEVKkS<`$)Eav)Ss1JIx*dOOI*!4YE1eqMw2M+MruE4x zcIAVfr1(GfKfrEz)cZ))S32B=8r>~@f4X9MKZf0?m-nEIDp$^(Bo>nbVJz=e*NMfX z1By|W$&{i4^IeMhwjNLZ-ePF8g$&D>8+Wu)?>BXnEX3#!iMUO8GP%JveYBWufG#(} z8rv=<783@j6PcvgV-HbyS1Mpf(@qb=3t-mEFJ=#*LA9_gF$*dai`fS}*Gywy;z+?_ z4gx#R&bj*06yjhpk-*zK|LWiK6a2XWqX*f+4f78cgI^^NP9X|U36Ys4h{8I|WM&Cs zd!=YGh^4idsMw_PwiuF0waRJyS!Q^pH?bHDV_|hN_oNnsKa$*_Mid@#A(Kt$ACMBZ za=HC2M7HbQsWk8Dui2Qx2j4gy(c~UJeDJBTo*SR;vNfy&7p1IRUGHq~CR&_wc8b}Z zmTp`Xld~1gPNcJwpXjz3I8}#BTff?(hc;A^Q#WQlT^pplXgjS?k*dR0&drCtWqT&LJ zsZkcmILTW7by=k8m98Mc=D+z0>!kILzVDcJ-lB^}A z6N~XO3Y9H!zJ9W3^lNsgPoB@xeVW|bvA>#LHF4v8+k5K0-x{U-E3Zxbh1Ob}UQToc zo$78}+rW!^xa4$J@1@SbsS|X#fSSi$^%}bIsV*7z!`p6EHgK{II`Bq^8!<7tmt`GN z-V0$j>g9d%`#7Tksl;M@AdKa`q+JNMVip66QTG3%1G8Kj&9~hP_;;-sbJgvmf3_IO zVot{(kqP^L^1+*l#UMtW>zp)k9I=?=fVq2T-x=47Sj-8)7v9tR_+KX$6AkFFX@1g8 zKfz*NmmFKa|(FSSA9j7?t;Z28ybBw_AG)M*hx$>cSRR?yF&9VNulTFjEv+vROBm<@HY3^QG3_{bY9<`5|Z$;dDMw)pCq zBoYJ0r5^#VJpoUE1es zD=p6I`nDU@z#m}w43F2#)7VkrE{VIx>u}Q?Cbg35yYV^G-YJx>rsPnfu~k~SwQSiv-aFrHuC5YYD!&H|9ii>i(ait3Ci zh$@RJhAIjCq*GZW<0S71$>`jVi+eug5o9zqD%~49fp08syC%Mg8=qS%)o{tk80Cc*cke%V zufrYgS#w2)Mx?xbU^nXJy>3uu#!(%3xwC><0%0ug#eT$3Rsf1omRTu92WGPr^KHA% z`FlUHkoJmTDY)N;dZp`24ueDljaI=X%Lu@zmK|I-_a}Zb3h->Wtm~l;5G`g#1Ln4M zvY)nr_=yYPlyjcZ@q6@0lVv=x-RbFmKaB)GaRpwMncg|d0piePaRZLoSL?&1g~U&O zc!tVw!~BDv;8&r6PhJjzC`_UwL%oQ?1Ew%6vz+{Lb!X8}Fj`taabfP4x1V4()Wx!8 zQN)}jk)+9jVJs}T{Lm%~{zy1|vvFN`MB)9oFm*YJpyb_6DSmJ^U&U;(>Yl>3x7_}4 zO_(Ov@Z7o>M8qh zaX0@PzWTi0chkZn6Rpu=EFnB;Ti9dWQO{U|%g-C_?OTOUs%!S9cU>E-&Bd`o)?#)N zi`j4qB&>+3*s*yE8+xp0`8s&^e8t>3y?WTX@&4@R(3ZV!D*I0i@A<(}iyNc;?b3iI zZd~(mTMqjgw*TKCf9L)UyJot9(h5M5PPx%OJ<}i17PJiMl^#O6i41=fOSILYQMBzyo zn7pxwM4#Nkw?m#oPr<0wLD5qXOY14O_dh9bPr+=ctK&iU=5NnFA#D^4OYRjR3bhcX zE+>&95mucG!8VFzDzw3!jH{ZuJZ4>X>F&6-Rg>da6`DYZ7lG)yItu!9YZfDi~)7gRX<@! z45VANFd1%`VK5NwM?U|6VjE3gHED2$y5)?o-1=F=q$R&ruu98 z9oneLY3xpTt6}cO->J8A(!DN^lqthEZr^F6#f`0h;9UJKZd`h_&4mj?AF(&S2KO}r zeLsxfnsOTYNG>@;sx@}Kr@R*1WO#kh_W`Z=tpz=ZzIVfJ}> zbG1a@M<9%+d;C7)C)WX~+NhsUeNov_K~bSm0a0OrpCpt;GEVa6kWA-2)p}N0`I4=c z?N!ivtv=txW8VU&GzI#}O9=Pc{;}KlMyYJQAN|If>}OH$Xc)c z#82vs4U>IyXk~YQ+&$K}zQvHB)tcPII?E!t9&UWstf3PI^?Rhu8O52q_t4^g?#s=4 z1`Uj5CsGeMEP2E>{$73jD^7>AW(Vy0VG0ev^%=4WvCoH;3P zBiN04d2e<;+4tc*;wNn(jOAUk+E#3km;s7Wma&nd1Jg%}`L;U&|JF~Wv*(~eqH3R% z+zGM}$57zb44R5KP8a;- zI`HhH9U4uzEBHwQaLY=~f;Vmy{3H>$w^N(u%f5qI88G9u_&qOg82Jm(cpN(oCBKhR{ssBm*_CpKAp7lz5~zHBt(t&-Rqr-#Mm ztb$=$=V^JZE#3G{JvxP4s`^~n{O7nm=euihAxA!3wzGBPI*#}?^X1vQtfRlh-Hssn zikhFJ8?8?YaU$LVWz*NC@RrsR$dBZ9jfdj!3H+zJvRf!}P zv-C)qEYH)t!RZP~?Bb~AW`?jdrsu)*oo9Qy@eg~>bnDRYx$;N!(7$^0)8dN9&TGK8 zcjNT7p9|}hewW=}d6LWkR7KgszB48vR-pX_-5%p+x^sw>0oE9!Fd9fO;6hbAT5 z3G#>CsF(MR@4JJ31QCk~fiRYLt2xAC_5g}emf0&s2j;XC^KEU9{)5G+^?81`7;%Db zA@dg`^6ljFnpIyAi06wjD1= z#Ge%`W)bi-t5}Wkdj*SG0vz`3>Vi#4#A4PT4wK=A83v2Nufhyvt44&)tW>3ak7^xv!%~p4%HLD3 zK_5oru>SN1ibS?zST$|~to16Z9lbNPwHtr8^$HuqrO%b#JGog=6?D1ewKu<=A3y{h z1G|xJNIsUo>5B5rx2$gU!9YaGDwy*S#`F96FfowZfK*=8K&YUo&ZvT@vZ!LHlE6Uj zmPIm7u-ZzPtm)?mbKKv(VzhwHlMQBi1EBb?`LsN&rOV}ZYp|q17_<5cyHPLxl`AT&@Qx*Zk`G}l{+>^XpHwUi zlZjE5kx3CIuShYU^#%OB$pX(Inn<4_GB>vR?I|L2$?TPANF{h|kxS$}Xrw?B2C#O) zh{)J_Fu??7uK=oafD`2609SS@U<%)pDY@4H-+c(Q4r27lIBh)e;if*1PS+Yv##C+r zZ&*}4=6hv*GC}S(@Bv+y)z>n~l-v*bVKUsX0Ki}Ht7L*4BCg2UY83GoMBxd2VfG4O z6?!%|^B66yzZ@78QQrQ7*-%$Y>c)F}uFoe;7z{)6#a7aU!5>MQFo=>jejrK~_xF%* zm-VwaaB`YwG;6wecK($unw&Xr@9q}p%IQAt!FfMPQx0A+$z`Xz7FXb5_V|l~5${-6 z!``;iWwyXNX>dS49nSqQcQ-T0m9u#~a=d(Xs<>vE~LDrfB6XoM5CR>N*u zA8K^JdyQMlRWm!>c_G*4L{%#oe+c6#KO03X=NKSW92Fwf7?mCs6%`v55fv9$&WW-} z#z}q+l8N&RvOIZfoASEnw|*19Hf*bH#Z)aS%tS8 zGI3^V3?(Thldeft6e$AyK|a0 zewn6h-Ms14HPf}Y`*S z_{$EAWoG9Lmdx{4-CI`t)@YHg9vTLzIO|?FFEXvdgU9Rwd|QxOd`tZ!lQYH@^bYmZ^!P?;@G&LJKGQ}&-n)vkbvTz_T`EkAG~pYW#m}i9ou=I0&(q_xgDy8*Z@WcvI}22G7VKvCypiL( zZ@s59bg4furjIr!3RS^;!=r%DvXjI`3?`Onib{=&in<6@5mgse4OJ7kNX@cH1}3OL zGKRO)9sRu0l-B38{WG`f^BbP@bej0a99^U>gohh%InnFxYvu7~+eU7_Sd~AbS9{e5 zXD}JK+p|%~np+HUkw!s)$>W=9_H<#byqEJk&uDVZo-H13pJ2itJ3Q^(y4D%Wj~(rc z-tE!i+I~8&J)(~V?~=02ss7iKYy;;LMknfyXY%G(@vqh8)opO=ev)pKwRV#VE=YqTYQSQM;ECO494|w zRfh&zfWH`RK)Vw*21PFf7tsaY;%K|@iy)TPMQ-mtT;48%*-)3q z5vN9@hF&Btg5g_+KTkrDt~I@P;!u?G@cs6QG4Q0J zf8Af_2Zmemk=*w_MuXodC-@dJ72axbS(V>z36JW+Yvg?TRI&3W*7ww?X$B|YVg0GP za&+W$&474>^bFas~&cEUM)SHztDM>{3)wljiTBG#%B^Rwj!4>| z&562IFm)h|=eS=iagla_R8v%HR8-VOsEVk%sA{O1z(tJ9A{i&S4J0$9by|LMl~2mB zsZ(7y?bqXTj8`mv{MHm*#1_I)*FS}O&-|jCW_EZ-)X-|Yd*k*;H6}xSRxrlTg{&E$ zB`#7mbGyvSMcbx^?6|Uac83GQe!_#y`wiQ;YAg7R7q1fzIlNJhTI~9*`g<*|QHV~3 zGqtVxYE%8ry{_cP_B}l?Z`EOVkU78YEyrC7e$hm?o;s1~%FX?k_w2Dtm+RhXV|Kfn zq`aHLZq&=$W_Y|uLgkToP%R;h0?_Y1@H+UynXe>!RR9CfNhq|XcuNT2wmhI;Jbc15AE0` zxJWke^lzSyZ#oSoF7gq$|A29gu6hbC@(H-+6OU_`l>^a5s%31K;f6T|7s0PXU+)XO zV#s4#1W{OHgtSEvwU!3J5DICFAetnKE`nHE7nzZCth`+Wv!O1JHvzjsR;Lgb!Ei@& zb2d15q%aXBj+9amF2s^R=HugUi1&T0T&h;uA+yTveJ(alsWf}Gao&ALEpB&qURV8* z-T0olk=~0tyiA?N-_CuXkNU0kUH@9E);jO^ zdEVD;pSxf8c^~cR>|?|q0GDyO((E(vz+*Zsb)e>?8d)Uqt$@;kF#e7^W)q4CL9(7= zt;U*)r3mXH)?KV?ST_Mh#{P|BT==$7Om5lWLtpj3)9H28;dDcJW_*W`H`6=mV~R|L zu#eFv)$ezI(1Cr{-JhMP$fTxG^nDDQ$$(4r^q6;h2E!6ellm6Inz%rpOZizGTBoq2csi} zpBMYhQ8s5Xu7=d=t$0mu-+Jo)sP+m-z2nku{yRv%W8pGw^BwcK-Yancp-2*halWs4 z6N;P!DTxZHG_JI#a=5ZtXlxks|DeeK&K$!XK5cGf=2FB3N^y(3RJ%WeP{a-7d0)HY zXRirGJV0(b-;jE03!%tjkebySOFJDGQ)CI~qL-z&uFnxuWI5=Cr9b@a)`}^z5_EcI zrza5~2}O1r#PINeYYY^@r<`FDEYokThE5G>i(pBf@m)pQB3Pd2@s{n;VELyM31~j^ zuPK77(bgXFw$&|i%|MY(sZj&ShU!zu5{XU_?Q?Gj_z_)^M4HIoXY;MbBxM>aTMT zOrVg&!UD<;!uaz&q6ttuK(h8?UB~*11qy2@)@ZDOSYrWD7W|E3T==V@n4Fy{T~Abg zqxo9AZqyWchIVPztUOJcC2JvkEPuee?Q4F}j$Sj3cV1Ft=0>%QF0&^<@m?#gTFzwx z6t`_LJpJk^37%JO(i`;;O*20wgO*=PXR3CYF;Vr?n>ux?p?iMc?JA!xi;nH=Qq2dT zplR-}bgrJKkB97jX6h!7rn~AEv{yA}MoN9!^=!;rdg8S0mArWhXidbE7B~P2)f;oo~zsZfEM@7@q2-Q#&8PI<%#M8yRM>EPBy+alF|bE5<(I?DCUgwX}-E zvK#(GC=}~HVlZm3W;VB~lu0>Xp<~}H9e448JPN+o@Mic1Yo;!JqRhJNDq47Y-o$N> z6;S-P>Qv{L3AkC}4wtFzl)3VwW;tzR_Bg-uWeQ1r3)`ze7=On{t`drD2FZGgwHj+G zmLjZ+Sa-3mVci52@%bCY!1gLo%r(dHBFB-^jKa8(vdGgi%*g0FJ@321PA1d&p%6|; zn=ygkp#x+5v|qc1dlVCCRo-V(6+i~ISGggsn%{LXMT%m06Dq8aCzKb`uG??4RQH!f z6?31w_x*0gG+OWuIYrdc`%&Qpg<%vrQsi)FTki=>rtR&P;DJ}@(5UoDWM3Ke@c<_ zQ!e~#ir{LrwZ~1KPF{cxp$HDc@Q5(KK#^T#k6#l1^vD`FEXC6`WYET||i(VX+Ma!?G%lNk1FhfsgRhXr|qvvbOpOZRAA?e8xYr5RC zWp+!Y3>v-o2JP-yo1QsM0kv*F=K1`REn`{G)A&+WHGNR)W4lrhMObt%^|i=y3TDg& zxXb__&zxtYUef(^_{Q?qa!6uh0d*C^*a3@f62?3P$vTcTB5OI8F|5Z}@3Ed@y#|bV z{5Oh$r@KQjgS&inyt+b`iI{JeB(!VK_%|A9SbFMU#=L{DPx%;Ko5%7@qO#?qFHJng zcYgh#M`eH@0d=VJVNx}lT*4TuK8JZlwJ$6)H15(#R5yR8Bw5sS{$A5OEn8;E9@i7Q zPQ0UKR+O3#yGWrx^UOtGzS%Nw-Ok4h7=43&6*qB2H%DjzuFrM7{Kl3M8bqI7pHfYa zQ&fCk2Mf*zwF`NFc{<7WG`LLLe7o2WIJkNqVazND<9xq6Oc>(IQVT#z-fT~; z;mT%V9mwAdpcv@>&#HTU$^7wuEfsyqs{3!0O5el01A^Jxmst?TbOHIfPwlaOu0qV1 zo*<`Pd67`wVu~5l4`kUsSFMHD#EcmTx>Dw)@!m70gfW_+HKN{{$Ve%Z8R8+Jug>Vb zR%WINX3Wmshk5wGH3r7uQ}HuO$s#u_Vd@52Cu9Hx%VGaLe*()CUKQK*!SYWT^L9h_ zzh(@sMq7JijFxRzWJwr^?!FP^&Z`8=?Xu-5rv{BYIvOtwqs;YY>}e8>*$S-49pu~V))vC>R~@#*)fyu z7}uzb&84Tyr5Kb|DxlcARr2?~+A(D|mw1f}Yv_wB7Brk{Qbd~Hdwd&VGZix?8ZL7& za+jLR_m^~d*vgUlWpYSjV*!-_Vf^{@^9f_lgJd1Y8j-ae%NW*UtoK+?v0eklWc`g| zT=+Mk7~2PdANHS?V|17$fjuf(=#C$b?QGW$cEFp?&xNpz$Fq*FuPZQ#a*gK(Ye+G9 zK{LMEj3kV?;4ZFO*FwUWrJjd*yS$zC$}irdXDKM|Y|y8WdwzEP@>n~@T7S~vSIg?? zGV29r(rn~Vz>zJduRvbY1B2Jwb00Sk`UCOY=!P2Fn#>CWvg8jpene62@Tpr;M>mrvEi#a5dW6V^TNcaU*6C z#^5k!%;(lEEMxFXoOTSBM_}j9mf|uz^MfU4@5!>Ahk2>d*K2kC@6%^qt=;(e7KJt! z%Y0r^Y|l97Zril0w2syuRFW83DTiKnTrMBl)q!bvJ^y3v@jP04g4@kQs}<3rhKKh3 zCpa*|Pfg}}bPb&tklo<2R|y$OU0YM)533iA_%(2uJpHTnQtlOWl~?(YOfPvPv9W;q z0Ac)C9) zRF%Fg2_jHwcTxPIzLpcH$bqb6qe4mnq~y)^R1dCf7VZQ2+lEV9sQesp;WS)0^T*jx ziu20jp7Dr4w%?sOMWtDi{;2T z2~@EBQ>dU_yZ<#*a5dW6L!)2Fry(l8t+I4r3cOCaZSGu4*RSg2B@H){-fQ>6Vv`Rscr;w5H56+!)E78hypXP_xiIBx;4^A3`gtNjv9(vDYqfK{oT?#%TFsZRbIo}8#Xl3+fsKu zpKA*pB>{E*hq!7<#RMqfR4k7=XmnxInqu1heY%zj+`gS@Rc3weojv0ujLw*AUQf>* zVRX!NyF6OW9PO}4+kv@V<)bpCE}woCYPPY2r-T-aQ&LiPabPTUUOo{>*V1q9Uu}7y ztBlMiSA=y5Bl%8(%e2k6!;BA>GKUFJPCyvv+iUz@+)Bv+DTxZHOs=%2Zg6F@&_piw z_dprRU64W^tl4G~2zG{(EJ&FJrD!CZX)~4tD6>JHempd?Gd%>iQWk=YD){Kud`t_s zQoKM~$M!vbtt*VCz_PZbpfguDb@E-RL4dLnw6u{?Ug0D$P*#JMi|V~?!zOhMlyccv z9zJl5p_PJ9#Y;}eXbYAaH(@McoJmC)8Fcp$4ak@U~gJXGSk()a>uP>&xUxj6& z_j2eNv+L}@@gim=y8QUAMLn&f+11#rrvkeC@_w`5LJ?zDr<%h1luw`Z9U%88N(pV& zS#j-inuwXJDe+Fi+a)G`^mmba{m5(>@Bwe}qmq-wh(h zA-kxjVnIHAw$$X({RkyAZcD+74_8Etqjvm6`cn;Ul{|F6SFSQT*ev_ezMSOS7%tN` z-#t%GoFjdjKxGVsalUJh6R22%lthJ;6<69*&Rp3nEC>19R*D{Xi)?sI(D1f1%Ur1N zoMU;b=Q>(leM;f=DHO=2K1!PHgS8Q?$5#TG=wjKNsVL6?V^lyc4))k^&JvK*N_7S~ zzdzq)`w5CLrYq>&;^k+%oEI~uC+Ik*t~$q`$&t~P-k_O7ZtmNo2xAtAVtM$$2>{06 zQ_e#KvHWmvGQ0vkq3tBk~tug2S*j1y;F9 zN&S3M5PnI#+Y+o#DI{qTFAa>x6G5sgV|hofd#>LXTuf^%4KZ(CDvwO$C-j*k6fvD$ zU$yhIs;6n;mY)0L6ws0<&sGdw0B#>r`2BiOKCLeD_YCT(jJDZ7Jua0cVqRLly!!4l z44@2NW1&7t1zkPV+PM5FarGd$Ot#;Q^EdJ;=;19xgj4z{B8hKdQ$+~lk397ep@=z1 z)>Ew2SQoM8Vr|3PiM0u9AE3y%zfp_}-vNqIzpX!E;T4K;%YCwR@A22P?_}@f7nNF= zA|g(B=FjjVHVo@iBE?lRdO|4jBq5e(JZr7xuIOUg2Ats?D>|cnmiHHIK()k_H_+C z<*4emU>g;*t+nr)nRO)J@8L3S^Zl@+r+wXJLXk!Y<9sjaxDPi?et?ujg_KkxN7_>= zT-hx21^F9_=>P8^t=?}ojD*FslBP)#lu}}Dwcn@+Hn#pwrGh+hbm0i=B||YqPJt{4 zxO6Y3frlw_8f4O8uPp}82t_hM{t&I`Yab^~C~_XOwn*dj(NZx*vO%AFH9y_*8jnyU z2lV3^qn!HeAQaJt+TsHz04Rb_#eE&pQo%Ci#zfebmb6r`+{eeeVw08%mJ@;`P{Hy~ zp(3Rk@votRtI^gigF6=tj5tG}g2OPg%!LYmiPJQ}QvA<5+1)_nN-WRk#={Yghl}a% zy81n{O5{<((`Q4+jSw+K1v`gcm{?C=YYlDnS5!o=#%!+8@DMRW9t>M3e=47ztF63y z@)l*(S#x~vrW+!r$MXe4@4l&_m0LWQ_smp5!kfMU6W$Y(3*a&@Mg=-H7gO2d5z>rlETw~Q*Np!+G>>a8tQL=smEC}#-c&-k*OFlGfv)^V&6S&y;SV@<`H zjWrQ#E?~^6zfp_}e>)WOaC^IPO)kxJkD4a+p?x3H6P7-1l<5n1P=bt)+_sqWNJ4Q5qtqsbKxf9aHM*w;nn> z>_z$Xy9-f!qAw|<#LV?F%3npy(e)=?L-T9s2Z4?S{iIY; zR_sf!jNv5T9&nkq`Bv|I*V^i(m@yE>`7V4)7_$nbBr2rVaHT!9gDabbvSxArC&rBU zWgXmb&I%SyDCKpBF#`pLgfTiGr{;xDx;9uBGe#d|*pG+3mG#7o0omtJH@@L_!Wd(a zS4_VvhCLTEW)$dt6IJKe%4w1zmNB5aTb{eU`GuG<2((U})|HFaq~Wp%#qscg69A0C zr{YPB^LQc%OYxW^S!au-czp|*2*PrwMh)8=!tzfWE^imb{AdmxOz-_%zGD2X6h zd$F!#4aNG5br9<;)-kM;04T|SqZk){1{CvHHs_tXLo@BxlIao^`jGD0+wwu#mBAP& z=Qv^4pJ8P-ETH!75Ld02%`SZJaa2egZ_j=Yo9(xYX-3~=)=6gtRC?;mdYhrple8N* z?#Db&o6UsTW+? zEOZL}El}Xe%RdKD$W*eP?yn1LhjW&ztc6l+rANN3DJsQ{mQ5gMq}}oPRA+#JvJIr$ z!AS!73D0q(#TVqtzP)ABI|FW7shuE09rfB520b8+mLSkej*fn1rr47JB^31K34_LX zJ3b?gmc5`SEpEAJ+@&*av{dYlvM{r(y;W9g@laK?#?R{&BmIDH5V{u>)$8_mfb=z z!5_3nB~E@se_B{)cDeZiz2B%fguXWjGiDEjcl`{1{2AWMhGDy@`{Jrq+7ZSSK8@q; ztBOyseo{<(g-Rc|JzoKtY~Iy)gkdmm7`oNX;l=L%BwApkE$X`1~u!RceW}yGnfAh-2IS=QE zgEIC>r#`vY5gsM@ok{>X`P&%NFzwrQmoTh6aCaQ>l)TgtV@1s8W7U-H;QrL^S+5coRkzY!5>me%Ex5& zqU}wmat30AP?E4Xi2o}I3#jA$kC3VzcO(eetbK$xC4Kmn(N)ECO4n;k;^4j=!Rp&% zx}S1o;_Vt8oJ93>L;W+`!{-#yzOSE*!xuU*MIE%Vv^wR}E3X94h>}-9g0qYE`9GV? z)SsXKa(hw@{cN&B-^seF=%Bo8X+{_%)QBGnmuYK@`RB?nIw`u~d>?=?{+ubZf-yp3 zKzguIAr%W!@@9ML6jwHzst-N#TZC|1DZg!`aF(W6K^ZF!x_Y)4Kf?%_4AR6keY|t+ zK-@@~3bJo)pCAVjOjQ1$96-wZuU)NONhX$^LH6r6V93E`&j~_YKx-w;gb{6hf)H2G zPu%-W`1Yzyh&Rih4O&ooEO~Q#W86r|A993;4_tjf2tMTu*J3GNaZ844vE&TbVp*kD z%l3M({8NOKEnD=j5rV7H)+^Dy(t<9?wcwk9aJaN!QVveoPlVu?IFAs+QoPX{nOMe> zGqL={>Ilzh)9c>t!SR*d{jSb*P(WL>Yt9txc4E3_7Ht~^jvx9lHgS5ABJxY>IQbq- z6h|G{yDYO~KAm>m_Kb6rGMZtN_tbNmBjeuNOm#juext47gkytM(Sgg2YUdTm>WMnI zOp(r`rfbkh`P?v7H5)oY5)%ukFA&Bx2z4TaQL_HeajX$pkFnNcO~smxH4$qrAdJf2 zD8_}~2a1tevF^#jv5$lneM;{dWTLesTaNOg~O|blb3i>a}59=FBH9!fGHU)4=%Nns zp*wxeqbKfrKYK%?GP2hnpWn{Ikx5qDeY<014gKWHAv=F{RTP@IqID9V$O*26Lu94D)FuzPI!-G;K6GD%n zjQX>~&j%Rp!R)t40p$kiSHIux#N;KuH9i1tpZQ!he!~Gp zq&>yI(kWNOXxc3spZFz@-qidsspBhUG;O-m>$~$E8I$ROdS4FJ(5tjnKHclBiW+7_ z>jn=cZf}Ik%vx|BKg*+24;3amzEnmd^)J1>x5AOpsW`lCKq!op+XbA9@1u$e4Wx(f zHWud_F4H#OqnBSh_HGcN%XbLle8+0-#_bpBTkwlxqwow=uC%8*ab>gVPLRLSWw_)n zAUw*Vr>p)L?ZFPR{} ze^K{%z7Zy)Td6FNHJ&BBz}N3d`z0Inp1!*6J1y2D?H300d7i4rt+@?^E>}Pww|Km` zrD-^(i#${vAGrEJ7knz7Dow|uwpfbytR-~8(u(Ylco}zru+%y!p$nFON|%V-rT>~P zxEgJ}A{RYcF;$(kUvOApaF*MC!7p(Z#$hRDFaZvhIJ@`{^oag@GntI;_zHdiF`HCH z@B?tTd+y+^P73JI*Dp7^yoP4Wpy|dL@B?`Nu-PrkOA(pwYt6CS4?lp~6_aN@&7;jd zZ)j_sQ$|kJ#xfEK^n732Yv_NoFW&#%+!X*0LhY3-LOB4wYj?MGroOxN*`-=4glM~{k` zqrER(8EKXlo>~Wcw0ha+_DtSULzlZ<65NG+mj}Cdp-+>1yTE1I=3CKq+R`z41UPOG z#`#tcA;4J(QW6zXi@DOC+Q5~~rV8ESe+wKV&Q|*{$otD${^6WmoOGa!Q?kKN^mD#p z;OK)i?p}0ne;ipQHxlHF{id6mteY`#1RzIV9BpDY944w;DN~Ra3~%18YyX`9M+iF4 zI!rS@Zx{iN1?bQFE(fjM+f0Bn4)l?UGq!ZTrH6sDs7pK#AGrDe9DK@Y&S1%T<}#LK zXSmF(7&ur4ewP3T%RdE9+UFJj8aTKbZM`zzyELxj2m%}&mX?yDal(FfnD9%IF&CIf z0x8)kE|*A73+KN#r{F=}p$751k8?i8o|P}5f5Z-)HLE}#y`J8hp^z4>Y23C zZ51?V(zYprALIux1}^jU*u(g}!uNz?LYp#9(R$6ouI2tEnK_SzGY{TSy<6QE1ILRKR{j~@ z#D)db02gu93g!~v^qd>d+iEdV*QHAdopitBgxEZJ6uC2@*F9K0l$YXccEzQho^e<8 z^FbX&G`-83kSAdxMzQAckuxXq=+=@C9icl~(48%=0gM8XcXHZuavY_rA$f*W~RUaJ)aOy$!$Tvz~ zu$utqBgnY2#YP7kzY*Yk25s2S%H~3=7&uL!d&XWJ+3}DVINv~5?r|Nnr<4F^!kl;> zK5+E`IQaA`?1~+7B?Gr`uoOSPkhE~H|6h@frG2j)+<#f zXS!q}(tpBXPICrJ&I(;DIUOdOt?|4aHzLChcP^nv_B9o3+98kBtJZcLa6!ZrR0V#X z3-*53Yjox6w+d+1*)`0_ov`qtKEc}*?nVslUtT{)Lm6ERFg&3&TEy6xsrwHCdt3H> zerRT(3bIb|@bA}w*xL;*)7$ee?S3xZ zJu3(Xf;U{hXQM*$?E{x-o9{EOGY1%qBRKJcFwXaqTLdS&K}w=RDwHejsl!~^Y-(`! zcR114)#t3G)6+HjbvTBD6Bj6>DRIH^Q`PMev|n67$_%;GVf-h8lX)N)Pdzxk&>W&a zsQDn3r9RcxwI{REi$OkiSG}PxFOBe0Ixo=sn}pA2oDt(>Iq0;E04J}x?GYaET?u-S z&n}x5=ukoX<>cvj9zJmO0VnuW{7>4b;yrnn&YnzRJOJOVh~=Jl_%3niFclIh?sT5U4VDFW;(7H} z13O>qT|$5Qk~&2Lc5h#nl{hvv2^uVqqG>5`yrXT7>-|6lbozOYMTxJ7iEs+_9KAn} z_E{?3Jmb0&+Tym#?~RR!QJa(&x&$0wezU8b+)x#CRG4+!U*H5+Rp)?7fCLw}H` z=lJG!Nb_K6!<}^%!sQMDTUMp@!h|`_2@m`k&S1j=>PVxwYBM|uVHQdy@P@2Ys$Hy6 zLXW;)5O`pKJo<6eqh>~$h!NVH3*pVEr;WFLT6$|2%vRsoQs=*0#KeqR^U4J7cmAa8 zR5swM5>lLEq<6?!#7uQlz8}4yhJK&FImcc{1sM+8u=ce9$@hA=Oxt{qvF%gv%7zfe z2f{eti7yCY{6R{hLTV>h!j^Je*=(xTF5x!~7JbQ+Jj6pXzdjswIOh%k11LjLyEx!| zvn(czG05%DCa2vACyRB*fHV#(@gFl2qCY4EGHRFmQOh}mFcu(l9yz_1?M@NGSc0CZ zHZuFc5iwyVg6=jp?tPz)vV<^`KtC=RV9{bq2(!C2o`(-yeIN`zCA+lTK8Fc|C1=1F z%hLFzrt+nvhlJ(v*Al{D`KN?Q*}C~(69!kKtyey1ufEa8nGgnt?-oqr5(dA-nNq@1 zvUV3Xtpv$=lu&x_1YXKRdX1%e2_4&ih|Zy-a>#36=LZT=B4+dE(2`|9nCNGAo$_I9 z=2*-7#*N$Hu9t6*zrWv{M^9UvzJBloCDdujflq-hu!uMG4POBqFVcMCCW5g7Dyqu{ z54c+i#$c|)Wp=1-IeiH3GFodnZ6>o^0ZBY9pb8<3zjEY72vY%)bsTF%)?=*oSW~fP zV@<@G3kdW2ZxrLg{|LoAyZ&)i{!}y%ea~lCLUzk{b_W_Y(kg>kosr*jJKX7ggFYb@6KSy zVV%W@OXxwC!!;~*UlU}BM?JRQpJoDdnKiHP)UONk==`W5I>X?BxyN5Wm)<@DMkw8jo(uuEdkKPfo*u1? zX1?FxyUUEY{R>>CeED({WuS|D?AiO3U*(a+zyhkBr}#5c%L!e&fMngqnvnGuYdh9Z ztkGBlvBm zY*;`Y+$*kH?FvGd+^7UzK}B?i^2ieUTc0)j7enRH;lUeEZi*K%JDz8mX98Wu$9-}L zik3%xPMnYV1Or@^{fBC5IOoypYASl^6eyy!j@PY5&l55H#>O+oPBrwkC9|iMnJA;# zy=UiIOeFb!43}w}@44G^uU~T`bSZ~0_JfCaARch30x5|KsT!`dr<%F4*>qL(@96Ts z`^@R-{`$-yE?o{l8PodvWT?Tj#i0EX3G$fXfJe7*3#EmM1Nmk0(9b*8E8_M`JV^aM zFVF7(LFkeU(m?6S=P+29iF-&#K_mZV(~rLu)8z!{0mnSN_k@d|dw2@;iNd65`r`;) z6reWvAU}t-6h56m_L(C%!BTvOFKMt~skL2#6DS z3l19_tl&0S@JpNq3zkXnq=U5OWT7sW;$9{h!!5m#!27Uy_Q68K651&&IX~tgg-)65 zNSz2{hx`*!8C}5Q@m&W~6XfMljBv8b2OqGk^V#|Y$2_{kt#eV0u_D?qb^54N@DJ#* zt7U^CL^X83iam-4j>1kZcU*_9wIvp>g3GK#4kwr3%@w*-`o+WM+!7PR7Elnz-*M3@ zf)v@T|18Ejk2MwRHP%I}yI9w-ZUUsp{f%N=_9pnx+Dx`XXl)TxV z(&EZy(>Rd7j^P^U8vUG?#$6(qv;K9`h;#qqYbfJZ!@M13Zps)bwIK89m%aC$BS`rO za(U5PU%4j$oFCL@kTY6!b5hKQ;Yp(wkm4~#Wr7r`+5}$A1%-Qh^5R))8PF@wb~~}7 z5s(9eE^?stJ*RzdXHSrV;0wS9u0Awa@TvHpV{%h8mN1q8_d&lD>TM=bPJ;zU-R?>V zgXNzRrfiVtUlRsbqwR0ADK>s|^=d*G9EOFZT*Ba&IBgg#$!?$K_Ma@sJj zWD|K`XXX}^nv~ExD|ZLpXpu#`PH)Ut+bd#}yZ0Sy2|s`r{OPm2mdT+*S}VGR0C0wk zQIVQymPg-GTyb@ClmhD0GqZV(2h3^(>;+-$fQWSjI31}(i2+$(vX*0=$a;+R9_uOAYXF>{f1?-| zzBUxozVFt>BV?3Ndlggp>?sYxf|xFMk5zTWz|n!Q&6F*(i=32DgT88qsLc&Rn_ERE z`9r$l6}0NZ#8un4fdGdwPUL0tHIALPD4|_f?mp%BT^7xaeD>+(K@lUrVb5f0W<9Nb zV|sS`6>?}rrxN5A0Lzd*1l#P;&!hWJw!M*dNC7qS_=BvyM2ykmxQUa;*U+zHdfgwY zriAPwd>?j(wj}gOi{UbD^F8b1A?K2%1UQc%jPreFR1j{%yaXwU3aLu2w5L9CWwYsW zLE`@fIKNIBaexyJWgLI#y5z@f0-Q*YsAie3Y6}5QEXZ0FlW>Jf0-PftFMl#hliCiA z6lk=hfR1oKW>Gs(Oqdg(_qz=HENT%G<|OD-tp-K27ZSqA!^g)5t}kBr0;jP(@cq2d zXn~b3Ahr6|vz;C+|CAw`Q>XoFhTv+n{raz8d~vp)59##aFlQbJOU|BhSmI>iKX_RS zNb$foc{+1XQ6euey7+RSc?q3TGS(u;T^2QFC|Vip5i!e5-#RY?V0de&*o}Hfp&OmU z%vJ#~u6=vEK}#=>UU0Jg^tVz9=zNc*;~&izG0{3-MVXd0w60Xq{JCos(ejVMl^aFG zz&dc59%*vnqkWtdm&Fu)ts~!deG_ zG2w3%1It>VnDqlbmb~krgo1qHcf4QLAUvw-+N__`1p~tw!pcv}G#A(_q2tYO<;tQP zgn6H8I&!<2YA zuT?~6NA!7+JCo#lEL^5-z7LPko-kl70fr@nalYMS2{3FxN}@t)3Rl`wu3Xt{S_bmB zEtH>+U;f!b`8i4S-z+oi4kcNo+YDvQSTW*3jXME`R6rsxzJti8mnpPCTBr^nZ(KR? zb$2xZhAhafcdH${kCa1e9Bq)k0obX8B5M6EtcU+BsjtHPjM2uWyZh839d$4bEwq@b$Aj$aDu~} z_6L@n9uAhAO>XPs6L~qzO_N*JCG zkoTh{hh2dmb?Fz&2ls^`!n+UJ_nIq@s?}Ruzbz0kqt>)otr6DH4rkruO`a;C+doRA zC&J_e`~xVRkjM*iqbw3{R?xGz>h3TOr;x<40!jhG`1{q|O8C(aBap~jw?Z3)OFtMot;_3-`7s>A7fu`a32l{7 zVDO!D-7Yo=N0&@{ySEj>0%}6OxN3^q2|t#WfY}!|uYNqGgzh$F1>mSa^*M5^g$xeVB6%Ko#&F@z7S+W#^U&r4dl0P33Bz<SDPI3cx+7SMZ&W5*9bkFoqU5)a<)8lc`<-z8*S~#SjkaHG(1{00(tF5nABQ;$ z*02kottv#d&^w;$&27_<%Q|_0me1-y89PS zt}<6Zvi-)dS^={*fP&?4nbmgseR=^3M7^>%@BAi>miK4?gn3if?$xWy;#?= zhGKoj8j3{$YarHGfP#>}QH%@!5ESE{vuV60pkVj&N+#-LgRlspYe6ZUFbWPs_=?=x zQ1gjOXpB<#l&S{}!cEt_oaD+NETGK0Cy}ZZ`wC=5#Dn)$+r<)rft4g&W&DmV+TQj350RJ=Xeqnn1hr= z;d#kiX;0a6WwR*_^8e73_}Q@FG$lCu9z2IKmZolGwB`|(9Kp$3kTrd_ z=LI$qoK%A}vzc&icvrv&^gZf9pHj>~-%Pp*OOnPB;+IEi>Z;9uhe zSEH>t_-`&$6-5x7;4o*f6idksgSjLnIFw#&s`>y2=k*W=#S9l8OV9PmSncSD0*VqjQK z0%835&Ib^j><7u(i*+4qDAs4Jp;(--24al`I0^q7#lV6!C`Pr*SvLj1$;kuDqowm3 zgsB1VPR@<$h;b4R;q&7jZeKcH2^DRtT;=_~K{$0}x>eH+2n(qF^Tkz*3M4qmS_a$tw;N-df7K=~HvS`otEBc!NCq=3oZg%{b zOUw71XY*i)9Ll(-VSW=fSlKQL_0Sz!Lw8+QW2bRU9xZxubbSVFbOZRl4VP(~@BZEP z$I9&@I4OZJ&i8SZ4m>I{<5u8*lP2%AL*B5YtPdOVgVcC$3w~!>$F<6SXz9zdGU@7k`!3mas zijz+4zP8rayOhwM zwPQ*Kf8?R%j(l$&z=_B1)5psJC+z|UJzTv)2H9C!S!e@JDoY|u`oGVmhc1_|a1NnR zmPv;NJ3XP}?av=_M!SYKE((2pR7D=?1ufaxXBM&d3Al{*nx$v@08Soz8!lA4A%i3a z7EqZG#$UJ3E`pQWAX$5{u44_w`iwOcixbvBtg!$mMSr6h7yb(<=2qaI5`WmYKJ-i0 zfP=3ZgfkXoFB^MN4ddh`gkv1ao$i>!HZUctsO9qSg);sD7PaLN7Eo6*#8sQSo8Tmq zPU6khn%!G|HY}%Cd~sd>0}n-f9OSJ9Q(sfZyiQ*PIN6<6opXGp3|dp^V4(pxF%FNu zWcVtV9>f{t$YRf+Cmpk6~OX1mSxR+UF0t@S&5%q9800hei;Z>x;B z*baLMPHsaO=eu&`4%|_B0CGGV6;fp&C2zK;UUOx$=}hMTCr&tfruaY^_QAe0`11)) zwt*aR;)sW+BLJX<3IsX7m)pJ3G7$Yi?E+a?f5I$gycj2YL9eimclF&P#>oND8QaFp zx9B0pNd#!G3&+on72mK^p964$1J@UDf=|g-`ExJg)(Ms|^_V9FCs>NNK_s0WER~WZ zIKlEyadLjN*1yIHu0~sP^f;KSFH8oUL@DAho_i@Qm}L6%h8_G8r@?~d$?^C`O0vTN zmYlKEn@^H>7fhrM^mBu;Jo%BY!<~5On_QF3(qIwu<7USD&w!MXC&xZlebfOt2pU!T z08-v&KTdP6$fXOroCuosQ5My_JRgv-M8rIa@SK`6815LkaL)JsDmhf^muc`>+!ucW zmnoG(^+&H)(7sD{?OdfTgCwpMP?ZqIU%6E%LCSZKti@R8v8H0Z#+r&n3TqH?&!nv~9 z^fSocb$ARpw*(H?9bw#dcUnCTQaULo^A7b^T4O4nZ0QEl`s&hUY8&A3J}p!akc%ee z-d_L%B7l@$AfK9#j9kMQkq*xQ(93&l8^5d$G<0|dgTB3N*G#8@Vx(w**4aNRr)C7% z(%`CMG7lfPzJL^bD*knx!AQYU%#f$J!-J)GD&{io@L*Z~QGygK{}d@@3y1z|q~L0_ zHAnQDZL8`|5TxMnPo#_?NV!b%AZ~{g<27jFci@DQP7jux1tYJ9B=gMt9j+9@PGhU} zwx=z+B#pYboouN2>cF^ksdjwBucx=xTgWtw?SL9+6OX-b9GKl7Mhty({T6-eX5*AA z&a!Bt{E%;*o;WZwlnaH;kE`kXe&>_MKc!G)&GMP6@*J?mKf`6-*;je>+*(1mh72A) zY;Ol7F)?gw0Ac+3RKo~TRJ8xI80$RNRIJxnQ?W>4O~jfDkfQcCigDrhhGIO&SyiOG zghi*%SLgPa^F`R6*SGtCcomG4z7X~fF`VAT3N}*ecI?TJ^IwE!tpVS z6I`ZkzIC^krc%)aDcvEA^L$r@;vc$OcltD#!lXb`v_9%Ko(wq7X4hAAmu&Cop%*IR+os8@&)v* z2}PG`q(%~?d;^_+_LA~pxM2)W$FzWcG{38?x&=Xs*>rF?9Js!K6nx5g)G3L&y(${; zn6y%`6yL)})}UeOX7-*PL&5S-kzyP%>|Y}VSEH>tO!O)wJm3!?-Et6dGBjrq!BH z{M>F`GVk($&o!S$!o^*4%f;cG%Mbe4ZczjD}t&CP+IweE{>vfM=bnjXrSA6gLh>waD7vbiEUCnyHh@?Co0M(Q7-O z`XocXPfiPKns=0k<|iHKavAusZRW?LsZlrSw@;T!pSmc6__vbi3gCy=yzy@Z!PT_) z(1HEFK)&xGN1ZNrNxsj+W!mOD?@^CaeU1=*&=AJ?-n)?S<2uM(HY%iUf|R`3o+{?b zX4BEBzvqVm=Pp0}-|RiB$Jy3x8kEu0v@NXX4ARS)4pOLkDm?NYJSw?`atEm&_o7c| z7s8J@Acr5m^G3B3B2AJ7pd%d4?mgZOG&D&(L5HqCnHD`l%nvWnQgiENPLD0`JtJs|F8LhtI^gR;d7m) zkIo`Z5*)@&k`V@H#Z8h_k~A?xeDH03_#Jl#;E`--p%fA+{uz>SSd*K{JURZINVAUj z>G2}#vXEWv(S@$wxob{LWjgja6Qnn+j=r7n?Ne!I9@0}V7#$ull~IoyS8`kCI!$Sn z{phD5gEr}1o@W(4l@T@e{CMR}6&4vgnp(ytd`msklip5iXN@Hn(w8_)A)~ zH=Wh&&O;K{3aF_N#$Wm3c0PEs*+n2(i?PmQO~rbRH5H2#)xPjwPO%47)Rd@sC1km3kZ5*1QTTxn0u z(}**8CJDW?~o z5`@>3N+XG<1(XQF`12WbAcR>0l64$wMAl=h^;nOwgke3!dJPEU{Wpqn;ctRs?#&Z4 z4pEXp`dw7t1!wZmV5iUKJ2nu)Y=Ll9mzymEJIf%=s|R9wT;ieDCG+bHeIX20GZ9y< zn=B#BopC8VnUjWZPSzFCORCG)D?q+oPRBhy{nD1%m67M;1^Ip!wqa9pkTkmT4O#X* zVav!^ohaXMh@lNN%PeaSc0gAHHl%#bvSkAGB0FT>dP^tWTW0M)SQb4gc-?j84wCOD zaGAFG4t#I6aQZPqn3oX7`JQO#k2^hYK}w=Rs*x-0srHtfXtU`&kiQaUxa3wF-03lp z?Ckb?!fb&u>@*yX@t?u1HQ%YNAd4y@OAT!&VZ!)5HCc*!zx(9bJ(pF+rxtI%|uETt!yXKedq^C9|+$3r@$#w7yN7B;5xVU z%GzLtP9U=oZ0C;+1;$aiaxG@#ZIS7%9`{r0@bPZ6B1@=F@$j zk92(+(hiMlt!nm>wPv)_uC|{XT|sAbJ-hlfx_8Ih>Ub@ zt1xcIyZEKr6f&&$9INalj~gxfIN`{j;l*rNK=}lUtM*);AjKyvg*VCn*tVyi^XXv| zm!BUB`F8o(wbD%0n&~tr=)zIR_v3x$jx%~mBVp30Q&P9B7|r5sWjSUUw58Fo+H;y6 zkkZOmjQR&F=KA9XgFve{^!v?HJKsRQHSa`e4@e{VJ`R^@oA2<&4`*hdB1kz4VVv)w zkpwB(AosITA(aDC@@9Lgh%1{--S+<;DX;@Rc~qDfDIv@b|;kaPToi}v@c8# zf2Tq~jty$35qZ%LBP9&v)-?O^CuPaxaX3gmPe)bz8AMyDD3CkMTWvN>5hEoAbo`_{ zyPjUPBS?t{ee<3A!pp|uW$}rivoBTzxO3VEL>Z9`rQgArpV0ZdX!6dc~gI^N= zQ|^nqMOcbApn|?+A(5%?@q=N>t$nViVF=}5rN%s`YxJCzQ@`pPw?iq+sU>D_$1LVf>X}RV0K7 z0?9g#H6rUV)_Sa|ShKMvV$B7F3H}?!xbP#On0;0FG`$bgFqR1l z_SifZ@?F1YM)H^&?U8&h-lW)LW0|ym*^QTr573{^_d3rM@zAG0dg|yGW0?teend&l zd_})nldye_s|>o9_V&ZpNRn@BxJ=u8_vtvy=-XLB7#j%Ve1Elt4>g8z1}TXOscBqk zPkC_VH>v@ofB&@9<6=5|06ELG=isjlp+ghM)yvd_T;&KInn7L|2+w#ZCv^A$()Zi+ zg8`Gpbdah@;rXOC(kE_->A(a1u~v7(tdU|mbN~&ba-px@5;_Ew!#{^`;ExV;z^9yr zYgj6ieF=e?{RXKL6cmAE?Zvu| zH5BVJ)Swqw8x~Nf)sK>@d3PizNY^{co7=a0z^Ky~Xkqmp&jT-{V52FAZRPLAGT*I((()nS zrZ=+G&M$3`vWHt=?RH`;Q)X9h)Uf=B@Z_-RcebyCk*Yy4lU6?)%Y4x5K4aCY3i`N$ z@5%(o_nG-osWLGn-`C+XZS#E~d)(`{=LiZ4A&m1~ok37g0#Xu%ZArKiwk6?8Xlx8W z`kVd>JeTx;8XLyHu2kbRHhiFr{ws|eb0?D#l5HSm!dA{*r{;(o8#_VTDs(y=HlB=- z1cDrrzF>^39z26~`sO#h6P;sKLz(54<~%bJJ7 zUst1=haKhN16Ln#f=@X+HIgXVG>kk;155EbHZlf_Wshzj+5QWbe~Ody+8zEiPH;8a zdga(sP3x!kNn-I^TcgVZXjcOlQZg zSvF=Dg?CR+wbUEKLz-5;^`?7_7|-eB0$fIv(?!7>YNp)ofEG@3ymz6S5pH{|gUdM9 z9NFqtcb^_s9`m91mi9|Y(lARbl9r>9WZbbAuL~|8N2dksnDV9i_*9jWi&m_ zQ~%W<89ZR}c%`^%BfApd1Z@VB=CsWD{49o+)$xu$nIMIDBc^7Cr5G`OH;Kkm5|w>?t+KjPj5nyM~-A4eC*Od=(P z=0Zf}R-DtUlm;nLB17|}L>U?ssYIbvlxQ*&3YB}6h%}%K4Wbe$V>FQbKYJhNzUS|K zzu)y;zgjD6-Q_;_bL@ThbDsU!)7cxKI1?oa9zemx=EP$*>@YUj`(K8m4UWS)08C%U z@ZZzKEXUadiS%9HJk87$row&_+W>x?VwoM}Y{3V|aRGSa;^Y+hMG*Z(xB^@^En;S{ z1w^|EcYsq@w)+gM(K$Lk# zbI=QwABITKTY8$O8nsvu^i{5S{LLIs6C?QDL0~Zm{;tJrvnKww#h_yJR>wCln=4c~ zwipx+K63`PyWhuH4El(*ToyrkeKFpu%|gA^M_u0&1+n$q&O{Jl(KIB;uHMUfdWsdfNVaL`+T%m|Cr|z9yR&YDiKN`TP{%r zVRVmGRj{Xg0mw*mbd9ONmA5bh^(r)~Va5?+Pv9#tz1IVxNcyh|6YdjR&7hQer$ zNy(OD@zbu5XXXz-9(F*8D)Ia^N2k_-N*EsXW-ah7`t{ZMg-RlnqPvw?Lc0U?mWd*IFTgYHIPG*KBGOheQ=;k4tc$~fAKZXXYx9gB;fmsM%4G0ZJ2MNNB`#A`9VyA z91nYnD1;H;Klfu#kpU=(l7uW9niFbl*kK$9@ZW>5;3-_zxuyC#lm4|qtS)PV`&3Az zwA=lJ{|xLY=>XN8l)O#)nKpR#g-Bi%FH?Q|tlQEe)ZIhJE+=R@ zQKPdt=Onf~B_H1sO<3QTLrpn7#Kg0&6Lrqv$@9*fa^4ijJ6VG+i&C?{UOhZp-3fU} zf5>LnsZpibi8;J6558B4Scp&p)p7|n2%~%aP8EB|IDm|#7^N{HVzkAmhEWrv8kUFX z{fT6(RE!~+x6cxF%0wD?C5!d8C%ec{k+#z(?@+)VLP2=mH-n;kx(z&^*4gjOFG2X{ z;M_@i5atpF3Ng57d1}~0Y6iw|0^_zXwDrj%H!nPIa%i^@6(u$I=r~0u>drys=QDxt z!Xo#RPBJ1?!nL%yk{V9b8u;(Y-Tstxn;AUevI2)1nQ8L5T;7SA`ctU3HmjUhmb-ng z5Adx&phzonFy^}jvgytD*#nkNmUpp-sHoCkYDgXS5OsiOm?%kT02EvdtJm1D!}vVF z|L_n!9oXWPHSEglV9%P#VR^_cNaWWhjzJ~uA$I`oUTHmg%N%ftF5(_Q^@Dbe$xE?^ z3E_bh1UCz}F+Cpyf7e6Y?#TXa4?)G~Ee@`-<5i<7>>>YfAZV7L zkLZephglJ%NrR!5N0?#Ow)F~zF`PBJr-+ho56G{waM}q-+)aK&`XF~FYV*o0u3_pc zp2dmk(XJqI>0v>;T3wy^TZg;OIcoZx6y|gkrh&x0+xDf|x;atf7M|R7>U{~%)~8JQ zG)O$L-DUipJx-{rGXk>7a646R^fir_;%nok2$mvHEtePvVRXx5hhR&Y1&~n~BRob^ zjMNwrG2&uG#Ilsxef{;?In?zIxT{IXQO7+vIk64rP8Utm^(Q zCn{p!AoJ`+ttm9KlSH^)z-sbkd9?*$B2RxctxM; zdJRsn$bMkbTe-))MN8~?GFM>gu}{=%*!~$g!F0&x!H4`MZZ8k=8p!v}n&1Qiv2ls{ z5JtCq$58A9YXCCpVnoO2iIEv2AVye>fLKo8@F$Y7QgMc4BJA_e$G>dh<+#1k>LVgU z&4`o!y!ELta)O-@K9W+sMzyJh_r<1Y@ktHXMe@C+OVK+B!zz(@x@gOXV<*^gGlt_K zFY#G@ei7N{v~^~Tn-IlKo9j>yPGGakqrV66{n+}ge*y4)DYxa!PjCXWXX`eZj(S0g z7kI5+2u=_hkh^Aus}rT-$kl-p6?jF*MfJA=->rjoxSge)z!$RV&G&tu>{+KDU?=d0 zFyg!Tl{a#NaDaj+NnBt;&Qf&&}W9r$AvRkOz3;^3KSg zme>jU0u-I7q@*?)JHY^e&SMhlKKD3*D&Xt@tH`#Qv=giaJi6wpd4C=31m|u*+VDbO z6`TOQrB_tqjYbf}r}0(Squ~k!=>=wasBeK_X1Kr!5d2*y_`YWF-*y62jNbQEjVtZ% zRg0Yfg;|XN1cw~@v^afm4I2JL5K)PKpiO`vH}%1;tP3&72^Kwz;oOOA-|_+U8VgRK_C6q>sH>Q_WK@n-1t`gf+$nDa(cl5vs1lr>gn<0$8 z-;|Nq2@U~d)WwL7(Gw#xMnH_P7y+@I!1qriW2F)d$&|~--@R7X!VB}55YLA;fy|;L zxsP>1$O+CuIHW*#@uGPNVHa z5%9#(*R`&rc8CJu$cg2k7b-8<33|(#uSJkG`iWpDnyoFs6D$aNe-hXUg1>7g^5cg5 zZ9755=q--D%@0!E)?+(CVb*iI2+|8oE0CQa$ZA+1$a>~(hh{A2lgq(Xql8|P=Aq@h zr6BL|u@Aq$1v|OE?8b!W3k!M65A4o$2YJ`5%H|lrKRPFok86pRYI5??X|a5ew{Y7o ztK(oNRof><5-MptW0$wdwIJ`4eX0IIw4L}uHYTa-wwS8lCC3krzD|Oj2n5U}jzbvT z?mlC&okRj;)WwL7(Gw#xMnH_P7y+^D+27S%ZpG?+|QRC13MY!Jyy=5wVK>hFlq7- z;Jbh68Q%%ekjp8wR+r_Z@mgGd)*D?FrQCJZ>OawT5)Ik(<~w`R;j6?NJFycF+ z!vi%eZUE#nQIbdpD7e_1$Ya9}V~eH#uXe&Z8tVciA}LyN+}8}-$rXS#i-y+6bFrPo z0^I*$jMn&-*iPaB1_r}m{4i`M$pD{E32>gdneL~g0M=2sY@}gK+etd$3qzlb-ijJC z3dGYTu^jY5)5=Dd;1* z>v9ZrT@W0OPYip7MlBG;qs5xIuM)T|mUCdtJ-^1+Z%ENol9RuJ#1p5CnWXIDM12mo z;Ccnz<+)FLQr{0GKFVp_9AB`MI_rZ<7uLKdZ$}P_&;p4cv0m^03M_@%u&AO^)r~ja zta_0tNIWq^9RXL(JIy>lkPy6OQf8pijAG?}f>8 zE<6NFDHokFW>(-`Ug0L)+Oxp7Z?nRiBCwS5C5r=J+rKCKPUy-%AAfp1yE<3dWFPN;8q9J1-nx7YjyWtmU0rG!8j@%_}+6ZcgB3Zf)& zo(;{3I5zAsR*n20EQP%_fWFRze@~{cEM*NOa#%yQux$ah6bFE$c-p{U7Z#y`(DeWb zFW;m&tFfhQ1h}*#^vyzlh;|cO0ovq#Q$4?)wv=svFY?9|UA?>r4}`h{=8U*yCLRQr zD-h`su^jY5D>dVLBn)XQ^NHh@kI0jlDA3x&x%CWXtFTU17LiT%xpw zE}E+Wc9^&(u&dYO^>dfLCC>#kk6i(L*K_Ai4asoi^Idlt23IEYVkD~yW@(C0F8a3y z8z(vPn{RQNTpxWPQ+MaA9t(V{Dj)2>;kF}x(O#7+KRzUr_u5i^_0JHc=Fgp9Iv@q} zoe$ac<~w-P>s4AM*kMW`jQA$c9 zxFq^!*~D;c4!!_$hMSB_u*K%!2e72C-CmEQ*c^@lB*sSu?&_H(IS%-y+>MiGB589t z3ApX#wV+Rd*c>DvXY@i}70dy>rEf2OMi)Um=;wj=Nkot}E{fo&Qh_<(i=WZ||MNa` z7oq>-LbsK1I{_t+ewhF7|5JP8T57}JHV0IU-uE>~TcvNu7Z6(vW{9;I3|%d6iL3!n zi6BTv@iYDhq~kcRys3Zy{(Eu~=f>HvGeXptBL!#mpz8DMH}2ig=}OMtdztH}FG8h~ z7q%>gs-Lx{ujw@IM{-f4-{UR19BM??-0yEQ9r=|nrq76syi2ZLzk9QFfhcvq`|fwC z>sX2>ARF1np_@jYDI;yH0@Rn$%+Xp-6`O^>)q^~mZ<8tCUB3} zxRTCSxp#yNVBk4a)x;gD{`M~F?8?a>N#z+e;qS+BDBb?KMG{c;AB62&JTCSwnUs3> z%_ZRbu_akNp04^$kWFvCuMIAh-}4+-{dNc=zPZ|7sBzH+P!J`FZZGaHWWY1g5YH{dxBUYZqqjKp z$iW4vUvc9Ch0*iE-&2Th zcJlHxZ*K`IVapXld*lz~Fw-IIBDF{O>sVp_+)9_)6(=MqDYqC^eZ3CkFiHpLqKQw% z4kLUlj^nUD&t;TSE!pwRtNs}9EqiR@vLh!Q_@5_jej8wrO3oH)-mGLJLcI@gGLk;( zz;|n3x5o11C$jR?+f|~#xAud1`E?-ywrqx9-)+4(GPTAP?XhuDY+KMarz`CU1IW)bWPZ+^N}M=iH=^=_|wXs zFEZ0$UTfW5@?J%A^7aT={TNXal)u!T@4oulcahu%(t6vwi+1NYlwZ(3*{?SC{4tWN zewA-2Ca;}aI=p@&>^aYyG4GzGJ#v^@$i{6#-`P6Lt4OPe9M9YDL@0r#xkL+u(f9jg zgdIja`X9kDI%FiqD38$;qcuiTEQgW&6Uo5Ac#w?Q=AgLw0UUm#SQK>x9t_mX8T0&1 z_BZ4(10kF$D$Cp9E6P7(@zVeBCUGiuU&vL9s_)2Q#y_Qt_JqU^Q&#~Eq9=hz@6Y*2 zCfv$P2nD|PTg`a>%i5lQz@u)yHSittVW;s6;5(owb0YEoeuO9)rdE79q&$Ce8U4 z$7yp}UUGHpCsL?Ob;5OfcqH9u#^>#~?D(?%`)qpeT0nM=%+LAKEkYGihg8qsu;W|g zrFguGX(Ekc-cAtd;802)<+-c)cKmrdnTM?>my(9h1Mbf_B}QG|YqHiC(gBNE0oka& zD)*P40;{vDRXC;7`%nT=a|t^Lqg$Rb4O`4EfQ;f8Au<|cq{oPg5gQ{SMqIF<-R(~# zW2JHkk~yyz(>TA9;LBD$4BjavOuhGeJbvUSY%#v9FwqlkJKPiI5^{s%anVlCz!tM= zR6NHx%yD|mm`@}bTX)O}_}-_Sw9(CN|g zs-r#dCAJuU2qV6K+U`Z&q*DObF;S8T1t_@KoVdn@9mbPJ$NxWC%=mvAF=mj+!K+`Z z8flAJ0#J!-=j=ZbT%e0s4)CaQ$BVhN#jF5$udUWleHcW$2^)ZigQFt7do0El@bSbz zH|x2y#W(`qRhU&(WJFucTEMT0OW(ami7OB%M#gi{3zZ)%2EAo%t%xA~R4?Ag2*DC~ znB9_#yG;lt%YI|JO$h$3#kd{p_}dnPiqTsvuB9^4-@5Ry3ktJ_T@a*q%*H2eA}Hu1 z8QLzK70;RY`Owfng$7c5-9z>M_k^k4TSCe}Nj`N+TeIol%0?BfT4G>26*L@cD6CZ$#ycpFnf?{;WD2P!OqZmd>;3tRw zL^4(?ry!ZU%%mIpstA5?S?Nh5LYT^u`{b~s>?>-rgtEf^J>i+MJz*}9zKJf{>N(g? zY<9(SIA%Hh1LPY>S0`WZg1f?$L|dJ=9r%D!`*U+$;9FzlrD+?0@Ak+e6LP^%i2ie* z6ae1_Nx63)S&CBEigt=BfuCrlZMQR$dqGxid$(^h@a=9j+t!u#6IaNlH{XX%FPeG0 z#(uI7!iaCvJnSb&01Bcc;m?NVL^vCE7^}Gc4}LO%wdzDqNB`eV7M7oALn5DF9SV_9 z!c7)EfYwr^(z|#A-2fgBgenK!S z877UwXg?80W}BiI%mb^Fgs#988sRw}1QEOF2Rcaz68H$AM6}K=F({r>x_7{VW5*iF zW!KLW*;7O)UElA1dpNfITbBDqjTL@I3hlU+Yg^HWy14D+l;^^>{FcNW2lIVfNX4J8 z=j0TLQqP@s-CrYN%P&?LG|^D}HF@WDhp59=amu%=W<`dWE&7j|2ibgBWmfSeyoOv- z-&f5Op5zl~oJ$l#7=6DPbFt&p17rlq=#r5fqeMnyjP@8!F^n->fz~+(O1} zPx-J6_ow~yv0r$}+k_i4zcH{U)XvFps)5q2gl*EHkjAdVf=?R(93e1QIJS+UFzM}*4S~h z0m|&qoNAXa7&(p}Kvn-Cw)$?^amEAeHhbe6e*&W2#6*D9_6cK-+t7|<2)JU>YUe96 zhG55;0+{J4qfXLPz|Dh14sRGS1UXLOy?73Kq4I;{pttn@XMB7(f)03w6nBykWIgqZ z;HMaY;~@CEj$^p{*WY#=RE*wY5nU5;kt>272Zhn50zbREnf>O`N32El2nt#;k1(b5 zSUNub_d<0%$76XPgRqb$GWwFn zr>%dml0S^Em@!$Vm0Z=KIqeP%O2BU5PY#!?XS<=`o^W#Kwq- z5f@m@>pzigkM&zk=F8+e-0btY5064|GB$GaE`_s z(rH{V;LIm*APu*F=2Fyg!F8@8Bh05>yHl86QZ9SnuC!X;~gaK`Oq3(|#^NYf*j@GXZ*KXO`GI2vOiMa{&r& z#~}HUwHgw3}E2@Pz4vch`D6W-(x&y?S0M2Y-=hD*+3@eO!O!P1-}ZYL)|* z+;7y^YuzsrJm#iC0tdYi0pKy{E&Y@UJ|+i2`b;T2xr88ES$lC-E^5^vSoU4uF$n&y z$E=&u{kJ^^6{ELWuGC+cHJyV!28GeYlFmOHNTZKf12G5+9^o^z%^a7&$+Wjy>8jRD z9&L~qyU3;wWmn?#?Zql9{+h9hUkBQik&}3%pXzmSs4&s^lZ$Pv_>w~}_PuS}O19SR z2$OCTqqe@2N^Nkm;xFmvSF1d!iaehgG_CO@L9I`@rM7Y{sCc5v6Ub%|;WS*!td>-H zJat5VFuKPf=b`2;rWye<5@VFdh>Fn~qasFKjA|G)fvGhAiDax)enB!z zpT)%ug~^QNL5sTfaI$$pVZMrn%UY4CbVFF8aY*v&a5?_7OV9fpOU~w{jpx5fk;kUe zyo@f|?g(ru7i|+b-`6}jrvQ8}4f&a<2z+}x)|stdZN+~*<4M9h+cHu|Yx>cBz&G!- zPW^NEJbgoFl8Rj`$qRh5HTjDeb;8A8%6Xj?e@ik?c%NYv89H*f>EIxOIy%e9r3yX= zzLOxE-h2m4@!5RfEjE=j2qV6qne0X*FPQ)ZQIfdLhOnTP4Liu;cK?H^u(yl`QH3V>dy#NZ<6ExplvGU^*4 zNbh-6fhLd;q}Ov~As0bVd(L-etOdc}brJP@`G4C*P%(PTW27nHWtbRt5fnx)au?RX z_3RmqK4Lu$h#)=9R)i*y=s!UG0>h6mWbL_@?U}%tyfs4V0NG6H)XDT){sT4^?Q`5_ zfPy8zW~bto%k^cX_+Im-d!eF~-ypA&ONy5Kj$MW7e%`HQ=)2~Uw&UW|*h*7MdY~o0 zHQ%n<*0YM-zGq^hosI-0lu#-WILH!dz8JEJP$xuXf@;YYb+aQcD?}-Qs=34q2&3<} zDw6gXfQ;f8Au^Ix7vT5=xfQJUcNzhdUX^5Q8z_*^o_dzO~yLWIEqrkI92D;(J^o z_Lw4of+$Ipu%S88$cCMSS7HL^(7GAwbM0`GV?RJii8Tc^!Pp)A0G`(yERwVzyMsT# zDmg9vJF94S2mm}ZvNCG-V%i;o0B6r%YGK*q4k3Uq9^5%+k1=+K+V}(xdZF(M?ttFX z+ppe4?ttKZb+iNyuZ~6V33|-+93F{9P%K2?4ha6PJIH@6{M+t;iqZSVwtQ_eDisHJ zh{2T5H3ZKkqpJm573Je7s}F;stnK543KKYcc6Ej?w`(TtKOH}06U3pUQ!XyG0W0va zc`|$Pj&gF~;*G19=!;Q5v}0uMgB4hQ&e2i5(n@;8sk>H=BB;6{&J_;_Sn`F=b>xh@ zS4B?j+qJ0pfdqBNzB^|uZ3TTHo4fYu7d*>qN#(;A&#UbeqXgpP5~>hJw|n>%Yz5i? z8F?|PWAr7kf*wIJLSqEP2n(!W+@DAWb{&CaW)4r~J_Rc{E2fpoxb+k(HhCxT?a=sA%Ln*gqI{P> z1FT?9+@qcTu#T&3=IJb+&LvM|4a{o8CM5rBb0Zs4DZ78&^7mZm=0*iz z^QyIP`+2~hD-hd$CUDRTl^6^Ky`>kZ;1#t9(uRU}8bFYB5Fdhp?*xW|;O`pBsL@aV zwxOV6^p?kFca`Qn61cg6!l=0s_0QR!=p)u_4}va1Dx77q&(RY+2-2(XBhlDvpMi;- z6V4A_egKh+>`Cn6kApKjvn9T*a9_r^-zFFQ&bgdC`E*0Tl&4};{?r7IBCloqBSy}L zoIvC=XEqHVdY_=woX>CTJg|&E%*5PRE*dd5i#NdQ5Cm&&B#<{LD(v1O+kr_4BztRrzH2ytvumj8Fx16 zLzqi&r_n_#ip8crJS$Wf!m=_yhbgQFCp7SZ?Er<59U#JbdLQT`x>2zYJ$-{9J-Y>VkdGm{ z82x}dpeS9#E+Ka?Uzf;PTVPe{4r=8u->K^dOS#Xay?Av7+(E`FX}JfeweSAyhu#~- zDY=abtKNb;+#b^~GXd0kK{KWM@oEVw+INzB5x7HA!%rd#)Y@z+bS_^=iaNAWa-kCK z4vvtG^5ez4+29U&kMG-M#)?w{J#vXH5JulGEgrjrH$X;lj1U>gG48-r5gi-Y0I^aNzr1=ICY%;CtsmJKJ~Q4yUe9m~94p z-zw=imkWG<;)YhC!`mO|dWZi6zAqgZ6|^7tKDaFF*FbQGecBI_p66DPVds7rw*udG zlTQ@e(C%Of+4San`210M8gn64qX_krM*b2-pM!+S9!m_8V7PI4SI6cA+X z9C%aWZnlpH-CMP?=ipX^NmG{94KF`c99tep{DcAX+K@imb$0gqyzzS9= zUEw!@G>7@FeEq6Zf>MsVZlSq+l1sq}x4FxC2X4>h~ zqS{~ub4q^1DwzSQ_DrU&03ahTMs(Vrz=NDhW~86j`D|Xt-KG#QEU5bXh2qQ1;RzYo{k?1RxqeW-c#MJl_#f^_xgwn zgkhWM*L2bBQm_?B)+TaB_E)dDzq*-plJ0A<5BP3Z7Ao!rEAXCJLNskJCspSkinas3 z)wSPuG;An*fWI2Ys(VCZL&*W?*fehR!JgIexq!P4r*%#^ zM;l5$V8fKgUoJg{@({3VzlD`%0oYL1eMsb>7b-Cr3VKVc2=_h^WUZD*ke)%o%?$*7 z9tjKu!QV9$zE|YmHWXBh-tuS;ZxR_Siwy;ZS=*5y=!u_ke1_T<2(pGV{<#?UJOVjM z9INrmo@9W)XB@PTc_=JSX`e1R(G7;OFe)}V3k3fCUg@v6D1s7Al%CK9hI01S$!~oQ-7Xp2=IMQ((2Vm;Je`1Dx1+@ zC~KmGueku<<}04dFqAdRUNydXP(`i}`+4R)@V)8YvxHQ-Ef){j^yb^| z@H(f%_1I9ZLm2UWCl?z^CO|47AoG4(!4szPWr2kh#(feoN>M}@W*07oZ66pDw zpM*6)V#cncGc&NE*a3V|=os4?j}65M;2YBMb{UL)pccwHz(u6{Bi9JpP&NU+mOJ9W z^&Ugn0@%=f)lGe9!9WY8$N(;f7b-Cr3VORgWCpBw$8)d<(%S{#@lgcnN7wLnX$Ur{ zb};=H1b^31)?L5+w+#gqqqjUhzIU1FDF=pc5=uvv**&(?a?RPrqGt*4%rM*F)HmUttAtuZMjph zSAr6VluP(P7~N2r3~U+U02u)>x?&W>SOy~*MoNrC80mmzT=)~oSg9mHGCC(C^mc(| zm`^_YQp3HKC%)(7$4Lw8k!2)7Sl0MdS%jnvfBnP^>#+T;yb2Bf)@_y$<`TKP>7un{ zV#~Pbox~BFCpNbq@Ewu%!t_PBICX2_z-bm>8ON5y?aS>vTBzn7ug4ufUfes40NB)^JWTt52fcHld4zWS~ev}Ig}Y{p zgoZv9h^7NjVc~_oD^zy$mi6Qdg0vj)f(ry$-4O)kHwY>_g1=kYEk9iQ+m#&^qxX#s z$R_*?<#Fo)g;}dB5Tw_jl%oCzf_QI$EWAk6Hv*z|{kBVh7CWb=+9q=e>ifdzfQ?Z1 zvl42C^aCw^J{uA1@JfQ>+gw>X0P6l@uSa8}K#RA8`&)!OmZH92AH3BB>i+Y-j)(4m z7UNd;i7?p?JC9fOAMypd%+UV`glr6FuNYAWbzd@nPVq%mNlKtLE)fJ_bbp`Urt3aH zMo)~)7(p?0pHUE_EJiVmlA!LN{}ahT{{xZ{+x<&_A=Ld1QZYl{?``D;%pYUE=WQLT z`-wP?tKL>pCGVO1SfVzKiW3}u%;JezRZ?^^T{Z01O zQw!8w5Kmi^UQk8KDpu#L2fi;(eZEhKuKNa%O>e&4#nbMme8zQu5`+=oSwXn&PXQ>1 zlEhRtG$&@UVJ8s{kUvvDvVpGqF#v6*@#44eaotY<7@jbE+msu)?q3Hu;MqN`5j{`t zrvNtESusf?hOYZJ0P9Jf_^jG95qcA_$jO!JKhQX*0&(kU5(mA|cZIr--qJgd!NJdN z81~1DuVBp03&W2i&=VM$Xqg1MxcsJ|?j!iSb${EyxW8TZQ89Yo*tIKH2}}3IbsvRU zYa$S&#~vP|x{o01Dcb7BB#s(ae?>ZI@ksnE-#gC;YS^S%14E(ir_M}nyboGTpV4nY zk*g&2>|E@}VNmzC>5a-S2Q8-Y6oihgm!>wyWVw!ox-S$oy(|i}_|~H8{sn1S>gU^V z&osL3H$pbgi$0t!fx2HQHK(NPh9o6W8<+S3VRV1P`MBh*1`! z7)D7@_xt>bWUN%AA(`N9>vYwi?mN^e%(prSlN6^fAGsG>i|W1%giooz+&>-aeq@Of zsduE6XTG-N)Z`QhbBRMr$+&3y@8Y_jG$ffLvNa&w1^9k7TSV;?@cqrIvmylQeqW__ zl_=nQz^-|BIc}2FRi0h6Ce(c`=g`J}*ILOjpURgm0=~(|J132Xy8kNhm`>osDst^W zjgBnf`?1(kqZGQGl@8hT=6m7TjfavOaNW;=Fyeb|2d?{h0L_>vNjw55xY(R{#)h55 zSoLI1Vr)SS4>t0F|NB}1$1bnDe&-&p`?>({4l}M1%fxkGAK;#!GYm$orT_060JhE1 zH9C|)*ZoO=56_m(nA=nL4FPxE(DW@wqnL2YHDrxm=(|GQM{fnQ_HfEIKzbA8GF0~w z%!dtr2abb>OW>4ifc9dYOd}t`->v&eW{H2h?xSM#zOmJ!Hg$%IxbCAcYd={cT32O?GluCNQ%l`u!2A{#|U?j=H+!a zCSUI-MX5!q7LEfeIJ$4Ayc9_D#_O4nx zM%ug6R-g#k1UH_qmgs8emgXD#g&G|{+{$a(_qF!3&j(}$S`dEn@UCbiA;TZ- zzh>m%TiauZkHvWohR~J^12ZRzG zjsV{rjd9{zX)9O(+4SZ+=kd2umm9Gatb{P)Th(qC>H^pTyvIagMgpMVVsm0E8+H;Y z0B>uHWyHY_=U@e?05^smw0)e5t>7j=$Fivrm+oLI$VBjy&iXkpIDonU2-kM5-TfGP z2xztBZNP66lcPO*tl$pdaq{Vj@o4-J4vgHC%t0^oUBL>_Te=GX8(O(xcr6#rK|DoP zfTH^N2WB(9F;rSAumTkQT`Smj==$Hb0#uCNH#X#!+=`|Buoa*%T|;)F$w>rnd_g-X z!ZLI?4iX^UK?p_Nf8r?INyS6XnxMrMZhfnDr6s9rS4#t1pzdexj&hj*S{(9S?*7+A zDe7ZrozPUM`&HJjgQkEMwa2ZEEQ^q#@}GnsY1zMwKYYP~uKA$Fwgd;C@R@Q{dV$0p zE?xKgLN?Y3GA{8@_g}@W+Z@^`MG54^C6pnI?yvR(T=z8qGJ0ZU#t4e3`;3AZWig6j zlmvBO^G_sWr7{|ldDCq&_Zigvof_eR7ml^^-dLS5oHMls)qNBe{w2DTfVv;!o7hl! z0%j;8w-25>9l~5<^mV#u3I(|CE8I@z3`;yH_hD5tsr$N>lmWi8N)@Hbpzc53IC_LK z@ST`&*KBx_6eaXvxVr|_{g=U0>$d~n;xpo}T?D?Xe!bw7f!8kGfAE3kqbky;pXbdC z;QR59*^`FQbzcp#>CJaVmqFB#CS3P5AdL7<&ck(oI6y&^Bu20y?1#>Vox~Y{hv%2L zZ-DK{q3)jr7}Nd4wlE*p{R;rESZA+Q%*J&;5@5r=KGixsJA+06zW+WnEEjqRsP10@ zygTmRgsVMu|0>}1>&NnxpqT)5|IDpq4tk;Q3Uwd773`GjhM{0!%L_xn(-__uW<(0= zKKk3=t^3UxX@9%!qhj>FvB?H}F9#)D_feSD{l|s=rx}1CYw`d=)^SPd70|w0xJ~~x zNVB8mz^9mX{}q!$=&ys91>q3O*LPcnLi7xz-huL+4UgJqUA|(wdbfb zB@iDRmjq#SyW1aPE0_Y1kr$&nMqi8-FoI%)#t4WJ7Ffa5Kaq@;%1lVcdv(I>Xs`l{ z5aRNtK-gh;h}V+~`tOky%!2Tilq*WE;xhcxenzJ@hP3h&gW>|^xDbYYb%d_tqE$S? zR^TsjoinCl%b6(P`*r;suSdZ53WLtot-!b1h>uOrfN!(4CqC!{-`1~<&#QwKOg-CB z9tM1$I@|292>4d)B#KhN3dSq7etiXei}j!U=mzlpafJg>Me`j3+4SanrolKj$7XB= zry-2^o~`4GngQnk&S0V>5e86ju{jaRhMmMufFUd7`WwJj;$Q_`01YlY7<#G@TY-?| zbxy5(vz0{-wt_wY2Q+PK8P>B8CJ%Xkxj0BoMHj}zm=pBW+pPi*X+i8RhC6E`FFoiI>zjvPC zy1yJCqbEjYjG&mh&nSpd7NZzONl^DK|3orYDyt!xSQq_-qo@mD+P*;{xRvMoc+e1= zf$vb=w}tSE6MOD_7L(yOzZ{zMFtnAoWuWSb$wMH_CEU#DqFpS)b$^WIbwW~lr^Kkh^?A7NM*{rx{3W-k zr|w4qE`M{Set1?-GXQW#W5UO8Ofvv*;YQ;fW@sQ$frwoW)WZvXSE&2wEo(FYL3%eD zm?8JVQF_V`9+>dPu+aD?Ga7&{{@uDCI`sD6uKTDMy>IO58DFQb=#T3@3bRH75PVdK zf6!pYR&W!-FTcc1-vCyy zcmO5Rajuou^5x)<p!U?KUVJ3 zNdUe*wJV<5(^jAb+4San+k?8sJs+D$z zoY;b!0Ve>~D{U;gUxck71mH`t+vh9_uoZ*?oSLyI{7KK@XlDTXcB<%{f(`>}28035 zIJJ6{I_wdFRxgJGZWGBV9gD^l6$t+2>m2k#-xaI?y%lUp;D#Z37D_#-7+C>|3Z@Ia zF?@MUU!ry^KDhI|*)RfB-=l zD18I~b9!JZKomb6kjIdgu#zDkblm z>n7R`q9L26nr|kXzz#g86t~{9k);FzZ(4sfNw>KjHwjZ!G;0T z*N*_cC2m~W-v)e_7Y>^@2<%|Jl!2jqbSwF4*6J(bz;|4L|M2->2ZeY0W)uP6W%9#@ zT>`#~9<8}Gg0=%!$fh^n0gn}vlUs4iz#YPf?`0L+QLkVxz~fAmB=!LmTx?GGv0(>U z0`NcADE59J``>F6SxbuEKq@(YmRp)>Q>g}c_tn|LH{b9hmo)(ITMrb^Zp4pV)&blz z%3qx7In(GP;P8&h?mgx7BbT26JKkS>L~l23Dh+_gA3Y(q?g@V6vgr$u0WVZyFctKc zUWJ&1h8PjtiYL+WOe2D<*#-pVUkXeG!QV9%-8skqwyB_E^p=M{*=O3o0oYVfxW`nO z2eQ#etdR!<>AA>4WGV>KBM%YCRN@p;IC{TKpV{thCSxnFs+TCsP+y(*-AseWD>D}z zdRz0ooQ&M5H%R)nET!zN8(7iLl5bRTP5PRE*dd5i#NdQ@QmglCe_ZK{6%!*A~fE$nbBq2d3^BU&k|CNWH#f zP=!ndh4-GFHENfvEPtTKCF9&xb-X2AuPdV#Lm1Xm8PY}j@d}&Ds_7}5Gad&W#sl9L zw`=on0^dPjR<}C>uO+8VhCc?rYd*buF%I}n=_CKx4<5TzSSNNX8u*SGop8eo_%7S} z?f4SlwLCN}pgV(MK83n}$jx|LVIueEP+&Zulo8@ZyRDedB0kCAL!G;Dg_;Uq99}0k8sKnqP=q+78 zaDxKDU+6?LJ$OdQ3rAV=7AU&JRp1~9{;q?Jx*q(u9RwAlw><3m(%Ojwaf1SdQG)^< zMAFksK_9W6gFw&(AB2r}ctMagm4P7L+z3PMi<)@2xPF7jfc9oGH%Ew5HAj}JIoq^* zpsf|(X=O-&NYM-O)zA}UP=g#LJTq*i8GNqi+p*={v@hgNw;g)Yjq;RqpyHTtdn>+J z-A64Yk+yZA?P?jn!0<4W?BK-FBL9l}Tf zm)~NK5l;9=af}cd$uSB=^DeuX?n3c|C*6Q`A)ljGM79eY-9S`N=PHPXZU=xgLLanIz7Eboud(qmxdz*mo#tHp8HpAz@_X)_RH{a)9IXYgZJthRg zi0}0>J5c-L3_wAYB+jy-IdPEf7@|TF?x$ddx=HKT2<^gD2xsyK?jrcI1c)VH7U9)3W2~NRQnuWYyue+fmPCDQ@5v$Iq}iqstV<2ZP_eBKNo) z&Yxo>Pjxh0@mdU@=ft>ZhU9)BQ`Z}(t~F4gh9>tPHvY*hn$UA4}UsxsH zmr9i#sC()$-kh-pve6taBzr`@p1k2b_xVq2c}k#hE>RC*^!+w}z>d=nkP#rGOGa{x z5*dv#+G8}uXbl|a>z_yl_LPETT6gzz&oz+c%b9hJ8#en5S<^@5%*^x`$Z>u_I4FK+ z{#1WCer^24W_yb&Qu$81$d9_0$Z>RsrsAS4uEUN~p_R(lJE06cd-=kE!{No@G{_A@xH@9;ej@Yk#9LZMpppouA9 zGSzlp(Q^261!5-@2fa}F!Ew-A!J0xh4C(3t|E|3-WR1k4i-Q$^F})-Nf7fx6)Xx2F z$3eyDEfy)$J02>7u;ZXGI*FIuBq(PPwBYEE~E{ zrjIm}quwcgzEKWadOsZ`wBGd18`5i?&BLL4K=Lxl^ZLN&r*-0Y=N)Pzm-=0MF?72E zwW(ymmW{A=_xmx6zpgv-o-~!K&DWpVmwF>q9UKB%RfFVLLpFIiVFO~0ejOnIv=wzv<(MaoO`8UM zFIn-*tuOHHJl@wx4R|_pKz;xh_$Ie{C+h*llx%Pv2y1->^uEK64ezB^m$ z+7f~9l|df&>VR(%*#_;Y!1tCR9;z>BzBM76-h4k)s4C^r7NZAY#JAo{Y%wMP1yPci z$A;#F1sir4rvUuVMvY$2X^r&BYRoA}tcS%}jhcIq$h`GW5A}hAMPQLfF2J%!yW=W^ z@S!9H0E>4=EEO4zEv69QxyJ$XGCL_`F+~7Z@3DQA2m2qRMokG|MPpN|kz(|rB&C3J z1UgGXx zu&Tz;c2j67N3C1IJ#5Su@`{`PC)0R2%G%@jGUZ!#{HnK0RhB%fCO`gqx#4lNJmvpW z(d%)B9e?44*SK{i%S>o2d~(Lfd*D=%_-AWsQ24i8d57%AWj2RqJ1fQ$ecT{4nml*nj|(H^5I zMr+_Wm;OXDRw`+bj8Z>e>6Bjt|GWDy^~W!TD2HdpOV?hhK#iK45LWI9xAcT-AN7Q} z#3mkHv@$X5IBxk+dz|zP-GJ}1Hv4lEfp6tfXC-UkDd7>P!36j=y0B~IE8yE?+4rf6 znRfgy7q5xh1K)O;MbjgI@8RQX_ay+|t7d-j9lY%WIezu2#nr%fL&FAFCz|i0kWFvC zr{BM}bnaK&s5t>)#P_~0bT2I zf7dM5sa*KmW`T;)`##?YyVYT?2JMj;TxhzLk9V#?SJPX4!Kl*u1i<#|H1*%BDHE{t*Q$1{jsL`@IvSX(Hs*6#5scAC@ogYj~^AKdCmi0u_Yef@z z#@Xfdi0|^0Kzv*x0K(}0-XgFSTms0*i%}gTC`MR_uhKqJV5?jH#{%IU7 z8MQnI;5#zYdDLRy``d6Uo(1p}zTZ6B2Kc_f8=4gjeAmo%DjNY-p#IBj&I#Z<o6$Fc?~_ku*GB{2`t@zAY-zsTA)DTOk5I6BR!CdH0SF_$Z~ufZ zWlS6eIGl;X2}S?~7sClgY}jGkUnT9o8Xx0zCjI{!AKd@7f1?eFY&!L7%G~X^@u3IM z+bmtZb~irO6%L2sR6h1xlm`!w!-$F@z?IX^46@yck9D02&}O`Svpw1t6B-}JfX7YV zDSW^aj&+3*l^KAUUM?C@nFaW;{4u3YSA5LtG37K4dZF@zpP;wdu$TXhFYu6=7luyw z2L=bcF^uUF7zn!fcMZgC&Dy_hAgCC<)lt?$1T-K636n-)ba)6lM5L#+fj(jl+9J3N zFVTkw^&VlCXvQz0QQ8XzX`Fbzv(L4O?c}2CZx5{>2`j_~S&y%R13}N%{Tlh?uzHG7@8y$B2s2 z8lxgcU5siNHG!v;{E1|&RNg`|#Hs|NoQE8K_~lPYHIx|D<+r+3*YP>>ly?vgRqTJM zAzhSjajViQ!C0J{KdYJ0T~Uh0Oj4}rqOFz1o^sPMjT4yA9(EY`e(SYzge~wb67~NP z_a#s@z5mzAO{Y>KLx@b7r$V}h?#VnQDO0A9L?~mKGLs=PhYV$oNL12XM3T%hWXv3r zskwK5&U4Roe)s=-|La{ZYq@LP@Aqz>(|OLb&))kyXPyvh0{-r`eOB)&_#T^F)AO_agYN7dLCeSMYr^tlBpx@cnt8|Ky5z@$2V-4~ou!?*ZShw@w4!E4S?o31WOd zMKkJrU#dUlTJK-N@Zvqn#P^m-GbmHO0;;MC?wb@kaGI`?YLWFK!2hyCgIBj&HJH(E zPU{A=LxY#mw`b_T@6h;TCcf1-Cs&y*WXd+cFvsn(7DI%W(eDBLw7vVtkt|aJ0jKOd zH>>gh;brtefa}h6AGVtwSAk491nl~G)uMu->}B-Ffg9ycnf_#u@G|-$mk1esslUh& z`l-4!75A47yEm!t`h=%f!Kg{rFC0j-?VS47BOK3X(F?($QSuKP2= zu^aYG4v%aay4fXh!P<{o75&~R`V0;$Os-OuFPVF=LQ}lm+~fVP-ofDois){qHriFH z#us0!E}P)*lDPHoE03zLa}^zyxu(WFtj4>qx7B#W-iH1Z&Af>3x#8TmuZs3ReeQN> zi|ZhMOZ+X$w0r{%g-9s|6cr{4Pt=qsHBm&OxI__2BBkta%*M%BeoQsfEsnOcO1bp|K8ro$L_;!78s8J61zUr~Nj}`d-o{`hw2Kc^v>|^N|@b_!_ zP4igrZF0A8cMtG=r*ynV0Qe3teOb{Pd|$CLUv>$6_lOH9F~oeZhj<^&sPjE{RcZ1$ z7Aa3qCcfRT36YWmsH!TsH&W=p{glEY>pAEDYowUB?bKNsDV_e;NLh!O%$pV0F_uNj zX28hYsGL)ChR|-$cEC}~-r9b`Km@~-oq%cW;+78gM75mT3)pG;sB>X-?K>i6AMoow zturpn9U@!+dkA>6sqDeTS(v;kR}qU(U+OO+g?_RVJ-FK4TY&5#8A7B`wVm*y#S|K) z5NxC*)V`y^I&Dy3yq)?e&93qJn`X_eOL)g_JsJe*Q%K7Ha z2-%2|E2ooo|5Er>crf5?FGD=x>XAcO#N@=0*0)Mmoco}VyBe5JHLl8=I*o0pb$)W9 z!g0Fagm;CC3DX;gWE)iDLtj_#XBjy;vH9oPG08)|C@SA_@*n@Q8vpK=hV2GS4^6*C zGcArjdo!}dH^sb7$8&C2R>gB^RhrI6nbxsUbs+U&S8*-+Rwl)_MlM-;7w@<2Cq>?QyMe5%?bO zd-Bs9@a<8kZP*3;y*{S7Y$5o*h>I(3f$!2)36}2Q`<<80Vl(?M3ZH&UbX>u=)vS|U z6B*yRXhxmy8Yx2$)+-Q(CHW{5-?rv6X;@MKsH!TsA}Ms>DrripMb`5H|I4rhF9GTetVj)IznK z3j}n$9$Y<;E}BP%><1q1vN9|ie@weJ!N3*99bLAm5+<+8wL)*`OZ`QL&`+j+Awvk# zlOq(Jp3{mh!nHrFqGxomENpt3AKfU8E+RUb9KFJ5dgkxWV?NP z0KNye)emY7{*G^~eP;{!4(WI*aVhxjXL5O6EAaPed*r(y@ZE3H!?erbJ9tRd;Tb-z z{NwLS4%`Oc*%wWA%>dsWT5D9>!1#7UGwOU#E*f=cElZdgC==hU0)&K_1*objxY<(Z zz^#$OBI~Pw|9=V7{`XTlpI|11%{O%DHdjcPY``WbEt>7)goJqs=X}oD;%@U?yaHNdB)L$eF{ggbriy(Vu zCoT~65vr1t!&Ei0)OcQIR7s=#=0t*jnlO3Y=l<)2p>C*)BWdCIqXm>OAp!@IYforu z)g5~oLRE5kTg@5ZZ({i^YpzJqXL(DTz(epR3Oe^FdZa*A69J-fcm z+^h?Ia$EA&_8U>6aLZepnhHG|$$HGMf$4wdMOiPXm9Hr6o4#!(^xV1hz`Kb|&yCQG z+M&NYs_67*R>0VkG%t`8Q_c zWURn!tg<}kI!5LvES~bIGz$4q6dC^OnfYzX4<6+^6(etdxsadGtXk*qNfq?@vLnSW z+&ZEx=NfKjU0YjE$PeB9k+O}7h+$2@_vL2uTHXTR9m{<@x`MwaS)VU_@|o>};jQe@ugm1Hc^(OuKxb z$*Xe9_d%Ta(xSrp^iy&(4MBEM6&^_GBUG8NV`*?f)kCXP)+hL<)?apM;lH*%bwho< zK6d(H=+QvfL7_5{B^g}MKS}Q2CCJ|Gj;DEL2rRJ+hWFB8)b=rvvYch@b7E|Y6}u1g zG`S6R%DznNHV^7d4V|4@QS+WuPi zexxC$Z(nG(S7HB6@$jYJv3XGEFpFQc-I+SOp_xCEd}NCTDNfro;;BIqsrp+=74cD>pNE0( zMn02o=OYcmHk};c4!+wCTI0M3e1B+iF?ToPyC#}Z=lfvSVF&sb3i~T{Q6|2>WD03u zN(&`c6$OQ%5L_iE zBuRqhe`7XI#%nQ~rWXt!ZH>-Pi2u4FY#)-~{*W`R-z>OEN#Kie$Gu+_~f$tN066Td733io@Kj{j-jhjCWSq{E6 z8iaq|$N27yX4Lu43O@Qeh$TT+l!@<7?}Q}a0aaB6XCs9U+#o3|<_-Z~Hi+8Pj1DW5 za7O?;yeY79Vo4AJ=%!`v@QWqEDM0soGkZp{Bsc?D^Vy~Ns&p3}4myMZ-#6*fJs*Ee z8Dg@1?0FFEO4!B1%^0^}4n#&z34ibn?1<8QNRa zH7svAwD$?C&{fM#>6(b5sl!z!DQ6dtr2mFoMI2i|FHWu4_`s%~XbFSTaz7<}t@+5Vw_NYwq zdN9fhDz!)-6qlc1Qfo@EKD_SNrY!Q>7?kDQP9N5_XUzq#5AcnW&CRg+Xav6Z4%D$u z0N<}IZd@G!{$|T(+V2M6xt_9p$HDi7OVeZN7);Z)J;zQ1-*|P`p#9)``>xPbJxo9F zYIp-D@O`)-?c`eUZPwHIbui<51e#IjTXue0r=QI0qfsWlP4~OeKEQN9RaL>wkU|G; zz7!U7R{^)2DU0)BUQYvToM2n6fcDr+xeUOnZjSP{I1Pc56gL3lgZ%0*WM01o_+jU^ z3ayl0zYVPL*>Gd6((CttpNwqYK$m&_#@Z+ueQ8nQb^6KNe2TnIkX?%<+)z)D?fPDz zeE@;xRNcS#zcCvpbzf%4x=pR#$0DzJJwpT z{-XO)vRx}G-zs@mrpSAfdM_G$&pWm=#u@w_$gO;NJNUjgz7Ml(A4!As2p*Mk9 zzruqk+1tR~b_!;FExA4YHC9?*7udzcYyTCRyegM}FG@yVT2xq{ zeoA)#2|B;N+30bhu=`I?vY97XEly>9f`4lLkw^OeYwJ@t)Yog{c7AKQMuPRJEP1ss zL3YiQ@Z@fSk`oC8B@gF``xYfT`en7tDnkuk!*0axi%{mNbEkW5hSD7RSB^XQ;)mjO zc=6D1D04>NDzAD#X)dpC-uJeuz@Mqp$bBc2nPW7#>p)C@vtw}3I`aa>cAwNHo1o0r zt$cLXGG$&vGYxA@&9OaOtT?M#*7+WiK&3r7cLQZw-5c5pNstXFs!J4|s3%coqJTtU zi2{-&!PCDn8zNlh-u{5(&OUkJXl+!scl2jB5O2Rlv$f8|e} zTJHznzIF3u7s2-!na6E6@Hcde)urX&`-zG3B0uo`WBBKRW|)3`{cqZ#;Ctis2dP`Z zcb#|Hg{K(b8E8hG@0;$uhHYg@a0_MP+hn?s1TO(qRR#A-3LUu5QdrFOGP@ufGuPNu zMnn1%t`Fdy$nh6@vLqM)_&zDmeiKWAL4XEFzHX?*lE4no#p9l0gfa<+0Ea{m{&5L^ zOap#L;J~xlWouaybVkecrA5V|KKgkJ#`l>f9O@%DLQhj1(i8ksuRCWC_}5;iZm6%h z$mpZ3Cz98b1P<6eDuTIbYGQ{z*vu2G&Ad;?_1@Tk&b6D2Q%-5{4UHDeiGbKne{NH- z9pb64cOa}?onMMu$$9Z4HVKYL%IC^}K{mCUV@lbkC?nU>GNLNK>(kKck3 zbtFneRF0?#Q7fV*B<8OCH)i8xTobdo+~o5)W4PB|d&{wcWh=b%5v_t8|zx4kQ#?G#u;IB{f#@}v(?;ABv#jXb5jo;Uv+#b_^t}>N# z2H%+;zjAhg?|WNAP0upEAEOy{z76Lt;U6(`KSP=LHoYU5`!%4diffsq(1H6Zg~i;^ zITvL8C!3Av#mwyp*txS!Y#t5DOSw^i@2d9ieUX{l3DDOts`agk!g0NEfc4K>Epu0z z+Zp&&ugMPXN^`paw_MTj=Rjs|3$#pMT2yT2>1QwD4EI?Y;S*$AeOzGUBS7Is>iO|B z!l&xcQ7Y>b{8Q`u*BJb-txw%hU$3UetL8?s%{-MQ*9#DoJkElkWHbL83XjXu_J_zKbM)i~P6GrZtG`bIx;Ac>+^aDLmmUDHYSl7xs3rSEd z32L_c>f#E%yJ$|bJqf;Z=d@gcVxlPiq;2) zwdnEtSrTLe&iIk+;G;}}XTWz1r`)ZnOoANX0o!B+)mRb?PrM+bFD)vPfPS(Qe36s{ z1lj9rpHmVLd}imjYi2d!f<%IIkExP?;GZVJO>zcGmi(+3v~}d5^$vRhB}TrfX}>nvCh)ioIKvJS)g_8f)RQPP zQ9z=wL;*>XK>jyo<7C_yvstG%vE^)R^b@}N?3jflNS$=&UdzHOlmz`zK0HzOwPi|v z!iU6t&+8xwe!S_}bzCvZa;}F~w9vIHU4->UYLExL`*L=Ug`0k5l)cLmjr2TaqO9ESziSMN{7fJ$0Kvh-24VOX(&P57~tnUE+ zzg#(_yeUg^ZKCALp%0jeW>$)B42zRIz}QQjc8*|i@)OW)@0ulgI3zfI(*M|$YaT474Llq|k|1?fK*Es&`IH7K+izB$E5AQ&6k|Z#6 zx-UH$>j51rq^X&ygnO*=TSdzPZa?xKu}qU+XtQa{F$h?@*@W1`5M;}Q16S526)6HO zp3S`l0ry!P_s|uB46x*WY&l+$pL2S)p*IBV_v7?-y0oap+M z*VxYltk*hP_Qqp%)dT%B_~WxXy`{iVNmR~NLz!0S$?ig6Gy@d%Bg#rtj3^{gBBFFe ziAVyY#ow5XlW}KS_WI$zz8D*vI9$K&bOc6egY7}LB2p8h%?cqfx{QsM-Mij%oE`Z7_3+89VDMeMHNVOl@aK^=@A7K! z-FN%d&=e((aN*EPmP%f^&U zs~y6;?mH%0MqgS~c%6Q#t^@QIAbW9@a2+yLCD$PnJl?aSc>I9ipL)Id!$$ww>(mYP z^?G6N9q+wt=s;!3u|k5X6Db)I{*KaE!EqsCIVz)fZE&aj5lF6A7s|^{4p5F7-zo271rOpv1f9XwU^2I{?tm^R&SHb z`3Zq_w5DBy^%Z6#YTx%oSrW#+~?Ev3;=hknV2EMnQk~bNN>4&-6+cf~+PW^1} zo&eu{Pn*~zGQL-$8FjuboNu_@XV%|vsY^)8Ft* zd!_Ze0Pkq@Y3%}L{m77L8GUI{VSV~3*=r!k4un0U0|o@|Z&7)j;GcT^UDc-l+UwK} z^%eQ#n?w0C=5;Dd4j2$rT_BMrP$D^CKvl_Bf6vuu+2CH^jK^H4$ZzNsJ^uitxZ>HO z{7^{i{O3_;PMMb~9z9$XMN&-cwxs`jNNZ(C#MJZ8W&AcLoks4EqTxwH$HkbwUd+=W zV^@?bUVcfR7y>D}B#kXN#-w->&1B2&FF3cX0>3;YMeiZ3uM!(>KSr6>Z`a;}^{)Vm zauQW03P{wIs2EX6qGBZ0Px~9QaWZ~@*~Ip<9qQ9o?$U6fT@Lv6DBJO53;4TR;Q#s}_+E1`KG+3(Pk8?;k1>{! zthD|e;2jTF80F%RX@s8zEGw$AWgxTu+k$8reQ8l)efn8fxJfaB4j2$**9Eo zkJl!s{alp<1phP%j0d*(*GWL#P+zY%yLSE9powt6fXb4sKEYYt>5xG-ZRV%cyeRAa zBqMKuql_Pgoh{Oy*{W(?!l9*s6RS7*F||zb&2sB~(w^a#5A&8lOGajADm`DU#VaE3 zx0np=%?yffyAsoXU-0pm^H>f3(WjApPeXgxK5P3c&q*ynGbZNW_hgx9@?8=iZzZp* zYVt>Kwy8uP~h_VtDBMM2Bh$tOVA`-9f`5UuwGCq#k*i>x4(+k`2yZaj6 z91X9Zu?y{gZgdKHJp|=f=24lC;dO&8Yridr*B1n}JKAV0%5rXMch3309 zSEI1f9PoWwYxt>M;9K!xry&lV@JB|jnfVQTPke7__5pnV?BIG}7x?~i!?Dd9@crrK z`SNk#+qbNT7M(L}R=huZI`|Gs-Qj%}e1~mW8J)_!-UQ94^F5};uNOAV>#a~GzBPjd zuXhGiRTZ3E3LUrsQdrF02W&X{$(=RK>sf%iPuBIbXI{?+e7q!9Vr7|Hjt;+UwK}_4R6WaLVd&%i{To?T-2VBB8Wlm&b)C2bU}Q zzF%~Nl-X$E`5vpFw7yz4nYOhn@wZZ1ZuX33%f zAHtY2j$!jN+apUp^*0m88T4GLjTq>-9ehtM89WP@?ea?tEsT=D z_f4H;XTE@M8>1(+>2ltO`^}F!fbVRRHAhB)Z};k&4{#!pw?8g(0*bo8$PmIPFmZ1oAUXUE_$Uz$LPWc*K6$&COT!m*lj+MKo8sKr-$shdH{ zd=YY_`9&zr@XfSFm#1s+c9x3fc~Iu-wmp*9LuoCzii!*8EAeCc_pa{*Wj5KA^NOw` z3ew@jdhMvdAKABH0Vy+UXkInt39S8S=F-ix_YON&|k13-?ftn% z+b!U`|JvjfT-3{3Tj-6y1iouOZT9v%_+B#9tQlSG`>K6Pd>r^*nybCn5qxi)R$-|( zrVn^BWv?ChZt$eG;|1_NYyKUt>nsUM(2P3Y*MciM1+yeD&S4AHD_%%~27qZ|Rlzj^ zR88!_wU@$T?jm64A8qX(vm}TGJd)aQ!%NzXmvYH~TBZhvZn7k}1US?5{steG1XlsK zOq?mpRVKkT;MFnZr54I0$OJy(KCpTwO9FHBg1*Wmpr4W_m=H9pM0WuRNkCBYP$Yu( z*HlSB@K2M#cV?%5odnbk_4V3er{(;clmtl}mD$k{;RruL<_F;j|7VRD*@5bYqxv?l z#GkIQC`iy=x|?4dwB(q0zSBdl0&l0~=kx>Gt2^QAY=3B}Ab$Fe+e5VZ2%{MW!=SxK zHwzthVEWK$RcE`HYx2V@F1#W^6N_mP(qe6`A;kePKqVp>9ca3_Nlh;*pl5-r& zv_dOt3tn#sDC$R)m8cj|NTNhU>4*}Mc)ju8n2nRMIcDSj?ySKtcs&Vkei{U?ul~5S zYw`L-@_I*&50VvZPj_^KHQQ z!Xu;FZGzWx>b>cYV1K)ES zdl}Lx#8h%=T8^iU|u({_@8`lE3NwC2J?DNl!@;JW>aXZUk^}K zRdA+K=)kp+!eTBQFr%aWVi~!)ggXz|+As6-Y3B84z`~-+X}Qenv4C;9&t8vZUQYu2 z-07iCq0;Lqz~9#|F)79$)4u*y;F#KPn}#s2_Xk<@rA5V7pMJ7~Si;2t1lhhm4)gg4 zRd!-rc+v<}-Hf%w@jt;o^}6$MtAFiv>V~?H(sWlv%gls*eJV2ptWv=G1le{S*Gs1f zkf@{&#{X1hJ4{FDNPv+Y=(<^ptP-rtzTyx##X#EcVH2e z*?g7vq@7UO!Il%dWaMh|y{fP1HU!Fy>uObDFQ#v~VHX}XqRC(H`SBwu^Vo)xmCAEZ zW@x5?S5%EN8)dv#H;?I$kpwF3$+^}j)AFV33Q1rCD5^^oov0^KW}<*ZVTl5gBtg%= zF&igiJItoi$L3!mv01-V!J=J%Btd!1`>KWx36uo(D1TXCHsS%2;QrFe{VE{|vNhhx zzB-~T=Q_=2T{}}*NP=$5Vq`my-|TA+zWc=I4BG&{z4p)fbQ1iHFFW0l_`dqA*{(A1 zJ+wjfP5Af3ud^O>xDCGJ8|_jI1m9Z^1m4FvK>p&Dhz2vkw@t4{%i_WJ?PdX|Z?PnB zMKkJrzw6ZBvXCW#JIcg&)J7o*<^Zay3T~bhI&iC{u$a?c9wS@PcDQXTmIS(hDTmkP zE@4Sv2zc0OiM=+wj`RA}0Ovhwn_|t9peA75)j317=oMJF{m&SwNzmYB*MFS^ z)D89ZI;{D~`IeLfNdiNv=P{=VP%_}BKW1+s4JGTh-iK6)XxY%t8CGuY97j?-xpn8v zOORHuo{qssUXxGlf2fS4*p7=WfyEO$E;ZNB^X2&1jn$5k6!QxjjXsF!OYc@G+Ay^u zuQ)yI9ZB)t<0r<-b5GW2X40yvU#>UT;^!UxaEGj~5*u!mN14{|HUq)>V*o`ti7FEX zBBD z{De%?ZI&O)D)SS|jU1v*qAch7U1DAHG8C-8|3-|=WlPGP{@{DifZ$+X@O@g#ZafZ= z@W-sKyM6%Qr|M2NtcYjLw%Sp#G95bEKj}xxckq3F@ax<@;QOch_FQ80(|N16aKM_z>RdC5t=)h%4VKFx( z6I+%aA$9DS^&J59ZoW8T$E-gRaMe+rYo^TlqXBi-jV@@wtUn%5yW_CKhDz&C0FK!G zqQ-Wm^<9C}j{WqS%&fmPBSuDFT2xq{eySdw>@7fcOVCRi1W zr|O?te~5|VUt6ELp}t=0x&JB zn}9cOLW+8M!7HvnS|=MiC4P9K$s2W;KbxdDFL!s-AV@2C(8_v0n&|L#U4IVl3n^Oa z9U5>1)4%?N8|QBI=DL;;Dq5)~sVNmPu)`aXYSHcrMHF`My=v#!*Jx3%YWPqTsb3omp! zSE*4fS$`AC&Tsazc;~`_W6@u@wg(>%XfbSE# z+S$>$L0A2&8~20nH&aLJUjp9~zC4<6AJgOEZ7tD^I^RW>2?P5w>$gFf_^#*dOymFd zfQ4dJAwbo{4qRtcRj`8@chP=-nuBQKOcDLZPQb|nf1f!#>(hRiwf)0Pstlx2p-4dkJs72 z>pntNa)%IAZ)#Q&$NvQX*!oK}|F!k08|v%z^}_F)x3aB1mERVh_@eSFR7s)^|Lnv=i=L2T+R%M(=!&4_9o`QO3X<_x0%lDkDIQ(*Ws&k!)FL#q zVq2oYP3KB{TyE8EWPO#KkTQPw`Y`&l@wfAvyG*JxP3sA!9eT?EQ< zZk;phnzpfE{b|!;WeuvWZQT=mk9A#td?omGr z)dKY0xFul_vwm&BM^WVk?<)wW`Rf6mw_P*OOlf^nU}w2yQD>#~n*cvKdON5Yvwr5( zSQ&k3QDJ@h$qwX&)2Tm#cj)aba^dAo1c%UV0V@+}t55Lr5S8@_{;Bm3Mrr+P>r*$> z*K66{Y6Y=ut50QS0AbgkAbS^+@D}ag)x%`{z_qcmyxC_)_v@&`4{DsLu?kXj|JbKx z2Bfun$eQI}tIPO9k9Qs?DaLwqIurtF-B__UMQf}sfAGkUK?+E5nO(avr!l>k^SJk? zyKC`3$HsjpDO$hX@1;EV6pCgXzQ5~!ucQ)x>csGmWPO#`C5eiWSpUY~n2nS1Bg`iC@b`=n@OH^cJTL>+-xCtrKHWZ=tp5aM;}eez zY_8+F-Uc4+gJJ!5+~65n4k*hxkJGGcnRNy0`(B8ZeOcb*K~M1A_|)Ce%fYvP)Dj~c z6X7jZ_WYIyzMZYAH>d)>>l`kNjsf3~b`8Ix1HLnt$f>+PQRDiVBG z)@`qw2EGI9x@~&ItiK!0sPjF>zjUD=v;F~;iSM&*C(u^^D4?pU;Eqe70~aNQIM){q zc}-5cb%t4gBjBF(e$Q?*>u&`tXg%QN1ZMs1fH#|DN8V)C-wk-z_LHKW()xkG-x{6m zt*^9x5OA>e=;nIN`iG)oW%Q**h4twtdyoxo|MM0gUC`h4nQ(;g)B~M!WW}*;b#*&4k+=kcMdjLy~=csZ|-2}*csOE*PyA6 zMR^oizZm7jW8cfJ!1@9Ht?W0#`gy@!Z3k&wAnR`_VO`s0Dp)_OQk?AJMD4L>!1wU{ zv+b6G?+?$LoK66LvH24^6W^5|UWu*-zAbWBbjQCZ4!p2`%o6Zjyxt+bGx(0HZnTI_ z2Da%}XxSEgpPe;zSUULLn{6}y3A6r3G^5V4#381Q~;L4=X zfiuvSREw;a0RH!Tfd1pPDVG21JwRJAlNWW%Z>6*R*a5ibt50eu%a1*P2Irk+^H_ca z0=~(+yzBzYk08LV5f=5Vl=*Q8xKDkjUa#@Tbk^WFu+yC9Tpmqcl`}1#LJ-ax5LA3pvvH@AwSLmigFTFCJIQ@m8cj|NupvT z`4RCqX5(ah3A1_BBWC$L1jP95ImbF6KQ8vYe*V<;NXm~?lqbKv7SJ~%KVfsPm>@6Y z$Nh+YD^6yhEa$!sU|k#ESjdkY$2gn_fB0h>_|D%v!DI>euGR4C^T){g}&*yO*^Mrr+c;G$JIHt|a9rvP8Pmv!(y zvwjV~>;iU<9e(T=>H zBv9fg+z5qdD`W^zbx6g^Ieb=}tV{O%p>~`e|8j-P6cSsXm9on?pv?PrO-QWxUW;E~ z{C*yZ&34(V$+U}_wxnStGjm)LTYX3hiOp?<^=7(KsOFQYb01dK=KF-)y+vXxyxH}j z@|@IVG;><7a<%t2IlfZihKFQsm44*hb(Coh_B0dB{Sr_VjHn|~BBF9cO^8|%H6bzg z>%TD@C*yCJO>mjnl_HosZS06Q<}ml1_O5q|eIv-+KTzIXI;eXR%&mK<{M{s&+fFB| z>9chx%Q^kstZU7h3Fg*56en}JbKYwp_gph@;E;bH(iH4BEi zF>@yZ*6{DYVGlER3gGq6vm7=ub6*9FY-hZpztY^-fPGx;P4+0woeBIYUB@h*ncE>a zPDWo^RBYGjCo{Kjhkk-t<{zI+=rvWNtybK59`w&>wASo)$SQMFZMxuFDbL`)sOn|nBKxz`^EQA zZT`jpv*)DDebYRD-eJmYhh~cRc!!lv*Wq6_eA?hCl0cY_Swuu85cUdWnKHyQb>Y_c^G5|eDxdyzF%KyGH?O-ZfMh` z1&*Zf4ihKLA-;dcjqou6-v$wy53Yj0Je!t-dGI|k$6|C_@LhYeUoSd^SfTQsA;sW( z&ZEhjZh`Ophi)XiV0?c-GwOWXE!yU!Rpyk4h5CXr@mu$nc%%sWJ9u<-&>rk8=1bk4|;ItEqlOurh6(?H_bw#y| zI|itm>L7DwadHx{P5WQnEu z02VLJ&^!84{}C_rbB=J_L5LTE?3!ZX!a{=Vak?pV#F1d{2da1>_^0vWnfuS^*}Q(hZ%Tn_^iXHUNss;nW9p$oEv~LE%u$( zEK>kQiHXV+MI~xYRFSAIQ8l8P@W$2&e`7Yt6wGG!td=$tM}A4LJliy*Qq@>cp!eWbXq^3cOXG^5UU%jrHdOA75n$me$8K3vE#qncHY&LLvlYvf z+JKMdXO_(yDiboLF7S`9PLBhWnPLk3v7y(?GO8m}8Uokw|2oElWy&t=co}`E|Hu^j zDH*a5WXJ7p+!Aq#awT`cvU==9pcGKI=SmPLmS z;!C0FpCtD*5oAw;6Rv3_C^^_kkX;FOf)Z!)n0T37Gp6C_O}GGLysM4coDd>vx+7!NDpPd4wqz9LTD z>H4krB?mMpi<*q9Bq(tfp_y+zv+tA-*X1?6>#d^1QE6PxtwEVOwYR;HI0pbl0gAd5 zB_}FT)R?F}QB$JUkT}7AV>V94XE2*_Ga?N2s=rTI->zW|Q{0Uq&x-pwXI3~R&RLY5 zmE~2+@}1ktvYcDHl67sVg^)P&{o-Xhxy5%!fbVf_j>OCZ->;26>P3UUrF=%RG5DT7 z`k_H1@O@lwcpFOiaINbe{lIs6gM^FC!S~ExuFiCdv$@m0u{z*8Yw$Pyd*C~Ggv)c~ zsBs;dQRln8>4QmDEOGo%CcgLBj-~yX-GHj9g4-j74qS*77FoC2^nXd5PV(O`bTw~l z^*`S`FL~e*kC|M4Q>pXC1=vuQa6JL7-IG>~V~H~WaNUlv7h)HpTE-0mbTj^<^-e=L zPihaCQ8H`wn?+>_G>UNqo@{i%=A1HdMgqrN9sT{?V$_j1qkt#sU47DxB~IkVco}`E z|41DADS0^~LH3?OA#n(#0%r$>h^4ai~l!q+hQrj$-JaLU0YmL_-`S!NU@iQ_xh{Q6eb0Y`RHE zyzE@xRUO7Xsm$lBD1AthzjpE5M!KMNB=lD}T}RY$skV$1}`8-ukB zc>DRa9+KoEU9H;SCMy1RgjsBrHyl6i@W9q2`2joZ4&qP>MNB6&v+uxUi%LgydEbnA z!4xqnQOh}Nlxg`Ubrd4T9#B-AC`3_XqVz;jiDDB)B#H|W${X?Ik)u|>snt+A!2+VL$hsGRUZw$ zPrO-LX)gHI@iR@pW6=5L$A>4>2j2yzZMHT6-y8dTX$FEn+n?{Z*@N%;P2U?f1>Zld z4v)vP*7(n!vDP)f_ssD-1Mh=xos?HIlvl0nMlm zFyQe1VVHi}x37z9*U{l$T~9khk}v*jl5>DX%sDhuyU|`x-G{n-X_pfb6fr6l%eh#T zsTZxRgot?vC@M}AqNp)ZdZMUAv56uQ#f6A@{5NLfWc(hpX*&B$fliHw3F-IZ-|0Ah zQ&cn^6#8*>7)8uSl$$BbsmgLt9c5Y09XCx7x>lu&5HTlPB*@lJUFAFme79Qc={y^J zug<)GZ4LNqyUHkt_zur1dfOCy?-~|)fF6Cdrp0rQk>FeRbN0%{;9IN4x`hKUeT!Zm zVfDfHmH}>hS>QXbi4{k8av;*<(2P3Y0dG3>b!8Egf->>F!DJkbV$uOsRRxzJg$~?f zDJ<`&d3g%vy}so&A@9v&NNI^ro$Fsw;A6JUa@re(mX*%Us`me1O1fj@(?T#?#vbj zAOs~xX$jUa)Dd@i2>xk0Bs%B)>vW)QsITX~Nuv(uP&$MN46&oMTj`!Hnwq%N&=3Y6 zzai+%5UP@kIfD8m$exDH8Zfq(KCkP0dNwI_TK%XgG=5%@uCbx98OLwQu__{^wtZpS z!yU?dduePP|5q||}V>D9+!`Xw92>@gjz!+Q=tT91^f(Xz%#Jm-;=8jfaW zO!alr)7Rsl^m%)Ql0l_KITwvGE%3LlLNeR{6xAk*P}G+wJ5f-g&_n@=!a_3K`Wv%x zGS0?qG7efyS&C$6*nRp$4J5-l1LMbQr<|c=c!hGNvTUL(7nRpyWjy442J6~`?m{x8 zdnL$nm#6qRf$thUi!(jJcgQ{Gdvqg)<@$adi0^k5ZA@E$@6Rm`-^Ii467AOyyf+$r zH>%ayxFPu7P;1@_2TZ?r>&EvU-$}FGyVJ!s;QJ|>QRln1_e=LhEE!&- zOnmFF5|ZH)psK3izDS`1r{OKB7Fl}%{?{Wa7VUrU-?VRQsYL(%fvy`dlQoS@ZS(DN zXz;NKFihvfjXD@V;5yJ9fW1QEH=MFZwT#;ds9956->KX_5pRIp3usoJeffk#jxhMx z2Yk4AL#6M^!AB7ABcEgECJjR!gO5YN4KGxF*@4ANb@YzD)PKYa{ggcPks#ZS3h_cv za{D*Ij^kAELhw)H4Rx_hb(8s)vcU(HiL4*xOWEKfL?BIay$4Mpc{T(= z$ykISyVXv3g!Jw02{PNlc7fx@>GK{@m_P>~bh2jv>kml;!)%@{BIZvYeB}vaTJl z5fbOiWo%uWpZYc$eA_l!Gr$9U%dI``wFKXnwhb+93cgRC&NpubzVogmqV06rC~3a%-jYGMbjlN1(p4*~q2iPOGq`~L_W5&ieTNx(e(n{|vE_svp) zgt__~CLmI70A^mg8)zKfT|xUVcYosq?5}hLh4iHkATsDDlY10hPfD<17@e~aB7@+{ z#A`vlBZWgE1RYPQB7@+cMn;2&KmT=PP&d@w)e!5kMl<2W4wZ?l3)ioA7xq^|1ePQR zVZ|wgK}v>DW&3n4$A?d4@%rJC)Waj_a{Hu>(j z>r%~bx0+x=nr$#4{hXR+ucDa*qxi0r5l_N*Kcb9K$q<*AqD;M5*;B}fcYtC>h*ACVlD;Hz5D5# zZ&Esuztet0@^>bn)AJ5DJX>@V{QclJCV$%*CCcbajl?z8NjWGWB3!U%}r!07ZX`QWE{G#43M_ViNtW#N_W@ ze`7XI#zSb~PCtmA`P?_&@RP@*!z+Kq`{)MsvGvxJ1xKX=@sf=yDc_^{B1Lm zb*){0!QX8rCd#Y=^~Vt3a|R{)65qLjM~dsi-yzv?X2kdU#>J!*{c@v(_PySY*8FjuF#Oif9#{AtI zWm?v|KLmf<0;;MCZm1MGa1*7lnEM8pV$-Mf{iJT>@8aK({4JXVd98cYJ#tSE!QXnn zG5LGughUyAsd4z5eo7wpOpra#RJg{IAiHcsc=iLqP5pGmBMJon)Zbhy(|_%6>W2E7 z%6{whiYI@E2nTdQqk z9(h}(COJ16Wm-O?fr7U^0Yz_%G7`P5#42x#LK3~L#N_SSe`7XI#>;8p9_$P=_3)2( zsbY~hwQ70%xe~6ue}}E)?Ul-9r{xzvg=K z1o$pkQ`wsMK4v-fiV3_u=9|`4;=5)V*Samdy)yIi15J3 z{4x+uPqMOx|I@O6JvOIqsIRHP564yS!@Nyp$u*q>_kTHtyWsJJS3KMSki7#^c&(1u7jdFY{64oENe^-y3@Dme)QxCnC03bPRE}t7B_=c5 z|Bcx=89UR$RjBzcx{rVS&9>c3buX92Tf|T5cDs^b=84K>SL#Ff-zJwzn{0dpGtd0a zx^~GPU9)ojRtotB%yJ(NzMp?+{$M)HTzyzfc5Rq>PF$nO#CN*il}zHh=Gi$(S}JQ0g1jqjs4ad&GIJ+DuVYm^+zhl4 zHq@PeV>0t8%$mN`ILu5x11~kezI71oXcNSnm+)-Hbb4F^LAIlPj!p~`OwUo7nc$yp zsI3l`|7$Z-H`LdZe(Xz)fy~TQW`VYf4*e5kgeB2+2LvSt;s{D!Hn zpR4vtspX+ERcgZZKPc1cKJFlRdn2IeZBa&|x0P7sZBa;~x0RT@{a0q=Wb981=N5JQ zOufzV)mw~rbe~!pzfrYUMv=EI z0ky=cLV&7?9k{Njs$ena4;V0Hql0Hm7xMPD-;lh$6L40_n|i|sGH(a`#^mjL1CwO* zrN-fH`pGubcv+CQ0EJ^{i}7Y+oaIOLhlQRv>L&Q7X3o2O2afu=qqm6Nu|q zp4k$qxE5D898cn!#$6mK71x2eRb?cuieddnsfjBP&4fI7^Hd*ZPBqM^PG(jKM9v*T znU>FUgka`yK+(*iZbUOHvC7P%azryLF`4!D`9Ocit<~T|)v)dl&;0sv;(J)%$(7r~%$E!9SY>8WIii`Bn9Q8_H)i8x zTt*AmYJgL(hMVH2`&9XPdtphuZOrV26V3=`E>|u)Ex-6Fw@D8yYA={s;~DFk$ymY6 z?(eWR5{9`rfN!HUnqls=Wmeo@Qx#^8=(N(7_#Wh2;V|)C@ybYJ1DJDloZ&<=^M{LN zb%^iQsW~4G!_37UtOs@m-;Lu+4W7cx)dC)CE@Eb0fM(SBmU)LXPF9*3Wm?uzS%R6@ z0II4AZoL#baJ!_in3KIvlJ&mlb$Rp`Ic=GBenT>|0pPY%dFKXS;e}Cmjo+BeeEDsX zjK0)3%uGL-RL|3vnIL;A8lDZ}BS7}1bqq0A3h>npm6>VcKQ(iE#f^V$X6lCenyP4O zU2hySGnFN~&;*4SNbSIrlF|f9B%^MsO0M=@qm?Y%GtIF9X)WJ=bc|GMhA)=ukk(o` zI-QYf?YUc(`lPkAH6xlzwKn`&H*M0I=DOi^)U>uA%@}nl97f*Oym6!zd0V9>ycz*z zTHPAs1#h1R6um9VNc6T6tGq1=N%Xc7leZ)P#%!F76KUag-@3c_uwT4)X0Q z>(({yH%;(%lDO zqpm%Mhxw*{F5eo1?-5ON<>v7Ahruo>hVbgtJok9w``&@!tBv99KGqKv!SME$2MzmJ zf$t|Zx6UBG3r*jKE@9qYhi26IzO^=K!4>B1^(fPlep5KnsCy%zs;c-;h-aortHoR- z{cY5Q#a@d9Z(sNg$=lI@PY=)f=(w19JLWegZw~^bFEtKt(@%DH%Wm>E!4AR)=c;`K zsJh#3r2yUQRTc-~H1VH$+j#M@+b^nDt)ey5Ata13Otw zF@jfz_k2}*3i$rCPVu!CyuEFNR^S16`^JKK)^hM29@Z$G_&!xB#(o*|b_$wN=i74F z)THao+m}(MWo@J9NZ!5zsH!Ud6FP9$rPX4t1n?B!Qp<-Eyj}JilDBKFPL`eZoT&fJ zoO!$UZ%p1EgQ@9DjlguG3VJ*F3X)II`KU9_@NfQ#K#-lmEF)Y}CY?*40U zQ#aJtl-97Cb*7QGlY~yQ4K?B}Lx9ZN0p#8Nli}4 z?H@|jRMo#{7PDtVh>aAW*C%M+jH=@rM@ zv~#LzAGVoxp^cTxPJ$FaO|#qf;S*2Ombr5p>snto!M$DXB+Kl>)~y}_zF)s>x10Em zY?^&Y2kwTLZAN=G>5`PZh$byY6pH?)AByETbzll2JER zC9fvzk(VsXtNWoBX>ItFf z@WzP@n@eQVMTj9TTyNYR!*cz`#gklyG!jvS@{~R*7!nx z2M%AX!u&qm;bzqe!0o}k4}P?Q{9br_(MQbhv1j_sPykmaZ~t`-^Lt@ZXnG~!_Q_k% zCa(o9Qdr2L##_k- zH-wS}CkTa2{FK`W_g64tt!{+H<+e`e9i`1}Oonzz%~meII7Z+$nk5TP5O$(!_yAko z2r(=11NAmSv76!&9PXYdE3@HpPxQ5hZ)`e9eQm%~r~T+_y*t|ckowyAdei5lul08S z^+f7x8DU>CupU_wS2$10*P`JubH^L`A-8*nH13Yv7QG2xKn!M#U-B@@?bQGox0xF; zZmY4#ZRSXf+iHy5URx5u1S;Y&a^E-IslIQ10@uCCT6u$lgzV3DMMgVgvEJUJjyuMm zeclf5%->6Z_2x=$VwjM$bt5RZ4Mrr&yi|sVIzfJO`=VYC0&XYYy0=~i+};tpcn#+F zs8P$uH3M$A z@rT(0x8?8{?fkyfCI0(kf!h_qjB(X%-3?paRRD@s)qg^N&QfYE-@*%cQ!~dOJpgk=uucC(7``hXc3qRvg}mrZ5**Q_Q`Et!}i6o7bjO zc&nSpZL}7b+lqzprOj!zwYd;#E>x%y#S7?{dJzVmq6x@8jNJVdNxsp z7d{-wjJHA)^Eh^)5$Xb-RMcpeG{O;{9gXLI!ZPoxG{Z0}@dFh#T19Pi310FjQPy^T?M3Ko8~6TMEA_Q7 zuTVYoHQkMyjikO-bmg84`dXp2$7QLnRhw1i2>M!I#Y?4@uf@S*{MI$QYXID~vwSoJ zxh;B=lG_7jj9=9;l-oQ&#%<8_6bx=A!?pQ0$Yw-_YJ0~3@d813R60i+Xzj*h}=e4TyE#;9V~5bV=}Z$>P)41(X)h#8qGE6F08vq zW`vT88lhz4_}=Rjg@a;MO_He7qQT3=++{Fh`6fkEGCu~$$jtnPky(vJ zGBeL%WL9G&^V5=bqEDmRl*}L1amVkV4ljcBX z@7Ox-RzOaxhL@@hg8aU9{lP&CAoGjgRW2=t-?#2>dDtEDyLH*B4>7-k`tGQ|NFehg zc#L*_uP9GOyc5Wr1!jz^?>I_klfWdIXjO4$Qs~dsk-|bQ4q%u2o16kSIbo}Nj|L){ z4+1RHdBMwmo&uRqYA}-77#@rlJ{-u5x8i7aG=*d6Db#ed46Tw=sSq|M#;iw;u()LI z(e6lTlNpntT~ciVo<5o{RMcpe^r#W;SchwAp-1f!oEnuRi|Kdpwl{dwA)_6irQWo8 zoxx!ACM(a^Rixgu-(YAavNyUBe_HBIsUDZ3(3{@&*L|+#P0!#lg*&2pBYQXYxH|>e zEBcF)dktnR(BTs)dv(WZ*vlM+u~&^n_A*yt>{VlAZ`qOvCQxAp!RW-PRIMJ*O>m5z zu;+BdkA%Knx)xR97GR&*9L-vvX-mJXvc9$l`^@_`2j#f7=}M+qIzg z3e4|!O=AoTfsI?AoeRMHcE0jqDdso1vwvw_U}N;UsG-Q-zAdcmF~4(9#zw@#@27iv zFH}K(2XcpOvw*$6+nY{;gM6?mehZJ$&hJS}0~DVG_LkWtL`s%L*{csww5m8mDfH*6 zNnwH85`h2xCTs_L2S>}ukkH1X8Z;^7wm}#T`|NX@Zv9RLr#{33>{xi%p!|F%JoRC} z#)_vt90ceiSPAIEF@V!{bZ{$rm#e~4?M?t*cBaP*n-*;eZrMJgvC~r@&H-K_*zw4z z+K@ANVTpl$;H_k|9br9s_BY+)iBPg&4IzmY^#fsX^`ptmTcUfbh$-yXEWu2;9e zJbu8Su0F>TeR*w*$DPC1?9VNZQA#R6;EBlVrZ5 zU##r_64Ei?NDGvZs$b8pdITBzEUt#+bBUlztF+h`M&PvS)KXc z2OY*+FVZ8+58IEQ@Ig*Y8*G(@22+jjg~w=nNx;|2m5;^+p(b|&GsblGL8=kG0g6@? z7b1nQ7gP!hTshB6|9vx~iM^xb?A)3Vgy&S3nRR0>;@MJG06S}188#ZL3R)Qr0IHn< zTN(BMPwnt1GKQ0Iu$9pS@KQ-D!%<^b;n`BofYtR0wlYSwxg^62QxAfIw~|%{LP0^O zpdb|bFqd&9EyCpuO;|4lVQ~eeiSD`578Fc|wyO-fbT@jP&`UwHq?dwFcnd3C7LQPT zXRDG62oZ92=xoa45dc}ivhrp{sm3Z+cC1WUS*fuKcs!~kf(cZ_s3WJN6MPnnUq@%b z+2@VFJbQo2i2#qMi)O)y|7J0>lDj`!NLs78l*f@vF3EI%Pulmj5lm^$jEZ$>Xi9QD z^r{`w4dH*ucV%R_!r+Q=H+x$*Gt$CP*(Bp!03Z8eY4-rTbL5po^Lsm*R&;YM}u)V!3iKgV-inh@(GqwAYkstTEy5FE4k1wyc8V5> zimJY}2{q3X<2d`KM&v<< zS@qgBG9_6no%5XXg8AVgV}oyiL|mV>>6c3jGg9N=ip+PL1Nf&h3cuel_#l;tLGT!DxA-)CTK~Oms6<47 z8Dn}olS)JsK+&q=qNUKEn<<3_ZaDz|dx>af-$bdA2%W4;vYK7bY#Fcj1-k>~H4wW4 zMgY$rf9g3i;5!{NFagYZe>i4fuCdeZfdydJ(gTq=m;ua&3lj(;fw#i+-(j2_L?~>} ze2OB0aC22$T}t=GAWTUXMFL@QMPl*vgwn3fF&Wz4F!1}?q}_-A;FtlLF|+XV($57& z0>2VE05K>M2y4xJ?{~5$OfkT|H-O@?Z%S@!k?{9?EM@OafQ-GYkQsZ`SZt`XVrIps z#>n0~B@s-ZB1;`P9i7E$_Fi;tJ0&pGrhYiG_qk{m(vSaoFtd`|RyUbu&5Fg8y^HLV zWf$IBI4!Y+sX2cA;(m2aNzna^6Q*eA<}FlD!N=(NVG{P?N^fA{gcrAHd(yL2B?ASd^C^gFWW4Q1~Zc#L*= zz4)|xbep4;y}Q7S@%;6JviAT$(W>GONufV?K?)1pTpB0;3-&tLHnj$BB9)mF+yp(Fh3xG@`m@6@jP-BfosGW&9joP_T zBVLt6Fz{+mb>uLD!iRV5bgT26v5jeG{`+5M9i5KM3`vU=lBQZtHDcSuWSPgD_zgSY zt$+gqeHXQ>Xi9$VIe#;MeF%Rfr%}xfgd>YrEo*(Wml^SYw0+&+uibe|y?q_hl8s5F z>S3o2pM@8uw+wHj7~h4D9ns|aB|UxO-ZOq^Etxrqp3s-G3=G8qzvJ*2Z7;E2v$STT zRlTtja2Cv%6#dSAIN+BAP_(MJOH%01-I2lqH`SznrxEamKXJ~W3xqK!{psaCYhI&9 z1Zf~@L!EAOvL{FK3$|w%lKr0fH;?I=lIM$!TACDu z@C_DJv>xQik?LEY{Fpq#j96`J6|ruA4?eN_@Ym=TA-2Hz$3A_eHv#pk%!OkI^o^ul?-vdinK1vR(xHi!zh%pc zc9V`!?oQHR?N=4-*4u!d5x5Fn!>D=}6!YAjNb6%wPO z8Y2~T-jqNvfeJ$iMu<53cbcpBshlqRVyuvg#($Z0bUHAzlFK)~O#gb>I!eX&ip#Qk zm8`GiBpZ^0)!Gj=)HNkGvuZ{Gs%|wA+^2IeUp2IsB>4h&5OId5@lL7XR*}PmVecPjN6YCvn{p;)8X=u-^O)kI^oi zi5)wK?0ZS6D61kwDzR1|#!fXxcG{LiFo6nZb>uWtR2N+1 zWofk?_Jtrjm7+vzkkUR`AJQb{CO0IMX z(5cs&xjCsbsAL{c-hdO=j{wFDmFc=>e5I0+slik-vH`Oi0wkl+(aSQtFu5QZc-xe&bvc8QflxRE zm`Vo1%dn%ZRWLmf9ih)UQ8Ew~S29-rTv^(ZfyvPJjrSA1|2TV5$v`t^7Jk~F?1QIC z;8)@%)f5UP?QOSo;SUCKl)M1|Sz)p=X2qw*B6(Rkvhq@6ByV6z1QVzTS4U1$qw}tt zLJCZ8-GpJ|AjLq@EF>8J-N?)^5C2n0nwvf)uV2|KvZ4N=?)%0X62;R)CPpeAc%B*n9Ww&hT0b zy77J5-`P9ojy`cHI1%)wvN_rJU}b!r=ajsm@EGj^x*Q*Ka81`>B<~mVzOKfK%~hWcHR<*z+;ut^s~^1HU`rQt;rl3vL_`uhC-{I$m}8{$X6 zOO{3+Z|R$0M*bYQ@y@*mO zy07yU8D5wkAS&KUj(tEV9C1u{lOmMtCPkRyEN2aI`r~50i-1HAEN!An1Q`Lc(TKvhDyVTH&STQs~c}kir5t>&^d$tj+9|lBJzW2!rpK9=_## zK6aa1Yao)<10d68AZvSoI?;2NT8}8AwW_ZM(5UA@VJEp)@?jGa3LGv(FwTPuKL~yJh!id*;0{$xoSbBBQn$soJI7=6SWc^Fun! z85r+wKz3B@HF7r4v*FL1=dAt13D%|X80`}Ia$nKjw`K^ofhU3)6EffvrRNNQqE*Gs zl0v9UrLe%QLe9UVXVa#dG3V+KM!U9M2OX+KS7TXgAkwowK&Hk(Pdk9tzsCl)83l{8 zU@?}X22*-E0cPS1^xXF0iVQDIAJ7wTg~f*_u@Q{0GhI1Mholio-oc45@wP}$gvF(& z;>YmPrY9yt+ZmS4@_6obg3=Ssm|6Ild2tN(Sn(@7bG(c#jA|*l1pTY@7p9ddJs$#O z^kk*T%1ez!da{CJ1*FDE&u1kO3~ZiOM^3ZcD$zCj>E4PX+dxGXr1&VBX#(j#Sn+*Gd-G=k7F>yaX-ro1YmhqOmnoT0<8{-;u08lz$F5K2&ovzSiUa?$MF|)}xhN7CZ){c)BW;hdvWz#5|KUU zsthko9!LbRb%9BwUP)XP+wd!?Q@(^^)gA_q(Jrghp9%Z(CsW=I1~bOm z%J9Mj0aNi-GK__A7+rcr$D0vKPA^5cEmQ)QSbrC z#GUyL69qLEMS*z_^Aa^iQRq|>!2~LLs3WJDk~-qr^;P5LYbOPuCfaHF#cey^_guGf6SnKt$F#fL0;{A^ljtpM2ZCV8j zcrE7P$1dJ0`|?)0_T6n#jY+i)IY}`Irlhg?`l~;x1@ga)^V{c?GbBd*ggsjg&B>Eixp`!2>9;59R6J1{Pp0%Ee!h0}dY`-j~qVN%*XjO4JQs~d+NnwFoBkODbN)((V z-SOrS#=W+;bHAOTqTr%|C<-kBzRUdfdbHacT3x$qFck&FtPTKC7!2{l3ljvQfVVy9 zw8;Uiz7a0@h%efOcEe-}g$ZO>f-;@LxrP?3g^xcjt|-irO)PCuz+`Bb{)K(-I_buP zDD0+*mQ>&P>&o=hV)`~egqW510YN}W7v+49LqVw0ruhDA|G)XKlCy%xU<6Lqqk_;7 zAQJ@UH%t)JSQG^2Im|=U7zM$$B!UT4G*w3qBPe`Mx{j^2NH(BscN7GNzsx#1QOvC5 zOa}`|TWCWCq3!5vviwLNS%oPEB=f!gfxUA~i1kUG@c}!-_-U;#f2{e0BO5>d8QZOf zocRAV|Gr!n%n!|bv(5(gQiLab`T6dEDLLf-X7c^mK>o+Y{xel|42gx)u&VDkSe_l- zw^PhIDhQq7G1@M1uE)HS-|kXD@CP#{#o#9ugnj@;tBMPiLVs?k6c)H00{CxQ3DP<0 za}dTf*W7`_4?o6M!bJ_l=6oVRHXIB3a2a5Z;=dNimHs`mEx+cR5(*t^d zw*#pHz{+nJj{_*KcAQKh9;4bW>on>CS}z5PdVsLFdeGT(N@?o>CPTaMZJt(}T>cu> z12hZs%=2(k8sSz?Y!ckW<~%}4a~`3%AstTCSR!O}zXp`3Ljf|Pvhrjlr^X^tSrIa# zsxcBZq9lR|R7_Au4n0Bm9CAH2_s7MbW&Dt+lm0U6=p1EcCD-VrkThpoO4PL%ugM-? zm>yks0KD61+A7}`vrNdtuF3MQ*v|viq-S8OgvWocT z>z8K=3t*rd4rWY>#SJfP&YuD(T48yp6vFaQDJ*bPCjL93Hj(V3@PRP4S?+z-Y%`qJ z_lxrd$c9~jw*eX}^0o&+Cey&%UI44lI=l4SlMKq+ej1Fty?WuA3@=O`@D^_+TcQw3 z4njjHnWIMdc9+OogvI6U>ZhKi&09={wl56Y`P188zZ}-%XqL3(5ef|-x-t}@I4q~+ zR%Zw~YiLJ_dKe%pI98slsMJ^_Dl0QaR5eDT9xsVtU_x3QIV^hNv)}d2BBOG3Nhc&~ z@?T~homb4P2+EC3}uC=ZU*FovUT%!GfW8CS!>O6qj0|K$Aw)} z^Ep!Ho~u!aotzAN<500i9# z@>%W!)Vx5ma&j1n}45o(h-XRd)aXJk*1EsFFJXkHI23-h@&<2_U09^9<$# zYJ8p*I&%g_c{N7LUoMGY0u^`Ek;4cIpS`YK6TV-o8rT^r|KKk(^s1Rz$(`&fByGL} zrTl?D*JU@##r8bxX+Wx;7&WH~P<~!z-*0;y!}(?Lv)%>i>XCilqYtW@$;pWx{UYBj z3FhmsH`}*izcJ~zb<&fK3rtD0eCC*G@j?72mA-qs!G>g7!r3dgisYnFVRpNrF{L~Y zkI^pl+9w}0^X^Y6pA2S9O7MD0`4oVnRmG)Ap+EOb3Jcu4`ummA&d>mCXY8M zfbze%z5rQU3=|+#V?_lB2gq7xpa4SvzS(n2p_`pa6<`=(>47AX8awTSj{?kwTtE?i z_P#E|3zH9ZH{ME?s36p*gXUBq5Yi)&?dT3kgq1xjvOYM%;tIr%zCNWb5SR>YU#V%n zqw|@GwC+Z;*auIc875ZNF2VaJ6yKl6{crvZXOzQZsKYu^fp`p%ISlh7<|1k=wh5T8 zFdtB36o_Xf5lo=sojP(DLE*E@RX?zjvu6b=5IKLDb#(NYS;;-$DkQDB6BURvd#}sZ zZk4}3>S#bRTAl2=db$Z&8F66u@IK*uL~OH8e+>1=e(TiUBb9QJc<7?dzB9r6y35?a z%{z>V_Zd~C;Ay60Ns?z~g`yySsez~nQ2<#J5ENkoznI$%~kfC3mobn(LUL7RX=x|@rh zV1Q84Tt{fPOr$)*;!=L#7T?mQJSIcC^wYZgha2splt;7VL_vfC<>_$+2r=*Q1H*0z z#Uo6V+}*2!Ro{g&^%FqGR92v@=+szbDl0=)R%(n)%`1suV8hilP1J=1>~?){>Ey{j z*L<)lFY}jKN9P_h!%^$G!e3`7DO0lwuFJ|#SmiCNYe3w6mSv9vrhbY4adlC2IH}rZ zMfhQb9{Di!PGP7@PFk+2dSw5LVE+7J-@vXLjmhV?4`c(QP07?n-}3c+d-1o&cN|k@ znITEI)ZfGu4j3H!sK?UqGnA=0@EGl~+Md67w8?SG)I2a_Qr>5KBU66>6s;<*Knnf2 z@`Vy>f!hdx|NVGa6MLm(?e`=IBVhEaX19~UIf}R$8i-7t36KdhFm*1#%=qDTly*-j zQx|G5w$|H2Z1KYMK;4YDLhVZr3qvTJHw2A_$<*pWPqw^(<6&qWlqC`sVR4E2Cc8^% z6BU!8UHJDK)YCh1j}jHll72P9m2EIj;KgYvG)pA&*~cp1pgDWAC1qwBK*mf~fUKz0 zSY#$EGsa9cMrPhAiC_X1+3Lt)(F>m)u0hrBZEnbSKxV%9%dDf*gPE0Fn!Av+xo(u1 z<=fwo)pP6j;q$a|djVrNcGs5ChGp1YL(xxURL%Z~k3_1TgMphn&ywEH*n=eo(S&4>L zu@w!wio%7g?4zR8YzL50la(MVD>WATzpT(0HPslY*`XwY2~>1fM-G;nsCOyva6J`P z{%oD!?U9r@HxTE@WSeaLeiSGqSUlmbwhUEYvgLP3I?Rfu)7y+p#PhC+WE!c zrr~6D!`rDF?BEE^YEc^ow3m~SUEZ(S+iEnWrZYT7yKt_&^b2$>qSPc{#+dFt;(?WB5J1tY z;(AM=KNlf|1#T|^{u^q#NS2!XfH1!JIr64Hcd-9k2#}3;Kpk3UwP;1A$^fdp0Y|{} z06ra&+t9krBg#|*z|#J&sm6{>9li2~3@=PB)TwwoicT^e!#O5|!jdt%<{P2pNI!(j zCyB&GSX|x6?!rlC>!ZbY=ga?t zJNq+tR&uWJ7%V`p4b=xH$B?vI6}J@uga;PLW?Y+cLcTVj9elPZnZ&VCH~uykkL)^?`h zBt86bhn>#&$}RKvxgF(X-I|;hW*tNLGXwUuc7~Vy%(GCAkM3(q$np*4Z`SI~e_8tV zz3(MMLUg8VDSRgK)7)QA26MXQPn zlR|%Pv=kP&y$1NN^g%K{_7lSJoc_Fa2gBQ_4}So%`T+Dn_DZy(K9mQ@Y6s82!sLQJ;H_k1G(yRKON1G|xJQI8DMfhTx~LEI z$Hm-l8QrUXY3l_FoBAN>d0v-_g$`Dug|r%2ychvT_l<@ z$-<`{Gb_0P4TPl4_M+qsZk8fz`R7{YwIB4!Bga&|#F-`}_n^6hXKonT`1;1CUV%gP5>KRS=>wE;Y4boY6K zy7=+f4z~q->|T=7ka2J5*p?mOc7C#uoB}s|dB!P+6d7Kaeqb}+3UA9eg0(%uP&(m7 zo9PIJ%AYpV5k9C=nKjc97Pq!PxzV$2*v=`klV7_zdnlZUxLdU<>cFKZxzN@f7(6&Y8O57 z(4oqPw&3!+YyJ4@IX0BPwD01XPm7I7`LOdtX9w75L=7`M4 znCmg8V$Q~#h&dNX%$|}6CQxw#f^q-UP5({$!}Gn%4WIKelvmBax_$j|gSIF!r@-u{ zHg{2*=PSWST2mh?F*B#8$i`L}Jom7Cd24dY{f+~{AU zmmaxtD3Nyzki!AJGb+2S2<2lRHy<*0t}&S~_wH*8KU1>(Yh2~8U;C2nH&%N-$}=Q+ z5jo~JpUX*T!>2O87j*t?6+A{ezejtQY3$dFO3Vf@V}7svKqY1yK+&q=c1WQ=cU%e! z+#5~%M~P`_598kwiD}m4FNu+iy17Fj!>2XwbvESfd1xSb09-+8r7as{hZ5rja8p>o zR>PrRQDQm(jNa3_%0_!D9wf#WV8x)gCF5%6P>J!wKh~*ey5wXlDly#v-*=6?U-a`E zm6+~;-EMD~-essWN=$l8iVQDIKS&JT3eDx?C@}~nulq(Q=};j2GC-6VgvFH@KFhwe zB?gnB?JSDRqvZ+fsl=ceGt05r5hgMCm86e>P;v+<`vaQ8a7H*-#jygIlHZsjbA2>C zyLJr&a%0l1Q695R$RyR*A-kJ}^ZwUwosFEWNBZp04et#Mu#H-2+Hy)5@4vrA(la>r z-fXh@LN{Q*z|lVz%xfM>25;K1v2iUUGB>QzsUN_AdIfW1>K>9RbT;SEcQFkO8MX?9KY|v-@H_5?itC`rkd}#It;-NfGP9_{a}QBM$F_ z)pXZecRky|lyrJQEW1?+C7n;1kLU{TBidnqC1P5poEQvFH~+MT=Jz6ajCOu6e0*x% ztZ1q@%fO8Jow*ev<<6}JC|XtA8Y%SWwn<@u`*(nU_ekuT+B>P6F+!up(djS6k?d-d z-As{XRjm~{(&RfTP6dE|GeA5Q)v2G;Gu$6dN@u6bkF}HsK)0{tuw|I@fDg>~27OC)a)W0T_^d zJ9qBLj^X^llq$7P+|?swYvsAFfpSvCGk(sgM`8Tf2QOEeq(aYY^}B=Oh&~SIa)TKY z73~iU@FPzFG6!US$y|Rqa=a}ROCP~32UGANH#4vpZ?a!=i`#6 zs_(>n*8GAts5rS2^Ch+UGc&^>mFB55X&t*!#R;pCD%&la@yFT6fY?rJpxb<&2}#y{ zbk1*JI6t=H{+iy;^oZ_WE^97i?MbfcUk3wU!OklTubk(pjpaXtgwa@g(irvod*`%-*wGgqoOKLB=#3#wsdRSy-X5MadM!gbp|35rt$_*Cu0ry1{DsN(37E2da4XBOg|_N-U>%y&~6k$aUVnDik&o~wj?!N9tr5nwC!uj)2@u&ON(I=}+oo+k^ci)j1 z{dvyIF#hu4LAJGC= zfxO5{BA7sh9D?amH)v{2+k*3LuhxF^*8GX;WA=l#M_#u^d9jd~UDW2+%&g?Tga}Fd z-h;|ZouR3+s4;!km78rqDu;#plwV*%4sVQVu|F)F@AY6{lhwBRyduOM@i&B$Ee`x_#sB8a% z=C?CEMmxV}Czf%~*h}Tb70j65{3t3f9sotFifb!{{#;inEO5UL@E_y_UX-qG!Uzo- z*xai%N&^iZ@uetFAdqsaJG&*M>+sN^$pSb`S=r;^{)Q+ouK>oJe|5ZBO&Jdjnl}J# zol^dU5o?r}j{vWRIp?~}(B*NI<`duv_iJ=(^vIFQOCI2HEhW-~fBFYQG;>t^A)t03#FPIE% zXX&}!c0xiS$jf>|G-GBB47U~Ng_qEwG&=k>& zm7Fn{G1@l*sis%~WG==$k2w|dHReUkyO`H7ZvsuJTN1&*i`5~RZC8HheKRV<-!IqY z`V#+aRqBgcV^8O_LQQd$m{Zi|WM)=!76*l-ZRtfdCGAwItWVK}^IxABkf(9E7RIqA z#C7apRi%h4Xsk|C|$ zUtO{(jMUs{+kc1BnA9A!!>-SLIeDM-(B-8b&F?4h814MtQFi2>`j@DtWP%y<+vy3_ zl$QWStBQLqh5p=UDJ*brclv+O6c-n1lf_A?ttrhV2iSIlKy>UZyEfDXxBbQS1UN7H z!5z<)4Ny~h0o>yfwyS$BJ=B!m0Eaz#qmcKZni2wVar8Yi+1m0{Q~CiuUTH_$kd6*i zQ^El2PEgv!ZP%lkG5~O%U(K@*Oq-yl_(F2Ox)8O*e z9Sq#gx=@#Qg~z<|arw4j##BW0p%T*vAoDoph|I^B>oKQd z&c>XGITuJwNJ#_}s2ByotgO&Y;bByPKm04BOODkm)x;)^2JZPvP-4bN%sbWQC}vi2 zKEH*ec?VO8QE+K8{mv&kRs*dyUi9Rw`(hLF>&V82Q^&x#*MW`88o*+&iWifYgba|A zs;4t@idw;rib*{`bjycLRf%<12Q@b($4wvUIX?;`kDm~S&~wHl)os%C4R_?Elb&t0 zE468U*N4Yw=lAGFeks+TP>E>`X3X!1uT)~%0~D<)&RYuoxt>y3;GPWdADS)jR*U}_ z`GvEDw3;o=CB35i5Qv-q!;kZf4Nzhp0=!@Uxa*%`^-*Fn08V;dp{h$6W0aUIfN#zO z`yBmEdqpn+M$a?uUVFI#m6%t6FK2uj6Emp^m6&&cg-XjL( zjG5)sY!s6i{7NzogHUMe!5Y03nui_WXu;W);<0Dcyk45@eWN|6v*3kj!A<+THCtjr zbQe{>@T*@q@3>&8PVNp^dAzJb{p;ZJ4lb4DoNGAWV&9HNu`mEIXnC0ZC2;xW_jBts zvj`_=PdRRC*x7`9H%@=3~tDm{T!lV@|}J3na#?B!UT4bb?@ZPu5Kvk!QgB#I?5{7XDV1 zmc4}(RiF~%3uf!G3+Hu`8}eJq`X3!X?X61XUHj3YDqvP}UOqz7zV)XPbD&$A%+4rx zSEKueq+#&U-bi5=^fR| zl!Ux}dN{v{DKWnIOEvj-82MHASI3tY|SZ9nGo4)B@P6&*B-sEvUp;0i0GNr)k(jL1O9v z=9b>^*_>`qCB+)>i12ndo>XmwlHv@}#|zU7l7hFA`D%oZe@=$o1-G%)f^g~zT;B|D z*qBbCpKBF1(1OiN8V;`jH9qbDd;QxT zS~u++xOhgp*fq7=g!8ityL|sO&y?h!SJn+`YD!*@{@7jywdJshncKd6Fd@qZZ<;j( zTzpHr{HZZM)Wt*LG0we>augqp$XWX`O*o|)5uI4c4Fof$;aV7#lu-bghcU-vKE+&( zIT3R%=0p-n8C?>=1S%#%FpcU>p6A%ykgwY1p=}k9H>$XvMTwT5U9r_N3Cs&>tobnM zh7td1=nSvut#4Ix7AR(wUFMFG(toXxv`qu3q&RL%lfBk|xy!Jh5t-)n-S+Wv6LP!l z?=cTSQrg*WZm;JBXOVA^Kd3rPP6ph|O^JmL>Vx5fXP2L2N@nhkdi)e#N#FO?yo##~ z!-?tdMF;etHFJ9J!W#3_V66SrvX16LE0MrswDWuF&7CjZ%ZFj4Ji(0lU9)N{l#~tt zMJu#gq|l%1E`tucER~dGfGzC$`0RWG zqEWS5DJ~3ttc3=7odW@`Ze=Kz7f%{@0YwD&h+eh zWLV%;5Dfiy2c~8{F(fTlsB_Eo;+7N0T zP6j}$^97xxjlNM;mpT5xW_spuVRSmW# zSF97)5(VQtm@RH~Y4Y-^5g)v6U-b{&-l#m<4(>9nIxN|OGa=pxNozlZ3dX=MX|fI} zM|X_*WJGFvOgd$<%7k3lwcR~zY&c)%RR4UN=Y}LmZ`kU!Bjm)}n-A#TGn_A1#dgKf zG*e=C%*nWM15+}^b^oa==HcXXY?*Tl+nbWH)n8t1l_Dokp4W41+>++^7;LeT9b+ud200ramXJ}=>h3N&sz+1`42|{5IfR3CX6iyvH zi)|2uKOTtsfv~vxL6#bnwtiqTw4Gy%qV=Kj6RCcnS!i&?pnf0}Cwo#T6s((3Kf+9I z%Gw6xp3a+YOd5>4f8iSVbK;$jQ?7x2)M~v+f5%uOl2K=E^&jBRtDmj^-MD=?KmDoK zro1ZfI=Zy}OBaAYJAdhtmeU}djPSR-d}Em@DRh!|+64Yw<8?-GzfRPjhr?s?xAkZ- zqLK-bweB@F8T3Q+SS1$;W-Q;D!>E2t2FTorc^Pvc=2y&Pm?trhk?6;ik_aYHF&BbK zoxG!y!&pOp{F}MQ%a(nmlHKe*ec;U&s2}sdeC|=$HnWdL{5qQ#ziZZgty=NGDPv_5 zXpbnlElxtx@`h9W7(i~yUWP-}Khc#HeuIbK~Clos*2n!hJ=T zzmAj>e$SQNS%Kla$FLz?J5@F#laFVeJzme07}c|>eJ@ii?&)e{PBt7P#L6_|N*$ zT-t~Edn8u+>fXl?NQW;Qe=1U_emn)}7iZBnbRQ@L43hwyy1ITIZ%g$f6X5)eZ`WGY zv_k#J2Dto6euEcQf_^*)TrawDkkg=sR6kw;?wU1cn@&#{b1~z-t8U8h!t{cE;H}W$ z-h;y;2!&1y?ZY4x4tYF{`hiekQvH1`Ek;g;K$oazwcTKEK$$&Af>So%9lSK2MBP(Z{lBMMi=Y)Yj z-+8uY%5z`p&l&KTWv5q-QtdGzp6<%EwcuSpqQ@$^S765Sy%It7;~PNcPRz@g12Mm1 z9>Y9|d5lCq@=GF^K!t9fo3cLTqs-o~GURh_ZOk|O^FlS{%i8cwiUwAo^UW`#6D^t?hd)|!`HNuJa z{HU{cUjknCqy4ihFq?eztIZjAn%__1G1~cUf9_(+(Uw#{UVs_%`^VKb*kSnqP_)9a zuTtpG{g%Q4_pyuqZ~CED6G{6+awydj2;^qJj4Z2ssvpY$j=R@&i)B10L=m?RV81Sk zC#RcH{n!A|!f(*AH*IR8er&}bcd-BXv9+Kdae#H!-oE(#PkpK%@qmB0?%F%V#s>An z2%?V{rWf=BZ(*JW-XsbN5lx}+CSrP2G+Kq#ZuHf|2<^s*`hl>x`mwm0ytMTLlcDV# zo(+E;S+UTY5cGwD*LXC5r;%!!;~c{1LNOk6mi{$cQE2R+l{-i}Zow)^QY zvI)F>sB&hg!&Nycdp>gP9Y5;N-{3KMYdSS)X=zHzU$i_n3iLztSS42oW-Q;x(NsSS z_G;XTc^Pvc=2y&Pm?trhk?4m}Ndyz9r~<)cZ%B2#ddiUBXRb5YPWD0-++*~g`&KTf zA63EJ+U3sVIu(rhU&+hT$9#C9dg|C{?57qWFG}uqx{$PXQB*(HJh>^GGxy@YwV>06 zO}}-VxdE0ZxBa+#Gw4U*k_R0dz%<4Xj~Sh{8QfbLx7qx4mvH_|!`Wpk zela82J*FO=2JYRUTy)MY7`L-+ywv~6WHa*Aug@FP%W_ii>g%0If9l>Q@R$at2VSf? z#FV5SJa;A$q|vbTrq5Ne4cEN>mFt9ZVh83K18fFQkQ?)D%*YJ0tmmqiK1~wtyoc>2 zO0IJ4TQq5($5A9-}(c zAzDrbFKKi<2&Tq1gd|H+JOYw2R;uk^vYH*_B#FHfz|bQ;Kd%j?S1Npf=K z$3TbQZD@XfhR0~tvm36+z106QhNdOBBC z3*{shpjAS2uNz|oIav&NX7|X(jV4%AIavm{QCQJ?-=8qH0t-nXHF#lqK~C^iatIGX z`r?X?kLW@YfWpBabhSNNN0?P(-5G?%m6INwYn8T~U^29wW1Huyb-LH6oS<3K96?B5 za=8eO@xMy*PwdXXA`-Cr&>c~9bi}~xmdqo*d)%_VFs(9X#*#+RO8L1m`*-|+aK8MC zoKKBjn2_r&cjv7H_YVHnap{z9;e64vm@?a2$jRex9dFG9_imlH?dMhKmA8zsyl<0Y zMvmk+pIH8qoD6LJUf(cZ3KrjlGT||e^hJ5V!ZugGbWUD5=NO!TzZjN%& z7R*y?@2qtY<_?VJoM=A%dA3UL=$(2ClR#~hoZAQ?Y3n9YIZ=$eB}=HVbIIObunB5t zuV2fzm=OI47g=|Zlg@@SMtQz9A+>(=`&4f{ER|1lkS6NoovyT=C=(zMmxW|^QXL;45o6@7|fX8 z4P|cFyKw?2T2-8j6#8>*rLe&LJivdJ6ZL9W_1f3Jrem79Xr^OsK_DL-s}S36R8DRK z96z4(T9pifQN%q2n0cf8(N~^SP9Ecr&19!+PS-#=$prXiqV?hP3k5mJ2E1sWN7v0= z>QOm)4cMW@XUE^)V5r568xakX02ihg~Y6hyPvlsx8O=`P@J2@c*0Y|H<8@*AVN>A3pl$ zlq$*ir}$yNXLjwsJE;DE!vC$_bh!qaz3)ymwWNhEbbkC&H}wGh5It7O^#wC#O2ibZAEN*=cVb?~9EkZ9^BCqy%wr__F{UJf z2~Y?aS*pUl79Oqc!sfCd#Y`|a-9JbEyq+HS`F<4nk?HfsiigMOT8`lGH} zYg6)MPRz(x6F@I4Yrii8z0B!*#`bSJRZgxQ%(_CcLpZ4rS^m_>nsO5L zq$g zH@NbD(~rMSIA|tWgreG^Ib!vmn(9e5NxCU5QC%#A)~q|j*Rt_>g;QAx zwk;o=?Tz^|NgswhG|W=%H|ZWUWHRW9k{e@?PLuX&1{I9{71L!~<<13nKAIBUjkiyX z*lt2vH@dN79tg&#{zv3L7QtI_uX#EwoFpedZESL`4S?0G-}}Fqbq&t{zEJ;yJM?>M zw{M`ba1JM%y)u8r4~3t3BU*ks(m@amc#L*_e@Xh%Y~D;N7*Sxx{GM}{ z3dTf$q7|ldrO=;SD1`;?p8)=IgX2FI#7*WAEVUaGw3)2gNfwz(a&k)|lb@1F16byu3^sPFy!GZ98p(q##iz^r| z4RT6bFfbX~&JoBvCv_^M4GuI*`Y#A^^f@pTCah9u4y{kJghQa{X1#h2>9P^#qp!Ax z`PI8;mhbuk{v734@pKXB$Jx-_tgy$XB&_F--KpTum&<+YeWDj^xcRa9$k&SIWJ~9{ z${6tH9^+p}e1@f`!`j!lQTZec>-oG~)D8T3L$hroH}<6d+#DXmuah4%Tx~{PuCGu# z1N1}mSZLLQ8Ot|m7S#`5fXtnkmoW!oe#Jb7c@py&iGFl0iC_X1y&;(WvxhuzaWUe% zv{>%c);~k_ASGR8a?RoY5%(ofHND;c;l>elo4ZQpc}S7rYPiP~B2deprm=_5(Z=>$1NI%mWbZb7`hmBcNz02X1xw&ozMnwwp z^d!?LS!3AtF?(s%k=yZ#^!C*qCeKb#r1!`;%Ke;5{OtwRH21gEr~Zd@0*HQW2Q&KH zz|asMSau;~ts-hS7n)N+TnO0*0R9L4&}~!`j(%{aQ`;`e;FZ4jn=mzk=tl>DZ~Rs@ zEL6}y{g4AVkY6_Ax;fDgd4Ne~ffRJ73v1 z`8E*P!MXRPo6GFQ1{)L~Pw1~edwnZjGzSRW$ILzK4ji9xN?EjVkBt)j>S0>ArlLF~ z8+i0XbBaA}G*986Lt7=XfXWi9B5kh&PobZwj;5sbsp z8NAW*9*X?U3bbLLtNUfo!n%2N($i!RjCBgR*^37%(9>LwrTK4Gq_5^G-%Er0@Fw2r z-l2I)wEe_m{Z8=ZY4a(=o~elJ=^i&9`hJ49^94pO7!Y{_(#Zr|Q18gBmq$W1&HcUC zB{@!bj0na>Fr&W>!iiwS0+d)q)HN%;Qy0|Ef+W;Y#sIAnOME;mh+s?w=$KHt{?~K?3Wh1bch76anwB*_p#WA>_;L8E zusab93&7{~wmoq(huK#J>NC734KM632nK#-ULkS~*KZLr>$e3c7zjDXVi3v(NdyDo z-wrt9u6%E4!N6`bC&$OHBR9e!f@7#cR2}IL}|xOMblq?RK`J{sGY2Bh1_5IxH`m2xC@{ zJ*!0Tb+53>2YTD|^D7tt+s1Z`mLCy3Q;8NAT%A`6^u9WLT;v{WA}3;~MorFX*1RFG z&AR9N*f}645&{dU6fooM7VIH%@&X{sE|zpGpIDl)1Y(KB5{M%wdHVob9N~ppbJv(%(#aPUOT9;3*A_z(eLB7PFtRK3q=u33(o4N-fbaZJ|^?I&^~Hp%2!E5x-jP*S9$4o@1i@;skT z@3>vLFYIpbWi&jb{GI~setem|9?Va_S$gxyN=JL~?32om)_#T2$@TR5%^l?FM8^}J zy$Z{@1&gcXoc?Zo`a#$vEStf7p#>7oJHj4CXzP)BH z(7W`$X?c5~arYR#P6djJw6axI;VPgvz35$)F)S~d%V`)dHBhFd*4nPW3iMvRS*uq9 z(75xspx4Sk`yThtOpFJ58%*`pTwz1xBnhe+^=O{|FxWKmxg=uiJ&+R#fnjt4X1v`i z4iGtc36NzMOFEWMEX`N~vBY8t#F3L%|DqU6K_wLPLogsEVGEvyu}fQU`i015{*%=U zFKOZE2(?2p|ckm^Wsy3PU$Y1ihP;?6d*xY^7K zV6xx1(T@So`-i4792f)j9FTTHF zrAg$(5pX->D6Lc(n5tEv>JMk~@WTGW=mfv+9D}P3a3t52K+bz$(8^hkLDjoS>OAyNZxG9RRbdsl;LEO8mg+1g*^JqVxE$b0!WV z_k+F1&j?tpwG(V`0(z&m%CNi-a$+zcztYndQeB*nS$+oSZL@A;S{dw#A3cnx@9v{a zdxvOGdkplhiKxyU1FN`W{oG<(irqv6P_pUudu9SgUNDY0- zbnX3NA}2lHW%9HvSDEs|VKRDlY-GSCJ{^0rLmz*TlX1JcsnQE!lbbNOBS4HGx96*UxL`~pAb7~eBRvTsk{NIzUzdh^>`y(^j z(BVyT@&*bCSZs0pv?`I4cL3%3ANVC74}wugeFb>Zb7bLoJ0d3)0L>e+9YeB}P)>dV z?DKL--|0gbIjI61eg5RL?JqQloJhaVqn%=m7-#9lmq+sc}m8OpTB<4G26D0zCS@#?r;u*SRQYFF{L-O6;|c~fdLfZiVJ z3q$1=5_(UBYEH>q&e;evxZ73-#`iZ+pd|zrQq#bUw_6-S@j? z#S(}kCyW0@F_r>nC}uu?_T9muvf^a*Jxceqazv*l&+VjjdmzfmS}^DDu_|~vOAfZt zR7nZ6-9c@$hmW(n6-9qsHVBU=X$@hXq!Rg}g-=3F8;oQkNfD)^Sy1<3z zR00=P8;%!d{UgwyR(sK!+0yn_}XClUe+DMv74 z`;MDK%$d?&09kgiq+|KS(u^e#ODvW^968zgFN(1g?1y4}zx@a_zW`IQ8AD~Wscg}X zHxum=$3v_?~iwf@rKkZonW+AoKgX!A3Swv1uw`cLJ zykeIv(^sPHN(=>_F?@P-$=2h&A(hCf1Jxf_)kChtiwi1ZeH7``K5M(&U2QK`{Cev{ zn1%|?i&kIj&4Ua9>6gMNGke;S*KXCh0%bb!lXYHI3_K()FU|9Z`vBRAY@nLv{@(Rq z^0D`j)f*aR4`%fD+|ELj6DNQYtB6|3h33>IF03~E0`Py1PS|`z%v9{KKc`|jOTn#u zvUq_y*1i1oiJV9S{Jv1jEax}~Mjh1wp!2PipVyZVIgtg}xt+cFz_$u0Ckg<0DH}e! z&0yq23Gf=9ydxJ{bs};i0KB=sTHu!sFt4jXg>TE^;f4JLIl-^Yix|ke^AIxUM#xkw zLS|)76Y*JcUPOuxz$#HYJtnnEeA}46(j7|`C-S*xzt_zupMaUVQ zAY?+0tn9d*%Hp-L>+$N`4kh|j&Hi`KfZnGJ^5%R4Iho?J#6HGYiQc8>XI%{RPOg6a zOBWU{zb-2tTJhm^>gO!cyYcQ<;=c7mIXMI7qZPixGOXpqF&?*{_$+)T zx?b#Y#(4wexe!u*516iXolE58WL6f>+ElJV#s~b}5GPx3nNN?qHfGUmkP|s|=Xb-W zD$xSJfS7YT;LSK|r|^QEAw{m^s&W^56}l|_a)DGEdHQhCs<$WMh{3nvS(zsWs?dW9 zm$pxgR-|{fzLY+LSxJk5YMT3d;P|Ms(_axexdvwRx861)Cy4+hRuPrNh33>_F03{j z`|Q8T$sY&xhH@5)XF?$+Dz6_cg2i{3JDCGePbERkECK|hj+zHBYQ$5IolA+F*Z@?m zTe)CuYa%Ch09}54u3a>rk(0%MW7}Qdn0Q@{$jLIm56;V^`sJyjoczqp;^Bq;1v$a5 zoRuAfoRuAfOp7vb#rn#CJ_$GYlrrV@RG+SyI}3ZH&9$Z2!{45Q!d62C4Cf}IO{tM#4%ft8bQ zOtph0;!Z`0C0#G8&xil8Z;%w=~}8a5e(fP&v@HpDnIwhP@?%}6T`G(`SkAIvr7U%Fy1~6o^5(q ziN3z3Xm{XFMf%~*Q{U~@z~1*WO9PUkRcN!M)aDVhtb4IKdf zm+{9R30Q}6j^a5%A(LdR50_aJ!B_=w=rdYgFHs%^V>Q59rw;qZEhmEE4A9lY=gxrs zU~Qn*0DSrD`9mc~MljX_p6oY1ZM=sn5eyf=zA6^aLa)HgtpfF~`!gP1*k2F~{3_wU zD}hW-XGrw7i9qIL$Yp$-!9SL1-<5rwLHM_V@$2K`mKF@`MssouSlDxUr860SpqVq- ziZC5sN)8z$@o@$rx)ML|ID?RxJ2`}ttrtYkcyfM2e)@J%rq|bOk=}^(9;ZHFEDWQa zXJpNbEmNW$Q#=xH0KKQLzY-n{OT-=fg$4JlSE1V~ALm~OdfzxEyWGlNov|X z6*{iaYRXlh_iCAhOEOD{oWwviR)ri}7H zv7}@9#L|o<5KAnUKpZ)V{};tr3KF205^Wcs1y5zgnP1Xv=Do=frG&=ppShzC%1I)a z&!t-OH!YMC@2-4U-D-TMXu*tEnYVs`8FrS~GhJI_OXS37)id54DR^(UrZS!V+4b=1 zt9*L!7pu;g8S$l3>-8$-O0@0GDKRU3VUernk6`V!_TuA)Lo+gKRp?OLW7J3~d0OLJ z+JO=*HzkM<8%{L+^d%%qTejNsl zGNkqblvqW-Lv!i?*II3u0q{S_3G5?jcCuH8v$G@*3TYqSwoBG>A}9F(*CzED@-vZ- za#9E|T9oi3Wd)IwB7oleK83B00oXtl18f_lVY0-XkrTwT+ev%$H&Y>U@*1$y1i`DZ z$6)4Gf$9VhFYGVK34Y})1ta{HfjdoL8|Nls-MdSb>Br(8CO3i4TecqT_6qc) z!|gDW6kTOHKkRsi1Hk9hQ;ssxu!xiPAuD40WK~*Ya>W8`;Pbdo6IS`aEb2_D!8$vY zRq4IETTk2%d^VdYd%BMU(T}%K&33Y>Wem$CmN6Xt_$S3!3VuRse5g+rez~&ZXPf30xmKo&PKm=?mpJrB{Xp|1 z|DRvpEs_)4UEPoxJ1Il-eCR3{&4*wXQu$Yyu4yhJ`f)Jv8E<-)^bK1FWx9A!T3q-w zK7DcNFDM@XFGQF-;HN|k3B3-#-opCwnhgrq?FB2xI(nnuWW(9S8TCKgI z_6*oSoVexX_gWQIIzt>AI2UHYd#{vU{FzxCI}Ft{_xGj8#ok@2iGCabGy40HtRCve zQGgPw=yzyN9p_rB4RZkg7ybBSu||h;l(z&533dq?HxV=do?l)8%$%w*NM zaNw(7eFi%b{XkgWV^qY+zVOEl)Ej`e4cD73@?rD?u~ps4x7|l56a9D#SbC{rC!;`^ zs#Tzd0>lgZ3;KayC5d)i31qgy!z<-B5h$5^^(N5#v_wDf-~O$BxW3P6Y5l-%G$)5J z?z*z=R-zwh=1hkmWHyVy4ACRv5@zpS0FFOQ@}Kdh_3m!05UWhv4E6H)1blww^JAtr zJa@-m-Z?GBOPSVna2~P{_^fxyOD+LcZA{1S_xuqE`tdfYTd#UPZQm(j8Xjf6r`+XerSTbEsxp!SU-s161gr;ji5~8!FHe#tNy~V8;9VZ86c0 z`2bluu`FW=#PW(|49g^zF&zD{`4`1l3Kl^z)o~9xje0FBu3mHRcprYcs8jO87rjg& zbA^>)F_>lSZL-y2?yudB!Ll#rri=Fcp3+ZiaI0&TZ4W~4}^5vTa{@)A7lB}eu{MV(8=Zp;XM;hm%1eBk=%<#jk)(Nv(2>Lmet?}7$^ey9PQ(Zk?I z#SYk+R!4OLc-VH<;uR~2ey9T+{4qIW(Q*7q548TR zev}W*Yia$!ZZs!{zsp(om3~A&(9A^9S{#2Mlq4#8MBw3I@n2 zsVXqz{S8@4^rQ8FCOWY!V+q9aie(JTB$hE8{b=(qim?>5hhjE+C>0NcOsW?G_C%Hs zdn!t!!ZRw3AytKyKnBc1d$*ac1e1O9wH&nTU7m{EirQ_@J`83drEbb}ZS``ZA0I8V zd0mu6mF5k~^zDqPpFe=VBfc8S90mR8F+`v&3#;a-_boTXgTFK7kB%4#JLX>+jGwo@ zNROL02Uv9R5<}w+wnDe9)N52 zO3;PTDfnUivRlQ579|)DntH-l({DDyN?C(ur z;FxagbO>7iRzIG)7q+y1U^kkRV`5dGGL=B0A86)`KM*qS8GMA}4}_ePy;EJYd1DUE zztLl=3Vryc)y+Zie0tus;jN-TKPJSC%+2efLdQ-kS&$2S_6eV9eFCOg+uXA2X*5WU zUO#Hi=taP1(>+J7>%crmyL|nz4fU#YnET6aF2HB`FX~^7mlOT4hH8EUWyTsLtI+XX zwziuO`XON~ygmWUcz=x?iGH{MWa-4Rj3p4uE0!@VlUT-Z^uzUE6a%S5pqRFARAdfU zLMB!Hs1-ZzJr?O0iV6;S*6}_{n}|hrlePri3zG z(^yILL*r~VZ(?r#o^Qq~^oL2^F4uy;SEMLz&jbCawz(~;?W#h%Ic~Ob*sVw(iqk26 z2>PL{80D!wP>tTCVx0Bs2V@f1n5f%!fjxcy&;jkyQfl;VbCp&0=M?EyMFuOnGSk;X zp_=CY){+|{4wEJNF#^o!@5-MNPD3Fb z=9-DmA1C?|0r35R{yo~9X^;AG4q)`bg6aEK6a7G_r>SoLyb}1`KwShlD&*`G!$?Ly zE&={DGtT?GP=V-23}6^7uGxJDW?vPkV-eXrys*EZANWdFVPRQ{;huO&@XCf{lIQCCx>Hn@hHn9L_g5XoDT5C@drZYfe%J#sRVMCbJ5C# z99hmayO+&dackE1H-|t@>X*$E-r&=@G1ngI!(({YiF&8Mu27+8q@2F89q4_^<$iY$ zm?jZc^(*b|szwh=3*0pPCuA}jayf4|OnZFTBzJI#i5eYzarE7-KyRMT$SlJZL{8>I zH5!|zY7A3=ryaMm)*c`y5&{dU#bCzU{bd!A6K8-dyI9h(d}3+F5{M-hOCXM%toawk zz>8*}7{j=ZPaW!H#qa879l0ZXBr4tCWpK|$a1b3{G=ps)d2_@XnEQ)rV;fR+`jO~c zP272(Ffc=+fR9Yq?m81WS@tuVmpg3?egB{etzCA%Q0gY1erH*DzLUGXcv+XnU3pF_ zbZgg+@g4Ul(wDn@YBd)&p$*#Xq^Y@HjegeA}**Kp_|9pDi4Fp2*2~fY!-#`!6;HLf28#02Z89KflqL$jJdh9`-fpqX>- z7oli4W^RVfW{-%&n5}4J@4K&Z4zJ#En@rj(SUqg-?l>CwJVUca_de*y9s|X9?QW>h z`*$wh(jWMoW_o?52~3mB2#tBuEm@8JIYeu8uS!VF+Tr}tJec-)=_I;8?}!>*7Lv5& z81Px$s@QF?BjNKgs74gJw{*mORl3Kn*1dv3KO~G5Qej}m`+ImT(T^JdSvs*SV+q9a zie(JTB$hE8{Ydy1#lYToDCR=lj)V-JoY>#~T)DA0O|;af&*ll6;as|v;4zqAXk^K~ zc9awEn4&p*MfZoIu-r#cZR5c#qz>sZU0dlw^uujJ4lg=wbl>YGD)gMl>qn}<-_x>J z9-agGaUy(hZO5A`w2`q+RXF%NRYohm5cH#~%$;8_9zsO*FqO zc8P0<8trOiy)^tRBzQTwLOFz4{_=%tn)_RSW2=%>07?qd`@KaV;JD`w^Z6H{$O6GITG-fF1@b390C7Yfyx@6 z!@~>v3;KayIq$wh$UM%F-DL_&5PC|S&uON$`- zfo9I?F2e3)#+l>|K!~oy56B5ZCXIe1&W@Z|n8VvZe|~Xch$_9Q$Kzhw3GkknvLRVh zU{-H==aP%9+N;uYx8E?h1N82ca^#Q#JoUWYw0=S-c>!Ib-b;E&1)ok7YQ`wTQ_Ks? zW$KP^)#zPbWfyJ(y(dY{U9aFohr1|PDXYc!dC?u-Yv?HoA@HkUT z1p$29Wmsn;7ipA}qX4Uy8Qg7`1lD>g6ky*Sz3$8^;-Q?J0%+$22b>k)h2JncavJc# z66>i$k7^v%$qjv;L{Gme(n-^LHM`wB3^K?(VQ&98wMD(xdieO(h<#sEWvY` zS8LuPe!xs0riQeA+-HrWhd0 zIF^Vk$5`sIq+-d&l87ajwi*5EUle00_zcBd`PO&IiFxhCb*Bvce|EYn`tj+;$QhcD zIMhn;m18bzG+$)RLh5x6)3rMriNxdq#W08qDbLsKq1kiKlf*4o_kgQSG?UoKoY$ zYQt>+|HlN%P_5y=y(v%U&j}RHe)u3LZy|eH7Zj4@ALp`0~HQXH$HE=Mk^kXn6rQtGx|?HyNQvQ3xGpT`AlAX9_+1K zQI`Ps8#T~53=VID#Arg_@xuOt#Nbzws3e7)-b2XjZzU3gkdyfcp?-=)Vi5kV#JEPr zx3t7yH=2{h!0%qv=X4aMRm^~Zt(D9wK>PX%2Sn|u6xZY9VlON$7fSHtnp0r$dQ}t zEufE_O?~MBls_34@GcxEf6Q4Ud#9~{=B=}^?*f#Ux%{c_2t)brP|f|2y6>WHYP5Cz zs+YMSF%nY4%WS}my$JFo5;Lx$iE%6uS&p&PV@bu5jU^FFE|8ds|DqU6!AvMdPU?l+ zktsa!6p`rH>o#K1=Ruu=U+skR>sEr<9J8>|e4I54sZYJ1ldd^#ArkX-$aCI^k|js- zPpHy{Z;N{RCGlyK6JPEc!^4looE1j-n^oy=mR+;-_bSrQm(84Z9i(2_zwJX0F9ChW zFYH6;M?QUC;huU9tPu~F?y%ltfq=epeoLGY957by*h4D~=5FE0%`olffB3uOL={@A zACZ{RU`Br{JRuS@9-zc3q9$^oIc3d-)rOA&{tt=K(GoUpa%Dy_+JEj*<48;~6cU#m z`@kZ*E(s*&4Zyk{Z)R#dZ-o-`5#WK``QFz%H6($=d+-_R%cHwUh>>fMlp5>p5GwrGLp3f#b=KxxArzzh2i5`$lv zFE)ibSY-OdW=;;{Z!*B}B8RVoW-!Qrxz zo!f=G?SRM_mAujnBA{~EN7=@VCQ>HPd8wDHdKpYqqnG<$K2!#ZBjLD^qQH#p8|zIJ zrz=2~fGjUr%CSsjImU92`P@L}nq8LkoHWU-DaYtvKbA6JLXZ!dO_pgekUfIz` zTn0zntpvlse7(`!x6#~}H4CZHYniU8Z6k`)u<R(*hO^?g-(ds&6n1TmlXZm*f& z1(an$L7rb!1StRb>sc4T-=EKA%o+uQ$lY&OM@K{m=#b;r-M+sE#d%^Yb9a_K9h?&1 z-e#wOHt62jecKsOcsXHF9&^Z#zv)kZ|6GyklsJeejxw0h-==Sf;%ESrSVdH4E;OeG zaACFKc7XpyasJ5ns>3;za{vnYQQmcLZ6Q&dV1UU-S5{sul_Jkg0JSFT-wszGigOHL zoapkEOhd53>-PXIj-J%<_+q8w3suosw4>%=N9QSCt)=HHIx4`94B7-9(m5=Z#!Yr?z1YbtI>Ov6%g8KVCaBZ zuzaks=-su1C#v+$Let7PAoLGmNWyj47CUj(=KR|+-cE9#ZgUumuv z9BQ``Ea#Zb8qKP#SxA}QX1aE32N96251;d#ZBDGy{iI5d`t(bt68x=ypja&o1Vp;z zi1f~?qDseLj*(@%;@i34Mafn07|SPN}mhODK{>x zHZ*qJC$0CSK6W3}{H!HTo@# z^R`$Y7)q(p0)t%5Hn;e+qo&%Rxo|?bq>V*ypLeRX-Ila9jgw#UH63p0(gT6#!Rsv)h#}bj{7)w2tR4mz860zh0iCO(Gim?=ULNNym z3(w3n`JQyIR$F}BAgips`f$+QO0b1vKGtaFv1TDc-I8O z6qmPCqX(={U2_2ZeaB$pTu0cEY(`JXocJClWUL?Db_IXC&FH+^1P)%BPdN5M2mBp& z#QAAqIV3J{xbn1YqCNd-#nr=d4+ZprPhD1Pg1-m4JUH5xNilsEs%h?T^`Ck>yALN4 za}mtw@2n0wIPnq-P-2A?(_Cmy-RHt;Lw$`G|7(n*tu>-?s-^L%=+B84&OyNGP{@RW zf&0G+U!laz1eokS!p=$iD@x2gWYIOme76)nQ5s+V$h7vs%-FN zBqoyhfwMUd|Ke%|uHVDQC6d87!~#n0m}DS)Y{(5 z0uIZ^#LYMVrAoiQlhxS+C~q_IeHk^=Ud+GNVX;A_fPS#dXKN`?{)9sQcJ)s7bYx-A zKI$(7bidjC)4BoWzwhclqj~_D2=IVvIzQH~F+ZS2-yL>eqZTAaLTVwk4b0dJdJmD9 z5P&S>SR%3erF`@sW7)!w=D8_8+bh!s6uag$7__lTb>tNCL*f%cj zQjpZtN)XL4(~V|V)(me1n$L7iWiOGK^$st13*)DI#wn@M@-x(Z``zZ#*7I|9?XB#^ z!47)UJ5;IC{+egC)4|_|$J~ki0QbT6Rr_;0zYA#k_U#i(-oRl9HD25Z6?^*7zDoCe z@OQ-QjW<_?Dbm;XnQl?-OZLUZai z7gif+Fa2K(Xj2)kI#7kcA@WKv)hTvDuFa_b0pXM-OOEd%_ zXZaan(KLyMApBbmp?dFXX$`?{G-pGK_@|cTW1=BwMrXx6d}u(1DUrl!oXK1K3+4#J za~!p>|A2V-5rLfaN$a=0;I%D%_~SZIyx!WeI3Fa1rMSWVxO*Le;%&pstj}>M&Xe=$ zu?r}!^+csg11P@wcHR69k+x#Jo6g?~fZ|;X`ji_3#qSk8ySQr90-Rg)g=)mVE;!Eu zNzspAH8C3`MM7dB6$oZ*-@AQ8QX&DelEN~Nm6S%D#Bz+~9?PjloCK0`;a?PEDM-Y| zZO+%<6tF+hIy~&`^ze-$&CIQL`xwA^Rx5$HvF+G?_G3Ee_O{3*I6W_s1OD!weREk5NR9H& z!2ZP*0(!BGzR8tRcs1+npGti%+KQFy@6-n73TPv}Pj+Fa6ludL`Bllf#NVD!O>=)2 zY?GCZ)+ds(70lSy?uA5Bb^(-FMU)>Gnp20lu!d5+_JVio`Lm!+na5EM1Wgd-pesP1 zgnpe@-aReC@bA@xlOWu)V_)#_!pb4s@hfMy2|{MAhP)OFAt(6=!k;0Ma7XyJ;Vy96 z)6(IN-DrNNmh0Dg#bl6hM>9H$`M^_2Byk#N$bf%Q&KyugznY$N1L(IuB795^hko-`$9a?h{aR@R8LZ&YZ(iA(=?8&+ zf#W(`Z~mQr7onQ=#p!ovL%93iJ|>ERaF-Aac4>eaI}~_;gnJr5Hr!cevEkl`CE?C; ziw*ZijN$(HUle00$iv2MK2?wt9FQ2edt|$VS{|aEBlAoteHipw2?`q9-grmI|II5; zy)y3{sDY3QuV%Wo^biU66kaZGOT-HPGDS6d+430Gz2NWol@~WmgAD!yyln^0s#c}# zm0PXW3{a$hnH{Rlg7*$xzv*u}75sfMtHb#r@aE;mndztPqHV=?hrAs}<_Tyj^@85V zlkjHc$E_T8=#X%K57jjH_vO~*$3BWkxPJjNHgxjDq4<#U6QIN@qJD9qIVCO4vDQ%Q z0e(E>5hw5?;l8m6Vz_Swc;^0zEwW3QaQAJ(GJN<4(F#1HP<04wJ;-OpF%^1iQsC7%s^ zee+@WDHjf3pLLLpc?*2?Fg1Io&f%+7DBms#_-b)!-3V6>U-gFxd6~f1%R}!S)A*gQ zAE25=u}gc-1$|g=N6R>ZK1diTq`re0+gBb!^r6G5CVgOO#OgyMmgoaZBvv09G3tZt zzbM91&k_vcW@31dX^XCJ(bQ^b(_2>0fL!^j4Xb>~DzUgzkPPD$#0>%bH>e)f2 zYXe&i!pzJ0$8&iny`?Ic@=$Gm(_%h7ed&XMP1kJ27wq~rIOGfHXg}@veJ2#@@=@(KI1VKG z@Byl6?(bniFLzN!L?3u3m_~i=Gz@?IRRBt?B1(-5&8gm8SVM&Z92}ade{c6ujP27+ z5M%p1z*R1DJD%xsio|ww6UNvc0qw#IT?Mg?UzyFFkQvOCK<3;miEXq>vf6kPtA&pw zw$b{xvAua}P)q;VV>g=LskFpp89mo|c+^mN`J}kKwS&WDr2INvPmmZ_YA=kvc;)bO_uI**& zO3uHNt7Bp=ufDi-FG~pKsR;w@Odyyg^bt}@U?!o^1{iNj_Xo(1NOpvj zmkYsQ&S-)d%r5{MD%QC?>T{9=b72$4U^f4h%fkyRhhWC9oF8h0v&lPFNH8PhJh&rt zekKWKgnt{%qYfTv>0rigG`~}mBRXx?D<;8=X3nG>Lgt+`FtMLX{Kt7pM=R$Q37Q@A zc-0HmEQF-?Afoi6!ALw8OvF#D!K641fwuDVWN*~O4yCd6@*fs~q#x_eMHntnF zB(_;1v9aBVF}7#@i()JVi?MN=r<^e6`6u!&h-P*2TrU!Y-#IzIJ&Elljcv#Fv!5HP znw}^06fm}phB009q)2S*8RYR+j@q543;uqtZ_rN&v8~cZpRR{pAcCDKYFokIL9@q1 z9RPoumG!!{6_#`dUm4U<8~k1PEm8McA)oHQ#AcaNf~`24=P=2$05-bncwL_65CUtn&$qNJ-E*9=oAv$W?;s)F8)Ab+Y+F}Dx$2o(41P%h1CW*0RK+|c}@m-ep`i(*KKSbA@$kY9fIi^YJC*&c{cp$O zk3B-pk3B*>1M<_HJlP{W+p{-2kVp8p`q1s=v6j{c>_+puy<~Y%n)7SWhg-xYoUFq5 z*G!@^veIW@na7)Y)&AmeVC1`?*x&|G0G5%JZBM>KMxNMOSMJJTq|DH^Maal6(?*`z z$YJDVuQ3{%fstW0hM!0N&d8}y&7dHsLR5fl4@T@(1O#T{M4>Mb@_T1QJ`Y?u}>ml|BIDi zU1Qs^{p=_Cw9G*RcMu36HGT`zwf-H60+{W}w zzx&89>vKC)k(QR}(RN}_q5yVKO>=*%-oGz3WExQb2QXt>SEy^@P<<6ZiB&{7bD=r4 zg$rw_Hhy`${x6-Q6t@Or^tNw;7`+Mr{Q~5S%C;OQ(W};kF?tX9=JD{t${~93E0cti z>~BWM9NHqk?g*JhIkJ+E@XBgQ^dkJ*=$&yQw56jLyV3kk9a=qU$ND!UdeO{`f5_Mz zA!kv|E&~4XhQTYZ1Dkp-8xYx#!=@vtwhxd^;!&?=26EU`dO&97bzswu-G&!TIBc5v z+Ta1QX^pXC_L<+=~zI`*q8lo3ow{Gwgl5k4+0`CC=Gv3g8SrWbb0kYA{5`~T4 zMl6Y5mMU!YHe!t41OK8JOTj79IGK?O!~GIxDTj#1%wH$sANM)U8wh85tOTbU+m7vL zKc0QRcI3~2qz6K3^%JIRnS2tx>t5vX^84-;jRk*~IzFGY75u%da{7ceaC~;j{;UOS z>s0CWx?>ilfWIT2kGi)LwvFGN>KI}K{%+e_s*`O#yiR)Vnw5gvw&EFa(TT2wFv~7K zYw8H__w`A($1=N-==Ftan)};s$4-ZnGf4CXfEn8wxs}1Pf z|KsmBCkK`plwoJmv2Cd^2o+#X6GR2D16Yx6zUsi7P@(|KnlLIr@^fGZT-X6n0Q|~% zD*(bXN0K24K3RuHcpTnX)T=E?BZ2UBl0*Rz{;dMI9$wSZ3V_{cez&{%PZZ34N5=PP z<~*z;WCrxG=>CZKkFz&${f|7}tqGUjBSFV)GdG{XA?VcT3fXl)&_3c#OD}Q=8oA7G z(nKKWBK-|L2XP2GJp1V~Hz4S>BLSwJe<$c(sK)ta-lTaT2wV29A6o!|AfX`SS^zWN z-v|XF2-P*nak7c4_=qm)oEhLMl`im?>j!^UkMnelVw&cxJV zeQv5uSR)#;A2~rx{j_qeZzuY#>(-;p&VT9D#q< zd(8QZpGj<^ne#)9keQi)k$WofA7>&Ct<3To$=4DUkk3m<`BjBn>-oLB@-T;M^HjFx zAlDXr)$=UmaBb=H-g(Hiwllv5D{;6+^^T51u9y z0b*OiCLwhP%y_$N1thk!0J5>o(uj@iMl6YKmPl-DH)4$KXaAxYOF=Pd+~QY@M(jvj zm-Ml(uZ6RyZcML{-t8fqh?StEvF+G?_A@@J;P%-!5c)!@Emy9r#=RK&!>)Aen-|I@sVc_&a(*t74h`kblMXU8xQvQ&_tu@(v&TJv8XO z+N2kJx>r>%e{qVf_-lUGIk&;z#hpDbUOx&ifjoP0(?E3++aIBt=KiMo>FqFv{kzbp zN-$$vPbQJrt_3Kuil}-nG^b>fIo29#C&0q-!iiDoff(EVO%P-I06@nx!nPg0944_H z(u6U#2SCwyVdW6p_%-I}XZUTthLdOrnRj83*hY9CeznKg-o*{|2q#5KVjJP##x~`? zv87`hyV3kkX>K>K==+VtHkvtSiV?0OI|N8jo7nKqv3Ok!IAkd1AYMr>?1Vo7YXL}FvR5o2tt z|BGTQ1^r0lj@st6@k#9dZTo2Rm8(VD`ade(@euNmSqTO-ww>`X^S?abXe7bJM@uG7Z?8Wy_^cbwv0B;buVj0#2 zVte$Aowh?E7n6PZ5~-L^0y=r-gE^MZ`Lsg%o%XjL*ovo|pQO|KCH$UmtF1NyfA>k} z^9Bk?Y`=qQn)|!5;YI5yb4hG}0W-EVC5OcJFMtxOh^pp7bE>@}$69T$7U2JBlAV)i zb{mvoplvq3`=kA+54)Qn>cf73v$C_i%8vyTeF$p8s1L)Sd3a$5Kp*fcXGI<1&9z8> zvV9IAC({YSnZG3ZfbehiVU*scmevRCM)SM9KTCC$*LR{1Xy*L(BV?A@AXnQX;y+Gu zw(nX6ypZ6ID~|&~#b3S{6@ehI1l_XsV<-~TFO%=woZEa2p-*3JOMG%rRjKQNRiY_3>41wT+oB-oH?|$y&wdo% z{xJDz26sb9Y0qZ5*1HE0gjkyb-kU8;`i}>HYmc>Y=?j8T@!9ZNz(#xVhQ1oJoWS3@ z+jmaW0e@>}_8o;eWGDH^KbZsme*4}z!Ziop^gMH6ari@9asHs>YA^7&yw(0UFGAq& zr>!0|UX=(!HdNEx-|xL#b9G>6Jv1s0%-GiVpNSy60w}SHs8TL8rz*IxhFW1;z!Qd> z^!@P+-knlMIX6KJW_N&X9(JGE$tH*dvu6{=VCF+vcwyxb%=ncv{7wkC&M)xXY-m)Wdy_Shkf!R*u6c5FZU*{3)(z@jJo z_zNjf7}K>Uy-6_ZUM%4CtB7p>v7;JoZW;S#90aqTO7>M-PuSD8@$zBN4|ky{q4r;d>;6FY@0V{PG-YiH@B*n>mJ*R``+*TG7tP6Ep2b&4E`?fmpjNs znFRAhsHVBUbtCw>4b~)>r-2#UdU0`od@7%Xf6ZD&lm!=>Q;WE;hROx_qwP@*pO5=6 zn2Vbr26Gue?WO0^EQcN%xSn!e8X47|on1HiR2V-evMrjF7Wab!=JzZ;W++2V|4gyaH2A z4x3&*A1J&FY)Twjd~yhfO`(^A9Fa}NZTSiw95&I~M-20UO~c!{x3>A6O=eJyNosOG zTZrDuej9ZyA$lcz5mIx(j5jo_FNxk20NLneiNZ#2BbG!jOBFVH8!<+&)4wRjQm}zE zPNyz3-8=C`z)0C2ZJk6Rt!~vjZGsegRsxU4wqyI*kETYod%AR6jNa+rn6A0?C()}} zTfl3tsJS~B{QW@2-^2#|eY4=+me-r?>1F-iKTw0WI&8cx6K@Xw-Xh(j;RO6dXV0{` z8S@d=AHz#%?sfQ<)~VNhQ@Jn9n!U?Juiv8Mr1)**ZO%!?g)#@}}tk*M^^v zzEOMRH?B>EYOHu`HezgF4bI_Bg4mX@Nl2N28QV8)Ac^e-0NL1PX~f2MBbLNAOC&b7 z8!^VV-M=WtQs9V<6K|j4cF!v@KDmvLuJa0!QLobXTFW3`rj=l2W81O)?8msr;|rDf z5c)#uAkB2G=U@`s1B?rKQyzqFG6sK-z9Y5I4g4*t-8yj0M#y{dV3MUh_A9PeQT-c~ zAu3qmyKfNDhpHxs`XDu>kXLcPOV2eQ1BpJgYr?1xt0oun@WKv&KHyhQq6>t~8(7KW zI6`Jdp3KW3+^5}-9jYVzTYaF$n6|V&U^klI?Lb|%+3B@JAJEKs?ncO*8&(h+u|yD9 z=CFd$h*1!d{zWmCf``~R+F{}J;w_15=PXH+Qd=&1-YO`4#KzVr2#*`vj_qeZ>e+5> zXB2{72&vdTOxGT16G3nZD&+0&*Dj@@gBl&@sA3TS{ zI8NXuNiZY)+hC6Ko7vLAjNNE{ry5SUC!DS)!Hj0^3l9J?NjTug9#Yf*Pkz6U#JJ;)R$aVkV%=<{L;2}mD z6MrYyEU0F1>?8gH2<8k*mi6``&sy1;c3!W zh;>M`m(O%_qEgTRD{=Pi7K7W+EJ*}kKKIX+flP0c{487X2Eoy3swDz?p_Z?9Yw-88Ll?z- zITFk#p_=CYHWKO?+1rs|J_BZK>)H+j@z?!4K#5gEMRB1yb(0Hgr~z*Zd7d$G=TDB> zjln#m31To02lzz3%cgyA0!T2AZo(MMwWWnTys&ZzX8g+8>4Grl6eh+bX)+P|-zK}# zapaCr{gEV?5&ms32R*lF>0rigG`~}Ece-w{m4Zc?NYZJ}idmCONH8O0UN?6Em&g*@ z6!A)yeO!j*nw+)rnJx+ z{w@q=vnGhaJO^N&f^AsIuYDw#ZJIC!^V4BPJiM@S2xk1snM6a#B#R)!Y=q358X0CI z{Horc9cCl^+h9%!p3~C7jNNE{r#2ZXl~AooFr%3>%ti<=37Nk85J?_~Fs{qC_oi_d zF_;TXi+E-yz0Hwal|~a?PI1U(8XK5|o$GEA>zQZr}QlIagXMw--zl<|l3jTh7|D)mI99wbxWX;eJ@OS48?M5yFe^1RV zeQer+1ao`uKmGmWN1IW->`5^5!HliFqep^S08nBTQR-Z1P7UJ18Y&iGO`8;Iq?a$5 zQ)_}4%y$5KE}8OlMjs}aA2eYM=3&r%ys&ZzX8g+JVCAj6hh+vA8~I2 zRa5wPkB5t6iZXN?%ra{-X6Rn?kU3+fLP{C7b-DX|y5~I4zI*TUocTFvZRmCG=fuCYR)EEPS3eX?-fp;D zdtPB*HMvqv##|}N^m8BW$GqL}XqmSK842E2V5PSOAqn1AVDfh3%9xG0v^8d<;=Zev zWVCDO{MFqCHtA|DyA!y&^X5?{wC3rmXTW#J_knHvo#FYVg|Slbom=NY z*z?%>@}{0YJrdtqgnLA37RG^Zd(EH|THsr&$;VA~YBO&aVln0Ut`bt$&2}F1b_vSV zPZLs?_ewY{biW)VGJ5iZ|VT@fj)}%xfA5iz-A+Nf}#sf2rjy=%m;!M&4(#E=Kne$ zs2k;f?YF%a{ghT``9NjS$ep0_e)my~KcbRe*ea*0=yFnx&k2%WY3~k^UMIF6xZ{~f zukHH&zC(IF+3x$+10ub?jhLXK3BCR>o%8&r!J$mwJEewF4Hj!s2HJ z<%7n)`Cqe<4@yNEbA~8W`$qI<`7j7j7|07U67oTTmH8kDNyrBUrhFJu8M85$no;B2 z9}O{jurl<^LfyqR>R8EcT&Nj1?{Pcp4h!11Vq;VqaTJwP{ zAKo`hl>EGWz9 zA>=4-FoQ;YLz&vzwYn~Cl@|gkt2oz93~{bob5XU3TMu}$k)2zYl#S$V&oW5f-U;~N ztl0_6jBUKP%P@JnGiFV1S~$E-A4N~(BB;Epx*MyCPHmy8Y4wi6K%QVly?yp{yMOI% z>PGor>QA-w`Ri*iZ&O*ci;W<^c4r6235u>R?bkO^QmgtB-CGbB_hWxQB2J0KwYB4#gCs87PnOd=ip1qTF>4lyD|yX|f(L(#YZMl(6_n45?){l4D^F*DBt6wEB>MliDiE6pq@M=-MjlbPpN#%#=`PONc*9vRuVgl_de zX3(qH0 z?(yyDNcG72@@iH?`@eIvmS3&jB&0)C4SD9U`D1Q_@B3?JhL6Vp->%N~F6Y4a&!F20 zx1Qm|)zbGFecoGyUpB0-I~sgPo&U9e7x>ma@vBWhO=ji=SWJ1oe|E`Bik#2PyaZ)x zYm^-`^9n#^RmQo9p&7SD42w9KU81D$$jegg2OG%DL(3qUc?@9ntlIBitngxHo>Yd( z%tsd{O6W}shneXky91#Y8^{yQNe3j6 z*6!UhsdrhVHTz~EW~8+XzBbcNinJCusE;XW?PT+qNgMvwnl%>Vbw9lqd3)ldg6!w; zwo*;ToE^&abNdcs-d+PJcw3N>;B5s~dRq{Z;B5saZ+le6Y|N!QsB!L9Lptg?hYo7^ zE2(e8IkLCs>|Afw`c2;6rD!{~UwCbry{J*~Z&)7}#b4&T<~V|RdwNKsq@I3m;u!Ef z*I8|98+iNS(Rs_l9jxVgmzG)01m8Z3T6;eL-&=3H{V>J=Kk0UU2Pg3DBfa9;2Yipb z8xlC-gGG216IcIr;JerDd_6PpogJ@XzOM%Jwk;M@o^Qjv*bDKvkqjDThcdO*@-6eW zBcQS>em;#~InQqsy5h z7zcycXeE{oe$iix*38at6D8eCx>p+uHTif?HmE03(FXmq; zAopHXw4K^7ye@uxyUEA{=EfE5rF_?#j%Mynt(7FfQ?(B_1>eOR%&&F_-`Vb4_FP+H zE&r0*%4rAq&aLh;Cl-8PI()35zLT|l&=0SGf#5s1Yrj|FPjTO-l>OebK3aqu4Y;~7 z2z;AP&(3cGzE#6|ukftS-1`%YDbII3^-J3_aqBlUs)$;FSCs*6X_#HLc9KL{#SIq4 z5I0y9!y@hspl@3zi&yJC$h{ZKAi4J%pv|VEs;OREn0rIYFu7L^3#K+T_~)vD_?>%K^93-|AMN?Oa4 z&57|7Y0W$}=rn0<-t3Yub^g}cIV|R5udXiSZ7*AYvs>`CQccF(6_lxc(@sKb@S!n*{EBVp-ma;8NW^H)x^ozXx zTG4iDzwmOne`(A6?uF#-ccT#RvN%0CNs@Bl+0WcsI2NXNugwtfJu)X}{SA9- zx&MWcpTofSPRB1t;=p(PT9WE`zPUWiSuLy)`1Y3#T{;qcKV079=lkO6k%!ap1W`2VG0N1|b%o5^F9DTR8TVQY&A1v< zMAag08({v{b-#-@ts`%HmqGHjFJSt0Qa&H&cHCNrd7H|jO=yD3 zu}h4IKX#||)TK$1&40qxKSNv*8mk8zio`Xce!tq`5Ld5^kp|C1;U#jJc{#{O?=+EHkqdP%yKg z8^O#9tTeNr9Kp;AOlH=qjM?yP7# z=~H+OxSjN5U@5$A%zZk}Uiu=*Yrp7<1FR$~R(;k^%5x%5k`_M+8r1Dj- zr=2_lzB~Ir$~#hxnfW^wQ=acHt(rG_jk~p>QNK~9w(8AkM=R$MyF>Qr48 z2vp_|f8!*<2u7Ilf|Do)MVsOD$Nb3PBpoYHy^|#IX*#!%^xD+FL3n?WUNi2=e~@0+ z&%QVLok*{t<}IyAua*~VEFOvUTDxkA1?ly)<<~QZ|JLhIEJo+Z&P$XJGi{HipFut- z6=}@C`tnS9yfBFl%;e5}B(XFv1?-+%Pi zADauld#$oI{A6b>-}BQVMx&aBJi4XX;cW0-wBI#g1~$)Mj_en88+;$#vZa+1`2LW7 ztH2-;Pg2-=B}N9mn?8N@(Gh%43vSXlq$p^Os8>*~M*O-hNYt$=iL?e2riS+=$s%zXgtkj0 zaSd=d(S5c^TtkX|K9RUS512jA_HS_&V=*flth!HT){pPJ#202($_F=kP)lZQoO+3w zSrbrL*$cW6%&fplGYiTQ%&fpaA^=KsAj^2fd@SKxJH?tV|cYkHTNnd=QmmgqLP8o3aB-}&4n&jEY~*sq>a z8)i-)5d@%G}ugDxyrkZ?!;X<{^NBnFZYlW>#RO znFZwtW>#P_^RUX8jk$CRHBO$C|IW)HG`L}h_qICIWz(t;d3#JhpUiBoXgjrEc)51( zYg^kFUdNT88~Cohy~@n2z9U&OG+OihVDNqRu-#^N@ZH)n_;8;^*7CS_GhOC^ZI3~1+f|Ig5GtI5m} zWsuB#AMi+Uy&D7kJeZkd$}pLE@%Cg1z1hMY85CVCLKV@S6bbSdf`!xhVKL(I1Ph9cg(nS+Zx_ z>s-=W6Sq2x7K^mj&PUsewAOQo^O8J~*2bUvl1o~vmyp@`m`H1>LEXGaYgd+K46gIH z)_P$vnX)gr&Z4k+)qHZ5KGE{|^qWqO-vl);H#AyyUyK z_6GB|O?u7U60$4X|T?^Bo89pu=0v!)!P5cKb3& z-ZlVCX#92YnzQSew|kUf^7e_3$r5_g!m*;JkNjQE*@10>{PrSSQ4U{ zE9!0cy$%1hx2YTDf2ph=gL-Xkz`RXm(dp&{`3-Egq9(`>bWYKzdty+Gb3*@ZB(Ag+|jCUZz!FRb!Hhl<4IQ2O=-iR)FNMbCu4#Wfd; z3GmA-Av4E*d3D(6_m|K7{{l1ffnVDAs3T75`BbZr%m1Y){BbZr%$;_^mF&lH~ zX4W`)ssCg9P^W$0U9q7Q&?hlmr}w-#8-XP;f_|(%R|%ErwqETWf2vm_0SS zsLp}64R21W`S0{qHNbaH zt@jxL;Ct=yc71DqvIt+?Ek5Zt_zsNT8@C61Un@Nyn^eNQeF=*x&-c98e%<#tuoZP6 z%GB2INv&x`9So?f%D7u%XvRf}VG-AFWs0QM(up4Gt5=e@2bDqcwkhDgn>qW_qSi2P zk1NCE?IhU4ZzmdQ{cCSiH_HD~(QRc1 zd#W>UQ(3g4CKyZiud!vPlM)o&k7duk6p805cMB3%uf6v}_lm^j5wt9l#PxQUXJk#0 zxMmD`vxUT^Gs3mmagn$ty2X4UaXrqN=j8RbxK3a(F5`4`$jrmvwL9qqGb`m|%$-M> ze&6#E%*?j|1v3k}5zMT>N;3<}5zMT>WahBSmc!B1zyK7`%u1X?su7)k32-uzCC1n3w#G^+zJf<-+B}M z=UUoY%iFfCvh^$YHt?#}yD|9wwj?qo4qMuG9)r@-GNtmCJ~pl9fbTR_r^rBALD5Mo1hp5d@n%|-Cx?mnReHnQeJ1?KcnH3;=GI)G3BKQb^Eopi)gruLk+z31_zoN|FB}fO zX9o1J-dD_4)an|a{)6w^Edr0m^WN4%nc5oomU+81pt6eNSYl|#brZuPE)cNeJ-4*@ zm=)yhn`Mx^9R@h6)gO6{y1cg^lwtCAGjyNcv~YNvKJu3+g^;%i4q^8+Wyi4y@>hl2 zr@dta`xPs_O|YWg-Z7xrzxFnDqr5XFd3;X}Zpc>DR2H3(Mvy=7he3D@qeQgpJF4p^ ziS@XF`XnyvxLRHOMdE6+VE!W#*AlP(=8Z(+GP522oy2u|&#>loMdE7Uv3NU)YiE{) z*}%WW^$v>}^*+BVnfc&K$Er3kvr<0BTs+G3`<6arW-bL3%q-|eFtY+H%`7NKFtY-a znX7cGgxQ!&>tQyy$kYAQf(4<)X*bzSpa@%xniUzk0sTsuTFWI&SZh7T|lBUN4(t z*lkw#MwO)(z_*=2-4!n$*OzY}U$uWO%seM1aN#8IJyB!x%y!`W?3mc-l0VGM&9IpA zd^@g@_Fj(XmY`9(C{vR^d}U_t0;sIwIF=aVrifx##61GMHQ)MJ1E1w&=GZbwW_|}~ zJI8#@OiwqqqE0BoWahzhKS}6K3x}EMqv)VC!M*f^oFZmsg8WK~nVF!Ksh+S!O|YV7 zep{{izcw>&bRe$1syGG2+R2Gf8365p~hlA2lj6cy9HC6dz1vu5dmqoyuPm(qt z8ZIZT^&NZR#|@FzR(^|IOj_&PZfa94k=Cxf9_U6|b9=w@>3xybYUTV`Mq2xrV_LiA z-&%{nV)6^Sn~=9#jqBlW32!UaWXwgOOh5OzXy)xSK*8IBj0A5hu+rOtkOXflFnK$p zGG=2g{mB{^73i&L8+x$#%E8@{X0ow0H+1Y!oJHO)P_&)eFT4u7HhJc)g7vsDSMMC( zHMb|s+r?KtNp#{(HLbz7`I!F0pMvixbLL#yYhx{c?fw1S5b*7?CCx_{d~3VA=rw@1 zd%iWFz7u@kO4yRQ1AO0733qWz!-Gb)SIb=jzR!=Zv#196UU{tH?nS(}RRjN%?_>I} z9XULQ42^1tGPSjNji$6ktqrKG%DARtXvTFE!y@h+;Ol*c*2nFak+%cNAbI;b;McU- z`d>L$=IzijOx~V|?$etV4sX*(ew&#M!U^(bW?R$**+VtD+@TdU!KDY3-X>U4Z*%_X z4Qf(by3Xq*TdtzA!l%(=6a3$+mi8X{Km2RyA^QKB;(t85<`H3)t#(TbS8LvR;fJ$No&zQR}MB8Y3+VHUn|m@g`{<=he&Jg2}6F8 z){5u8u~qq7Yi+TZwZol1{zs zg0~fzye+Sc*_ca5QRCbjG}-mUCUkdj(wo>v<7FeH9-|UYXOg!^E7~q_O#g3u)1vO( z9ogjVfxq~!wSUgM-LFcjS_mci?wbS>i%QZSUyQdVf z^|mt>Q=V_hS^EvUcyF&onc69_XWsS%R910VOAO7p6Jq$gU-PP||F@G(4O=)^&eeD9 zU{J&vVIG!8oHI=)IZ-|smqE%0IiPgdkV8iftz`KyqzqF&*r}vS=uI6!KF~+e+2;iL z`=}+;&07eH&S4?AEnS%p1S^^kD#cm+SM@gW*&Yk)W5eam# zzPpqJYP2_bPSW239e~B$O^6#qfzbU%==X^T1f>Lxx#1|&?_2zW1;TVdArJ)J2!Wu$ z%0Lj5BLsp1Qy|Q&jMXFqZoO`O5^ z>Lm*d^})Bwz5cOP5eTKH8#kT>zQdm{+T0j?zr9uPW-9{WhNn%&N$~ys)uFLb;CohT zTz3mT5T;@=<@vsqts2`H4=F>V7NSgT{rrvv!cstG6&HDmp&7SM42!t$fcZgo<6QAj zRG9g986-1T8Jj9;`Yq=3GnorBbB!`gX5KeCRYGrCILu5RMfXS~sC+ho8>{llW#_O^ z^;&m*VIWViqGq-k`T1X)nf1AxGtQ+9T0OA|TiH`tv{gVi5KbgGU{KYJfvGBH1O~%|@l&O7Z-Y{=F01Dm~WF&Z7ftB7C zgd})dfyvvBl`$K0sVgyNj&#|pNsCcYwmg?u}Zw%7O+p86Ar}hi4-meQ) zLb73f9MRv+cWu=>=54dXsgfBhJTtYy_b%_abD7|K#M5}oy6|?X)Ap-7!1t#Q{f>48 z-}Q2SB(BF^b{B)MVMD>UOQHRQ50C20AMF|RkjtS5{oI%xBp%9h+Vw5-BG5tejM102J#yLl~ozHNes<6Z!s+5)O=GVzlxe=)f(nV z-j1~1)^>*T+Z~xlc)Q$4LRNRSxwi&#)sVo}E6Qr9xyEMW%EK!US(R!PzqRYEo zgHt8dy{x~I*7i3UJTXC}wKH4hhmh9hHO+U@6KSp0;79jKYwj-ZOJhY^yEh5i2hT`_I*mfC6L?Qligsr|xhjLEUv&X-_) zWA0EA-?g?MnYX>NQzhra8+lg;-`fm5k9`B*@9rgC^0u~?-+!K8avFS3scZ47C;0YB zD$uJBZ%^I1Y_}o!{@~rW^c48+bELn^YIu9;iHXI}!S`yDUXoql`%l$fyBG4_K8D4V z=exy|$&R(~Kw&iM49e72ZGYzNOMuEMZigy{W?Y0A{x<29^WO&YT@3UL3|cJGckJ9^ zl5_7CWoXPIt9h2aTTopzlJAR|B(7g)nlQ0yo|2iP38|8m){Y=+ujv83``_!c}krfji-A_fuJq&|;n#5m#g8@JcgQ64N_Ht>G z_`@R(kxHYDYDTAvR9bkcL-jLI=`YX2SwF&lGfEH%#k(13w~)}gjKjtA#oA1(Ve#pdUSpPwidUZC6}rv9d9 z8ht`XM$PI_xFNjXs#8*nJ{u7l#$2R6-?e9nEESF#r%4LW_)Pv<6Dj;~XOBYgz0Bc7E_+@wXy@#aQjwDg&>rPZ*^&NTI1gaR90nNm>A-* zfnr$1+4WA7I2?03@yBin8QKZ3;oRQ$O6``Apt?>zp&RQkN-&K*V@d>K6Fc3!b1S@LjP5lb~wV|mS<$tMc=U*cV z$j}jtA^wr*?4TO`wP>AwV^W$VL1H|E)U@i%xr8qwHLdHJ*NfD2@Rmt?TE_@#YP#qC zYEn~#Ylq)9A~oH)zj_*}>Gm17YmR@b={^?oM7yaixi@fK{N4U=uTn3@Tr|q`gPuxe z?)?ZTxK|L0;9fx~f_nw22<}x%WxPDTGG=2g&18+cJ}mo+Rp@7(;C(f_j*>kJSa>oj zH-+4rh4O=WrvN26^uvd2b58!+A zi%2__`}O6UicY)Uw8E3dw#80;2EJd1`uNJg_eg2zA0xPTLRQ;_9QbZl^ru&U@a<`{ z>cX^4i|{t`dWZjj@1x^yRI>oz=Zz;@?%>^narf1pf!tFC44{R611 z;tAhkh$nn+5>5K^CW;XOO;R4Hk76wGe*sEk z7!(ZsG34N=UyYGbYm%GAa&X)Izo0t$)~geYiCke(naL2QDE1aV=rp>t)- z2G147Z0@-K?vOCGmi zui&i#{U<*H-`*=5e{KN2?*v;Hg@9K*lcAqJf$zgt4{*c4x81K{7cXOa{OZ~_e*Tck zv%l(f&;j560Zl$=fmf@Q4F;>_OXb5Bw>>=ye5*D0+CQG>dp{Oap6?dwT!1N_TaMg2 zj56`vHit#bNkC;)#+?>JGw!Mw{x)g+`oBhup`KCCzaqwvNB@1ZK^HSIeS3e{>OT#6ZpNjboziKKTQ%ApS1e29v%?#>eK{vNWP{?UX9CmPUq0L^t#cVG~~;Y zl0r!GTlVRUJBR5%wa+Jhtgk6QJR)p+Q%HVPzXfzD#J5AVCT)Wl0V=C9uA3N|aRbEgw@D)4e;LIX>KXsNXX1a1n0(CS zK$pBus~6!W*nhYJzz%_~ntEd%P{jNJ3{UW@-g^_OC0q%hnOa)a`@K;u<*MnXOF~AT zXt)R8rHH8xyl>OpsaEzcS;W)=9{5c4{b+ofBBlMrH_D4;QwRON7Mg4n zLuDfCNpxKq8^!oBTErLL<1c=;r~78$gryi(<@c1bYku1HPnTrB?9k}RL=Cx3y7Txp zki2E;ut^&s?RwGg&eu1?8A{6nQpQ2@&a#1h*J66jQLA_U?x86kQuS`_LP&n-{v87v z;Q?eF2I+U`+f7q`q1r21Ur4@cz?W`KF&&ccfyJCzUPEhDiiZ5o$$D34W?7aZWrU%M#E##}EOzH2MKu!xCRk}i4vDr7(!nHvD z&GSctZ_DDwKRSSK`!Cu@Z(=(5zK_L}=X=ADz0Eb8*(l~A%EY&K4=swA$AHSJ>~Cns z#fq!HO=>#)*N8FF>)!2uKZNjM^=6=1i-KL`4cV-eE^aFNlJ1zo40 zTEgi9CSD(G_+|i$n0A1NN`~w?i|xiLllo!jJ!EgJ$ zb@ktRD#$95eec##8k>`%%vu1%?#Bacaq0R!W(%spU|%5I$7?= z5vJb3i4-y7a^H1)x%9oFY|PmN@m+iM2wm%C5gC>)nNX);)J5>U(dJaILEyV?Y>xd9 zJOMheU&k6f!MDb$20F9B_ka`QUk||aBd;DTiv!<54fQgvg70s3izgff-z7B@0_T8l z|Jav~THyPw!=iVm_(+e!V#@RVa@>X%4t&HsMw$4&ew0N_44|?qCgmt@y`aWEPpNMU!rs%c;>V+9SBx*0P=9{%YU5?)Q$4LbIW#zoCj)Q0OH3w&7U5~jkAkFMg)$9L&DT` zX{RwI@*AdSrJq)P>#HfBxkO8T9nxHSF~FxDEI(W;)YQ^PQ@&Q^@eyrE^YW<-e|0_z zoUs_4)RdvFrc(K)ch3yzpo&s_#@s5D>G$=EW>K&PP>`3PIzdo^&IAPs$`TYKC<#%p zwlZd8E?tk=EQql5OF1RtcwcKd*K%Q-EbCDwzUw)$5b*?5 zR%M)*7@Bd1#1O}JX8b=wq?ckph~j*W|8cL#F3d!2{GaIJ#i|q{djKsj$2M)7evd-r zAfVxZO;6)oP%Ytn0DrewlX)cp)l%*#U}*0pLnZdAEJTh0KlgZQzO;5U3z1X6y#7%~ zh@1w#(7(wiCzWUlk@wRwB=n~KV^BgLMW=caYe@df{1-+OAnk}c-Q<=dr1JLnon0Lv`NtD$Od5~roz?Sq zM|RPYuUZ?K;Reb3Ogdbc3~Ae)AK7SICoQ?YNwf2%kbJJBk2ALFX)E0yi;?wwW40wu zDvz1w+Hp7{Mk#7z?kdXEhmsd8Vj=+r#R)af}=a`L$ z_WJH~om9hpEMK(pS++^0e^kFtQ0fPYn3pI!+oHUMM zdMDR{*dXwI;QPaSmf-vSqb|MnfLHyVyK;TNce8^Z4ZeZz&d!go@8$V^hQ*ZUd(fJY zj`R75d5tphJ!%_^m;^v&RmLTWp&9p042!rG=QAWdGzQP|hQpB#D*-oUNN)F!y-Vrf z0eH7_=aujIbl3oRSyT1$?nkJWa$5nH)wI7s0OJB-mo7G7Sh;G!0gK`R8ds-6;RN z4%X|XWkqS=$2j00`GE%>M=+>7b0msE(aE7SFVU?QUOmW=^h|lDx$z*L_Yu`K*a^yX zyVG&y3@EVAVaM)^_DkiDB)dDUq$Id^=IJy{zdUDsN#IH?xvN3zu(?pCv&FP^c~IcB zrp>huI%~-r+^FrJ2W9R*wle%XugnZACbH>V_l@l}FvN0F?neUqGJC+1r3o;~Uuk`KW48DWL zT{l<*zR!QrU2z7y-gq-yb0zrB%_=N%2j9QG9gjYR>1ulCTbu^p26s|s4F}&NyIO2G z3tn5A-KcvOe0OTSqhTueUbxi#t{=~L)x!Ve+ulE@T_B$X%~2-4y-u?v=m4m!%D9eV zXvXys!y+yOuwMU#rVW>{BnSnx?UJ#q&BHsC1a|?|9z3f3flq=5fZOLf)ogkP)lx1R z@bHF`%~E`qHa4CBKYcu4-<9rBED2r!ck(#)`CykQN`kf^i{8{!BmsRKz)lRuuz3Z8 z{Jsm81XSg3z{`?=;E)7m5)iCt5)8Zi;a`sns2k;d6gc~i`fWZ5s4O~7oZxt7b{ras zVuTTu^um~cs-pXizi*r=k&MVISeb#RdWB@x@PIN`*}OEcf&v>YF8$=1hKGnWZ#Zu) zlo_?Pz<&;=FN(CtIUA)VAKkf0kC9O3NB0v8N})j4tVM7A9%#vXPdVq724(7>^IB46 zH5(Ir#bR1s(;T^FnWp@S|6TQwNCKtyjJZOTseR+$vm|KTBvYv_L3Dzi1epl}5`-lP zNR$N9%9xG0v^{3?XX&Jt-;e~>J+IzUEnY9{ksUeZMU6O0f=(z0rE5-p2krNm`_1!! z$_Ck@Dc>(k>Y!}Q74+r1*6t%qg0vx-l1tB<$Jl{y!}&Q0+rW2}>3Y5M;8oHzkJ}2q zM_u$x+X%ij7N5It4%1Uzqhk(%?|X5J#~Xp~9f$K4-2~sgANtn10lqb?pB#AyzLO(A zIEL^^@B@n}&v)p~dAfys5)`6Ld_M|hNuV+`Q=+WOxGG|3#x)kh2Am9VoL*Oc=v~C^ z1GGQlX0(eBh68{akDm84eHuZ*a0GBmv)Vfp!Eg-lc9$=kK1QKh%AE$B*lc(9UPUmR z1&(^UV$O}s2P_!;fm^kWcd$#wArjo=0j;JtwH(1fA4O-A66BvNlt@Dag8VTKwoiiK z+%Ae%Zx1I};b3t5_^*S3x>5dTPJUMFMtvPNM4&S72M-z|5ab`k#I6k^C>kOV{9gPL zw|mElFTE@>=VVIS^?fg!k3)2u8+O{c6GFAG(X(J71i5O%#g*%Eh|alcXW3>5b#qLV z&jL)Jk-kyBS3_H_v);d2cL=rqj@1k6A^@%!ny zfo88lJ??4Be^;BcU=)HuDMe$h7-jmo|HQLkP@P+*EBGm_4UW}X>}xbH-qo%Bd^ZV0pAhpJ))x!0M%QZuN?-yQ|9fs{seq4xS(?6F&_+F zv6%9F*Y%kl*$3y9p;5h2CcZVNHm04LQvj7!88=M~%{V(TEaH9xE|5MvtLDIl2*rS! z_v70&`V>w{Posawwp(fzI)UNBgC7@c$)dNhunxEPj-=!f!1KrWo{4nGgPk2@HYnpD?mNC~D?hO$ zP*2H}Y&%{2xexe0F?OizEckBO@tw+5@ETpx==Ub@ogEnwvpvG4Q%lUB;Xh%JhSdO=DhP0VwE4kd>eqK}do`1nCG85qaIE zGG=2g-Gtf9AEb8ZBE0VTdiA{h;cI0@PaJM_?edzuz6Iq`zWM8Drj&@k zI)L^3$6x6VUVO*}qqKy%FGBN$)$uC!<=*X##pDU+Yk)@VYjz-Emoos^vZA z^%nH);v1(Ur{Q=5o`GPHC80Mp6<(*0{7%3iTI&7odBzQ-on{dE@ zU`4%tG%Mg=d!4#b{&%g}EHC#nzt*R+X#7u*&HugF7CrjLs4(>0iGb>ina>nb|( zoesY=e?pnJf>d7{!0}H88})fqsx4n^nRht^%Cy=)x4jXc1oN>NtHr%;t?<{9&+VaG zcN~&HsXb%P5oP+he`m5J*a9f1OAwu)CqZU{fCOO)0um*GXJyRBT^W+V=IgHfy-x(HhzLp^szg)HpDfY;-n4DOu)-_u%!8XpDUXQs|S5RB&(=-?-+WYs;0ma$%DA0ki07M#;cpWa_pFMa)S!WxTz&bv!>QR=Tm9j*0c$SpYOCJ!7R5<( zz@5`H<8^IOE#X=M>Y9D4AF79HDW?mV*w1CyS$vnBLJ79eBt z_%T@3qgJx;|@FJ0q~WT zGG3@!(Ri8C@9Mvf7wSfNv3#o2apT7!Jw5n&P%=8Kk{XKdJxmSz7XsG3#0$gXDKM$lvIM z>5S#Y3r#yW96c`=abd{{8=K1wKf4rcGc`Pb#P3Frhg|ac{eV6Z=^A{E|8)LF0 zlfPB%)f{|3bzagt3Vgd71z21FuUmKdPQL)YJGOp0^%VFv&T2D>_DL3odCeaQzSXx+ zsQDCpS5FTa{|-^2XW3!fJMbNSQ7%6VzIVR(9!(n@7;NmtV#@PfKWDa^?ka0`tr^P1 z_qD1TG}t%=sI1~zGch#dg2b?hYx^Wia?G~gw%2?*v5n*S944$y2H|;H}Ie#35$N=+msG{fva|P zvfT9(2Qk#Rx6v57;7v_OI?zX6=xp#okUuK%kp>?GMbB&@SQw~G2Z9w%hh96b|Lb(1 zZj}F>hg<27SVHOG$2bt(VV3@y-&@PB2_q=Fvi)FImgN4Brgu_9c zQSurcdC8D5I_DtGlR=V?I(!uPVKKh-AAVeEpe>iKEPOg1QJ@qb9)5r_{l25Wu_%ZJ z6yznSP7su!GeJRuvINBlNYF_};VWS<-XxT~w{Z)d27svU%`< zQ1ETsen(F~@a<$_b&vK!cKqzN+!TD@y}IzjZSb8JV7NE~mcM)RO>8#!9%mAN^$7Uh z-e}of+8#j^aC;M1shuct3AF~W4QMX%9HJYAq%bYhfiduWbXuQ zUKknF(hJp6&Kq#RWUmI>@Ld{h><9L2R@ma_XFgASfS1>rvu-55O?h$>*fH(X2LB9} zCqK2aCG@8LBTwifzt4@`ex9J{dhvqE=+>bs@;W+8G;qfll`f||2j{o8|B3^ zDnxtkMSiqFWg^R{?1BxNBsv9xAio93Zk|C9hE*#r$Lu^KpK*r1rZSK~nJDq{Zl<_u#wHweahQ!0Q+r zn_-W^cj&7Re*WOQ_qEqo4q|#vm+bF@!T0|9@$!q{TbBB!D;?1^x;=7Z0r*}W)5d-u z_#SB+8hMN7`!g0(p6`_(j;LdN*txejk$c3seQ)_ zSmJOS%LFLsQjnaWL_uSM_5@7{T0`R0u8i5>EGx`LCFa2VkGKjo|L})n)$T2n`Sok( zE3L{Br>Uqs_Yhy!?4u~-+=`2Q*OvcgiIZ|YTjG+qH=-f<{=DIPWD58`5zx1>GkDcI za%tZi@O?PsdGHnRJ^xgKzyqobw{^YMt5t1BQ)qZI_b{ z+rjsu6%*Dj=K21P#gym!)j6x8AU<&lQ6|2xePM~CawA)!tjf4*Vra&xiQ#V(XTblO zIOXo8@joVxCuZ`;_O#VIQ+6+noq*S7)EGWv`xQzYZ@~S<8jimwvwLam11uWaZpBCs zR7*J@z~PcA86WXoN*rI{?EO>QjO&A=FW7~09C*F?oxBo!n+M+`=2Kcb)&pkdQJ>IsMCz? zLZLE|^|0(-8Z=3?-9%7>jSSgI8w5o=ZOb4_oLaB4C5KySdp5*L0Ux-;X`kSLV~hB9?(&^-DzC1 zEdhM1w7zc_1il?Yi)wep^n{1sPxS)d2b=l^d4X>=gAsmD!0XIr=ik-^-#TrV2X6%5 z=2nYe#`1hm#$w9zz4_+CHOYM9%tV>^K7OGA?NPA?R90o2jToA7E5z`(Njl(vNu2-1 z4Z=j5QAL=^pW3#o=MDKpW1Lbz+h;Exh1@ztiBr91j^x8a+u->#P%YtV0!p8*KGyjp zs-;|Az&*YrGwktQN*q<-Je^thCbZ-)B2foEWpiHYh;LKkGzOl3;Ll;tD(oVXWz};e z^rrqJapeB6Tt+D-X;JB-6(f?NAO*>Xi&er|Iv?j5EkSE|^UGe?=4ef*?4UFg0DP>`6Q zJV8`~)&vy^>Jn5Vs0o>}xH4vAE?tG$7;nEN%fKDM3{Ex*>|`=dR%393;vNTawd6FZ zo2YDkoGRj20{ z@a>{+^6Vz~)?5;-YmMn9nTGdzfp4eF)vvmN@21=1A7tY;Nau{kuh#+J`aSN*+`)Hf zyNsLp{Oys{u$c0E>rDNcTnBes!qF)y%EWgQ4K>P?=77qojB6o=W}KcF;`9%|2X|F| zRvXIVz!z}c<&7^&Pn@JUI0k4o^zpiw=`0RT0fwo+*U0ihwUj#tXutgGyt?=<#epC2 zz(MIx8=l5hBN%}A1BYaz9dBwn;($K#H;uVM$8ZSp zw+xP>y|e_+(j{g6!|50fL9gCDguN;RD;fvk-8cQ~IG}En|DC0oc^>W*2Y#&6{CL8h zP7$TQ<_~K z+&7YD%i4? zih|0Rjk$C+W;0;MM;nR)i>=L?4VXGsR@<-7@5#Thx|$|kBPx4s=F3@U6=h>?%znOW zE&W&&Ogf$;DYOf$Qi|Qx`7c{_E&$&JUg!I`g4dm1HcsEbcg&<4Rc?cCy%%HRR$}@b zXUz$n!S}v(;p^?ecVNJb)vdwnpM6grGy~tw^)~7`gYPe!yC3by^KFa8l;_)ZqJNPQ z9|iU(6W_bmuqf~XR90o&4ly+2j)~##erhNF+wh|7CgT6kTZ)TD7rK~7opXJHO>8E~ zkRSSGkOHGS;JaCaCp0dZE~9|xTZZYd&7NZzUf@j~Kp@aZ(G5fi@@GG>@c}{p(PHeJ z5rS7YDFcCEMFYWp^VWYI2-J=8zqa>QNvJ&NzxR`ykDbX?9X4 z<1m-MHM+@CkVvT3ZEc99AGDH5PbDo z>2HD+_4n5g+y1q`sT<{gDX+IF^W%7bQ<=!(U+!TT1JESVK2Cz7M+k|(fFS`vK0(jW z)`5GyTuE)4flPkw^*+>+h~(Gn^H?Uoo$XS8+!4ty`u9vGKSTZHSvDg16}m5E@@st7 z$lB>|`R&AFcBw@K(vaXr?K)c~!|qCf;an<|sY6FEF}t4!6znc2OR&2FEA1|5OR&2F zlie>=#%%DI5x#K?6I%q|em(JCVau&XVSSpc->(rBNp`=jXuIMUVgFU}U-9{=21c~T z+`(>q*PJdhyYDf{#f@5GUGrdfS8w&h9QdBOX-s$+Y(3LPnqLgNciOpbU?lk76O%tP z6w?cP1;1_%yMHP?Rd*)%9u;)+cOvZGRHMqsPO$r|fuo8RgYV7TcWP(wTL-7HnDTt5 zj2Z9l#M|8;WooG1Bs9u|y9%hR%D5mgG~*)0u!!p^%at5`81#5gGPAo$86>+82Ha5n zYSq@`_|>^-878}D^~;sen-&hc(??#pSIO=K`3+fijut`DRpJC|>Gl-H_w0`=c$>Si z2D|>X-KiVpf2pmDcEnX{j`4kjh#{PI5yhZr_aS|mKS?%_%zS!Uu0(6^5GJmt^K38F z5s6E-)GLp~HNi#y@qLlF;s)t6arKBU*0vOhtEAO3Qxeyv&V_52{4K5^EXJ{E4`$}1 z{2;ZdFtbuVI8^~<`h7Y*V>af}c)oEp4rT}6 zPTaexxQceyupf`#YBYCX>+VEF+o}D+>p|R@ZUd8)x#dJ_0f zJeAQP5~lsudcLOt_+EIcaOOhrt+P7ZFq${>8Z4$f-(xLW+wSDeyb)z;>rOjnW-mZx z6%YRuLo@Dx7#4APfVz%1e;HI|X8u(M$;`!o1G+X(j@IMX-BrDmn9TfTYp#Uev~ZZ2 zJ}Pe$y@EmhgiGv|a$_*!(J>sqyiFVH^v87_m1ZVb(RKI!Z~xrP)Q$4Ll>WR1*V~Yp z{aB|(8|(DfC3L~2;WP3!L86jgSWy!co&K=sT&|>P=MQ~JYmqti^3+9IJ5*&E(^{9r zQ%fF+wAT9D7^bz?ahbtWMOr&{KXWT-t;d^&uNVETH76{lb$HMfT2Y@@jooApZ!6V= z`%9rr?fV|YyuA)k@U|c$!P^R~^tK=*!P^Q<-u9@B*_cbW@{POY{pRNFmtz~3Hl1t~ zwy}-nrlPHEMeV6*JGEbU#YBF&;QIu(EimRXp7C9ay1~4CFfLaT`PuDFI`~dgJ!7K* zzJ2cZnTGST!|ke0-os(K&GHQa(ct@eoy5YQm>y@~(7iFd{V3C*)fn(ye?`o!v+(e` zK_l|IgYUSxrd~GSd&Ia??w5FPAH!nG^WAcriMBuQ?NcaITZ1<+Z=VBHR%P5@(2Tn* zt`>1$09#4t$4yylM&t7QGDzP33FvWjN1(3BR5mUzD#PUMo`CeGg~QwQk>7;GnZGL- z)CO-TxnPXC774_x^Eo=iY3Lvu+T2;ja95ZK1BaBtc+JP?OcIPC`~M`MW;p2>L>SJd|k zesN9i)FtL>7kt{NIb*Ky=U;ZAxi;Bo*L%*GtJB{q#9XyDcT2Ws%=Nl{!f!NJaj%#k zv;J+aXHd=Jt=0tQn3R!U@h#n=eWd&g2;=fS5=vlB1W940zM(LyvW2%)#kfLq$DLKj;Qtkx4J*6+K%m~A6La7!{!C>r~xToyHzIX z+Tyze=7$|JIg6$HPkw^DZdssMs1Ny`nEv8#BRHQoDYoQ6T_``_^mLy%$oH;}?uQye z`MuWhTz!DK?r-0-Hjr;yM`_qrfcEq9er@|fzUPd)_j)SidvnhQDZ2!irII)4n8|gXKf(3L#!(1!U$sP-EkIsA(|qKe zqHzS~{%VadkA`{S7b^#t@ux4oc&~L3!i-XQ(gJK^t|F4$WaJ!*D{71`)G?!5-6+co zbK&BE%7z)cp}C~AHV6EkBEXDc=7FaGPhtBSZ8wkI`t%8Qz)Nn z8!}$Ivw9El+O`j$*SuuB*5bVz@!H!J)#XDOugSW;ZG&F3Ygwj0{oh{W24!-wmZ?{8 zMIC%{Tla~;w&*4)Ukk#xxCe(5wsk>LwyBLM+bS)xO^rm^R%v9rSw+moQDP)C&PXff zM%a{bMtMfY-6Fc(^ZnAUDqQ#GBx$2+JGP&GUM%-bX&wdJ=u*DHJfUkXBMI9{OEbCg zD<{2928J8IO0Cuw^4;>T>waTk_{U^;6)%);?fGWyYsmNLs@2W#ft)(4&-AVhY;U;K z^{FM~+i%TT!^ObxvFXeI$RXbkk9p0Q1o@73^63xvQ{$!3U!fY!d>>ys#o@ES_IC(l zTL(_4i+j|WAjPPh&tj#5FJz^XALNnAmG(Yd#Xj90*&eEv$hIBGvN8S6EodjOtx#)Z zdlJkGzgRi2jX#Ce&?RIWCA?e`K7?(Q!o!2^BHJj}OcdEhSzflgxy-I?wn?8g$T*RZ z|6+~6Hint&b5N3p#IKLR6*WqM?Lb^nw+_hU^!sZObItu;b4`23T$kIw-G$~dlh2BJ z!^$=pNl!xPo3}DPPqjL*lF1L&I&rJTexlEv%UDa0;n4K;gxj6&OqJ5-%F9_rE z&ACTl?hlf}OnpOPR%sDt>KqEQN+ZkzDq=Q{k`Y4V#u-(+5q8iqW=02@Nd*7Bj{A8B zxK7?lVykL9wx53VL-;74V%R8$`>F2;U3(lwVE*jy%4;pq;iv;k(@tSTe>LcT|6cYWgs(C)T)xoIH4 zoSLa^>D8t~{tawNri!#DB_KfGr=yy!;UN%Zi{x(o z9Wz94jk26l5wmfW%q5N6q8Q!G)MD48SuZAiGme;dde6SE{`YXqmw_sZdqKX7CS7zI0AoYIqPn?*Va(Xa zwX5R<`R?6s{feQ&m|+0bXy)7Wq;soAu;UM7h7p7@->%*3;RZklkYZHMcVwl4@4-sA z7YgKm8#CCKeE!cd!y9Ju?9|BWZVu^kxQK5J$OC=nMh<*%GXgd$)`ML0AlYc

_3j-hCCix-LNy^xDgY$6P_eXNRVSAa@&P-dp|&=t3Ftg8y9y;U1#B8}5SyLU9;Keg)r z*Z$DubYH=KMH;tqmHU3V7L*>oOG)ynkowz60mWboyiEak(<8(CGE=zHLn>hX=-gSe z6OS+FS!AG-%7ldCQ;)8-IJ{*aUWUR*1O6Ig?J=|93*wT?*@-d-@ zv#Oa&zz)CK!fcYxcjHAHeS*b@r2`fjp3SP&=^%t2*6uxC?o+N*^6QLkH?+$Qp@%EB z{OKX|u;WO>fP4^oSUB5r+d~LFWSmvvVXKhD%b4G(0EYj}|JT}tTiK*ezM z1y^g1mLGaC-3K!3+I50#cJ4Zxydy}Dk`9Cig1WbEXJ>M2$&-w??*TOf$44^QvwD`u`YdJZ%44>@p1zB+Ml#)pl&YDR4uAdj2s3orckzGyID+vu zG<=a^-6fASr2Ak=>Tzl&bRTL}*qu2?(Wdh4q8ay(hwj6=?A5*xh3>hwj4wkErUyq5F`p^uh9Lq5H5f>PYv!(0y1_?sbFtT=&6-+x${j zUsf-^!*w4H!%Vr|y^-j z6rhOH;H{r#rT+M2z}cDSW>0>Z>po1=FcCE~vPUPC2SlaI_unrKdzPQQ04JzZFD9tI zV)AD{E*+v0m8@|k>bXY=PE;y}W92{2^s>rN(tQYJh1Rv>^lP?t-!n#3g1X^3K~>Ss zB;C8sAN1l=jHvGbMa7Bw6hu|9N>ovWf~X26qJD~xWUR(ScX;OX9q_EPpA4x#w<~Q! zlTv0<{mv1oVfF&p`0%BA{{frv^mGglVKK=?1Y za&Qr3AUdC@b-NK{AWl{d%TOOO5U2YOyRsZI5YDN$4@mEpT&|k2X`LaEfjAjZuG<;N zKmm8iz|s}j0JrD8Z% ze)68l*QUM9R3ON#TX9a1zdvL|B}k8w4z#EQbxTO!dHi?o`&hWINlH@kZdN8XQBpPYhlsy^zQSyh z5?grDcAjJL;B%|R2K%ngBS>t*=VmdNDiE7+2^^ha7Q`lIKAe@2#3p(jZ&O=>*hHJ@ z9@A1lY~sYnmTyRG!t2Mx^hY2zalO^4qop7=(JIg6KS*q%Nz~370T7$W^}~C$Hy4{o z*7{eMh-%qmeq$~+kp^bUZQn;M9=HIiRn9IiTVVw8VTB;KUiDE$`|=dxFA)hABMszyqd}iihw(m%JTf zD#-*F(6riDHXbL)U;bbl2!HnDsZ}3}@i70!eS*aT8>LB9%S9H*wC!y zpd%zWy+8Ib##C$wiX$~YT-X_nG`YZ*$)YeX*cH-ECvaSVktLA&xM3Vjq}5#hLf3uMIGG6(Ff8OUu*Bc zB`g}jOgXJ={XqQ#U%+(2YL={k>W?i_FFmw-zXXg;JkU#6IBkT}J&atkso5Lq9~b~d ze-QB?rDmmgkQz|528ah40L^~m^R97+gazV(QNt7u28J#+&`HHZJfO>q_1UX6nx7-c z_km#(>je3?u2?$e&#ZH1tMP!Wag7IVjYAVU9#AnHec{DP-_0YrL%~dnG3OoE}3$sb;@|qWI;#J05pD&9ImZ8t4lXgVyi0XScLp$Qs zt-AKS(2f|>B4?Rf(2htod(Yo|v?GRhZLqNnwx(G1Ak7HUjtCpIz5Mrj zo#fTE{hN?>M5j={z5AgZamhRN)C*iYqC0NmSXaxJdX9d=wIlk&OgYVdj`4OlplUTs zBlQr=TJ+HFoy;CP-s-g@vLcPhLVNeDNyfAzasrBe8+e;Xvr@ml5MaMvTlx&i0PP46 zwYY|fs2e{oHqc4s0W;~6f6Kt8#t8B?U5uFoBk!urBp6p_zWKQ+p_xg=aIEc@<(3?> z{`g5FZZhjyYJylVfTeBhl@~#Jc66ZOCa7D;(mL}JW;I=B%p3wJYD!d~V5WjqW{Nr! z%v3Njb7XuZV>M1vGN&=~plw&>!4tYUGu4JaR5LFf{`&0{W|P#{n-}fn4aUs&HJ2ES zT>{RKYQqC-@yEHL+R#07p)Gfz+OTa_y|0U*+E8YalQadY4aw__vu^v?US78;pq2@$ z4S$~6(qbc28^&kNJ?92g8!BI`H`o=b4Ou_=jdH;TvIB-bGf(HL4dZbe$GY;moT=1G zuG;Vi%#>Su^^eq|&IVMiW@(NdTBH?vX!p)iYe}qHRK03LVWe@uY0Z+9onF!_uaX)h zDw+V(4@=%CI0;v6s0b_;CJ;5vnw_Y5qQ(*fom3#Sp>)Z|h})?RCCHmp##GJ9m`d<* z(MO_BO)#!ZjoQ2|p_xj>aIF11K2u+3CDn#d_DFPXDE*qxLSV=p$*elPwy~Y~lU;d> zQF9@npr)unK}`j#Z=*#W3Ti5tsJS#glCc_tmCR|>+-^Hu{Zi`sX*$qk*gDlrzQGPZ z)ohZ2r}CmTyThotVEz(Aj_;<lhUTB#3F->gMX5LKgStZU9+j)KhPuMJ z((enc*aS1>w1ACK^BSOPHA^@35VO{LX!q{5Aa>N$t1FB_ z8htW7t(fx;Q&$)dC^|`C>SWDIOq~uG+;n7A$K+5~z*_N{!1}k*^E5j#_2s-J20E#H zU@BemR+BN6U<5T7#aVBcpt`M*Kl^d2Q7Ti(8ds*y>a#tenM%cQbOzU|*XKAzgQzgrJf0l(tZ-O-L51C99VK)6>8~c)5=EcM(Vil}1Jz6=V2590Va8?=*Ll$n+-DJB z=ffq2(-EugFM^&zuaOrvcY~h7v7TdV-GQEh+#yA-LC{m!+;-1vr;n-SU4x2*Yz;#M zxRE<*e`R+$Y2t+;51^+|qT1;@*P*A7cVIxih0s%|@nlrg2f^mFp=);5Lqx zzOZnwQ$bu$;S9`_)AXf2QRDm)P_>$+H+pE1oF3_{cJE1mu^H~_^%RyMjY^B1+s@*8 z3PFG(;v)jA(X12!HUKVgUb^Bv=_#OX-lkz5#?S;?Fh z5BAwSK7BgXkE=91SItxccK8(*W|MTL054j;$1EOfEVU0kK%3~uA-633DbuKSp)G+cq1<#Zj32e$!Lt693MhZgCz z9@@RTm0B9Bcu-QeK5YcjC>XqE|ELVlX!>h3poss72NN_a#e+WpUsSlVsijY?J|RfbUZgm?t-qxmoTHGSoMqAo_+kqqiqoZM)@pX~J~jH&McMa_u{ z6--sI+IJUqD442XV(RDkNXBYR+E8(8b)tH^?M={zo|8{QSg@rrxoT#oi?K@$Q_uYwY1^4wwvD-MH4aK4TXKGM$}_yB9NENuY^E@GxyR!#ZL4NZ zBY%(Vn#9t!qa1l{QDPTgcRAVhh83@2!?a<6$t#X>?INdZ`EExqAMBN4?jL4Xa;hkf`|%Fzi)rWY$f9 z5mcM*NM=g0YwB5jv^v}g4MQKxQd7X3Z@9) z86U}5jn$OQX`}b8wxS+y-!Cr%>EV{fTB?~!zz)A6!fcW<9#hB`%_4wwW~m|VjwEeX z;**Zx$TAD_`J|9Xy!`p)Y35dPmBOC24{UUoyS!=|S}so-dDhMsW6N&tC=XhDNFLn5 zUCuu5^^K7mlgX(jPTSq4XBRod^}WYzM1Y%NXKO25I$x8GJNAv&S=DK9DSgG z&ya(cZm|fE3uemc^Q$ZZ6aZAMW~q=KS|m?Bw0my={Pz){WHFOYrr`k6D0$0ztLLOA z6akKDkRrfozQWUR(U zO6IiA`gU9E{r3k>+R%~$KoiwWC18hND`7TC`7$hHMQi<<1%PC(%M9Ibe^u{V z*AM_&udnNJvUZp7+#fq8tAhZL^-9fvcPmoLJKm;!SF==e3ILgK8%LKoSYUa~rUIC7 zFiBZqrkvh-%>sZMplUTsrS;Gv$$Dt_-Ub+(0N|+$0LPI=okT;MPHFL&0zjk&>E-kp zKxM2(i&ZWFUi|(x>h2T)ObHOcI%SMnZs2!pn z0KvtHpNP&mvtHsGBmeor)QC1xcCuw=8z@uqbcl_Qfk3=dveH(j~lGrq!j^VKAT6b4WS26Dei40?8gl9AfdIHE!ehya!jw8r`Q4 ziw_-Orrc)xGlnMjx&x|KvouBzu?w3X+P%L4#wI?LFQaV*lcwh~gYj0+T8(NvqWF+W zgA^aK0E*@S@xc{vezlkH!YV#z@gcW{DL(AzzRW-;l?U;GE>)!_?5+&hZT3riUdH+h z1V3A7$PiBPf#CT@YJ4CV*ZxAlfkO%1U!Y<*R({U==jKl@l!QhIWY+Z;2=-ND5GN&am#@t>{O_%$9qW8IE+%u{ZIN+_G!iVTs+O6tY+9 z`)*UiTg#=VPFz=ik-L2N{{QK4aYFp$nTC_F|fCZgk?E zXAgA_e_877)V-K?uaNCVkmVUZJL$c0n`aGVs+_S0ZsS-v0gsqm5Sl$3zJ`meVRXv5tYokS$Kkc+ZxP6MzANOn}sJU*I!&qZ{;pt zUiOO=s;J1y2aB}Wfq|%yHWdUGI*b2C3Kh3;ECE$F9q5NXhnX&)d;-NPN$(WMtY+!G z9yXSfUeSC_xS+_I5N{MSMZ)VuY*8?69Fr_QlCek10^M65q z^E{cIXkf|>)F0pcjVHF`3!Z~X8j>uKrQI|PB)5BKNFMl)E$T14{hJi(Hz_~T5P_NA zftLgpGv1)$Z9|}ePRbV=NxI~%BKrcH;GZOi-R?GVkKhX03oIEMR1^I9LggO8xN>h# z?!biR9u?!ao*T-Z0iVO3MuTelH6LcMPBcN?D0+RKK$UC{exp0Q`8T@5;`gGm1PR6O zg@>c**oE7OEDOy6s!%%MRR>_E%LZRrQ+*atc*O7MByRfuq0{;JNXBZst7K05VC-*N zsP|Mem4F{QE!2H=c+tkUeL?#$t!)};C|vXAUrC{b+GqO5msV(@2EA`mxWn|q;nUts zf9H?=Q7;#t)%D7!FCrX_0<@x}3BJ~BBDW^40v!?ncplUTs_w~>s z#pt2kYf7_NP##*Sx<2%BB=PWDtLqUR47Bl5um-7V-UMjr7tkqU1H?}e54Hk};7M=D zcWQQOsy|u+4Rlg@5FhB0j~Q9pOpx#6%cj{0^2KayhctqjD?Sy2Y=Uu(4~_08czmE@ zI95JA9Xim7CbO<>Cdfw}H>nd%P+h&|*)Fob=C6H!iufS>NHn(!Ry7EOCy8LBU}|oi2E;=$R%1FOLz&a! z!)e=jbKtF-)tPo`2Gz`eM1Ri;Gv1gl;{W=22NoZ;tO_)If7hV94DHm69S2<;0x++a_xtU8;*UGP$cIrXg#_@Sy=n&D)c@oo3y$Uns)9Vq7 z4|f1nt693Ihj?SIhjyRG>nQaKwv@$S$2!KEw;U)NR>7aHA{DGO?}D z3Gx9a>&p`?^@kcS2*x#Dd|t6Uq5Bh53`b|EQPm^o)g1_ucw-JTZ)MpRBLsCjqZ8CE zp?QDkfA`;XvGre*lscSO;POr^Ah-jHfFK-41Ox@k!bODZ2$xVW1%!O@k&M+?Qpubq zN^;)zC~(@imZo7ewlA%k$p!iGK$uNZvZuUgO}emvaO+K=VQlo{)KNa}a!~OtRdOI8 zm^O9^FEus2yrKWC-CrS|`hN4QMlKLfy?pLa$6gRmUHaN*dsm33j+}0NTLa>$?I-72 z836IrKL^)uJrZB2oJ;NX(;Hu?oI3X?_2@}VJoOcBDIlEF>?|N$02a*w0)iLHMkkdI0f8?0A{n-*mLS(SV~c7vD+>q& ztyk56KrpTWVMV*3gboN)3`b{p6d64DI`Irl9Y$KSJ9wi;&D_kO+XPJgdd6cpkP(ROn8#;5Cv0ws2v~4 zSdA7XbNUX$i+$;{=kGI=;zM)QOeNq)v@n|_V_9Cbecf4n$ZcM3aBpMF13o7g7E|+a{wrg*wsaBf0ZDf-vdBQP(^TKT$UE-*3uj+G~SEd1l z6=urmq{x>vThb9wwVI_adT5b`=%L*!1~3-!LBCUsL0)bsc+@m=mJj3_ze{N}Nbw;f zU=!oo>s9t~`P59n`T<2&%}xV~0hN{;=%n%>9?+$3KtYgyFv;Qp!MhD(=dPPl&C#C#c)HHEXN?&R=EW zulQ6Ix1kE`(~|{&I)EYo2uBeCK*8#WLAZ(t01Bo6P(MDBu^L+{nbQKm8QUMBdG=qM z#Pm|zs%9zyKPC&aNh<5li{{>&1%N!$mmB0NW1jbi1nT7p0~*|b1Zsy1&MnujEiF$f zSmyB~NT9Ar-Qn0MNTAB40$aT()<_P1cGiU?P!IcFI4}hgsAbRJI#p?XGx^2YiD_3u z0(I)W!=;O2Mc>l8qtoWe0Zx@OmcVTsec;BEb~~CGnFMM%m?@`Qs=lHCP!CYGnxzJM zXp!3Jq1`J2@LvZ2NTBNG{%;})kL@|nl=ET|sJ8*djsl1Wk2EXAgJ*#47yG1oRgY_) zzS1!9fBLlL20E!Y;6Gii!51S}SFo8OOUg^WaLn}bxFT#yPcu=q!9)#zJ@StD{4{hQj8LP2} zk~w{NxN$#A!9+!v$Z0RtOeNsQHDNYMKIeJSru1Xsq1w&mhJboQ9zTZ2sc(J5stXV~ zeV8PxW$uj%@{}Zoywfx1k!!i;iVlUy>579vHwt`fEWiG~XmewPhs>dQGkHMdbV2L8 zwMPuWjul}AUVetiX|my!+9cVUOfKry!#DqNCUV*ww{d*li+^_Ba(X)xIc*Iy<@Cm0 z79P3)E)iA;GytkUwn)SE(C+mSFc#rKFLIjl)^fv_my>cmjI}fYjfnZ$2Lsb32 z2^}7&7>;#stv9hn#aR$FJ%y9UM9T}@JR+=eQ!(g4Q) zZh*oegr5lhD_G^fa1FtK1rz^!#78n%daq>8$!VRk1I-!Rh*E9NwB(|uLsc`CfFHw! z*(9yY6~u}bGm!DWQK2A%wep!JcOh!}v+18u9mDxglzrt>@nU z_aSO}Mk?v+1yR#IyY|*0QPWX3mTk)lQPX1~{r;Q*QBxOFwxNX=xXTOQ%;+;AJefSX z{UKxdo&{)aKs(&V(FZ=v4G8_6^tOLejsMO+Ckg*FNh@$0s=(mEjPN!GUF9C5WYl zrHZ+`32zLK?JZxl1H@9(I5S{hEKX%*F!*xfS!PCTZ3@{$!npGh(g-6g4F( zP!LnWDltW!31TXkh`A{~lCc{1D4ElUdB!$*_N6c0TuODHY9`;{hiW!SNA~lg9T~xh zdGvUYq2S|yv428JwRQ8LQo)c?J-RjGU}(yka`@z|jYvxM;r&x(DvwJkr}U}R`PyGT za-JgFtV zg4;M&PPv7RA7n1bq*QOgOgRne7)34dBS6(^mY(RLMf#wJc(r#T7Q}>)f`im%b7){Q=cD{9OvrtVGNifQh%J{42_dE33`|Rw|pl>6@?F*~I<=VDVZ9#7&3X z(@Dhzap{t8{;-=??GY?cl6Ea-4L3pFXt9+61WRsIiAyl9#N9JyL_!mnis9%RW$lmd zHseaGWY(=5BFIIn*jBOx=~2>wiG6~)dA*$ve)aC-|I)jiKK$R_y;XR(NjinwPzHvK zV&UR8pzt5zRw7&|*epCoc#`lC1yi`V8z0G7jn9?LY2o6uZF#-y$3n6&;ni2FnM%Nq zKw&mX$5O0dMJqgpg^P%cD-7WQm(4vOyxPnqCQl@US4&mwJ!IJH+H&@Qw9DE+tL0v% zf<1abc(ro&bd}BCzVd-4zjxku8(Y&g?sRMb zgjc89Zx#>v;7#G;25#f%61`jHIXHSr6Pnn605j$E?sXO}q5)N_S$e657U`QF+P(U@ ztoZjG_cF!w`&^Aj61OUy2-@DvPOI(z&>+Q!Ie@FS7k%fSf-9}g1J=LzTcp`pd{_c3 z8VkgS9LO%6R6fK9y3}>-3F=k?5Y+7nPta^v;{(CC#)otbY9w@gpkg>W!`{G~rxO=u z%By77Z8c4hi{Y^NKu|ZZC#c(N=TeFP&YfoncQ#2ca2u-6J7ZaVNL+G-8XtroiTI#k z^^1MsNy0-EO!2`GAIVsa8ITNRPKyuFh`7XQJ;H2~J~ik6dd@f& zA5OGiVMsoEz%f@SuSyq})i?v?)tgrfqrOa>}PA zE##u7A6&i!<<)=*(`WaF^6C_+sJ%9nS3e&8(bNd#)i+L+TYI!kF27m4&ZF8cyxA*f zyo%d6y2O!CC#f7)UcCu3$v0eE zY&LwM?nHk;(R)O=7@}DzT#N+l?Rw?h_2Q6P#lphT!20)q<1{<<`->pAbW-u~4S=|0 za3F)aWdda7qgwV_fS_(2GQm2vo{MP!f^m%&o=$ZVI$BUM99?61vQqED|9nrw05a=_ z0R(yH0*eSd+r1bQclVw48~1%J+}9*IjpY?s!=J^241mHxgx`pGpkQ@)AzVeo0|iq& zaEXs(tj1hQ=CpWl!sb=sL(ytBrts>nn#t$*Q9+nZQo3MXH2VY=4>D{;W7zWHwT)1C z?Z3^p&mT~D-Cyrwy}NQlIr;9PEs{dv)ptscRtuo;YRFr4W6Wc#Y|4_j#&c{nF!W?T|QvJiON_wP^`?AMi-#)dd|6Np9=Mu!fQU<#<9{%cJ?V$vMN(} zEetc|w9g3^4@v{7Rj6<$vviHMRv8@xXRh1c)WB@I#l zxCz+iuyflp`?#d*ZD4(W;l5_4&+~e3LA=08)NotL4uL5*7GYYeT~#wL z9sO0!kW7Eii`F545!L>Eg<;%{#aSL0v74FkMCpz+C886mEUmUuq@kHsQ z@_?vxshgoAn45iB&%U!K$hU-KZ|n(9f20zXU|fkRb#9!{M5SUl5_Lwdhy~fgKM_&M ztozQMARqZ$q!oOcm5DSGRKK_~Nlmk_WDh#?6h_oufP$!^LIqJ3thT74N(E6BOhoM; zAIVsaqm;~PL_KD^T6On=bxWAK>KN5buELMY!fcXiRpCYZYbqmZy?QGRo8Q*=UxVH2 z{Fg*!9szaLg+CkS`UZ8?9$iwk$_sVX3d2inje@$WJi1W6u~1h{)wOK7EKpbVnY*t; z^+n0$Y%|LI6$N$G6E|a=7h=SoWZ&7Q zrkrkV%7{7$+$$Ds!mg=G1+qM46el+@3Rb7+geM6PQ7{FF z@$r$2)i_hhoIXGt+|Xf1fznJ~b*^fr60pP1Cd?*j;w)aYQZreA=(c2~q39F$%Hfb# ztvx=bc4oI!a^=!1gO9pdXT8|8l{B1>a(pQHr9Z=>dsj~GXo*7`Yvqv zlD&{ueO=)8^m>q2{k$}0O$_8!XKrb`aueiL7Zg0&=RrLtuR0R9`Nbt-rWcxc6rbgr zr1>yYP8UQzqLw@mFq5#Fr64`DNSpQ0?!9?w>;gm?-IV@eq*21}Ty%yCOkVW_pqP?H z%YI6;QoJ}1m~D6KJ$F2yr;3*SBCx&-eoeEpcyR+*G#7{$;fq%q=%n%@UeKj(%8npk zoBNm+-w@O-z9D$uPmLD@;~FncM(0cDctOQ*bdJ1(Hx$I;MeV`l1(i~Yx!GfR@z{vC7|LBv{tVjpncfmkH;gS`igMU0a!m!=%U$a zpm6o+N&}r#T!at0)Xm`$)a{l_uo2fTr=|S_Kb%p+2f?_854Vs)2^~JD7>>S?JfrPS zL#_f#X5AbfLB0nkmhwcfN1~hYC#!BBk79U7=&xhEoTe+NP+d*vB zDQ2|f2eH{vkpmB|f!J)<_945Hx+RxK9?l`JhuG}*hBZf=huG}Hke0qhAU1nq#_{sa zIxw->FxTI#dU!k_G}g^a0Z0R>YV#E>F-M#9 zB^lU?mW7xoxKeRznvw}kMJk44 zZQpH?u371~-)Uxm%(|wUpl)wGg6e7=d}O|gKiQm185Oew3Mz^k6I4{NN<~p;f{F?z zD&~xjWUR)5O6HuL7AfoB_t;LfEwyP)QKrCJST&Pxu*2`TFq@<-5xi&@mN6=xy0FS{ zD3f(LDXy@1y8T!Cq>p-N_wINxc2v|WuntBVhtJGQv#!M(>SK=pRL4}` zr7@b7nCTDLadz0#hysvYMWZaS zsZ&kX=6hA95{xTTeIpZ`sZ0XzKW2(w8_o@F&FTKRV<8nztBz1omrMX61s>T+(Yb%BBwXp0%(@Te30@|V9tkUBBH8m(d(EEhQdRoZeG|pE`$Fgf zx1kD*e$V1Tc|hSG!fk{{C|HdL!Zk!ZP%y;n|n&&@bqDw6rN}9whC%+Mrs^l0gqG zQaU}fd$$LSO+3)AtnGs|uI0}2wry*sAUi;V6aWSTitvvBFdVS>?rkM~enO@apTv&V zFa>}?C<~ob9s~foRKM^V#-O^4d<=t3=w|JH>H*M?=QdLV0KvEh0LjBEp#uOF!?E(+ zJ})XxJ0K;$Kaqr!ni*#ylY}|7^BXnvzM7%3~9Xho&E@eqS2s*W&)BYh9hEDB- z)lXcDL8o?w^YmUe=+xHxqgO#0I<-FsOlsO3I<=(=eQZrSwLM;V_4I*GZLh*%$0l)| z+COj`M;|B~aBtTVu2Z`fX3FW}#6K#aL$Dc8wVI_ZdT5aj>Y+($d6WO!sj0tJz%INu z0b>&n^s==tkVdZ;UFsKo3fbE4(t8ckkl+j8ABXyT%4xVx?N?y^JlapqP61(oZMA_; zDqo4~4AP~O(;GA516elLyg$OFSWX#l`3bWAZyh(e#6#VWU1bay$jZrpANw;HwptAr zWQ}XMaJp+w=x{;BaCDW3;)|y|=9-pd)(!0m@;#5S1yLk>Bz%Omnr7LCCR)RudyAy- ztH$zNK*3{Czk zZoB6MgmsWdX1uXwS7mqkMT)$KA46VtVfp5NZG*gQ$Kxx9Exx#Q?4=4Nd*E^#U+CS z8RTo_w$XYVvZ^cT9{&BuV;I!wP1BF>y;Ye?@ZU4_#NPyLYAt-2g$de}?&?VbIK!5? zoFbtc&lK625Kj1;pGyg!Q~oPo=7Kp+Q~M11GB)c8Dis~#_rmV@@3t!cP6+DsTh7zP zEE^R=UE;cz!ETA2Sf((t*Q~53PmnkBOpszsLH?Z6BxB562q>5->QgXN!D& z!Nkm^@sSLa;FZj2L+*XHlP60Q%~c7yY%Pr;s+m7R{Pp`&m`&1*hP-HplcQ*!?FP13 zgZ*6^cTa_tbIyY{mv=?ic!O)tN%^4r`XgmkIRv_|_HET>*M{zEq5AGMnnL&0&3k6n z;?R99xxwvOX$VrRaXm76G<07l)be{ny01B&?W)oqy05!Ndt|xDbzl8(8%LsszuYk4 z9oK!G1T*D!<`+iP>42)$EX~kEi?mD+?cU9;|4h_hHmxjMu2>1(8rN<}Lu_A8^WPez zSJy)UxhFw^0z@4StW+;sIX7Cfvya!t0*iG~Ans$|H3mAVfcQFvE_DhO1a(Vb38KA4 zqstc35%guRZ4OZvoM2MK-v^Y|EmPnZRlZRITBE0QTU_?HVRgE$Q52GvZ7%6@a1fLBx8}z>obRU zZz>eS`%AXYAwEUFz8*!f=bmb&vhicI?|{L7W?oMt>Ggs9ITTBU=U|eShHzM||99#e zr&t#YBI^|@h?{wkh}zx7D%OI)A{2v*&bTF=lr{8k=~7iH9mXJ+hryzWF%0srCJz$% z=*PuosN^FUSMqtLh)!toQ89k&x`$bzd3ZWc>qzL=x^*N3xz91Sojw+Kwu#DfWSd%v zCg~<_LlyWSHEW%t0so0GB2_^ck(!P$FXAH^tMP-9Ic);$ZyFSzR5O);A36<+F2ws zayULf*^b*d`oP96S2Ig_&}C{V8}_Nje9pTFugVJ+w%-_0aBR{um2V|6PNk zA(D7Hagj%GN2Wp1RD;www*}?ifYQ7+1pIJMb!D2_MQHfo@8hO2ya4u#PZ6RaC+xJL)&KU=QX*S+~sr6$@w7Xuzt|3ZucSQ&@pgPgZm>J%KnGPR-Fquhe21e zf7=N;hlx8%zQ6T`$vM2lZ5*k#^61!01N@nsLk!H6&r?4c)$D+)gw-tl091c$k_P97O~G1*_XH3Re*UK*1~k#78n#qcf7B%xUrsr)`EFr}s7UV)6|cR5Sk( z{Y@&&Ch6N`{;#`aVgcaI?6ros<3|U*@Nt)~mRq5DnCZ?AM8J^odL%v~N zrpj%TLB64i=ZzeD_Sceq5Be_b4*7;2o96ay4f%#F`-_Yz2Kk1Y^6{|2cqv_Ans>hH zcq#oR(bh$eCo}nmpSX>qOOzj+s6>w!OuixM9GfX)mv2~yB)VTr?sY#s0>C$EBcNDofN}9w%}ViL7og9vnFCgAgqj1I-u)UT{x?TS z>7>UF{?nyy2{%DnZ+P>|9qMaqR;JcKaM&<491x6aICzu$L_&uHDu!d-`}w*@CfSU( zH%og ziQvD2RsIXt5d2p#@xN7kB!f>pl+0-zfb+K5h1+|_^kVW1y;U=nfFCo3*(4RX!i#ps z$oQY+-daP!znYc*;EffZ=9kk~K%SxTz8URjRVyf$np@pZ!Y&JKY84N*-oeyq zysVz=F1c*V26=|L-A^ts7EC2SeOG5(SI9FIIiKWXQOGkK8jy0!0LU}6_3mR#G9wT5 zwbS7?jy~X3#5-q*50hue1T*FIXPqy^|LlOO)hv1Fp+zdMhu}Y8Ecmbg!ecd(uxyx= zy+w0uCI3wd1{6ap@PC75CH`*(bp9~Jr^bG$HGuzN8Ycdazq{5zClv?$r%UzYU)rf@VKNZ8V?meFm-1Q^_VqhpMwC?2*{hCCi z-L_t!mq!HEmq(uMihuvrT^q)?yPBlxxD8d{_-u^-%>ji&2tN`0SFp-|;TnSf3MT%y zh>v8f#?DISwD$jk?fJzNna@sU>I_{~GnIfJQNoPSmN%Fct(+_4f9hhvhF0s-{TK;# zhUKmAZjFLEL!GzBO|4dymXjK8S?)odAu_0WdLO7WeECwxB^%Tk3VN-6MCuIpaz-aT z0(FMhi>CPZTGvcIx3Euz`A}y_+rDGx;!tN8+4NY}UgeoOg9~os=mYhJ*xa{eX6g)? zVWym}JIwf>6;QRBrEGd=k#gyw-K#m^zve&G8A@rI>Ftn2TdDGvI+dW#@LlSpK_Yxt zK)(&eyq7mj#t7eC!$kPdqQM3_DgPimgKsa??~raCy^fU- zOmCr^YNitKqrNbkB>w@tXv=dk!nYn3YzRw!KW#Mh7RtNc%5oce3su_v$bI@+1^J-d z+jlDT7GmlSe=-kx3wtuPaNhN`v0QK8lcJ=zurWiSueG4JuqkZOXbE}?KJNw$c?-RT zu2oJ%I6-eAc=pe^DGoBdg+92AqYs?ibS?9M zbjkHe*|tjrBTv)8wrwTIcX4HVLJ+*$K_xuFxDx(k?399SyP11!u;Bx5zM zP%@{zg#OD`bGEJA^*00QMbJvsOuoU78p3Rn7KZbpCCkH@*zK=iL(dW|eM$LX+4Lz# zN%_E@WyA9RP(F~B-WyHI2fJM6H7DhRH7SZ;t_bCW6A#^Mlk&mx%o8t?^1+gIeX5c2 zL5BwG`jGO$p1>JhN%^3Bw=GVkx$?mv+{UqTR?MHU<~>(F7!EV#v~DBD#Ib;?)hvzE zLyI&`5A9x00AtbgmM)<+y&sUoobXbXuFskBfn9^NSR~P@U_;L9FS?X;;>rgG4HFZe zM+6(_r2K=4bgAoW6XY*(SYMkU-)w}vRAz9S%0z;3Wn#ZX7ZRF@R1C+;PFeMO{WbHM z@&TE3eQkm<)K&3iuek{7UUL!DeUcUMlt1Wwc{wow1u;bh3Suf)T^%B-P!LnWM9ewy zk&M;2P|2J|%#*gVPwJLP_nj#eXl8O1ev}brlN9P4!hEPtenw2IF~o3jQ)MqNC={gZ z7rHM5?~_XQadQiYLcz{6TinxPBlLk~E1WI@g@W*~XPF*Cq2NcA^@A-?C|J3mW2SXb zDA;8wG_foc3hsBz(ked`3R1Rum%k_!3jSzU#lM^pv)<*5ZE+jNy1E|yC12GVOrfA1 z%#>4mk+0N5b^uhZW~rkdTBM$OX!lwU7z<+R6$&;YiB&zP4NK7#3I&)1(;yLZ2jIOV z`T8y}a7lt)8YW_<1f-Ml4`R|K7ahS0z+nug<{v6kpO~!brb_+{7Wt_XldN$iX4I2w z2~A8YhGS)aZ<6Ut9xh2hX5G%_1jqKU4Vr62uOWgx5_*($pvBaFyo|cY!DatDcbzKS z)g*1lZ72io1sVSj0t)^MKN0*_u*!eoDT4nBCjK9ak7TUI6H4avUF7?xOQy@4mhu0j zYNitKuYxBbgpfF|?d>`UA-I2?Q)4285H{Y)*o=e_ z+7yrOXW^H$hc2q6?-(!pqi5W?}8;CV?QgwSkgs)8*h(b=n9{-j(8;SkJ}(><#h|K9h<4>F)_io^8ebhTM5m7Du!ca2Ok>bJB2G7keRQ_m_T1( z64XtC6I9>do1_c={K-!7U`%`lD3~Z}OfXTwDicMW2_`C-m>3fu$ykj)l+0;NJYlPL z`QX;1S((Ow(*&M(@(giQ6=sukKa`s*6=h7k8Wv)>V5zmMFEj>Lx6l723K|1@3a;AY z`l_~kpl!j;ZLwqFt25c^)P%-B(m91Y%=Yq?ty`)T35UkOc;8G5ze8i-ONk!mAMR=` zSKsfRcPlgoB9EttY6*>jC6}v*y^diT1J7_9$I2;j(fjV%#Z71>$Qzg`ubcKWCVm7| zt!C-79$F;VojR-CYXo2{n5h2}>JKDQ^hSnl8(P}w%gE_~;$;MgIa{+5F&6-?G6ofC zp9YcxAm$Pc6EUkJvvg8%Kuo&iJ-)5fFcUoPMq81xPaz5F7EBZDxKt%3!MGCBuhs2@ zCMFfbvF_hwn{oGLp?5TPC9|%_Ofc8P=*D|;;_Xy~?)f#Mp)6VXK$mS-mh{4}-n%!x zz1JjV$8D%SV~VkGP##eDhj1Ga4iv101K}wm94MH=L5288#%ipkWKQdtAF=fwG@{AC z5=>H{u4<+d@S~S7o1|1tm#kFj%_j?mgY+;{PFG!I;lK!}S}|Fz zhZd=T9@@R;0LCI5{Ox5GlDKzv{O!7lzfd>`0Tj}(2nQQAD}{q?fKxVkKYmjbk^%?^ zyEIJUpgtZbom3oz1G>~LRw2l~gW8P6Dr0n3_OhC+y`HJzfM8t1K|$9$2^|io7>?m! zQcNn_j}z}H9FSSpP7~xE8@6_ZAU#St5Do~ctI9mvrE&Y;y|;R7z1Jk=#%(AA)>14S zlmZm~A>2lU0|l$$KzND>2MVTeP$oW-!H3dH=Ct0yG22Ji4HsAMVTuAZRWp@(Kf_ilCvPuk@fQ>YJgXFFo*9Y)0fA04WW4Kk-`Xno87KYE+W1$OSeM`3X5@+jDPg9ZE{ta3ARVA;HB0IB&?4p3L%Y`sz*vL>y`sPtBysS| z$*QXkexiQ*P7M@i;p65!MEQ*2v%(}H}^lL7z%$AW7)Gbys_0jxu z-EaIe@o)Sy;y3=8=U4x1h}(!P3n_8c1MzALW~$#KWm!Dv4k+S*@EZ{i6s*Pr;W;86 zD44$L>JcBwSdBxK%xT?&W45NXQb(lrV8R8%RWp@kOB+ zW_t7#LIh9tA73~N!UdaVzjuFmqmg`OPI%t{2oZFT-V?A5!UfIJo+;SRt(AOo{I?I` z_-QP_aB^J2m3&{pwHv(UCSP3!UZ0T5(!5<+K-FrNs_UUeYNCgBuQ0%W9SpbAJ2g#goXNRl-qQw;rQ?!`59R7@xN{47cm(^Hz zfqi^Qkna-0q6I;n!Vtl&6V+(J;3fX`+VBan?k5y>eB%|Y!E7Fm@9wdxfu2j8kso7DhL&% zERgN~%FIltpdoJKSQ`!c?|smT3l&&kri?Dh{E3L!9ZZHJ?`NTbW(_5Ix&e;{UlpgU;$2!GM6#7sM&2+LsRPe9AE7suYt<1z+`UaiwU z_ySXt0xNc6>b4i_40KX)!Bo1`eQilFAA1AKm`aezkBnk3#t5Fhs4|sVDL8i*-}Z8LM%nk~xjXHe2ppXNoN<&h!LUt7dW)cKGEKW~h>v5Rt#fU4CjP0>S(v``Q2-UhGrvEs2_PaqT0$n~*w6>L=T)`oO|HU_a`({sThv6e|O^EAZIQZKxSPJoFI>7=z&MDM?%kz z4vfIb%0DFE!oG|4{qOwul<;4Zv=O(V3%jv;8H$oub?3$0G^KyZJ>$r`hOO)DLpky!?2)F|? z<#dr3GF3@>0;pQeQj{J-<5Lgq-hHOTE+FV<`3x^?VHz<39zgH_%B1KvPYZd^O}wnvo~Sr;xCf&KL%{#2?$7kgS>esR4js zTmwMV%0meq0H_#_wY|HJ`CJLUl&!J5Ase&eq- ze&er~e&es1e)ZQ&xQ!^msiK`yB^!`ZRz1=r-GZ5_J9%mrA3gwz_#oU!#0Led@j*C} zhz|;;`0yz{lCc`45S}@$!*I}+dD1KIpczaNAeCyS60pNBlQ5g4hmrhW?@zYFno8VbknPfaoBw*a!pR#7IwEDKEkaU8?KN zhcUQhF&!+Nkd;%3Elwp^;h-8$2*x#>l*m3Yp~DFk!_hh3X1uZL+@)_cqfcht;#7hk zNm1bgQxGA@y`1$Y2y!_y_JS|+{r~RXC1UH|_#7R#p-l8m%i_fsKoKv5TL}kJuqs$4 zJV|(nf+=2njgMrk#^fKgC&ZsrxUF!a0h1PTU4j(9n4SCz3A0IhmOYdeEl+wDFCOL# zHDo!k(w}q*Zq%*cxh8Z8{`ma$^r7O^4uv?w&#N`K@+#UH?AFt>%xFAvux_>9{)xU zQ3J|zU4o4Hd8P&yeoOs{?0~A(EalWgi&R_>Ay@|Z@8iYabqS6jjZHgxo2Qa4!8hqo zKrv&B?!`IHO5x)oplB@+KCS`wAJ%M2FsT+`XPBG7`tinH&CbHdePGd;Abga?lcAGp z65)d`bz3D9Tu_y!{8;!PI5{&ludFvhuxaY|VmLxDuHj?rg@A+(A5;uSU)eq5)as{i zn5qGpb-fXS^s)bi`p`R!WY16CD%m6@uF9Y6)eMZtu7ILqMSY8^RIu9ci#io`rC=hm zTYMyAH5O4ar)^51r zL!fFY?5HEMRPitXDO7fHYEPZdSS;sTzEjqBTeZgSUV& zTTVM$6d8kez+%T9YUw{~b{Z&j8yIS!lL`cC(k0))B#Z_M1o@jN_Sp$RbJ;c+D6@C< z1SeZnY7&eqHGQW{OK56RF&t|@%YOT)HeAMl%)#^_=>XQ06V#0i2wK@H#1NVqNH<$^ z*uuYY*lWLW*cZQX*d>a?-qIX4FK#2Ud|DY9s4i)eioi_uYtGC9L=`|0AcP-@0HI)Y zDp7cn2oMUU08uSIlCc__Dw)$p277ESqqFC#!bJ~!R5O);9ex>w*(9~!!;AJV3kwjg zM?wv|FAv;Eq6aN97TQ9h2j25eUH69Q!I=a3E0E}c`|?aBN%Y`tz=ggfdT=b}enk>J zIGfKrmP8MF`wj>p(Sutz=0%X`!Q!nRiAeOI=7*_0qPgfnA>79Cd8f1NX{CrB6o;8| z+R+%p-qiuBR{gh^>cro`dT6UaNKEw;U)VwmYuBXtA3MI z`YwOaAz2x5>jH|36!j~Jt6;Td7gZ{Vt6(B-!}v(XYHX!s4lTB#PO!_?rAL34MG{jd zXrr2W>G0RDvoK@PO|lKlhgxQ5#C1=%!BAwQM>T3bm%d)P9mric(oh8 zWD(Q}-i0=HnE`czq=QNoJOXus5}7=DSA;r2TGtu23h) z6V@_o4s5~N>r~yFo4GncDcr`fuF4h~7I~x&Qzs|~Gv&5f2}WFRK-FrND(Rs`s;h@k zD*=oRarJ9*4@9+>*sp41)a`_cf_Os>KXKh=yEkxhBgj^<=ct=(pWAyNLbe+-6iV`gB6ewIGgLTk;NXI`0Y74e-z)F|{P%tR;Oa-%ibS1Ihp^ z)yrnvOq!hymn#B`xfC$BSL+Q1I;ntQE?tt=y|ojhLxwT9>)rQD!=ABSjmb(q^28p0 z(%U6g z$p6lPe+UOQNt1CKs=%RcEFuH~iijW_M??e#tJ7=3b%aYOm?FZ8_(;ZT+^l3yiwL`H zNo!{HO~eHWwyS0;0XzJX2s4VdiWkkpokfHp8#fr5ES*?qKJ*Fp8FwdI0eymb{s;RU zcelz@W_KCr2YmwPMe9;Mf<8f@Q@sj#!#c>FueVvgzA`ij-JVW-34H?Nx#<4&p--^v ztohG*&?j(SacyQv=o17!8uN3&x~4QLpNQKy`astz8{SSj-j+t?t6-*_J{Zj+LMWhW zHA@@y&?4>EL%Vl{O|gpzdVPY1NaN6t3_k{pX8Hs^8l;HO7O-xXeEt>laD9UI!1`Wx zSIy2MLU&-%ARr=~-mt+yClwIeo{LKc2QtV<>1@zWR^4!9Vis!EZ%L)Xs%Fj9Jg_-jX^d3 zI(L#Q6kLayavJlVQS~06YBfs_^w1)`(nGtq^=s^?T2iM_&=YCYZRyf?f6`|(fi_Ts zMAcz{_qxq$IHC9(_GW#IhN)Yf1Noto3V_C$E_I9G2p$Z|2B|;x5h_7lx0+zZ`zrSc z#+7^P@&_d}_ox_-wSBgMB5Isjq3N^SKI3WiD#5-PXt@E~iIE_u;(DUug)AG{ zldV~RQSmvTprWWTK}7|tR1|e4sHk9~;;Z;b#%lbgWKL@}!)z}XB)zzDKSqx&jXzW~ z`35`uqJ`Ncy{^QI_O&3R;?Y_g4I^p}y?baUJ{xISz2C=yDdYxW7rZVFZz)F)_q3!5 zbC<8L*s!8W<}|Y1=(BP|+m3R{+d0?g@^zONT&odw8C#(Zj{0!zl4}=vRoZ*5y?ye? zAvrcZD%mKd+&t6V$ZK0lqPT763gHsnH#Vd`D`wmAU!)eFd0Qqw^PgY&fL1CFr(&sKtWAWgMyk0R)@Hv z4h1z8Ow{}wAIVsa$-0QFi^-_1wy5y_9YS)oCTgZo&AfE@>!+Gc($i`DUw16RsCjL{ zMnj_1*_W)u7aX_7U22fWCxx6R;6k?dnOn)T>onVK+vqM2DYSE0`8@xRxa)w5n(5jo zEE_5IvUXYQ3W6Z83ht=byNG2$1q6Gq*s=HCd+%bwj*G5cRM6MnyI8ScL0859-bp5z zZ#|yxdx8IubK;xly~|{7=049%CX*XS@;rN+IW=~6CO0=ZISvWalF}dI{u!~umV{jS zayGnY7t-~4P{p}G&A7#@O3oQ(M_gXb+rD-Mywc&Nc>$-fY@8A6A12ZSqUiiVo0Ks7~XEpmx0r>B!>F%oYRH(TE%Ghx2X1N!0lJI%)Du8SOGB9vRV8Q{_ZU^>x8^_#lOB#g$jbr^Bt<6k5A>_a>R+WoIIvso9a2pr#UOer)&=< z9h+8s8odz&!87OXdajP7iTcQ?*l(T5mv1$W`}czM#~(MFZ-5|Fudva&Sfehcw&81M zHv&Ouv&t*<>>4}r<706CHSTRu5DLI)EMwrwW`Ao#IhgF$2}Qt+wcQ>?1)&;1*$R)9 zco-nmRB`BlM-kZH`x;{rixC)SU03Zmr6)P?vxdV_b9|C=N1n~Fj zq1xJe-q1nya|NRw1V7uM!X4cMJ-|cxhITxKBQMB|M{7nI-*3XetY$pAVcFWpdL1wL z{W@hln&mmIczO-E>1VXc4~l$3@@9|zBS1f9c7W=H@^Bh#qA~82@ihUm2w;K1+FZgi z<5}Y~#!DC(PcowzgQlreIps!qx3T8osRxENg5{b)nijGdJ)m2ZA2Wk%6-3uOJSgL} z9?`1j>Q>(`9(5wk#+XXCER}=2-ks;^7hMPPzWb2IcUEc1sb+RZdo=K9Pi#-Q0FRZi)PcN<@SYhB0r zK|5sTUfGPnK)0w@%&Zfd3>95l?nRkdb8NKg?fUID)+e0EePO`k;zACR@U}>y#ikDA zlKrl{O_ykibyNvZC=@t+fDCo_OAz(^3pVi(^$5~Ki93B?$|?_83<;q>4{wLad6%NplsC( z9eEfa^x>h|?+L*4Fw={h!ukSb6nghh)qCzwk(u8CG9`w-I8CwQ;M`_hw927Z(=pj@ zyrfjLQ!r9-SyZ$Nck~CSh=<&5GeUg!RO2C~B0_F98R6lsG8GYKv}-Q^E6b^fZdf+{ zi>RbAQISB!ZS)Fpv&r~tI-ymUG83Wrmgf$f(dxcRyt1nvL!`7M;{mdkVhzZcDPftJ ztj!oRC5+6Rk{QJqG>fFlDShT1WA|4JTx%?V?kPyKR5oL5&@HMfGwX!Gr$yIVJq6c% zLWW$5R-Jmi)q$Lb#aCPWbL@iU(PcLlpZi$fk#t!5#@c?Kmdx;+voxZfBk4MKMB|tf z;iSBGjtQnoTCzWXwrZF5+me#2pN%XX6=6D&+-St~0B7=YO_S3T?d*xW?E|OTrztZh z!)YuVC(T_ot>s6`%o$+DnjTlZL}o4kC|mWyA|3_^8+d5;(_Bs;Gpli#5-LF%fsb1( zxvG1D%&Y>CDKRk9L$M+=s{?G*<7aHXg)b;G^$JF2ni8W`xT8P7Ogt15>mJ4j!3f1A z9P~CBA(s;z;luqhGZAK#nTL##S=~vZ8<2@|BTo2nH{e>VHBJOD`5Ma3cx&oEFf5%FaeOTEC4Jtm;gu^1z2*W}UDh-%jdUY!VfK!Nqr~9ws!d7zK&chCHlN|Jpr) ztje>v?S?}g$>`NzTjrdhB_oCMk6*#pfY#SPv@_rDaB?-@$4AR%!PBMS(7Y!2y3f;> zn+u<;6JZ+ge7R5omWEWC*nY?L3if2nfVMAN)@+Ym^JF-UWen(E)=G|X3B%juSzyMR zri`Qluo$3h)eB2_7$9usq1jJcVrRO#W=|hw-pmuqaIT?U+ok?v6aa64Oz=Sf{1ht+ zKplXSO#YL)1|?AeXsBQmfUCuJs&GetKmhQN8zmzYvVm)f8zxWsGs|k*h_H>EJ<5kmj~*#$cdZ)Es8k2??R1 zYueY8ipzWMRJja^JQ{bwiBwFQx@Ta#K&Gz=JyW$(CsMCfzm9F7&s`U^w@r^0j->GH z;z|^_0cK&HD`X?a9Jy+P05& zQ!1L^G?uNgtIFom<}Q?qiD1T>R`^V*cpso_)e8@K7$AJ$q1mrzuXIw8`wYNnC}TlG zkLQa+A0ZXT0c6q(RGh3>k%}_`7Hab3Y0j$8DHZ1{7^#@j1Ly=h`U6zNLvaj9*IXbJ z9|O~Om=KCf3F!?h!rZN7Dk97%6+=qZ&uS{78 z#v97LivU?$uqI;Mld#M^)+&s95=QR*lNrUpA`7W<3iq}cJ4~$qbU;a1dK9F2BAc=G z=@u2t%sS!5F447V$&`DK5ARfk1^;yVoajUr$6op|@Ss5SZ%0*puoxC9l{uaII7&+j z-*r*hwuTQ-@2j+Acb^DSXT7J>?-g3oS8eoOa>ka-9pUL#_FA|pPp@BJ-!^k5AIlY~ zRk5=@Y1Fjlk?F-@Ld#2&0;jRO{L=#W-)O#)a_<|Mv8LU6zQS>^RqRfcY=zg8c^Dw% z=AqedCcyOEp?dI7cA<>TDeF4a$n}su*;OEtZ5O~bJ-u$&Xr58B?Ncz4%@rz-J30Vl z!$U580m8G5@sSWE8$!CiATM3ugs}MmtaP#3s)ctk)8o ziDSm=6Ku(|$F*$ctO+-DpB-7uxv4Yh_hZ8PPNVF}<|yZUhbB;Fu7%TBww2HO&DoPK zQ)aFQGuCv+6Uxj@0A;IQ*v!KKVHXe0ey;$ghnZEmJJb(Q##Ogl&;0w`M`ord5SjS} z;K{oaJ^k&TQf8(q7@64uAnxb@FcS~OR5+{gmK34*nW~HU{trU28-&kPkEgKTJDHhi z%_uV?7c|RiW}+LGtz94}b?S@rl$mJep4=jY)nSk)4a6#*UJ|^NxWOGNTE)4e6*zbF zyR>+rH>FT!I+ocbGm|wSW2S^;vsjhh)}#&e2UCOD1Jbi4p0#e^!?866%l5XnL_L4Sja-=qH8BoDdU|s z>{5{~Cw|tw1)qG6EHwMx6oGs^=~Zc7#}JZ#aGeW|17I;#%9D>1;M4J^#yRf{$kv7A zKRo%#f?Zm2aps-Neec>5Q?zf9@wLKDFV6~lf*U%M$?8oWnrM5H{LswLw+1uTbiVKgN6A3|WvgE3z{3EcHxJEzjW?!`@$TFc){aodj)*p| zV#eLUJJe8sY(@eEpo?O~C#>B7O3{FMb^8E(9lYZ6nzE0n9t>14>Or6NyHvQNd!Pq+ z$c>>9iaqr+)B}Xv6IO(?r^$MNFr#{~`()d!)&q3IG8P8iI5fII4bX#a^crwuX#BM} zN`~q6cxuHr>)6-MCag)4upLVI@0?&?hEO8rq>O2a>o>~L2dCI$c z&-ITeGfOBKnYrrYE*0+R05B5|xv3(UbF;m9?5W}|3?8Re!%*D0&HiEda%!~3-P$wyXGZlalcYaXHa0u(%eiKo|(8&sn; zehAv5F+I+J4jGT<_J4`zBP^bE!c;g7wr4@@3tWP+8Xyx07Dr4VBrLy*%OZ(Ih=frf z)@4R92F)(1a!TjC&bVV*VB=D{rYI0GvKc*~ThumYhNQp~MAyzcgKIt^eP``f`9`<& z`S8ezyr@xe=={zC3Hhg8{%v7({dlv zl8VlIy59e2OIocd;@+974>DkRX~w{5EJNbF z+okJv(NrMTff;LRockOH)!P8dR(KVchXI0-hh{&w+367oH&>mv@&vXHl(C{sjWxgL z-#~$As6ZS=Hv`D-p+GMJ0InSQv_Op4eX19MfcZBU+ADUd7eRnocL92lFmtyGck~zZ z0uQ-284!wjq-kG{kb6Q);UHNr5N1>_zByFRYP~==EQ6zQ{t0yg6RBRHnd{3Dwtl)1 z5^BLKND1`%ad+JdxBvge^LZA}z#=#eHsI(oR3JfOlQesO?SqYPaItfo(nJ0{9galo;38!cK+OCDiDX^G?pet*RsR!>;y+{MhzmsVFK(^ypKReVOcXSu@0S~#cKEi*r z_z`P*7mko}VK<$XL#RC|>jT1!>VxK7m8{kWbi*<>?w7w`wvU%)jE zfnGm(L5EMsj_?0_IOqJA;oOLYvrae-r@;nHDo^#{Ey>?ol;AQ98a} zk`sw2+jaDpW&+u6Q@h9F(xIgPyRAcBchHh^I|~&y!rlFN-+%IM_UU4pqwOfXIIAUY z{oj>&Xr(4XZ}+>SMszmqZT58kG`%yK|9zEdqoV@}?cpDBFOllQ2{?^q4CD_#RO#Cn zst-@Wj5WPBmg>VBfU;FDB=ayp_{BrBU%yIw(s763=IX-@AjUx%>x}nvm2Pwm^NW;Unn7e1PX44&1qg+@bog5HNrLu~f0s@x*e#Y;*~FksG|h9o+}L zz(el-1EDA%bUcBO8&4o~&GUoZe;~}LUL2a~k=1&EZdk_3j2@phyO*}bSvxdy;|YX# z?I1N2>IFh>JaMM}pW(gjFX27zUxs%F7T!AH0h|V_(5y1mi%$Sq{IIZM5hG#whJ%F; z3keCMUVP1rVhoz>4cHZ8v-sV>UrMi1x~^@N#qLdm}3UuSovdT}Rm zkE&stdyf-eI+5zybGeOm1v13SaJgo^P*PO8AaS%oOZvowPRs{-aey4&@w;Fb)7Les zTgi|m>{;@RSbsrHeESz3e4~A5Q+%(uQ!D+PN#W6DtE?#QK)!|!a<7yZ-rx4pyoS?Q z#=zrFm*=i76pqjBQoxKgt^J+qg&Cl1)eAp)2(L;H`S;Vt zR4>rXjV};F?led^P8W3`DO>--h}(PNdOlRi_Gm0{QXq^rUiKLP_mDiz8~a)slA2mIwO4Q@^UA zO}`dQjW7)zcV2z)l9r5qU;pULTxxP~ZuHS)U1w9-lPS)J;nN*6R^8vXqOt?Y=G0`> z&z4j#3Y`5j1|syn4W@Wgy(j`^tf^-ns8mhC8K7*{3uSm1Ab9Z*67&L0k6w6lPY;Yx zM#Y*PhI-bzf_iZrAnPAMFU}}doY1@ou=kd=_qymu$n4h4yqS*0Tmf`D#V3PR=B5~D}-r-FcH zZUPgbO`Du9F)QKWLOi{Gcqws%@dR4M>5AQ`587u+I5+%DIJf;T;e5a%oTvX8&eh;F z%meo2A30!kf*+W%ekDApe6#|{!ihy0lMe~Y(-$nTn0!bW<)d|G6l2hYOO@m0F{I+s9DXu6R=U@F)`(C>hVM>d8Jf7@}(J=RE!dlE+Ob-J)bOntXa<6^o7}eb2dAHqp??meN z+WPv0i$Kl}c)Y9pT9_KJjXGSfB`neF+_!)|EYXWdbWbQ?j4*9&f6iy^4M>7=bK3U< z#nt3Z+T4Y2)51(spI2+(=mTAMVvEwh>pPHT^~QflJ4?CO4Nha(8da~f?LTz@Xb+J#L9!At>X`x|Oy&A}%BMN+=MyR~BHWlAj+3 zdS9p9tE^z;-u$o_74GN&a1Rf;$v}kS>z#C2JHj!Pnx}B_EW*7Ff3llgto5!QgrI z`%>p%S^KjlJzgcPi7?gtUH8bD+gg&^tait#rPZYSsPlW`o`#wF?YP;qp_elmcY0Ug zz}Aqkw_)Bx!D*D4N8vP*CHl; z%=F?W?ZTi8hYhY(Zfh^$pt>tSb`u3e?WI_er~?2FuX1DO{?gYdQ6m+ML_NPdMuj{2 z1HB?1F6o2s_)}&g#5sH8AlfS;e6v_)Cc=y|GwN5CGZWpgZ0%#q=5G;h(q0kGwL_j? z*50LWm>|T9g&Pc$5y~IP)CrM^qP2}5rQ&>mtZ7(_F)B(}rXp)3MnwrD6_;d2F$T>R zsd5SxR~TcKKMOiivJO&ln`{=ngMXuTGqX;Z{Y7-mPEV1C5euOCP$d6P2V>)?w*#+4t}z~N+mTp zd(QPna(tMnZ^=)C=XyGm1MTWBatU!Dk7643{pk*=M!hu8;WUN(fr=ppg07EE$nlgc2 zKY7AjC+sS=mtNVUgfcfCAZtn1z>K*PmS?hAo3gf&FfunGGm0^2?nsqWhPTU%>nEqK z)t0P{%)KX@F*fKHwT_u}!p1tHYXfRi<{oRhR~4}-?R3GfPNdTC#SR0D2xQDpr9r?kzB5O)vhU%zXqLt6P=;w_eU;yr3pl);r9h2*p5zsj2bQTG8_t8}Fhuquh+_ohz%kiEdanf76Y< z?p4pL#(PaPi)(-B02d)Qz(vUA%0Adbyp(1ADL4NC$hgUxka1JOa<9r7ku{Elk()O% zqZotcnN&H2n+uHAx}|lpSFVNJOp?tQ40Mai&dfUD;#|?SJ9Q~Hk1XG-D&;cZ=dV;J zvS@7L@yGdL+9&o(w`-~}V*4VmN2&T+Qe$h-idn5--RoqMzen2$)3$@lRpp*&$@!VL zHofpxlRXF5+#}1vOmqAD`ZjcTCVlotj9oC;fjC@`2x~K!a`Pda#VrEv0Nlev?l}=cI_LSGu4_f;PhST)j#Nab8z)l{VMeK# zyJEhqrXspw+1i1VpZ{L!0#w{ao#v*6@z?v#;nGz)EsPK^C2la@MacDemE0~F=%o^F=EBp^WSC0b2dHdy=_X6nYm@N_#^l? z>MS$sgzpc^QHzB(l$~f4q*^{|0@i^Yy3y|I408tMsRwU{%fa;s?&b)7UnG*H1f|01+;41ET z^?|5($So*E*aAMKkas+NeuI!(0D`d1Wtpf5GfLFUNd>c-sOW}e z#f!-`k$Y8Sv%)<`X4VPWTt(NmHKE-5<-Jc;y~bSKtRGI~P3x6QZ`lc?&i9Jzwz!3n zNKfy&*K0#2%tb+wGnzY+*Y#iCSy(y3^fRKD-^U~^DK;X{qQp9C(l@ff`d)p*Ow~K( zZRq3bOsW|#4H`Gafy@mkcs(tNaxa(9zCSL1bi1{kb7YUewHF1zjI~`5{uFz~;s9l< zUMR`K0HG=m&3@|vri**-%3|;RP)3cPc2~#TIg8wj1;{>b3*0-VSdn|D0p@WXoTJ?R zL^^;y3s`DxdarpwvC{!;0$_Ik0^AISD~>z*3*5v*t`kKlJ{zRmM93|+KsdZa8XM0d z%qTYxtuK<*+(b7lx#=}IWQt7)kuXxVMrIUa&@_-Lhixrx^NdB@$ieze{gA4S|1eucX_y((Nskm=%iDrd zweX~Us+uuHzxw=gBDzu`_gmTuWYNstjRyONk&f<%uiYV9vNzKDoT`~4S+sX!)p$*W z=}{*b?!D5INp?Yd2RBrcqR&)6RtJTdem`jO>||wUV%0fqWrev8#CzoOGD~toY9TL8 zB{+>`Ygi>ewZ8%1T7>KE4rX*^(nv~G9YSW+3pIEcAT;Em+3y6v^iY-0jCUQ%81rjm zfmh4VAXV=GWYP>&eW+NGs?PzIxVG@pJCZ=D`T{V&F6xb9r&LV_%!C`LI$+{H74GOS zP!$i0(!3k{@i8Ytm=c0{Av)egD30~$x@&}UddXBpm{F=W=v*|bsfun`21i2G6GZ}s zQmUdkH+{E_E`&lTk7#{D%B;_L02ljj0jv{hz-h3>&a|Y8&;lTf5EeL05hN@xgkrJ6 zVnD*E2mzT$$&y#Pfx6zI@(HO?tYVpZ&N&n5j(Yw0j*YIg@h*i^Vlw3QtpC<^7r8lPW?dIE`ha z$E+_obU}Hl2wlL8HT``39(LYi0m@drFrJ42!h9Z@{cNwNQxUjSM1`S@4%v-mdJj5{ zickz7>j6L!oE0l7LIr@O`(EF>{KN%1aCTKN4xFQ}!pH-5^amJ^hg|23kn5ZgicfUt z9WKI)u`=TkW|Z-VT$2i_u`V86ee^@EtRh$BzfcqY>yxAC0{pM(!|&zz-^)D0$L`QqiE@uZn7UcSmb0Eooi1@`rM1 zYGPiO=3&)6j2sCaV&mqlxM|GgscW^#T5|t)?#s@t)#Om( zpgaY!m|(l5>lN~u|JrxwriW- zM=A~jC|mWy2p$Fq(|Kt2vvS^_zRsDuhs_6Nl>ZjexIybvNJR}mCcQw#;))fi=nU{y zLiOacP0!QLxeQ=_BDjKLr_^-XuZo5p{X=TP;Yo}#eGwoF5EeH~5F{+$ShG-Jf*@fOgv87!#-Mp1RZbCvxyHpM;`99a=7WOp zSTMACx=h!n;ij0nZdJa%(~<#GL#tG34}Ei&M(_N}hMAtvUeqAA zJfv9|Z@0Me76-C)XkLBrFe(Vs;WU;p5YuC|#-}kAggIcwnzlGi1z`z5*{T-~@Gw9) z!$Y&5PyciZ0(WEG2+AmVzgx4CO-`a9GzZ8!01$-MiWLPR2;kC+lZO3FJx2wh17Lo% z9;(<;5U%$H%EONSfgs=^H_3%?6TA_;djP$WMyRib-#DkEbA(^o$bx_{qk^zxYjRc# z0=i)t46*+2!fGF&eKnf7hqegCk8;r2XoPqvaf8`tg!J?0cAIgL^7xtmf8o50g|kjr z2B*OajP6YJVK+b)FD#6hK1f&|FtEsB`XFJ{hrO9mj6q|PDyQhfG-FQH{gQGfpYI$g7-lk6d)swnIcHM3 zdP1x3I~~Z>BT>`aET#I;5>8_o5?g27s97zD>O&xyv8I9_RH~-X9-wU13kDtr2%ULo z_S+3GJ$LgSI%VSR2$b>b{;`j%8lFIXhy%zTa)3S@SFETHrvTnNy14WBt!Jq|oB=Gg zHl27or`YM;d^}(_w*z|dHg3NPck~zZ0uRNJ>ju1=M<}i~x{A5X5XwtH##5MMqpTNb z&8S|q>-sUP^#a|n42~TWi+|4(PxS)L;)o#%Ke~*t0v+5#Ue*K(SD?OjTZ;m5_HM@G zdBA^*XZW@=oCX^(sS6c|djMI$usC7@Az^vCkA)5k2??V>+|P_+44S7>qZ4)ox=f@-#+I$!)&zV`^=*?E`L&!@;|oB zPg?>v_oEB+AMB$gm;ILyngL(Jv8mVNmHt$?XvBtzeB5duTK|bBCPmHW<0`-GX7=Rl&oevx?$Pc zxrWZm{q7EBJes+?d4%FU7JOzso?bBS4uY1YOvJyeAYSNZJt#A?RXiXwlQke?ri5i? zvLWHZzJbX!1fa7zN5U#~A$k$@r)y)sUI_|1euc1u?TuNNyqib@pDAnYRrP z3&WN)iB)Ndaa_RViyzeF^rXeVJ8ljmWq$ATu=CcE<$GcdmaOYYy2Xwd^>BZ4=cbama_*W;Ez8Qp^0e=ptN zgv?y4Kzu=YJwWNs4ilbi1(@8nirJ;!Y1(yf2h88=?^f)z>y81;268}T7w`sm^cRSX zhuk|42)XCk2)TQIgiUH$Jxl+27`;Gw!yIr!Fv^e)8=qgSmW4Q5vLM1gRV%@~4oi}GYOEw0*rfSxqYZypv+JKa5OviRcqkO-u6SnbY=29q792`b_iN5^h@l zKKNCGFIr;GU;kBbPw2V_FKLzkO{nRlF}g;s(#~Y0P34uvk3-kpe#nqr@2NnPfzw#V zz`UTA`$8vCfv5y#tZDE|DiEFkWvgBYv7-;$azKSUx(oV% zhvL2KLG0)ee!%ZoOnr<)dxYFGb%f(*%ld#Yqx$ge_?fKM2Xw`XqaY1(nr83*`==BJ=@HX-<6 zzY3hjG9+r=%n{gXK9!4VV8)tO2)T{p315J+RWH=yVSvzrhwz&}+57jU5}nz``;LgOI3SE7#&5OM>5 zgxsfp8s$GoFZ85Al&IkVS;MjRWJHy)OjOo{jHnVuqIS=WVhoz0QstCe@(IRD{-Z86 zDq9taI!rcWsL(B{A~VBhqicw+RUbl$TD9&$)!qBP>q_U)k~{ZjwZ8XKO}>@RTf#jt zjO1uG%t7Y?5Ba9UX8Br!X5H!v;h}i}+F`{en9}aXCp6cH9WL z%!UYeRm#Q&_6Rdd)LS(Zvzn;rhGpYVdtFbpqA(>Ynz!1@_%@^U97I&(kq{BJ$#A4GL`cXj771bu`ujw?j{ra)xk)_Dh2xMRhD zdU(h!bwP+v%d%IZlVb?Q*Q{tB0fh0xWa=TzDD_OXSF)OV=*C|IcN@JzTpx+Q7C*Cf z4JXGCa(yI1@$HvAxDaOeZt+3~ji7zxB7iKcSqrhSmhk@)*2^=a7=vc3R5>fFHBua3 z=Hqy~Y?gu;{&P0ou>6~90><&Ao1$yEM$ta9|Ko$IV&CWYah#(i6Z>sH-3p#xy}va( z<@&seCf5o6-9|!^&lh!*cArdDlX7+?O02!8CmqM0+qGn!6WL;(S9)@^14*krtM`{X zjYxloVO!OAoQU1!gk0Z(;rE`-L58KZOdv92;WUsr4dm^szTWZiyPgH)mzu zBFrdnb6elYTHbD>mp~Nz3HY1}y=oSQ;|7|&6Ct+hpS7bXpcta~1BXE@I;oZD3L;n7Kl z;oatEJGzt)&WzLvQ;nacLYTW?b~Xq`m{CTTI&nK|8U0R!Zdf+<#HVYmP0=v? z*ha4q*AwHf#jy%3WJ#dbS7qHH-PShjdfzk=uWY4pl!-P?56MhqEykEAVVQ}n%@`9U zj7$_VqZorGKNN$_u5`Ws7+1y2T5RhRiA*dgo5dgDzblv-m^e`U>xbhh6B9-qQl-{- zpFOD!tU6tQ&vgJtV- z0~3D=O98Tx77%l_Vnt$Z1lYuUyRyx8ff93@f{~aN!4=%m9k^L#hZGK^Q0{q0Q^=(S z!5=pYmx+lmqr@a*?`JhJ(GAPC-`{S7vCS?R1Rtl@K%97|OUnM^f+bL^IAY#`^T=nG z{TZ%lPck`Nb;5l(4Yt_)iIo2-09in=IAQ#ku*`oJ8jSxEM*e@vjA9^<_HwauN>6;n zXuU4a^&UNkBL8h=GkPFy*_c@;Bpnz3y8dL!|8o}(shm_P8(;ZpN%F--OBXeEBnJbn zo?mNRo(!#Gevvb~GugZ$-vI3cfyCwhA_MM~vnQ>~9nRAt zK7iz(J=4L@S4$$gEpF5;)|Px-`*Xq3NzTasn{XP-7$`Wuus*UKWM$9^55bHzt$vI0 z-waT;>V+RX3=r%ua#pkNNPy|!e^qWp*(@kxSwn{e`@rnj6E9RC5`HDXRaLj$XnaUb z$J(m_v-ty@t=gd2sQ^H2D@y)A&y0uMJuT=$YFXQVbp_?nNbWphL$R)j0X~p&3m}G{FpEV z^`MGumc#)5)0CMZ1$gemlzO|SQ9ZCKa#)qk`Qz`=Wwm7F`0yWZ-5g1w!)HB0*TO@p zyl1~YaC9bbQf^|_33V|7GTjc}QgOUJct6p&8 zVSwPyL$mKXfd5(#s=4a8$4dL5h(4>fAM>u04fWut0#Of60}T5y`^~RFTdD_V0kius z)PoC(9rd6?;lnE2(I3zQJmm6XBNShLqH|^lxd8#fkyh4hq>eD7dN9Z8VOHw_x?$P) zTHEYljv-HRK!9d>1z7@xa!Nm+klfxG574K73D93GKy^Y{I1RQ~=NXjo)d4cbv&dkK zm#{nnV6nj%FJWZ7UuG0z&@_}Pr!fAav8*opn&qB@k?~DsGkPFyvRNlo>L|KaXclF> zrrTlFx%*cZC+F4@Q{Oe-PwX8@c#rGFl5bWg_e!}9omSA9xGa2DY}&LOgxt#6bo7sw z#AookcP)VNJ8O`&ZQbpN_t0j>%Y)mJCWjg)CJ)n+qM;Ke{oZ9uJY$2#%#6)PfbqU? z8p}q%Q`H~7U;$tMfRFux8Ee`*n@X0iYv%%}jAGG(~{pc|I4Frq-?klQm~;D7+l-191g zat5RXYUN%+bD5a&@b&sj_|{B<7B@@}BrJ~rSg0^PkTB{& zP-YZk&~%k5XJs`N`G4O2dUE zCV))-K@UzVR$N$e9^g>>tG=&(S<@MT1O+4iFYZ6A!X4cK{^OyXEjp6ILbQK__0pp$ z9J{a%%+?*j3~2b{H!EcRBg`oOLu&8L>Hz?{VcGWG{H>3bTlfa~k7jPF4q)@{^1JA_G3`e?5g(W3 zCEB;mL8jkwDc<+Efo$pC^M`J?mV7&$=W@M!w&dZ!)=!HShq-t!jUG;884}~aWN&kz zL35OYT42VSc5QJ3hX-{4%2vJL&%*$r0T0c-Q2^5+2X5T6x#>{EM*T|jrr=*F2QvXO z^#?hatyobG<^gQ8Y|xYkY1!%UU_M~}{$QbEM|pT{9jn3}-2-{RLvgNt9S#o=!s}9y zUH%fv148)?_VEw(>`GFxUqB%WJ10*H0?vSGdXFx z2+?fSB700$%LBS$84HDSR_Zye<9n0`G>cP$Bk^_t;iXjiX(61+M<`!EpO7I=O8DmZ zOZcAuOZa;KC45u=4BruO8dl}=F5&jJ1MG+#pgLg`nDP2Hwz`b3uulNU;)jJ5lM4yU z%h*{YF}aX1%0;FWW6(^MD#y!3;Du?PCj}}Oidl*f_)h>c>x2mnMAsT+2iJT;Dzu7K zjT?9<`>_X3B>H~#cjJaSkS>dBU!CqypM=yqo@*b-#cJO=We1G4BSG=Q-=DkChB&)i zDO_^06M0)~NfJpFNQ-W<9gEfrCRSE=%jQ1^xh_WBD&dw*O+Lj;dX-QG-mCZ0c))2a zulHoTS-sR1TB2N312fjP$2lq&)d9*@NI1pA0HF>K&AyWW{%g7LboJ(5K${CiIN$Ep zWa*6`_?pW?1)@GI1^9M@X2GQFpbs!#utLG82j^PGs&L2pgC5|am_TYH>H$Jbe*b;+ z71RTS@~ZXm6u$DYVeItq16aWn(vs(X4wJ`4RO1&D^?lg!K-5`gJWb z9`yjBIDfbXpX}Z5D_+?&Ys$ng02vcmi!mljSY{$?GsZ*-BNM-8MllABO+T@63KK6H zTdXL$(yefR?6_@ZGscFvHD_i>nZ8K;>lhVf;_NlCs#?x^_24T`Wc=w94mNrRQqsPB z==rw|$;zq&4uzC(Ce7-;DOTp99q}69+v{bGc4S(c5f@|UI+3ckebna8v9%f`>D+MAGg8;7Exoh>Sg4rk& zLllfme6u=Mg*(zOhh*<8~ah$ zZXTP#nk8nS6xYOg=(+$%0O}87E%oE^1254*(f4Spza+N?0Z)YeGg$ z2_rGTWJWOtO}3+A>O|@KAu(-aGlq(|?P6wl|NNQw*F|zrV(xtxt16ba z0E4RUV9R-y!<%rvi79fj=wlHZwVROs(1T1C_lW>Rl39rhmTsaYx}x8cAeCu$FCAamhFRQYF?V-a2m_D z8gsA4?~v30B<2|~V@*v zTviu^6|T!fMVL{dwyPbR)kH-%EF0f-!;Mq5&U{9qqM3W-hESZ6phQK8ml8MVK@o~H z-h_|f&)XmQe+%E9EPSD(hSOjL678rSya&kifW-~d0}0D_*er6G9!MDV;A3VKW6=DN zDyK}ioiW-OOeVtalTQ;Ky;wGEn)$ppKYvUZK9^CXjqFS>5ob$G0PGqjN->O09 z?a6}ykMEzZ)ttQPF?oLWLe8W@p4NwV1lW^8-se9@BpJxXk*Xr^w>gnmbK%rzcpXRe z#-?hpTL>vx_0-h*@W{TE;GQ>WftsXvhW#$p)F1WW1)Rn*BOr zZrqT0Boxu1eyd(b_od<;_E>;yLIvbuqGCmPm=5rRvA;vp9clDU&zXSvJM6iN9pCJ# z4wc6p-2-{RLwOBOB!wmM!^RhW-EBc?PA@rhLLO%ldGFfYo3ri7THlmxzD~j9?7C>f zdHDT@8>yXgC927V0Hv#Vkh8O0bhzEb6s4%TE`+x4FY zXIJ$^qUvR{=pFtmo8e*ICDFB3`6yA#-#()1)5BrfhP_V2t!YG$;ce~7c%5fIvkG1r zZI-)BX?tf9^Q=tR%QN<*(m}@|qZ)T0Q)ithRp=~CdH>84U3ZC^N4B&@qSgj8*3%)|73^Re0hFzJ zp(zgogbqA3``rZi--zm>^tVzE>*4CfG4&0UQEBR|0}-viU=RBqARABtala^5ByK7| zCeuLNUjUOPjGRz$=?_ZW-+=iJ*XE9FN8%2@bwq_bx(gjH9&+Pxgd1oMAi4w&A-4n$ z;nHI=j}c~+$B~m~XEl$h&wjRxD@VYGp``iYK6fwb8(<=Ie=)eB|1#D3k zusWe7oCcf7wg6RtP=G8VSfH>Nkg(iUvtVEfAYoL1&Y4k+LDO5RoT31yjH|0x^xdd-YAl?otz zJiGQNVB<_Sy{U95$9H@3_Ei^Coh}`T?+bOemDim};>^{#V!NwJKmV(R8h;2SH)r&m zl2XB$w5yh26P0LAf;8&e|`2auHF2yd=O%F{(H2=_bMvN1Knj8c3{gZWua zadgA7@tcn?_NZ@fGj`Qz=H|u_${%-+r&exEjaCuD_ey+1{Qdt7U;oSwU!BkvPJ`{) zM?>|X8$cExENqw_NLbbb7AZ^*B#e5{BQuJDPs&S`24UdIfnXXDbEH2GQ}a{Ny%IZ|iE zvw>ydi$rcMnoJ(hiNx;+E??!D6WQT0VE?sRYI5qu+55eQgpvFyc{*+Ia3)uN7r452 zlt5mT>$9_SL{rp*c5oWYkT}}EbNuN`?NJYUf*EUCZZ6e>0RUyIUKqr~03nKpX1@;r z)1wFc9GvYCqpDczWz~`@f5Nf5qXJO?@&jCdeVzZJOW&vf6jm?_z}7)V74GN&2ml^( z=~56LDuH*^u*7>bwQ^Y)(0V>d766196@V7Pf~*z*bi=Z>hg~nZyvf!dC;({YZmJQU zh4fOjLSWrb0=05?(Y@x0SN29xO2zR285LQJF)B(}rXp)IMnwrD6(?s#F$T>7sd5Sx zj~jm%T3p{SVra zxy!S^saq+KOn;YMxA-%>fL5hNfeq;l;oGuFa4=c~N9y41duniRU{ zxO?W8Fw)by^gowsKu+UDZv9Fg5=gc06H}8yVF8JkCJs(x**Fn~_r2AL2BhLiFk?+$ z#b3q2`FVh{RWDrRVSsRphi1Pzr_x77cW%XbYbaySg*DC-PuG6pa2w4c73tS*5#qJO4XB8aevjzrF6?~gK2id-%U=RC=q~~4 z`j-H8{xd+gz-d^Okij|HJ1 ztOPT<^58KQgbe^?DFHk*DDC=70wwl))|M=R68k-4G=y_3oW`=s*uJ4j`Y-^A_N$RRD(rEEl6 zw`wC^hfby8I_QLbokaNE3@kVM)eT7paV-)kg+LiBJr6Loivp2)1>l6ZW5uAW#zS$j zBIO!FaS%-(MIl^4v*puog(38;r)Ia!2s6sHM{QPTHP_IMzXtAcdWFi^;);0s>Aam<>8#qqz$n3Qc)CKO}PI6yICJhH(3kBmtdC==p0^f2#-y_DKdTLZRoo{>4c-!aw-HJ9UXkhm8Ix*+)X}^O zR+G^0HA*d9LNg|Pgwt3y&M9GF?#7d}$R@j;Vx=NKC!nh211MYdLLnXo2xWL^_MHpx zzumz8(MkSi#-wdfMBzyV9ChK4G3l2Oqd@Ew4*}fQRX2V^G^9v^WtPVjj7)3V-W1fWN*P~b)vCd4wxLTulW)x%4RD@!%U6rT4SBx&D zH@~;5Pg57U$Y$|J_-`d<)(MU&;$K&(M49*YN1SR%p!*0Nq%JBjZQUpXyIqEKmkgIGVV5zYQ5_73yC+^v^3CjVquQ~ux+k>mPqr1>$;vtt$0iifNy@$h7 zgkpzE^C=*Vd?GUwVMdv0^?X3qGV`4V-LQ;}$F$MnR~X z8O0bh&85mIf^gZG7TPo0Zcmy)DL^)(2jcdNnRNmoqHBv?sUV~^JgQpveN>fakU?pO zmpLzHP}(_h@S!iW^N@0hn|;$DgVLbDt%XZL1|`*w<0ow58jx?_#%eHwl6y&?cOH;I z>D!<+m#;wvrI88S%S1s2C9~g)&)$$hsaKK5&66mchUK(Uqis35FRAPT}NfK2{D5Y_=K z)Nsd{2Rk8y5(vTu!0Z+W1!1#dr-HB*FzX#a5JtcS#~s}TLBK=#SxF>?;V4rx33lZlDkN z$MVdxPe{$Ke}?m(zl5{RU&1-{FX7yig|kiwfYV?F8oN<_hycj+fyEJv7zxV*1{OLj zBqWUb&^0rPF=z%#l~eQq-ow~FDk@)Jnqg^(Y(@{ntvNI6gos(9Yroy8J~Ur)RMjte z)5H|Wur%Z00pC@SVX5ke<=bo3D^H&6aZk$u%Qa^$-}c%XGAsqBE*-LHMHAv)Ce5k{ zWLPSHpu$4C^7drIvKiY}o(mxBUrib24jGmz3@BcwA7oe>tPV|VIm6im697HnG?p>2 zf0(IXzP2>OQeQA*OeetC(TV#lHT+QmmzxT8NH0C*_o8QzEU-3Z0`7dqdK zP<+lp=erS}7%d9`!i);QmhQu|S^&@u%f@dpDB)Ium|+Rc;$VFm>H$LW+eb9nDZr>0-##EY8iO6R3K-^X{vrg!GPjszoH7Wq^Nk>%`bF0rrLQ16{ zpZ$tFgOp0U-4hpeTkkfmO@IU2IubVafOsht}Vy8=cqzcD(T@gmN5{uh_v)BL{lo& z0W;RL{$MHq4FSqlz0jD40YV!dnthJ~{MQ2nNU6kq03Z>HSaUe(?lV7{Qt7$^Q2_1& ztbXqL$Rf=lr4oz)9x50Kzy0}974BGnAUqz*0UJr-DB9)ITL83*OHt@z6NKk4%7jOl zQNp*VFe0l7k8W5t_93q|S4Ve*6iVCZCE@Pf@z=9Y;D^uY9RWgdi95|RzSsH~y|P8U zDHG2EWK3i&#+WE!nTf2;7!xIoOuUd8#TYc#rOGMKnlBoE&THN;k1I`ebW1j4Y>1ng znRUYWilS??LeJsL$#Xo9sdlXG>GBRz9eITe?(!5;9eogntv(E?j$+HW*1=Rqo~>K0 zo(!puo*p~cyFa8ldVi?PBTRKv?wF%>5TrV~-7)pvNl10{%eTVUw~*?n%-+{EFx62< z&(~9r9j2*{*28Hm8>d9}Mb|rtsgAaS8EfjCLYcS+U`b|$S0Vw*KZfsX^U&;DquR0b zFp*Dn)C7w75q{>3P?M%QY5|ZvNrYSZK*fs0Gyq(8q+wqN8%T8o#0*g|67!|UF%|CU z4iFO$#q4GDQyd7nEW`-K7yjTjbv*sCx@ZnI6h~`DiRqSmOjZ*U-LP!?=Z<#={g?%* zjgC{N1b+4?q?HEHD`1B`g!3#R4O| zgpu%jGou)T=BQLTh4AN$hDvRwoccs_8J&>L=z+MkXJ(zSDN=OpYd9tRnsLWeVS@F= zTae4>&Pnff5s=HsQ19%qO_vGryzxct47rSMY+dYT^(Y6qS}HE$2IMk&GrLuV*O1F- zi|?8%ACKiA@yC8%D__1niR(}|!V_{CZO~e6p8>gy_B)lDsP0z|pC#{t(^xiowo_|P zS13qx865yK)^w&2k7Mu00A;IQc*?^7;Uf>tzFo(si|~9dqv24*mNE^#wtqr%8I1(U z^c@I4L9yaelc@lwKHh%mhgr;JG+V()_&iWM+|eB%JRXWmxnZ4RB!ye>n|Zb9vQM-& zp-a0>NO*)*y32$|m{Gz|K zkMKe_+8a+T~-a!g0D7Psn97 zdvW$2v*0OM;|9}n)yeKp`tMblb3t;F$NpC8){x8SqSNY`8|np;T08nyX$!fGHrOO} z7z(+JPMRM4{Ax0grR!=8tqQq}QujPH`$8_Gxcr(h-=Z)%@1zNWo&<8vemx1m?eLyHCFQIdD ziuEY!1H$qLWqm;Sf5d$SToujNKl*re?bd5|cXJWA*Y3O~7AiI>Hg zWk}yIbM4WcSTZ9LOCxoHJQ#+J)Cp>#*Cr+G4S%v3dNWJC4=9*iyisAPD%Q5k7VlJh zSNt85r9O_2VqA=G)XM3Wdd@${biVZ7)XY-fX=2h1ew-F!lkzN608^TvKFm^Y<_<7? z?vnn^S)>t4*5k$ELr5dEKg>ORck()xM4MX=pfo}O=~wP7f;2)C9;bch657hLYjDRc znUO|lR<-kUmm!Ui=fox*ch+ogIec(qiC0n8E#&{iycfQe<(cbSbku64y~{*XNFr8SkN{Mw;mcpCp8y_ zOP9RsW*s|0o^>0amt&ZecU!DuCuw&>3Nex=7+1r+U$03*8!k1&RyWqB@EFvEXB{H3 z)Ugxfp_g!Y4`WY=dzfyeIkg{E|5WD#F{tzS7}R;#e^O_YlEaa|z!7~JKU4q|3M2GL z@PmrAo?NJoPzeAUi# zmF~~@;g@@WAvEdXkbX#RboXwmnvb1RS-dZPo8J0uJi!DPEWMAh}VGA|aVo2?6{%?td;)eq!cMmgIIp-E$zhQI6ah zvQ_Mq%(7ze>J4PqOUW<~05p%(%`geZ)i8}$6WlPV8Mg2K<%Z3R@|^iZbKfME zM$`l)Zy17_$Edw)jT`@2T|Hw^SN9myHRqq|+5)!`RTkmjnnIeCb`aD1tv{I2g9o6{ z7okRi9#pK+gU}p74=N^l7#JVLxELp^mDA}V$bVd~+96N(vRp?~H8Hh-ADS51g#YDD z`!$5ogDH8S;cKd&qqZT}QONQWEBYhXQTF0H+eahUQT^V|g(=rjwMLC{_#)TQ{tRXJ zjYqDd*I_ejyhkvI>)<3Uwj$Tj)f)%X_eQQGbBXh>>tgZzdf~a3Un190nb)PpwBfmq z8sav#&-;P3M!5i<>!=&VRMU%>PEo(z7f_R8H*6VNm9a96a;lvo@bBrNf~j-`X<*+L zWdw*#c7G}z0Y!HJe(0)8X$rmzASlh)6Xe;)**Kq|lnaUA!FL*+5R5CGEKOZFq5FAihOMsrY@)p0*qG%) zBC#~iCx{J>r)Igy#`y%Laekk|fm*N!KCA!7-LidR2=)-a7w=XCdx+m_@3gXUG;U*C zWqQAKz&UgZ#B_OZ7;Mg2nX5u3H7oOE*vzsPP$-|!NkKL$);#ls8j7l@n8;>*d=z6< zHp-QAG5Tmw_{`t%chh&v-lvJFZTxtmtUMpKb{#p%dN$(Eq0ewU2a__mHHSkQoTgxp zXu!Yj=WT*La<>VTgFOoA&_bqK5?FI=gJ)|wU_sRA+PAj~G|)*EN7qi5JcH-~nk*wY zmSHxTPLTV(@?~wnvrZ|+H#bS+YKsB4iY2ryQZr&yY%FU-ERDGd`VaOpCTYde9T8NO zfc)ABN|WgY2glts#k;gMP3@hU6i3{KDv@U->&lw}3hRnP2#Pg6ig7V^QY&YteS%+< zH|_4MiN$05Ed*uX3f{EKqgYoycvGNZLhot2(;@`r$JDhOn<50I*5K*ssxK@aP$;Ok z#|TWhRovI@!ZC!PjBw1C_SIRlWw`yqfZszB~E>aSfaI~qZ$>n8YRrbZV8<4PA7 zSC>jyy6|RgmWKM&D*kQ6_<*3axJFRgIdIj9Kh?KpJgM(5p}vSP#BJz>O&!Dd;5496 z5TQ4sw^gy$+X__?DxhNOZO_Cf4>F-V{RO@yG46?yI1!z6fmX>*l^payB`8$KAtgEXobL-L|%5= z6HTjWS>3JZ!u$w~`7okbolpeEytz1b`ey9u-M4Cr?8^`slX7O4wcZGf8QieznC5&> z?{&D1Eg$SF-nf1=-_v_D#8lJqjzPo+fqasNqKMR{45GQkMZ13mw5GPa6qto$Gh?A+b%w_cm#L0YW)Bn9Q;$-|wJ@MKx zh3z!H7Pql|>F)K;Row7~#mQ`jm})w-1>=VufSS~-?2@5X36)`#qpA9dzyD(ReW&pT zC}My8t!;m%2S5B&8Uc#oA;t^Mbt%zB3qa91fG*n5kB8Kmc5(;bc)Wv-X`(ON4m-9cdzlF4BukJx?ywa+f+dQk5?>Pp<7)rG`O7D?{j)~eBwbAU?Qw5^ z+IZYsdP3vKHIIHRMVb?&M@a|1CJ0JVbfF#pROWv1t;{Cn7H&foXg!&+!wW#6E<%fh zf~Z(y2cao~9aK#0@G3rvaWQ^UE2p!=Ise`M(`RMu%c5kyYGP^uKXwW+B3LK$rlp+9 z*ui)13B#NReHMR4l+4j=d+)79l+31vk2kicS=8cKW>o_P6MY4)W$W}kLa_`>^SWXV zM9IuQc>WYc$vBF_h*F4>*)VoWl0k@)Nx9v4)p-t!k_o_V zY}w)BybNWQwqj8-Cn2VqPAY$fMh_u?n$)bEm7!I+D#IwpQuAWP4)VHzBZ>%r7TV!B zkCLgOLmDpB15?by-a(%S1lhFJ`RlZTPf*%s zkYMYfn*9@utNq(&G$pkCQ!{K|cIAv4+ttj3xjS$645Y6I`t|x+v~kcyijpHJeLWE5 z3!)n+d2*he{6Qa|#thR0C=64)Kw+3F)(lg;LSdLHCc|`!k7BSruv$4gJ0E}2226DO zoA&yYoXVqD8faoJr2pCrG2-2?@TLu#!3^_z1au)w!%3qMy|N;eyT=PeuejfI8d7$B z1xv5V|7N+5=#`~tOA(~h(4j;O&b-Z~~b z?SKbLCp8ClN|)L;IGzmh4gOdP7?Mikbb_N#X?995u6FwTx?@7yDK*2^PM1BoTcGh=CVG-cYMtu2l_CqDjwn3*Ya&%U$sNou)}z24A)$5_lv zA>77R2j1SzSK$kfnQ?%aYMSaKv;S&OPx^%5 zEKdgclsEdUF$_x6di3Kp8B&XJJHfc}f#(vZgysWkhOI7i99JS=BZ{H%X3s#1W~E=B z&P#iw!t*ACN$FA20eT>*G;S|n?@w)>5l`BDO=vT6{o^)Nfw^-TJv0Xt`Xbaw(1VJ# z=ystwf*w>%^k9vTVqAX1(J>#eTexxVm%v$wu<2N9 zOwAXFu&Lqd^B@U!3r|zJa=ClhEqwXz%$v&~!X};DYrkoTu(|E^s=Hrb7GYBox3N`; z8EZ3+S=n<+S2tdU|08`?l7#E|LS~;Bng8h38OP;Uk z59X=ASQAqV_|aX6;azZyH*NbuMgZpElLphyk++=?Qgr*2OP%+WL_V_5q#ptJ2PXAmu=U+B!X1{&u86Eg*Vrl_DN(-?` zsh#Q+x4aK$Da5{MmQ#lQdrE`^BXB3(KObgpN8nD%oV!kUPEp5FuUu$b3fyUu+Z=2{ z;Lfg@KF{|eaA)|$tdUs}xKnl1iA0kSxU;eN`_@TowYOORIWX}b?EgJtNjm2YiIQ2W z`FA)!yaWr}>4@9ds>H2xC%b**fjeCwrkc+83Z!|wo`9Ovtn`+lRT(P7D91~He@zF! z@Be)dMR;Y)lx)jY1nxvDPjyIi@C;CpKj`2UV5gDmufIsdw*!B#W1@o#nNJz$q~?GQ z=#uXng5>0$4Dv}U#FLI;Z~(Sh+2C=M=zxCw?x#iv1mj8vYjdPZXgZ)~*uMK!Yp33B zH|zs_9*|ga5+caA17~zVkRBx+_&gw}P3zgaPOk8$_NIz&?KLS&aT}_DcO-14nPoSi zpaY>cLP1ol(SgtuK?f=(I@l8*#UKD*t(-nO2=cG_s@a7VMi!?NsEMfs{HP(s*o54L zH?8AmMhA1OB*8I)UzxNxq6S{bmqN#^3sAho%$J1 zTpxfqog-0)N*qU=j{mqi5lOHKxy3h8om1F^{K=X*t#=_#XS&^r6Ri=av**@^83R7D zIGr`Pjjc)yZE>}Q50BH?2r<>Pda4sd2S)%ksaZKDL#uLDhEYz7yTyVIDpV?6QA&QZ z8D$9HO7OvM9nyGUAE4?<$>#O_bW8;Bt?MZRozws<^V6l|z)O(#c5J$UU^*57@R0aG z{GIxFK+xDAjhHSV7*{?h`XFsW^8q!(_T~3|)h^{N9;icNY5I_0KAJ6fgN4vA_JsJR z?wHrNcil7oRGb}n#kXCIUV_-08@I8oGQD3qu)1&tV!F)w6-MN&Tu>pCnw5((Y-Wi7 z6zn0COt6P=;1yL8Y9`o2#l#->;-eU=a$l~Ti}95P#ZpAL>~Z)`6I0vxG5_M-Y}b9) zkaJ&}ZTvZ${f6gYQbzi6n0pG$ILc`U;9qytHV(Y|P=@f!gk=WnkU8+41r}3xFvZG% zbW%mp7tP9!j=HP_xX547OUP*&a#bYI}-L#)P&#YDSET9LO52CCUzC zkax|C$=Ie|h`X_gw-ckWVSf?ahThoNDAwEV02KBjUcIoFzsL%|Gd_xOG5V^N(|g2|70G|eY#BE``;ggi$sJn#Mr1vFySEwH_G6`p`j!=0eM@A8 zOYY?qlbfA`OK#YY*4MHvVOima<2JT0-S}@}d;3}W$!bSJOf|j!i}kjn0ka9ISs4qc z{n)BZkYSXg58z+hG+c6}ol_2>i0#FLQ*LlIP;P2J9gM#vtcFFr>X}lH7ml=k)m2PsEDjHuOrKMKgoX0VoV!D27l0 z6>E!gLKj2_sbcCNbHzt7F2(|C)u__3{qVUx;eG6TE%@9z7k7D` zW@=5#^alQw3d84i`mXlJpTg(1SkIfGdq+006y37w<$U%^bUhJ0)Fk|o%X{F?sJ<1Sbf-oQIK{k!NT=-1pU38U{22Bpb4l4@(8_O4NV{?zWV@uc0~g?5{i zJlPqZk)sLA7%F_~5dC-Rb@_5?h!H zZXr!f8p)5^LJT(rFW$6VZfKglYtmKF&ob`$-ogcU#qmpd@_;V>`LM#ce`0#ernc<^ zzrqDKI@#QyL~z0FH#}(9s3UbPmCMwr(i<+gC!2h_=>`|vUANZ&<47ub2yNHi)UFosu6Vy2uNtNzF<=86sg>c5t&3qlFo&FnY$``Bzj z^rv))-wV0z-}$J2H*Qp^x^y3p)x6xYZ;jLpTiqyo_(AT~JDE=|iKVqXf(W%e|JBNT zeF#da>WljQsm{s%Qk{3kpw5ehI-3-G+=g0xsT<>mdVoS<#c{H=kHU^dcO>J!fmUGsRjJlCB!Dh=>c!r{GC&N zY;#_6)e1P_-e~wfS;@LZEl-AY-jxzgxG&xx?~w+n>L;h!ojU!hhL(V3jhwT=3AfC$ zN=KrKq_k8iob}5sIN_$vI%`lRIN?^04xZc>PPjL`Qw{7fqX4COjQ2tI6iH zW=^;zAf}oYpTPK`9H1tJua69^N)s7IIqn0D1wY76xTjEr>B)wtyIa69@uzYIP;>|2 zhqJnrMi=J*#aI$_aS5=_?WAw79OQ}YF9XY;6W4S(eNHTViNOUnlNjX!F$=w0Y8BYV%E@%_gN2ZbKC?^gsKR7P%+WN;P@!U#W+^2obCz?AN}{a>&=+N64_7C#MA=I&=(!UIE+MC{t z9(tOB3=xOsUmOWn;I+p;_J0mn;MNa1r|kn*;4Aw_^(0r|6Jyc@w1O+}&(C{8a={fi zUx}~x$rU)ulQt;>;R^h5;RkyUxB_P_`p|O`T!HO34sJ)Tz)7z>cK=+NxdIQxZESVG z+Hc0}L);a36vR~1s3=AclK?fTS(ze3tFlmrQI0Hh6&4K;Xr51sPh+aV2K|S|mHas9G z<@O=?HBUP6H9;`0_W!)qyM(rXYKHB*|1>$`M6yoI6_~`**91Y$6*z=FFzIVT|1qXx zOv<=c{6VjCXLh;*P}r$>pW@A_ShG{{3Wc4jnCx^-d=%qi+@V%ZUV}feJ9CYIvMkO0 zE=^3T!jC{9HYsyP^QN`z$LzG_)F6Y?iq`#}!ew`G8pnf|;j$aqGH)ffTMm{Ug9d+^ z1()3k_qJ}>3YXo2UimWS{MpQM=TnV!F1yWM zT+Q|mTz32SoO-|4Ddw{4hTGV_t94s@<=yXFmu3ZeLQFNiFz6T!^ZNm6QnTVAL#r}M zhEa}>0ApdNvdiu#6mdLpp6ekdq`8k)e(I3M^@*kh8P?|YNHgbG61L`+OvhxH;ZuSP zbW;6cm~<&Ex)bDT#|)F;S_IY=Od3cXGr{+LHNzwrSHql_D>9)ClbT`svU3*yc)Ksp zYfs{PO=z^j2I>TdGp{=YAKAOk-KZ<%kQfwllB$q}Y!tF)3<}x&Pla5A+lV@zE#;On z>A(~gP35o-05QGL zWbwuME%WxAxH<_=xg9HZ8!)I(5z2Et54W*>-rkCDKoahhy9Z*bY2Zvo0EYlIsaZKJ zL+o=Q!ziZ_*J42cS`z>gbg|-LU?y2 z$UrBx2NVBvDJ{Yily-|H$Ww8!X+VNJkq?^&B$(P?;|GFq<%hfx3C<7H3|n2u(4|q8 zX^UUcG$4t2*UVyV3G!^2h;j;JQfiZnGv8^(_Upml#eSnxQhYo^GIV({rWKy&8Pb8Nz*vyg

_kxIZ-vSWxA-6 zP%}{#6%(0cj*nujN>;gYSaQ&yScLy=jj@O(rpEB2YeyQk!1fbw$nu03_ET-UKnJG~pI;r01 zs_9Z1Llfjla@aRCK`HE=VDS{`#Tc4kTurfPcvM1n)vS?f*t_Tk)z@kVQzWr8h9+2@ zEmOijE{sWeQVf>3`ljW~e{G85B?*%grYK&P`2T;HqDhIwZK#TOhqA6YNwqVYH3`KK zrT@heebV?S#>JQp#qj4RlF8gtmb+DQmB+^IcaFAgkQ__&2acQ{9Em0Rw9AHX&&9K5h2b`~+?IC6s7FO7WZ|_W zm3F8h*tU(v2L$8F2W^)9N?1PdW^I=GUTPJ0fWsVG7?Vmv^>lOp)XzCF=x58=>ZeI5 zjN8x~sy%`kya`ZffKUu!@G92E;zAch_o-s)J{{wu7#Cw5wQ~Ac{EGjhd}W`lt;?3^ z>uX|a0Y4rHF`U*8@TNtLWCnlf_!&dTOyfp5V~Kud|2G|mVa?6rlJvsZ^yvaB6)raX z7?$YUd`a5f4NLTfvf=5kAuZONA>X>^!4iGrBTG8$!4mz)zRli`7~RCuZR)zNYp_J0 zv-+NHtFc7iD?@+Vc9>O;gxb_gFAYZ;(Iekt&$ltMOm2&GUu_gK1nwVO^ zkE%j!QmQ5iW=-odmeE6oG{J_eCC^`f+A6>0NsjA}X!rQpORCP@JuAIM8Q5t2Pb|rw z*qPxQ7seNjCGB}8>xv}v8Ni~1fiA=imlg0-mjVmAAsC*%z`GA^Xs|!kak2j0= zuqAjBOWy}NWJ_)Y=~2=FdLSr;(-kT4r#8=zL7UBgsm+l>o3U(-+fW6vjA!)F6j11k zP$NMPD%M61LURN?sF>)Xd3+S(Vr;KgP9Hsl`n#me-l0uDmKMuZ6H^QLp^1?%zd3JO z=mbU&PVIvYY0IVbeUBCSz4m>)S7JpzcZPHWd(IU`4)6sQc{-Sdl+I?d9rzSdsU7@;X_`nFVM? zz7cL?s}f}dFugEutm}>f_zaP;<8$eBJR@%$Zs`Qp&l;Z`!SkQyKB7Yx66kR>E z*wEH&Mg9q(=nX&*FLf!=!#lu*CtTk4Il{AKebO<}!KQY>20E!ZpaZ&;lIRlT>2_F_ zJc4{Ofz9j_462?%OcxN0D;Rc5Sk+B zK*dA{W81jU-#_Vk5=IS z&3bjodaS^|D3T=IW30e`skS8RDy+bN$-b`;Z6#lC$buOoin0~>F1U@YN|+b!uDUjB zEw-`;G1c_hb4CaK0W~RB_GD;P#>grQgc8DbjhQ^_L2ubL9X5R$w7}G+h;!2 z30mkQczK>i2L$6v2Tg;nB{UsSGi=}ev>=Cwi?p+RAZs-DLO>otlQQTGe|Ar&GSiz6 zDBgv5MZ)w{teKv8E5h_tOs2OeK8kTMu2UszoP?CQp2ud%59ZPeGX_pzwH&9zQM739JCkkjV`?HzwEdV=3 zSt5EK@?bqmr6i$6b&ppK4mHQ3`k7C?-5+7^c%?-~&=Iz% z?upyjKK`GjMt@q(^I$E7m}>g8^AYNa*8*x%v$9@>R>fC_*gN)ntV~Z{R4Ff#eVLLNDf^Y9?rbjTYrdM~)t%No`YKHB*A2IKr%^q{v-ti=cGhpbtT1amn z#vYiK*~+BU%pAfVW#gI55<38jS0mn-utXJWmMC75utXJ;C3cRFVqA>wYUT7!FxY=| zL_p3ApV;blKTS-^zzUOkS9iJRn-M)9JV}_|%-5yry<=0|Z z-R>Nm%RsB!ZGFpneDBRxw|C$+wr`{Ob2rP=Ol(tkABd@@w}&%JJP24!NU^#NsQnnL z+cJ!Dbf^;&n@&(pIn@|N+*on#>c|%?+_*YlRr- zr2513=#p-r= zI5IwpaWPI+E2mpxkbkwL0kg*bWXWEpX=2h1ewc+A+3IKTruCl3Eb-{V5W}hN_otbV z`)U24q1#qtajI#?#D4V?)wDdU_MkuQr=Fw!?3)hA{nTXYtu95epZew&RnN9S?x#78 zf2>=K+)uR%XAd8N+)t;K8`*Oa{yL~*Y zHp~6=5Mrun$4|@>p95-Av+`1gR^_V<5ktNx7M56{Tb_aiyAyz4A_6ktUM$qh) zE~QTKEFjk;?B<5a?29@k%PfiN(Mj#WWHwz&ekKGZKNEt1=nf79vyZ$4a){yCc6vtX&HO7HisKty@e)ivKTuFAN&m{1&&dZ2_+mDrHhWK}@i~ z0+^Vy@6DlaGCKk#?m4w!bs;HQ_C3$=lV^vb37^){7WnGM! zG$`Coe#`xkO%wCKp#Kit*=*I}6D#N=^UDoh*mW;F2a|H-p<4FkedKmh=}|1~_BXea zpGsYnA&8kAOPT|Vbtaf%Dcq4xsuxUATrxO_LH-@Y@-UH<2RgH~Yy?@3kx|E~&m`C| zL^DMuy~0DQ&b&4?r4T7Q|12y7i;Aa1gicu|Wn9Zbuo4BOVWC@GY-h~6IiXFFnh~QS zd$UGMeJ1^ye>{iN=#`)p%JuHwKW$IEoB!7K#Jh{p_7Li67s}q}%tfqg&I2g!5|jCe zQvVn8$sZrZxERZ*mD9WC-~3D}Xkt|b@Q;)VB25wAH1iVHH9sgDYN&pxLWV5xGx6?z zWJP`WnKWK|&ad9m;sMdQPTUy`Ka=Mlw*T;fpUJSz|C*kKm@N_68jo57Ka*^(1xxNg zS6(pv*pW+b*0(I}ey8@YoB1rQUuBw=p+hpuuWscV9bC>*LA=9lY;~YXt7Yv^jLuI+ z{25}ZZRUpi8JPiUQnT_)hE^p-IY}DjI2Q1)XNrFJGntDbvYj3g)uk6p1+iF%)D^D; z9KQa*hvxgZW65e@L6+1tuh-?&H8)3X>7@2x&`g(FtgT-aBx$6K53m2LoI!G03pTR;GLLBaIM=>slmFJbySB}H|n?4B*>(YohmbBHx z)B=7q5n?2j9>V{+jvJb0@0xmSs9}9@hjESISaLa^Ux7hbIsV>rZ;R*x=>o2HS(j%o z982z<-gVOvjwNO0 zkY@lKOR}^ok)hs4=2(&gx3RVG^!cV7NIHQzmgI++YFg$rv+&}8n$)b6kfBvE$uP=s zE8t&S`0tJ-M^MDA5|fwBI>=Uzj{=Gz8^+!zbtxHq2;js9p=Ewf;Ep9{fd##j!C%nj zWbpmQgc|6i=E30UQp)u}kPp7u$}vGc@MIHI1m||s44z1S?U~=n5KT-i;D;tQDJ@U(rtR***rRe-s3EfQv~+Lace3(?>0EBG z$Jj5E8yY63x6}=*I_MkxPLh0EoYVlnliYqa_HRZih)nCt2K9p9$>@}8S9F5kiDA@( zkV5b~>23eG=n(jwJhnt%tp&f6%D?XPQg|weTDXnv^M2=frDL7f%g#18W4e_5(0>7nt@uDD z|C|pswEHJ(;g8-tGlT(H9z7_!oXBM9xljY0)LM`UT}rz%5^O*B#OI>z*=#pKJ{Qi& zgy7-58krD`E166iuqUC(gqmTi8qFW&$<%iT=pv9kp{#6vn{Derzm^u732Kwy_O8ud z>e{?Y)#eE{+H8nHo5#eU%}-Qqw%4_}D{dpIEIjKqeKje4A*T1+wHITL@qj{|gq8^f zQn5Dn5Sk>|L&d}%lj5ToBz;#aC$mR~iMJ27?Zezs7HMK?0YBOau}N`Df0i{ZYahlQ z^>Umw^iO{9&L_B~JbWB&rrp{;|NE&)2zF}=**4ghc555a@_ED$?AF$xs!u0-xTQ>g zGITNR*0$sL*5g^=ma@V>>zaOWOL;uGqI+q$rPM6z)nOpqQUbpwD;_$VxuvwhZETybScdP5|riv*^lc{ zU;2>d0SVS+nIhOcAi*1nGK+5yf^lV!vgLdenmwo)wyJR{Y3uOglqkZRJp*a-fqs1{ zKaJj4+9`tcWa+?AgdoqU&xRr%_GkZp%mYrsZERb>tAt9KlvxlHyy(u9+e?M?zc3HD zNQTWU>j8!835^uW_7~x2o8qGwtFl?H98z3rP{hw%k#oQv*2L5{eta}G+?H$d0-8ct z+=)MjN&WB~@K}0r=-B5V%>$O~9Sbx5Z65H4QUhg(*&mp3Z9wtK2s3V|OIb?T7Qo`8 z0fu_H=UD@tRB!a_ba|F$IGAt(@GCciYmc)Q@+gEM?mnLp3qAfFIH<;m)1B zX|D&MY4)yL4xTl*rtgy`HD(EWoFALlidn*6<)2nxwxD=G?~_jcqcBVO>0HtAr!Y&H zJL2PzF$;6LBOf_|X44ZaVP6MtNQnL~UsQuWg+>v3FWBWs~Ab{Uz z3HzalH*06@`M{&m1_25#h5dW#Qkp{;4Orqv>aBOxXtZ&_^00rBE~kF{^?|bnI;nY} z2fF0Se}L$LAoni?JxpXU)oP6oNE%l@@LYc^Vfi4CwMyH0HjF_j-pu!ku7TZE4UD$Y zz(`dCbJ}R2v#Nn3|FZ_3#%+WKitm0+sZ2^3#Po{R4q_Jn2vDei&ZhD)?x^=ct68AL;9ne z9@NFGVRRdZ0hBRz@7;5E8s<(HPitWf-G_T!2D9gxUx?P_ae_LQ@1CsF>&= zPka>PVl1gvPN##5{(hgI8s3}OG+=2>%pW5C_mB{ql!x_r)BHUd9o(~?Gu$kze0+v! zz`EH6IOGByEIR(+rgdg|%gO5oZaKS%r5~JP>|1WVM!CMV zF%7ub{-Ey+Oapp!oHb@7rU6H*6O2{zEaW!Bp=s=zZ+=C*To^0?mKTQK7W4sQ@{sRDat||S# zBTe+d{)2Q(_HRPd=%nY2FLiOr;2;LMvNJj$DTkngiA>tsA&dAlCuv;me`(FR32pz> z4BMB@?H?0+-mKA*iw^x-8y?uZe(?CeQ^-i6kOBoh076SM^QwMs%5{Y<`HCpfZ~e|1|OtL z$>7fcc3jaY&l5kM#PvL|_`V|oxU9>G09xSz(@D+4n4T_qhI7{A6J!(nb6Jm1aOgD6 z;t9sp;@76}N@$CxX4qQ%x`^366L<(2iKTTxg5327pZsC$fk_!>k{{RgHNC2@9c}dW zV+{J5Cv1ijP=#Z>HHAv-)utn(1ARptf3~R7Vx8~5M#H7r@U#i#xj0L_5PgUeXh|5 zMkAzb$>SD?`SIQx- zC1Ak)!DkUt=DX0?ShXS9Lk@L!Wo&40KZSzz=kZ>A@?WFECL(hCwN?g{0H3 zY5YJiuKaN0#^QwL2Wp1x%fI%js`qt@Df4E}KpGLyueA-`!`9LxyNrIgj3AfNMNp27rqek$fDNN{Vxtm2D+U|j7#?}p_GZU58^+jpPE^6(^uST+ISbaxLfTvxDn z5enkzh1=Nbz|0p%Q|;m5bbTSFdJY=J?0+zzCN(QVWN1~!%P`9E8DK2zUk<1Hjv~^n zSl?yWQ-ss~RH6X|-NXJ9&DNx}fpcO&G5P}?Bm=Y_3V0eE&4cYy>6qvsd}f$|PHG+K zfG(wkbObLqq8UQwH%w4UNJsG9K#dLv#+43yx~xcOI-q9Qs=|^}qhHot$a2M!m@oQ` zBS#>DTE>Ym217sw*~{!CI_SRb|4w`F2<=7kc-)3wV7h6H4i*3k{Say+G(yE%OrKB< zK?f=(I#?JV#kd&Ps+H5}AjtpP^zn~^q6X5E;08@hE#QYHHYqbM@}`}d&gj7NR+!;r z<^o45A*L_=KA%VPvBcM9TJMjk6W6pXm^$VT#qYn7;F_jr-j}OrKkct6^mk)33hBKT9NSVnAERqoQB)j>Ok_O zHNVZP!(#eYLrgV2a+cA-CO}PUR<_8{svMAEl#|EpSkQq@Oy2~QAvV(mA4~xh^bbCm zp-X8zFb|OTUp%I7k&cM~?%WJB&`IsV3?W@gzB~jaPe6ify&#zR@(`3#P7sU^(D;C0 zT>0SromC0V2hjG zwqeGDbt!Z083imR`e3(TikvslNzFjVO_w~Lg{|Ea#Q>--;tOCu-&NiM-z;{+?-KY5_kaU!Ifh zylKnkv5x!f(DR0UxvK9<1z(=guGW#{%QJ3;qgQ+Q^4LAAoQ^U}?>4wMI}Kl+h^=SB zBH+t&yU}1H`SQGdQsMPPbo6a9bUmFBzC1;;_8LLHJb7m}Jn zTOG*LuGpmA+?OW;Vyfx6pRD74447L;&B_x%?Z;N-qYR@QTMmnb#sBWh(-lQLaV_=z z9QWnv1}GdkVDPkC#Pl>7?d?59m_c-`$hJ zN*&3$hiwW&(x!a(Hd^Upu!G8Na{~y*l@C0-tw~ru@Mf)&dS+@BZ!!z=ZDY{SvqC>j$`9Oz-cX|j%;3{4)HOgThA?;)Yai}H7evRdVj8Ju zh>v1ijCoKDRZchfEB;Q|%jf>VGfU^w#QaC}Uk4#JDPR5gUng3~4F1X~=wq7sp;h6^ z<9TyS9#5>@Z~Sz;Lg_T=0wP{7oDcw4o}IUskL?3j9>1RswJg(XTD;B=xR?vBJR7HN zf4&i}JR2SS3Oqq(Y0J(b)7Hb4=f;fHb(f}2X0aRow%*m(%$4UcZewfkg@2tGGh!+R z@+Rd4#8l5@KX=mD<~^V$H7g%vXjSY^OVTLEE`Wdi;r@F7;2;zc^wv3x-9F~ZGYnAh zI}CoLE+vB>514mpwe4F7X(0;(pD1$ zd3+!v0D{tXZ3H`S*9d@MTnV6Qr~U~`0B?=d3|rl3eRTceI^5NV#L~n*LB63K%N)&F+PgHLZ4bWsvtkk`#a3e=x40RTz#7SA;tol5Sx??$uF>`^;*K{B2mT* zhO6bgGCzW=PoY(v{d0gWYM$^*)ogxx%ai>bKmCHM&+Y@AhZKOT&k}3>Qe}_UwUl~% zd_y<5`b78dII%QbeFB3YPksqkAE%x(Cya-y&(!H19V^4tr|#Jc!#_`An?D!DZERKI z{`LorUEVQQpVAOhQ~D3tMRZXaP?MS!dl_1lIx>uM+z%KFx{zIc&Y*~`#YXM&q|KkB zm5Vwgez*p>=zvQPx1Btu?{+$s`H#nLhTx zKu`)8COGQ5#t#JJ$`A934@zi$pk~-A!!L(zr6>6^S0EBgu>b`5Hhb)YfuIy2T(<20 zo&MGq`iq4>+=gD@n<=}=`M({YAOxW}f)G@!jUR;S2$fJV5kiOfCML+1;Iwui<%q#(XYo?mKG5Z{~+?RK3; z5MK%BYP%_jZ58KE>1yw#%Of32z5kXGLKDDLLTXl;0ctjeXy)Lcviic1CuG04B3nX4d4H?KIA*JmK;Vj`2yt&>eG z43adi{9ybtG@c1v!B~!w5SR zZNA;09r+QZOzSf00sM%nx(~nbX-iAXGfPcf0b;6YtDdNovtk0&q-Le63^BZrVU%MrpIETT?|wuk6mjX(irL$^ zACX0eL?5*PKO8JJbhqj_R0midUNq35^^G{Ws@965>4Yv_35E%tDg*7RCAg1~q zoz3WDB%q)Vp=N?URICj~grW%rQZdoT==dnc#W+o^oSt6$qJM;oHIXOxLYl6LsRjJF zBgEKSK9VMxzBY6%T(9;pQghLDfyCW zHzvXh>CBfF&pN;h>0{cCq2z_s|3~A3uJA%Sx@ci5A9x{ESYh4u3SLNUQ-_59f)~=( z^+yX#J;c0_7UDLx&-+FHi^29hz4kJQsiw`wGx}Hus7cMrF&ScMM21n0jeo_8K4dSX zt|;O~m|u_XRoR}^?m8s;7!3Gh!Kb?$>-zFz%bV2aTBaI#i#+4q{P9K@j^gzw9ec6sxhZJ#{&D@SiEX__3nJ37Y%Qm9yh%Lf1qoFL;JLaKhUH^ zc3CZ-PnH?@3jRRduD2L??Rauar(ES% zE-2d8a;w|P%2nYHWS;43T>yWe_G!)@YdMJd1C7OPY+p`^u_;?bXJP5JCqqm%O?!PS zb>y=EHK|#dBSWjQMut(2i5gz~`_F<(rR9Ku^eEy{;EckDBbYx>MnLfuh-riDx|FhQ z=K<_>t#PC1uiOEskdDbPpVq%|)qY zFs_C1U;x&^A8f5Bj`cJL=RizqZk+CUbS*M zJ)HBOzI{Qb+Mk(!&^}E}E#SvAAvP&Nb9vLMEoSr(xa^{#`tG`0?cpC}SKQ^`3M?DW zR<;EUL(XqwlMmC#Kj^DNncimj2fayD`l&PggTk9vc4!IzAn!hhzRZJv(4)0|Th51n z(6*0vvzLT_(7I8xw^f9HQ1wODQ=53s?<=^C?enfUWkOIC&-r}|VyfwarrU@f9sz1n zEHlc`s(h1Slw;rJv7(2vmGsO%<59%hbtiAU>l1w(d@xgo#0T>MZ>3uQF;D>?AV9zi zSbe)}nqY}8XXE^3z+w^^e32g2rIXqRzMxAfJ3m2fUSJH9N)g2*Ei+Ez3xaXwi>?3E zPiVfNX4opj_5G_B^>SqnLL`QzGr5KJ}K&0!c$Lgvk&w!)qV6ahw&*ar^-EEe<-w-#l2_q492PW{ij8D zCVW*ahc6b$kg`^L%N@^d=l%)KZ<%soWgNyimlww5|P4-uyw{ z#)|;OU=nPyN|zFwYyiw(=i7q?NfI+Q*#s;cUueL0F{txoRh^gX>ih+_5mgqW4^3fBN;JguemksS z^pVzZNz*5xW`aIcY!(_MG)riViitil#78kM##|_dDyP%ODgW|Uj9v2Q7(m|1c{DNq z5&gHE5Sx?_CHP;bU&ZL-bEQj$JJa7T?i-%ZQX?WwvAfRL`={x|@C|S4S;ikaSff+! z0+v+S*1v0UE`{ZJp&ak7IJU8T>TtB#iTOx8==MJG+ck-Yi~q; z%iy&WL)=Owvy?2PJdciaBKk;P`OoK_sYhw|jLVx7edLFj>gip>n?@hS0X3;vDJes% z;v~Z;r=(Rb{XKnDs8qV5wBty2lp(y=z#n-4MRx)ID5Ohi+MpyL*JpSqV>D74Se|vP zpv&oNr2(EWozy-oQqZO3txS+FVzNaFg1K0Jjwck%Nbvdw52qB@*{lM=o;h=fj~9Y* zrH`H~n7^`A0R}NcqYw&+`Pp++rscrmN(|UKt2;Vhi z*8dLY&tc43JO@0MNgSST4=ayy+6Va8{l4svOvd*Rg$U|}v2~e!N1FsH)zq(UQji{hH@ZW*!3sdGr)Z7pSa@ zyLE||6{B^Tl)ShNy}zGX+XMAeeP#kldYxs|`e#W?Bm)KhzL z7vmhbjjaw;o>Fqi_X+t~?+Y>2wD9-sL{}vMH7Rlh$Pl>#WEkbR4e+mx_;(lMBPb%I zScCjkyJJ(4pUP1{Y4CnZmr~~&3i!HKxm`{^e2|W#0X% zpWXjbKl8?*pUH%NVyjKuhThQfP0Zk10}2fgiXnPL6>Dn&LKj4jsAB37+r~#RF2-(Z z<#dC;;y*mwevb(}TVM}OOfBHYP$9-1BU!>((;9DK2HzoXxZ$kDe54^~@Y=y^? zddLlx zy}4u1-kGu0Uc}SmHuM4$Z)0>Y7EtJiP#Zx9D%R*gXo{c%6%!pyh>v1ijEmID>2wh8 zzpQMFF5Rm#7vklbm|DP(r9uq<12^8Z1Kx}dn)VAfJe!_;)DyT6AFyT}o)dInO4=z& z`#I??`&)eI8Vwg>=dlY4LTVOFAll>p; z8*ZSJ>W>bdE_wDJw&^uN9{kHXc!E*~Pw;9B&EN^f)!;9FD3;I$PtCA>*;Sjajqssu zK)l%#lKOx8HUEBQvvCCZh-fn{(vO_UpKR|P%o3LY3QH7kOjx3dHA@ulOjx3d$r4w` zM=>tO9ctxtOFZwtpw0ESrFssdd9YoYm~?|5^M%-?Eb`?|%e{+P;u!yMLwaZPZSvjS z;p^v2zPk=DQ#yvicemZ?ntRE2H*d1f56O4;&gcEhX#rynIj>!_Q z90@njN%e;%(xue(60FVAbTM}sf;>o{b-e^XuGcJ)U|cOR@9|OzZHd$j+n4?2!iN6s zGBamf5=&h#dj{c@xrDjP5R|g?%)hDY=g$A2pAk0txi|*>O#Y{SuET9amBq4}rhz79 zE5!7E!*?@2I07j6KShYF2-|e<#ax{vES<|NMVSKPM#btwe)yx5t;C;L0TBGBi;C)*)>6`H7YbscxvYi=o z2i~`pngpz>1n=9*#~1qbg7qSV=6$;dx3PWRr|p{dZ_2%I4?|2f-BWEd^~@&#HK|!SB}1!nU4~JP z^;2H{`+@rJ-nSi4M7Q@za~!Ldh`!9b0E$Ekpobp1l<1)^pqpQ}`k7nsEPfuq>dR(} z^h0zxTUHweEY?^-AK#N-Hqc4U1%1$^l*NOfv`9}-8o3iRe$eQHU|i{A?W}SMO&`<@ zTiruin%962aIcL_@iOsCxYzE>*YWByB>C$xdT?HHuQlDj zw0Ah%YcnP-H?kPqYscnuo=fhviGypt>yGS%y)LJ=?~LA7uC1 zDJUXYXoFuPxO?qF9TFj|0Nh-3+=OG~UW=*v)xct&mc|e3bvYx1O~9ge03qZ;b?Kz` zfe`4DZ{f#A_5^u)5cVlgP|6BSu&Ozi_>?CYS3;=UuzW%j0yV={8MZ}xF26mCx!l2=ZEO}`zZ$fb%;TK|A|3=>#6!XNY~%HxQ(dtIW;S=rlBU~ zDa7=C*B@Yf5d|ptLgJ=%<(1R_;?Twv~Es)mP592nr&)ci}j>uY>nG^7Fh^eMuDs7?hL=d1RH7nO-XjPudFv`hm zODy=JynX4)(mMMFlp(fL!+>HFpcp@5K(Sqy5`Xvr^6@dx0=8er^u19E)uWTzgPA|N zl-AV=^4@VbdFvD8v22Vk2+|%RNP1gwG=Sl7*Oc3 zcqKxQg@4F@p~u$vD8|L;s#Z?_$o_5lyNf1PwHE(K%iqOJylFvhXd3n=seZ*UssDwB z$+7%>f8UxNt+4!k+*G@}!@S}FqZ)tuXB?Kl9qK*ba1P7g$8J`C{5H&N*%3Lh{~|1Z zH%Qg1-w-T+hj_1Tx)K?-HiU02oC?d|8`tjX_6p12?arn1+`F_|09Yj&x3PUW_xkw-`bbjH{h`oK9dn4P=i%%a{|!Am2G-3#G`Z?)s-b9*aRA{bQ?-CZ#oQL$75- zcV^(d0L2>@iXaSJ#oDM>ynE46shB#dKJihEi*cx0IoZIImfu#mTOGDJo~I@jie+b) zM2JmF?Ww$JrF$|1pFjVKq5j#~k=3x=eRSArx1m_y+T{>g^i<|_0Xs$>zI6o4-9uJ4 zt|d_&2hi55*}8MXF7Otn3FpBZ=n;Cdl7D<=T8A6u0hGK_Mp zw;&b<{(DBP4k%*x?C^DN2ibCWXF$Q{G>fK7X={w0fT}W(z4rt3s-AIp@C2So@2QI-$t%bqUB@e+qLW5v}Zfxy`rNSlHDh*|VK0||Gg4c&>22U`q25&dn zIiWjdYKE<9Ja1EY$2K3f{7qsh;U2-&?`Rav2Ehb1!nAj7zf0HVW2!bEu+iqBF=+D( zRhu8%X!E*1wYfKLBdQ#xelu$dYEnEPruX}>7h{hJfI^*wmI(z?u{H-UG)b_BiitfY z#YZtN#(8SxWcH{y^6{1$_H1>0fhMLF@S}ndo0M)>dD9m6VeC=i-W5ZsPdn4y#OnB~ z!p*lB!5*cijyG;wmEN*x#v!rJX!k4vAUMXR@X*%#_D+6M|n-r zn^IcRR$75HjUzU&e|H$Cj;!&b*hEV;uH(```hA%tP6HH{DBhT` zL=|h6DBhW{L=}@I&Wev>T#QT9%IUdi&iUUepS!3}ceXmdOcRrC@Z-7=o0QoFt}>vcs`wu^e)$yVY%M`AF)$v!$gL3r8>bTvayDcX2J?{$O zHnuOvnk8S_I<2eGK)o=;RMQ*p*3;*IQ9w;MfvnM5Bup5CJnC)( z4cw>I|5HDA#kYRKX9TyQH|FcX41NWmFnFODLIqT;8NAR1Vel#@gI^gR#kd&Psg={a z-t+#0H!c1$Z#G;0UayI%1^gHp6O0N%9j1DU}O9C_7nsnDWE6S4fg-|{4PB$mJD zbpQHK6qdiQ?=ANaC7N-z|o`&ixY0-}nI!-9<+;xV?n9m@_qU&Wa59rQ=bOp2B>ln7r`pE3 zUYgv74u4OF%NSSsTl+i8aDMnZ0?e4xodY&uz()d#RxP(!j<9Ei91U)klX4L7|9AMi z5+q@M=eO6`rZD{do2xD%K6>i{2G2XXsbE(a?}k_L1`=b0ADM7RfhXo4A{>8iY>pFP zj$ni%@*in^h!KuhnZB3Ol_-d*{$hk9<~G7Zua?X22*+X=SGJo?qe(~j@oY5n`|Hq| z=!mjq<+_!ULmtS+A$w=zke#z}NW;GlnE;nzd1T{NqRVNxBrs!zmK#k4;4vT*0Olx6 z00b5VfVm120D(~eGV>xCA61r+IY|I6=u(GVE3n&bbR|d zT*ml*{~R#lmFXV(5xd)9#+*iEQUQ1mC|b4LM>%?PrU^2u!EHF;fBnR7SWiB_Jq?mr zm3hUnF@f!)esQw_+3+Oj!F0hMP~FrgsRsGT_~v?q!L8E!(65Q5>Rh^-Fp7zw_=U%)4P%1h@=V;Iwg6E=-Kr)y)7~Xc{|C^w@`{L7}abM{kSH(m#Z^Zvi zXJ!re$|{-uYv=J)E>g=RD|XnV-A{($?GMZPH1vbv?ahCFJ~o9tu5@uFC)vU9_KFE7 zS`~&pt_+h>z7~W%t`=7PcIXuhZ};i2Quz$_xO!i{Oh`A_<7(X=hpsL#yj{@od$~v$ z-o9Vplhx=Eba?v@T*lZ3+D*FidaN*nCg`3Re8)of42eD?lzR0ZV?l^s4>tx+tR;{O{K+qLq3d1{`2i-FITl8(Q|OLQ^wTn~47_nl+qRZ@y@2CsDbu2uW7>>{s8%Z{jUbJm|Uv_qNX0#`78aWMsXgp@HN#IwRi92fR^vDEE?t`R62FNTn0ZB!276vb zrns%ZZ{l6PXg3?biAUC5oq3M`CSEMr_O3t@%lh1|*rwla-1F+Tgt$vhI^ey2n>_RiUJ&j9vteF* z-FPh7@pZ#5I9Y)wmIvN1@TY7W8bp4mk50EooZ8NY^&lYTHsWpEo|RJK#U1;(YR8$F zgsv%dr3w7kwQ%_;{ICA~-_`iv8^V9doh1p#Ci8}l{xPNO1^lOYu)k+^<9`<~{JZc; zbz9+ehOgz*wSTL^Vi?!`IzJl+U674~ zUd+ZpF9{CXRC3U2a2b|mHr-xyK@C?I%y?5ehfzWB0Azx|9ES;lz~VME%ypO`2#kWz zEH9GrQFRtFCryvLpbL1Ie6DR#DhORfGnRlq{Fqt8)r{kdW)@Bbq11t7g{DOLlDLZ% ziQKv(7Iv}v*ebH*T-e3xc--(VxQo@J3FN!7f%S2WUcZ7psWhe=ARc zU97B6KME@cyI7Si5P7r^>|$m4qusz#u!~g@Yny=y{4Q1=a2ezK-9GTZe6t#K7pt~l z#+)wd6oZ1$6;QNlxo&dw=K9Og;FbaSUkk$j-NouNB+;$S?ZuPs!Y)?7xt|iEAQU{9 ztoZsXsC2x7-?mBt%;X;h!CbPVAPn1|tiTh?11$plDcffTQTDMtMA@cyhzp`ceL&2u zKCHBOmEZb+#W1e?d6mx@NGRQ=3eB>Gaflu0+Ci8;dzs!p@qNP8uS1gLui9+<^~`_i zuNH#8T1x)v2bW=4X4_PW9tq=RV8;4AHkInb1VE+_%#WBp2rO=r$vlbagTSZ{lky@N zAJse|b8>y?wRTK3hYEC?ss*AMOTZsJnOVbi{LU9`=ya+NP6bjF<=j`T9Rb@^jXggj z{v&KtHT30DuT5F4NxbW6D?iw#s%6Yhv&OJZRo{_zySulDV=U#1X$i+C?VNVA7+@QDDcGcfIi?)+3wbe{5N4~2Lqz4{eZaXg{TjRxzz{P zyIJ|I4_FN2%5T~D(}MT>K2&Jt`&{Tsc|?AKEZr#wQPy4QQTc!8uS({x8qNnUgB7Tr zNd;gyAQJ%QC`i~=w!FOu<5g$tRJ1mKMB(#>UqUN{WL^|>=eGnRlq zE;2Lh58i?=TJkI^0K>de6sOCd*;)CLE$Lr1ZNQ^KmgLQL&-SI`+L7@VWd{3~w)A1fxw>^VKTUfA6>7D$TuHomjU8^XIu6HftXtXFxl}TzXbq`VO;su zn(oLtcHuLwoJX^4ZUFsj+?sC_Z6F}xy~6`~5D;ZO2q8lx_wARB`&P=veJ5w*zD|Ps znn>;&3YTFexGYQ^5*<{-O#w6JZ*ByYi=}|ff0$b_xe!=vFECGHav?Cv#j?Ce#z(bT z$eh%{a7Nc+SObgKhliqEY!%H|0{-x1W(~JAiZ5D|xl}GDuT4>$Y@W0`_LMEj=sj-W zfCLMo@Y?dlqiILdd~TI>re*BN`SmN#9PzdwaaDJkY<}iLicRja|3jQDSrpi!_XZ1& zcx8NXnP~4vR-E3psSQkU7_}|r!22jADO;jinV9yTC>QhLGRF5iIpoyjjAmU?E~3DU zIUU)D%EdlF(W>PR%F&xUFGqu0i*-4Y3wzl znIVb?Vs6DFcHqbS77r|ju`6_#)?5F!{Z|wZG>ff=M2gX?@Ys%1{#PC6Z{^2%G%)uA zvYKKQ$m&L5F)&#rvA`5q3xRngFOu<5ofk5PbU7A$jlmU zM+RTCtqW*iu6mQAST?BcmM2GGs{W+PeMT&@fSx?(PD}54k)Cmd9A_4{BaZJ47j8sa z5Oe=x-K}kVlVzT5*It6ZpH{$gjP*4oF)^tTcp%Y_^qj7)GXVa+_}I!1$0RCATEyG4 zQ_r-(z>I^-7}ti&M!VZx!n$E#UI8-}<<{_Z_#D3tC|Y41oE*Kmr*bs7b<4^@U^>=w zb(R|P{UM1%$`&uiPWg&~IRudDFg(XcN>&Wa(SS^qAuz`Se!EbAj7^2#G%&*?#=v~{ zIz@pemJR|Ff66|YiO7FMn>OnaWlM7qt!{~diJ05Kj92{3@4&=j7`s9((_%Xw>AzuM zqFMIZkH}Aoro)Jc;%k2*{bO-eoQ8`poJw!BPb3Z7D}byXS@p7-6IcveR)s8V1;((w zo)^jZsO|}wlRr;~-kN>LuyGKE?L*OwuEHOKnOVc7+w(;$vY3W#QlnJG_^dsPx9qni zPBD9G&hBnOvUXRDIii4%=iS?$Rn@|dn78db?%o9pvb@f>jg8y(A(>_RrNzMnCFMKh;pCp(CI7h+z`l~%Vx@=W)D{hWsK|U^bm8K39;QV zY@dS}b9(O;4coVXqE*Yim!miLM~(*fv5iyzlcjM1%T{z3*vT(WX1OPO2DE;H>M^<|D=JsR$>g)`j9<5u{_Y; z#-F_3(Fs9_vi3G&ds{VYZzJY5GQZ#Xli!hv#W1ez@o!evsbuqm4$*;m239!5bMn}m>%Y&g zPQ!s1d*-4UYo8wB5zMUN-i7i1dTbPpy|Qys6+KDgf~WS_l0vJ?E;Y5WAU6Y6bgE

Sc53o_x+@a}s;e96xxH_L9iV@s-bJ>|T8fRY^1_Q(u>?@#;> z?b`UYrXBH$u_}A6DSY{1_MUV5+qcEoYYdk$u8pm>Gj3;{?SZk^49u9*=D{oRk=YJV zv}(Eba`fi<$kE`Q2>74+zW#r)=Ok;)K87@|RPj&#;P@G1FB6b8ks$V7OID1%4}ep? z>==sy5vdA1v3&5*#GfDOPE1E}t{&odZ`@UmJ~R>eohRt4 zFyho(3$ zJ)DjI9%KHi;fihLE3npbDhO2pnS(IDVS*sA*cZlJg$aVdCviE}_V!sA`s^#h85&9Y*yf!`B^d(&&jTd0MZ~?js&bQpxf=1vh%4Ak+dg7Ny5SDhLe# zMXQ!`lA|}*OpXTk{eU?U1bJuJc}Syk+3Lk_)%b*hkO0UUUmyrKBr7(elK|Np6zD?= z;M1;;7I-Cmr}~fvEbkk;FWFHaI>Qae6N?M_fInp)kU~ttub>X3`hX}KOG6xaLevMu z-0DN>_zU^14_FLieTWJBbLrgnpZMrTv+Tpth;**@!Aq!lAF>pKNMKV4rA0cy6C$>(v_Rf)mwsZPn;Pw{HeCgnS!`Cn~ z#7OxxTJWJWp=hptHLIp6J|*{k-hYQJ3E48RO4GwIn*A$0(W`b>a^iQF2g^UJ$vk_X z%$^-B$rHC-F9*2#5tpmB^)`OACEoftcXJ!q<=L{m?b0s+q`)WZsy7rn0GRBqj_1F-v64!h%aQ(oHxgF7S6+X$KH(l|CS+(3iK=F^gxllP8 z+&=>5Byb&M!&pVDr76;r*4(?%@FNamm6s4BwIU$XX^2!iz#=W@YBM9h(N=U#i7_%q zRY_CeiRFRF#Gm{q41IDVhR}m9c%^?#m$=he_J~U@>{z23F}IPqzD+`YMsm)~|Xt)rT&COdpsVF^3UY)CcA{OdkYBedv}K$@r)Oh0IAU{nNStn+28D z`i7uB1dC=Y0X@R~nOVbm4d9EG96|M=?Wi=xhnkL&JE0dktja*k4ztXO(s__u*9zT8 zqj7$ABi^XVfWu#-|BkXGDLvJ;Z{q!kW?ce2byUeQP z<^YO+?9Hu~qrttz=$z<7gL)d-TXr=_!)nKX$#b+HP#^3i#HPIq;LG+EPc-WEl?sBp z#3%^MMy4t7!~%dI;7@*?&0%cHBg#J7jA%!fkZ*6?*?xVx~2X?ThZfy@j~WIOjhbJlO`sIbo;dLPW&ns zgnF@CH1kII-|)T6tl=UR>9lBDBdK0Q6-`%^Y!qib9GdpsPPDDPvbH&C)ox+CsPyjS z;w|qxDRv?TO=di$(tAt;>$s#;_;FI5V5I3t>-+kq2%)a%vw$HYRoH zx2c^S>98v8c1qvE#CunV`yPHU1I<~r5iVnVzbjZwyxw(kAJmKOV8+}II02bz!kq>b zty=D^9KE?)ax}O%FP5HzrhS9|(?Q+?()e(#P2gF>Tht3*2~jUX06VoCoPNRlGu4X$ z!1A~5A(9>SBC1Hb0#7Uu=mq{1AJ(B1`6+31O$%E2-K(ylULfxOBI*TVZuP=z=gs`q z3oM3l?YEjdbZezQf3a0rhIC$&2m-A`T~*5wFQk%VH+N2s2KUCk zISYCD{xlsSjaK6ywzdt;!jSJFA%=Wkz-iT+`fMroiMG~*B*qZ`+&f)?Cl&xg9Dm9t zsUuF-HuOE#ns%%qUPpIcOV&D5Lna)=15E*1V(+x%!_1vR3C)QN&0Y1w;}WG!A)fYP#->t zW-I|c!q+o1?8CZ&FWT7UR3A?6NLTzUU=cTFw=LQGu-ncGcMFqQnIZFb4(v%n>n-{= z=8BrwZu@3gHN%oDw_ks$OpgFk?QitlqYc$$gIX2Z^pqJXZbD2vN(YlowQN$4c7~}g zua2a)xlouydRDLC^PcL%b-0Z2{qDKZyU0+hzNil=V8)z!Wl?>204Q3u++#UNUsoMAdMuCAxo#EzD9irlMwY`2H=Y3VRcRy{7Cg-j>M=Br6E6fVgW!O z@TY8=8RE_gI3I(KnIrOZUFae=#D+^meL&2uKCFD1@A`nnFs|)Q*Y^{|v6h8v8P-Hd6LQ!Bb6j`0IP!t$L@mpRb$(JSrJ{{QJ1s~O);WEaRb85}9rFr+I)tCmyB(VHtPM}zwU!2iDEy+OSOvW~S4kjCzHp&K%SUtuW5N{FGj7jUM! z=CfZVKhRJ-EHQ>+UC2D1SO5q`{K?ORq8)39yl2rzHKJ^c9I^c)F%%JV8;UiyKg{n( zH5S9TwinbHv+8PhQ+!mTS+?F3k$(T`C0%cdD0Zy5`hB#%D>|rGHV(Qu8wV|tje`dK z>!6A0w8zu+>i-N#BhY5nfCgVB2xn_NJR}i&jc2@_bC|!R;*rNd>FRj`iBB$?YXso=$tsNI>(K zo5o%aCaXuhy`Rt(_QPsYIId3>bK-D)eBk*WFag|IWzp*2`yFO|EACAr$g_qk4ra{h z0d6@8f(lTyYPoW9^yX^G(cr!sFeifG&`^3d?}0Riw_WnRV5yflgnj^!O_>0FI4W6D zA5H--|MY!YKh1lp59cLDedq#r6i+M<=mY-b8>(~%3PgT}2z^u|%ErhMN7k##n(~Ob z)rTYJ_T;xdU@@3JuwdKTH)lSvK($QT8EbMA;a*O)!6F4Qpv+x&yMBVim|D zQ(!SNS)H-S6c{73XVTRg7EJHrX>CP( zH7SdG^bI6YYokw;>Y*kB3+^hB3OmfDapNvetq?-ougp6(xSJhu(OK6u^D-xuyDi&& z_YaNCI&c}|%K4n;cjMav8kwG8#+-hhMkBKwplH={9pnhJ-Q;L+zXq6-$dvC5@d(n0 zopx+=#D(V=na=>35<_IZmaG_=9{@k7loL9geap{w0~TtVZZ-8yvTGd*m~uaW*}g&$ zxnq~zRp5!`g~-L9vX^i~eliz*vLni-j3X|aBt|Y`t|NE({``(yEQYajD1L_fs%#73 zlO4^nMmD0@?RJ@3@mAsi{qks)O&M>vpTE%o8)+bS0Av-*>YD|!z*<(7tcqFH35&-NfHBX@6oA!;~ z04p~}A6av(N;lZz>5$pNH`cw0d5dZ#PV9tFolm-@aIv!@ZOgsC?6NzMTpROj!I%Iw znSNz#%EX;!QT}5xdI`tD~J;OG4 zQ3)|}tpPh!Yky{Cv={Q7gWaeE3o>)MLT>Q!Rkke-_;%2%) zkwz{e|7m2p3JY;}f*84oxsBZK{SW7Nv1oQ|$#>^USKn=cVVcV!8bZc-=F?QGfsJP?s zb%(k7IiwNn;v`)R*spM7L^nSi8aS$S+#w zNeU>!)VQurk6VZ6zXZ*y-v$(+(A=9|&(@ohq3?d~E8PHAi8!l5;4;RFu%=qn&8X_o zbD-gdff;i;XWR;GbdLoTty(Trj^5mCIU3x*1Li~#TxE)2?s!je`0<+fjeVZtqrDg) zTetuMQChO1K$HiZ)#CHqN?Tr2fv5<)h~FiWKH6<1I~52uupl6M5QzN__Y`KKy)#3Iv*E zjdH}ZUuwW!+|Yk^nchEH|2kS_YrOk+l-&EJ;NHPT?roEedtb}Oy%mCc50l(`0$hfb zfc3A74y@s(f*Gs3!FDPqF@VgynAb5m5m?I{ia8o{Ac0X%*5ySqKB`?p=A?J{ox0j3 zeg=JN0y9&4srHCwECD^jYcjKjn=_U#+Os$+Ckw*wDH<3)Jx)AnOUm}G^s}{1Ve;eS zHlK=(`j8->WdW&c)#Pf~y&AoX73p|{*x%3w5nt7m_?R(jQeXYkEpE3NaSpA#(yU;J zJ~GtCAr{`@Gwv;zXmi1w6ztOfb;2nsCu`s`#`pVKkA$JahEh4%3TDiy`XiN--GHK1 z%f-vln>#5-gL}QHIg=9?*)DP(kVYxfA%9JpJwZ9~1Z0m7kdwBO73HK8;Ixyjv4dS+ zQ91DjmbW*0NOmeGJ%QQ71?1$(lzR$1vAiHB_>*oUS?CZ>u0yOzx2>n`4McuN89Lh* zu|PjjP7re|C+`jUE+<$FW9R69xyH;9H473Lkw ztrZzHcU$M8(}PGc``_`y!r-OeXV3Vf(A`#Y>ya@RPX+7W+pipO6#Czrz0Px%h8)lm!rYG-SwP> zsWs1^P>f6W<2{vULs+s>1-s9r~k7O?^Q_bp)_{a@`ooj@@q` z6YnYT#PUIC;!oMSZ^S>hLtj>NprMH}E@SKxj~ZsK>i&W1!%r|{PUmG&eJEJ*zCyHWIfWd(xl(d8xX%F0$(un#+4$UY zNTd6!giuFK20qGH1G1(Y$i;feigK|5kUbqhF17(W&i9?~8TFjX#dcu%lYN(DN4Zc# zQSrp$f?VKF*}yuYY(*QQZ2uNSkAl_NiveP8ainUr^@+qIz9f0$ znx>ZX)x@*V@{Or{=MImcABogST_JW7RrJdbDPy~F*Yx30Y$5p zvy&ryM^=so_Z@&akq;+VX*BO7q>)zr#(vA@kFj}iPC{(@Ujy9fR(@aa9?$6T-EE0c z5ZvGv;)w--wmkk6*St@s*t?S$@@UO%$cLYto8KXi#W0Sakb^z{TsJR-Ed(^ny7>|L zfe^YfM#5N}UHfXbEAzvXclJQa17BUB)a}kCKcj|g{t-bfIGmOafQq>jB=!5hK z@6OB`j@!c*ZPpPQ^4!t;iftR6Y))OVC4WD4I56lkM|y7`H7%faUt(5&rNJ9o23v+4 zC^p#3icDQv?c7M$VAAYB(wy%wr$N$-$Ghi zkYIDClEwDYkS`0DF}~kroZ<_V=to1|0nC`wE*UiB8v%+|*g;;7-dsmH8r;tS<|yQ4 z>vPf|4Zn-6oVWNr!WP2=K-NM81;~`Fr~t13WBc~VxNZNGHWA(c%ik#8OLkO*-bdhx z2Pc*fnh5w))^~`=zunXQArWPLhlmr_iF$#UTfI24cwv6)1s22D8A`?c>EF2n)eAJs z`VJAr4Wtw4{o}g=cA;K)CjaZdK6&lG8m<>y1}pI1^rg7AemEd=5au^b5Cj%qA(*Q$ zK@b=PVPsw;wJFM4}unph|C|b2#OF4RTJ>&?xF}I3f6TBq96#6xMSqlQulCDOk zQveZV!v_tjNDjOy8wZZb#(^se4&2Ykfvp7xUMD%QCtQYQnT?Q&E((MAV8;6OoJ|EI z0FVg=^D8D80*mt#m}fDM5f}v{C@+%nQH>Td2cP{ATM)miFWb?q6wHM0r5Y=mu>|x8 z7tI=OP+Pue-y^7Cbm;m(ackQkQ=6N%BtF)w)v>Lx9oEcxZZ4IFq!DCoDsDNS`dv!RL~}xkvsM3|5&mXoKCz7nQFq#0TiuTZmt}?xoA1UV*746 z6AbyB;3|+tje6>}QKRmoVAPfn1;YuD+dKc^eydC>7|y`*CPQP%P6fjam_08*Fy?f5 zpuiIg2!eq>`2}fo#V;biWRI@+MdaJpbj2^?w#GGBF9Tw31>=22OnwUn7Q@&ZT$_zJ zY)AmXI8E;m->pEG_~KvVy~6`~Arbk{cp?WI~Inz01*2%pZ(FjHU^Uo^k@R4^89dZ6f4X78lNu&-X)pc>8G zS8(LJ*U5}_ut)Td<9n=6ja8H7cMgvH*~5xlExIGP$Sv4+pjwO0XSb`#u|`D;yWTb< z$7~J;TpAXnzn0+nrbSyjGH&x4*RRVg$gcwK-CDvP)X>7%2$wOw-vRMXn|GN8VlTsX zFk?=KKcRxLA5gSvxf^oy=AOyX;NEj{4h2K@$}t$yxZ~n7;lum8_{uQ?kiBApevFl@ zs2`I6&qw^&x42{m)sHY>d9UO&$&RlaCpSJ&;ECk}y}+N3CzOJXq>kbEB4Xqj9F3=X zfe3RIU;}}RxZ)S_(Hv1P5Ob>+D>tsqZ@s``7(0VymDf9_7gAss1)BL)1aol#FyfkX zHt{3-r(q{0qO6k=QP$oVte4z5RdDAYM((^U8+SgMjXRJ1*PSQBWmpN=mh_^-!VUpo z#_BG$kjh6iAaf_?WlTN<7JDq1V=?&<80BM4UL@nAiW4#?wKw8)FHVQN_N@t`{|jufzL~x@$&)#)teE>=C5b`ffeZtF;|@ z6minUZkGkw)+xQlpQbP+%UQJ?E@OPZk941IRoI@&$1X5qPJ@3@`8WtDTD9B}IeK#! zB2XU?#Z87UQ^Z?|2Q)9FKZYJn4Y#|@y5<2pT=i1j6U}_-;D5tAGqZ*}+>kGt{Zbm4o3#%W zz7I0bXz#*muD=<-rn_ACP&lAJOr09j?5-~ z>NfwlWafz(YXMs^v1|=*@kUqrrU$d6=WF1AE!Jq?l31ey(X!3{#>Pm?*Pz_BUD)7Yez>^z)t}loEgS4{{k$;fW znaGG`tJP#JeZ<^Grr+ej`5l>94CC5vm(?Tb%1|1aXqI&iAoAla(C~Nl)A#=0dE`Fk zks9s}Tn4M?NfZt7mw>FwnJ2Ii7g!8&R{1Q%1;!A6lNZVOsD22UliKc^b&jn+bJbEh zV2J+~%~%3@gg0Pj4VN&TFWSoGG{kia9x5ulc>7!p-oGOyQStK7uCL6GQdDz^|r{5_y(h0oc` z5k6H6S z;xQ6qh+9Bz@x=1LvlxHMHrhkv_v)aXfrzrD`G_?~ixH2Q+lXJ;X?T7|JQl;a^6!n@ zdF<{w8u4hB4G$o4boT-}p#V|VR!0<94Y~T=iu>1nE9JHO!bjcVGFYGOR#H9q1IYY? zxee0;fki!Fp2GA%VAKQC9eI$9kE$pngPD``V5@F@Q2VFX3G7zgOI1QN^M8bYx0abT zTxOE+ucN6R+`RixG5t(p=DSC>N4Y|2}6`23*G2B_5X<=4Q5w*8?zPZtq1=Jt%VTp+dB3xngqk<|@h2;2sJ1-|K;W zJ&kNn{f&@@i+PU*?UpB_9&83=`VV@rL$abC>;t^B?CXXdn)_4_4oi%B-~eU86Uzg7 zfInq>WFvN=t#PUch@Nyx(P?~lNAx-)>H%VI_27He(fO?hSPbLJ@6dj*Q_pKu56~=| zfQZOV4lPDL15GehrCF}N7Y2goTLw%b#o5itfV{zpSS3xBBB{fK#%ZQ z%&g(6**u~}>mNh)A+6>kMU~~n8*Iz8CF7fZOU~%Qk+|w*3zswXCx@5JjGX1KCZ?ma z9BP0*OfPE~Ri$@`-lp{8^J`%vkxHo#)&%`9BU~FFx1VbR_4|t}?7}?k$kxJlzHR?y zLHfjh-1vAl)d!PWkN&yeC1*z_Ot?w)K>=pW>5!t4*j^|CC|W@uo5jQr+Eko#hBShI|Ud38U4mu$l2Q83|gI3PQLAU+upjF{AEX%BaL3Babx*yC~ zzZKR|L1+fZ1cCVt69j=pL13Q41VLaFgywmXjE|~|kU6Q3V6(32lm{v2+q6MJ=q{SE z1oQ~kGP8!OGn6mdjrCLzDu+H&{1~y|Wb3m^}W*Y)fXxV4Z(~#^`1)w!5vVvYB{YOy}9;sG`ODx z%!wel${GweAdQk&AI^>JbQ=XBO+plehk$4PtmxOYO*$2XrxK$e3?27KfhQIK1Ob2Y zYwHeT?>-{`{G*Ez5oL3Z5$F4gf`FJ?L8x&oG`|G_i(y>bnLbM*v{lTocOT8NHwHx6 z4k3uLImfM+Ne((R8wb6Tje|DI#z9y7>!3bx8J1<%LJ(b0!v%sF>vzURDhOi%nIJH~ zVS*sAC>v@f)JV)$@r*d3z?GyVXf}{EYCVyzO+I?m?N681oQ|O&G6X_9bYup z%~TKuUwEYOo$%b@`V06X-lB0Ik2U8=olDX0nzryKNw4|_hWWr={gbW?E(wBQIzDv4 zPwNo<)1@c7zJ*=?3{e%gHRqIM_V(1SH+u%^dlYh+9pi3C?5B>fU0czT1bp~1%&`RQ zx!|mt1eY3pMhlATT;=m5-SkAPsroqwdj z6AK7}fj?y%h9mOBS+oU#$hR+O3xZmAih_ZdTfqq3Iwija1B+qo4PVBl^t;`b3I>{G zuM~)~E(S!give~B&&<68&-zaetl?(BWv~L@Y@vz}4agLMISx|a>Obv!J9S-4RD|848B0Kq@Vd;b;X=$G)1s~4MipUtsmF?h@Xk#= zUfYr?eFjFV-9Zt)U$gZH@h8!(hFopZT}?`TpSaKk2KY={d-nSMHCP|*;#TC?bv1c* z?)ToMMU`aM_|0~=HG%p;f4i+b3}5$2>05MfY#mGD-^urO{mxVoqTw>eKCrBN^UMt{ zR1r3S8FN}boGL;bplH={JLTxj>Evi|*OY#oqb7ojY#5;fq%manne#Im-9$y`E+Hy{ zFW@G!(eQm)3RMI@VEKfiAjwV@Aq1E`5I_-POFmZMi3J2jz@PAi`lmP4bV3oL>=Ocr z@JTutcA$!Yc)=hl0%C3z;r*0m`K<_83}bJ&+&xVdJ^~csG`&OOjDSRnvUQ9h4!QT( z+5gF7HQZ#l4Axke?NkDm0x}6;p28$RU~!5N^A+X;0;2>h&x>T>v-3jcBngPt-QByV zU~o_ilz{D`8B0Kq@N{O@aPxccMdNl*378V_SYbAx@8OkMw#3ldD!yJrj+Cj^*=58G zf0EiQy;A)yY7$RMK5x*|iddIF-8?ZhSbw+vp>8cQ+ z%h8*=EJxT9JTQk6Als5)JfxxOV)uKJcM^6hP6uS&$e;)jk`)yp67W>L+iffcCDWIN zWfJ2{!vp`v3Ounq5b^j^wh94}e}|xL07Sl1fp#k*{%Td5^&%kVHsWo%w#@H{$6^>) z{$cyp8{L-CHUOGsFAa$NSS$VB7b4zDJYdKlQTCD_^wXyQy5n#y?h6Pr2`q{?3-%I5cb6xw;&g ztX!j4Z}2Cto4RLCp%{X0oU9kRjao33T$!cObGi>U?ib~ROV9Jb- ze**M-CNJJ@Myim5Y_N+UB=h zU@?pz0(AalYO7M^XLV4MrUhC=U4+E}nwaQ>yX%AX%a@ER zcqvUyO1v7|V15-PIhkl!vM)10?|WiNd@E-=VqRis|IjX$E1zz+NWY6*9yuv)(_^BQ=~kn6ZB6@2C1u4UqW@b0ek?0*m^< zJcsFnz^D&3^CB4-9~3et*M|_(NsW${ZHD^bA)2uS^au}TW)1hQDPJ^lkm|#;b{PsA z#kksKKiiT9hHV)`Z8(xy!p+P+*`M@LDkEOERTGzJ|NcX}!iFXFQpOgU9jtGuaGiPb z9;^{47yikiwvt@;bWxn2WIc z-G1c0i;K2VeW=i$&(yIq^YF=C6;QNlxoUFs=A7kdaNiD?BYluf=G8$OUwdq|jh>o_ z`fv)6Jr6)1E=pG1u;db;;0*-i;u_%Z$o{Ge*0*R+zztye(tz8N9p%FX?gXA#F(4oK zlizdqFv%3kiXHN579WT1jy=@RX3|ifyG{YR;4VC1;#j5 z=S4C;s)j=5q;dW=y1I^|i;k(>6yw-MH1k0W{~KP1nKhhhF<-RUBQ%b=)ftMKcB`$d zzuJ;N4vzK5l;g;ipNCGYd+Sf`x0y9?Olvh+^6m5cLa=H$pn308YljBw=UX>uJNqGg zqvt?O+GYnOc`-&ed(7Sdy+@OZvCkUVk%klcu67z^N!InKXPFg1xsua)Kd|8?*{3Fs-Bu>|x87tI>Z@gZL{t4mNcS3kwe3`K>>aR+~Yvn4j+ z>V+AlI5NjmQ8Y;rKn%}a=h(DVlabX|++Nt(ifsO6HFQY#VEsYO&&|~`)WmGS7u_=# zC8=3=sIzBufPU%bIial`>`0Gd0}C!4V@b-tO4!|TF_nO7a2exD|F~)54Tlse0ky%5 zIo<{dm7~Eu9xx{o&`{RYKLcq5j&to(ZB7D8z!eFxZJz`z_nE0{FVSLhOsvU7gtnJ^-EHl>*T1wW-S&ZOj#_2!&lT6_5Q=e6RnoC3QxI*4SSZ_7-|ou;01z0i^jh z^V4rU)x*cai+HUN-(3kd41S%En(y|Ld>5a2Zwt zHWyIzNDUVRW~}a-iBuoP0Wy7HZp8FKU{N2KBQbpt81-R%UL@nAnki&Xdih_e>oTqR ziOuhupgznN%~%3@gm-3U4L5uuU$pzzs6I@YnW;EF^lzsHKW$0UdwuD<<{Y`ye_~pU zeE|8=sawzFrfSk^P~DabI$Dw7)D@f7*9q49zI|i<{+XIMDW^tUX{IDEx$lF<4GYk( zOlnp_QxA3ynVNNUa)c#W-QaMum(Qp^EQZS%-|q&OK1Ba94aTWIE5M97ef^5+!#Y6G zs^vDz(VIIcM}vEnSvk}P2Wh*(u8_v@R^jWG-@l0Z;42~OLlEGSx0jk!dwh-R!$65q z9};I|D)7VtfIi?)+5V%5Uvby{FSMT?kzY$d^#SqAAWbE^--lk4TTK43A7Yg?6g zu*C1aR3FfM_Xl0di<5&9W&QMs;&LGkH+Ca`XBXd~p|}W;g(9ml7K#Fkp~&itg`&V1 zicxuyjE`!gkU6RGzC>4d^b@<1o!l`LH;ZQU4SIyvW@h*Xz-7K@&2Q3Bbh`y@pF7&( zjegsb{sH5kb}-{eHI=LXG|vEH*1zSfG@>RBy(gb6)WM1b8KQRm-)Lqc_)Cjt2J_z??j)<+rQt>hA#vfa9E$l&?G6gu&r{;!r+U^0QTOs1~vk8pXeR`1)*3ODt zFEjG~A4Raf$gb~E4PL9stDxI~FFPnn*H$;T+-Vh{|FomUx8AkwNWHWNnO>`)DZjtK zjXF+LADY2sjPLiwh%)}`Yfyb?4ra{hyhl_YS^Rj|KJ)rWdYR(G|RpN zj41Alc$wZ3yp?!>T%eVoptlO;Vs#VAeQ#vrz9qA9-`Cl=Z~cGWcRgH&l|XFSOYXZ7 z%$Ps_6e<_n0h#+SuVQi`uqYSIk(gWvjB=4D$-pOtgv`mC6U%1A_Uz-+2<1XDV+rUH zE}AvmgJ8aBrPHWf^d9y^p|T!SwTlTX`)|{zUClpALb%@wL;nD>sLjC*F79g5`jpeN zpKYwj8&~Ubo}YvCdm{#avCV?*1E$?D*mhBpkpsqR%ew^VYo0hXLQ%_(Z2p!I^?AJ| znK$Ctnho8lT=>CdjPLi3exok>G@^3h4`$5iRBgzLN|13>F`9Kt>?@Xsyzndr@Xw9vBm^5?AZ~4Gt7&}9$3905oH&XdP zvuqp>k?#r6WAg%$?+RRldU0j`zy9lyNB%pX`LBk%50}9Tyqr!2Arp`}2=f~z2m*`a z{LEFDAP9_t@FXvi@lm}HGA9YbBHgN43*##&G$;r!MKhLw9^osP8NMvAUx>YXR1jvL z0KB;A9=j${ke_RWPH8p%O|$BA}g2H?j4dDq}Lz) z>-qI92*oY4!L@rTNu_i1s<>AR&{vNxs5w@{jyNr=kX0wvk~r!jZ}u5a1z|p1#@Gk` zSo&tTwxxow0CNGy%;eeleh~>MTD9CFIeK$TAa=%O z!ku8A&~%D@H;WR0*4#<}acq*`5`e`pu6~meHzqbdL?r;t{M-EseD_BbH&aQZ$nOfe z4kh48dhR{8Vm2P@z&uvNy}`@C;qZV;z&Ai90nAgF1PCmS4>Dh2J|Hkk!1ugJ#z*x_ z$ebhrOLQYohgzD%yPyO}W-I|c!iO`nhWlpvlosvjLn;C1ES@SXURC&9qabYkkv6Zo z@|%(b`u23aHzxr0-!nvg)~HF?L9a3b31|<@o&X>L0gzujv4GGhz@Pl&o^9ADK*UWzCzOJ|@Gy$vGQjB+ zCw~+b0slC+iZDDY-xUFiVeAbD`ix62ahWOtn)!E%P*em&ekbK?I9h-x8!bTOw_VoF%J=#wh{6o86Q=akU2>p z=IX9Jub8xNgfj}nd(n&~phtKjGsBk$y!fKE&!ht3;PX^bZQ=P66AG!x*B?Qi*FGu9 z=;N!ODpv)N{XTtXj&_APe>;-r&4Z7Z9i2IDh4Z-}eYLD1?p`0^qldrGZ;B02678Xs zzE;Wr{r;oM_%_w-NZmayuY(U-k`F20dYw2-1;Q6DW9$<5%az#He;^fzKrmxY&u2}= zHo_o4(W>Q!$kCgdCP#z&H^7{<5gcU`2$a2^Do(Xtf6cV(X?$t01Y|FXpclm?E9!+c z;L6ao{so3ypn9PKmd_`sAldPyVN%bh3OuoVpbz*{w$~UUKUtX0A3)?A%yiiw;%ZW# z^*JEsRv*@H)8==J0gGYm3`yR{xoYX}*SGPK@$HOsg8lrqeh-NGSJ;I}zS;KW+ z%NOn7Gb$eqW1lMaPabpPm_kiPPmefz<-L*|_Z)5>v@L*ax;^wjVHfC%j6dJ7a&s#( z;@8HJ=?8=K>al&H-Yz2QMGe5_hh|+G*6KX%ldLN->ciq~(AC1&#W1ezhO1v*d-0m;1Da)>3W(xXLzn6OleHhv zDq95Pf1bb5176U`91qAMlT{##Oo7G7WL3x_Q(%nDNqLcsk7|yPITMrq!aSe|UC)HT z)V)ql7@6}#Gr9^r!h0|?Z213%FIvS{G%^Q&eX6h@W9|ON3Z z3?SFk{af#As3sSBZm>Vz%!*iS?ODPtHb~#>XtCn0zogBc8mXcgErboG8srPG$A!wScceeY;wPJzo9*VTMO{W^iOXk^X=Gv>5&293-GfTC5) zZIGikcU+DJ_gdd_7@4w3{;rV5u?kidHaMKZ2fG^}Ysf*M63L2z+5*sH_~l*A>z$*4 z+D2jw)DvHxD)7YeK%nAJ*;k4YWuF~Ib&+>4L2PwgB6(cnhHP^Aae-j zCrkhY76pL01`_~*Q2>_bMKUnEK*$_yvMUO}gvD#dUa#SZ0{ON(Epsm@%j8dr!wl^GZO`s^y~P=*`8-5k3*r{8`Q(&9Xgy zY#|M;Z=I5>=bu0Us0zpg9|WMLWJLj}hv>F&>XV9RY0KUoSg38<8R#h4X-_~yVAc@? z0+HG5nF3ENF9-zwjETmIa~o&ZFC;_zwg8$>Kn+n%-b5pydLs-SZDEf81? zW9L{EF=;XSF2iBO}-tzSL5yrC7C$;#7F0A0VMsq%>-9RHE9sH zJJ`y@itIbub*?fpNdItp37dD{)MQoZIlA7Xl*HxL!Ojno{Ppi=B#$bfwj;Ncy?!jb zVoClUu6W$4I2DKsa2aDCc>2uoz>0NLAQHihIsK4K1>z2%XobE(Il?D_NUOlSvLrqNn==YX^$zAQD zOBV9H;IFS;x%*u!TRY-^w&+st80*%a%a2eyey5XE$pur9rncu;Txt;Nr zMyAQ*XA04(Kfx#5c3 zEr7e;_Pl?l;c5El-U=-5l#7$>^wGT&m^I`ekS(FCcw%`WknyK%g)XAFurG{S`RCL* zd~~C=)SAY(C%on!K+A>X{J(?CYE?9q)Fi%Xb2XeS+_>?ItLUox>1 zJL!^t|L@%UHFIwb_ZBXL^;!5U)r$guq(EnG#T-arv8m5IiFt^?s27FuA{if5Nk|4W zCq2oh>9!OvfBSMbd(;bS(air5{BQVXX4Y`esywIv`ouS?7r*O0S4^{cFs!qfzVso-{q^e`cge7`u_MLPZ_l`W+mg)R`f}fn>Qpc6>OcR-B}Ux&yQASDsuwlD zjJa)ebrLr9?EyurmUEONtOAsy!Tk_mj`Tv-iGLo_*k!m>dzkZ4)Qf8pqF!7FWRC~X zi`#%n9UU`vbktM5NCuV<`lU;De9$+AJB%lm5A*?l@-y9F>ToDU*(ZX~I*e}TNmuYA z`jvKIO?$-L>O=Uh%K81E$6^@k!<#yHZ?|xw`haHHgC0@b%`=hSFr0_IvqBs$*+0{k zzq2EL&`5m<$e!%1LRr-bEDpD^I%JV5Fh=T=yhsK<^(hCcgj!_-;zU8+r0}Q3%`|X@T zocf+Qpo=?9>8-nU^M@fp`rE4-`}_Wc)p`9#4=)v_Bwc*XhFpsG*H4Vv^SoJQJF;6@ zs%)7wOOn|valKsw8mXV)GRBp2X=LWAU3wa+Kf#PSjcG9%BelTf=L*rPZN^c~jQLwJ#;q*s`@uhq*AnSyIz+E9(u?fB!@O47DqJB?L(nyT~mOt6o zOLmOZE>Jc+v3wAz_> zix>V~_@uh6@H)fS^6A>YRberVong^kx4}__Mk<>5XLUFZ$0PFHnzwK`9+A%h+|ERb z;_L=jzuM9NJ9o}t?yTWF;WC(sGZ(^eJ^w&J<}b{Rm_7(BKFOKqFntgh^b>AzoCppx2Z~^ z3g4x8ywzX7>b~pJp_S~&gb(BG%H6jlmDSZa3pc6{_2DwcE>W zP4%HMplH={?sD|z+R72Wvk90ZeUQ!Jy$)$u`WLDc5O)am;T9l!9)LciN>+TZrvb8d z9LU9ez}RhpM`OKDP`P*rEL1-2!^@QH^hMw)FncWo`3OyTuD}zE5AuOO%j38IrqX@> z5%HrIp)Vhxd>}sTh-1@qZ6D&wy`p>|=2kxJXJ_TNd|)w*eZ{5D(YMXpQTaf#Y%~t> zBEARs-N8OQL|G@l!wbp12MO-I%E-M(3huqs$h}8qyq$Sva*~yryu4K0e)R)r=zp)jX+?oR;$N+f zNBMec614O~eXGV+urpw0+E$++y;(*^$DY5{B(`OlVIyY1i^TY58z;y3>qDnCE4itn z9kDC%ZD{5rOJZMh(V(HtshoJgWsL8)b&st<-|-{j8m>8*F{eWtL#AMbA)sj0a_!~l z&H2dD;C>1)M{*(?1Wbf9F2sbM`51N(+X46a2}4I*hhP5b4GOW2u}V^4|catr0}s z|0C`^prUr7e-G%o5kax94H2wZu*<5rv3GysVp~PQ#g3q0K`boT6??~qC>HDp))m%< zf?)5xH$cRK$cnyuCz&K~J)Hmh3-6F~g881iPRZQQok=p8{1L(l%KV0tg__L54kx6N z{6~K&n~k1KG#@aKgcCGNt{YHt%b>&b$rN(_B##8tE&t!$JLG@q-c6``E19v74L0Da z6cR6Hf~5XK-HLh)uZ7DK>N?aVc#ZL5c0nWqlLq+0iSc5le(2Un&9l*t7%!FxW~>3( zbc3l`$&7L5s@CNii5Kpp-^;d@>-}nLNqctcp0gu9K9;jC>nD{7E}>;zW-s6D($Jpu z4eFkmt+Zx8@7+G`jH{R7#d4PE@Y|lPcQL|t>;gGE^`UvQHETQ#vww!1eO?vf#b(C? z(_UM#XD{7&IIs_i7vmut(|EBf>)ovvk4d~(3}!6p(^wKOR)Q3)DrU7*s+n-9%yD7H z{A0Y3JToj0X;@~sHBt?a!FT~NSLh!gUf7COygac7xoJZm{f{B1NPwsbT6%d>N3`SR z$;nagWw>MgARyqOVu12q@22!d0?Pab1g6pV!VU;n4O3@m(BRCL zo1PF5&XP04jlf_)kw~QE&LaNjN@P;O0lc#~damfd)AI1&iFx?1Bk#XcO#HXz-~KxV zvY|z$)Bgkyg--^68QVAKI*AucLDKOBbt@V#cr9G6P*0-qg4Y-?mKQ`a8bugiIPr2t zr@wZ$cG)S#>S4UtESRwdWYb-xW+fA{kE`0jnjO$U17vDkB{sH2}Ptl6;;y1|6 zJL>If@#h4I7k@xYuTP2`6YOL_Q4};CZ9@FG9`jy?JJuKC2ObI^)(aq#n;r-Y=FgT` z$$$cX{ArUAKTzg3e)N4`=HjVA*NG)o>-pj??gQ`KVFO&n05lzdZU z#m&F{xqAWma|-om_(%X`gAF+1HVF`?KvIXHenbNVuZ0T`>N?aVc#Q!`enkq@%a!Poq&*uX5r+>jS{ z9?02B{v9&ERnfBB+KzUOtZ&b{mu?oB(aM@FclG*`?(N~7iv?>nl9NV$2i>F$#TXsa8yfTagh$zU$)CcC=JQ3YLodk#@V8)VK zz9a!c4^ptIm>W{5WI$@x36D(I_lx zaD@{CM2LRU=vmcNEk>dJ6)_3gM=qnH)JeIpI z^SLi)+e8=n9_pZFb1(hs_`%Vhomi%OrJR=5?3ZPw79LT08Fns=>3_t`fwkAS@D5%s zX9MDW`!1a6X>fg4<=xfF4s0`3!yi_ktl0RM+B4cwBtSfaY)pM%XX(IW>EB3zcnxMO zsrn}g5NY^pYE?0xq*Be~N@b3Vf4_eV5KSag9p*q9A78MumkmFH0b(IYI%0$X5h_~o z4#hH%^!^mYi&Y@^geouX2|PyP#TwAk0mTNpUL^SZ?cS~bm+n37e{ye#7my7Wpy?wLFTP-|#^@5omb5fbx1t`y zYhge^U5B~^uQ6VHD~Mz?3Nv4>a9BWY3)E}BgpMCSuolJ(*^qy z^)gIYu6{kv+<~pOwrKV5D`8f1vB1^+rg$3MZ)62Df_PE2UUcPmpJ7dd&4U9sP9X83 zc=+EwQ0a=Vzr!yQFG_+Lt74u#9j`blfE27MMj@4IrnXe(xNHLXFIOB*B;P6A2WiAx z1uqyi^)SYZLm+AY0P*6eXvKID3$hpI4LDQkBuHz8tud!pEQuGVK}*LMaiX2X3j=7{ znLxZ~1Py>YRv+R89!lPVK*`O1@d!j2bM4bynhrER|^ zJLZ#kfoAUW1TZx!g`6|380jPW@TQ{Dy3>#loJF08#dg=rGiesEhDg7*J4O zp+3NC3=kCxA{mXs0g}POi35rN{T_!64J?#3F+kK2%-oOQuWmOrD;c}j-2d+LoCJv6 z^bfMCXFIr;DFch1Jp0||=^Z(nG)XsZZ4)g!E^_mPW%caYap`SqH)vtadR<#pW^a8j zL$$M)(<)iO?B(#`x4W-_^-ceLc^Ks5X&4u2pS!k_1AFM;mbmp_;k~Db=S{sQlK^4$ z>F-8wb|b5Pmc=N1+Tqkbo z^Fnn914IHy+95!INEWRaAg+R>!$}AbH$h%=i+eJwRScQ)d{5MP2eU7nVBE2K5CHIy zyJ1hhQihVdKSu%pO77~Lyat8R=e7_4Q06xPEG&Dgumb>A!!!WYX!_>u;br6kLp%o| zIKcv?Fy}diNXc@@mn=X2KfAB?U)@*9Jcn$s0WDsVc<>D*^$+Sc)FXH;!~^OYG#>C8 z{TgE_`#E8yb<5Dyr^j5Q#e?f^9_8Hc9a|33DL#Dj)y zKgwS1e=~6}!~@&D?NXy}!>7wv`YB5~YuQGXYh3(P*PboXSg}Ce+?tI%6yC9MEic2s z>(zYYAs(b8=PEpgU=U*cyM(8y*u_INM>AFxO|i)o^NcH6n+5b zMp}vzZ#me29FeiU^;gHEg!pozM&bk8e3api6#(M#Q1Z+IWsSpraLqu7N4cN^F4;lm zM4;Sc-<)0|pv*7vcJJ>NHt|>u)7IV)@yERHIzl{}C9A5U6h2?1WLgg9PUW~aggrNq zls(!+ls#Sx?9oP|?C~1e8&nXmp%~lS(z?EtNSgPeA??dy>@w(jko} z!%p3ID!U)q`z}gkF9+oODkDputQSp&3qRcOw&-D)rn@y~SsW*J|YISh&7Q!Z)B@+x# za@Xr*f&oh5O$8+rxSKn(H{TOfH-V(6(iWwt@>;mArfo{wir0v0ctIqiQ5@zAXJ*Fo z-DIG?b*0rEN4Kkis2&x}=o@6yIa4!y4)rQmwfP?jsyps~lpSq0b;Maf)o0||Zp&}V z*|E7vhl_U7vLW`D>Rqk_9}H6UXmX~hHG95ew`64{FT>MTPm6yBRI7!^{zQbqlfTJ( z*4Pa7G#seybR(;x1AA=9sdv|Ntk_Qt>ra0)pP+gavN3I(+e6#?jVw=4Jq>0osYMV$ z^&&{Ys$wolrJA`bl{qfz2mgqwWa8m?NMq{yWg~0vjKX2F4@ml82FRTvT9Mp9kf&A| zN_TF1gpfN6v~+4vuxKab&H+sWH;|if@1qQNtS^v@hmv;(QI>3o-_3c6H{MW6W&)sm z6DN?1GQZ^3o%X1($;E1zI!F4*MlVM1B;=x5a-$w4PRv}}@exi8Kq;9RfKqZFZpL@f zy(jSQJl&li9UXWuXlw6zN#bo~`c}dv?tYIoocF%d92cwQR=)jk>cCPAqgKUi@xi&1USl z^C!Bjm!U<=>J4WWbzmP({`_L;W>|*oc8kl426!6MRy_Bc4&mf*NEh?$Usmk-lr5b{ zgpzQw6S6Tq-@AVuZI@P=gp<8s#*(J~B;n);NWrRNj!LDPxgeEBrdypRVfz0=}=pX$RT6bu0^y{G0O+HpXAt5&KEcPtyAkB5>=Xp~zs z@PnY_86C=IWFrG=lwYk{&;d2d{Gvax&$GftAFE;7kUfTfoB1vZ&_7GgkgX#I1 zKF%IXI*QKbn1{2O=izJ*@^H38e>>Y&$cC0Np`llaVt$sa;7&?rADFR0BQglwr$ADN zp?*Z+=Cv@ar>;Zc<~72tFNkC`ic5Uqq{I5~6SXHlGOLboUlz<*1G4G1QnQjdFpjI* zfJ_4S^2w>P4fZo$odLMJUwT$@?{ztwP;}a%gg#oOXH5g_7Rs?4%l_S~lB z?b+Z6n@>sCV42`+8V9{v%N}p(RHF+-fX}@{4sL2}%|4rSVsJ=tFGIV_HXCL^1gN;D z=C~^1a&}~d!hUcsPeba9uFY3gaA4=F*Eyz{S+lqPoJw7_jzoY%kd3Ji9B*{vb=6uV z0>pwDOZu|k6pR2@KnhkBlOmOB=7Ch^xO6)Ij}bsJPq-hX5%lIzdavWVFait`CEisZ z0+K#-g@7;|WQoD2J%@W8AOXP>v~-BzCE76{RD$B-j`f3pfQOvB!!nlvL{3?)fQheU zEg`gW?;n%3giyBJD+C0T`3(qlD?}A`K)`C4I>V8WyQfl*ks$(_YvI+v5?DMak(?ns zceue*H?(q#FOhk|cc1<3zrFvL{_FKW`7b=XhHS6^epw_S zAn+Okg4y!|NJgWuf@H98;*h{kpX2jn>&kakFd&o`%-oOQukI%`E19zLH1fY|XOn>N z-X={ZUw6QNI|KyXzR(Ikugck-7q6G}8>D4#&U&!>W-WWRM|xn`cPDFh;fxMG$wj>k z6W3O9{00Hx(xbj9XSd5)>-`ZecXahMw4T*@SS<($E32to<1DP%dRdL{b=yP&f@SHn zzkHx%t*+N^)*}I-G?=lpD^o~7s0325s+cNLsb(Cd(#Y%w>0p2Ep3A&Qg!zal5oSF| z8oL2z1IV9&33J@aw%(BI6c^SYhnwDALV704*JNKNjsss@t$M8SYp= zAQcZKSK=rokG4cBS@#F!j2M*X(W zxxQ1*?p+>uFteSfp`2#GDt8D7lP>5ERV-%BE-N#5c+L(I5bPlvQy=he?>lI2QxXuI zz>FnbIh+K9mLLVIifJvCYNnf1=D1u1`A-2sGM)Yjr13J;W%5e*9oSXB5hX@|RFJ-- zhBsbbaxdwdzla)%pSeFxhC5aOh{r?8`XDH|PlS>yZIs;mx}o$qO_ng_V2~$@!Dqc1Npl;jLu)CUGZPZw~GY3wMB|WYPwt zWb#@dlQtnGlh;V5PeCN3Q3UdZ6Um&UPY928OiQeYWX=@K=qhB>U7%(qfAJemZUQo6&Q?3^1Z2Kf&puu;TWe^r zuWxu$xdYp8$?tk?cF9?vxle;Wwe~b*?AlYr9LU@{c#3U=+?q|S_I+vYZbIe+$i}p- z4)!XsU_nblrXQHGq*nW(Q0d-MB%iA~2sct^ z6Up5-IfJ*F@yCfyt>};!Wq#4zv++z}qlwipZT-`!t~MX95j4@vu{aawZ=&RSJov_6 z3X$A^co$xrt{BCg*-(a{c>p9uleQp5lh;CzN86C1$!kP2x*(F#DB}3SiD-K3_j&JC z^c-3q(KHBV^bNAhijD8SYpZzzPq! zS^wmQElSDa?$I_?EE>U zV>+g54dyf6`Lm1zTc^+O=4GPftX0gUnUx!R8hXl(*DVHcZyXUGoKV7=t^dh$<&9_p zcPeCKdcI3n3s^j)J%KwD%vjPFnFQ{iAO)+6$&pGmWBFEM&2gCl@}K%$$!k`NA&rQ0 z-$pvQZo>evQj{1V)`6UFvEYA6pj~HQxvjsJEmA$JNGFI74eYCJ zYy|NkDeChGi;r4E$k(85DwjD)@Y&(JM_U!iJ!Hzo!+bu+mY?p_$aL3GnZ9Ej5F@Q*634z%}a&wCH zIEKa_H?8bU$IvMA%l5>;wS~<#R>QQVIvtAkv3N|_MzdtP21;&<+YRjOQ9k-P8`h~H z4|tyT<<9JdG6bU^ASp()#VAI+7BHf1Mls?wVq`3cWHbuKl`EVSqszNjzp!jt1~IY} z%;+0r(_NxwC6hUg``-cO2u8PpKgj|!%+G28qeYSXXS_(1v&vy-eEUq*vN=9i8~wDm zXW3zAyPm0U&3=2?-}>`gz^Kn`-zR`kna7V7sQ1g+z_Q2gB-HaXm|yMj#1Ak^T=QA& zRMMJ_TUO1v)=7fV3&_T_adw<(*5puEg3%i=V@W%;_D77;KnhkBlP;BN=BHE|ne32H zvO|*=Z(CPqGh&o0O2nw>oKLd$%?6~Uwu~Sc$wiGAv5*$-m^omChmw1-C_mv!J*Qsa zr6@|tTFodu#|Rjq%r8dHt{V#*BdmsLOL;4{wU2y8FhaBBi)tvj+iGMAG)l?6Sd`q# zX_0tknzNNV(G4mPs>*K@siF-?sp7Rj6>UOF6|a%1$_0^(Mo|ZnK`)R}HDG=j+l(Hi zkt#>Q%>4-d>iSc&k|~qG{qN@$2~`%?Kgotv@0PI#sJhkKCeaJ13V*1ucb=|g^&y`- zL<3bD4-_Bb3RH!T%Fz^itu>q++h9qp;xIq4!`V{94#?Tk>opEfYI_>0q}+bm2s@|P zQ`>u#g3l+EnEtV(o={Z=vN3Hd%htEm1?GeROYyx z2l-EfSIH~D*CCCF*2}_nM28`ncSVV0GB-ZST9z_9wX^efLS{)(BbnaUKFM&$3cw9p zJnTXiJ|-xllw7`|Ty{)A5oLZ+oY;6vVWWuEFl}C$<^GLjUlA11EV*Hek_%Q3aQYES zJa@Q32Zxfog#;f!Q8KmDIqRBA1Vt7k?civOQ51PCph(+{qR4ARv3o%zqfrdt3nxW! zT9L`APe$4xih~3*S3CHtn@Y_}rdhcRQt@t82#V&m8M0vmeNTS`6m8Gh9r$!v&VD~x z_35t}TDC%m=5Kre#pZ8b5B=z9%{nj0+S>kw)^ObXc+OZrapFGZ)gcGvY~1kyqZKvb zBZO%)YJMu?z|OszJ8PhgH9P&|%w4zQ2#Td38`HKLR%!J%_ud3WdoW{ZC#4V++hL)o zRmF6WN;UJJR2rG9ASX1R5;>szM#SirC=sIvAP?T2a{ld*aDvejQ6ol^t7XV=$IPLF z!$aYwMgWnL#~^5ZXWW~4vp1R6i*jXAB^@WC%r8~p9}Ar-atiq6f9Vy}jWSM4-QE(a z&@34zqU07xCU577R&rD5No&!$>rqYqKv3V78d37}o2MoHbuoV(Ii6o`w$X-d;KkFe`Rf-`2mhHQTD(Wu4zy z0&`Qy#`Jtw>G*W|um1?lEy0YXJ@uNv+!mx@RWa?PQqA;`${d$HApfafmApzH3u)-e z)vwy=&w309r$vbY!2oh#-J$bNT5Tf%;ex0!AZ#0-A;TRj0099HC3lHYaufT>@|`F* z<1L~wWcC5d)BS{ifHJ=U;r-67h270!HB4LknP1&j-XBOnK(plG3(5{2Z?4-vA{UM* zxycBJuwPX#;?As>9YN6>B<)vei%}GLEucu-jH1YEL~&w4B%@KxK_z^Q=Z z_7>*jx|FeIhifL8XPhS}_JnLq8>i!<1vvrz2#VvuOiKETpy&ruu&Nk;sZ=vMsWdWK zAS0X4I<+`{9b%LtO2p_7$luk5v@PztgGG+NmCwi}^pFPO2Qbs{FLIM?nxoU271&ZYX>xsE_Kw8(UTEx3=8ISFQL-{y4)%-29tn5o}T zn0YP0Og)Ff%xi@CMnNQ_Q9S1hhXv%e5&BydSNAxjvqYF*{$)1P-JoVAv$q#lwfA)i z%xedHmentNc*6~VIc;(S#tmRrw3gjFG!O2rzTDDeP7Ql@PHOKsOCdp1}RuoOte(0nRuzpaj84-^S_N&C5z9rfHb^6_P@_eUV{Ol zjVLi7upkfj={NGp)G!hdI*A$sg0cT+8SYpC2ncw{jYnZE{yuo|YVUGb2@=UgTU2xyjcvnX*TtXGlbTY4z*RN@BR zEJ|VKkh8}T|Nq%vHF@~!ojm-t!{7dT9TuL>d=jp7SmII*)Ip}%-}dHdhhi(`EFDwwebWYe9eW+n41jH_DT z1|&Y5*$LhpIInKe%JytohJBusAZK5%y7>6&0xjEL{xSBy8ZgJcW{!0uh!5Qk_73;G zqcuD+)U3D^;zQ-lX16v)%h{Bt2gY!S#C9Sc6#D|9<1*?jAB$coW<+fzl2Y*&S}aL3GnZ9L?bhKfeEQC1_X6p|NAQF0%^CRd^;TQ3pV zMwwr>?bykM%{ErUw54`hK0VR?8(|yGlFlBbWQHzE$(N~~oE4p`Odigan}>5%%EP&e z{_R|ukPR&|?d%2jfk!@I#`Z1Rh`?-fPK25I4TYK40?gEND9pS@n9CMKG8%b=&%LM%BXPSR%L%u%hPy9!kBPJk*ivd8@ zfUaSaPA<{1hl1Z9|7>T^UQ*3&xe=(k_cNfxyc=4Bt$IV9bfBu<^od!r7&$xC@xiSj zfG%tAwfwkd0|uo!w>Atg<_ystTB~q~jb3RrVkS ztBR>9m1@RWDviupkZbPO2%O-%5~;c*N~G#4NT1yy_nItUN2t0bYNSfbX3B8K%z-LA zlza;oCHJl)d5Hxjw|*OWITU3`oi=p%i!#4djk#IqRADttTWaWsq;k))2~}v8tgVRB zw+!AwAfIkSiKh}b82+M^JQGz6Q8iS-%(FUYc@mipYHX)^o*GN_Kf=EWA zQ1OKmsT!tFKBAuRahwdP>L8f8+QDC45;ZHC7W25Og*rghoIPqT&y?-!+cY*5sM;|9 z)vOXgRnq%)zZWdkvc|LtsTY8%;QQ8{-GD0XpqaCeUDF!WCmxTfR00N`H)H!A0IJ?E zeB5Pe8Ca3nO|i`ts47zPdBrTC>c2`q5{6wTRJDL?OxvniH*3TDVT7tSV8+sR83BcA z$8-cKSXE3XsZ=xlr837Q1>`?HMv*MF_zcp}HC&KhdeI6b^Q|b6%ruafYs)PhMy@4f zW{MigoU|-chC5aO$izeLtK`RV@QRXqszUBmq2#(hGPf4x$|(YwDDz7udnKr_`#Y?L zX=~qg+}hC0NXSI9q`yO{pNtF0kmsr>C4<*?`$Y%cn1_Rg-Sj$c7e~ zUWp1WsAL9#8QYhwMFN61NE#5R-_U@-Yat*|&!GW<*BB6d3L+VeVisRGGc!AWGVM@3 zJGeue%>RmFKnN1dSOc=@+EFu9?G{(HZ?#E4V4q~luHBxnE*1j9sO`Sa7cR=#_Oo}k zX}4ULtZ8Re<-0?a7$3-j}_eF__9tcGbzy;{@cVbNRyGn%=cGZf#PK`DG- zB#}tT;1#XH_ePYAUk-Po_tYg+g@UA1(FUYc@mipYHX)^o*GSdMf=EWA*uoc1>}EB3 zzwx=hpLHsNRBaQ?=qhB>31%hZU*ik$p`nh1s=@WY$d>(iH~ukD)%BC(AstZFI{WnS zrz^DVn_iu4CIeN&f6NKEUB{aJ+HGJpk7TW3%s%fD}LJ&*VGD+ zNTpKE1WBclc?+_t>*}lBPc22NQbmbWWq=G0Za&Pf&1yo`cTpo%cOAdTaL3GnDm)af zVFHNkGXkg9z@v)UL{5V1!yOaJYo7Syuch14!7IxAQgxz3zrv;pt6|zwHNsX7`}CVo zg=We99h6^g_J(srW*VU6hPFF#roqB)+?lm$Krp%nl43+#jAF!V0VCRG6eC_EMz;zg z8I9rvUpTRI8le9%Go@*l4i<>fE5VGuK{lOWhBsJ!xvE`gNH7YW{zZ1~Y(rP`D)y{* z@u+<)V05C((hXx*Y1!7>S{>{I7@gQVrp`vdXll;9*SC|jh6S5L&#eHAew;4f%kP++ zH9EfCzt7s!@MrqE>Q8MP*bYN)UrGXuT&AUauy+VXF_6t)jkBwWCP_;$It6Ad>B?IK zqw^qZP^*f$D3!3-r&Jml_rNc*5aZ*QkL!gZMp{uKM&m(tsCQ(Gm-8xu(IinLM#%wR zWVmDIfDs-_o{6I5E(yuJSd`r7cgYMslL8FE)i(Kh$ml(=np(wayLeMCTfxhjSgz!@08ZaIW@$JJ)W=h8CIL zCKcQVmbV2nwr_wFfjJH&g_-&dg_+j^%+zxz%)CaJ;|n4gjUt&ZoCvdH#u|`KXF<(M=HMBwY7LqYm;)|-k=aIdbF2w4SB>vFs3^i*c8}rdYAxIN%BYd` z0p?5nLl{qhc}m0a`r(OM!#3H%fiVEH&FY5Ne*(-o?pNlvwDL3@sl98}X@L23y)n80 zm8{veotQ z+2naY9qyl7j4<1a5@D_fve}Lfo9z0oBrrD=HNyNQ0b)Arm^r|VhmzN}P;vuLGW!lC znQ8Vj4xeYDEOk(T8D)N9zW!}+VZ)5oFl{NHlac!ZEC|eKmORfy$-Qqv-qA)We7Z`> ze06OM$8)#BidpVBVG#_(Ke$P@ftC*E{J3_imH$dHoJ&XUwyN|!?JJqnjuEE zf|>gf{M9w3W+ii_#8>ja*EA;>tuOyoR^mwA&Yc0Hv_GMBuUwF`2Lj96wO^}cW7em= zDGnIv8#qVQ2aI$HxkGa=X$>`AZLD$^Fe>-fusQI!oR$4>uXWqf(~y+tt`7r@-j?yM z@CYz!x^K$+iuVadJ0Tm>#;Ndd$&2ly2u4w0#?sbIAs8J2DOh1@fmFiO0;$Y#v9Iv; z-|pZ@7Ql9bG|rbk(O5oo5u(^!l!#($kcaOns{9_kf}p4pHKJ$@<-r{*04U<2@R{WR zBDtwEY!tB?rmg)mc*U$rMFGXLtODG|7u0pGitxeGG5g_;RWoiu30a04X~H9G&*YKIxV{? zbb#Vxb$fQP`;A-KwPD$jqaHW+Cuj{_mVT?91?+kHdKCK(?45XJ2%A&f)9|H5%>^@n zy+M1J4}&VhvLkV2{Kq^X?3MERyEVMh>w13~P1q|BW-RTv*MvP=kb+gk*h!_DX(E+I z<}}FAlvO*M%NHUyXGMwJB!Y~2*>%*P3d;#M*F=rnbb{*Rj+p~Dcqmy~7A3bXG#QVg zoJJN>CC?;Kj_lz=FY8d|mzyyW!wQ=ltcEE!w;DURMaoDQhGxloS}29}jS|WE!&8YH z3{TN2S-Mc~SI-i}R7~lcGen&w_06=+MHh z)0PspFNzx3c8BWYj+q17c*xz5AX9QsT3O%{IZyGH4NA$f(I{tb5ZFeUU$zeq9bVXM zV>Kw-l#H&&&#S7*3EOCvJa0tFts@A}8&k*`;%48Gk3iU86P@c>9?o?&59b<_hjR`5 z+qs%SHnhm}T2pWzCDRtn*uDxE0<$Yf3N!T^3Nx<-n5pMbn0bvbs|z9-jba2}I4R7( zBd=ed`_qUpdkJQ&0oioFs2SeA$>OS(+>XEu%OuI>=nOZv0?cKObt~BfV4gNGqW+%^ zTDGX6vi1h^AP5_qC}V%fvmcC`IL^?O9;%%M2#?q{P`-w9Ww`*@lY7A1rW(y zT*3pm*+g;+O_L=;@W&Bv1(;Fh7v^r$>J>K3SPj#b`g1QfCzv5HqgnEZl2jVMDm(KU z!i-X~M99EuT(jy}f{_nMiVboumUDuI1wW^eMvJH#jB+` zh*7X$M&BTt&Wf6qjC&`pYRx+kjLP--Cex>?ww(lwif25kQUoySzb^G?wJdynW zHGt9G#vOb30!H_v>Ll8o*BXjs#prqgMw^yqUr?Qtv+j=;to$MKGz=*IU&}gx(U@z) zzwQH!9wzjh`Ry^ms3v4%+Bk9FJ*UhbPcW(nW-MvPQv{>NAO)+6X)2X!rkzw8nNuLE zTp#z*C1@^U6fa7|C;{X;|Kd^Z^A;0~l0=OdE$;nIhC5~s7~!Gt!e0Q9^HN>m!3Mcb zL@W2YFu7%ea(DA~bi9i)zZf-kZCKbCVKq!!DxN(w{Z?^;5t=2pY*6AyQM})gDd?h= zyy=CKn>eu>pK8n;&zCEGXki}mLJV|SJcyR&&nms z8mL+syT5hms@AM3%&u(Fr-Z6mkd0|u)l6(@walAPwE)amm3b{jVdu00q+nGstE5uR zL`bEPslVl$Ea}1c^M;9Ykg6u4M5?wP&40gsOI;Myg^reUssinFCdL=uhs1 z#^U@Ll-$EXGJggo_soOLpFw#iM4$>~eyL*XHz{nYuo|WQLffkS?a9TFuIpMaW-HyaDC4oW~b!roHf_X-xl#STue;L z`d$j2GZ^Z7OahEzt&3U}dqyxC1=*N3&c?QtWh*8SjK+Z(OM2}v!Du2#!Kz|{q*Bd< zN@b4AdyxM$l}+*;uhDBbZ@^6do#MT=BHBZ~Jwe3Rjh z6#x|RQ1VOyC3n}4Jd;4lP4yt}SfTuWT|g0Keo`=|OHFKv1BR5?|iQM!7xvR^Ms7+#TDW88zzrTsmHqDqY0ZFN%4M?ftwLleZLP`~{k*XU7k&H(1gfE;(RbTx}?>DWQ zPyUWnJr&Gc?clFYFvFKEXL41${U4z!Y5sTFo(-)pRs^b&P95z%0;rnvRu)%ctCl_Z zG)mh7s4A7+!Tv5#6{WF`ZyK*P>|QYgS%y)clvvNssmrvN3I|^v*MbynP8(&%unPJ-(Yz^&X^PRWYR&NTiyvlS(5K z26AGY?M(G@9a0r8N~9_h?Q+4l&T2=RVedI)pdQ_!tRZ*8m29kx&OcRlS>k+&@7qmf>QE5ER@1sA0_i*2X|%{ zx)O|jfutDG7NZ#PTEK|58O4a#h>_XO0!RkF2MNhwvx^w@(%*{dyD@y=H^iu2N(^^=@S+M z80qItY&I}XYhYV2$p*ma+4Ze${{Tkqk6kx5H1{+Ny}Gh?EMT<%SO0mF0i&!`i!yO9 z2u61x8`H*lRJl@#ZW9Sc55Y`I8&5EL4pOkHnAcLNW-_JH$PBvkUFPFB`ofzDL5R^% zQ6feoK+dSMpmE3ka|uSHM2#3JAuZf7bHE4>C6g~va+9FQpbn*EVN;aurv;2q<`*Ny zG?&802&-Y*Qni98HSdgzHBj~W zY0SAbKvmMEs4w%+Xbn{#dn~vORP9de>ecf!th$|TdD`8~)6n^f+nMb^)tRwz#oEQn0ERrBte!u2N}aZh>Tuv<@DW zJPWCMAWEd_1;`o28k*PWI)_m8R@6w9uYHybcg!59!b9%qPYm9*K*?c5IwzFelX3Fw z8|8}PEFJQp%r8~lnzSoys<0ZSEj5(AIN#fbP=#hm=Y*2Gi2)BC63Gd}Q;8c4`Ow;n z%w9c=R8?oW6Ky_k1ip{g0wkr1HXx;n*CJJX6ADyu8mUqiL^2vhN4{`kU)4wdG^4@{ z_ugNSs?LI$s~!B+J)veL(`YnTwb=PkHD`~Cld@!S=Cy|P1FDXk@i_YX9DJPo&V3}U-ugcthBoh9 zyDtZ-j1Af@FJWuVet34SrQ0h)RUOF2w5_g{eBktyqpBg8v9zJ-gsK)G1*?i_DV1ub zvs4+P=zwTR0X6KI#pN=)0P?(7+b4SHy6A~$@Bs$DcjVIDBHXi*rtv| z+2%E}9bOR0zprl3%=Yb`$G<%ciph0u%>uTU4K`MH1-66dq^R)ZItc#YhI6htx_ z#Zta-A~)Ui2YuyhD^2-~+^i7H=nQ1j9iV1-^jG8u@sfE<2{(S$KV&gCmoJ_S+=Q&0 zcliQv6SSTxQQ6vq{3?8rfB@qF9wdAIgpKMYrIe2k=nzbaI+B1Ski!S!p#bh zf)$>RNu`?EE|o^6Zpk0ABJ*oM@)BU1@5D*Kb_8s->?WRCx^f zAzK!6)NL+M)x5}Yn<${ltmdM~RS{Zt`<>aH6tP zK-IZcZ)5|3s_5Pyw}s?-7^>JV>`9LrHwmIs9FqCu&S6)sZ=vzQfXx5Lx0GoZf=yjyj%cMWhF|asx-(;Yr98vts6wB zswirt>W1cr40p^NsKUd|WO-|{oFK|N_-2@ftlEo`yBs06>``X4Z%?n^Q0A8^#-&G|ENx;1Op^m2pZZwbtikd5j2F6#NT*6PWmi`)-pENRhe1m+l!f>p)DN~M~)FO{%Z zaMTZ3^uX->v+hhqnEQzmVIB-JxB0M8-zBpM%)>;DF#p{1LxwwM4lv^(t|wBmA(^a< zlADP|hL)n0ycmnJ@(KZFl=+3(`A4C{jMXr0sl>bK$@9vQE)va>E)wOXo_N27OjbrI znXDX>AUaotJe+Ic|I)d>{q0;ykPR&|U4lh$A0=}O%-Fug*AbXgK~k8h-%yx&Ex=4Y zhr-NjggLz+lF=xB@rAYh`&}ZyJf`TpD^UP*)Bal?eXD8BdTt%RcJfKBVY#xMV=I8U zxw?uX5nz6M^@@8>fVu937yc~3yyo*2r_KPg>n-`=a1Q2l$j0=1x3I9?>o|qL`~}Qd zmELa&%sC(htBNs7rJ5;`EwSdftOEH@6Iq(r`FVOd`PXY~WOhIrb}lul&{)cLT@pX1cV==#(+=@iibN^00IIYmf@z2;g}gEH%00dPIyKsxjT!p>r){h zpv-ST&>gWY?A{%#VcOabRX?|NE>8jinkDytf=C8FkyxH9oY>8F(#N&B9&&sAM4&X&b^yv;cXWWJe}DIWo3c6t#NHh8C&?KjNWehZL!u+pu#r$FY1 z;bUIDKA|-P4=fSi3CK*AMPJSZGJRKEjyi4hFjVhvSF9P3xpw#JpgvM7bs6=oBwI%YUOF6|a%11_hCfM&ZmCPNb@X-s7w~qJPT|NL3rb%+(J5>V{D> zte3l(tJ>17gsLKIvSo8h7So>ws^X&_&hG_OIo)`>?FCSE`;Odi1yFTw!PewNpz618 zgC|3Qs!HE0Z*&E!4)~7W?{o&H#e|1OHUp~0>8t)%8>qU_%jwI0pen|^>zET9Rdpa6 z)3(~s*xj?kRMOuy05g`hrR6ZZFWL;GU{x_Kq*BdvkV;tD6XflxPNA~`{gJ8!Q6g2z zAY~6;b~iSgPN=#eYNTr9>TDVAm^n~|hms}7P;wZNl|4~%9z_PPDCYzURH4i-RhO@4 zl#ydunvHf=O@sSgo6B8k2md-3ud)XJHGKZF3IDy$|I6N4m4w=CiO=MpL6s8lzv4!J zPwl4v?=b)WbTb=v!+a)g<}9rWa@PhAFJb4@d4E-Bz{n=s;ogWyE&HPX{4R3=qfv`$ zy@~~lY`bSfK02;747+?h#T_uJ&^^A~aKLEC^#6RKb36=J?v`#{88BKO>ip<2V6>+0 z+-=JDq;o0**_bxY^nqa;&T|-51T$9T;yi+pEl9x%UmBH4HB(*57=?pu_+>}&DbJ@7jCP3{F`D`!TZTJk4r4q##IG({S&+AJP;!@qgd3D=E(_eC z%r7_Wfv<(l4OYXnY5HGzm0qbL8RMZ@@`fr(?xkJQ8==H=ha2=pC?&5Exc%X*dv_3w z#)706(H5f^@mj!$wi(5U*NBmKK_sJ5Oyvv56(0X~(3cwf)vD^gw}?@|UuH91NorOy zU2Fd&6?cy$7--f5Re*zf!FYXv002l=qKW4E5FjBs# z)y5MrI)AsW`&ht8S^ubcC}0#{dVUdSz$ot3uY{6-(Ga&QZ7l8JE1@fTTgGr0^@nUs z+sZv&Tcq7I(i>^Oj1?JRJ{)@^50HWtmg-GV0}MrKU}i5SU2 zo?TyLU(a1r2}V|;MvNkze#&si%mE`jan$mmrV*{$}}Z{Y1p*qbL!h&mi6V-LY{Cm_ji6CThee zYSvE~?wC0Y>hMr9Xy)FYC9eRW#B+xm^hPMT+Y_)fS;<76adQ(C=jwSZJb#u_o{XQq&ErzGnTepox#`} z%>yY|Rm^;;R5Poj(#U)V*?&&ah)c755u+SYB1XSKHdxuBxs%6af>DtaK_fZXI>rtJ{LW6_Mxft&6dH7l7NHaWy;)*d1lt*x9Rd$;b_fG>d2`Zm4x zd_D{7DJP^|sf=A)OI6al(j##u;kqqkALpG+3Gh|-RWvLuSo4|~vU1+Pp-e@~W!Kz{+q*BcskV+$CH8w|fbgKE2 zH9fr%BO6g7MioGQ89l(VMIS$cQ6*6$Mr9x^+%a>&2oLMwH)!kbM~qO$T%HOOl)-0a z6B$evyEu)5Iwa|jCJp|Ydt>}M zQiW2|IiZxSYJPtnccPEP5URd{q*T!cq*U=*po%sjrHa=`Rdzunqfr!{&lL_Ff$yB0 z^}`eHFR}E5S$IPf#Y8ju3U0b#)U0Ga?C1XX$YX@61IKb?x&>E!i&le|q_Z=--UO;b z9;ZdV2defpOb+M@R0T{ZUB4etwa=^ez5YN|^zG=gVL+Ab=xNTqfGVf8^S3nss-6TM zO?m=UsUEMZk_=SIt$X{#b5xy%Y)soKt&Mhc_vvJe7Y}AEXtOXv)di4(RmCJorJA`R zl}4uN@f_Lk_HCTL-x-HgwG<^%)fVLOX#q8751mA)VnvNqHG;Ho$IO8$Jd`XtfRgK+ z2vsOK=E&kyD0^%Xs3JekXXkXd@9n~-3aeq-QiDcxxK^ezp$g61H2#@L70O+kaPAsV zl|rOsjOTcpJF}He5R5v2q!`f_qZsj8z=*aP#faC4QI~>9Mx*G*7Y6gA4+tH~0r0HdYvmvp@V81;EDWpn#IT6SH< zwv|+X(fQ$VqdNgc&qi-~{wqdnNOxRYYX@L7v(=9e-hk1_4Y_-6{qQi6|`6Hl~ep+&RrXg2U(wn6aR*$`8TLDI26g~h366Un{x8Hc?Q zT4$#U+@Q>FZ`8Qa{lex3t6|zSv749dn89&_X332^l-%plu&7%iIVE`Ra086c$~|P- zg?Ak4*>h($_%w$RNQx0{F^Und1&nB$QH*#^Fe->-G>X1_;h^LKM!E2{tsxy@KtDv$ zPc)O-!5`f(YF09RyK_~`Hh04}(AubtGMPn_W90y&CWC7HJ_Z=gJ^QNkI>4yS_93-f z0Y>{q^y%LUFxngBG=2|YWDFQwbsu09II89MC4f<*!^@im0Y*&}b3;=Aqwf>7y{u|j zv&Fx3eCW+#Gz79SZL4%U&8;jBqY+@n!k*ngFd7R|u&S8xQmJO9OQn(d1M=jh*Q-m~ zjzNryx(O07Dh_hj>KkiUH1{PK*@zl3TGh`e!yPjRjPQ_KR^TX(@lbMO6bMkWi3}oM zLf-2{>rrKAdZ~mmzf{?Eeq7j8VKq!!>Zmc(;u%L3nk6%bP~yu80UyZ2S(K779!eo9 zDVY%yxf8v=2)Ldr8w-+BMH`S(#cP2o+JuxUUL#ef3L+Ve;xb=2a0H&J=K8MAc7{&j z@EPhMiX_pDzJi;sGc_w2=k;9GJYw{5l>;cLb__JyG--1XK;I^LB4EQ1v$a`5~;ESdG*tj9iP@rAXL>7HBuEBZj|AUnFCdL$UR0PHy}`Q>*WxtP;!tF zs!(2DAW(%ezf_I+Q|MHYI=d8G-(aLYOJ}=2>eg4|QiY81&@B0^8cN}QL<%{7o9WvM zO2#LSJG15F1fx)p6eHSV6eC^>7|}MP81Wi0T3Hauz<1R6!a>XP7&X-ooUA&tuRJ{a zfbXb@W^@kRbOWdvUIlx@RqZlEFzT0Kl+~K18RP&Mb>CWf##X>c{;+&blf7CtqxRIm zx`2^EdJ!<%x8A+yt1P%wI+Oc34loK1`|nq0 zz$nym>NzHjjPbl68&ixXDnn1N;xHNqW-O@s62Zt1q+nGs3#C%c9F|JBRQha`RV%Lf zbMxp(#K>8ch!G1iJ!7Khj&j}vqt2p6jP`so%5cZb0V6!*UJxXU4xr>doJL*+L&?3v zLNG#k`Hp}Q%KTz<_~etq?wqh1rY)uLcDlEY!wAiiAsf<>6fC@^CKQ-_A7?vY|z$FRcjf1FIT>8QXWJC4o5%B!!v!4TYK40?gEND9pS@ zm^T+hG8#n`UpOeA&?la0d*18T9#}nQh+@BJ#wy^ZJ59|>W^OaCYK^T3%pNYkWXr3p zD(?s|dpvC0Y&F1qV$`<_(*fquvZ^O*0L(jIm9i-ZFi(AGd*Z@Tt-<1@^=bpaTz9Y2 z!Dj%o(K1N431EJ3Wqr#N0P}=sizOZabKCW9OZ###dqXy+=etJ2xcLt`m?wc53%dC! zfq5E8!Kz{crBcnzmr5h^5oADk_4rxqy%6RMQ6kJ=L2fH?IsMGeaRlaUQ6tO`+y0W_ zj+q0@cqmyk4rLa;miV1~6cOc~1bjuqfY)y*e>!xbBTba~g*n^*X<@^R)i7uelu<5Jk>kW;0znH7l98V6JK#N)fgrmi&^11UC(83~YBB=@+o@{}6W;P*Hs0-$#^n zR1gK!wG%}#!C`ySuv^RE(cupke@GcXzvr@AJKP?#%qxm-7ak z!<;iZpLxc)`SH$9lG__MRdG8`Zhu)G*)TV`9q;QiECabcX-Qmn3%Tvm?~DC8a=TVw zk;^~GZO03h%C#o9Crll8We>T1tx;`9`qg-D4C+ zQ67C|Zl57kqV%OkEz%1iwP=;VXn`Sf6Jw^kW$ zr>A{kM&jf)7B$Da!1K6JP=w6A|wCi6Q&A+zW=LS~s2nMKbLGRq8^KcvKN%zCSwIm(|hP){qoxk2tvbQ(QC z|62{C2$(EWM3^3&y~2xT=gMS0bc=dqgRuD(NoJQtryGtYnd9d6c#udk$2@cM&PFnq z>3pyE-@;D5t#)o%ZX}rtoqL%#nq+?YrT+RXC(`@gxtF0!c9Qv0=MfRxNM_y1;Q!{3 z%z>xRZ@$T8K2OQm*0=Ac`)fLInJ-fq8Lez=g)^(Mgi6#X#cRYMP}p-}mf z?>i6g1eph^2$@F`)>y7zwcz1-FE0*!d^PN6`+^YFggb& zixM_SY4ZJHou+$srqO@J{x}>xRii~!(#ZWv!Ciw%qk=AmJXN=L_RSX6qQ5g~G{sQi z?N`#su}ngcJ!!OJ^T9{gNTb8^mwFZ>jplTyT>RG8pvWIP&L?gljq?26(PJ}dw6W%r zCoc2>+W){Q7na#QRi@`(Op6%YLxD2(ImarB3+>H_~YQV>Fk9& z(>p?=t|~&KUW8%g1CQ1{(3NS_Uu9@ig7$?OiIYZH}#ADy2E=;3yDnp}ARD8@xoHW8BKf%5m7bt-IbvEqK63D+Hcmksl&=RO<1Wc|* zK^2drwniw1twtfaPMvkj%ML9O*8FS)_F>(v6Z{%wAgk(NHV5BsMWKR3y>a4pYbG@E9A2ubKo2i8ONJmBbi_R{Z@56m)VPwv90gRrJX8f9?5ap%$Cz6B+W>iWX7WA zY9o+;iH%(s0n#f?aI6WLforxZG6Rz>bGBotEi;N?+foCr1Z-)^Wk#3}g7a|i3y=?j z>}n%WbF~rpc*8QfP(p_o2C2nEUeRyzF{}C!3adl|3aeyRtP)Kqtdf~ol@hz5hi~M} z+1Y&vM{l715b<^BDEr54X|xZ}k5j@tNPk+sh_FGbE+w))w7LMZsC9)v05}qv$SZH7P}@oEZE}|)BH(0ShYe$Shbe0_ORZ?*SG4-tlFqDtU8i4(E&3O zC#$f?Z#!f|B#?I@_Vy2;=E+dt!yk%Oz~ovr`%0=?g<{yY)Xbf2JI&)(A zA0p`>BATJ*iRvb0c+Ivb#5C$gC^Ql+CNz>+(MYtJ&`4%z)GH-+W7dbrnNu|?5ix5` z`YkyEuR)_>N*H~EO%^3=kovXaMU#p!jb;QTI*h6jKeZ|8a%gDGtLCK9#hx#MT(@=h z&40dsSu3sAJ)Sb|25HnOwnQFJ(&%8fPae-nqlLzV;Gv|^bKSHjX-K0s@26g#LmEBZ zHuv{;(x~aOdc|LHjn+^ywvAK%Li<94xkg(kjGSh8#5CGVs6>s@K`ol3|Frn4TK$fR z|9>yyDXYGS$4vXk@7FGLb(=t_*hxjG*q!jBPu7JST6JP7_E8xs-sq6%fEfiK6|vZf zy^HH0j#h#EIySpv3FM!C`ws&g@QYtP@uLrzTor?6O-$_p4#lu-?bgLSZ$xty5!ReL z0VdMTG)2qNWuRzQCCVF|>003^Ub7MIOvSZ?LPgPHLPePs6-Ao~6=jBsn^Iyo^nock zb6ORrRGxmqsRuopL?4(^!sr`pvP>3XgS2oxFIxX%OvOz*spG_q{?dY!d-J07jE1D* z>Nkbj*CZ9!jC1(!8?8SQ_pw4WsW_v>hkU>HbdEH(ox9*Qsd(+7`<_XpqU(gF&#!$6 ziX5FWXV)2|;;O4J+GZ%^EuXJvKw5p(;Y7k%ZoZyR4bfr6bd5yvoq%^^Qab%t)Lx z!Xm%8#ohr6%+21G%rpY_W3Rhn8UZsdP&5K2SECPor>3?>D28oI{gEQ8IOJnL`Vdym zofxEui@ffN6lbE`Bov~EHW8x8tcW67MTjCZM7fm`yP-#PoTkQSMI7>obK!*|{U%)tn@X zLvX)+b+{;dC>h)8e>Hc)_A6YJgA_(iKi^`a94AzwMk!K@^e}-It&-^v?b_8hw3MYS zL}{ZUMCm~I^?0iS9mfPQQG!*5C||7xhNTPG?{lcjC~tJnUPV$$X)~Uxy!IcDdV; zv{hdp`&^A=Uhi!zwuEG^{ATpBceK9bzQspQkjzt@ZnWG$GP}GecJedH95dW)!zPkB zbM^B1Mv}}enr^Hyfn+{a^L@|aB(q2Gs`vf4%n6i?ZGAh(S*V(nPHV{O6N;w({t(C_|x9?3|;+5}v7Tzf9}` z0-+M63kX^?NqMzsl~xkETV_l<_@Wi8TBjnc3Mbs~eCevj>)SD_PN@v58dAP6qpHX% zENVWh2;`46uyc+;ehQ6U&Ia}xqgVw@u2ub8tV(UGPz>9ay5&)K%Thi>BJ607!w4E8 zqgjRVS1fG7%_!CbYHuo%L~jaBqBkx6zwb@bK{b!!ihe*k1r#*TM3?@r^=jnE!9N9a}a-`XFvUgg+^);T;`Ztwh=I$eV_eZw%Y)$sA z9k3&hmF)fc72C(`>GJ|6j8itMdd{Ke~0WbY8yCJp__-o)KGa~ZRE_UgJ7YEZT;J9ySD2BGzwJ0C;^)+TSeF)Rr2ITyOO3c9`h?!!A^I#!_Mp7 zNSBAB?z)sDjm}p4-YC=d&b~jow!HtC)+cPJ_iG1f)GckEGTx+7bkLqLiKNlOg8O&I zkVbF3M}E&h8olV&X4-JlXlDKV3r(a^!@jMvKjIqsP%^fSQ+7ok=iXeSY7|CJ>wjh% z)h1M;M#)c$CaHxMtbeNGi zX@o`14VpmyBn7*Q4*WnjcvYIhGy-nT-9Q{#0+XvzP|j|ttr3c0+fq*|c>VmyH9}Z( zXbI%rFpbnG`!-dJ=DcRZ(o$b*=G&c6Xe3%pXe6_uk!Ulak<8GjS4!;0tREt0PSvPD z#LaGF!iTh^PbLNELzFQ32AeF`MVOxJ8^()P$$@F)8fK>}^&mP!FVba-&-BAZNu!9< zb4HgUjoJ+L+x&pm=h*ve^Jda$z^Ji_SxBP}b2}eOL%O`GJKXOcY4mN!!?Vvn2SrZx zxYII()(<=RqGAwfRO8D>zjW`}dC7v5jBVo-EiC!Y8C3DlH*gGkc8l*eNDxv_eHT8WF~}>C&-#-L`x*QW+X87-y%$jKoPJENb3}0#rUg zJ(@-NbtLvi6h!y*P&5K2SEKl!JyTmF6yu+ks@L8#SAKS05@GHQdv^nnKafPH`p&Z& zLRDg-BTYp4ShXI%&>FAi75!Srtm;fCtP%|lD!d}AdbGOO@f=w-`QgBZ zgK7Q5MUka?lU0`+O52NYt7cI$wr#a{c)krgxmEKhjNJBq&8%8Rs6>s@axI#qty;87 zg|FG^Jlpj&7$!G|RURtBsxpMjrNC`rzgjb^%Bu{k&Rn(AVMgL)6&5v*`2lyUIoS)vH;H&FRUW^0&;Bzmiq`>l|FSnXDSoV^8-1w0_JQ z&&eTVRa9W!p0&7DA(V`5TkV+U-8q_DHIl-}>7|>Lsp`^LLM3XH!nA0TW@ynWJtvIy z8ToGC>}Ig)wTiInJ>kHkKckIDTQRG?s0^z<=1Zf)jKs+*EGjR!rkCIm@)sS`kNnXL z`S;9@;+GSmPP&HTkPnz#t0L$3OKq!A4BM9aIdtK)U~Uz{nz0I~d0z?;Rf&nlDjb!!PwtaOSGt<-fkEW(#l$&&dUD%kca;lM$nA~IXZ(tz^*Nh<@Lx)9=b00? zcR#tEn0ag0jO6f@-!=T~BGdb>Iaz7MG;(`rk?-63()v7&SNo46w--HFHaCd7y_k}* zt?v=ed#AnPZZD@Wa{9Vi6S%#OP>C9)^;$GZd$ma4NbQ?OSGSk{tt^|G!tGKj!tL^e z{pNPt|7luF=C+T@aQjQ|G&;;koZQBu^7;5shNIXMcJ#`D(F|A9vv);w?B^Udc5R`! z4NR`v{WA|wZMRVj+m^~7JLAzr?l!`j5fjMoEM?CY05zBWwoX+$*QF#nSFR*F*VQCC zSKfa+*I`OVWLcbYQ@Rg5VM<}NZ{e&==BtE4X3=ki%rYx7i=HE7mKic%ONrf>^>^gV z+1WjiZ{N%nQU24Z>=y>p%NGLlca<qJMAws~;Jei=#Tx*gIz z??*DvKVCFjZ(6_EclC(rB=d)wSBj40GOwp(Z0q~xfT#I&quB+D%@jsXoi8()cMvL3 zqqIwlCh3S4ty12IG`e$zOH7Ym*#t5dR1q>4BkVZT`|7j7Ett$DREEsXv@gs^oMgtL z@|K2BhWwl+d+9Txnp2#>GHVr?fytG5_WMz(Ei;N?+foDD4;#FR%Z#w*+ze3jqY|h& z`~_;xcwUO<6+O+3S@nQWSS1=zSS7P!m1sg?mCUf}NlNU-tbZ?OPPHmeM9$jxC*18t zzjXriACxe<3Y#o?5jIGl{_>(3voouThmUERXGD! zy}3r~2kvrtKZmS}(N+F9nyh-?pwkd%vgg(6p>A$uRjW!%kF+GK0`vY})q~c5JMhNe#|U z|Ir9mJyQ`@y(DyLe>Pzm{?g=Vq`q>JAef?*h3-%W=H>rl{Jv zx+KxL`u{(6uCM=gt}m2~$g()zRl1Ks`axmj?{f|&bDCoIip-+l2$^M8WEMR~$SgBt zwoi%OnDyytH^`iNyqhOt*otny!@AR@WqOuY3G8>GZW{9kX%$z+adZLeF| zphM0PByA0kMc*@#%-!uzgv67~J0s7|ze?*XYBU6o|clklTnH(FooG`H zM&cwh7L`lVp$z#05A5ABi1Mx)f#0&g{?+}(Z&_e+WsdJWCbeZoF>G6E@`5&&$6RKF z`TuY1L@Q7;CIXd*01Z;nA-rY-ax;x86N)iWw3yIHWW~;P6Zf!h@bm_BkWCMvb z%5~%SkN2d}JkN|BF4Ow|nq=)Vl{9kglYM++(kOlNWog|=msW*_zHujw7OxoU?@k(d zI$K@4(E1%0Gp6568m&s#?&MjnQ6eQ{+c@LB2OVw7HFDU_`*HUrfzjp$nWjUC{`bT#bAd)=zDXPz>9anl|TDtH1n66JgD3T7djj4s=U@G^;=5 zdWBC=(bH<@>YYUAI+H}_YMDgm+Wv3nsz}L*EdM8;15&z=L8?q)wD0MBOlE&VA+zW= zLS~s2nMKbLGRq8^8>hr>%=)%+=2V&W5wja#+2b{fUV9Lr4^YA=0h=r{Mc5$uzT!m- zDZped`Gv4ZLf0`Q?dKEUqSKMgS7+6$t=rMrw|DQsewS!{x1F8dOeC4x?YZFNLo%D! z4b79Cq|K0FY2nf&^P`6)(m0dMXJ2Re-HFzZ`tDG3H_6;GaC9)`dTzet+i;Cq6j}cPqSq1?D~*7T1CiwgRp3W(gS`^Y06}d zR~a%d`fRVmjKoQ1Eb>Z;({?s4)9wd+t0POt|zyk@2%)sQzY!})nwPi*zY+EX> zS+>PF3$SaE2y5<)0n#}!x;>tq0|IKs#Ne!HSB8iylD3eGmW~|OsjkP;coC) z(&f^Lyra^PMo+Um3(ZX$9a!X6?*gqiPOw`QMjF*GTPj^)(r7`YY`OKM%e2WwzEmKM zE(guH^z&0tWS4sl6N6~|pGN7kA0~}@*6^$GiE9)>$=Ehdlm3B~M{Ho7lxiV1h>@acBulu0|i)HcM@dPz>9a>ao7u7%#37 z!kRG=$Zi(BOmEtXW);RSB(X2oP3ypGcAh)aXcM8(NVJ&HNM=PN(Ply;nW544l-P|~ ze^kz#R-=n?H`i)o)h)&}8aF$wE+o8Fy)e?Hz`AK| z5=jep_os8qkVZ$c)enxM^$SK%8)YGlq&%fxWyWZfKj+_^q)XmDD+8<1_A~rv?tMxc zEgzOCcL!QOuinbBCrG2ME$am6KCnAu=2J4ZjWct6K#SR2qa_qZPS+e_8f_v}qDE

$Te@dUd%3e7YZOk&*f!3LC#?e3ag9z=7&$%sz9B}VC_*J_lrCt|BqeCkDz&(u zR(Gg%6VFmnb)ZpO6`@fOVbxaoqkfe3XBq{o42|C3O{>F<#7QG8@+VynKqDYO(ZMtV zhA@xV8?S-R|0x;)ldDnFZ>g>kiecMQgVGgU7sNF}SaU4^sCnBFkiQRV7w#xKY~?lE zxg^u*GNI5&w3yIHWWJFU&}sG{U0hbHqU2XW02dAU_R4N6%qwV^7z{;-C)E z0kWjZh5RmYUro`;#GDBZM`-jetK)co2%6J_MpFG0`y|kPq(cKFy2udGul# zX4OMNVU=h=VU^5^RiX)nRWie>Cn>QTv;M7|Ii7j^nLXlj{aSO!1Ra4@@BazgSw4!e zLHgXE7i~;AX4SLd>2%*Cw{@6I_5|n7{@^QFGO5PXQ(efahG{+hPt*Dmftwsd$*PTi zOC60TtE%`#=EzU>y!hU#Wi#5|v+T@qyU40pla1-jw0@V*i?P?qD#w9!rd8!ueWGM+ z+v>yWfbnO!Ro^L$f^2D22UaB#Dp8~KSBoYo(+Ew}Dh(pk-?r0VnO6%|g{lavMiMr> zlI!5H7WJ7`V^xM#0kmt(NSv&~BLBwLP7F>!eo~&DJ_NEipA2QE4}l{)DpmoLYgN#j z;;C&FiecMQmrESVFqK<{ux4-q`mv7%vD1e@KDckd;Ph@0uUT(zrct`Zsz##4ghnze z8i_U&8p#Ze(x=33%z78v4VqmYoH9pjpI)}-3`cq+M}Xc{3GfBn2X z(Y2?T6X#aN~F#HrL z&~*ZNv#xAZ^GI4hcK6YIgUFjrc|K=9Lf({i?2)w)`BC0=e_|kQU$T+u{w(sQN{uO* zTGRTYUkjGGPu^r|X(=7Zz44@EY+K_)*urAZxHsh}jGT7xqfAwo41`M5C{@v-Nvf|! zt8|61Mw!xk_OGk~Z*HmxZ*CJN{;rX;{Utx<%>$L;O|R?@I?PC%yuqU8T_-@zV*)_U zgWSMre-v+k$@M17-g2q!4T@pgQp?*&ZFg~R5LWK-KF=yla}gL(QJ87Z15#& z)@HuL2!%$X#e_yOD;kM56B@}3jYg%!Zp`{Aa^|!eojP~9K;nA(T^yjFri9Tq*kn<{ z2B~)dFPi=`)2L<_2i>z>xerYzT{4Cb-t>;NxDoi_`#jR9;0up0$7%i9nGU8-k>xY;MPQ}-7^DyiqkS)3VKPr86f%o`BV?9Yky-Q{A+yYod3s9h#;ji|XHJzl zb3|;WvqL^lpmW6m`sGR(C18`~h6o#^u3LD~EHO-G^F9Y%(KId7%_M1moNF@b4auqh z+xFTTlDUz8)W&19KBmf@-F->sY&DN;T~0C=8L;M95t4RVz@yM^wEePyIR_0QnHxs9 z1+}2{!B_fje@QYgFLQKhD3`ehC1YFPW7}VyXFrDBJ8Ypaa{6LuU5trS2$iT&nx;jQ zv_y+mDf4~@UGob0&x~1bgv_ogLgrkAj+;+;FAS~CWX`WLWRBQN|Hadc#7Sl>db5eW zG6={Y{bJ8`12xZe18*-;WCkWz<~9|pq_)f`hHXnt??39?RW38anyXhp{>o{3uKPTz zKU5_qI?_Z`xhCurH0Y|@*S;sw*RCef*QO@X*E;{(*TzvYq6DX9x0T*xkS0?Y`73{& zxxJK7xGlPoa9d`@ZPAg0+cLxLWht>6vwoADIXk5nJOPm1x(GI%I%;ixNf& z*ksuv!Zc8Smo>V<+)kH9r@Nal*>@H>T)5!)ey_+?r(biv?rLBl40+h7E4h9D_m9FRT3>i=(~0lM?YSjBotVJg zmM9t9`X1U=I^xXT&PZY8w9RMcwj-euHA?>jO;Q$Z)GAdWobWJyS?Hf?aJz|$aJv~{ z-32aLUv{m<+%~BUx6j(?beNGixs65T4%|?NHG`gBEp(e6;~&kCKaWNijKUZ`eXh8T zf16yl<8vBQ+ieuXwxybXz32OYAMYZp+~jhe)q&=CSB6SV9c+D=4Wg0Ce6dH*Z z6B@~^Xe8Q9Xe2WAz3c+r~1 zGmZS4=ydV1-FnR?T`IWDAN_)~nEJ*)IGi-{={wLEPU|lW+ql0cX|%4zS$!C3G%BsT zdoj|b$Xxqp{b_rT2}K{aC5`SbE%UP(tv~Y9Ezf7tD0AK&CFgRDno%;gjq|19Y4C9)mRdAPZM0~WmJtT_sNilKQ571kQxO_%BFs=TtY)S@HJL_R zRfa~d8|!qKkvM6DMdd?@p$z$LQ*=&lG{ZS>N8;f*XoQU&D>fC!yTD{?R61>HYlLFh zwp6F`x8J|xLnOkQ<6WTgdfoG^N>G)UXoy6V-)Bb8RT!k0-n^pIB`~XQ6AG(D0}88T zR;&_DD6EnhR^3U7-I(hUZu@^?R?Q|OBs2Ea%S(TtN ztSU%|8HtlsSX4f87Rpe0c6u~Jevi;0ScQ#ij907zCfBOPF6mR-DimYA{DpII*k;aq z=IU>56~dYWPauD}C*4UF&8mdID`puUuZcOTcCPJ7bgsoobgp?xbgnV~cCOo$jL5S1 z6{&O|gYY_Qu7ptnHd#)HutB>2kQc4MeJ1nK*EAYU-#ULTNn7mlsb^0}&eEZN!PiLUz;Qpb z9ijFAExwXN=U$vo)ksm8@g+ID631P!C@C;Tk=uqMfzkdXCi6I%c4XY^t# z$-H;-#*$mO%u$q#ZGA6_i*WbmGGC@Ja{8)o4GfVt36-c(iq)b?daOmO)b)){mv}Df zM!*~cWbUORWDX&WXqtD;=&8O;=FuucW>4A|W+YBBV^MRt9GHK?>t=`Zv0sruer=dt zkpMQhrpOFTuFT!PWlU|EQ4HIbs@-+h?+gXmt;7gx9w!I#n?~8MNTBAx6Q~?<7^L(W z(zA-b@qk%Xm{3?H8c2L(=i{1$>W|5iz&aTd?~qj|@;%CanAX1-eKVvB zSrucI#&pDi=iir&O2DeOTw+(SQW1#ta?D` zU%XtyT-}Y#s;4T$s-}kYI?PC%tiqz^mPnxHL@SV=xnXw}1N#?fCJsD-$+appA#-Y5 zg<{yY)bIX#$7bhNA*{Jv4s6bDFreFXqFMbZhZyvg#MZoKt3F{GRU{M|i53$Y$*gE3 z+DvF9Gc>A_61y?$8_Jo}YP2QjMz~iDy?dH2`zc}c4K`Ueh_FE_Jen8n!&9cwqeM%5PKx@*-QvRXQlXTJF zNS|n-?VoOpHyHMtIm7vj56`|2u!rytywAyv98q;XA%4~3= zggxcNF*wm8?-g|CK`2AbCk_yeTi3r@#yF-Cut8r%BVckhx_aCtwKYO9Y+I^YkX_qC z^58^a?chYnZ!@7gi_fzP<6VyZe#5>rr#Q=RQ2Say5`ArT5`8Uu5`8V;-@aCdk`W~k z$I41?GDr<6j6AM?&fIQKDBKp^NVqMt;VTgFrX$U0hJ3`N_t4S>iqC3qicO+7S(4~Y zmLz&piGO=j7$qa}cuKxNq4XDnG@HU`P{-HI-VKDpUeQs6y)rBIimoE;l^OPKOo`o? z^?T*asrIIe=yq%P=#Y4NUMWDoPYI(0Y_fC}VY>L3OJYTfe8cQ*Q$*60XdhQ=Az5ng z_UG(9vhhy&IZJ-x0C)DNt_NuS{y;bTj$~tV$8nEqlfA|ZgA-xz%ax{^lW6<6s*kqi zCVOxE&Q%chE`8oJOGethW0#K|uX1}wQZlyn?KeMtfSKDnj>5=k=s0HYR6-?cl%{LZ zBrVgTRVv~x>Gl+^f7*FZdD!czBJ8a|cxqMLnd|>mX7*N98TRfdEa@;Kak3YSnlCE= z*Ve)9j_ghXAiu+yUVjnBHolaxxj4W@G`aT1&wZRVJ@Vq+&Bqu*^|9RTVs-l4CqwS} z_&f5$-(~pws{FU_&AAuAcGLO}{y8S+S^QH>VtWy{{dc?Ne`gt4svgqmzmo5_>^nV* zVcSxN+a2-p;r1fD5#MJWNJq5iSsf_96AjYv8oVk8zhmAkAQaw+CKBGrtau|DNq8eO zyjhwOyD{rG%b8QXv5T1TYWJeAJ?X0u0s5^_3CW1hP2-M(E935wEa=9!*;j0HP+Dp8}fK#L}6y%w#~$U%~B=FZh2Q|EZYn{g__o2i7QnuH9v+|0ndnWZwkxjI17 zVMgL~2#dw8YHitYc_AFj^cRn&vwh{_aM4JdvWL88Gts+E`8KUe=iQSm>;d17*qQqSJRpLwr z8lnUA$CNNypG}slB5aU$ALK=w{h5h!AX3t$fA~BWqI5ctxA-0E_+4BdnKP0o+1fU} zzK_9^OeWUhsUS%Xv#yRGj*?`v1c1vf> zLfgNpRkQFzE=mF=W7`^62DZu5i;MD*!pP~a5!G;b_>xeG8l|^dG)aH7XqBd%lytd1 zH?3N6u@^*{r6NRGNSOZiwFTbJK1`HlDnpcvv@gs^oJ7H*=DUwTe%6g04+2YUQbYkJ zSCrX-uTxtT6vMV@^1mJQt|9-ehp^_V0^1tDe%G;6CMwc7ai5^Ach%n1F^S%EI*Hy? zDv91S>)+mVl#&ryJ}Dm_D*eSEoun`twDwnK?@dBsujnYkUYQkpMOP8_$_#tsQern| z{S!HJ$RMBWBkq=;^=o9@M%er8pRk=JL4*y`?Q|Jf(SCem_8!TcLAPRDx!H@!(rwke zzb254X}@jA>_Ybbnf5Cu?Dg(_qg*?(u|&f@eM^$PCwI6uEJK#I&h+5cY}$VJi0F!G z$=-s8?%b$P>+c)JW_P9SCl%Gjz2Nqqr(|sFyHCqJR|j%?FH;yrY4L;E8%wA}jZ(Z8 zP118MTBTs;47%slGquaHp&ab(sUqwhNH{z2Yne4SDl&URRffGeXkVC-I2|5hQFFgG zFp+)fmmMAgHIIY?D|}UC1}0bL!!_Qgw#+DoZA-O$yDeQyE;GWK6F0!T?2CVN;wJik z)}KLI$&4flWL!*N!u^Y4gw46D05KJ2poxgX<*zNSF zQ-J9WA5ZpTma+7-d9=N!snbjA$DqjTt$f^}QSZ$@QQ2sF z$0h@ceBc^AqGW6v=i{hJd53e25-E(FmJF$mK~UE&gHDMWB}t1WNv}n#G@sD!VE4^8 z!^=XWr7A+BRfIhvjM=VjtiUwds4_GvO$lR0;-nE4HD84U@+j*&p-T-#+2y9f# zBz|Q9ldDmv&*#+E2*t2%sRxsbt!l?LLRd2J-0NcJ#*JpKhekD&FyDy&w3HQL zx*E5J|LdqfOe5>o47yJrHavqy7xEX5h$k(|)q2{X0BK}r8gP0Kt?#mB`cE@y@%v9H zuY9D@4cBdJ%91WEpRdTdkhULNdgiY$q|u`xLr2%6^&k4DZ>^{84-Ts1`kiZ3VB5cq zvvh5M<5;edJB5+k+nMwSRQ)!H3E~qthxvql<(kK8Gy7 zHNHI4=&H)ls0kGxGZH6_u*m5Y~)FK=$nFOQsP}^Yl=TC|-+gLJT0GtCu`&l~l&9`5V>#00OZE8^7t{7V zZ%yv{jx_pRzUqUzw0>@B)0tefeRNcVO@FvXg((@^#@X{dX!Rtnkq3p5)7kxv7>&vi zDp8~4rA3oeLyK1F1Yv>7IYze4QW_eaQ4tzlBHVr}a7X?@-b|wym7!7Z9~pF*kvM6D zMa^ggoBZJE#L{ z&TO>Go{`n8#h&_FGv9uMLL<>)LL-?KjYOLXjbw&KgHvKRX8l+>bE-za!rflw@+cIt z78->qVe}0)SzJWeAhoW>i&j1z((~)vL;e8wvBVAw)OT5uF(t%Bd2xWGL04xDp8}fNQ)+ElNPO#d%cXhOs;bW zna7ueMxH7{qq2nU&etCGexMiAsFKRiD8etJ4l@!bjj*WsZ3NW(HUjc{Y}rL^U_z-D z;-C(gT#cH(OiXQ!Pz>9a@^*WCZ!p&gVa*FlfSK7BJlJRiRGy(XNUef-&AxD88Vw*6 z8i^JY8p*6^B-%`9Br`M`ni9J)>&MBN(`r;|Q<3(GZ zo@q36K}KERot9gm(Nuf?D>q4tbj~+*-lUPf`xZNBlsS626ErIBRefkC(r83LSg;rA zlF%oc{R-NCSErTLACX2CpT~y#(fam2U48S@_EU@%u4LdEO`&9L8>esIhEemlMzbi4 zoYq)NnW`==B2=PAX^9q1(jG0+Tjv&L)MdY{3u<8R35|>@LZiBb-*cB3QgT>1rjftO z(CFm+j5^FnoHW9sa-VT1L;i3VJE%icxsg4LMIVk(G(t4F8ZBP;H?=iFF>G7vv~Rha zBe+HgYepj=zx#td%L>$dDsISLUb9UzFpXvr3XMdI35{e{G!ktlG?Ez_%}a^hnDwjW z%&8hBhM#wvqr0$hH8fhQgwZ$HWKqHfY2qzjv~-!6M&lmS{~!1Nlvz%?Oe#9>{SDIM zQsEP;d`Kh5@4traqV)-n3YKn7T6E0Y;;sW}G_`ca*U%_*=rEU6wEgo&`#0PnjV{;m zt^kcLdP&U+()P_-Kb{sdH7^wacEReMQGH7FuwRuzdno0GL2fO42|wQqH&LABu*M(QS%N|pytgA zK+W|jp!K|>5iq$L`G!QLwniw1ZA%p^`)=SkXmpa*kPAERWy24))|^vVYL|&sa zyqWF%wx>7w;eCF1`ZcuufF>@j1%VpkzcI zBjxK;N`Em(k0^`=Es%xT`;}1GD>{m>S7yat(N%=KGQ-~QDX|-~-k}N4oNDj4@Shb1 z_~v-D0`{g?!YBcoEZ;@gAYB>4|MiWm%-$jw!$tryD2$x0)K|u+_kmD}(v8Iy4bq8qEn20ugw?&r zG}+=*4EAnT5%%sOELz0hnD<60X753jVQ&sf2{RHWd$Gt5jSk|BAn^28kHA@{9^$SH zpyuEaSh1^OFEF|GO0}=1w!J8ZZA(pQlW)yTZZE?8Lu>5nGLYZC#I7zsS+4e`AxZS6 zG)eTP*GcrIkbisAS4u|Y@q}!z(qHJiNfbtdPIhJXx~@>|6&*#`E3;y+=qkcqnPG3X zl-P|~Uzm1-%&GQ%37?$(!KqEn=%ZQzdUqwvH=;i+6Ghk{Jw46;b=7Rl-dE9?bY(4H zmcibBD__pNMmD}#c|5W%+52nT7bn>3WOBaNf^4j@wnfA@vbVTL-PYyF(yOI*ZCp>= zpS!kyd^Fkn*;My@ZCc;=(T%4?Y5V?H@=eLd?fpr~*w%N;#PZ`db9?PB^Gpp~!0eR> zm8en5s71PUSc_I^J7H|t+NvdQxx?PQD#G4FgcFY&7k{f=lG%G)W!PJj@`V{yMfPG* zb3Px)A5vpuFR&+j6&8EpIIz=x#a>`??cH4BMrzxOV%WCShANqA&gb?b%>RF5$E-m9 zf;4)ifKSlJS88wSpG0rUoJ4PmNuoFP`?ojQzgF`o#$Khr(2F7|j0XLXo!Oh0P>j8z zqX>ItR_qmBMc6Ad?9HDNyD{rM<;Om1OCu@kj5*kd5oFnd=iBb z?eFd-OJMI-RzsSraoC!_b&O8joM%x~B__JYji}~(#`XrauboVyuf0s7uf0y9uetu) z*IXzWQ35eCE4|4e<)kq3*CrQpyELJ2TXZAgw#8K0nQK>)NUfr{i7u+7us_(p}a(n2QMV=MN;cnkoKHo&!*U0U#_YAqc;!cLIwP^jURauLb zpzXg+yc|%ByIqBnv90gh2cERp!`=3!FmgKj1#`O|p%OJp4YX*I+G^1%#S;Dv`SSV2 z*1~Z6wu*53G2yyJ2bZlGSe&{2TxGc3y@#U?GZH7av8cI32)r4J_qQ^)fzPd5K3;3Y zZdd_MZmPHqOs?C~>5ZxFHi}`}Qs0WZZe7XUMp$!F7O1(>4%A#CtUrm@Y-C=hQD;J- zk!UfYk<5xlqRoUxGDD+oDX|-~eu$hoRim%rTN7_Mz4KTMjY5<#`UaaUTSV9(`S0XK z8=RkMROPUv?$W{%*PzkIuZw0~B`qqqJhY(&Y4px(U)*+DU$BGcmFA?y=hp#oFG(X) z@a!4T=(y!iw=J}NXr72wk)+WOyPWf&(Yu$kH+j&Z20NXghX&iehOx*gye zHK#Cg+Nnzg43R^ywTK#}5G|UdNm{f@>5foKx{WSkTwe$pWmFLwWg+aE*#Fai`8=3L z*;R%{a}GJ`Fe7o&2#cCefdKhquuLPM=EGFL-76K17~bGdyPSJtXo{y+>>{$Wr(&>s zOyX%4-|?=i*;6rT&Sqv$)9|pJ$JVW>tr3c0+fsFMY#Y3eAK)U)UWoRS4sg%23e!AY z)B7f`N{@ofn+b%%8_`6<8<`bvL?a1rWQI3WQern|{Q^02a$VD3pTj+z9xkf$Y$3c^ z{7=}lO0gjdNsJ8}i2K?S|p-W?*1M zd3aN^oayIN@@7Wls#owPFpd7^R@(kt$9*Rw$eZ;KvQ&gOJ6}b)m7?tj_!jUl!@UWi zWNcfbWxtAbj&N^AQ5eN(_=tHkfl!GWrHNWJNsF~;mGY){(rt9BZRfeAAiOE0BE0b= z+}Yy9)aSQ~GH=SN3~zQhIO#AWaqnu{60&1W0Z1q|j5P;+S=c=e6q4KTUGPyabP zQ`;L9!?vY1g}$`g%!eO@HLqO&c49a2u-}P5&D++873MWNy9m>0E}_s!w3yIHW zW zW+YA;VNr933XuQ)V7DCuHLqO&zO39@{6YgJSEC1^dsAB@6vMWqn)bTTd^^_&Va**X zK;`cJ^Q`_*m6+%k8lwD5UhLfItO06YOP54ni%FudbxxwMmHoG`t)^r|369I>PLd zgi!)ES*#*V&($sFMcZDSxxHhplkP>0*aWz3sPHxJGP$~ZN9K(k$n7}e-^<%*eZ5}s zIpFr3dFkTrk=qHs>o0`cnV&2jx`VdQekOR;0do8NuYptHcAi|L50;_r3*PJ7w<34@ zIwfOU-#VuW-6FZ$wJegIO358Xn z0fkjED^`gn6jsR$t8S#kZs?Vma^~#pcFRu~ybFKdX#Y3oiSuC9VDvNUqc2{HA1y^Q1b{Zj)8Z zk1u`-t9~pwvtuW1KmX7M(_XUb)$rm~U{!A8vA1Pu`*p8M9W`*PUQjZ&Z8a%p?R}@Y zRc|SboDMNp!iXt-bkZqNqm)UDCMl;Dt69C!jXA65Wro-nxKl$q6RRB5KsJ3^t6XfdIY%!)>$&4flWL!-|ru^Y4g zubeqmqYvTIvAS(mjF}6K>@)Mcqi4vICA|pKdp67S@W`@Eqr25J>wZnGGXxslxicUx znzZoR)FEqE(&*r^Y2~3&$1|gHKqKpteZAsIqbxy@Wh;>`?Mtn{v5U61TyQPFi!_R! ztNT!c)<1UJ?dC<>ABsD1t18#%4JBjSILmag*UoZ{zET)@9Tdkj`a`Hh=__+uG)YcI zP1Gt)B^+{T(5>UM^FX87Dng?Lgl%7X-1$7b5YuS6%Fw79?HV%@CylVkf1$BY8UWj~ z|BBgxCy)Q8x@ zr$PD~AlIxH)2Lves*z|hp^?mrMxxDxMlwSq_mtR;S?@)=L9?qGy$Yv$Qa4PPHU}D& zSHgTF`qQF>4N|%={;!{SGmYL(&#e2_d}IVPx_7L2M`+aWx_kN_q|wLXrng&Zz3Ugh zHBCs1M}6K7xk(zeDD^7@8b#E~^=3D1-)&{1>f1@9Ch1}}L!*zwDwXu6?XRYtc*V#y z`b){!HqL&prqLypp^-o33p1*UG{U0h_ZyIV!%l+$HNW40JqIZo0h6oIgD@9OUv#wW$?|)(M#%$R?ULqS^%9Xy^i|h@Ejoku!pU2lM z2YYj8dAjKu*}G_INI2}ReDcMYJ+%F5-#Y!bkiC<-weA9YM~u%_p*(HBsN>8PHMzaM zl#FeCkDR@J;U#XbABBCvxD#G5^ zgf*A;DARRy0cP(9m0@pKLS`LiBu@5Xk>793jwOM-tFl25s5zDdu05&P3rw!P9=lGY z_8^F2*tXP)i?L^p^Fa_{%`Y?{|Ed{#%nqm=OZo&g`|*G7T+jX=JJ;}kJ6A9zBeE<` zwBZ#?WbmQctn`i+oTW<_SvbA-$?L*}rQ*o|2~Th5#+^Q-Wcud~ki zF=rNJo~wjW0ybGzh_FF&%C9)saiBiOSNc~^d+2i{hCyc zT+~_*ne(a$nF|vp{F*b}eoTHQb8(d+^9~PZ9cCm>GGkG5MM6aAs}wlh0^}d^VHd=K z(avqf5iKyeGC%k^H??I(F>G7vz=p@qPV%7`VJh(f9!5v=8dz;@MiN+ zXB}oFPTpWqbD9#!uT!yS&4HT7l7La|6mNjZ^(OSu!qoN##jtHDmv8wVp5cQa!kQB* zz;n3N8AOAiL7Fh1S7pgB%$qfY!W+>3|kZ(itsUCI7R|x^DL??|S$q z8@y?*BD^sZuDa3m&d~OGm^U3%hBxtNNGqC=IC+Cb&3FUU+!_tk++4|`+Z1nr$@Qkd z#ign34T@pgQs>w0*>{e6gRth{5y;-VHG|z;2}D(5qDyzc?(7?3J7Lw*M?51S$Khue>=Wh;D4JBN@}r6=8tfK^@lC2VR$megA6bvcTx z8rgK@W>|H}@#Vq;wEejYa~H0{QQXM(p|Hy5QJpwg)i2IB#GhMrnv$_?tCqUf{bRXR z7buL}u6o9-x<;r(jnWM*(noT%NDuqDWzpS#J-GkT({8Y8n2NA!7GcmCXdt3;pIf?^1{Zgy~CfBMg`&Xv6RVapSOF0!7(f$Ir z3SnMD_vOr~8a)WF_`2@t$782JqlZcueS=LFZxJ>~ajkjLcK>D?o$Z)K7t-`}fwiQI zN0tFup;5Wlp^=3!Zr=z0QlUASM&nh6Mvk;E%t)Lx!Xp2#mz~)F zZqI}NeA$@|Ab+Bko!$qQtY;QKhJeY{XmyRwsjU%;VcSx3pKW}8iED(g=AaJ9pG%~J zy7R35G}oRHRemb@1U(+D_O)V3^tD|{^tB#I^tDg__O z*dTq_z>5}?rZi4;JlT~+XUvn(3~ujU`Rc?4ay4?-C8)*AF4_<6;%H94#$=KF+ z3Fp6S61dxryLqODer0aE5h_umlwFG^sfZS>(nCV~`rb9OZg+v(FI0rv?+AN8t{D2n zL(km)tTNoLM)|^wdL*~8s5$Ti=3pN=WJ4s7KY+$gbN~YuDsBUl>vmL$ZmI1yiecMQ ztB(zDa)rB%u=diOf(aNR5mnAw(yJ;j@tSo@OMR`GuUoXLk!UfYk<5xlqRoUxGDD-h zDX|-RIF5G1^$|CcJPJ?f9dG~e{X}R~N(u9g=ub<$2pc4aFZ^FerDGZ;{>h>nZ|Q4+ zMui*B8VHT@uJgP)f;4iu+PXM2n*J=^K7Z08%gX25PmxB=qpVe+kuh%jEoijha@`?I zNTUZio<1?s`pp9i<*H2Euf0BPadWPbbK<{^Gs%AKoI6}2Hwq)S>jsv>5SfQii5jK+ zS~N*zwP=-g6AlV~QQ+0ytkCG7iqPm7;h2dJzK1=_&NMouGBj#M#m9`qNh2(3F5Lkg z*;|g-c@H4(LQEszkSB^pz~pLF)~#1+YlLFhY80N~!@?M@5yF}yO&~uOXG0_qRf&nL z0xCnKLCTRkD~pcQF{``?#o#0wP*^3iVwGq@VU^6Vs!~eq#;mU+XHGrvd>G!Y;TA*8 zu?euMt`g>@qdzTX5jIGMn!IRbC1zD_|E#*3C1!7jRZHya6o*w0SD)N4imWO(q{5%g zw7!3>lRaRS|LSIOk!00^W%;_ps<;PtCLX5kuU*}Not@)t8|tyesGCNpU-E3RhLwR zRo4lp`|r(|{YW-uRlLfuYFNXpI?PC%?#IF+e}f#;2&j1w0JzvIKpbfTldDnGpT4QB z5sG2kG$S_6iM$StPO>V|+&O}+H77dC^x$>(Bm)zr0ih5@w22T!WVYEJ*EQdwdAoZNhi?%ou6UA$3R^5V@ zJ!2tCn@^`7pQnyrY-{$;V@Q;3+sxM?idQMWA`nHl=y%Q&BucxOpK~C}Qjgr8M`-(L z=K>!sAW;Stdo>fH4DP(5R~6cRd%{r9R$P>tl#Fd_%+4^Q$OA4)0ELlLzx9-<>QZMy zC2Ev{wP=zCY0)ZuChQSbCzmPK8KV495uzj#w!U?v(zV5IOcaM@3PY4hOS0-PBXJsj zu&DWkCL;3XDxl`tGjM}N@dlV&Z+;x=m)hQ-7`837`A5#^n|$~|SaTEySL?8gz(CDt1iXG(u?m=6 ztIAFbO>L`C4BM945i|989JdN#%}IG6e+wadRV7e!6xZLuh1Kl-EKH-RghC_HVnQRC z6^%rj35{fiMzd04H)j1ZIdiH;3E_>?7wI@~`Z#E`LJ6a9u*uR$gbmV?lDuf$U6@9b zD!Sb#N4k7#*RC@(s_SuS$vD!eaB*oOGzy7+xegjV*Vlau=gNmo$3bdr1vwlxC9KGH7(MP03DexkgJU8QaF$GpT04W3JIE3L~fgtz;T) zAylG9X}cCp(s3=)wXI4nx^$Z#+@8O}5gIj95gN56^fQzRuMy_LG-|IhG`d^CMTZ%Q zlSWw7oMHe*U;1CfodtB%OxW*>Ey4Rjfh`m$#fm$0k#2Fv#6`m!;N{fnNWBmQY5_L zEWHs)65eozH#_2EF;?SYUO5-JQ+Ll^$fM?)u0dnqO@s`iGqAx{P=rlN_;9sp7cw$$ z){akaSROI32E1|iPwfqFPJX|WaXfkR`#^&Z@aBs5@^0{^OU*J}_mejpPbN!Jj{H~` zwDTFfc@?mr=$sG!M^YYpm<`@^YF#Z~Mf!c+{1xw6Rd04tG0xd2*1~fAiR#S(3ZtfJ zcQbDy31!r*T-T#Td9O!@GI&CIL-|1SjhCLO;LQjP;f;;(^Q*%be@*|7c{5pKc=Kyq zdILrjPTpWr_c40l$4m97pRiMNK;6fffF3=iH^8`hGr8!fg!Tr_aL!bTmgAe=R=q)3 z{jd((-T>w6vP{a$RqCo7pP6}+GDP!6q)2$fS$ZRqB)s7aZ_>rbVywojv>4=B^X7)# zW?Zvr@p>D)$tJ_h8*>@?up{zIJYt@@5D#ke*73WqqKU2LqPhr%yc{KCp8ljAul}CCcZ}jL;dS6a&7%=Zk zN3Vk^;LSh{;mrub60L@8yb$Wjys>EvZ!*%dFrsks29vs%*#PN(rF1s{yIcj-?Y03+ z?vviIAII@692a5|+#58*Ia6=mrulP6-EBiycQ6E$m#d=L`qQ0Lc=%3Tv#+x-jeZe| z&5y{K(1^3tNaRdt#2FeTdLIvqu^Q9TVvu&dMptrYtCcT!G&FLRVf9D!ukDfu)Bhnd zWnh23(t~Mq!83!Q;j(5^pwZDSA^V}xr)+O7O(cyh*?M_GqsfoTIck#@<#OfSu!l5S z`6i|+G@5(4Y78_wVwpH#<_G^HtNZ-D4UJkF?&kNU-v`vMx3rC_(PJvcIXSIIb)5HH z)#wd{S%aQ1jeZl#s9ABzsY8q6sz--1gK&U#e3Px+6=)QsAv9V<*roS^rM(uUV;Zf{ z7#bC(k}#rh(g>5fQ`*30>|`9%NQ<&(BZ2jkw-LK-z_@OHjB5fDdh>&3IA`kI^DMLP zsTv`yyXp&!IK7HKr%k7{quKh~n|;EoMtkWVBp?456}8TF zKEN;Y%I;%Q6bd81O|mnYvlB|0dB2e|t1M*}Jx9pQ88Umu$6~C;!n|^NnLQT1eqQMJ zD9Bt?hS35x*s_SQNlDyUZJOfAWd77AgCXYEkub>oa;)cM$Xv-dJJV#6`F6KNi6Qgz zyY^F%`L*}BF1tzQ8n>Htgv^Hyukt@Yzwh7jagiA$bGaJx4?<>pmWrz&^NE`8@3mEB zcJKS|`rbIyaN~t4vnPd7(-;Sn*_%*C%}N11T9gWUbSTFOJM>vl^?2^&komNRkogi} zwja-LC;6C$$$VX7$XuJ6j}e8F%$U^O38f)B1_SE80R`;dRLTsDtIYmwM<=w*Xoiqk zn9<%hZ<+_H%n0kQPXTqOGJvY;^o3};YBOD3vj=iAjT#dQjYP(TMx3QaB4-&eG#nbW zlwtG@HrP^#uu1vq;>J47jl4{wDyiHI_hY`_henecA1?rnE)R1G^&@r zOHXLj#LU@yp%HM`2dNP-t{Sa#v`%P^ z&H;(8s^Nx7ODt#?sg7#?sfu z#?sen{@d65sTk1$JKxiky~(6>p)l$<-J7{RoKUzex{+|3vvgZ@B;ht^xIHR97GpI| z;gv%L)!~YL+WG}O?#~zox2OFRcCk$rVUyCgf!Z{`0?h3;E!_;)Kfd|_w^J*d|DGgQ zla{$>n?`Q03cb1oZg0%c$PaGkPgVNYc5?fS_n2L9dv|2!)o^=r`T3Dk$nE)edh~?b zO)uoT&o?ucv>ax{a`I6A4tm$4Zx?quKh?eI~Kb5OvLd zF32>RNGLQC850_DmKuqi35_^IqiON67^`t1ubhiK`G3V8c4yxnTe$#ev{;7GH`rhc z6=Axrv0QE1y24DOL1Au&&^P1KuOVI5WWRn58r5kwbK-Q;DAC}G3!%}paw9WCqem~t zf89nJMUQqr2aRgKSeoPz{l06~r-vq!M&8LUH-<*VlUAzgN58)?@ooK%sz&3f80X~d z+Lg5C8&#u46h=*R-(woBAe2$FvPzE@WwRa~O3rm|hK$#b`kvpJ7#ii(5E>OGbPRb~ zq*N(|X;eaEXml&o&43YwlSY`7=duGBs^{crPjei@pEIO4_;Fml@#)t#p}j#foKv&W zzeirN{LuBus%%@KYr(*6fip*P-nCnk}uABv4B4_&*gI=KS6ZrS`_jZUhr3#l0A z^*!%yKEJoBuFENmn)dj@bX`p-qjal?9xciiJ<=ZSS2siMMP+hcJCF#vrqd9*W+1fm zJU7Vt$-s0qY7AYI(6TV1aMBf%b=jlM^sdkVhHBrWuP_BNT*qE$d<6F5$GPrEdx3Ga zw_AaB32iT$;hd?Tb?5ecrrL`zR+fv)1=tHzpWh6_36)dnGqPx83FgfMLg9@_k?@AI z^hP8}c*7aqJdTgWSdH&_Jg*WHceoqf?hToayfHxnmeA)$X znp|sfdm?#rdQ$s5@Wx~4vaj&w$(i9LI;-AnrDB}35%qI+!FQ@RyC{s>c3htaCsgc& zGHO;1=+UB_(xXGkS2d%d$&(k}6E3*Gn_?Qmo3ezHdh~cQKO!0Prh>-s#+{ah5rvaC zm|WAZBE2Ywc>`2$yrbt216fo(g?_TSQpBHPMDAG=b{9As2Duq84oktAOe)18Z<3c+X$!Ygc3GYc8?$wfC{~ zwJiVkwYOA^=xgFgQ1&L1@|nU&ccC)O?d0t>w?#J+ZgZAyi;g7R<_x!$_*jh9n1L39 z%DK4A<~Jo@vQO$cvE}ZtL2%nmhSeX@zqSb?Y*M~VQvW)RQGErBX!0os7Dz1myfqlM~+(K?IoH)j{JUQ&@O8bTM`y?xx{hB~- zUn<|r6>g_2aj#}2`hBS+qyFony8VQTabDlle+8h zz@4Xt&^;^c0-_dW7Z8CB1Ekx)xVrs)SFwb48_jUe)PJ5kCcRMIMp$J=5^oGX_^zwdIZ-cuO0wXR`SeFciBS^1_%i<0z#F6vOa5?<^z zE?138e_&Nl4PjMZ!qpcpxu2YygjqF6V_4Oh7L5^wlU10^PhUL!;vJ4XO`y7K$@VmX zx-BMf>U`n zQrGOMK1`!0ghC^cF`*G>sgcN;(1mD9c3J-m8V%488U^6TT@QU( zGc_^OXoSYlD1hpP5vz&3!K8eVbs$6ayF_eH6Vdr@{$fuP7*}tUnLY{a4VvMcn)G=; z_j;*%gRpK-6UhEQ)A~GiErIO8@U_XL!>y zJ{Ds&2Jp&h-ki3-7?QDn&n5lg%?KG*rJ;Xq&qbJ;Hb8CKlYz_|_mP3PT3pPIJPR=&VKM_h76-K zu))?)gz2)_5w&S`hca)xPiHce`W6rjZ{8p1`}PERa6as4^SR{B=N>gu!J7%T>_y>C z+rnQCr`PC2vNA-#Y%BWeXq(_TVPmc~|2jQy7&S^HC`2lbCXb5i(68fLcpqRG0 zFmEC>hBvFC=#Obc;p7b_<=N^0hUy#NnKy{4FS0%iZ-9rkN^gL1-TbT@R578wK{K2) zW%;r{=WBQq#Tu=91{1&5-ElSbxwNCU zm6InCPS`(IcvvCn*1qs&mkgsbu)+3LgiXrmw3%5i**TnfQ_Gl{?h%~48Qw$%MP7zC z>B2)32az|KFPC+M()_DFgWTXv_W8YrZzOM~KgiJo-mIVXq$|8xef(@?c=Nsd`Q7kl zSE+gH;LW@{hBMroW>k!GHUd&*i{#!|DU6zazskJvCzMgM(q4}irKcVp%4x#%ugfle zH~2feIj14Kxk7kv^Va&+LjN8ro+y!WLt|g^CNgto14a~1`)Qa|&7eCU#xZ>QN1B0X zT+O&q#5bYMKr@_kk*-zpSImqJtkJsD1o*Z3)C=vHMX@MW76#hhAgbPz7K;6}$)(j* z*=;2ACX`TkBT^*1;ViuoNfO?0_9bsN#K&T+#@)Pf+VDhQz7`$2ZxAzlxb9Q;{-aXXq%^oVoIak}y z`gi%PZf~wo7`63%!@RjmD5GZOz8)>gJ3Ts-kzF$z7ABt-eYo&9cr#8zcr%$W)wkX+ zSN;CYyqTpjy!qHUvjHOtr|k_Ub+=dn)lWD-!ijaDdOy)gSOv^bue~_j0mjuTB__eG zLNlB*^`q6x^>5VuG=x`X!ObYN365gxK)3lpRNgRcQliGGYxcrurqLrpp^?a#(1^3t zNaRdt#2FerjgQ4xjURaBG>uN%Q{?(HKK-y>(CD)aqi?XmmRy8Q%99Oh)5ecs8g1B_ z+0eVY-&tsMG^A$;H0qK6p6@);sNufRccD?QD38a`C^B6^T#s?jAX#yL5cCpU5VqH1)F!l>!J+_`X?;4Yzz znw5Kcv?#Ci=ujH(%53;qcxC@l-@ibk<{CnyHiWb5*Z4c4_b;YV2aTaoK3Wz=6iymp zQtcJ&`V>&TD}!GC709Bxvu%i0T`DyK##N(+tIY|$aY8ekGxc#-fp%}zvjzz3&b9$d zv;VbR#?cQ@w>7$QQC+h>V?ra&QX`Qwp%G_j^dUYLV>LQ>*2Q>O4!{{4qu#FL6lk)q!+O*f>nMT2hjfSj&-)=&q;ZxU6gGL`aM_+(OOM*_F zhekD;Ha`oE%HOUQzMeFCSAEueXf*j&i}Vrn`y;7B2iZuYKCS(yL8GQ?Q(B(QcY(j$EsJ&Dn9GT>vUrB^>gBZG#} zC?#QW$EA-RUw$%;QfUm03e&PMqHxj(lk((I0K?I&ThN_6feahYScvz|VrzsS*N>4J z0pqHXXOKriYlLPvXKHdvuT<|;jS$xD;{nyjPiO;8&yo?UlF>(1?lMlt#!5jnE9|Oby(X zdo$MvVRef<6W4x#az8hUAyy>@vI~86=!LcNTINb zGpwo_AB(XX>+s5HRz=#!t{+CPsqF@<>dCO$I{Mc(MubgDmicPa4oqWKC0$`OH1MzV z306%yAJ!gL1-^TD7gn{M7q}Z%{kPp30;{$(D!yVJS@pH$&CReXN5I0tu&UJ9IbC5@ zvYD9%z^V<_+Ph&@63@z^+^URJjB~D@*Ke_cTjfq+)HcmUW|b$QjGC34dZc%E>d~RB zBwYL{^w;P^A7NFfhOjD}uw~y5e-8S6XI5>~7*_QPHX1OZaIy-MujvV;39q)nDxiAg zbO%-e)gveN?oQy;3DPQHT&=Pt&z{g$p&8DZNY zZPAT{+nlA_q9X~nIm7J^@v#`Iu`jQj=5~ZVWw{PhCm6cI?fx>17O=slh_Ffd{zz?F z?pe(3VsDIwYNtQ^f!mE;%=O{+$cB}z3&?FH`?(Ep+spcKCfwfs{(=|WK5%2oez+Zz zd+2JoT{dU&SApcVtx%UPaC>iHfhTaA_9MM|t6R)ARE+cbe!69E)^F+-vonQJQ_BnH zb}vF1rSB2x(V~pfBYlsEFx}C-gF8ijfZK`RN`%|V361kNR?YeQD|0)I#&CP;Yx0vu z6i#kqQuj0pP~FRV0JnkaerP1Nn85XyrQ5)`y1g|b!QDnPoHMm=*sfdLZG?4CngP|j zwAd?kfa>;?eMqHMN_VzqZ_H*I4Iva7iHr%2I7^L0&V)vsq0#X8Sd7&;nO9EJ=#c%v zmfDkRUG5Bxrphq-1{-YmMcAaYFRnIi`dp?_=ko4`Jol5OTuZvtKYg=2G^%CJb%AO0 zXWt5FRBzUdka<&IAp2IZ?q%dl_>@U-32BD0am05bUC}DbZD8(zd8-{$Eu_Nl{duUWv zLuh0s-2EbWXHfJPrcqUmq0x?V?goq~oHW9u?p0Jk^)_AhDk`Av3lP9dIXj9SPhea% z`aU8@LT@6`4ChRFO<3LegL*a*VRh%5?!$^=D-7!n1Kk+ftA*B^8pP6@>i;i$Q;&ap zQy>*1>L_l+mHow}OrkI<{m>m$S52bQNJQXV|+uJ{Ds&Zs3)p9anxM z?os=cjpd__J37JMa2ZAm*kF@kdX{Xo+O*H}nY}}&xEq=*o8$(2M=j`D0QSB~{?5FR zHi9?H_{@jB5A0cc!d^d9?uxM2axTXO*n2up;qS2bc=z$iVDF7?7aGFe!gU_{z}^8q z4U|6WMsNxh+l#P#O+ge}VY)q9 zMA`j>9vg6+xIa`~v+EWzjjj_4jYP(TMx3QaB4`DT?`v4D z{3|;`qt`O5u2TBfc2|T=N~dVGX{{GCjY6)w8wOn&nH?JW?z`s>jZUq2ydD}I_)>Wq zH1aDQWQ9hZR~5Y+N*c|{nDG`gIyI?Mj-&MZmltO(9Yq@5EOWa$G>S^{wH-97f1%0% zuF*Cs#yL49{)LNMfpA_ zv_@!#bEZmXEY{_tdYp)`?#X80_T{)cjJ>r0h*gP!&b|P3?*f_gnP+(^vuX>Wuu3FQ zSjAadB~mD?;tZ>H#K&T+#t2?H&8pq@TouY4%f7q=tcsLjwRQBb%}az$%E7EzSi>Wi zF{=jW$zrfCewPncx^io&Sv?esaYaT-l1 zqh`gXM~gCEj}GM|;n%wvJTvWo4XaLT2&>K!CL7voh!seceqsut4C<_a845_ zUyl;aP<>4wofG!)zfxK2Twbwst_-nsuEw!+t}6d_t~*qWsIoZSBD;@Cxldu_Hz1hF z{G3q8Ec%U*nX{Bx^c*2GXUH5ci?JGC^U7&5AFwO7)E{Ejv}c=08Ac1(U`sB-CM8`D zwQ2holQ%y8V+Uq2OxygZ7-YWh*Vu8K9@v^Qj~llpD|WIo?8c?HOvvtaLZka>8D z5w9V0m->UdLguhm(bq?k%;mZcE(MvJwJop?GS9AVDAQNn)0|AjIIr))gFTA=Q1>*a zQW!N|H=D^kolr*2%Kt!%GFu;YRU!$mTe(vXYnCoxQ$=S*Q3y7KSKF9r%8D;TV1n#mQt1*`F$f4 zR*8%Wt2j%mM9zd&oMF}X_*jh9_?uTwv+9uj(9Jh{YaH~4Rexj{eS;0QgCcBFvhP)! z=CzzzRV9Mf!!Calv#P7l8(1}9XyQ|_D*NBI{b1GU-ERuRs{K)}yVjCb9$9~UhE>BW zM@@!Ren0z-f>kLye=7*9I?oA=f>qzbI?U!))udvalXK@JrMR zS@|DmQ5x!_4rMZ7;tlso4Z9ixjizY`jb;*dPVF8(YxjGm(HxDTQ5r&wD4aCHq!J#Zx%{d zBh7(!(5R#gqi?Xmc3p%`N>f8t)@i1$WEwq8m(}3m)vXdVS`_&BJ~VQF(l6U$(x~b5 z=G~x?BiUk4Xyn!=q#ZPRGRNgNG)jNG&N^tcct&DxXyozhT`p)exNf2tXcX*r@hR8n zH5KEWoN-m2-{Ts+qcCc^`8(6-Gog%{l`nd)P`7caQCMBkz9G!2u7tuWkw9S; zXK9s4p|FZGtm+*fi?JGq@ycmd?Y2jHpA4vwt1YY=DZ}V0Y_LU$uu1W2qBia0YGzgG zwpk6;i~Ls$Rt>6K@G`6#Z~W8;R^1)G*&kNDF+9uwtJZmYriE4CL)Ry*K=y2W+Uf+X zD$>$+Z3J00`%`rfSe1L_f61%S?^D#Wl$gtO!v4pLiVm@s_Hc#qk@Waka|0Ix3;9LNlB*m2t+L5!@<-bywJc zyFdND5)i}Q_XgB`Ypm%Ab;{Y_W zr0CNU8kIY6Ejcv0T=?6OHKfsztS?hRqfLD;K7vLq+BTm8jSN!_8KKeN=96+kqx)4x zj^`Tvred6v6FFe+D6UbWaJ5pMk1~x6gfdFcBkR$kq}L-ok4!js)SxbJt#if1(z(jV(z!Or(z#q({L{H6 zQ8A**;)0v(J|<;4g^}O1>zT~U35Cp}-w2sGOPNK_5i)az%q!w!F;?SxUOBzYcdeiE z7gt(A<_$887O=r~M}$qvwD)S$j&5Kw5C2KYd6}m!lsJmPaeD^@g%zhllhol3>Tuf-0 z(G2HItzI5o=!?3iiLk0`5DwUY>N!n%O?VVTtV#@Y{D!FR`rGWx9&AMq31?P?6AG(D z0)nsW=G(^PuT7J*QpriTovuPK9xh=)4We%)Yf!} zS@n!iM$O6#JzA76dZb6%YIzt&yJ!Eo@6=;hHC97dHHon8jn=P9FOFeW&CnQDeXQYO zz=*=hDom31!r*WYD8U$)!h!vKpA= zRm#zaAHk~i8p5irgsBs6ORQ9W!K~V)F{~;`&Buts$tp}f9PUQ_WIwC|sxM?@$8SLO zVC4j?0@fKNtpdi?D(`~V651-(X8s07u@{%<=J+$rstDHT-t3wr`-TO6EiYJ_lruZj zRat!p^X3Vm@J6Iac*9wGBa$S%;S6tL;$tyZ;}>2z&71A^qya;29ZKFD-h7i`bOtuq z5{a-$d3sB2+RvTLo4Zdu47pS6?GA5zlYU+XZ#t&+KMik!rqj!zX#VqI8}7oJ(pF)qQQ%;Z1{%8AiaH_jy)2F#p|-GLzuV3*RGixi@dA80Y`TMfbiojeGN% z!l`DDH<;9&_W&Lk6l6@=jNMcP)ZGmNY;i_<1B|OTE&7Efv^QvmbEdXd^2qpA z-N!>%cisc2Zg1G@yMels@*fgqV{3NvZl+Pn#Mz`qB4a`$&Qc?hGocY@Xp}BK7GpJf z&|;8wO`~o0{N+3K?{~K;G|Dc+>W}a{ZxJ>rx$~=k-C-}&=uL@ihN~4T^@TO54GBLp6dFCceX{^`S)QR>YiQ)SQ_v3@<@uE9E9Pfi z^L`mLs(3ssnrrlnig8Yk*XM&LxJF4!s+G#!IwLenO(>&gC5;{}iiaK@ibttzhS}eb zExY^d0W|W`5E^+CCaSx0>ganT$ti?9?HuyEhTo z$-S%CsRPDUBOm__39S*D;hd>&O}1INMhNT9djPYstATfMs00+fjt-T8xi>FoVy6zMO2&5TfV$890cUrWRsrK`)$A6V6WS^?!#PvS8jo7WtwLD0 zaRSz7pJ1ok_kH|dF4uZfXe_;{PAt7?Z7jX1_P@R97ZoGwDDI+?{l%mt3sw^vc#zra zPAKdZ9Yxs7S=uYQim;b6?9CbHd$bAAsI%OWP`1~2-A(m z$JM5lILz!Ve?FVxVWF|ZVDF%I2gbtQ3%lA6fW0-_S1bm5A7&eP4EDB}wk;*>{dg%$ zX;?Zubm(~4`^f&^>yaK>BUF+%eVDr0J!}&bUyulUlM@Ct+0?1*%E!#!G#bO+ zx#zMOFrsj>7nAaijsS-FisM{2vlmg_Lu9rh1;SV3AZ^*w?#)1ZgYm)%{%xaQn*Rqif)H%c^4v!tL#g z7TDo-i#82!gpk`+K3p@w;jwd4FNE9oW^7#vx39c$e~$UKj>oRU?Uru2dULm1Q!&o# z+qa6T3wJw!!l-G*d(3Scp^Tc9v3j&9bM)v?vS!b2NT2Ivqo5Oa;C4<8;dWlaM$6nY zo?QNjxm{RexV_FJy8$B#C$}-F+cE=nr(1x!{axURB;CaRE-Z%QNS?KfW+?C4F)8!QsjISnB=cqkq3}keNO;3pdLxn~yx|OQR>j9+ ztj4vxa@rp42K#;QcH#5G8^N1U8AfMdgYBLOo0K{2)utsr!Mv&1GrJ*6lYL|1O^Q-| z2f~|L*ZW?9H>JxM^1++=ne*<1H&42+UI%a1x-|BMABPKutb;c_mL%y9Z;m_)euVk8 z)3uC&H|LUHSjN4nPsKQUv%So-`P>@|g;CQ+tuter*osg_&B_2hT9h$*bSTMsWjE~K z5z;1Q!`tx2O+$F&LFh3usOqqd51BWf8pE6EJ+d1xqHyvClk|Qdd|n-Uv_SQO5qkm^ zsGj&{rzwFO8%b|~arI_p`~3;+4VvMcsb+Uq)o0#pV5>xT^A>CL0DLflJ$wVis>DFY zi9npJqOB$#X$zjLMt7fNR_!AcR*3`(t2j%mL<)sfoMF|W_*jh9c$!yEZ&l30lzFF} zXb7vKWms(;{cC$J!X{Y>rb#1URkvodD#M;@Q>yKQRrPy3uL7%X&u)JY^Sws>`T?tA%D#@`R^6gv zoO5-qOX6ePswWgiZF}BgR=p;aQM2+!k913<9v#Z4{n-r*o+$p=-`<2(<1~a-QwUe2 zZqa7Ui3iN8SsKGCPg)j66i!xQQg`+RsD5FO?P&u0GU?cdc!7Q^rB%SVTGg-dp@g;y z&2Y|?HE+aIuHf?+h z^LwUzm7+Q{N|OBx*C?EdaZb*;5~bd9jkZ!4HQn}sX|#(_M$O7@JzA8bdZdqaDme^g zT`~<_JoE-M%A+APDo9xPgKyJb>+Um+if9atve2?HqHxj(lk(F%0Sy1p{e5|h)5(ND zhU)Df?B*@}xZGQ*5iqVAtxSD5p*2D?oHOO&Uwt>n=5)<+7(RWwF%vTTKB?CZGMAX#w<%kp`O{3l)w3_TDU6zq zyyuEN&4Pq7YF5m8v?%rU=ul1&ZoT*;S5VdKkok;;kohvhSqPoYtGYnK$^pF+l@eErrLSdCipszeZ+QHG6ELC9rB~<1C3_mDerT`mm>Ep5D)3mFKwOQLt)$ zrU#cWzqmPfK3J7GN6V_*sw`BDbFO~X>sygqm4m{l?b_D=!K&PZGHO=x=+UAS*P}z3 zO}PI`(#AhBT!U5fG=x=)3G*F$u|CzDJItzJjbYV<)j13pQ8-zJN!^D&f%0`Zfh?-K zzZuccsnRN7T&?o!G&P~EVyl3k_Ym6~&qF^md{@tVAgq4Ljcp=s|Ib(5T8kVHcaP z2%D55FVv>ZUBfgg_A!USE%L>DXyjLRo&_2$NgcEj8cjNUEdw;_-Kx$!XcSb+c4rl7 z^lZeKM$qM4!8f0vk+JiGHPEQ#(7xv}|7U|WrJzyvil4f1jjB*F&Kf1@m7)XJs3wKc zl#92RMvVw%)T}hsqebbgM~Cu~FppQWr=G8_K%@5>LZfelL)!Nb{o;C?Y4l5DXf)&l zg=s|Lq!A`{uk{D2XA{{08&Ew*!d~SATy#Tf1dOXjE1S+tXpPVe=S-!r8O%(h4Qvgm z-}jq}JB#sa-TUl-@{g`vU8bZ>0G^H>0HsVbgm!&cCJcPjHvP+zNaa>4}EZq z!pLv+P$qL*LLsy0H$rC4QfAR}gv^{FvwwUn#%k=xE2rNkrn;RsUG43)AoBnjMhnlM^WHwl zJmJvMCXn`ftsO3r^!rzhe8)oOL}iPd#r*C=dsKqV^%~Bf#%1nJ#W=6;;-fc?=Q0nV zFlw5tB~{8-8Ad3hW@We@Ey^T4I+WCvJPma&?Yr0N_GQTYpN5dxoiOL`ZEG8CyUAqE zt}$fZWcD;*MByYeCe_y?&`G!ehU)+Enaqf)ZnKwD0?*{_A@($Zah2Jx#@vLK8O?Cc z)Rbf~UAfHKIv5X`f$GT^cJ>9RehZsk+-p(-+o)@H^LnPyVnU&j$e7TGv(!lBOlZUz z8U@G4Vywn+UO7#pV7sAI|Cs)rYC@yUGK{{#2Ad4i&DrDCrghlJG-^82({Qmy*Q zWa$*OpwXnHxt>6yuclFHppi?@BU7MJScUhCpwXVhx0^$kHj{3ohDL>YH*61$?tIP| zh57jp&Z-BEQk5PT&Nb>l#W*MDeaFRXxkh~{jGA`nof;YqA(T&-x+0;yK{K3Fvwy;(ncN$Mbw_Bxt2iH}(5;tIY?WZ$VW1;4M5FLs?xLG; z_Qijr*11Z=(z*Wj_`i3q*0FRh?|(a2KPpDFU^m|;%I;%QhEN#w%e0BfJc&@qEc%U* znX{Bx^c*2GXUIG`J{Du8SJ$eQLj~0##2yxXu~iTE8jyLxKVcW!S`juWGcT!seR?yK zx$hlMLzSMzRzT)an+jHi%uDw)OtPG0wr8A`5;C8D`Di?3o;&5}FvvVCUz8QnZXMjh z2$?hQ_o@t;KU~ar0`q@wPuCJMd%oCuhRZyfig8}wNi&~}p zmoaFls}}+G;>*D$Q&|ixB{75tvGN5^UK_@^nuLtbGJ-3NWCKQhKg}s z-@`0@|8SW19w^T)N3r#XRf&PzMpQjR#9rroZ@#*s>+fM!IS7SSB7wpx&eAH8 zLSYqWSmm-H9u{LYrlZBE6&F@5vA<~jC|iLoRbW+m8CHKp|Jt63ut|A&K>h2)`l{_>QR&7i+IS;JrwSGqj*z=wE@`oeOnfq@ zK}PAbKYFw%<@M-LP7zib^eInN?{nBhp3@LkT_p?(ZP9)1mdnhlTN=ZvVpK3j6i!xQ zQg_%0>|YUAq1hc}z)6{~31C(M8*GwR0pn`bk?jK#+A1`|Ia9??FU|BreSi;P-6j&K zK4DKEOpRviPxk;{@+az=-Myb_l$%g!Br+y6;w&{1ITIRjhDQ10V=-1^8D2SUk2fgmF2!2^Q(RBIR+Xfdyvh< zHA!0MjOk1i1*C-W*QB$|4Ors2hGHO=b^k`9X>d~RBAgs}G(Zo%+&O)O#8bYJ> zgd=BAv|G6p!rAvFTVRinLO zLlRmeG{ae=LWyga;u;~W+c*K$*LSk#V1c^#e;G@tYc~5Krcp6Mp^?a#(1^3tNaRdt z#2FfuijT!ujg@%iG>w+oeJbT0{dR99XjDap(Kpy&D=WfuVXvjyv`dGXMuv`FhM5od zZiGgbR;`OdBhTF%Cqtuo%M5=o-)Core$Xh*w6335l1B4F8g+#($2}+4f<{61lLw&D zk~S;$Vg80;=BdzV?Xy&kxJDVN80X|n$>>#^Ym|k;sA-Rm>995OB9u|Hl1q>D5js7R zMue3f9Zqtq*%_vhhR|puVa=5b8$R4}k!iF=V`$W?gO>p#3MY*)sXj2yt_1+q7XjbK zc@N-cyfQ8?(+D`NRxfeD28^pl-IfebXpPVe=S*EM-?t&x2w~mU2&nteFi?F*F5NCi+&&8JtLZcaOEmlCIbXlG{F#p$=DZQZ4 z%0l+L(5QW$f!(1?=U-16L8ClvvW7yV6Sqh0!F<1#%jQC(^wsuuKOF zu8}{5QQPAWnMPd+Wt84VsYi=4M2`;T3E{%Yk9+NZ8wHJGG=xU)3EjTAH-2{F0@LWT z#?WZNRxbla6iympQr?goz_1G&*jpJ8Ez2Gzq4xrhW6>Q8rACOxRU^L{feEbr7+U{Hj=qLl2B|SMK=;|bCzz4jwIaX47UU0V=-3aG+sH)?FII70kz9y zxNU~pvt<}9V1vy^giT8CFKW|5PB6Ed{Pi-VK5>5w9PTk?s5ji+UGnBmxLt40{U4Zr zJ*G%^xIHvYxl?ev!cf}>M;r5zg0lP3i?air6;C8uArcvDO&Qy%^ z`pyy5Ubw$8yHu&C)XIA&~Bp{ z&Y8NnY}9z>b_81`@|D(fVUK>Ts!sb9KK_9oxnytZ8B1@v5le3hiKREC`?ojErD8-K z#p8XlznGLI6h=auonrQGAQbkBjw0;kEbSFtMcB(3_J+sDVywp9ymESbH#PXBTq@}c zd-uvPTEGTdxCqlnW~-=8OL>~v+rC~dgImGV+hA$B+O_h)-okmxN5S3?jlO)t{H>c@ zy1-r+j~hE+@6R_Kdc)F0DO$9Ly%XyCjD)?{-Dd8<{MEhEg}~nJO_$E$_V%S>oY(h) z@!O_ydk0Y%HBEY7!4B?lLK!tHBlT!eChL)|(i4WZ=$xfTqm!`rhla4%rG73$%Mv4| zo-BBd*_%{j*n6gKE(1msPWEC_w`B&Zo8nv8!3Cjpo@)ceYn~w59?y8Y{!-8*H$Z6k(IHV~*Oi0ntpOy-RZ$ zMrB&M1G-dbUd;;{EjG-&1C7de$^8}cj~x8f0U8CBo3IiZJ-%78FLWusBA^>IGWLAh z4H|{yKe!F^cP1;g9vbB+`*sc2=p+^6tWnY~NrSmY=P8Vu_HB~_8eJ!pQL}PGj~3;H z9vw>eWw{K^=jBTp<8cBS_0

4JNGGF5C8{%g!>5MrsU=($KOnqHxj(le%jGK=sCH zwh;vCo=yN387nmc##N))J!&VkMrej}rm}Uav4d-bup!yIad$lYOs}ciQ1=PJS z>F{1Pn)f`j>L#JEN+eKN#aUVH(F4&XgXxALDYG>+KZ(-Ge`8_^kevX1U{9)Cw zQrV*q6gNFOl!b&RzuxV+<3l8@TBaeaT0?l{SJ8Dt+|Mwp z)@ux_GEu=8Q8-zJN%h;-8RFs@d)wymGgR-qZrnabpG z_Y}7ZVci{NK=wZR`|Rm*pge3eDfbMy*_xesiD~qmP-rAFCN$zKH4-@!8gYh3zv5#t zR%6QKYUMPI=Gi+pS^T*5eiJlGEyL&=Y_N3_VUrS5SpDnDSC~dYKDiA;w|?CXUHJ>v2of)D5GX&haN4;F+DnzI;Px) zU`NZQ;g60%qsAISqYi{oHBWUvwLgk!)Kz0>6kayB0V4`0jWDU+Nq7)9Gy~}|I(nAw zG4}C*>;hZG)7ZxYUdi4^?BfCBs?mi;jT2fUG{ZSl-lhESa*Ytyz4sibUPEJ-)Yu=> zQ?S=pZ^Z$dv8mR%(#O)d#>UdQM#s{*-u>ITyr~#bW$_j=*?mk(Q3@l!`w}I^6MIz% zh0LPg2$?xcnMKbLGINH^)#76@R-=ViPLnyvUcX#n*FL>{Aahe0Mhn^@7aDK4%*Q zY5iP}j)2UA?k*_>nMb-_4#)g6qlO)T%*P^qZgQE^PW*R$ulrR05|_CIg;CR0e^Wu` zDugm>R;udJqBPZ`L%BxSdhMCWdS{P9<~tff=0}8%k!71KX?%*w9HTL0Zb8k*h{8!` zOzK{63+%+sCa_z`fVyoWaA+?nGcc|)dyZ_E&@!VL&Sq>seEdC^8DZTO3E+fRjp%$S zU9*W|>kq3E1MO)dDqkDz%w^$rCmBWy*kF@kdP4HF z+O(?%=61R(xea}DJNCihk%3z>!|g+}I(owGHq9g7VgBXm5&^I!QIYA#W=5T?{_yJa<{!GjGDIDO_lOh z@)63YS@G7RMJc66hZ00+U9@AR^<@OyUZ^45UQXDmRM=#5k(12rRT{(XnU`}LFrsjB z86C-39>+&ws;lBi-2%$Z*X3Ds*#<9s9fZ@m8g;*xzLs z#}{>a=gptc8lf4^8ueHl;>I;XSa;Y6yqg;zHe+9u1j@t4XtsvrHGCiciDs>@9g3x| z-HN5JC61-9W&gLY&7opM3&ifP>`nB-K?)zVfBy#lu_zgh}zZ;@fNfDN`t5vC9Fby1tPHVt#TK)*bOWCOPy zfWz0ri)4V?U5lA3!tMS_+BcXVkmH#JZl83$VussOd};^4;qc*J)8TgAN~ILI{Uthd z9p=}6bMq|Re(k>^*rzyV^ZLFpYu6v{whx6-(_TB6+Z73A)U5dG(W2DSqeEFq zct0SxXl+;K_F4_$_Bz5GSF;qqb1IU#9j-Cl-qkmc0V4`0w=pUA*8&(0W>+8SG-4n_ z_DbGP%x(PmS~KZ3Fs_@(fGmX*+HEw$Ia8Hu<$ zu@N--K5%BWeXu19*Ck{%t(Qo@*sSr)Ishp>qZ)({%4CLA$! zPan(9V@#t^jiJ%mgLw=XQ8;OYN%{KL0EX&eBR#wp$WVTKXdJ`WYotc_+qi1_e$|iB*MDOen9yhvuL(T)cw#9oD!OHTkBj4W9eLrV(DC+W9eL7{_R}z zs2EXYao8xkk4afXVdOU=y}C^#6f%o`BV^_*Wfnb0$jlisuZfSvSdE)_<+N?$RC}gi z_k1aKm0;UM8Ac1(V9O}N^lG%kd0Ep2yD^#XrpjvwarHV3X=~5TnGP~X)+pT^GSBL< z{3Yg3On$QgWbXdsZXU?IY}@a90&hG-{-drFi%v3URVKK)CX@Pp!;^|?m9x<{w}bEdZ`j_@6E6EwYstN zwMnt`wFa^DwQ2wMwPRF_Xo1+@mA%QNL{S*&&Yy|7eT`7KExM6#o3nIVbR^+6XSjVm zJ{Ds&-shFm+@5Z~P<COhj?G{XmA%0yfyri?B&K)lhBP-OSAGzk9 zm|C+f-2&`zJHLi-yD;Ikh1*XpI3B^=F0L`$E#&alcQARZQDH7c|iwc_F^a;klD^OX&o z-7f~KQp&LUBl_1iNrdSl$_n+bt7TiG=Zl zU4E9V3#;k|k4+1!YMgmJ6820fX$gi^m(D%92CLdtNV*2|?{7$XA69j~{JspgYBd$( zoU1yClNaMwt)Vb#>$;g)6-p?hW+hCI^d)FLI+RC*Hyd=?kows^SoK6hSoMOie}l4L zYepPlR=w01Ry8EVh{DM#OsaRi(NRzULwEKz(P&tO==SCB!cNrLgEK_HezT-iz_?nq z=v{?`whGN~&eVbiMcZ+!5Z0X`0-D)#9dwI+G+QO=?dfZ96d7||U9&$tm`0xng+?M{ zLL<&nBat(q5oc)hIX)I+HU8k0(>6}y?f3j!JGx&e3XOisF!}}?YXO zrct7Ac@3iuH9rbnx>Su$0gX-;X*~=Ybvn@XIp&8P7+)J2bxFS`2{dwye?JPkbQoPf z1RA}rocSy?dOX%;HRdn>mh3S!s?+X3C9Y9wD#kfE#b#bA$2D@LFluT!&NOl(lu@&i zNsksKhaMeD0O6*zw#@aH?1e_dHH1c^2;CZ2%Gl)UVWyEyV`$X)YhD9J6iympQoXNj z2Q&h{9f@wju2%rn>u~H%X~5xkrAENGYP5BI#e~)f&2Y|?vFDebTqA_l=Pu`C#}lZ& z@Z%gb0?HSZ`}ikw%O^Wm*H}8&>R38g$5=X7@V}ia4HYA*EWWENyN^jpM`7f*y(g2| zjZnxe`i+p8vy@r%93eAj$Q&<=u^NrMa+=H&?M1Hr>h#p72xQj6XaO5+g+$n-hb;~;bK0t266{`7TkYeMETk<)*yAek#>ei{gA z8#hiH3Yi;zc^v_nue?tcg88k^9DfFxpNBuI!)1=5Vw~6a+1tOWa+%Li7&Tpdhsk`7 zP)5zl|3Hg!Ss!&MX{+TkLZ*YZ6SFYeCL%hwV1Kcv35=`E4?6lLw9IIRbEX&IN3k`eJBmb9J?y44L?)$p2X#e91 zE2p=rOlP-&MoETmzwsgR3z+qaA&6hR{0bxF#}fh z44nED^H(+NRRdOi&G_>a3dTJsS2*?!RI^tQt|h(q33qq*|_3m|y!jiehs#+St zs``ZfbzMKL+I)an)lg$tHG`Ig5rvagn3Q`;0Swhm6SWM|KHswB$nDm^Ra%@j!m{#V9=ovy+&Qe#=H-xU7p=-PNSd7)!iC0e3b-caSk&yF- z@&%!5XBkEd*kG$6!Y1YWHMMC^y_v4R9^^9&Zl3-)v|MeemJGUn8r*pSbS;@{(-X{3 zeePE^=vw~Frf1N#N%oC4Xjv?O(oN9yh$GDw=$igzwUwB^Xtn(fbPWhS-j?f{=;6QX zyUo?x&AF~gD2$rEK9?A$TappVs97=S(W0c(qeJl}wEw6%J>RdL(A7^v=vswvbDc}o zf9JI`U8`ygUAIy5F`{tN6_e_b;BxHI0`UqbI#UQ;f$D9dw7*O5FeSWrQtAqftF8fG zGbXgIXoj;HQv(alq0~duUYj^2n}SqjFS?b8<2y4)W(3RiH3x8&WR`H1Z{sQMyX6M~hNf zk91&2xV>L#pHt6wK%)^FLZfknV@6vxb&A->G@7U}G`d#A+kg>;lSY_Sw`=R55l|lX z1Ts{=I>femh1l+*?;&(TR#Mt4#&af&fJ{Ds&UgDM0tQu#JTzX{l z&Vk;r>aq-@tFXZ)!zN|fK(%SRiZZKSj`TLHpT6M)?3p=jMPgVL{GxRjta|vyjaii; zdGji;YF3NgS7FtDOO>&(C#p#G9k9x6N~T~~^>OE>V9c+-;rAz4mCOBLUvAY~D#kfi zO3lmNxK-~djGDGR%dGl9D5GZOqaH2FS3T0TfKlECpP|0HgC1{(Ro)uHsse;Z9Vx5s z>9?0zRY+r4wU(BJ5rvagn3NZ$0vJ}`{fXW`6NQZvqUxR|JuEejVPr>X6{2yqN_mtm zp{+tQoHNyPWzi6B6~ek(zkw0>Ht8pN@Fkk95_#6wq|{%cuG#LznMTbCg+?M{LL<&n zBat(q5oc)BB0d&lHMZuJ(=?i3zxb$4mH$fRgGOy+7=42cw(}xvQd&l+P0Lo2Y1HG4 zx1mg`E+?VU-16NLL8GV7@@;`eHT$-Fg!!}gpZFpaip42|*=VnpGj5hmq6N&rLk%my8Q z1TvK8-4Lj$#pMoyWbNaeKqw3{?cSEB?PuD)g{6@iF z{Gicu!{8Ip=uNBbMn}v_xa;}XRmMOx_aq*&t$5r z>UU06S65ZD8-=Hs{~2y{yvz4s(~Xu;GJ54~n3dFRy3sN+<4W&+VK-VqQd$EXKgmGH zI@KEKcuX?nNwdVsUu}RJJ^dl!MlVRt9eZJWw@?JdJQ z?uBnJ`K9@A_U&;YJMsMzTaJu^Z#VrmbuRvYPKWa=eEaLOUq+g~9Ztzu#8~BhJ9Wk( zrf)}(8CUwP$~S+ye>+1`S_2$sRT=2GqRL1|mQFd0mj7mK`zGmz(&XDYR2k*SP14BjUY`kiD0SB2Td^|hjE~CKc;C- z*5^Ob)Zc#t)6{>-Qf?_Mn&Kr$$TUr^Rdtt2(?OrAOjFC_KHoH&a#Aw!%kG$-yM4wo zFJI;U)#w$sjO2xu2$LD55P6opH-Mz&y%s2z_gZ@L&c^q$6|YprLdEi4Q^R}9{ue*f z)VDhQ%pK?QF8epnE4?V>(uTwfrtGPn@XfT8t&_uhYna!L>o-3ki~Kq-tG+)IIvx4e zh^(zY&)%DVYYyXdqZHxr(t~a8en#It7SqsU9Q5V{!J-Ug#H|q}#@9noG zhk*l$llS6OdCLT33T|3%qh*E^uTpzK zrE!Dys;s#dxR|xCj>0}@SrpbPQ!;FSuDX2ko+Fb#zZ_I48GO5+ zdF{A<^Ai$SdeM%vM>4{<>wXbgOL2*PyKc;!Mzca$*tcJ{Ov2^;=aGj;;M*xz_vG>} zbL|-W_Ne~3w!pV{f7#9D9kl1~Co`^fRwcTq(vGeqr8U6OO_hO;0ji92ye2vEL-L5zC-~;|!w-pG_cxN| zrW9-(+aYdVqsNjOzP&U?P6G!LC*Q_tn}iqz;`yME;%=39QiT*t9oe@b4?U5-4e6VkL-zbA9+2fbljk=Pw+{mgi z%Z*GeJGfSzS#D%%xKWS);%A!r4lplHy?H%cU}nd~*R#Nl21+y7;7`aQ%k1wMTt#GU z$W?Zumi5Suvh`y(@~bh9o5+(#YafRjCEMo5ZZtc*9J^5~_kq9QMh9Oc7=fnHr&Yp# z;70dWWEucB3J%^r8~=aMwIk8tMuDH#Pchx7J0+u6POT{u?6A^w@8@$lAjj>{U}1<}~`W z@;k=2hu?y}!ApGC*E|cadK2952L6ANfw@Y(pe zK~+XN0v6>omNm=Ne*fte=y+CCWt5{P$?#3tW8I6lp>%<0(H!*@OM3Fl0&f?3=)j>eD> zqYj6peft1O%eO6zEZ?@Y)$z1IvV7ap_IuA$HGTSLXkGS+h;wUPoqJ>GTuq z+gnLWYk*^$DgzzIR2k_g`!c7oua19-uvLG;w=1bK%2AEvlA`h3-3wgHzFkMrRV=Z=!LCjhe zjkN=H$1!UzJ8Oq2nKo@Fv2R~AeOuDx?>IqbTwjcP?Atd;TE1;zWcjwGE#J04vV7ap zmBS+0BE3cg(WfAa0;=C$Mc%}>bkSKYEcyOxANl2=7K{7dCB<{fHTE2srOr4RTa(Y35VvS*hG%X1wNcW70AXml+T&~M>Ds^lm* zt-!4yz5d+IQrwPQ#pnyHa?)@p%YvEuSY1n4J$01E^S*n#5kxk0%!Xz5xobKK%*xys zNb&Yy+Qf-o3rJFF1b=*a4IE`ilOK+<=YKfL#sA?bRsV;hw6QzN1WLxr!6mz+OeHg_ z`?rVeD9cD%j$&bCIf|)e2iF40auidegS-5{_?f1@o6L**(ZL&7qqa!TY*d7E`)LnlRH9cID$AawX3MG5iX1f-|}ZWJKJ^p&NES<99S>$xXf z6~-wcM?E9ybX~ZV%UD(>jJqf0c9xGscVm0>`nS+MNjjn;HyKO)BTJyW(Wms@x#*r0 zbL1F_ZpgLcr^E66$lv|iqkHmajT*vCXkXX7}VB znURBPe|^TS$7hn#8sPY%%0NfV%ZfG9(Trrx?dxu)4qSrnNh?*-9=DLki*GQZt>o@W z2SpQ!&FH6bAaNoQr(#5x-X7{^$y1{q^Ezo*#Tz(wfkenbdnJjGo|4!pPK0+!T%{Dj zSfGYniEV!AfqVqZF1vcuUHYGhqaWVqGPd+B%=FaP=*hhE@l|v(C4+{S}vceuQhC&>5(-j}Gs)Q9la=M_qDdGG$?a&dTHnrFe&;H{yX z2eP-`?mzehzP~ul%@*+1vA>?54sRX(sc<}efBJ}b>rHPxNXh8sJz#U(m8Q2ICNr+J zaQ-jw)}th)HNX+B%0NeiDkB}Sv*k8|>aEP3Vah^yYaCTZIpUF=({yCYY`vDTwZ-UJDeT$?MRkR6xeLZko9ndC8~^a{7KTc&A_I+U1F-m${!lH3oCl(HgF(S zas`}=|v6J^U%oZf?1lJtNN4`P?hA;%v2(ceq{46H+ch zjk9&LmSE2~|NXNbXGc&n{+s5qXB3O`S3JzTP&{KCnNh#Lyl2mtNz(ERiyO-`ENyv) zMULeerpEojtpDO?n))uHpLrDXpQ^)B%q#6*^8A1z#c1Y5(mhF+JmIIaFyq>lPsqj; zv8w#tm}g$B{#%&$eqhfiazMz;`66+DuV7M?ad}x34+|}yxtja< zR;_h@FRJwl5@|t_q3r7;zs3vd2C9%a5-y+Kr@7(X&~zGX`Jdru-M# z<8rtCJ_$XWwd`6VbWQOCgQIq%wym{;zT@7l`Xs>#TMSY-WO7IboSyt1oG=gNjzIU?Afd+zr@?b zBO7{6Da6Ap_8Fj_4Q(f!H;=LB;{!(AXXDTKxQ2@$;bGl zu;Vj{l1bU-{uFd&!c4>^Ahew@nNfpRBROC%CTRt1iwrAZTiOcP78_Q;wloFoCI7|G zH1%CgKeH&^@L$@OUuJe?8t)u%=2(*UgSMb6v&Ou3T)+7Vd9Xh0_`}L+(3OeaP-Jc5 zH+I*%E%O-h+Ld5;Z9HNMH;_rP&3FNKjo+#qmv^a{)!AKBr5ZE=?z$z{c`omE(dV6p zyDq49ts&fXYu2k%5mKrSt)B?)IU zlj@C81xRrtLQ^9mSjyh3)AiS&JjU=;7ucD*XmE{4cI^_JxwZyZ?mOKWuD%*vd9L?n zxSHAFIzq{W`3_-cUTiwE#K+%pj?Adv@=@%}cS%~#Y;j{bv!yL(w#c!Z+0x|9|H;qL zV+^{Qrw=Zk9GAp;jL}#fRe%}Su6#m{Y;G5gdq&#DRk)XAh21BkXRv2P&)~y7IVSlaRoiyX@{OpW`J z|Kw+y`kth#d2y?Ir+9m3m#*CB*V8jsP1>`xMqusAS?QL%neQp{+Hw8nCnU$b6U_~F z)nl4>KiKjU&0j~~<2kwa?!`W<()=y-=@fJ#!rSiEX+BTMxc0uEj80p^?zeQBFOwM+ z+STV3g5jY6Av;AU>2$TJn%5Zr*DSuq$x(y&8te8r{~8^gR3~EcHBJsL%-4AJbm?*E z=s5cqWRH7v!2cYs(G_h$AUZlnrp)7Od{pjr5_sId3k&ZsJ35^y8T}e}ovOCU?C5kQ zGp;dapAWb%=}uBw0~|e68R+Pz%1Fm$l5+;mYu+p!cXY0+l3p7|^3O8$o0Se+%^jTw ziYDS?ki>z+iFlmKhT6?ic|HQGTqqsN)=c@`R!0X`Plq# z+2YLFCp&AmDVcoTCbK`JH~m4<j~YnB)L;%X}hfMRyA$E4o|SitZLjR&=*C zMfcDD#m_YLjiR5alQwI{3PYF3n;7vlWfyK@d^(D2$Mu_^kUxeD`Bv<8N<{Z7e+cvG zSnS&qX5=;E4iDw>uJ!mU-^4sEALl)MyI6zzT;3f!ZRVSpa^K>NhHvkzo`!w9*ziv0 z;oC>@bg2X1ew60wO@_ zQ+VpCg>#XhDDk0t8d&8v5l+{=&3O&uVrFKorN&yJ74QFrZ}-($+csaUKdGd#cCY&c zX04T-wfB@vu6>2rxAU34Eoq`%yU2{|8y=f|JI0nDzHMP-`L?Ak-?l)qeB09G+cE!( zpK0nFhkj<4qh+bx!HcDDD+3g9$&71PJ|W**yzSa@mM?t!(p6!0#-XgyqnG$+DKI6{VcazWytk->1Lfq3Rp7AT0QNPdPvS*|qX|;M5HtfdhX?aN|@|-3qhutD^4V@GPZkUx;0P=BGye^D3_lw{n5kne0(Xc?>d`A8` ze=^)Tf3L=~zb&|1bnVA*mwO(KXMbC8-))n&>2!S@n$L(6?FC=sx7+8~0bTEXKA{^l%*fBz zn7j2jcEFR>6OTYQXwT7+e2t$=p8OXM7&xd`O>~2bojf`T-JtBdMx?+s-pkT@pVAW~@ryDJe#_YNej=x%XiMR!YE z(cL1)itd)C=-%u|xPJ2!5~uyqWcP0K46zo6 zMb>&GVP~FtI-gNx;AJlF!|_|PGe3#-?hBmx@RUEeyyH$t#?D;6gx@eYbF}ikxV-P} zymt}K9RAyoYH;Qu&9Vw-E-}{^&fL9d{R5^m&!c4Y@~+>$%P!NI7m^v*+M?bYIP+4H z(i-ry40Nnft&xszBulP)_AX`T#ptT}oKa+yBPPkVGkx!rKD(U9D;$a@XLisZ<3Qr% z%s7?1*|}MY&4w%48+uKBSvMe-*;RvC-1UWF zgbtD>(9tj^w`P!X2N$QS?DKrav#6mA*EtQYF1|$>t`r(v%Z{XCxL#{;Wx91T3@t?w zJ6x41nO);~>e7X_pUwzh*sq#t}u6XCxwt1F4c{;8boD(*ikCk9c2L} z6ZK?5818AZ*&SsGnNi*2ec4gglC&Jf!pL$IOIwa&fn+&~rO8p&{TDye)OR!eOrv(q zzm%T)W09q}+dqVnJerfh*N*EqKOv5e->*zc%!@3Cw-M$tsn}7rbQN+>owvBBX-pCa z{*YM5si-S@h~{P~dhFb#gH?2Acyc6Uzd*@4q^GPqV$Jq8>&S*qio!a~$})Y(hP*D5 zHnR-p0<$WCZgF6hkG-6(Wn=OiQ(UuoThR9!>xuf;V%GgN)@x)h#H=ULSU* zYncyN#kSLY&kMPHk>mr?Q$AcN=X;wEWJ51qg%6mOE4@f6z>$od~~w&5lG3LOS*g_VqsM~ zAC1V2>Td4GKn#u&GGPXm?;Hi#I`9eev5+JVlMkFK>kJ@y2~0zNrwydsCo9wex$mXq z1JYAIUY+$iAIOGYx{{CmoN2jmJDerT4j&2__+w=#JWtjFMzV;Fhf(n{4U?3ZM=}I70 zai*13?D)1a-wRS%Mb@l$0i$i500tt52E^@7Z_fghZW<72d@u1^4=QUw%+5caff#28 zqCF*3==$CXh!9=vKy)HA>Nj^*CLsMBA#Y`4Ie)2;P3k@e5DiG;FoD3S9Q1IrH4ASa zbprR9u!_Ri2p}N4kCQ+^dJ4p?I9w(p$^E2mn9I8o&u3S=I`DH z0@=_@R{;WMd3zPXWgw@}I$aAB7BmvqZOjBz*9Zvf{3{bMQ6u2E?`wXaP-l&Rss)z) zfi_~Toq$!8%$@6({y<2WU?*T5nNgu%b90q*>P?i_74YJw@{wWWq@Nf9u)7u0f8+z#~1i&l^n2L}9DQ=-@ z=qa3~(y4@18HoyNSbcP1(=ULc0NKW znJKT@F&_);e2gJ8s=Hl&2BPZ-A$<$7EIm=k>Zh2GgA)oGI7~ipDrOJRTcF$yNO4oe zeF(^)4ut z#@~PSU?93_KomQcnSuCA1EN>|I1I!%4Tx8hc8^EEIAsUoJS8)x^y~2m7#r+BTqZN> z_e3EkVAVMxLyEAheO<_X-5()f+`d-Oz+nP`QxO5z0SL=N+fyT8Knm~JfhGeo+Cd2f zq^Cf*{~qFPAdn5cbQK_A76D^80tTd9_!q7e7~gcjD&NoHbglSO&}j1JE5D^RSmWbj z+`mpEVEm);k$A^6exKxAjgPRiRhf@lc0M*yGC76}W|Wo=_-7{tON{5v1*RqY!tx-rc67@RJD+?B+D2EVxk5_hSH@Nh;tec&7WsrAl7O? zT#5DXI0TH>b|CUnGC>>TFc4?$KolY~>Nmr0OhD-#LSE>~a&dnlNB#a70V5kp93~Jr z72}u;1fxD52xLPqT?Gi3m9-U+qRF6vy$CK6 z8E~DhOVbM(XIdv?AQoys)E*Fi3K8O-2E^DL>-as+do&;%<=QY1(M#H%oIa#v7QL7@ z4lT%CI}k6(jQSn(I}?y%kC3H$unavSDbRjB8IJaA0=3oE+?e0QV-4PN_W4I zvG2;Ff55?C8Xu+KHef#9Ykc%yT%7qhrSb7`$BVHD7)k7Wz)im=U)r6To%OgRx%;iTqQ}n8z^J4v`!-K)WEsc*nCk8MdneBWOr(_Ph*NsK|i1l8~bWt9TmmxE*uSp*UBB+^= z@%ph$)8+z#~ ze84Pvpl;luK#CVB(Cpc8mP-2qtDI!vbk#pq*obIfiTSv%@lieaO9Z&dq46;?&&@%I zA2D|SJZB(gr72_Z|0~=1Xiv$^dvkaU;zxEnAHR_q)tzGy12N!(kk<#ZY~WLbt(RUi zA19*<8#qipa4N@W+zv=Fb@B@02c+^=3CLFuBp;BT@^L9%D{u3GZ0Mz{@By>ZA%zqV z7I||$NI6@LUf!0rh|zfX*?p+^4;m2v&K=1>6xV=ARO2@WBB=(%#CCoRL}NP;QIt&f zM1c&1za5BJ=|q)J8o~rbRuHn{P?j@l3EAWJJv1okNa8Soz^QVF0x4dq!PD;`mC59g z{zZmZ4GN^EK+GJQ)!RTI8+z#~K)@`37=(ZU8IxyTFc6S(VuI5ZuWJ#bL;scxgpu&) zC+YVlC1xP1X+Zdu{WuVjAhQOQNN#uF###3 z2)TAROaFO7es$dk5dG#BF>shb;8f{>Le77=oL&kl-YG>=E)NdnznvZ`fxwqN1>)1l zoZbck+0aW@0Rm=aCJtws_cSDziQpoUZ^&@EPXA5r*80g_L_B`aGwQeXNG9O-+d?KA&9d@SAt&5oAjUo^ zV&E`=z^R-(;dVfZSEk%SlL0B;O&!W|!x;$#teyffIyA4hfj~C&(p7+fS=^;fL4<&m zQs~w2SWJdjlk6{7=@(DS39LsF}LS}J2K!n)sENb8|fxxMpT;^u0;Da|ZgjE^C zfV}J%Vl^3%o&r%Oq@cHfKsNN!Re*q5X)++iTjzL`6H@LQ?{p1lSk#ztIywVUTmvH6 zdc%o02SX@1LEX{+6=^8I}j5nnT{<&8HmAlAZCym^;_T%CZO?PA@5IM zS!|S$BW^Pgr$!bvaF{^gR2kHQ6uIXGX^`TrdOLAb3i+g)1On1yAjTE-HW0{$Ub+&9 z{hVojhsNRKXe01#=|N6c(9)vD@C+08pr)&91Vk@ho(Y(!5m4%JHYT96M!?Q!*Ld^S zwRQqRD4F`}5-;#M;Gb;31>~F>CNk``6LN1KM^2K=}dzT}b$T5&44kq9-OPu=n zyb7S%ny@H$8IZMjkcJ+t-&MZsC_^m>tjcRDA!qKCd_a22N0rgVz0C)*p_jenV-=Ty zxa|x<3xaQ_6l&M8E_-GNR)@J2PYIWnv5yTKn&J^xVY#M?~buw10r$V2sfh3 z91V!D&O;f9n|2^hQZhM`ZyAB;vd<30IWnVuGbd&O(ry*`Rh+HP-1$n9FI*-&TWxSf~M!=Clt3aZdxH(UAN75HR*=KwOwHi&vsXFJ*fupNf+C zy+Xur1dO|OAkvW;*Z0ns38+<1$Q7wr?rSDw=O+w=izE)tP>=(s%KZzZn5V;wiy*}^ zOum1C3@$g!>Tp1M%7^RhcW?87Z0Mz{@By>3Rsd3LD#yFUK*}*>rz=f=r&03srJaZn ze`!GMcr>0@T)x+Uct4{j193_NB4|Sv1|o?ah^&;%uPvG|5bx|jSpx8no z6Q*N1Z>5kyT|OZ~6eEel1OlgG$YwcO5Xj9(`_iZv4~j#I4O4lw8D!ls2?V64K)f0k zyJYE zKVd$Gk;Gy0fm1mx$?bp?L!#WnfE4kO8x+X-HzXgBp7L?)^kHxFfo$ldEBV;ZMIr`$ zc)$bSR-U7FN#<|F>+^aCBE)%(fN_5;<8_F>8Ucq(j%5PgXarPfP?`xSYA2vKC38Jm zFD4*`oq&F1Muq0i#8p11q>#5Vv;0s|$e3L|^MD7*f#(0h2nU^tMqxD~1SDROdbm1A z2uN%<)U+Kp8IUt_hgwYrq^ATpPaX3%0mz14x{?4I(jc?arGS(hu7|S~WseU=ILIo( z3B3=`=~~*>--z{eF!OO=<0CXiLFOZe#>bwG$(fHBdwzb-Uh?=cUY1zd&c`ZB=0d;k z!w?~|+xb{SW?bLYtPI4`u|ihK&a&K8Aul{;J|d?08#p*aK@OaXO^A3N2Bc_EZsMT{ zr1Dr5^6>!42c)Nb?29<*Z9b3ulX`?(C{ljd-iN|S*zMYCr_;Zpc71wgXX&l6ls7ECbm1%z{pDyhY18um8s#7>ndXjI|mF%@koH149MEy5(r37f#`AKtha$cHuTb! zK&;{dQ*KJ}Z81*8W1x^?l!9+M&PVwhpSMr@8!d>D=;!C`{mxWnAgXCVYz)cEKxEc{ z$Uo~2FH7uX2jV^@6J9Yn15wou#A7m}e%s|?0>)=8&eAs@%hCCTJpGt~$UqW@2?S18 zy*^vBO+wzq4^p~Aume)*V?vfpG2CiFAUy?QX2ieV1_Ig8OIHB`W;x2apNmA!#0h7K zqQr+<5PVs_#lYzrQM0&lp;$)d!&l=Yu+G1{XtBA*$AqXIy%8{qYJB|a+nxCsVCN%@ zl38|e@ldoN&Fp+kBQvh=M1BS$thbOM1zF}BBIJh7kq8(=gNqwDI72}!#Z%;M=wZMj z;^Qr}Adupb%25njKrU@B`GEA8j}uqC%?Glfm#)GG%%T@Q0i#%uVl#gp_J$M%=E5@+ zNHHyx7I-^dYvvR;@+Moi9q}WF#>bjGZJ3X48Xpg@RboCWYkahS|3$1(v-7c&lKH+U zFZ0pW&c{JAqq++hW*|=gBV@7I@9_lg`w1bZKW09HNa8U0z^T#$g%sh0`G9Q6V;ZzQ zOsE5L@+Qd#q^EowJ$}R6d>|Wo=_-7{tjrXL6f6Fj4@jlM0V!Vv;dG^ZQrs9htvK`H zukjIc-3wmBI9TH&pvAc$#E(WAAG`aEVm{{B`N&1dG|ad&1o2~#osWEEMs+`RFc7yB zmSDLcE=%9kLS|V&GLd6ksuBhclMkHA2Gh+}(Yo?XPgs?io{%e|jj-AmNKg4_JmRLe z`9L=G(pC6?SsB!VtjF<$rq+jZfuShzq4)u-e8Hj9mCaegn0Wp0HpGu=8XxgK3}8Mc zXna&z){6P)r15chcM|4fjh&DDluWBGm6?w}?0gg^Gp;Z2R|X=grI4}Xv&_|5$Yg#W zz(?y&B@7&#p&*vxu^BC$akEtJVDUv|ra0u#+L8}QPx;u_Z-ck_KsNN!Rrr8e^gl+U zeSwq@7QnAz^*Yk_Ha5%5i$&eRf(wv;`pnQmjtpCIeE8;Bc1{^4wEd<&d6M z`OKl)yl>GxfoM}z z$N*oKMFWMLy^#6%r(Q_|2WKeAfzukrFs!=)d_anO5Na@kSt_@zu-@?>X>}bg}Xh7tS zKB*_#h}9Ypt5Q{DAYR&mNJ7b!KjLN}PTPSu3FwE!#pl!5F9HZtd*NME z$cA3J3J@?WYXueF#{^4efmNAtvuBX{2!vXFld@e9R7WG9Py|J}v~LWj=Ok zd;~T=!>bg1O4}Z+FQ#Ok#f-&#+_v+voXjZRW@#CS9ruMy;Ky?1OCdjq48E57LC!!vPU&GoP312SZgsBfCw#xwNx{ajB zP5e0Hq@Id@_q~dmgMUw(|CYHh`53g%xZit!9+L7fUmX3%`o3k?|89f%ch>dxm@j@e z{|jGaLoZ#0515q(1ybO`tC=CKYoG=NQkkiB^Vd>Fht&z0kM$ZK_YNH7Rf=ylKKz1K z_CWlI(D;})t_Aav$j-+rN~WlD(qJ?wZ|r=$Co`_`KzaruLt!ENWn?+2l#n?eFdvyn z;=mseA2{X5WF>f}7NmTN9L!dEOCHLyLgrCcgMu$x<^BK8$DW_!hwGxKf2+RrdbaBS zKjZ`1&`Ve017_tO1X8rXj^Vw8f~&rk>Czwt*~O$Mar z1Wffd0mz14x(Wd>i(Vv6fDh*~K-u9#K)@=uN_V;zRV-~JtX-CYc&h<1q2qgAlvYdw zB0Tw(-w_fLX+TuYH-T3vHn0P+hLX8;b^kzwgrasJ{vtE3uWeo?;AB@JQ{-nktFMq< zGrUDeFi7Iy3eZ75r_wU9u->NyZIy$uAip_i@%Vijjv zd9aRe%LnV>Y*m^JSe3bY;ZsT*qpC-2M8Jrd_~+;BvDyt~KB{PZlu6Qo`N*j8u_sq5 z=A(n1k8_kvqf0fJkIHsFE|3}3eY^kzv0;ahLkh9%bWq6Yis8(fH^%;7vEgk3t$B_b30!OB(yx`A9;^1P5FhfcVka z&PQ@G`VySdFVUhcd1+!JGrP_t~ z0qgruk`GAF`Do{DK9CK)bQL~eR=S*!vdbC4MIxdLZE@&y{hcqs=-B?jUkDgkH6ZQ} zp3RFEyJ$e9&ohL9sGtEczhWTxeS@5@))bb0r|i9;NSm0 z{KxwKEptpEz4>pw#Y<~r>MI$Sj3ja35At_&;M7_@O1MCZX*;}h05U00 z^yAftKdd|?3R!NN#0Ao-{{QzOjjrAfC&-3g*a|K%%jV{9E-+>BDy+(oIixZqn)yV4 z(e3p24TvsPG+drO+Q^F*$7{G`ojIc`nwt(9E=xC5XIxgl@4oY|PyeSX}ktDoUj8ih?05SWriE= z%UU}S!DL4Lb}7LGjGicDx>78g&JuFzdj{h3%rXWJ69}A&F;HG<0x8~o%&#edR00NM z$`A@W3R?Xv$-Xhk69WYmp8xUHH_Eod~Bp-dbQ5PeC)CFv6;-czO$tnh-ue_99f2C zpNB$5-Fd{_Rg$sH|Aqc3ohmC$Ams+y!E99)ufm%7q~rtAb3Q70n-63|FI~w8^+3ri zhJ|@Z6jB)!pBb~P5tKI{6EI#Q;B}?Dyh`!3MnLWlN4g+FtkMWr6@L&D@WM{OLQ1Cm z&h`BeAx_x|SW0FPP`n&h`Keq&z9`SKV-X<(+dc*XNl40juW(RP#0g$cA3Jl7Lm5X=MZq-&|@K()ciH)@MF;XnYKB?_fT@+xd7w$)rtOlKHr4=i?)pQQeCxG7z`> z3)!$T%kiN?uDr{91dzmG@_|#?M{+wL=qZtAJaNfJeg549kW;{IhO_;|3etg&f*W#(h8#z%ppk-TK>wZ=!+ zez!U!ejL~McrtM+uVG9OV4J1!f|3a>d9*L$$16J@ugHw+i(8d}_q;hp0|NOHuU0DfPh(<#|5dp3J+2Q z41VnH_p+=pBgXl)h!A@;0+OW}%>+cB{PSb?I>);*0oODFPToz=1f;hUkd>0@7*?MN zi1x|$*gYqiQK7wRaFwS?UXEqfS}X_q3Ay1O6Oe->4kjSTfm4xPT7K(hDfjdYW+~?} zhO(?;jJH}4{H^CeH1swQ$cA3J5{UhrX*szuf~9CsW+MjVE>+GLvfRZ4oYn~Vwl^sg zkW?eU+5K}T#DEtX0b56{yVPZ0wqlEh&WfKxfF?`EsqfG(J&oERL+a(#VC0RGl<0-Ac80AxciT}i+y&a@o1 z+Rsunn>4jEoTbu-z;B6e_Z;w1dt5o=-N0vS5Fu`BeDs>SkXI>Y(fC+fegyLorSXxg zxj*w!-p)s3O6H)W8}pIb&POvcqq@rlG7wER3i+Wv%UrvJ9D1MmIJ&c(fy3kjr^-xE zNV%Fn*a0crfhXobK3XjKfb^V?mfq$A+0aW@;R9x+4*{8vCp+@nQz6B^@w~x7&&%bE z6jR&`#2XEWX{&QH5Jfd0PB%@&KqTDv^E`}NL5Fx*VtqRhgDIJZexG|IU=*zOF7QsW+}Ho4rVD=J=G?#u^a$B6Bbh1vMbnCb_}u z5c}GJI8Mn_+LwrdXk-WCB$-ja+50d72j>cTtuM^p*m8%c~ifBNz-P3}B=&u1Wzgsy5B2WV&&BzbD zuxy4Mh}4wKmV!AM2)7-GbYw>Tej3OGB=i?@&0v;W$_ZJ#(*wkSHY9PFK;TpviGrlX zAk+{r5Rl4U24rZC309*3={XPuy$uAip_i@#1k6gK0J$&~`jOOWh~VOs<>z$8a8)qw z94*2?RMLQO-G0m~4aaIg%n3W$9ucCQ21Lr0!x)Gab|B(YG8-Fg?S%+2#tuXhGNXQ7 zLzsXRql8R4l;z1VA>(c(naI(VBn}e@oGO#^AVqe0avr2ukcH^D#%`qwVvi z%ts%MkK3^lFdu*0`6x@t4A@wX`Iv3zqY{}>-A9Kp5QQ%YIcPY`Xg7r{8Nqyvzfr-! zVe)}fWs?)g>pvEdK`IM`AlDo+`FP0WT#~smRb+W@lqlysLjHb_3wB-ZiUtn;gCGY^<^F1JmST8|SNFrJ>`w=IGRZ_M z5<`0Kc%{AVc*urcx(XjKE0Gvd6c}$u1}Ud`(K}qKRWuUJxv~PD)?WkSk4+PJiQaAv zh@)+S7>F4f5S0dIV<4{Dff!H8+|1UDf!JjSVk((Yzca@$0S$TzSz{c_Qv-!u7|B4~ z9#D~XaF9UYRLm=&iLUf&dy*o%x6xOF6uX1)c0!QR+ejcFJqIGd+dv>2dg)3a=w0?? z7I(DdBlIqNl1k`>6rFdT20MFZMI-sn4h+Ot4T!1dQZW!GH6Tt6i)xDqu|fl)=A2Eu zMDLj$h((mlgUSzkAVNggfmljr0O9io6R>8lkees4%o#3Z+KhM5G%r0`(ZGT4(^F-f zD(fmB#X}-~%M+yRn1u3|53QF#!0I^=3B3&jvZ0r*0tC#;%j+SPkP!BuqLF0i+vNxe zvo!)H&05Zj@NQ@XoTxIM3D~X?P_1 zvU{exh!AJnRWfjJhJsisLwvBv{b7RHD&Dd{n}vk3d{#Zo>Ot~m zV3y-O5nKk!{ru};m5kI$e`Nx8YXr>7y^q)AMVs>TbK~<@m$pG0aaALr-n+(3fS;X! z=%JO2rwhk30Y0B?&y8b|85QcB!BzhEN+F-kWZ8R@km;5(0ntg~FbTk^$RBSA11Y*p zydeyv$S$v)fy^*l5&-Er0cpHV0J5Q%u0jCJN`!#q4RlWPhA@zF=9bg7;B+Nps&nR_ zXfjS}KqRhPgMmn_0a4SZ00Z$%1LC;veO`o@-wwobN~YZ*Uj`zP9f*}=M*S|F%>?ZD zC}jP)EGI;(%+{0l7>G2dg&@a zz^vSMLW)<1@?%0s;Xy0VMs)J4Y*Y@)%s|}KfH*Yn60f?;qygbmVs~pqh;JGY!GS#) zh_ZGd22nC8e3t!=HX@@Ph~Z>L{W|6|0rx8kdG*S5JQdngTgY#b41|*;4igBRDzld% zMVE;Ocp$~xRbK7@*`VkotBrv490)&e1A%PlrK^$h{75W14mV5AmZ=;`ML4u1>blXRXsZpzfdxhYZPE03fX~( zPiEBb#A{4Irl~@fzrphGJRy6Gyn#+bN0K;9AaJTY6M$6aos#{Brk0Ff^6ues{jGBGVlQT3h&<@!$ZK30vDcpmUU-kW9$8r3`De~KR+lg{QVWL ztE;F1(S7X&7b1k82E_A2V;G3Gb|4B+G9!EK?uH0a!45=WGNUj*-edym-w|^4ZI-c~ z30XMyO#m_ZDP^Ay`~lr(;#9PO+=qY^3mP~=K+4Jdq5S1dXC)A@dJe=#Zv%mB=%p)x z*w2}kdl-bX6a>`4GXeauXhG=phfY_yI8}_9iNcp6LL}CJNS<>r1JO_eqVDC^3`Bkn zh*PhVF%Z4&Ks2OeI?b=jKs2xe(S*#X-&S{-fW`TROmd%P{Nh4>AH_f{@~>jxFoD3S zxUE=++fGQaM-;tUD43<#@Pnrs!MZ>FWUI-5^c;vtZv%mB=%uRw0dqhRv=Th`3=(CB z4*>zG%so5bsEYBiLjwjPlLkbeA#oUpjv5df^1f(=2vJr8B5&ozyi{(49f!9osv#InR_AzR0}gb1;J6jdr6oS`6=V$(dDq3&iWW>)bE zYS;hU56#O!Ot%AZm6Ca%uMGpy&kn>5GNXR;Jz)ZFo)Gfx zQUf712IMe;`mO3foQ7% zQT6-|UK_XE4#Z1J=1$0q-w+{2+ktpZX4LPD=S)D6)Kytlf61~*W+4;(av2dKDpOSh zhY18u<>0%Ut&;y>mLj`6(F9*k_sbNk$$<16h$G$x0@=_@R{;WM74% zvIF5FGwL_$6%$atvyhwKuNI9K^cLgz^97!Bz zmE%-Az@)J6W~&&9;;~3rW$r`S>RK)dfYoyXPI;REWJ51qg#eg&v+_JV_y{Q%{Wx7U zZ&WqfOis)MxHST9tvbx>+jeOLq;9&p1)P4mM!>9It(br-b^_{AG6nsnbU`by(@sEr zGNVFIedH?d7ONV|(9bN7#}_ir1SX&jNgO5tIF;`ub~_-slN?>lE+eVDlM&XT?ulI`#IBc24)0H`8>zzYH+lg@$&fA zg$N0&H3GWb>%s)Q)CgEHr8W}~t`U%RO$;U=URm2S>-Ln)-p0k4fERWGx{?_c8ap~y z`H7c8?u@~5<7Xk$FJ}VMki=mUfKz2o1Eg3Be-R-8vI@V}hQ?Y$S(dyd34qme0B2L%AHd8YFH`QhW64?pZ zL1t9wMF&^;p>aYMuk!6$04IH_W_N5mF4n^A^&O$`c1j(Q%?3b)Bwwo2na8!Oa+mn;H;(6PzU7nVAb$&Bl3Se;Aqx9md3t;zCO0U`gcaSv9AO_+rt+>1!82M3l_4q?{q8lLVE6aH@)q6$cA3J3Lh|w5*mrn3n_2W!&xeh z2djw0v*CDGYt=An_vy`i_$2%J*>A)j*_n?D8Xt~Q@tBWv8XqGY?B{i2ZR~v9qGbG{ zzwZFYD{trHE}2o?dulNduloqus}9S1LxemL!F;qJiNoXrr-{WK8g9@a=}i{&ItzZC z1ElDyac>NAPzT8er00C>_BJ2LhF-b~A22I-?2yW%U`P}tJ`_KGe3>^HXtBJ8(Pf(t z^N~p791W2c+kG?C~}q z$cA3J3Lh{lIPiLh00OUd8TtZ6xfK`r%I9(;4)-Z;q95oN^OGb^4r~)OJj}96i z#c%sDA7wN?wtqgy%f^P=`KU_C)crFy^U>bUM?Es5x+gSXAgU&=$+BD{mUYqyndd9> zF(-9R1Bb~6PL-Y|Wo=_-7{tn@!1 zgR7j5-<+?-F-lAg0=Z=t#-@ zv3FK`G$?)SKy)KB>i0uqCg7Ay$W={QcIqPJfVyYU;rNv#4igBRiYi}>1_iPk5Bc$u z1;`-IKE2;Gl&yK{N+4kM9Eh>r1_Ig8OIHB`W@W?=QfW{iQIz;lg952+La}R9P2>KD zrE?K5%4>YIP0)n-7^U$se@`jqqqW9Inv1V__1iK#A4e&fEumSMkCAphj*}VJ*RnYS zac!NDiCeP#XSXfKxf4 z*3DKiz)8z~gIUVq!BCbV&m{r)Th9rY>}>*&4ZUB)So)cAOrs3G$as`1e+XI$pvh@B53b1lQTSc>^r zVduj^W>k0HwhTnJ>O$UW$8vvtAxC^?K6;YGVe)}f8S>l?w(?e>+=4*L8`@B|hLxCU zbtz!=oR8_=<^$Q#OIP6oX62RyQn_V?L{Z{H@dHwcAA5V&GGZ^S%6#u3HKc;GYlpa2v7sFk$^KpohxtRZ0Tf~pQ?R*>|Gp=uX2L>YhEFr6P5_~Kc za`%vPh#wV5;@}Jgv6MSkxmhYJT<}HFzL2wovbEh9$p@^S^D)QUd>|Wo=_-7{tPE*D zDw9_!wC*6Z7%d&PM#U1y1#d3Aig~ia^r6-Z@&_9sUre>xJcqK`M{~%J=e|FnEZr^XD`Dl zCNuLRM#v!-B_EKU^Rd9&d>|Wo=_-7{ti%sUlpSp|hYkm%oZIPi1;?*#beYEo{}k^;cgoQjH`AaCXyLf*r6K}khO@A zsk*bQ5Fq4(F$~1D(zOj7_ybzsfK%m}Go*4$0x2irh4Pmpv&^y@6j(h6;x}&tfo$ld zD}mV0nHDRBnE-rS=~9F?uWeMU@?sW3!b**R1FprqHtxAb!1n~Bn1CZ10fVxaU;=(A zXM5&6hLTBk;ddtBnVo>~WJZOa?7>yOEL6y0y;wH>L&&_poJ2_YG`_Zh!z2Kwa_>(! zTg66yJTnbev9%1(PK8X?TM_{2IRV|hO#tUgD_u#zDlQUH<%7`W#JA;y?r@eUN_;3n zz$#jhg%}0jxvI9|8asgb*rD-pV{u;Q=#E_E5Gq|3~rxtLJNPuf0{v>=Z(KHBvTWIl4+`M6EVd`mxy z`G^;3o3ZeS%&6|rUl@oA$uJIhsg&{l`bcwvW6B?*@*@6 zRf5@83j*mmAN{<|2eP4;uEGb*qD#>m@dHvU7~+Ypka9A(({-y-9i#iSDKpWaT-AVh zzP2(0;imzSy+v*Y;NhYk6OeM3kg=1pj5s9ZoC^%ZD3Ul#AaJS-YC(#} zsx-4T*a4|*#tpfAjRXSHb0C7f4Fs~Gm#ze2KbL`s0W{S)oF&Q*9|8h@tlV^zyj#b( z(Qfq&M2N2%5X}d-Vj#+BK+MQpfq_V+0g3Z;`Tw2jJ z95|eduDiYHno}|_vu$q$U#ep-x>jUHNn}dNW!1Q`kQY<2%-lxEE9Jt`+8%0M*T7*G z9Zr>XB#?4SbTEHe*|7rF2UX@+tu3VIzBI(!zJzS(r7H z>KX-Z9heSZN~Zy_{!>2&qKyW`ljY4Bh>{u*o%SVUAVTaw`Rc7r%NCpJqMzuw}C)5 z^wL#;fLZB&L5eY7euM-mW0BJ}J)*ABYHu9|BCiI-^@}kXh+Y~HzM~%3MTDrK0Wp2S zJYInoW(Q&+C6lklnU;tUJ?%g&Av5attsfK6;hm7nGq6nhUC5mkk0C-V{#Mt(VFH0u zF=n|I!4*<0F63ElkjjV-OvMd!a!^yiNgc}r;>2D15!K_;Ae`E%0_sQCkoEBnhZ$KfoR}u zAdn5cbQK_A7PsiU9{q>p5kE-fA;7TC^^BFJIx`S;G$67yOv^w_)qrRdD>?)5y9UIq zv|D*W+D1DN<0+Z`#~!ypgqUInVgi{_zX!510pr4i?3bNo+u1^{i+d0e;_9q=1`ZPl zoXRS9vsJVp=g}XBRkVzW75vEnhaPy2O^udfj~C&(v?8$=S<7ZbR$^G0&}`j)ekfR zddFh|LNx+*kKfPh(~f8ad@Av0ZG?nH8UcOlH)R6u+X=`*$s~w2p*h-!!*&94kQo&k znV+lt$^aqP7i9TxxR4bmG67*EahL?)R7^EmgkB`1vJoDncm%>z6(KkLCJBJ_oPb>3 zCIH#cOIH%Gii<=U#KX6hQC&!7@6@J?1C7Z`XH7vHF;xR1;qICY#3c=g>Rk&m5F0fh z!iPWL@zikUM0Xf2jjODWrPlZyS6Ec0G!w3ln&ITGd zOdxP7W1O3<%D@Ax%40&vyMId{AUy{nzqf%vHuTa}fPh(PBOq_q{$s}PiFxl-NaeZU zidTWgtb}37%X#UFy&+h;&l4@1`ZPloXQNj9gr8?7{ok*P6MR!wj{{U zvFBTD1f=Ic6!ta{$cA3J3J@@hC^-$!eIUgKAhcj8oTc(y5LRXN)YQ`TjhAUQPDa4k zs`1gSNC)QQi^j)_d)1ha^BNynzkTObRlasU=2J3zR~BSGKHK?NL}pZXmsku$`SwDl zi_P-W??To~dISMu21y(yA2^kB>)dP=<8V9<0qbJgtpD5j?dU^5Zfqd=fb^UXr?>e) zHuTa}_<&it%YclZhu>oYJ|Iz)_|Q!Ur1FlRCFAQG->;QsK8|R740`{DS5^Ho{paV# z+m>FeiTH6}e1u7gx2yF>afm3%;Y&PPda z^MP#WrThO8ch=!iBr-Q67qhadrh43+@FT@LQBSQd8;1P>5&ad&rL z>{riIlcuKn`|F#%Cb_OYr|EY&r@FdJTJeL0-g>-$@M2DU2g>zM4&yEqX!fev z9qq0)GQ6-|g&OZ_QCYE6h7_1aU2Pnr;`x+bF##jQeg6Nf3Av<8JpWfj6# zgmHe0$DskEBR3+xic4G`TVnQg6e7DoY%U?Nt8{Gu<$5?20;s%A3s~))ONdv=f%?}{ zGKsKqX$E%UpXh-MvjLU+d0UP~M#GzpnaQVGCeMG2#Z2bWG8uQp>zep!#W?KV;W}a8 za!yFAVa;R;ahS|Lmz&|ImD`%h^dgMJEc=70i&Ix(;{?QX%_TNJ%uM<;Yh++^WfHq) z51P{kluvXxF%dW*c(HhIpYSM<(FtW2hhLfz_57z*Dx!Z{D2AS0MF@nIN5DW1qc0^~ z3u8*;rFkR9=p-A^$jI>c-csZsLh>AhGOZQwT&o7ov1T3xQ(j*;RxXGfO^FxPEJL%Rg`!y@DT6zD>OC^iOnSh zc9okupq#oa`b_<8Ky%1nAn{(#CE-^PL_HTGRYVJcV(8gbgg{t%`~x(bCt*y9ayQqx zZDS+O$}toomnOvc;1U$VR}R^%VXVYYX^Bs#Ni1yag%D1G*jz$jS9T(DZ91TAtFg}rsH|TKoZ&Qu0D3M&x`-A6 z#n7{>2!XIN%m64m+E3ta4v19ZPqZ+8f0$$Z0yi`^jt@&rKT2qRRGxdB6Vd`SKZaLb zR~;2bGtG}*j<)n;q1BJc;xKdK&TN7!h`-g3X(Ej87nGhtEW9MKbw*;zI}(46p&!p~ zH#V@bKz=stnh(I8MEPPJ4(UQvu7$xK17NIUrXN7h{kWebf?u41V(8gb{6JW#Fo5RM zpfLCR*&S1R79S zAU2l)*fkqPP8(1@@#DCY-%*ZC12%4N8UXa%faeiy0E(e!*EArADN!1g__R6lB8*X` z4e@zy6JzAxJ13z^@YRHfa=1H%*rEwh%C8=Un4}4@XF_xean344qdoL#qh#VquR&L_W6B75t4MvsFM<6zr5ZF~7@Br(gelpoZYhukyRXKe6=HuP(vKD3Xxreaek}kr2(Pwni6YA+KE2JzmiLw zJB31Y6o}0w1a_6X44}N}=9^N0@&V@tJeC0Z|1yODdM?EKh!z6H(6g%ufw0UFN2USg zKqT>s$}pxx)*o~5oT^-rrpBxi=O&_tn63$txZx-YaY+-RPE;QXu~8EuELBL8Q}QyyF*s`PZ^I^WcIJK^aBR2W+|KYagM$SG%E zG(UnGjG!OqH9xXY+EPc&b-5lDRT)aA#k*TkwNj8*n3)HqZ~TOsasjC ziCrrWGvD`91N`t}{IK@UiZH(4h&aroy^6#l@rWJkN!%a8#D1*X%)rJ1`Ps0mtZfOD zRWEB|pz>BbU{d??@R}It`48_$ME~$m3_ZJw9|$Xrcc6UyBid@A%%AeZL)5$%vOAXc z6zNPHg??Pp{79Z>JLjjR)ck00V_s!c%pWvA&V8s&KkQaN{uYPvSvrD#q_Fz2L4@N+A7MEb-M9`Vm_oHkTjRRfdBB&1L!hZ9ruyLtxI)rXN7h{rDNtexMk7 zb`?JmR@(AFb2->hW(cXopQt|&HRov99q0B6KiW(lkBa%R?uWBH{m7;Jku4kjhzuAu&FaT3aTuQ$@#sfRs~`787~ijcA_}qmzCBJQ{~yy2pyz)4ifBJj3_ZJw9|$WKZlF2bA(RJLQa zt)H0GWq14)tGUr^R#NjLSK}>}P=6%V{8-boGyQ08^<$SfO!-vv z>*M-T!s)k0dT#VMKYQ7ONB39p9QZHwu+rH4eYD zn91GyZZ|h>!A#cDGWjxkS!ObumdS2uKX8^$H)|&2G;3}|JDH7{tZB_;A`wPnGNxqe z{v0OpQYvER@e;56!%TJ_*WAG7$|QE>Er3{|$7ut~%M$zcfo9KLAfuytxiUHB0HU7% z(r!icFAc@ev#SV!u<}a-rs0Y zjP-(k%)2apT4G~?{A}1Y7Y%h1m9Za)DsMRe?g%!2X+ZsJDTzf`X(9vV3lzkgSweXv zr3yn-ipl5Oy*@TKk{91U7C*e4T4HC__hVvvYKc7;xhWG{RZDE0lyR8YiPpr95Qlkk zv;ri2mWB7zyjo?X+A5T?YOn;u3~UNAFvn)rPMUmk-RqNZlR=}Qx6z*NnE zn4^2q03XeOF^e+Ofb~`b)``QUuhEnSOtBiURfKUu4`$;jKe$t3{~W|c2PF=>MFZZ2 zv@o!_48X40?d`MyW&Z~oIY9YzlP?ef#$RI^0QB5|^$~3VilJxMG$4p6QLZ5P^v%rZ z85S#^hbqy!Xu2UPSE5^mrrVy|Ee!vE+tZI$njha2CZ``uH9v|T{9Yb4#9+;jZPzw( zuGN04A1B3OYL9tP2Q|bJs~_h@7^gdDE(#GlMoZ$Y+{7aBB`$MpM-37DM@s{n%Ma|D zt$HV;@~MhwnD`T=F5-z(Ao1EK(+~Vx&;8gO(SD#9dUh2*5SFd=A!y43&6&wzMA=s3 zD4Mro5oQ0Fm^I}jX5ly*-s|Cm>9~*<*Wv``oniU`^xTi# z5$y+xp=Vd|17YQY0+a@bUr;C$rreSsYX02pj?mDS#>MzC>Bm&fj|MsRajw-rnje#| zEG>r%%6iR@IBy%#k9Sr-Zi>UKSU8S;T(J7_P=s;16U3nq)!s@x5|=paUy1!5(~lGa zvAO)ft}^Hf$N?4yIE4l%o8z2w2P}No^aJR*AHfmr2a2I*SMlR_4xG540A&j_6n+4a zO8klX1E@T;Kb)+Uk=%FYC|qBbYJSWbQ;mK+)ciPCBrpBgulZ4@&OJ`OidxCiof;+% z^W<9+`tiW($5|1^_Z#>Jh4@-pVx9!V3sohq`bj?u3&h3(`Ps0mypakhN1(Am3X~UH zHaLKF|6CP*eF1vz$Nq@+1I5s@Yx)tw3>`_2xiNe=gik9K22dG+V{~d|6x@`7LTuKA z*c5t^Gsr$^LcDP9E{h7|tR{rdw4M|qu~mo!;xJK5FRO(M%15gZi9{IZ_ijQO@Oh%d znTd%zW=T9yeKRg7Z3SX;34vW@zy(m&5FDciRA%)9hYvM{0D3OOw1^f0#n7{B3K7JF zDcv~uw7iQKBXB|)MJn+pDhx#B9qe2*I3jIrWz4<4ZX_y2#PW5vpoaKRptXU`WdL@~dFM_>l@U0IDpSLNNmH&4 zzhnSCH(+i=8-QZy*)38*#|B6YOH1rF zT;j!Z6e68KY%U?NE6c~17y{+gQZdiP-v%@vdIl29bTNfM)N>&gMYIqohMrwT2!xeO z29T3&hj4jspfU#Q)S}kLwP^Jz#Ai*2rfCccQ9=`9#;IqeQ9~rrgh=pk5vPnbvkGxt z942Vm`5LGpid%)aEy6gz!_(7%SVtum&PZH%Mq;$56r!d;Y%U?NYZl091DcEF`4eR_ z_yQ3`yKQ#~@hUk`|5|1yL->zn^GkHGgeu7Af%wO!iFU__7p;vWd2WrsPs^6Vy(_mu z<>{PURa48P|HuB!WL7Pc-{a@*UCFRevgTT37|S0=G5i@OB3_dw3m&n$Yu{fTBrULdhYv^C*%Ek5k|Pit{R|FlpH zJ-dn!2%F2-hA{{7iSTSxu5n7VG49Xyp#dp11KMs(O9NVK1}tb3l?K=~15!G7a5mKt zs{u*HVYXy`ULC)sR#pR2h%ioQy=*+?iP}kwo`d+bo5W@O0%H(IIF&C0MK&-d?MNa6hqH$wG>Bf-!jB3EAH44HrH7TB_enD6Af@g zl?Hh3aczt}M?Vcmm5@slqS);qPOkFRgy=hYN-0#X)ifdAt*k&HCRv3jB@Q#8!2k-; z(<($65yto1m6HZk*(k9`ZsPY{68l}J5Yq%=V}bl^*i~-OfU?Tt6P@2tKG6YgT4D+T z^jwIZ5iJCYp=VbS0%3DrSr`*$)}eMs<;!i1`mq9OKuOJjvl)xhfMJ>evCpTX0nIf7 z#yva3*;I?H1~eCk$v8VI4G6Fr;1FS)&$w4aBH92HL(i^hKoAQpGsI_l__TcLDO#jq zj4E>?l4Wri-H!c1A!=(vJiUF0v#F+QLS&w@x+JQE?wSzGR<)!M8?8d*5{D_#aB4MN zBc@q}C@8`>zvJ@LfC@DwmMTbW*;wM6hZ`WosYVV1n@b4nD$6$mWdod50#F&64SZ2D zD7=*b^jwJk5iJCYp=VbS0%4^A4m4*4gfgAVGd)Dj#gFZd34RVE+4%XxaLI6Je#~4} zhkpE}`Ej;hA^PF3`BB^F2`5(_wE8h!9OiM-)bwMy)sO#)Fi!W|LKI^8Jc$>(uSO?g zg})?b{6RlHEO!{#Tz+8JtO3OxyFjzg)Ssv<-iv6`38o)F&;1C9Xg^R4J-dn@2&;GO z0+qMSBZ^ewPt+ekWg2eR5QpKjI~)Dzt@-if{B_Q?+NSxDX~cmNs6VD?ek`5WmwsHZ z`q4`qrg)XrRZ)LzwffOVgz^2x^`sCNo=7a!i`e*`#FQ!5p#F$05E~2RN0c{c^U=mc z?(KcKsjzxbb|TYfaWvbK%#%Pzr(K}h2!XJ9V;RC6n9Eg!5zSwa-I1!b$gWYALd?*FIGgqZXZc*#gou6mN^w*P zn=~QDJ(|c_U>~hQWE6+VIO9MSR0)@?LSzwPoZn{sXh6zQ65|dauA40Jk90w(650#I z<`M$C=53RcQF+tBZXiUJ2M@r}{Y)W%o(oYoqJ=;)^z14^AS|nd$*3WKa@>iiA?%KL zYug&To1XGVmGGBlfW7xH8t_Cjz%PAA8gNiE;H^Cc4KONOdWMsU!;F7elLkDt8jwna zaY93!Jmt^MOYAp@c=v|H>q}`sU4htK24L4*kJo7fDl@NvavH994j0I1*F&ZOh7=W;BR&gpmP4F% z2*lL+~1bsJwz~h7iDY3D$;RBY>U@(KMokKr!^}DncMEpT&$ol>ju~ z2oXv|D)A@U5Qv(Ma`9NAYCB`ss|Q0-VI0x?C>mofCw9f0>)tcmXZuk4abNS}&FTE~ zBb(Ka+Tt+d26v<%wqKT>;d&yB?>8-gLiqSftTdeX)hY4KO8T))AT}1r&xT#IQRF1b z3no_xL{#2XiRpiVjGk^|`hlqDezc5eKTr%kyNVwO%SL4v_yLqZC^337jHujpI%c&q zqGs$(Auee`3@@IALZsA$*!wglh4`QeQ9Md8=cn1NLUa{}xv>6iB~%zGtU`1bVVvKu zBWS>=eG=D=B-S}5Fw0R9arvgS^ZwdkQT!>Z? zEd+|8XIBvdVL5iSFN6Tfrxc=lCzNPDmascUJP?_!^kWEWh{u``{;f7~LRv0Oh+T1J z*>MGle$2h2xM-H@6r!3{h{@tGXU`3#5ILxy^9p$ zUE=lzHkT0C6-&1)t+ZV%`X^>T2$cTc#9anZ8LSG7|J@V<=(!NBBU%U)L(i@v1j5Q- zW}qBfBxXN|=?((TX1Cq3zCe59+@f(5;)^CkogJkpL`hAE@trbKh@_ejwt!2VNY~sd zM6fu_(p<49L1%DPAQ9>R(IAB*MxQKcH-_i*;hc_t0$mBfdWiO)AljJ0DW8fOIsVsm8@yRtx{-^a;l91g>|g-jx<%$^1|oa4&m zlmkG|e_CxK`lp3r=-E|-Kv;RA1C+Dv_|pQ)+c&YAt=+NvbbDiSl4XNY*QV5j$d|V< zg=nn_(d}k&3SrlTc>3`bXP^zS3UNgoX2i0L6rz z2=O}yTonK)o3COns#r-)pfVF6S(*+;p`v*yL@rH;&2{c^%9*bw#LJ&Yi=c+6rU}t4 z*0v@VR@1V34vX6 zsDRT3lzvbMpf87Mai$1xdZG2MU~^E(*WSRg+ecFiSuoJ45=TVseSH3aa?2vZ24 z=R%Z@XdzGxJ-en5K}?BqKaWr6XLE&@44}ChrQK0yR|n(x!pan)rY1z??f=R-M4Ax8 zJKipg8p1~t;@8j_oMX1$Dnwgxm^nF*l}8OR#VSM>5yts_c6kZ<1^eESxacae!!wD; zpGhH}3L(T6E`->XlRv~@A|ZspV>OD3_NNp=ptp0)UH>lp`}SHS|9|tnN{(Xa=~RS3SovuI<+}pK#W$2G z3I7hF>P6ICCfM#6*QlehwOAVp(L)oWK>b7%Vv{CBkH}vN;g>c+6XJP_wVaK0#wx@D zahQ=uZWD{GZMLIPUuY2|wTZc@97S|Dhi!hMry157FT&!sfMDbhrwXH^O2XwB508 zc}Js2i|0;M3I3V^Tm2Su`qe?rfY%vE(trh;0X<6CX}}$;0m0%h#*=O|AjE3GQ4vN8 zGv4DVUwT5~rTfGS|43Z6j0Rl1APg59{(&$6yYg0EOq6jFYje$}2e@BD)Ewm*Nc_0l zGyu`?Gy4B;z(05KRl@(q{+*Z?V=o$jV(8g54G3bPl}iRbEq@f(P(uKfO9oJRGBWOM zN8>_LC;gbB`BCrB-1Osu=EuZa@#)7p&5u~04|Dp}TdN-n#9@{%|56q;#CfY9e~B>i zJN_Ys*qFQ%vGil&@Qf1sW?7CJBDX+n_y@ud>?-qifpRHycD4YOWp05rV{Qz;f&e}D zBe`4Sto-t2_fXS#(GL_u&#vMJ!pao{X!gH`F@MS!ow#K?8N(w-qYz6pA%3OU$=O&B zG$D$IE+~jgMzAKt&bxIfM3gF)?$}h~F!d&nq!9P5LZlU8oZoj(Xn@gK;>u^lWxXU$ zT1_G92*ieeAcVlK{5gn~3!Fsx?3Clc5mn}85}TMp06iBXwVMzLvM%?w5GaP8T}23l zl|i3Cr8^dgRN_xGDS%36%gsrhj8es>4!{Lvljg^sdKKx%N6n8H_p!mo#p=uS zy!C+?wS~kquPDUo=A8{}E+Me1Tu^|8TjPIV4FOboXMv&RHifq^fd91+V=sGM2oyul zt|A1&N{<2190M9^11c?0pgB6m?il9mY-IaVh<-fK{8$nHDJP_5*ZjD%KP*2gj3~$5 zJ8N5C8BRYcTm6_W4)b~Bw$i9DvRVC@DZ)72(?3y&fW;Cke<8M5BXQH7MQDMZTiw~f z=JEr(%A^7yUn|j{D^CGeAH~xl_RRrbO)>oddhSO$w+dtTE3f;3V(8gb{6JV5Fbuu- zK-qzC3LOYQWvQ5XM>`w8vWE0Sh4E1nVrZFu6rz|W#LidEC`2Mnh$1oKQHUm1A%etV z&TJ`1A?#KmHiBSJ@<)_XDHkT0CHLnp)M&@sZw|kL06iDthno7IFmAW&V&qPaC@!?e=%10ogSJ?p#hm1G;Mlq#E<{Pt*{VH3Q}@-pmPU)QHJxV~O zM+w;bxakM*zxJd3Rj>PjV(8gb{6JW#A%IH97!aw%pQs^#$`vH`uP#PN;&*=VA3Q;g?S7O%d z#6R;%yg6_#niM{Nb~UiEKz>B?F2hNbOU1BBfe*^-3+oTy_@rCHuOL9r{rKfpf6RR2 zbw5xHJ-dn@2rEqrpqzHZE@+_AEn=_L)u`0kpF&jEggDf{0EL*W3Gp*aG78Z}6Jki| zlboNn)+$7GahN2}f0jUnG07@KeG$g_y>^2J)afg6@-1Q;e~FL2Q;2y(yBgSBLSVPP zyvf32E1)C_0hEuu*`xsO?O+N4^jwHDZbA$iG}qfr3KT=nt|A1&^1=3a+;jltg5vB+ z2bvcYyQ9+lu14^PSQMg#CPc~k!JMDASQBDE_2qeS1sSLb@v&VK3bD^BL{o8?$$w0s z5R0rrI7ArdxBML%;B!#or@O?QrzCy|n1>po*U7F1HkT0CRo-O+jF$&h2894BLxzD< zHk(2KJs0AFn-GCNyeGHI1e~oEzBy!EOD6jyOL3e^;RJkiZIS^(0v*(J-!dI^+RG{ zN{KO|&W8{eQur9yTtZ-1SwSDDG%0{elLGiY($?@x2GDaMF1raaZP+|-*AOU%o?S%< zgq2GM&}>qKF`Y^qvu;rzV^H)=6k>=b#FsReIbH35CPcxoJ$X<=%+rL}^w5_=+_DPM zP8_EC^yS5I$=Gid!bgO0eiJ^X0i#+=Joiy-_7h(hL~CwLJ|urx|dheN`Ipw`M?vA>TRw=(W{=bK)>Jvge}#XRQWY z6JeatLC<)~d#sh1_XTmtc8LQD(17FuvAGPuuB;N4!vLV1n8jt10dUj0%f>>zfE)<_O-w_!#$)M6q^g##^XK9)rK9dGh8p6o)sI&qjPG~vC53qM zuf$oeiL;}1V{}b5`cYgUHWo;{G(qgjXVqs>B>>-@uO$+|mqr7dKR1N{{?|ezF6eb3 zPz*htiVz4Z*9f5b>LKx#1cBznJu&etLpNi^hGV@@Lu}9t$aH)#4S25^(0YJ_283w_ z+?bM>1|+Z=FkT#{U&*R8;GNZgi6V>>TKz3g`MjzUf4(DbtS|A3g9bDah>ZsL*|2L) z_i+-3mO*cqcvA0AR8}a(hkF&<7T#z8dM?B@w;G~yb*~G7V(8gbgg{u{IB+gI&|Jef zlo>K_E5e9oU$Whir&l+l(wheKWavM3)DTf4TRO*!i7-z0<_{EN|161}J`o=;k(g-TEHo;|3B*P}oJ9HB3<`mW zoVv`ZslYX3Od)`t3vt~|h<S`*^u+uRhQpjC+U;xMxpIVeP8s}Pw*7~e1D z7aH*JfyC2ai8o$JtWb6~gqR`_8w=z|Gz%owIuMbkSuysXOBw^s@!Vpq1A&_^ntlL1 z_hXlv9~<}0@^+&V#n7{>_<^wO?c^HQKv_eG{$R1Vfk0)^^LlZ*8$fRf^rQt44v#V$oqNO-Y&B!l{qK3#~6{58W?%SatTZWr^2GpRfU}s>A#faqv}fc1Zr|qJjV%UV2L*o?hv0U~>t9UFkmu=mO8-p4*2_ z3ZU835oiO(JYWg|^jwJjZbDSN?sXwh3_ZJw5C|)62q1EYKT$&f%^KG3*!rov@hpD= z3Xwz;qD%E7oMzWd6Jq(-H91g26x4*skgzp{7+@9RfH=(V;Aus0$!Ka7;)n?2`|XZS z1J0)DLF^l425N}Y*(4V7pN2L>I)T_&AU~p62RMmR2)q4LydUj1Af>>y!^An$zQ#?340;p6NK;;T@uwoA*pw_}3xPoNW{P@wa z9{upq{IDk}LO&{Mer(V4jI#yDTKzaH4pZk^8v4=I>c=G!#_7%;jY4efChJH3bTc0mpbQB)JcciT)m(9{?-Amwg}6=M<;9hP`uB!y^osE2`#CGfLh zSDB#?lrPp{Ul&lRFn~jXOd)`t3o*k@h_q3rds_$;L(i@v1j0&R7tkDFXLqEy+rzkU zd|P)^2~{-%>fP;1114$)Oq^Pq26WO4h_xmP4G6LtkXsyPd7~mUV1m_vLL!V4`Xv@m zc@|qw;@UXG!U-kzFDg*H>>)u<1DneL?3&N2#mgQ9DkJKEO7}N#))&(Npyvk6b~C_l zl-CVFG4$*z1|Y0d2|(qN0W>cecE|I)J&m@1l&28QG$C$h`^4E`3pF89UcQzMRl)#G zh&it(b9&$&s}Pa@>}lj*aIg@ngauY1Vv8`&uOl7}sMc6w;`qeU4v80bQ;5lJdK%bV zLSWY%V(D)KDq|{v>niUIZ!`csH(;Tg0g3E0yj=&N7#ek z6=9sv;|X}m1OJjZBoT4SdWq4`(}19LJq>Iw1F&np-^OVJ$~N>Jv=V@vw2@0JvKUA_ z`9D(#L_HT`k(&^`_IOtf(R8YJTh;xQg=uZ(98rB@WXl>-B=DA%d-bOcG&!za$i* z?K_DNk`jA;mstEM{rKOvo(4Al13w#fWwThke$q+2T?akh_u&Vkvnt^CAm$AR61Utl z{Xq1;_G86)uls>w=-E~LKv=nC0A<(4RSd!gnwN|);sx{#785Hoi25UiudyS`V;|HX z6E!~ym!8l0fM+#7dc6#wA3>TQuc8;CAFr%_^bm&`v$-?h#9)E|h-NB?51f!*;}XJ4aZd_VfJ zQ1jz{_H6XyuI5MDE3xUv9?g#hZ}xL~;4iBm+r?oDFMMAB^~W8nA3H^uUobU==r~#8 z)-=Qpb0lUvOF!ZX#Kr>o*|2L)gmw~@g$58ce-43+778%^K-64iKhN{21qQY3O39;C*h4TU5X+m84V@?)aP)=z= zG|gU*jz$j zS6z8Rpz^X9M9uM-f&8~M!%QI%^<0QSZbBSB>vbVe3_ZJw5C|(56rlVCv8MwlJI45W z*9TF18I{LOpb+~tAr3DtLm{FraPJ)dRXa0vBE0~ zF<2lrmk`)B3*@u`l^OzQu0$Ki=z^}M5QzTQLTtM1bsWa#ISCRTCn^rjisQ(h2v@@x`HUI03MtRfy8!F!uhL zDMS{l5amP|=XXgC8c^<-#D=+urOrugcWW#z85_^`GO)RXz^-}I?POHe5aJHZpD4!y zh_@XF63^~1g}}e{T!;X-8sg3?uM2@<=-D-e2w|a>MkPM2+;jlVAC%qE>QyhpY2>32 zA2cC8rG3EpfObuY{HKp+LJg5n6Jo=oArzvqRfwMAFjZ%4%!eAHs8xu*B8>BE%R>X& zB)YYOSEBC;zhnSC z7oxhG5WjAX_4XwL#n7{B3K7H{C~XLQT27S}vo=B*Megw@ZaNT^edXdF&h8jfvbRyR z)85XgFrue%?dXf&6UPRl2@_vh<>BG?3A?4NM^r^<0SBZbD3G zH_qEapcr~O6(JB-9%};SV;xTP1Il-2tbqYD#`iYHCa6XOl4=GRIe&1zS98sPa#!zW zL=90$GhqMQnVbOVv>LEl9H!}_&_7W_G_xA8QG{_q2j1W*->^wyo?FC~dn6|9DlmcV z&Fg+MX%>?%Satke*|t;hR| zx4(;bBZM)X%2eQ8S9%-1&;IFzDj}OD#LFn-C`30+i0qqtP>4#J5Gzk)pb+D%LYx$b zDKnrEh48ToaY2M}e(&C<0n2_#oOzdcBxWB*s}7?O2?b)K5aQhrVpn!;aP2-*`7K>VU!4Qyw*&JcHHl^Bn)ICGp1t z;?*V+2hHXw&m$0<>y%?R4aZsYlmnH?oWPo;_l7qMfS#Z7hHj_);V`eCauh>Pr+Lal zYzWKgY8(OsRN9F^WrdJ0eft=tI=}3QAAL2=fIR_AIj3)uX27SsqiH~A&49jDiqn9< ztp>#H*T;zap$83^Xf+^-2;+oqdc;$naDl{*Pl(S~NL;&~1~eCljRyGHuq(^A5f7(< zatPQJ+&BQ`3RGfDv3QfYK<7kL2;hG$M6x+v7Xro5vug?=-efMq%EM`(ys;EhnZ%pS z1u6~0REPQ)*{2Sq5Y06qR<6!NAr@&u+-;JOLO3-c+Vnb_2UW#hs}Om`VZNmPHxH_W zg;pVoh%nA?if1&S!ZV3s&xtKQNW67~LioKG)xOwVLST1E%0ERl$7PWjWp~|O2mzGi zA;hAmfy5ctOd$~UT!=<)HAJ-yUKawz(6g%ufw0mn04nQb17$0c-B+y=_!-+TMW+zm zG$9JT-o-h68#Ez&7cEMU6F*K9;^p@G6e7$jM0;_V(d|c5i1k(>I*KsP@9>v2poU#y z;nzg}@)9#vABA?}oN|5!HkT0CHJ_z98O_FbFtDA7sPtd-)dVuSBm2JaO9rBz3(?q3 zh`~p_E(D69XIBvdVdcgFXuhN(lqo?f@h2(_M3t5Fo3#=DHum%mxPlDP{P>!wGW|H9 z`BCUXPWmxV^JDY#Tb%KC%j!p8ahMu&64H)*qM4qI#d{c zYeEz$+>JuKwh9p_4s+)2qTINGoV5xuU4(Id>wTaBqyLc@{S&e5Es0a>jYfrW{idIR z%_RhO<-^ByXi@;>Xb`TG{X4o3LID3gYzhJNT!;d0Li9WBbsD zKxJ7|pwi?7DwDy7e)BUr1_ZT7g|SHU?c6 zpu}6Ts`WL-2N$6q8#F&`m!EM0;Cs!F3Zu`YMg0+``4O@xkbWev`cYjRrg@DWxln(+ zv-(j>gz^0{e4`LMdr7?bo!Ebn#Gx%a!%mIP?_7TX(zHL9ii`;G|X{Equc13m{!EEQ=29$hay zE^%$tF}R>45Qxns1a{5$zBw6{JvrhI-Jhs*ZsEiEH<&^IJr|;=TZNJGrPqZ(G4$*z zLLjWPFo5QBoKR-Syr9?}0T25cx%#9_YwJd+bOL}IHDV?-F|_ibbvFf&d+;)A%LC>VRsXvTC_3VzJj0_dUh2d5LRwUfU@&KRGMNj34ur@ z{zQcVlrP$xj}~aOLj8=`{jax0g>g^wW8CB^oDY~)^W$)-zVsu~N%!9H@{P08kBU}5 zVu{0CkJ6HUWU=}YM}+bHnnjmFG?y4R2Jv_Y7Z#u&eFb7;f&6UPl~3uG!VjQ)%E=Ze z(0uD+Afq#D><@2YAnLgv#oYWDoXYEdpcr~~6+aM`*VyqGQ3o{N)DlLN6~+<>k$prz zB*Hkq8EesiF`p$~ zs!g04xj&;7eo=_9Nc|0LE+Me1O!Nab=Bk#Q`S}|;rvv!;u_*-5b0Lzs)ew<}jPUjq z1jW#^s|bOxyzQKc8UiTqGPueq&}>qKDbX$PV?bIFjX8{dB+>jBl(7)~Xr}qG?ObyD zQBd=v;ImVl9yq}2$5?TgQ?nw`kET{Xrid_3_xQRLVooKArRx*7)RCAyFc1~S)7t$F zY%V{rYd*H}XVhGsOROCrqA`jb2)|?iJr^RCn-F(?d0hw;Lr0p*T$X;wdP^Agd6sL>T9{c@r9N z>8`|h&4|07OWZb%LL?E0%_RhO&8}ak4JhwI#oI9biRN-`fy9F6O(F1M&xLrANPYQA zyLdyrEd+|8XIBvdVdbU+C=(`D0S#qJkV^cC3IkDPJXNS|fRW^0X8KW8^JB)pS2#Uz zqUOixHTzPc!sw*=QS)GL`VnOHbW0p-2A9N-Rpj! z7GPBGz4ls#I3W&GCRqUrvCt~S1rf&i&Doj;B=?tis||6_7>R$)r4R`OVsigw0k&tFrn3t_Tn%rPQ1#D`s2OT zk8UE2(_O%qLO7!hBtGgz>>p3!#K!@+Ls=bnpn=Wh2X>YBbO2>>+5P~^XP~^k0FQq# z{Q&;ge#H6gbw5xHJ-dn@2rKmmP|mC6oG>6#i9b<)0A>Ez{s_u7(CG8^-xjDpLNq_# zB-p^YgwYqd_p|2;nUM_Fm)n{jYpzzIADOIv1dGFzA3d0UM2lwWXFnps_31z zCD!gsJlRrW@K5@YL?AX6$j^pdWk%3%6m!DF6AlrTz3`kf2rN|LPz&SSqTKw|50Vsx^UDJRdCQKQ6gHJ1CeSyjq z1gN~lc?AgnB5;| zWWp6BtJRNhB8=1havOz6`C9mLmPB!=y#A29@CbNPW?bMTeZ29ysyAEJf;Mqwur zuOPr|w@p8Qp8Ijp&5z1O2YI`OKr!^}Dt<6rEsjXTXtXeZa#3=zf~a`Gut4RO^?8y( zhI7N>=D1{h(1iGOtO13vYeM87V5blXH6b=kdBM4ajjcj_7l)}@GChSTY84_{(m_1G zjdsz1jHM*T+(S%UMPk&l0u$Hfnw;{RfIrTd87f9_i$qRP$*M^RN_zgfv7S$AWw%uM&>@b=!cQc zy`O#A_}iR#SY7kuX0gLbP+?@&{Af|%Nk6(+{U|36^Wo>;8Bt+Wv-(k8gz^3M?WGX* z2@-n;6BEspShxxOnD)Ox1~wMR&xT!PEGMu79|4O#B7a8Z6Aq5lLUhw$(+{BMeq3|& zV@cV;-mWlE3_ZJw9|$W=PN4Z(i%@1rxu75_p8>7HBd^Ar2N`*G?`VelBbnyM-{-s0 zj~1FAkA~N!AB8nPI?RhkKL%R;=p+vFqq3cTG`ITEQ-pE4vmBrh`L9a68ba)FUt;H; z^yAdMK?XLLAJ{eDh3K>aWtRXu)qqN;8t`eT=?Cz?_TzjLuls>w=-E~LKv=0ifO0mL zc%%`=gekqOZ6Xaenw_pdA+l>iTz>SKv(UP0LL{7ZBQYwB%9;>U*H7iN#PL=kdWgg1 zXmL0LDvWMcA^M6i&hMl{G@wN`iRF$Er{tG7cNB%Vm2a?t%_RhOm3t7N@{9{;j#CS? z0e>Vr5`IAedM?Cuw+bVguh)e@G4$*zLLjU>0|m<4GWMYWkxKlD8e&N8!A9kDXPcsi zD5eQs*oVk`l+)6pbz~&MHyYd&gy6r6a@4$nh^Xg6>~$03Y4!o$ZgQejdUh2d5LOmT1ezKfMkxKlD z76wqcB}rUth>@UOKl;%_^JB`O9Q0$8=EsQ~@#x0{&5x?(4{}=K8LJ;T#bNHg`j`$C z#zw0j1w|O&FV8s&5yK(z?s;MqABo2f(T{pvhZxvcAU_*+&2AqjQC?2@j0;h@dN;>{ z1AXh7egHl9W1pKJ1=e}p4-`YsuHpy6$~YaMvc5mi>}9e$a*P>bl+P5ILilS!94N7k z^AHbeLVSBRHzBSd3p61HMy*XD?pTE=E)J7$<8TTQVilsi2;=q!(p!rfnw;{HH8Ra zN|d$n@M)z<0aO% zJI#rQ_ca3+AKjb)Rl+{afHb!|(SXP`Ej{V&#bLHjn3opUhHgb+aa;ARsVl^uEyH45Ke(Fj$-22F@9 zpPNyL_nHu|R+gp^VVV%#_rH@9%dA59iNi$io|QtpvkEatgz^2tZqWeWITDB8As$>N z@n63_5F({OY%Gu;QE46=H!n%;G|u)1Zck8r{-YzCwg?epmGNL)Yl0M-rR)5f{CY*!~NJ`0{$Ffz2fZ zc9jK}e={1@g0DSNgvZPbq+MeR^I{fO23f>ks}rKhqDO z=YDi>^TQFRySM8P6hqIh;s?UYT_{j#Z~&G1186QnW_PS!<8RC=b-4lRk9V3Mi5pL# zA4N1j>O}8FKjMeEkF*F&lbL=rwED449H!HWCiJ7Q)sNjGjMIH{Fono-PU5to#OK!} zu20+p^+ywd*j#>KSLs*>e!?nhAL$2B={N=U3o-owdhSOTH$N^+^|~J@hMry1j}RuT z^7i*X{&8|}FFuXj;ZIZ;K&8Ss``O<(`>h>?h?d^HC%ty!WE7&RCd9Zy-{PUd$fyYs zG~19By**SbBA6o$z{t+5}K>>O$M0YnKY9#65?Fs|M(6eg_5yTA1 z3S&C%Q1Iz8h4EmM)60NLPigVW0mjdwuj`|RNTLZbr0#OgLu{rAvE$bm3Qo?i0a}nrw{v5h^AH{>WMJU@468*V0aISZATIt4v^S-BZXMlUz}92xrD&3@{|H7 zhgOJ@Mu9fq-d3goK+g^6;buVST(28|V(95q3_w_EQUI0VyFlfV0hFumt;aoT!~X>s zRl5zQ5Lq=Ljt2foA$&9;A{R_dAu4J@1k^ard5B}JLUa^|N&e+qO4JZttwQt=VVvJ2 zqiMjJJrYC55Mv*aIO7!4H92A?TVX@qyn+AKz>BCC&x)#^m^6N8b$d~3m;r9U|c!glmZLQGW`I0?niYu zKW2aOx*sTpo?XQcgq538pj^a)_aH!}g#k2&rq~^iPYp91oz~Vx{n1tPBm~DA3sDGr+eEB3X$}K#I7@muYO1zf0KR` z5s1y@2X@Vs^PD!IvZ4V{-l6aw1lZ_-=?BnrKWe-AF}_(>Z{LHU7VrijQ2@eaoO1LfdDP7ngt z9A*ju^jwI>ZbF=D=i}`f0>#j?YYGv>94J>1d|FniT;c+#TtR?Jh4Fm*a3krMdh}zy z=EwgQN2edRH9yYOeijQA#xBi|TAdeh;^7agAK%1b9wj=T3>C&Ls~=Hz$kY9DA%$pq zOXAYS#9~h*rm58pe$;wA+`#7Y1G};XDrS5*8SU}-+nTrM_<^u8-XAF6b?2qSynuJmJ{=Eus3Y3N7fCGP#~cS}T}AJ;WM z+BDqGiHGT|el!q=`4Z__QdAg`3`;+Ia}mb(+aHZW3?3xW&mfK+DKXkp`f($0gnwcgZdUh2*5LRwkf#ztr&)0!XgZm;3Q!-Se2)h17li3`dL&5vU%%hQj1RzHS|!#EoB zrymKdevA=eobGHk3Nih-#OpDMe&;1ljNK6zl(pwZ7}#8XU{{&34jewSf=B=#X#kaH zT)?oMrXN7h{b=J>e=L3Kbw5xHJ-dn@2rKmm(0qG>7^x*t=_gzLdW2DJ;0OwFTNC2g zv?3HDlO{xza;Yf94^4<+&CYP9VL7W1JH=sA7*Q!iMyn9}MHuIIN^BaiC21hBLR{j8 z^b%`Nr4VrhVsid*pC@w3lxY{;!j*qfXa;1p``+iWsT#}k2jhh>3t7!;$b1pj}~cH*-&A` zJMG@Feziyo`cdEN$0Tu>KKCal!3CwD)sI;sjPLh39)-BsLE_)>iE(@-CP~r>6-I@g zfd)1f$d72Q3g#rr`DDC9!3UL98G-E^nSKC0_amR1AJ32su&Z29fO1u1 z(XA?8h$>Ldmf}cY;K1dkA3)FjDCFkHwj`arU4Nh$dUh2*5LTXX0p$cCE|LU9D)A@k z51`p8X?NJJ1sY{`XQdwrH9z*9zs7lpjWs{M4BsCE^+!IqK5wpp3L}#yM5p+j zDMV*Yh^6~$P>6Dx5b3V`;yklaRw15?!|WVckV15_3h`cqaen_yK?DA+E%AOzVuNN9 zs~)EiQ=5)7u(^c5u2NwDrSQC<0HrQm)fKp*%<1q32k^fZV#_A43xQ(j*;Rx^3NgznM00VN zlBf44LJcv%Dnwfm#`&F{ng+C6D6vLb;>1-Fhu)?T+g6S=u(^c5Zh5|sO}uQ$X#>ii z1Fs;zkq^az7bclP06iC?h+7TubqP-?Wm&VB{#44*0t;As>N3BUA##)7FFTyy#ztYiw z9?vCi$w1umQR0SA6yo!Tkp?!G5ZF~-HUm`VlL6&8E_Ry%liVxX(NRPAX+jis z{KbifJFG%f7l%0==So7<5Ob_T)E8l#-_Dt6z>H!NQ)MAWttfF%y>_?cjqLU_sT(C>rZ~KiV9<_=11-a8#yiUl;%h088f5d z3bIo3NFX*A z$j^pdc^4%X^L7$t3+g_uAc$t+bMR9bcmXVs_-yzU1n9XRY2ExN-Lk#6D-0Av&#vMJ z!pcnt&>V*m#*~;%GP@&wjnT%#XyYivTuq4fX-ZLuo0<@dPGz7FJ2W9uKfK6!h~KP2 zWDtkhHZ3NFxM39{y9nd_rt@uye$<40Bwpx6EH*@9=w}KsaPVjYn@b4ns*fcE%B5I2 z-|%;o6$Wr#J5vat=R%}&6Qa;vuM2@<=-E|-Kv?Mq0VX4E6tBYOV>q3g>hW-W7@8^^dnAfOFw&2ahRN)X2!<_<)zh+QX-7g zJ*E$ZNO?eFiN3@ip%O(uFD@wm6Nt^_2X@VlVJD+`FAZ&NR=f(yzX z%@5zgjp)ZO&5xi5#puUX&5!IqUUD8{8mk|Fh{J@e$v{7TTKz~Y!uWo#`%#Dl@x~CB z4dzd94Pd7KiEkVBH_6A^wPA8EKJGgmFTf4CE>A(NbdU!NfD2B%aIJ1~tU}j$;gL zE(5TuydxPX2XFGG6zH1}&nb8X0Y2(883_ZK10YOZd(&WUa z^j1F>i!e_2{vi}%VUR>Wf8y1xE*Un`kMCQ?7}#8XU{|i~&BvNRxw1L^ z0Lp!v1O8ki{2vEL3b~~;h zE6CYjIA^qu^%c`OEwQfEkFDY`ed-^Lhx#MG z)sH*h>wFS2%K&2l9n2BL_oB|6z zHT?j3?#B-|KhAFSx*sTpo?XQcgq2$opnS^1ffqof{s5ZeSj5{8(~mX&j(ffm>W^QV zA33s)rXLkFKRR6Wp&w~9KkmIuOF!CL{YWYfGk9Ko`cdBMM>-M4>7EiuAs$qgSYZ_L zSY3(pZqbiC00&c{GKHF;n8-V~MR6OFZ?Fe)L;3 z*1(2;AVzv(SFVY}M_xc#d-9P6&|IW6kRSfvDANx_J@@06n;%7Qd)*HdL(i__2f|AI z0hI5a5n~<0m=fjPA_ex2H8M7ORuL6O22F@1Jr;46Vn!|}NL>WzpW`&DVh(N0l zmBeA*-Swdm9jrps7Ga#9qf&?yRG$INtw{E*Gb`7Ax))Xn+=n;$8|AxlrIkDIO$P2n2U` zcY?bV3mzc2dvSNy@4Vl0vzJiWn~*}(6hfR`x`)dW zCpd*@qb}2--rIO6A-Xz+=%T{7zXwLrfX)Rp_8LuWTU_IkY7HU8)M7&|93CNXs#jaG z1q#$tJ8z>81E?ER99Rc#&3G!J1_AziAx=aRB6V1U|GEW=WXRk#gh1G6fdchr=&Bbm zoH=B_Y(u?0r2bIr=1|Gf}rBMDKldc*%(2qZ)1t|0`%MhOAb0|Oj30~!PCV;2pzHsu{%7F9-F zAw=Py%TkCbLWquUvQdc6LWm~`E^}GpMyC*q)nx|%m5@SAb_%gtg>io;PoM##!!=f! zMC^Y~2!ezX*RG#qq{%MzCgKPDDl{{;m` zu<#>E_15&`fYXn|>N3keOpl8iWQo&{(<+SH{dF>hIG1J^aotqn`z#vcU!xyyz8hxY z@c4mKqXq%$K0Nke@Wb3>jk_`eQ^h+SQG)>gy&qR2`O%@_Z~t|Hfn>csBr0 zPygq{3!q+Hv=*Hf4ay9&-mY3)1_eepAw<`Mzfp*-LWtGfOHqgkLWsO$UUAvkd8ZI< z)MXC*n4LmwaSG8%g>irXH=PEw`$J=*F27(DZIZvnGH)nEVud(7Lf}+)d#m+wY5}`K zJx;71$peXcHIZ80t`@MXXr6|)5Ws&g#I;C5thn}{3xQ#8-5M zqrddm^k;iEb*}L}FhTxAV`2^>y1?MD z2+(-@5b)Dt+YjKs_hWS=Kd!y`&;39$WbPV%Agl|F-tYsc8|9qb3)BTJH#j(Yb(pn# z@vhP+FeVEjO6}@GAub6adUa?(AvOph-VcsXA>KQMxT-EQu25+TanUKnZ577-&E10r zypK7Yc)cg_UP6r%7Ey?J3UPRZz^U;DRG=O-;W#_c=;Z|FdSeR#{P#kvk0iw1jP?HO z8U)FZxoZf4u+iiMW@JYWo18#n*lcO;;a2vORVl<0A;h8wQ7FVCA;jNPZ+}7wv0n($ zbnR5GLyS|yF|fW~UFKbr@YpCJ9y*2Cs=~Ox6MEBtLv=J(3?#amXuO;2SCkNW8xOZ| zc!a>I(WC(CVPj7J2kLoh?DhuMDR(BKNdf%#LTrvCM4`q1xe!Q(%w0nWgmt5G3`z)~ z-eiis6hJ+3Wg(grrF#vxn#R3Q3MIrAA;gu;Bf0SKvk)TXsZJE)oDgEt!z>gcjZ=u) z>N5GJG@uZloI*5EVcg$OeQ7}Dc^X&uBW7E!ao8FPQGMBP3x`JtoEjwr@JVkBo^$FR z(CDQAwjE~+0sQwuY>yLd0%7AB1gQ6JR(n3Emx(AeR*Yo{8*YvK zxg~`-B!r0TPDLRS%!@p*ULoO^k0>GT2_g1oTg#P(xt&53R+njf`nC%tM0}THVEsoG z#{F#(Oat0H)0lD~G1CW)I}cKb*6)?!>hK7GQ{$DEz!RA;6vl^ApfUX)IP|(L1n~d0 z5INWW=RzPEGItFj5H`B4fcgzPYG2MU7tnYp1sc2V)lV_PnmyuqNfa2Dgdgb^F62tX z^umw&b%)W9_ri~}ZA;LPpPYXDp)S)QRcHF~t<#TADvaBGWDteuSVCja5aP~?8lPXI zA9sEpVd3!jfm1z_!%eh+x(|Z|22d|h=0hpa%6B%R1_AziKXybaFdBvZ=YAj=GItF> z5H^|=Kt1`D52gR$D%2oBEk{_vKlPyykAx6W>lL67`GpWa#!OBj;vA1WlD;+FA+9v6 z?i6CQx=fuzpJSoG$mbMdq6*{w78*ta#*WZ&$7tZQvz zQ;5$(h{nO&xzez-5MoNfc^^=Nq!B_SuTqafG<6EGSzTt;+o2Sqlv9YEDvbL(VCe}Y}3xN;+dm%2kK~8@RjvQJ z$%$mh+_n7(WuoM{$*%(GBsGhhDpRcK^h-@p#g9EjVRIVbFAV4~?PnTLO&IWa?MJR88|yS6=B$y{pr-j~ zKxd}`@l_Z%^z>xj@|62D4w*{4eN^L#0d-IY3{Z%J2DBrV><-{;8bs`&y#Pk_0-?hw z5)iegRs<7gZtw^(gsA^V*-Pagy({7(`ak{u`Oo}MQX&~L?`=Oqm}tA7dkgV+5uI37 zq2QP8CRsR94~tAj`H}b0NUK@9Vzj4}u;<#qCtQa(K-iPI@TqqwKbi=8rc@hDd*(Uq zDWon_;KSCKC_jRo_WYp2_`*L~}dQtzL|i3M@`14{f|uoreFvUC+Kw$LEiG{+;2h{{1M!+jn{2 zH`V@#-;4NsL|p#f7|-uT6n`CO>Hn|N1<8<^ZRmoqJr`>W^B{SdrM#}v1yL;%3mc&B zhQz2C@_MA0h4de<~qc^P6J{N8D-@kb1DW3jD=1EVyQ50XuNs6<*8R`{1Uqc22QJP z(Re>ybrcxKHjlD!cnrX)PTvw309-VEZ-&*K)m+s;qCL4inD}J2Z2&$j4T$c=0Lym` zKr&?R8U`S2mk^=M16>BFA~l?-*Go)8kudD+C@Xg9YsFC{_zNKhHyF=_hns{DyIlbk zVyqCNRL0yC;*3*>N$N5e!kbcvjZPt^sW9&E+PE}e)n|>Z;uELF8qH|a`4nQkHQK`A z5dx=)bgvAA0P0O}*oy@;mWKdOJ+_4aN+Du+5yIuWLLeD3cWog;nI(F~3$DkpF-6H?l4A;er`ndX8EcY(9gZ2^JvQ*?_DvJ z5R-%-SHD}%g@+e~AE{1{d4norz3^l5qjL1)ozsuw>N5GK2GEZSPCqWFFm8AM#1!K6 zRE`{dg$+Xm%|v z{n#h`xc2rq7aqp0=@?00p)M1!AO`(-;PhjI3gdP^NJb$Z-PJfN1@VU$8n@k}AKjmi zws3g-z^Sp39?+P)3DmE%+k^50IO)9Y2T=ME%ZncgeAf>oL*}mG2f{{^0;ne^ahwc@ zti+G<1E?2Bgz%vw;TWs;n}qaZi}2$^g1uaL_*wW-c*m00C_l~#Kh~XXL_g9v{Yb1X zQ#E)@G}JGjoPMNMVSK;ZsVKz7!WykK#GsNI&wr&Kg%sjog8W@L)fEb#QGxaX{Xj;I zXH-P1XT2CvzW}8lE-!v0@?AfW44J!z9|-Fbq9YzUfOeBCjA+y^i0V$k>G0!PqcK+F zeKU%pehCwPT)I+|e#D<2d7M4@$inpFuJB{R!uwo!n9J$MeRY{UwbRj$c(EPh?2lC# zw|i?^3ej+Y#`fP5>yOgd=TId)k_;O;#=_z81E+R{8NjHXXTrI9i0V;z4x0fNcd`8d zNyHbcBokG-7m-)5C(x@mf(m91_sKU6vnKICT8YeZL%}8u>S!2qY zl_A8cOJgh?9wBh5=bCNALn+YMn-_R=w`~AW8W6{e0ZDz=03<_Zr(poXMhybg6P&s8 zCeZFQ_H);HuS%Oc>-|t9JQM~T`qG*Pi8w`Q^{Zka;pQ!4i3FhzSXle_As1zce7a>ymt`JCu z%w0nWgpIj2K;sRDK>ZZYxi&K=jynt`JCu%w0nWgmu^5FfRLX1(DDfsci z*IcTEXzmnZstV)&?#@F4;>8_D?3R!CFsa7swpq}7=7i|cj z(T@p?`_UExD1}JiMToS%D+H1ubJq|8VWWfq>d_wcClk&bGP*Ud7Z_(9D1N61N{9kN zi1Kx(aV=q2Aw*F0z7(Q{5aLUk?%A*a@bM-h2hersU z8jVU|dR7u_LjaApAOojNwuJynArg5JB7^S=fn>fG{~#Nc)sK#| zl9v2Z7$rm}*K+aTWFbVjHTgNJj7~y`D(S0Ghz(95nyJg&IvhwLCOL)pLxpjF z{crw^!OwcHHDUhb1Hyy>=_>w61Lg|@rn{eUwcuT+0j1Ps3dR491{`!6P(g)pLzg|~Enj*~ zW7DU^2KP1AnL-2J-5YP=@ECwoT_w&#D-t;CDfYW#2>~4Yn5zWwoC!>M+%^Cx4M^(6 zfb70&0Fohd*ES%8i8dZ9@M+ys!}&5mJztj#$(LCZtUU$uQHaSxh|*PVa<$+kAw=&F z2cDux*dT=XkhnL6c<&Tqle*0KovS{fNVw<};x84({Y~S)b=bwfziJ11Z&yZzrII-u~hhx<7o%_@mToLVpd)HaX|QSW21|H z#I5BR4ezZk)9d#i>Bl3dAN^Dqx4YLX3K6xp#(Zyx-3DqLwV!_68Zg1a;qe2fdR^!` z6c|8zv(P}I?v~?dIHFct+Yg}hBe@qpa{I0yNQTT^!w-aw*%ClqWv~VT8pGcs=S{Gt zWUELawhAGVm-@uTVPAw0wVqyof&$~b5aL*@iCit1)+xjcb(z-d4}L^}@!2WFJQc?M zz4?{~EDO^(`91OADUIXmmO&e{hC&=3A#kc&3F@&afYFhY+pGQl)Zl+0(VkorOzgPT z76QL3g-GE=h`hcl1d<_h*AN0>qrd>_@!$h!QUHxLKdYZjuok>JRS+e_VIf4O_(Lc} z!Ud7XyBlw7OCjzHAugTHKq2xth1jJo)1_Zs3Xvd=W4wF63giA(`A7qHrkF_l`iXcs zqsA^5Da1g9I6Ok&)M!!ww{^i3h@%h!XpeLR6X&|FMbsdON+D8u5hB0u3V~$E+%<$i z*ck5y+Dq-jm?g+c{3t&VwUAQ>`u4L=Yz3Jjp#fERr1uM0w_No3qQ6$oWr$*1%w~(rVXSYaZg4b9PhTSDE+A6^dptJ zOhR`%`jOx1M_Lue?Oqd&LZn`=v1JTm+#MRr-Ju_Aw@KVrouB|0P_GGN`2o~x zI@ZGv;E4scA3*6xYA=2i@?AfW44J!z9|#+dBtUzm@1w|_hj#n{bJy?#VWU$En2&RqRiiwdS)$vgGf-eO&N0c_|0o89NSGz^Sb4daTex_z zju4{n`k9YVq2v)ld_Gc(LUeKp(MnxrQjdWYqPA0rHY$w!+b=c^SY1{ws`^+>6juO7_b-CXK=M1uoSDMVT?LiqWv5J-m1T|)?j zjRpr$Z)Br3oDE}^7!?Yl`Wb&V{8-n0k`-gt*!-waG73NXZ!AwgS_(h5x6DaDN(w)U z2VUiB!CXh#t`&^1NB3jDpJFV zMjzLzeUq%hP18|`fJ(y!3giCPN<;%bJ<=F6vG(JQ#y|6xK!H(6Ar6laI5k=rK>Ze9wFF4b*jA`J#aUng z>s+yg07@ag^&-TNzAFThA#>Ld0%2pM6sRZHs2W7g*j9+F#ELWtqd?{jJ46d}a^IY%F$!00T5 zD7U3Qh1lp6B8$4rm6jXdqQIE!6e5QTd)GaFHe&I)mOgutmW zP6o6m9|pRB_BeYmaa<2u2t=h28N3Kl%6El8GGy)=LLh9^AVB-IIAP2ZqlJN}(Fa;# z^J!3_sJ5egq3YVn0bhKMpwksHrY9Z(14pvBc@eFDi`N zJv23iXnIcLPicto)n3sHNCdN8Bsez%1{R0@&Vix3rjR|q6S=B_P72otU6Vs*hY2tKX< zWG03s{#qY4b5Zl7|IasFvjtlodOq90R)A0OVQrXQDuABC5Gy@vv0qwr&0=sGSQ z{NVKCM|GL1?eD%ufpN*{M;R5y_Y3`wLX->D*flG$*I|vDcF>R8ho)FKm>_=_PK`bc zpl(v|4In_{85J0Ft?dU;`th9?KPvjJA4rDGUBeHAjZROXy^J!9`Dc_Lh-#S@phD?+ zZ;Ey7o0qv!ek>J!RLi-TYY86N2xu`O}X_PCpi? zFm88_>=eSCa4PXi4r0$#8ZV!vAMq99@c4mKV_F7KKcTRN0n~dpt1S$IUBEn1Zbnon zK)Jw$pPzp49Ie|5++Xeuo0a?8mP}O%0Kr&?R8U`S2zeg*~1w`KAM^za> zqewU~V5)VsM_dYVSP0Q*+)l0~Ot>)eIQ!(%3+|%IxG#iA*04T>$m0~^w7SenYXpTz z5Z5uzenExt{od!L0jHLE47ghyz6A`_PSgo24WK=J2 z;7lz<{b$%h0HqMwya-XP2@&%ONQ zR4d-b$+=KvTo!%|J6eT)WDtJr>yw{;d=P$=opg&!3rjft*rYCVxlBs>k>2UYHWkM0 zUV5KGJbACN@k3(97}FTNG@O2{iayQ4;qe2fcDHSS3#b;%sxpxibAa}1(}Nj3@xb;2 zQRzo^FMibYT|bZvnY)G`2pcoCfX3u+AhHras{8;N!y+FtOtY>}$V@+;2tS&vILDQS z1%)3|8*RIT@+01<$m8rOx^|==HJyIM$~ethopHfSR44_Ue#BE@d_OflivlBdMUDHO z5SP@_m^^V|lpnZ0Hq%} zy!cVucl|&zWbPV%AZ+w<0_~AzwOO-5U4C$2J!6My*7+5ybE3fbDuk%FzXgRTD})%^ zwGxF$Cxl2i>N6LXHFFA)Q(b0Bu>usLj8llbDvbNv;~5ReIZ0!l7sNfYHP)L#AsQ*f z;SmC-c0YcA3uvqc_y@Tf0N8zyEd)>sk<*J1b$wR|Btzz|Ekr1@M0f0QE+;;1m#}I* z$o6Sg!n;4xfJ9j%kEDk0!7t~_%aMM7R-K!pQCX+USE0lC#>uK90&fg+)f z(|~*`j2rs*OWyJdw=_HRDdVa^?ujfg&NJ5MoK` zJ`|#*5aQ;uW)z~N5TaS^f) z)P4%_r1*3ThersU+D}mdE}(wbIp^vDjmf>hgqd$g)Db`_L~bua)c0K>kPMl-h7b$~ zqU(l3=Ro_#YT?WAT?4Qe( zh7+7Zlv9`4()rADln`B=Lj0`4xW8*Y(12b+8e4uM_86uyj#n{bJy?#VWVRT_za7(hpJ|G7<0%dKM*yZLfc-SVO_iR4gDA- z{Am1nA6FV45`Iis9&!Wa#{%I;@_kL{$33SXUDah)bsF~+^-Gx3j~*(F+r4W!g=iUT zCb7#(V%cvr_IOS|{z^2{!r}1)r$!3{Xuozd&;>NsqysO%wfz7}KMH#BqlNGKfn>m~92D$5%0`8aRwOgsjAmDnAglvs1kkDDO;bOYvD*QNK(Qe*93kHvPCL{OBD0 z2l}yI`0*^wLoPgg=k%k3y3Ejn-_nl@PCu%sFuq^*)fA%QFB&heA=YWCaiZ&c)Gr^K z%(QSYLHS?oayhN%(R4WexgqR`^jnUJUw?+Uds#b(x2of1n>9oqkMHVchO_ z8!5#7=Ngx9Cbs&h@jwy!vG>DF3x~%Koa&xz)xHXF0mF~rha;sx`=w&RjNbm+_5)Gr zM`161wDDa(kPMl-h93wU6$;SalsueSqG!BwHcjW0v#dOw%2J3hA;hwwZ@H2z{-Vf3 z=Xd-rUq^v)R|wIf))+1=%;glKpSsNF&wC!Dz=#*mF?2pig>iq~TWP?Pk{Xk4BQ~j| z@$2?Hs6lR3oMqwg2!T^$=nJS{Ov<5Apl)z;MG!D%{(BKM2v7=9#ETGZeOCx1L*}k6 zL?|=Nn81xsBk%B|Y7n4NgN$i4%ld7_vF}hqTogiF*cVJ8z7;|w?b@0`yc0r<8=00u z{OA;7rn*e7Vl^p5I;RlxR2bjy;C33YY^28CJBc+WYYZ-z7ec(5G|R%l1o;!~1O*WF zNH7OJ@IgH}kDXe;Zvt&0fKrGbya>_WcZEPQWbWERgfL5tu~2+kZ&}V71ZdPCK)Z$J z=RUoDmR0e~Z}j7#@MC}SMD!z{@FVK}SJzNr#6BH)ti12lC0trq&FRNAb(xgIFF!(o zk=N~Z$_zM9poIc?`SRD8O+OLEOW_0KgTL?s@ z5Pn{S=;*sbAQ>_{Z6QLLXe|WCLh)&1n~EdRW?Lh++|7(4;iI_aaZXO>;=z*QmY44r z#9N+9-10qB3-OjWcHZ*y>N1TgwB{`@;k@NnR2X+~%3j{%Z*yv_x}R9Gkj5Fc@}Wpr z{QYbT2XDDQ(deZ>#C}U!AftL(h&lo&4JhixfX=>a0Fohd*ES%8d7wv& z2Vi;?K5Z|P3nv!;%L>W-SDa0=-jQbnqAPsomUE}&N;?sT_|7uMk1}Mbg5dx=1w1us9g2Yu;Oy465I`wJF)u=N@m(R144J!z5C|J}1kmpIRWB!2sQdZWU>u~`?AcaG z`zRD5oe(1X;PqTB*h~oVdy%PEQ7IG`Li}C58inZV6r#PlOwW%&6vFKk!e51Pe_J1> z0X_C>OdC#oaZKa6z7(RTLL3w#z=c!2vk{*&fw~Ulsvh8^jkW*vhgC=!5uN)}cPNiHM@+B^UFxpP0BZ6&=wA`|L}e8PZnQA^VRe_=rQ>MS&% znlPYB*afZ!9P2c|PhI9#*Z4G`v(tc|R2Vn(_)*^S*GcCPpVrHXvC#D2YJ53~224*k z$HGAa{9QOT_C5pZjaV+D;{m99qV}Um0B(%&Afk={N+EvqB1C}i3V~$E+%<$i*eDW! zdedpuunuRI*dwKW?rFv6SO+qvq7bEo5aoXi=X$^aLWrP;Yp$S3Xd;C861^3LnCBE? zmAcI2)l(m!jtF)Nu~CI_f9Kby0rQ$`{Iwx5Z(EHCS5k;Af6lRRc!a>IPSA4nGys>N z-@deZQ(_=dKV_(XxM1R`+O`n*uoU7aFGBS6T_KPRnY)G%2#* ze)Lk8+4eLG{g~kNqn`@n`^9ZUA@;4-xU(^_*;b8@{>+6&<;5*?EF4UbKhc=8kBENL z84CR^8O%^cegM5P}ky!g@Ecl|&zWbPV%AZ*ki|73|OFv6H6#&ag3 z_72s4?#<`sShHsqpdZbJAL%yU=JLQr!jJkb4_!w25hVOL+b58I>~;FFTV19@&b9YZ zek^qQaX^J}yZxI|h{InrW@|=l>zd2xv={UvnnD~NKX9rISc38cs8@~hu@k8CM$ID# zW;F9t+YdygA0@r`5$L;qAQ>`u4L=ap6$0v~J15xQm zDKCBm`K}*GhRj{tk5DFBzbT7NPJCJy7@VYEwaZ*)QqGLICw_L+)J!vOqKp?I2KcTJNQTT^LkNV8ek!2eA(BD>jp=tkCz@yZ4{S~$76~Dq&rD7s z9ta_FSNnJoCB$AKL`ch3To34~>l_VNmnob0=3SH!_nkugs=~OxN!rnXc0Xu5(4M%n zl*W-sv!aCXSBS$S1WxURi~)@5b$^HO41%a0+*SLx2NOqSdlXSeAS#6@>qUq`zAFTh zA#>Ld0%7AB1ZdAV3uBfTZA?V%?DTVIZ8Fcgefr6_C@?k&KYo8akLv+H3O{De7)(FT z2tU$pC{908IsM41F0-Lo2m0~B=|@2o#_jIakwTmps4-t>Vx`d<7v-WKuSd5Y`3+p%)9tPONz9 zu|154ti+G1P!Kixx&K-|&$`^VC;d1m{Af5OFa3zOIP&25#GjMUk2}JTB<=%T9+=bV zN4UDo@^~Nbp!|p%-!V9TMuqYHZu(P*U8gio?n+#DMdQvg^do^n988eE3#axQ>(zFd z3U&Q*3FQY+^=GJe@3IdAm}jr;2T=M^-isf@eAf>oL*}mG2f{`R185Hps_ilr+5<;^ z?j0ZIS#9=P6ykyq;@;J*TrHSR2$6Zz>f~}H3}_{O z98sYFr4SXo2r|8S!5*g3D_e5+Es@##=yJP-yP82B>{ z$SVwpRya2eaGi-f{2f&7I+q7lbsDf#T_)9sBs3t8(}3kFjBmKECvSO?jvD{hn>eqB zMt7$SXi~&bhy%Zn-=AnV8Ul!Vtcx?Y@j-h#;b2CyxNQRvl?MFm#eh-1YXFiVbJsQ? zgo!q~B_i@p4J)9^02)mSpuHKGpF8zrl|#$Z(~pnBk4Jk?akXGc;YYSEo6nh^rNB|KgRg3A4rDGUBeHAjb{*`{qoIlW|%QwCfDux z*3c)*(xSkKmp$@Wd8}A&3QQ(?m^Zn`jD0hrz$lY!frY~(1Wt_^xj! z5S2ny@*>1I-xUJMkhyCM5z0iTV)t5IvqAKZg>cxDeuPtbr7wuTzK->M~>2Z@z^R!tE4dq6*{w_UWD(L!(0*YAn!$ zSh0o1cvdC|(fs!X77mXPIJHOm0vOdR$FHMNiKu=C=i91*L6x6Gv>|{}h{|4snBcoY zAQ>`uZ6QLK2f7UCkB1I?`b+@+N>mvdMl@;=MC}P^e(s$87FbVy-kek&!U8AEDTs#Y$jI=&UG5F zMP26SyT@;$gy`=yV7Ch6hE@yYEkE)`W7Htx>?jKvtz3u(Jovi6!r?Ihr~08vbvy*P zfcj0OtTKT1BI962W8Jk4KvWt~)r$dBeAfUZL*}k+KnN3UbW7mVT=cbAO+N}_6j_NM zHWl*7hwwcrHdN1dWw=|_9v$B9}w=*L>89|zQB z+I(q5KgK)#IHAJ$ejEBxh~ecl{t-+(Tit_I=*Q=33oRT>kiQG3dNvtL2%zeOQ2UwP zKnVfVQ~24W0H!PaG@=FpN%9?zzAaw88rx^ z#?*@8e=fA*g|?<2&4eGrE~KR&3xyy1hD4@x&nFo*5d4G^Zagr!TZ{c>KVrE+N!wI|5ul{jPJCA3$APs%w&Y(gWD}-2)rVNER;}jyDx=e+GT`9yyrx4jx825MJ5E_u^Z;eHV z5&wLsFBLq(EHwmh32o&lD_iYpyKzsjGwGDy7DJN_pfKrGWUWAzC zyFwrtGIwnuLYZjY)vvmC)kXvA)AsH?e(rOz7FpeH2GM{4(twYJXuv^fz_L^{V4gH! zPdL{D-fqlO5$ucoMmGY{;cAwPHG zdW)=Qza8+L~a0Av5+7#we;E|cqr)D+@@Q;6SH825MkI2w@hu*Oak zh$+r!EZdSoG(Ww_!r>7Dr$$dUP;Vx|RwU49B>;o|vV{OjA!>UOVu9}pfn>d^#Aw&J>o=$HcP&5Bel8cwuZ zS$^)qr50Ni=dVeD5+Y0pvH!1@6e9kT$iv@J|Ex?Q?g}CL27lr5uUt+c%Bahv%wLc~ z#7p29{;sIPxW6N((ty$b(^z^sF{qQq!0{B~PRGR-4v!ExH5v^--AcZODg&q=syIa( z7`whL1W*c5*NYHKd{+o0L*}j_1j5F)>Oj`1yVUCWFy;`l5zM{kFM{%bgf2zwIyuITZ3XHT)KRT;0zTfK^ z6ynhajZ0?{H|*3nErfo&-?7-j!36ocaB8=b1BiOvE1xqFwYTC4W;Dej+YdygAHR6< zBgA+8Kr&?R8h#*b)F8lk-0_Y5R6wI20;u1m$9}4jmls=YmK;is^5cQ<u!YAt~rbRi_{G)n$qmu0lWZIQ>|m!noay=TL|R(U%avnMaI~K;xW( zsnO(2AAgC3!{Y}|?RT*RFsffm!k%nI_1o^*4*@Lk%Ju^&{ix@~kLAAW2a+Lk*YE>j zqsa->^NrZ#1RBdkqvcv+t-n-{LVOfL6nqtjLX;Fjw449*1PY8)LWqZd&FA95#!exU zsLKp!eeNm>j1o>E(x@=*@4opoAYW~bJr)vs{HF2P77FpP;SvjnM+ltiH*v6q0n~pT zD!GBKf1-R(2QYb=7ZEKCpcLX)FG8&JT_KPRnY)G%2#3J_U|A623J z^I^3_#?SpcV2QP`_swJ|FyiKjJXW50;$*HRtRehpQm!}s$RYf=+$cZ&Xy^3fqq_?mUe&`jgNW!(8TL{D z?Sa!^ez?*Y+YdygAN9TXvD$b2Kr&?R8h#+Gb7%zo0NPs)hY^hm1yN(Z?(6+atT78a z(2umjj|4k1(+{`sqf$E;{U|28TObX$C zqA|=Oo_njYL>T=TsSt<951i`M&%hH3&|Xy^NVMzEU}DHs+YfwL`q99PA8UQr48)3hMPSDGH1{LWnQpS8?%RCm}@9vJ;M@La8Ez z*z{XP3NhL#M2uuht(vah6r!V3h`1_@FV)9I1G@jHu|OPRz6u(Dy-p!EmtSh(z%QuT zcsMl*44`g-a*-g=Zhr*x!Wm+S2oyr(dGd&h2X{M# zIG`@Ge_93#G2bb~F%`!B-H@0D+{hY2{39tbG{43R=~6(5xC(K2guto(bKnGBpzic! zrxwtDtx+(4H%E$B5mg4FQi#T0gxKo4LLeD3cMTyBHaabUMlUDO-n8D&y|Y?~m9Il? z3eiajv10IbE*{(nTvlP+-*m}o zz}_wzPoyBe3)Gl%A%!TZ5Qj$yoa!ms6auIXU=0E^X43$hw6ui)N+Ftf5n`L~3V~$E z+%<$i*r-8(dMhI}A2Zwq)Z=7ok5E7N$>|~1){&bNqlD-$gz#I`mO|_oLiqnui$cs1 zLOgF5lS15b3UNzaW?1T?6k?xKh({`n`#Ufd4cNI`W6?Ck4@Wds*hV3KSBS$S1Wt{0 z1d{+o0L*}j_1j4#oVi=x6fqJVBZe;{C*8Ci} zA7XvnQ;tH67ee&7{En-^&Iuvb55E$Q5@L-IqTqtDTpsw^DZ~|ZnZq^rT|^0S)+xj- z6~_I2oR$V;_+}Y#?zhA{sWmn~MIrnZ;_wK8Q#}P&?VX{P5i8Wsne3JT+THqU88I;G z>xe1?D1~r)5n`9`3V~$E+%<$i*r+mqdd4bWFAGFg;zt!2Kw}sFGJeafYbj2Ag92lL z@S}15f%M~^@MFrgKj_D9;Yad!>F9@5&oPo-LtSRof?D+BuG5dYDva;T{^^#jR}xoh}= zu+gmvw0GeTW0n}tAc)#K5c|3R7_`iaU$-&+*dY8E-u4^%@m~0`Kh2vXC_hdKKgtyf z;ab8JPCt66%UrpBh zRQs_Sc(~kz~ zGQHmaK|f+Abd0mRRT$qdOEwA-_)+79?8NV5E@yOjm&EYnc#P#14kpN-s8g>tl@A~; zPm3Cq8`5&D*gD~iy!-a*AFB^=C0uf!p3}Epx#|_FIu2LyZrTY zPt3I3x^%oNg*YdKXmCFVg-9cWm@p*)g?KH5NW5k@*AfipJ=A;3~Drqd8o4B)%#!nw9#OvD2EgT*paBA;75#R#q-7~LZoD699;RO?u7kd-Y z;6PLg(ZY)m2YpuvBtzz|Eri;LLWT984A+DKjT!`KFVk0#BpsJqb7DrL5ch---+sH1 zYYB4;AsU2FJB%8{Iv05){oL*96r!?Ii2Ld?9mn;j5V@Q}yi{S_-`9C)!1Ku(m*&%c z%+=U6I0;IKBnokOguto2L?M7tz2bvHAex@<9#uQg2Qyk=h%E%7QizsbggE58LLeD3 zcWog;m}sK~icjmVe?FrEwI8Ym_H#eovE15MZd5{48SjMC`18;I6Ok& z)F>fp^g8`Vl8*WxZRVEhwh zfdTCP-P?#71StLZpBF!l`mP^HhRj{V4}^^Z1E?1XaxN#(C@_M5TVegQeo+Dx7-@tM ze;sK^A({#y-t;O-A&Lqix=eVQr3enn&5XXI22qZ)1t|0`% z#xn>o4`(+jA;MfhyM^KBuC#Q8_3TMO3Xxj~(LUB)E*|VCgjl-qa2QI6%0h^2$NEx; zQBENmtIO=_weBoRhz?F6TB$JZZ@I)Y;P>Mi-z6bdzo_x{H3~85!U_wAM+lr6O$s1~ zc?z?H0NO9L33dV3@3MseN+JI6BE(7G6#~hSxoZf4uu(z)jd2j5-aC=+aOm=Og%!8J z&iE)HeiA|qt>jN3`UxTSzWbFz{3e7b^G!SoG21D`aCMnW+e=c2Ag2%$R2cVnc`_O> z^4pa}cM9UK*)`?}NQgG(>TD}593CNXY7hMeFsgTt<%Zmd-u<{#ZOP5e&Va`fyo;zZ zfKrGyUW7R9yFwrtGIwnu!kHzyNx}JcL&~qT(sirCTV7q<^68_#a;?}nam&yCbn76> zfVSe6*R3~&s|8m(Z~1g}na9zNoIx2d)_Ke4t1#|h(p0?1GumoAn3}k=o5pXVxNyt= z?z+;#;ko5FwYwGq7{wbZ;zi>GT}15_alwp!ZDikaMCC32)5|SC>$|rc$&k5g-||o< zT5ssZ8M*kho?yg3`eox+TB)a=i-$k@rowM{?q)TaUSoCbucFm7n?w7lgjw|egHx5RmSHGUjS1K#dgY2ok~fK%NQyB1wfz$@Qj zgAwj<2sHlafytNI1^}f2ZM_(9-ggZ^GGy-B281w6jAj8otw%dKBNvFQ#E*K8_$L~I z=gdogD?e`iPCq(IKR%_PAM2$b%RU`I2{B6gv3E5W51w@T@l0LjLC0ICQ9`V9`te?c z@%?V4rx2T6tB6xF5j#n{bJy?#Vcjqc!dNKKc#FqB(VFO~1lm2le(p#4R#_!8KZ}dVVX^T*Pg!Nfv#i-w#evA`-^zWFTew-D4Y)_wzeykRL z6!#0`(!y6xKQ5@toWAwx6v~e?PCu@xFuvdVtQ6ww0*$S+6OXRc*k~pFXrT}X6Xfs0 zsa{6B6!iN5Eg52X-y zoI=DnqVI3ooHW4irN-mAh_60r?7ELa1SrJe5dx=re>=Xm1E}X?^0ghnDecj*8Hxgf zc+(aFD23?gMTqOZD+H1ubJq|8VWZ;`XfMPMW0u(c5aC37XxY!5F!gGy-l++3P@$|B zew=<-k$$`rek7cphkl$CevDlAH`fv-clwb|T_&qL8U1+c^dqwh<8}|oLm@Ji*65dy zXjRcT_A>pLP-Tqe1tw5sQ{f-q1qMHhQh^SD2(vMDF{J7z} zejph#cMU%fHfHn#^{VUx=%)fAEAgYs51=s@t6b~VR;Oec>Bm0d$J0D#xU?{KNaV5d zoL9E&L-}!2__5@5JNl8$=|@dO5_+T|3!uI{T}6~5LHHNoKujPWva#% zFX_kHDXT3UOpw0|r*;h)Kr~)pkEs6Z;9Lse*}k?PK)!&6`5*RlZ~sbNp)AmM)`48_>r_-Gy0KQ_)#Nm1^V$y_z_;{1DB5Z zIsIs&F4OAoJoF=#(~njvjN4te5QUg{MdPGS7RJds-qjfGMGQQ!9J{mH!r}1)r$#Rp zQ15GV1?30O*s>q^INbIFDE;vF;>R7|^#jR}xoh}=u+gmvv`0$Am_x`){HXE+QF|_| zpLM~ZQttU`^ zOprfOx3AWrenCVdJ3N5;`9-z9 zf*DPc_G3i-f~fSPix)rc`K}*GhRj{V4}^^l51`TE0W{hlK>dWLnsa{cUuv(hK8Edc zq5OC!{OEC`2mSa___2O$6Z(-{_)#z~1n1bz9t``F8>Qq&>Y6-H!N^NXEfYOhyUi^6A zyM7=UGItF>5H{MUK;&JNDBKkZXqUf!?zeN+ScC4>q7bojMIK3y5!Ip))r1fwS3lT; z0wbFcV*9~aTzL4WQ-}m}*I4zso;;2MqpDMg6e^5wn7Sto2s@zhXfNXH6B<{iq!9TP z;=nJcC8jtv7LWmrk#wM5O~;XRV2#bT5I`wJH!ngw@?9a244J!z5C|Iu22dBN97zY- zyGr@F_di))K-YYBLq%$38>~01-O9v&q4VgNW4}9n*gx} zLDb*+6j6f!r4Ze{2=T;sg+MZ7?ixb;lO;pY0tF^r`Lo(QOuZ#1jEJnnk7{8cYHu>- z=T7<4TB~=zHuNKx@Z-bOZ|O$|;YZ<0(dkDe;m5jWo4D|Bq|=YA>M~UmJUoU1qrKCQ z+$xOk_aKNu-1%MOtp3E??KIx2KtF;M;$VXOT{tz?qytmMz(z=XsTffAfA9$wIH#`d z2T=ME;Kh$;zUv2)A#>OEBa}I$iv%@n5Johb6!>L5#x@sCit@wPT91~zu~1Me z8p4H#K|+Xy9Y^m*4bo5uk$GrY3NgzmL``*>ZH2p2h`vrC>Z&mAZ|wmzpw3#2)*#~N zzcfZ|LLtT}#NiPFr}k^n0$f15K@~{U9m1Q@q(F4-JX;8$6rzV0Azt{d5J-m1U0a9{ zCfeu&#i#WWQ`O1}XVlI=KlkVJ>M!Vhe+p4e2=Qy;A1K6FA;h@QG!)`bAw;5!$GGrt zl~agB7uH%!2Suk4W1K>yRAJoTt%GU6uqf+@?T0E%o zLuR(&2g1g#H$eRo47FW%7_$Ufi65m4qDGfSk!imQ%abRI zLs5S87P_>J)rh+6a_Uk|T_)!G(MM6C%ysHgPlfUQG7YCL$E#~RJA$~izQ!+C>BqHS z*I782Ab%H5?G@Jn#PtWesrkK}rGcpNNCJ#r@^eIk11SCI<;9OTzUv2)A#>O817V{} z6sUVR)TE6tW|&dGAZoYY{M=i+uCtyunI04MO9$achwe4#$2#FhNY+C1W2EpSd&zrT zmUzPH$0>E0(1&U0$6BW!S5+9dd)O!nF>{8-5@U!57HNFeDjLd<*a~rY{J^Phe{%sl zP`?SCU0y(4da^+Z%rVmT11SCI?ZuCGzUv2)A#>O817V|n0qQn7pHP5$Uoo}on4kO4 zJ?pG$BeGG5AR)xz1(&!Eajy`35&A^NDxq)W9V90kT6rw{{G z829(ZSQ@bTfyPDSiBn%`y!C`a#8rsHBLq(Ejj#e-Kx2#zXuP8knDde?1W*dm$BPgj zd{+o0L*}j_1j5E6D^L$ht8HMynPIwx##ua@zgcfReYGwIN{F#Sh<5Q?Q;0J{h$Y*q zQixSTh^%L#P>7dKA@-}w?Ce*FLY#IAaYTi2e;ZDu0iXOdCYVgzUPfaSD>_ODKZQ6b zL;%qkB|${DusO;K{58jyh$;gp4G8pNz$f1|0LhTqX&8X8Q6vEM-rh6-Xe?3R-E_Tm zFwul zq7ZL|5EU}Cq!1^B5PSVnQHW$tA#SM4G`?MxLcDPbaaV=$4Rg+*0p-qUygHNk;;P27 zg(yTPg*fmF>Y)Rt_9E&4qFzy}*2@JFjfq?M@PvJ~5I`wJkQX7M5V5{-46L_N zVPwpiJ)euJkm^;Gv*9ZZlv(b#Aak?ve$dL4cMb^W3;BbYd-ne7Ln(vSXL{D|SZ zejph#cMU%fHU`Fkx*vkQ6hPxC6le^r=bf^_N;aeu{kS9i7(XWq{m3c&I9ekP{fKcP z^1yo4);qZHu%gqC^6E0TlfF2F@*{`SkD4ls+r97*h1j}NV}m2a#bFw2e4-!w4{oq< zc>KVr-H#dI0_qjDx8MiR*jEpDXO-;-Q2G(<#ShDO{XjBg?izj|Y?L2BJ(o>QJqTwG z*%K4|+}rP{ENS^UDhiCZLWoCw)^OoraUn#uJd?JgLP;isSXjO?g=pXu;)J?Pi5Gn+ zL@}ojmsA+{H~vu?a3TIiV(2mA{S+Eo5BQ1#Be_Bx9wBgQyd46lxBKTy=YWm)7^*fo z3Fhw>{$dM(s1#y=7a?4}D+H1ubJq|8VdE(jsQ1-VEAGOXCH7OApLuApKXm?yLR1k#6wZ{1LSzv_tSfew3lINr3b9LFrt00;6r!?Ih{Gz3``h&d4LJOp z#vG@JUs`G$Fr7jqR*1tR1Wt|DmIC$Sk-I1%fO;HIH8_Ha1*=B6@g<2BCI9GMh)N*_ zdJ!Uy?+Srr$lNuAK-j23fZMv@g%D~@ZaA~Vo*eDxp3#4!741ke3XxI>5p*kz%Mu$2 zA^sY_avMsBB0`9w%bQb(o=zdwsLPzJKPe1V#&1p`wy7}g@0HUuAY+Kev1f@J)@hux zmO{K;yV1ho5dx?7&S+}!nL_=BDGq!9^?F;?;0|Uq#WY(8M5Pdeya*A`cZEPQWbPV5 zAZ%0_K)unTnrjfoEJ0S{NBM!M-gj<09!V0N*l5jcIxh-pketGgGy(PKM|5@;mXmNzok8J8P?H*;KAMKoee6Paze&x?ohO817Tw$ zPM{tdQkxlvF^6=M(~a^2Q9U(Fb^H0bbEH=vu9cU56c>IJY;%K)7W)c6+NC=17s`(Y z!jFdqdeM)WPCv@3%M7@>@*v8OK&KxyRT#H>#U%>yzP!d}SBQOUYCM0PevGcM$-?3B z1E>0tmG8j@>c0;90W>NU;OZh#BPtZ2^kaw@KN9(_A4rDGUE7aP7Zc3|no5XpqEUm? zZnw!A|I5~|3sebFRT%J1`}QN3CIC`JQDI}K>3 z!nmQyuJM*PouD!7IqJB%uN;!j{!K<{j_R#@&HEl``7NEgg{j9%*t05 z0@n|)4FF05hI%m|vF{pyWXRmL4G3W#7;Q{^T90+9$M!HrjfYZ1?X7J6+%5mwWL4Z; zfqpa=e(XQ~fveEw3O}L-UE7KhqL=Wa@09UemblaDM|X9Zl;sZ`KnXF&=|_+X<97GC zK_Rx^&{*IWvBD#bW5Vdi+=rVi93DS#YK(*d_50Vj$qCS&XA z)GJWG0Cks!>e34&>OU6liG%1*9c({<(vJ~d{7C7$ejph#cMU%fHd>%SJ-wBqBtUJC z`up;8?^(Fna((~sGYX6`LWn_CW^-BMX(2@DhhPe^QV3Bpi64b{;S}PSy3F~Ve^Q83 zP9aXKFz)Y$M>L@Q5siO5Ar?NXv0#hWXmD&lv)RJo5dx>ieg{C#?VU*>fO=of9e88~ zUf5;}0hB_F^ddxR-xUJMkhyCJfv_=-3eVY-Dpvr7m?MO^ zRW>(;xFv*0|1uGU*dc_N8FwGoAx3N97+61|E>mRlyL~7jZaRfHrNX$s>7LPmSZTHp zPdq1{`c7l-M-(ETLL43;aB44a2yjJ2qC{a00yK7J1y+q4J)#ByN+Cvh5hAVc3V~$E z+%<$i*r-8(_H3juBg5FjKvZ{lsBH@U+^0%!u@XOtPCwQPKgL*_xeoD-@Z<1?8Jkgq z92b66I$D!{Bz5|6RbA#r&jIw~wbPHADvaAb?B*K`tG;TjvBYiSg3cO`c2TI-lPSdE z@dKxN;s9$9pzicnQ_lkVVLb}O0t3-<4QxMv(vQ(z{P@;){XjBg?izj|Y_vdu_A9x< znM1}_&WXotvEsBC^9eP`9wEe#-sLDntmTo%+4tniK_UJYLX<9dg$oa}IEBcdE_3l& zA_`$8c8s%URbkxU7k6mDr;QpH-6O8rrSa}?3Q8#bZ9cp>~~H0TfdQN-y-9(9@51!wL>g_6SQMoL*}mG2f{{|22j5&;sRP2K)tgqYmlP3w_0a6FZqZ9>`YpMyeVcM4Hgg>ip(Kc)eF>S*ltl$fHi#) zEgT*paB4T10$e~nEW#D*Kx4fjaB0~X5iJa$6k?ngA-?lnA&?B2yM_=5>mnft1qM*h zRZ?#c2`3r@>nVF~wH7BXOd;L~A+qGU&xMD@gb?nF;TusxBo#tjebJ9X)OQMzOPkgXODj}SPur;Y@;7(Id?HEbMA zyg$}908weccrONI^<4vy44IvV0SFsy2%z4^k`w%ab}yixyXV2J*3)#MA5bL3$`g4c zyBn z?F}driU=WMMw`Z!hCQ7^Y*v?sLhMjse7_HGX~6NHG_HJ49RIV%zw5l9 z5DJrc{*#)#iBs*rTEe1)P&ha_nnkQ5fVu?KLMY6eH)cc~fv6N>q8A}@`mhix88UZm zA=LXpRM_a209Ih%F5fT(G#Zsa`|TQj?w}TbS^pb(;XMkB?81-R3rBKkVO!xxhF?0< zj|#$%S?#jYk6}(fMykvFkh&rL_|xgfI2DE;%|B9zPs24P|4ckTQR6R{=|?SvIPeR~ z51iWDv;+`!3yOPtBdRw!;U*TqZoO?kfYOgiUi`@IyM7=UGItF>5Z1G;#-a@Ye71Oh zl^=$(4FS{(gxIkiecfMH#+fZCL{TBc>Ma^L zFb34+2MY{f^+UE0Kq8y&5;hA*MR2F>MG9m=?ax!r?Ihr$&(gG#U*+W5ow><9gcwpfq5b7Xu3Ut^r7f z%w59(g!P=p(jS)7js%n$~Q-FcIX2d_H~ z_(feNXWJAsAk=BV|1o#oQBoA`+a@+cl(4`8qDYPcN*IEGie!-_k{JQX(FGjR5*Eo4 z6_K1I=O~#a?gC5B8I~oke{O6uFy?X7zNrs z1&e%a+AYM7QV}P8sIhoB4S1Agi-p5y08Z`Qg}pAIHk{8QfyM+~VCsZP;u-~@G+>G! z14;z00Z4|-UE6>~%o3xQfKTfg+b40`2}D-nN7WEO{o-Fv!0c9Pi(OarzF1KuQk z#noU58##u*kE+Z3xvnq`xaKtAqza=zhbCZ=FJGpyOd{gAe>BcKO#|Wqeg8?_SmM-v zaiW)~7YTCj5k&3x^oB8-b%rejqEd)yeuO9;xI!QqGItFj5H`AvK=ocuH3+O8O-3?H zj0X>h+OKVNdtRJSnLV-${a7XZ2%U3}s|BA5KQ`1kz7jRWVc|!~4#Vh2kkb#>$t~95 zjGMQjhIr!iBc%$%k9&zJ#Qs+r=OiI^vbHk1;U4|Cn|P~*1HYjBz^Oev=OyX}MJ-?m zCE81z!icHfe4#*=JddA^a1x1GSuWn6JR z450L5h95u51+E`RhRj{V4}^^#22j6{Np(3RnSVz8fvB;S(SdGTt+}o1(U0T8kL>+j z^dngK(e%@QSD^lQDEv5AX%^QKmT>xUMqQ@+qvKmpe`Iv}aY=sqZB@9?tG%*cGCk)6_Z37n%{@^s=Q+1i`Ph&Tu zhHyI#D6YaN&@t&)hBet{{WbsjBUB02r|%Aq zXWYJos|BkGA?kD)w;WAIP9enMq2Ex5woW0Ysmru0){8<^bqX<0g;BoGGSGmbVHy_) z6UYCivGRTjv47My3x`h#oZ4H}cwInU2dE`*p+r4}pF8*?dOO4x0w{%;<41@}fhz=( zA#=BCrai9zK1o`k$Rg%}agT~m+b=ebWYp+VAZqN-y?oI&Yj5;m`jJui@y#nY{b(%w z7_c}i{U|Q{c(d~e*An(}`msx0=FhH)=|>}{A5kid;%=UqLd-g%G2Ms6D(5tMuF{X$ zXSZ26e1726=yC$}d}Q9T0*%L-!0q9-A3*8HTt9wP30yyr44J!z9|#*22GCv;7UcpO zvuWNu-)4O>Dh-9mCxn-QHYUFA=16rW<3ZVzX>f! zN2d^3RT$;FH!BS|@bPwHpO1;#^J(n$ff~~y16VwD zvbYumD24djj}X-YR|q6S=B^rtXeWe7 z)Vn8zSn3oa(I4BbX}K3|M1?WhDMU&YM*04klLqA9tg(7-je9gU=yn}K)Z4w?!r>DF zr^ZG$KzrAPP<~k7l5jQ+q9IFcKY-GY`F{MU8MuBR88UYbKM=Mnj7Vk)@(w?$hCtMw zjijDpUEOZw+q?DwYKSI6i20Y=QHYsBh^wP(Qi$F{2+#Zk6k@AWh|B6SFY1<{5Hp-Y z+*VPbx`(Wnye%SIa!TO`~Hy8k5&=p+mn?|RDRUn_+HQR~kx zL6tC47*PH2Xf6*t2q&iQ(tt%AA}0&+CBqQWqur%Lj;jt!#H z(uIC3trNJGA{nyC4NDQ$58pXn3q;=GN7Yk6J)Ws@sFZ8)JRMEcLuGa;*Q4bcy??z% z-nUhVgTH%*$p25g`{mU*2qL!dUZU<}s_RA@A7;tm!+PgP^?sZ%Mu$zbO9oL{GK>6_ zOufJ@86-oRZI{dK=oKND%`3a+lYUgW5nO)p+q0> zZ}XV=+f26R(PC65OU2*jumkhCc<_PqZ?lEE%qP9h{e$Y{sPk{LoeIN%e|l1vfsZwI z^b$XKqp?x;H?Sw{b-0DYXHVQIF@#b5(0?VScO$A-1ks*%J{-!ZR*m)`I`^7w4^Y~( z*pEH+1J@oTL*~6<55mSnabPa4yH)SdiDC{JFBIyQWruaM@Qr(@%4Z5)T34CEwS?D% zF0-EXr!HHCE+3~ZMqLs#c8tP@s>}SdxeaxRcIxu03ZuBQ^`;+TUuitvhuE-&#;+Dr zmp#>YSU7xs;M5)#RC})~)Ngp;eSe^0%+GCp^O^Sb`U)^!1ejeZ#^v$3S~(n|i~PLZi6> z+D{POp7ZN>SaVjry^H!|m+<40{j0gs(6#K{QTQgkCoMvAb5;0pc6<%`k=yCVO?8=& z@&o8ck|4(@{9P4Bao-<6A&y_vICl`S+f9vCs?(3#H+EP!e1726nClDFqiAYHZKw;V zTOUsA0wz6V`vH`GEc4?>lfd-@$&k5g_<^u}LmSR4(HmiL;wPfUE5{OBJFRqQM^cCr zLWpq>%TtIVU>Z=Ukj4~4 zh>uHX{ILavNUsowPY9eEJ8uHD0o=P8s2`cD&RCcWSR!l6xCR9%g;?%Kh-QH+1d<_h z*AN0>qlW?1)4I5sH&E9fn=q)Bzur#kN#bA%aa{-z^3ee+3=ieP? zFL=Ebg{a~bqP)7y?(vh>p#{n36r#EcqkOjyr2#qmXzV_m*zi}4{d!S|;e&TtIDA6j z)SlYxbpcbelgW)1fjTo(a~j6z!Vb0&h)N+=_z}VrxI!QqGItFj5H{v<0rewMwO%5M zS)!W^HIvEhxjSp8wRrcOf6-(-6GG&>_ydI~BZO%6TUiQ`UI=mZ@B3V7*w86N!r42m zK6P?Zh|*3WQmHV?H}6OqP$^R5`BB7S$27iLK_TWJ-D%=A%leB7_)L`wy-q9OV?ErMk=~Zz9&9O6cSiqO%I4d_8~A zfXLMvgZ?Bw*rKu4Qwot?Ar7AqIJK8adtJcibh`ofyUS`Y?)V+l5M_iACl?N*5dDP^X&QE- z5DkS8W4e7pA*MNn=<1_oMGAM5t4UVJeLBjhI9OuE*a^>^qs5G=;{@GylVbhtHDl zws81_z^Tzj0CoC!9|1I8Z4Ipb&=vwHg;?uHi1vXi1d<_h*AN0>qlN$)F9ibHy)3uq zc;4Ms*%%Lns3C;d_&SI}j1@vWS@L2YYKZnih>+b&xzcc%Q-~OKnG`=?S&bTEj8lkv zDva`d`QsCegIxbkkSd=S@Z07@a&`4OUH;0l3c$lNuAK-j1ufZ7kLh zLWPYROXPvwhj4p7-M!m--li7~=p+p2IiL^?SSbuxSvV~X7%2=WTxAcJ79MgMP*Ghb z;_-`Bs1jB<4XCNYDA0XvS>%~wHHNk)mVBzQa|{h={baX=!)E|ajZOnl&o^bK0jOX4 zqK0nN5)Xw#&f5k6r2+r=F`#SU8h~WT+_en|XQGWeNqkzrCrJ(KyFFRc?Xg~-O-utq zg#q428@PCIhcICE?CF1_QJ5+WD7vW*4Y=$ypqRSMzBWT>K)BO@@+yo1{j4L4ym@Jj z*Ep2IZO>_+@;yv72ppP}1$ zecT=khffHc8sptS{bD?Bstwc?;vQ59z=XYQA%Iedjedma9=Jjv88UYbArRIhQrz+q zXup;ridkYes;Y)qzQ-E)I4gyiDTH{N;wYB~UK2u;-n?!uYKW~uh<}c^rw|F6I0m>2 zsms(JIDIABh-jw}#Z?&Pn;?V+R6eP3U3cQB%Nl>YMLd0%7Am0;pG3b5mTPabsEi^&TtP=tVbC zL#z}+44c=CLOc;d?EL;~3UNpX@nz>{dNr6+h#%Bt&Sow^As#!0Xs*I2-}XIeK=+(` zi6421Z9mm`(|aE^M0|xfd_v&Vcw044-&SzM@_)DiH3abE^l9Rn44@QZvmYV6fhz=( zA#>Ld0%4=c0O}_V+;;$oti+FML4d}Lm`&C9TC3)ipdUMgA4N9b=4wG}`MV?99XcGE zg9_ua@Z(lk82!lU^dmxDW>As!D^Ou1PVX4eKB&U@en)#zhcw{_)+qFPx_Hj`0?||#`NQX@Z+>(W>Pbt`;mMgqV@G zJB3ImgveSTFNOHQDa2KEnRTZcQwXUhN z%TPm9bqdi^g;Bmg52XQ<7i-KtoY;J=#tIcF#P4e&EF3-|aB6P~?R5cb@Z_9^`^#l6r!ULBHO-T3Qgb(^ojYAzlL3@M?DQkVkiZoJ$&k5g2!XKCWB~QUefA-Mc9ZM&Ebbg> zMHNgzAxa4$s(-Vcs|EWBA%;AjI}7UDH~FVDNZ4_tIJH=Fls59jJ{4G_Ny?; zH`z-XaP|+4TmK`TnxXOFWeSl>Ar7AqIJNg5^16V=6e*xlLjVg6v4sFiA$Iu@Vp!k` zfn>P7D`cE^!*rM_p$5n_wF7o6~?_RTu^O^J^CQrD%=0-x6JSHI{9E7gfTi|3+Fk zd)67l-P-z4w+#SF19tl{U_{^=fMm$rH4H#lPZVSw05s}=+sXD> zDVOD>0gZ(LBln!<62BS3fIU67%s?H`OBhgbbT=BX#c9ARb(ssL|6YPRV7k+QB+2)& zKyUwW550twMKw-uNGxAg_Ksj z0#F*T$BzM{0@nZ}L*}kw0K?c3^=ozufckG_GwOiz4fa`kx2%Xp9neu2@Xg6qG+>1= zV8E|cX}}0!z?*5Wxhm_R(||kbGJjSpN&}WV4S1-+D9}2MS>!kSYqXkb14d}vpG;vI zSG(c+EF3-qaBB1uf%?@Oe6#@6@1*CP7vQk2wgEtCz+OKFj1F7_kPMl-h5-ocjm6cL zJCV#k{j|k{MgdV|rCPZFA>Pc}XB{o{1%>D*gs4^N0hj583n4~6IWZko!W1Dy(o`cT z#3iQ?Y3A>s5#dLOv4JZDk|A@~7Ge=|$QZo9r}fh~F4G4Z z52u0p4@$j6*X>F4WS>>NPUKZo7^8(Bk?s4@kE6nmM44OAk0rv7L7!!yANQSpq*Is4 za;Yl)IO6mplM17_v$voSc|Y7wJlT@iKDWk%rRc|@T>C8?K0k1()3*Xm22f9<K|g@VO8lt$1E@DVj#n{bJy?#VdGgfP;X1G=F6z|MWIoD0QGGdU+y(!+t(2s+{kK?rp(~q=HKNhLWbb8%_emrveu|kDW+z;DQh$jDN zoY$V%bBD%OXK$gyaVLDgg~R6uPL1sVfcn7{2giZ-QnWDsZt{h;ABajn_WSW;V&M9L zWXRk#{6N@v4gu89st=*V0kmIg;P!O7wBPzYOJ@oZE`&&1EIWlryyD%_@Nc6n3UNsY zvH!n~T*Q~dDMT-InN|z#E<}ZqD1&1(JXD2IzKuH4fU(vAVye!>L8&!9Zh0F*SPF6Y zgurPpuIJ_JA%XhknB0XQxB#!Z`%?9knDup=UM~F#*D+H1ubJq|8VVy&L z@%lfYzHR6J5I|%lev}_T`{j9V&+0-4tOCtnUPgs+RQR#*mt|bymqGY(E%$_}Xi)A8 zKU$QpOh1Y_{n(){^WUA`^dr5~k4P29_uJ8hLcFY}v1d18k>(nQ|4ToLH9KJ8V1m?a z33aOH6mLR@1E`lO-oo@MpnhqVEA~%8()SBU<>8X+~-Kkw^GZuja?}BmTvA2gi@L zKE?%r-#Goqp)S)QT@w0{+v!Ik6-IIA51|kl=V-jxotSH>#=jHYLH*HS$pH(8&kvj$ z)9-*>wDB$PV1ar~0%uDAf083TO5cQoxJW-cfQgy-tG$s*fciaGYIlq; zg+NpaambGl(*susBtzz|Aq2w4SSV26!Kx=5QOpw6-g;sVb31_lGDcbPX3V&R7Q`z0 z?%;Un`nnXNnh;_`Yd3|+DTFB5Kb8vs+d73v9vo#IE|85vRCNlGPK8mvFMH8|)a5lU z>q8t?RpW)vD8!g5Q5FuL5ID6ryzsh!y35HH1gQPz^cmo)!WrXQ5TF#|upc322CfiD zhRj_<2!wSHV-$KAKz-ApT97EBQA3n#9c7LFssM$^D1=DS_!1WYHWoruPPS_@YKY=O zh~3$}6rz_?h`Q=B%?>S|j~b$pQ-~%ijPh;Kj|LR`O=E`s#JPWJd{LD`ET0%<;h+#+ z7f$tK{hR1R0Pn}WPdSWuxSwqRqSAmPehio$xCS5@GCK_e5H|V{Ks||_GwOhP(>7KK zHP=L0n?u)MM3s(FVapWvY7UH3JGC?$k=dhi*SfAteW z6b(K97pjCGgb>Roj^zTtDNZ5UsLNFOde=Nu34NVHbX8%L@8r8QU|v3rHSZG#f3C6e zGYWC=vx626pAb0J$>l!kKs{rMBVoWw+%-88od#fRrr@|X0w{$z=0}Kmfhz=(A#>Ld z0%7B^H&DN1nFC`$ds8mAr(CUr)|)(sFQA5~CWPo)VK9XlEreKquPudWD}*TS%1R-Y zIEDC5UFP7LS`^|prw~n480DMbAr0vGi^g@2h$9ASOfpbm8rSRr2Q3^vA#iGMh~i~b z--U8j52AWI5zeRsZf|1?0hB@<_anrDz!d_?khyCM5zZ{J-ID? z09OhjdfgsKAw~)zo+T(jAr3i(=&dd@c6mDrvBD`te-%dg9(}HbNOy=h`u zZ6U&$=-t^cNlHC!i6YvMcHN$(r4LylO?%LQP+`D>9{Fg%4q-sST&ZZlRAIoPFLrRn z-({x(8`NdKzWrn_s)TT-0b5lV1zP$Qi~P`!8t=X)_UWMU`#m(^dHX{a4xa%yJ@+D1 z4d*GPy)K~MTJsbP02;4n0tVHw4FF05PWdrlS>PIgWXRmL4OqlH(0?Od+)3iocE>4- zsGr5KN=P*Pkd=EoHo0))DNlRBf@%%yz5 z0W)nOfKrIleuP*NxI!QqGItFj5HX5a*wY;O)!Pgb*^d%;cv(0GY7@JiXtah(RB6ymHOA=U)05J-m1T|)?jjrlS_duzrh z7tm-j>V_P)7A*PuENX}yLWtbE8&U{s<-6nEKXxxiAubCcE{%GqmvA|SXs#~fEtQ)> zB+lp<@BT@JQNG@tG@!|3jRkiT!{%zt*ZVwbh&yu*TR40|;M92Z1k?lE9Pb9|>38Z$ zo0F9%o3{u*Z2fYv zDE&At{CM&-hD-c{g&#%c?fU~2#zW!9vaO-?qlD9sPUW>)VN7xrX(~o?@ zkFBxw=|{p#?~ZquO`M#5RCfB|RhK!jvK;-$>-3|a3ZuBI?4uBqOK5zxU)LWMG(P=} ze&kSy!{-N1^`qB$xCa69CUhC^L4d|R2(Vn9EO8AAQ2KGfj~^QY*AFB^=C0uf!p36> zpz%&=;1SjSs=GKmmRQhKb;=VtmH^$3GxmESM0=+Y(dsh4?5Iy6syl_arNa1r z!AEGo-lG~193}QSukrP#6e6WU986G%3#WD;+Dp_+`BeQFO4P~aO({NHXs7K5Q2KGn zj~`nD*AFB^=C0uf!bS@Mw4YK$GKY*71W|j#H@D~Piz8O=MlI<_CgI2PpEJ^rroxZU zv%i{v3Zta(V`b?TTo2giJ$|UmRJ##96BS02_xPd0DDDBrDMW0xqr_q-iQ)M*W~f9z znk&TN^8=@PMmk%NxJbNs?12LHExDQ?7Ulx>PV-@03j&mWT=wI~_Q3T6$&k5g_<^u- zj|$YA1@NH-(7uazd+t|0YK^OL?-VMG{6dHiewxGOft`gA)q;jmh$=#eh=OG)#3-i_ zFVtmzJky0jbaD#uMukznH&4-kR9!SqJwr^`OJm`t6k?oLePwm{gutnBj|$XtD!CyQ zP`?k7qv61%&21roQiv;lgxC?dLLeD3cMTyBHlAVuTk$4Nt&59t0qsZsZcp-wN3C?7 z`%s87LWprg3R8&wLWl#!gD6BpAw;#B5nL@e%_&3%b(!dw|II)R5$Y5oiwdKBYn`J3 zpKZ~Y=mN3OUX4jkTtb&(=bob$4xbP>wclCkWmI>l)cbNniMl~i`#gscFD|u(!0$>S zuKE#TSKtbPWXRk#gh1G+A%I`-HchRIi)5A{EAgZJK-8GC|JAjl)*oY%(2p9zk8}$* zaq-|-;YZCMW{yV-(q8y+pi4davCQd54Rx8HJ{(3r#yI_`rNa1r|6HUH)si10cDzii zlU`%CSo#qgbj-rR1bJOJ)qQ9R0kl`fhcTM+l`RCKQiy0jLhK1#A&?B2orVwy8(j*Z zURkYXj6^a^>@J1d)9ABfR;R5KPNKrB@DOnMMrqh77DvScnc9limx}nA_p0gPEsNYiK@R17BxSqE-X5pX#Aw=UY6cN2{ zM@_?5BVh{dIs0M6plVs;`VfdpA+GrmA|h~wKr&?R8bTm!+=Br1j5>7>qDI0L>iIH@ za2NXbfMZs<;A|A4vk+o)k>gwsxJn4|?9xBuP$i5KLiBjvkwP4H3b9IECe`0Fr=!VO z=@eqU3Zr}v{YV3*&(|2%lGt~p#;NJgL5Q>parlJ5sl7|5mr?tnOc=4qB-;RdSQ-%H z$AEo-YXFiVv(q*poQc+*1~o}2im3l67Nf{d96V;#YP#eE>VW>D$Pf1Lu*i3cB2Sv@ z8y5LAQRG9vc)=B2SDZzDL0u->?Sd@w9nK=ZqQWS_l0UJGQ#{ppr!{fUTa9aGu*j<@ z#NjJ)oZ1QUx`6gV`B0*sG01KsqOGpm1^}f2*Zml9AaD&pGGy-B1}tJ87~MvETCbkx zKBhoqC4Q72K;yO|U)JMRjMq&+#tJ`Lj*I1rzvIG>=@pKQMU}8j`0-)GU+Kp~ryr%% zW!5I%Fb!40F{dA2sxZFajJ6b_U`35}+Y>9*)EKpnezf`axP^lW3UT4oUc2fg4$S~z zxDW$T{dyIy%mEH9_EB6L0hE5+@Z-n9!1V*kkhyF4fv|2xhu}#zP(Qj;v#ukFcBdhV zXuMvfT8HD-=ykh}qyCsB{77-gOFv?SAC*I!(vNMzkKGf~(2s=89b@G`s>?L{`WyOj z&FM!+6-IF<=|~~I8?SLwCt|y)8e^mAN7pIGEgU{SaH{_t)Y^Bi3)r6($W8PifO=C` zweB^HIDU}r2cpuCn|}N_9JqcU88UYbKM>aS2iIi)^;jX-WdMy$3(IaeZXF4#O(9kZ zA-*e=m_j@iLX0?nYYZxk!$JtxlWAPy7vvP;dv%#vvyMzfh4I8Gghz!@zFoS|fIOEq z=IBPOep_Sm7z)w6Ro{=zZT5Icns%La|(62By? z-W@ByRkSCCxFUpTQ!PJ*$mJAbhPq6=XH6-D73>%*pM$XaIrTFQ`0`VYBfAshyEW!~ zMIjcJJYnJR34v3+aqleD5J2s}TB;RFv^PBsBSw7maa;?64@)6#`w`-J;0nRq5V>mz zfv_=F4%~~?@}AvjLHNtaOZB7t0NQ7wTtIIUWd3y>fjEqh{GN~}WU-_OCVqIU2kA5MR7^1ODg;Tic*#GMZ z3kMSvLew|i3*ZMLy1L|J37~%LqE@zsF&f*^_5)Gr#~nX@oD5t)kPMl-h93wUk0pS5 z?IRyc0F537Q1?HUqyA_-=Y+NM@ROscKVpO*U*1~C1%Ua4AAKi{9*qVi;pKP7%3rSd zihfjf`tg&x%!H;r=|^6tAMI2a#XY|lh4^Wo#>Rb!6_5L(`{>8RV<#*eK0k13)E_{5 zsb{DQsC7{z!C}NSn`}Q2m43wf@#A#h`hjG~+%^0_*yw=*Kj)8{UJ}VHK~~~N)gOpz zT~@%4E)Pyv;}Z;`AJ2pzsk4-zA7z9e)%RtlAL)f3kyj6Ld0<1QAHS%}v>20sew23l z(MN^x{XXbNA^r|NN!%GqES6p4mMiq*;wL99986G%3#WF4=q2h`Z>Y85p+viX8b*BK z$`;qY;CH1T|N8OcY~cEVWXRk#{6N@v&JE1SPMB(6qL?N6mSib}XkY%Mb#P=V3gPA?i8Z83Zr~~89)OD zwANT)5V2cVjVGT|2$w<}J|S>w4154*X2yIg3IWtTP)^?k=J>%D0w{&J>qm(5fhz=( zA#>LjBHV?ry?=<>EI^?i`l10Fe>-XA-!SWi zi7o|Dcc?gd0;v61izWkD?Qh!vpfuo~9|JB1t^r7f%w5}nMNG6Yy$YX3-o=ZjI^|J} z+5-b>&Cj`$R=-=hDMWrD#DDS6ad}{8Aw-Fl+eV>Es3L?|6B$AwMmdG}M_uOIp7Z}g zmC(s4#AX%7H>^CA27H+C6mi6jqZsLkNuhDn6ACdxArAb4+7J_`dPeSS2mySh-U<9| z3*LhOb^Z7cga9slWD5b5LfrQw#O1&h0?ClMYY2g`(T4zPKhy*gHQP#|&ahhW1E}Y- z&PS7RDBme-!=Y7&QDKx3ew4h~ntt>be*FArb^6gz_;G*vTdozG=Jeydy3Ft@#AXX`oSy^xoi6o&MdJXOGFX15bQ;^^`5e#%9f`AHG~1xzkkHV zVPk~>LlT`Hi5jB4Fd$LZQ8Zwg(}3>kGSecrO+pPZ#%Vw=6-I&1i)E2#pP{kQU7~BD z#%B|0z~Tj`EF3-qaH>}Y&Vd0yy-=8)2B5wBOc~+3MTc;rWj>wzl-k|A@~7Ge<-ZEPliPyd2f247H> zW+bCJ|JY<8s`sYh9=U^pPFumzKhTfP!jFmnC8r;&gday1-5-GpW0dgYyPb2nc<`{( zkJ0KfH@lqv6BWivryt{07{%T55ry!U(U|`UvBWnT^X;Y|Yb&0%aQOVdsWCwps2_WC z0w&OYTUnS3c&b45xF!QA{dnxhkDGz(2a+Lk*YE>jV>=?C-qcdfw~J(!AS>~s>JLQq zZM#}ABkkPAI;Qditlel zKXy3%_(_HF{VqPG5ch^_9RHlSVuHr6&eIP|Ar2-e#D!CP&6}5~pHrz}pHQNnp2qZZ9jn0k0*ZoxE;8DAQ>`u4L=Yz9%};i(4ne7)E=k`?Y&#nbE*}mt>;C%QiyRv zh@RDQQiu~mh?Or~6k@p$qHx+RTub=KDMW8|nTW0TC!)eQ?i8ZG3Zr~0y`%xjPiuVn zA93&%jo&mlh(2asg*bdd;MC}00QFN`_Ar31So}g=0}LTfhz=(A#>Ld0%7B(6sY@PYAh&ri(&6aSD-Jg;Bm4 z;vd6fi8mn{_az`k_S2ZZ(;?Il-4x>R34zmBd@RAoR=`@n{i*hz;8O~q{o0x^{_dZx zY#|VpLOk~)#Qne(0?ClMYY2g`u0tna=p1NoX&6b=`Nu9NqQ-;ma#PM&#ZLy&k6pr# z)psMfc+j=_-I4UW)0PfHg>hB*(Q)06^dq;^k8jmw61V*0540djGC4-l>#8t{J2Vl6 z_%yt768M}7 zs4EOrKdPNc6po6QGp@-1N&{Z{G2n6F8h~WT>@*BO*tqEc>bEMZv2wLDi9%x$N70gJ zt?KIv(SYm1fXIVaxI8ewFd$Lro}s7`5?y(BaD33j-ZY?!(||JSGFiS}_B*PCd`<(( zt1t?*W^xvJg=QKPq$EbR(fIQ!8qiZA4jK^R!l}`z1R8_mKzlA$7(YC=rY!`bQi%Wj z2=O#OWmz!Hs3o+u$oxe~0?I5Luc z{JHk5g@XwSapBZ{Qtu_MiRh`G(r}{zMD;%V+^7V&W~%K6Q2O!8j~~wi*AFB^=C0uf z!n)Hi09^{8v2zX3o}T9ROh2Y7j2e|FgnB8%f4jCPsc<{-ZM){CWJ^7 zbZH1GjNC$qK?NspwP1Uv5R24hvYgp70To7drx43k80DM#84VcnQsb`Y#7`5QWAsYx zeduHEOL)%0;S&O-aw;|2{bBU2E14;4lx;m6^@L+D3S;Yadf9q30%;m7bAAJdOMPCx!q zm&yL34*h82^kbR|qqw~c`m-F-^y7oB>htCh3+Joa>7f`PoR<9KZ zCE9--VZey9@L}o48$W)$3S2*s44J!z9|-Fi&ErsE0QI|$)LmL6QTyRRhXYaL zDOSR+=d8=Cn$eH^!jESA)6$R5!jHdtKl>H+M-|~m#tDnLmT;8QkCf^%E6QIQkNTsN z(~mSNjN(?C;-Lj`|Ecl!x5NQ6HKuK|AN5Bvg*beE;Iu7wVp)dz19<5>+@x~f5}5H@Y{B*}Oob{s8LPNL){rYwI~{`L)}T zs6WaIKMK8`&ZUI|gdc5}gwc;i!jJ2_O45(%PCtsO%k=NofqwLN`cXoKQQTz@DFaHm z+Q(?Tf0#JxuEqkP^dp}_96mpAs=Hfr;Rn!|jR&+}>k`Ij)f2WKh)O@=Wx)UVe?Jw5 zrTM+wFNzE5|2Ff)_-)U{eG65=|G(>W{r@d;HyFu~xoh}=u+hE%IckGgdb^ce?UJv2tURo*u`~-%bk97 zRhP-T{Mk6vA7h<<^j2Yf$GJx-#K)g&Y;c^I^9zj?|DYdr%AU7y;1|?P9GvQb)AjHJ zsCVVymh3?N=b$#}2xBxPNA9@x1ySiod_R692wXpq44J#OAK^@NO}yJ{jT%XeBHGV^ z)i_9_^H!1C328txVZgF>>$%c!wlLsU@YKO*LHY^<+7zut1GYO27@{r{?_wAYnB_EJ zEW+w1#Yqvr1@p!6f5A3vO03k$zuMTmg;VvP>7Y|m4p~9Fh zgxHj{Erq!16ylP)Oucne#-hpC=@jCY3Zs0_pQiy+vR)vLy+~}6M`MW!d(q{*o%@1? z!zTnzjd3!d@eT)|vHLF2N|h(B$pA_r68RCr6}Unm88UYbArRKL?R>c?@M&JGyX7qj z5Lt;I)t~_NHXp0t$C-*3tnI7j??r_%PWVx7e`ES_Lio|EcLn;fT=?;9{9`UGd*t-v zhPuqy@_FgUai<@5R2bi{;$;f4sDsAmSBUj`Xne4be#BRZg9!?8;Z)y{ae*OF--B@2 z3~0a9CX64>*2MM$QRzowKYk<&TtAQunY)G`2pbg!(3t)YG^XzTKK_DL@zv)PVzv-s zN6<~KG`uc^c)jz$AXFIJg%Ewt51DvTJX5OY-+<+~)B23+5u z(Gx?gzf)tfs}$n=jtdqJpAa~;U!UuB{SUcaH_+J7ANXRSEd)>sVfhgvMc@j7WXRk# zgg{vLA^6Y}Xm`6KnPEl`15y14wE`8!*2@>HmD9KHL4~ne_)&O$clz;6_|d*~L;7(< z_;E8dCH+Y6^dmxDW?+FY>Bm#29|u$z#T|5mLIk@m5+iOB_omU9;|2XFp%91951bm$ zxPba?#C$0bP!Fqe&l6ys=e8d}=|>VjexwRqKadQWyM`YK8x0Du$AsWS^;4;BJ|bN} zWF>x7g95Z)-s|?f{q&;s@8BBrW0&xw!?bwx!?ot!arSvNVg{oAxGMa}`O{xqX_(vT zN0P!9tu1MyMx*{nlG!oNo5H`lyfqL&awarH)Gt8(z5H)u1 zZqVv|%^$uP!sXLqqxz?DV6X z3ZqD`{YxQQ&(%2T9S~&0v>KO)3ZQ;E{oq9gQK-7LaN*JTFez*NV zRQi$Bj~{6R*AFB^=C0uf!bXP!sOLJW8a9eqV%)M0+pp@PJFO_h4I#wagqbKr0U<=` z)vpJj!bp7e-BI{|_OIkR#HvmqW~s~6_Qw2%3M0Q$h@~ow@~!cJ28?>BG2SEMu2&j6 z4BUYVW5a(JEgU`}aH=Z|Zh`~UJ1cS%9H8EeSIyE0N5X%Z7>P8Kx5E+CJ zM`FI95RIHd^i-E=KfW7;I%` z2%OqoCNI%={{y0Y5$P@VFn|$7^2N0vKq*9WKSE>(Tp^GQnY)G%2pc_6pnfHW8b^v^ zhUqRDpJ6O*bIIyCxF3Z`R{Y&z_s3I8%jh^4Leap7S{rw|*}Wh$k4 zGYU1tw@x9pt1yIE6n`^@MUIZv*eoIOA%Mm>>YBBetn9awQiuxOoqSI23cq!r>DFr^Zuopx(8G`|1JpR>W#rMwknD|9~w7PzsUKj}VyyR|q6S z=B^?d_rg&+=>hG#PPwF^#7$P>5@vU$$`gguto& z*w*U;>bdUM@Yow@bSi-fv*eF!GJsNuRDOi`FmQ!HGGy)=LLh8(DuJ9Gzg_KcAH^K9 z7tpAEvFcp5Ds|6JA<79Mc8xm8g@=QL5O2$D3PlakLM|MP&l!m( zW1v%ryef?Hy_%c`H0z~tVoGAXFpc>JZ$+mv^`OfZ4xbP>wc9{1qf0)-)GgK!aUbN4 z4PlHHZD$LCs1)J@KSF#IxI!QqGItFj5H@NEpt18NQ1>u669;H79&vke%)D$ZnZ9fX zDva-hANkj}pdS;2A3wFOOg}maKcYkb<2tjIPCwl0GJOjarXS;-etfCIDDG+>P>ApL zYJ8KLc=fQxPd?ZNKk_TY;qwEh_H1@9qx$_1S5RRfs=J(ApbV_B-u441{YdS{k8FYK z2a+Lk*YE>j{S=EkZvySNY(+AMjHeWc+7AWYo|<l) zWBpKngbF{N>>Nrzb~ycLr7knN>!uN?Kjt|7=&Zsh?p0|iM4R+ih^>Q&Ek4%x(Pa8D z@}nyj4xb-5wbu)IT|oV|`^)eHsHYWhrUh_u;sS9E3Q+oy#*ZJ_1J@5EL*}mG2f{{| z6L`Xlu_7)&1?o|fHRxfqE_=nAvTaW|DvYi|h)kz@Q;0P}h3 z)CDwNN(g*Z*A@aOg-Gj1h@62d1d<_h*A^n2d7%4XYE5n=5qXCn)x*Fq+b{i8Ey#!~ z*4ywp6k?zdqTgAILhKeo{4@McU(^sYgb*cW&)_=5Xr~ax)MXCUJT@FP#4e{0WmFj7 zZ%`&0(0!%G5?P1|HfgLCK_NzLykg;Cg4C`^>eLt~1L`+uaYZuFm8nFJY#_1ms54o-~+U^pC z_(LHMpAb0J72+gJ&I8(06GMr*!BpdbVZ>$kY$5PrDMXMTA@T;U5J-m1T|)?jbsluZ z)El6^-G3C(Sdsj5?yJ_sM;$1{Y#~HYifk0(x)9>KO^GPPb|FO6v46PmFi{J~NP0hY znbrehhoOduaSAa|g;BnBveAHj-)gk76U+UevHw#F5n2DLg~KNVPVMz_UKda|8Jz76 z)C~$}djoHMQ82C#0hB_d_aj99z!d_?khyCJfv{0S0K0JZ8u!)&>N^zfSunc$RqKruFMbFmV&bY=VTKw4A9jthg#bz+ zGWZdqVBiXYWXRk#gh1HnR08z`c(r$2B(uc0=|I$|FxKq2YE`N|n11XMe(Y-JrXQ}g z?+%^64bDnGt_nZ;6+Oarh`F79Y*m-Za4`}6NRq`dbiPxCQQX<{P>3A2HJ;2%T=z)h z&`b2=dxbcBe&AI9Im|-~0@S<4aV{3nSdR+qan|+&DE-Lj$B$0~*AFB^=C0uf!bXJw zw1>VTnPJFE{HPuVqDBuRf0}6Pa;DVuc$uvI+et z>GY$Ry3C4sV~3(a33mEXT7~ibyz$mx9Hgz=hY5(uztT9b{U+2OL%xi*a4s6T*utXxgKiDHHs>xF)3 z9&KGHJ9R4>l#^2YX5c!1=6B8Au5Q(DS9Xb!ndW-82t2l*duP(DR@LjBHV?ry&}Tx8M!pt`m1|h7Wp$##Jq7$x|75|;6T;~J|ZB{sdN@$@7X`Nj*;77kyL z<5bVrU5PdVs5e_xBYmMn{ghwbV}%jV?6Qj-AC^U)*-w!d3)~_{GGy-BMZSoMHrfb$ z+Fqm`#i-u%f!mmj{V&>zzjw_R)B&y%?+%XlztomO)DS{!9Q`eY$Ss6$&yPJbdDva`dm5c_g%zllyA_Z|sL5&ZVQ;3rVu30#ILg3VRk_|k>yKD*p zv|Gq97w~D?PvaT|pcEpDA0bKvt`JCu%w0nWgpEc4sBbIy4mzOGsRZgyINt!WwdytN z!=zu*k4(ak$)7yoO0uTHj}wQ_cu`@L6n@mb^&8g`_Hp`gNL?oOkMLhnVKj02aY}_z z+^tekh#Ors2B#)2>8&x@Ui$I2*EI`=&kvl2ZQnQRn{`TfuM4Qx4D!JxQ1_9zi3Kq0 zkG3B`>BonD{BQ@ZA4rDGUBeHAjjdRLdWt)rV*-(t_)&cbpnkB&t$HK=ykh<3uvUjQRsnV?D@&7*+pvYe+xJ2tO7MPf0)e3qP*8AO3>+qoMGl zMeTW9X*kX4hjsm$_226=gHeBkI{iqa!YJ-y=_y2olrhAc8Hn*SYHabGew51)W8v`m zfm8ib({-pnfO>i+N5X){Y&>Ao*R~%(>BmQY{3si^ejph#cWpnynI-lcG9rn{JN&2$ z1HWw7zivh2a9oE2D24dgj}YYoR|q6S=B_QoB4&xv1I4HHY&rF$Ukj|(97ht7clc2i27cM-VH7(YWBqBp*@z0Gvk)Tv$E&!~ zaFr0E*1?HA(SnQ;LL9tajY1rD3h}kNOq&Uz6k?@Qi0Ueg@7M8T8qoTg#%!Mui^RXq z=&w^L#F%*3EgVcxhzqCsIW2ElfqJWZwje;ft}*5?dlMQLQE4v>}hg} zOAD_!h3Ka)(>!T%3bDf}#9$Rh`5wN2Mb z{W%Ct#xbW5omCj+TQ)Zh@J!HnKM%3OG>segQ;6uP*DV|rLT!|$PVe@`Mg*KZ0kkJ? zs*TbVCLC-V0F(yg@MA!wz%>BLklAS%fUwbr_#diOFKTBr6}5M!RQuX&ylz!JHG2cv zh*`pbz4z+VfEZywf*ECKz&2sPfc5vdS}nT_#hj95mpX(||rIi~^mTk41j` zipDJcS7W53`yGwPuF`;X3USbY5EoAEu^KPY7#c;?-uEbs(a(?CLLe%I$mvIjDuF8m zk|A@~5CUPNjR5Ky{oEN1Xml!pc6Pcwf4Od0JO2BWeykFHR0xXZ;=!lFk3Kv1c1I0y zSorbcTp#)oM|)$ zl%WvThmNuGJ1UIwEjgG5EbXW9&acGbLpA>JVhQdtN-4zQ69T8kz9m5Wl`x_Fu=ZbV z(-KB(*x42WAC^Mo_9H}%z!d_?khyCM5za*0FW!qJBJc2{gupNBvCt{#LtL4A!}@!2 zWeRaz2$5s;e_SgTEQDy*;&KRTh=)Rm^SyuP;=vM5A^ugD>5(U50BVSgP9YwuFuvc6 zp)?@X0gZKs6JMXu7(RF@gs7_!2NM)R@mv z)C^o9kPMl-wh)V$2gY+ud|LmFa2y0^v>-s^E;R3>8`k6iPX{wVGAqpS+!`*j&jA&Rusm}4yQUN?>3=Aj>7D8#`8g}89KUyYJI zdaYJ0c!|biO+=07+`z^SY(Id~k9>aos1vw;AQ>`u4L=Yz#>s%jI4aPnKY)51i3>n_ zj=5=tor+zD`XfoncgNY|-=E2qhSh~1WoP_KKXM5_Hm)y4KiWC{7^W^$w^b+lQO)Vc zSQSQbpBhIYeqX0?xjo)YH4Uvm#JW|L4w%z@hVO zKY-GY{C@nX7r1^P88UYbKM*$VP=I=~eAP#fWQHLt@uTVwMD1w{Zco7r>JQ55ML&Xt zA7?%)L_eAcKY|XXp&uoLALFm@=1RlfPCvd>mnkseMJVcz#!f$~sW84@`9CN`WTIQd zM-z$NQ)wLZJ^k33@|J~z2?}xH)E?*Y67%q_w|vTpsJ@|%K!+4~`?2i@Q2J58k012| z*AFB^=C0uf!n*z#kLmwF-5ueu2+*iMfcgoCdJ5?FEGux!%6&5t{m3W$m>X{cR~mK_ zeq35UtsB~x%EFJP5w+>ZNT(m$)McJ_|CN4pbo#MZg;Ct|CsBy`bu>1fOx(~!NU1s6(G!&wrQ-~`njPm_pDh+rsQ{&EQ#3ze1cD}k09nv%karlJ5sr{7G z%cvHfOVkn7FPl;K?_rD<9cK%Hs1%}*A0ZkAt`JCu%w0nWgpCFTsQpkQ&5_I!U150O z2cmcf{ka$1)8ftETh^}XS?Nc0;m234j&R}O7~x01bnCjJ!e}S__^&{F`mxmMN1BLR z*6*jM^+SU)+UZ9o6-IIYGJ`^7x~H+gEaK(o8WVP2#2Z?Lb$$Oy?RtY#WBCy9W6nEK zTX?7&T7`NPjWa!gT`t*v0Hq(F`thSl;QE1N$lNvjKv>_S_CK|xg8 zqvo-=J%uvdw#I$Ga1H8@#=?&eIya>sGlU=2vVKKBdI>)wia+JDvn@_P%Bjozcr_pW znC|qWk_y9*OS36N{x396m`j{fN#o=f^dq4{9QXz02TqL+2T=RZc^E+bgp^wt0J9Y; z7T2Hvr5}a;_|YtI{XjBg?%IBYGlz5w!kJq5H1ZBVs=@#od!FQOb=z87vIK?bB!u|9 z)@`msTq%U;{PtiMR2UsuUw5tRiwa|fQ-}&GjPF-@9u25DQe&f2 z%Q1#>^>>Y{Q!hq^(L^B*CMbkxtVl*g53H*#UP2i)o^T-AtB)-NPzq7Rj}V@~6#~hS zxoZoth9hAarlJ5 zsjl)k&JNVi$W{Fq>H^xEXoV3MN7_OlDupQOM~D`ID+H1ubJrFkoQc-=sH&EXA{s9w zYa8#5b+1BA8ZcHE(5Ybp8gN_~u)uYrGpdAT!hqbLOyNqyhfV`}s>^JPI@kwQ!ZD`- zeN-3)+Veb%ymKCn`7aVv7u6V3jt2Z)M-K& zjK$;H2z*!?@R=V2S_Q5FNQTT^+kiz(wEi0zf+_)@HePuOw5Kk)J#%W_u|h_iU4<%P zmJs5>?9p6W7$bxzSSN%+Y!gB(YM+NfBy8mvXJ4!?^L56?6ylmwh!rY~^1XP828`*U zar_lxzWy5Dd`}_5L+@BPd_v&Vc!MEO_n_20c&H0#Z}SvJy!?|b1fo)i&;1C|I&g(R zGGy)=LLh96k^ps;z<1yR?NJ1`r~A}9*60JRDa0xvM2eWq6ym86qVn%=JE4X+EQHv- zWHpx-204WYRhMbj@J4Uc5Ko*!3{+v1Z>4A&Fkz?0m)D5>qBO>j{u`Z!e-GTTaQKA4 zsnKZw>dne|mjT@Q1aHIOY)xQ_HMS5yDMT?pLbMHBA&?B2yM_=58#M$_k2CTv18Cf3 z0PV?ZZqMA?cdW-xAFf1&u~Yc*^9S>}4l&94cgNY6ZXHQKt_VL0oGMR0ayk82p)Rv4 zEQEeoSsml-Yg8D;z3e)Lh)NSnY;luVH;cx9I?sb2NfhGn`GHft9%=?!5TIUfs9p*l zO0@U=3L|DuP$I4c!H1wVOn*3#c2EOArG1<~a5N<8y9ci(0l2Kq*8CKSFd2 zTp^GQnY)G%2pi*MK)vFWccDOJC4N+w6R1bg)b8hQPtedU5a62`nc&K^>z0sW}#^dqObOp3E3=|^6t9|cty-)}^k`MB-u=EKl`l^<@; z?P0OjrdyX*pi;XdzGJBbzwY^N-w`-Qt=%hMi%6E{MPv$AFIoZ?CIfm{M7j! zlMUD3aa3OQ9n-i*4T-gIFk3^2#%vHobUVgo4X6ia`0xz4u#;^mu!!$XnJ(YICH+|1 zSy+n82#eQq*uS{F0Fmi8nd6sFIG5`nuQ;|+CoF>7!`cconfc6X(FL85slsR|9K-B2U z0%vrwix?Pj&Yd3ry9U00e>%JPD*o3&ZCbnWQqsJ~nlXOAQ<4wxInOEmveVBWJ)3}$R{y%(KDv}}pjE#y2VY_A8z#N)%&Yc*ER1FoPdL^G~ z%6AdtBcy&*y@aT-4tm4LSZm+Gv-BfY{LNRnF`9l95r6Yx6GP}nGVwPbe|aAIQPcT1 zzg=Bsa^uGIqpX8=B}_v};#L^5i0Wf8S^ zymWht{T6F=Sbh4v2He^|>b(Z!?9=VN2F#w2%bx*XsLPb8(9oX&U#c*QyLaf3^((-mG4l26%n{uDS580W<#%cmt3OS;N`}EMkV~ zGFDsgZ6N+ry>y%q_+?$CQV1Y&7C)*=0NM*b-JbkoR0|S%^1VVd{By*6h4{Tvm-h;h zws{VJLKIh*S)BX_e?pX2VSK+{FDb;0QLz>de&rAsPVL^e+Hp-`Auc4~q(7jp<5(r| z_qy9c09~s;q7ai->3^GCdRK_cF9Ti(BturIwh$YbC8t+?6lVZFeQHiu_4)+WS&d@U znC18DxL7M@@3Hq5dCSW~-&^F<$8>yek$<=#o4+ETpf0nvUOj(BK1qd9zNxxSLmjYr zbgYHLSL8U=^}O1^!^@~%YsPt6h~A&Sr+UfZYDc*+Mo;yyiyYA+9X@7}Z*Q;vO?Bnn zBJb*I&UgTK3y=(1huTHHh>6ziq!)DnJ{_;a$8iP#?F~Y9=_s;R{irqqQKO9j8jr*3 zO^CIQ);#=PKWeoZ{9ZpsW@z_bKav*C>d%iR>N2y>)$-?uM}_fqFaJkBf|M>en1T=& zPVKMkCF9!w-aw zZX<9(#yg3af8op$`*t?Uz}2{ao%*}FvlTBiLiinxZX>>~G1CTUZ$cWz5C7E176MV%iANM-(sBLo2iM;f z!doQZg+MZ7m1+yIh>143jrjEGRsGq&8MGetql4_jRM!eU64N-mH zYrx~aKfc$1pZ`ej&j7EwO!BX)`ZJ)93d4Y{Ygt1SS3=;xe^Nr=)aXM1b%n@1k$}2W z#2pKOwffmY0E_(gm_lqH<@@)>yF$b(7w|$L8M1~ogh1G6BY^RKdmJYO(4Kg+i`j{s z#gFPk@WYx=VF2~S6t*D2lVh#xk9O0KyP^eYm7+KO_)N4QGd4A&A1Oo&lJ$66`ccc- zf@D*dSvQ~({V3{eL2{@tzT(aU^dpVZ1qc3<@&l*#Mxtu!rb4}Zo$o*f8arA53-q`B z05&a?pvTon1e@=aLeDMgWYYLJ>mUfWsZUDRc)#1&cOpE-*>M1@hlQPC{& zt$)Q@IDAEpQ{&+hQ2WnL1JJmw0G=6O7dddiYhBc-eg77^^KOy1Z5Z%Hj%3Ix)hKd= zYrVFM9H_VVXQu&ZcN(HxK%IYU&?vl`svbP_4u7u!&&Kz7uK}NZ)#$wjtZ0j|0S#IQya7mttTb%{7BSIAF9DzStbH0+2LSbrm#PDH@x#bj{HRs{ zQR8W2p6RjH#cbQ&D@2o0A@3F9&znEISBUiSQ}`32kh;vWrRDtzQACCD{f_-dA(kjh zaqugv_tdJ>jcR#9fuWpU2h{WFIK2+ojjy5H0wI8V!fYXc_qV*E5CeSw{(SdcA;yLT zybwr+tWs?uHZalKx4eln0H4->L97yhMwI~6_N+jaP;y4BmAU2?8gO4U3X@uQqXET4 zqi`&JeHxHTGzzspO-2LiI2(m>>N2;_enA61cQy(YR2ap*q48u?2{%*?fx~A2PW4Fd zY&>fM>KXgWaP>k5h5Cgbn_vKc?^oLZV$ZiUU~CWlZ;t!#8W21%;0-`BWR+?gu!xD) z&1PFXYr>}w_jns81W?b|S3POBr|kbRcjoamTyGfHYU5HWmJ)kZOKMFiy=XNkg0?9A zHTJ8jQd(PzTT6sX#U9kI#8weX>@$wSBbpQ=ypovsq-CH$eU0z?VG=6g}gb1!FR(IMt+~h z02D^|sGv+Kf&2bygC!!nX zQBp8Y;ZEloc)$l0YvWZ;&GQpfFGs~=EQK6T$WSP{gRrRGO|l3Mf(++Dl%6^Fuq-xK zY)(WShmY{)nte#ChaWa>&dimz-<;@%dB_o)Gm$$j?M1P6#-StH)^)miEusmOI$M+; zY168Y(jya}eya3HzT$bTJTjb`S@L^5E02t%FbF0`&8tV3lJOg*mk~iq69ACXrQ}14 z>0D}Jva$zLmVTq`!Jf8llsyRl=4GoM9H(Z^1=Y3c!6^!(2V2Hd4+=TTP=`?PS9F4h zMQLD%lrAJfN}q0mtP?A;6f>3C_~wceJ|DQDc_ICfhzs(GBw`DY7($w@}VICw!*I z+S>Or`DOx0Y)bs0Gk$~gveXWo_))B@OR@rbxHc&h;)1)EG9k)_v{EL-{IJ|s3GpvA zQ~O38tAuz+Vf@^bMVt^nQhuOt58MtcYWp$XwL^+emw7n)%Q%q%h&pd*NS;utHv%nrYIewiWVn6b9d|$&5UaG5|$Kjz#UxZ+Cv-v60g5VT&& zcvEOkCF5IXS}Ga$&3VSJ%vT)1H>PGB%W7FMZc1SQP2bCm|5}G6Sl8*F%{Bkri4fGvIRlr&bv-f|?nT z`LIGnTV=pfYNmS0P^%1BPGR7_agsBj1|%JO;GZ>&9n{84&c)_8EX~n8#2l0}z(ZNFd|(o$+M=q<9lSI&Uy> z@L$N$fwn!0zOk{W-94}b8yiwf7anjSwM+4AH^`_dVq-(@i{8W=+ojjn&l)#&L>>)> zjnAgh4fAj%Hg*bclKALNzO9S3wfAVz2%FAPY)bs05%%y3nsYz!i_%~JTjH)GgI@c3Ry{i7$4?f=0fijHDT=~BIf|urxsNjd5pA}B zXH6lc`4q^RaUugC1J7>Z42VCY)zi-#GhlX6+h+i}VIHoe3_$qonJvByfYeSt>DAA> zc>7^f;ty?XM8%77=|W0kRzT?rtCR^bx4ui65QndQs7#2qx&O0Dh}mUHLek9J^95$y>?zH)*UcTE+@A!8bDXXJr;UH_sHc}98L zBS$yP4w8@~+`8d*A96_TE=)R?O6LtGhEy+0>88v#R%Hbg?~%yJZ z%J)@m%*YFxCdxl)@_>=IeSV_63N>@(R%J&1&hr!H)hG*Ot~MD3Sl0-bsnP^7jpu$P=dCvqIjSnrYbJEi2?LDU9D&y6{vy7Pf+< ztN(KTQGsPUKiZX=C+ynGcONcT-97B|xQ_gz+Wl1Yy=D~(gf*^TZq&ln-BU}{4dWkG z{jUp0v3`2*5iJJYa;45{bC-YAfEM$DuzueeG;3U9|KmeSz|BHI1nbhmRfN448J_!J+} zd_Rh`gbWXf<+RMGq}4H3jA@zcJ=>=xx?%RQl$Hnwg~a;O5>mUhg&u!*x~8wDGoApA zv3abiUQT0d9&5h-=L2QpUAcV6D)Ht~GcnUO#)`3K0fhmy{Q^q7LXLVQQJArtrS@Jm z9%~Sh#u~_WGXzw~(D4%)YU((xE_>AoH9Oq)P`Mi>Q%Fz|&NY6b4=SX1s^7~SOuF>G zc}-Tpx-!d@gG*?g_R7Jf_oerhjITbqWySb6YGzd8n^uEMDun@bY2|5P+=C>F&KQf* z{sdCHiJK>CAVsb z??XOlSPLKTOQI_nUo25FetqcYO2(Zlzo%q;qEWULM4MHyX7mseRts$kc8uF)E0y*UDrBfMsh+a3%G9nNC!uH6~4YNli@$w37w{K1~~Ql_zhzQ z?CWFu3_v%`4w5neVRxr#z6^kr&Kn@HDe;HK07&T?%q#2Zydf}NnE^9G+9@+&-%+PB z13t;lvdVzM)XbIn!B!bil*0IZiG4W(wo^i&@K26%U{PF$rB8#Al%``LGv)~7kjX`- zGxBh~9`&ygdEhYHBS$yPmXVMn99wj{4>_dx-ex*)A<6WJO2ht}8?pi#_gdHIB^R>+%BGh5n~u|ghBVf?=RPZ;@i$^aDp$!-T0rCmFu zG_XUyJYOJ(%pS9lk;mwD+HE89u$i_;j&7JeB9JHYCXp_>VC~c~3w;>?DNPnY3e!7X zB{pRRbgwl}iTqs4R!ZchAJtMKpIao;3VA7NrdDbxE99jq489-Em;{%XXepYA%WjC4_(@~{WNgE4I0J(8I{x}Z!(DZ`I``zbjjscs8)nN$ z8Gx_`m0oY1!rLIC;WxevKvbJUU4bzG5?dC3XbgZ92To4cc#=`G<|q^5)|!u%2~o9c zO=UtP4!&%a5J}Wb<2OoLCB!=YHzt&yjD+Yz5`}-Vo258kiDoID!1A#C!Jh&6cL_`T zF=3}(H@IQUfb6erp8@EG*+C)$Qn=IZrTu)!v9@@%oR_2Gp+$P1_2#UAfA7s!GXC~e zHRFU|-&QiNc;u25;~Lb=_E9CQ7>80AKnt&C#sx{DFykl(7PZ5-i7-8+_&`}SOKonB zo&)o+thhj!9xLbM8OX?E^*Z~e5qZpD+apIe%pMWQ6S>o3Bu`(rM8uA#u9-VDO9z5Fi$k7e6Wd!mR?sV#Q!5C|chts_r z708{gy2)7qU)7zZbos?LEtQPRy`X0NQwdAP^{JUUe-yW3{2qk?H1H%dE=>|eXN*O0 zJulh;DdrtKEZjB<;6ZF_w_aDhZDj14YJ0}$hS?MnW8Nf#2l;#qDIOp7@+J|; zovsv$?sCsmGHx`rg_7~`uo_AqKZ>|u<>Rf?%#SZyGTugE04;b&^D)V}`d`ug(OA?N zPsT_Nsog?DuZbmFlN9|UTa#SpM-F+m#$ZO?Pp?z&7?I~%V0+}~hS?(mc_MdOI()<0 zNi_!hG5}IcSd+_1ifIm~>+2M{&EdBh$_$u%q`5K!(#KR+WlI}cpx}H!pb<2-R(A%@3d1Wz*d05`} zBge`)!7a7JH@$v*--!I|X4@l2H_VoikRzNH+|uWANbwR~bu z|J`k-ME=gws!HVRww<*?KAf6q`E^k%m& z#^WwmQ8Lc+?2HxT>(osA$|6>bvnULp&Bu?2t^Xm3qT3paTL0qUV@PfGZ54)Y$jg4@ zkV#kDGV(CJc0M#BPu*{O3TOVVrEhbyM9F=BQBDQ7){BOuKrH>Cy zYpV2d!A5GvlR8*3?m*2{%wx&8BZUDpd=WElKoW%+yB%1R=GP#{HN@AVR)R6)XN!fc zArlt0W5!Os{`--UvFo($8KWC!QwYY1+-d0m4Qsm>weul|6kmez^2*ZCy@R5zLsON= zPiHkzA}=w&veMSGHk`Jy_3zY7Xt%;vw%$cy@NJgN$P-DTF!Cq|7Nxy4q}HJnxExZX zw1?#me+D2L-~KbsfKa`5JuzlLuIskX0CdA_87Tu0mIijne(gW=WdNi$15cmMp_?vA zN&|b1ZCL@IzoX88!ylIS`-HErh7R9ijqX(44_vV z(xTXTN3)a;&=9S%M3^3OcA@_<@({g#`qYR#`+@C|qZ?++2;?ce4I&Hu&&L>Ri=DUA z6;HCstT?5ue_!*V($-JAsG$xUe9Fq!i>aB{-mrwagu)=$ttb|yX39keT3Pco3Io};%n3N=x=X(ig(*g{)CQMW%%32ly^5Wl zdx>VL4c&bC3(@>bg;OEJPjz9287H+m^hG1%m_oK^jBc1+AQ&g|HjsADSUc!c7oTw< z#ZwPnURgRK8%x{1eM@x)9PQp%>Epsh)EN+0#WDlNQ!{U66tv2KiFyVsIx+?s@HI&k zJp-^P&7VMur;DR`Woh?}=tzGCK!(le${DclN3BlEZOVW$w$A``!|Wg_0}z&W&yayL zy81EzQcR3{d4ov@X#Y|4;ZKu!3^2bu$i1l%XMp+TLF;=|;xWMd@}Re)Pw*I^c=q@a zHM6I(mH~>F2R)`RaJTFJ12W(QNfbQ;uqYj%L5dGnMDxnh7=Y+)e+EE0*45+;n7vl3 zBVIOUKx$>%X8^ikc94_-2uouCWX9T>z6^jAFPio829plZqJPT@c=g^SWd=+vpw56l zw^dYTK$FAAtukOFHFJ98t2_oMGGG*ifjfUTXMl?&ik<;jl*Ry#(m5G_!8+OjDIKpt z4qhhq0+4CN-{lO5(Cb`zj2V#2Y5NR7H_Q%_G5}#|41kvA?evqk6|h2{o5J9`XV_Sn{w)0{6dgGhCDTJ{^W=2ndNi*r zjz>K#ANY}D<>cY@8F{!~Cpe7A!?L@-X|Z6FQoSUaZndp_il+OSA7km=IO zt#Klbs5H)BBAI{N1Z4({KlFhz19p4fP@2B+{0yrMxI)dG47bdHObP>cS|VqFmn4dw z0a(KU$Jue=M=^d`f~>} zc9KNl-{^K=F;E+*Fp@)x&#HP@wpuP+j%fU{_nBd+UN1jpWbE|Xo-w*%HiclE$eosU z-dMZeviE&1hm=m?AjR8tovuS9r++t|ZEb$gu+XFiY-{s_h9AABAvZtNyr-RpT=7uz zQEI093mS68gN7Lt2Hz_GG4f3$Q5boY1B=p45Rlr@2wwt+l*V~TuRjAIXLr^Jhv;?v z6UGe4IA;3{KsU^m5gCxeTPU(~10Qm%U0A!x6C*jKv@dt%1NZD}oBL8_k zIpp7d)j_r}78)nN0(wmfR6^@1&-wxnhb{_U`W`VoaeaL8Z}Y+aco3PX)zslA41DyCx*5f7k5vlLTJ z9+r((2wP)iXWLTDIPFudE_c?*I49Q!9JlT9TA*VCbz_gOS2u&uE3-!g@o(TZl0TaePw;+5qswj!OEk#69W!e9nI~aX1*(@ zC4^#TW+#O~|NF_D5DQ46=m~*EX`F}D-fqhC^N`|#gU126$+zjIq(X+iQksFM=F{pG z=ZpyvUclxFaWe?rFdIr_Kniy{*DIxc$g#G#;m^xa?PfQ=yRGK$^diN}KPZuZ@T{H^ z`HY!Agd>eF#s~; zcMWy&POWZp!H7Jzr0tQT8)nN0rN$d&)hOf zAHT4EzZLT7)XdzjFI)L|28F@*k86zldy*(Rax6~0F$`}N#8eEVIOp)Noa#r8=JYsypJ_zyXlQ%n=!V%N5^{tiZwTa&;s7n3Hwm^K{?K$=p562`dPOzk9v`R~$KNci zWL!3nCF8u*%;xnkSuxH>Vf>(dyQ6W$euaKA3jap>)Cw(1yJtwr){syAj3MKem1A26 z>-F}lM#ecG+nzDHVK#-t7-844az0x_iX$?*+Z<3m9;I=6%zsyD-1wFjP`}(~W!&L_ z8fXbMT8Db{(-DB$fh39!6^r8B+QZQStHj`pXmIt1Mey<6q-t8-_PUYc><+f4h;EqE zUZRL_cD0AOd6VqmZ6Hpj>D8(fl_pHClN@nuloINbTXmFBor_8-ow_MyuNBlA)J&_d za$7m|HihwXFPvehdr6{j58MtcO6N|HV(9U3^s=8ZqA@d{GUGtKK9yx;ocWdQ8KWC! z7YN3Q+-b3kO<~!3=2H#1m!)*N-1QGi`>Gma^T!bve5f%te;o1Hos!Jh{Bgw3^J|P1 zA4lv)&15IP$cz;qNBn}q0DAsDGj2u_MQ4mf?Z}z;xRBDx5@gq3gpVQJpFCs64!!Pq z)5zEvWqZcxhS?N?af$=s@K2ukd<-cLLcAQ6&W;Y?{~9uqeQajzomQKDY-a3eq-Oj> zhkw||3dV=1nR0n786T!FfS!Kr#^Ah(B#O=$i_#rxkQ#EH>xT6D8AC=y|H+Iqhimnt ze~pYYM%bP)x?whj#2Dd_=s$goA*C~5Na^xMvp=%}4j+zDGH!eG9VO$*Kb27WIR7TE z731dA%(5?Du<~&W3IpiFao>Y+2uT#3F&4$il82)otQN*a)OqDEhMIO+tEb#DLUm8H zJydkV>;eHbkvlETa$s%8mA`z9A;nRZmsghd$H^4ET2;-sXA?E!#dm|0jDrhUGTuVX zq@?7sV!V~Y09vZ}5HOxk5=Cc>Me$UChokHLj1diMy^k61Yo*l{?id*d&9OaWbi?cd zi7~>`4j3}9^*$eCNO6eb`F&4EQFg+v??SK>=^00hkjj%PMPRD-D)_Jsg^IaqI1Zl`4=!inr%@c?(HbEQ+OP1-wyHjeKznHS$yc6;mSbSlAMI32NrPy{+8g45KDR+Y7w!KVw zGYH)n^fhaP04Nj0?E)5C~7sH*Le zqZ?+A2;?aagtKcL^f87MH;;NbD!pdo%{??RxOW&czG?ba#<0v#W?a+st&GjHUSnJ5 zH+?Ikc2YVsZvFhXGAdCs|8#o7wtoBhZ)Jo~7(gpM`3?tY7wIRX=!~%_K8hU8QOVYb zKK3()jE`B)j6?Ohd`}}|M_t=9MmNl+kQgJ}FJ`%qF{JkDyUn6o;_%)gzM90b0Oc^mNpF zLzTAf_gM|4tyjLJM*dbAOXLn}W@q{%E97}848E(24+8QV^cztac{EG0^YO5Jd7WU4 z6*Jl;G2=+RZr;ntIQ&!FGe$SerjQsTEbX2l6WS&D7(}vZAKsU@Dkum^b0X2oUL45wTz6?NA?7Y)CicN_>G|nR` znf@lp3IBet%z(TObq0L6xv(+=cJBSdDg&~qnU2FATABV9h4K4VHQ@|6KoW(2vfF`0 zF`*VMNj_df^r}AtAk%hf84#h@W4<+JK*%??&j578Y#EUODZCA4?-I!UTZkX_ffV`S zbanrmMu^60#uYnNQ@Xs{D{97PDp)e^LCv`L{b$AaD+&YX%1+FiS*#^P%nMv=G~zAD3RA+5vW9-vSXJO@)6X`r+sp) zTpmMV@V#~bBvBZ-o8`fe@g2@xV2sG8+J$*Ah8(;>xEwM*U^_Do)$6VUjEr-p z*`6`FVfKi`7~y^a+cm~s-Ui|YmrmCk|IiI5_XaW48>Un39JFcZS;P`BUwR)Xe5l4;X5w;#8Z$Ao#z?{($;2Nfd?}#Zueb(5vsU=pF0?&kbi-^4i7~>Fzv+y3@HP-5Io%vcQE^q<=~{)A zU(k?enUG&DQJH-lYC>K<{Z&Su&xCy8xt)ysljo7Ip=O+u?=$im&m&KwF!=7c$H*s; zMA4CBQM$<&GHC$1#4j<06i=Ib9FR-=$RYbRnZmZtrPpHz8j(9!*&aE%VYZAwp2(fn zOu-+Xz}jI=ruas3NNL&}GV#^{8W`yy)*}1Zy=lgx+w!bZ~GQ!Kn+s{OnXtw zfV`#*2rQ*#z{k&LKn-eU#h>>$1FAot0ihHI?zcSyVER`{qHqSdSxWDqM?`u*Ipmw0 zgv%kblcqEB7`=XTun~DkitUl38)nN$$PpGt-6_0F~Y7xf-$6YYbm7I_0ee<$qpFMd>sQGMsO1;Ro;`rH_k19`+-LjGZ`#Z5^c7 zd50O1ho7}Qa&*J&5eYfM5fkV5Y|WC7e%9c^38a{+aJqWzr=z)?{){}+Wb2?p8uF?p zTenTk$H)Urw%(ud8zXP=ysdjuGrh*#X5>|#w{;|i!FS1LjQk^#C^~X1N{4Td;u)=I z2c*bh56kY!!sUp@d^nep2kP}t!;Q!@vuuwX-7s55AW!5@ONVb*yY+{2eHj2L?hEnq z%F;)qE>kqLqB;XsH+YjxZ_a?LH}Wbopl5((23(_Na;?8*l>rO5;4F zG>hK-Kvux8-u;xOf9QEbiM)0#HS+Z>f3-4w4{GM4oNO!PUr`u*55Ld{$QzMF(UD_O z8|Ue+2MAsTD%h6c>eA zQrtz&)Vp!hisEhx16ky+OfjA$icS%W{olvixcIGur)(;}wOFVh8MWy>lol;Fa~?GUF?z1L<*p zm1o9POb61th6J!vUp5^`H=4eMo!b2Q1L-={%!v;)#+9ExkbalK0NV2qGcG|AMQ4mf z>2V%N=`f0;TZM5U1AEaS3AN{)j zd|5fb-anIKHNgH%%}kkiLv76z2YzI~dV_qK1}XLl=^Ou5$*ACyB!U*6qNeHYGwI?enl)>_?91?Asdh5WNmOYeXKCYoXnD!03i~ zV+-Ud-08^MVq;@%ac<#swLP2_@JWO^A^z?ctQ@QJ1gjHbjMFk9{zuJ}y_BU+h`Nr? zDGX$p|MtbP@w+5Zbc$G%?lFQC>Ehv)KiMXHjA%l!5!zU-*Q?JNq4q0abEqlYD|fLG zK8v7NV*ljjsC3x$Cq?gm-di~s59n7;IT-&^?j_}5T*aAeH5jK;GrKNcXNZcycn^g^ z?CQC%0dXZs6oweZQkuv@M4Hur6w@>wUU{dVDWdWJXiP)(y7~nZ(-JmkdNT;!Fq=Ra zHIX|l&1zune*cIJfE1^=>C(#l#$ZIHI|rK`$qFd6s+Te$rtB)KOo%;Exs?eKK5?^E zLVQfkoO4*hqgT}lG4|INl?n0kkxfv<>knqV%>J0e1v}Fd=pk{icU$x4BPznQg^$EQ(Boroz z!WrOZsr7Y+qZ(L+}LO^gAM8QC2fd8A&K$}}R+2(vwMbi-^J2|2>j7yy}&-O+~} zQnL)1!pqxFIxJW~(NeP`m8PGQR9cDrP}difrvKEv(aQAk)XeoaERipwF!)wm%*aQP zL}BDn4lGKC1(4G7e*P%mObj{Kp8=5j5;}1Pxb*t>tHuln`o#7bfNq#ABQhX`w@`dS zCm(XGEgcC$N)La%mO;06-0rDFz9gR-`RSBgO5~jmY_LLJoSL~8ooVIrAPR$T)f7hl zfPN#2jvR|xO7k6QkebW+Yj2RRZWk_xOmlT+#u0km?Yfb%qoeH^qZ?+ANQ@Dl?dt4f z3@O&%6E{wdjUO&q+BG2h*d*tYb z*&`BigyVv`_>e&*z>lBhGI&v(E-E%ZYMGkvd?(-wZ$`Oa(W#pNMw0id~ zBl3{RwnvU`m@Olar*Nl34!`STjJ3tpFS?{jQabNya-81Ju;NRl%LnZYQZioK|B2G& zHO8;Ca(OdqCasPo<8TTC=&xm&aTSs%I%6zKr`nL>5Rwycc(p8LT!95$qMR5YUbpm zi&njNfi7QA;+RLbVEwEX1Pyn>FndHGPvK5GHrDgm8f%LyOsL?oHr!;^ zFGD-ow(*^V=!V%85@Uqpa~Je6hLn!TAf-20dT8t3{;ZqQ$Nl=eru6a3GHS+e)v;te zhML)V{+t!#A9TiXL%#syNRlYbIEtloaSRdhx_=KxWBiN}&5SC-jNN*@_@t3>;3eBL zMmNl+kQgJJ996`}7*ZU-I9<0%K3?NeLLHJ;R0(zC;Qy4ytrho+m2vMn<@kBN{wEh@mFU)9TbSMyR=-+8!#pVK#*X72)i8 zK|ZL4P2zNAP&Dw%u1e!h9#%wY-1I7Hip@T>qbGMl#5dF}IfCW)d$#iB-$ZzzBi#|$0^ z)e@* zd&zXE@#ernY}~g@mm1%CQ)8Ulbg6Oq`x@hB&tGZ`rDnpeonpoz&tGbMo5BEk{SGrO zP7+0Dj74o~j=ntaaX?o8LpT*OwN5#9YHPiIe8~v)Yz^B(MK{bYkf0(QSErnBG=|j9 z9{7zF^GQD2*hxuo_&&#riPE}A`K+WuJWJz%$g@LT)mtAmd977UC zr-(&q_=OZ_a2{THwjU~@sVTP$<1HM*zn(^hDYR2Wy-&HbR_%OkWaS>|9x%{M+Q;Sj$PW_*`^BMSE* z+JQysxCt`!IY9em~Y0epIM^t&>V+<*_ke64M z4x>iX)*aKQqteH@#}-ujxIrB?<87Z&s72{Z)@urxrJaIuXQva(^nz*1v z&A9y9I7sQ%eMphRG><_t#-9O@K|ej>3`m%-)l07#Ga&dg+h+i}VfKiW0SHS|(2$w) zA88rjwl82*r{frR}{OmC^j&G;c&MYJ2)NZzCjBc1cA{eJ|r_Z)~?6Wo2 z7H=1Fy86=Q++Iu#_5B)ZsP5CZl~C{B|Je#^e`;pRlH*oB9-u?ru$rN^C5ggN-3}~j zPUXAuAbX{Wu^Q4*;0aTlonNbu+%Qs1>SKF~=!QA%C5i}V3s;en3YHCUG3N=&j&M_;BnG^=H^}CtkZjvavHL)m7BSVUZUOf)TQ+}xY z?{;f2<92Da>t7?(TtjUS72PnWy#y8EeY$AI`6&`0kinN-u8w zX_=K5J5e*Aw6LVunZiK!@FY>(!C=It=R%GK6h&dEZkEzL(uhbi6_Ec+7fyxD8TOQ& z8mrf5vrSOP+8!#pVRnH872&jDPkl~>6yvRzH<&bW@ef67=F^ayZ>CIoT|;iZfA;$R zY({RrneyvvOBuQ1X3G84%!{)!*tm-OXAuU_|L(AH*ONqH#!(I|O8Znu=>{Etl%Iux z+~Y?M8T#%sMxI(nt9#uxB5yt2_Q=r}mSUW!J zxDPp`n91_;%F;+)`64|6`Q$St^4E*0k$2vGQ;Gb#>*^E+-@N}Z z^86%GbmUl+?z@8&7fL)1$O?Z6TSF#wJ;TVu^g8r`5qV6C?UAD!W{*h75thz?A!E9p z@gav4Q-5CGLei`A7gBUyXEpK?gYqg}-tJ8`@&oT%B40$!^uBi33i)CRgKx3ec5u0e zBnl&sVksSUBO+adfRrvmK+f}L0Ax_c5^Z2Vs@4DG7&D;XAGXf`bi-^JkpWKEE0^f= z62G)l8h6)jhmzv6?`|lKJABe2E8`ZRW{TCbpqRp(GLJ6tB_4jW7>&Ig6^9UY9k0^= z1-`?JeFo%rX=M~0IToekHAr#xOcS3%^7BrRuly}c581k90wX`$LaV=dXhiNhXnW-7 zhS@R#c?xfX;Fby6#-^!FT3edu8bw?8@XP9iXj@jD5R<)G%7n;&Io>KE#!xfMrX8}f z^$$AZt4o=2Pm(Ci*zLfgG?GJ#xmpiLqy113P5Nz>Hj?Z0RrmkSDDUN5nyoID=@&T7=Z?^JNCGwfS2Pl#6A8=i1 z>sAvMTG{$LY9{ktOXLG748HAKF!IkyqUgx6DCVo99gyO!lOC3Ryke|IH1wK=I`yhn z7aC?n9(&gI$k7e6M+EW|?sTqef-%;X&aEN0G|&HHm9c!@b(Q4b585ze^K?p!K#j3^ zI%UlEYs}a@osv6a0W(%ir(CCI=8rzWwpL81WKkGEBf2r;e@LR}jIk(9nL$dnhP>ow z3>mU`9oss2kyfu6Ze;AfVSC2thS?MnV}x@St@G`VAtmE>y+R-RX{LsHuj|WfTr;efY!rATD`vzx7F_w9GlSs#0hbj8wyw*zN7T)lZlJUpguPTlE z*U+D=jC+)t`7*?kaR!9}wB_X1V7!GSiq05|;#mi})sp0XKUB!nyrbEvt@YX)V}u$R zu)*#JS?Gq@1rk(*AZzg#(OwIVS_PLc#jdQ3OzgpgsaSAoF+`HF`@fHdLXyi&} zJf9?r&KQf*ogR>47RTd&T<>QLnQ(g|Gj{6rIgg2PIomTvH_WDx7$fYyJ<-P)QW)3E zn?#z}s&SPr@yz{1>Eo{JUsN)l`^6QdkAsHJv-0uV)XdsSmW*ps7(jdOWX6R^qUemV zD4iWaNP-_pfNVzPFsKDWoB%?43*-Y%ZwG5p;k~cpAPwleXO{hHj%;r`qeRJ zJdPv^Gmdg#QA}P&vlOqL^srpyXN;9+e=(UEhv;?Qu|~$>PTMm^H_WCGj1#%j(kuto zj{IV>4>_cm2lDdD(%DhDYxG~&S0k^{?gh5B8F{bVYUG)vERmO|W=5uYt&qP?Vesvd z&B$|;MA4CBQJTDjy!+&k`)Wo0#t@`-6XFKkUkzDuzi>HZT*)b%0l|9xQ>-xqGC#C^ z2A~^e%Sai3u<&sTZv$7!DZUIqRGfLFa}-+^f9SOg{(npF>2$g_(#qF<_((YhL@vyw zOo%0)TvCn!<$KPt8UvE4nJq;u6C#De_ZET+q=!V%)A|X zb4w-idwZX4TUzGzF!LA?I^v=d`RZA-t&rEEW}1EYx78ScF!;Xxgpn5^iJ~LNqBI6T zN)slKBEvln$SMcK7yy|avyjJt7`?tR!H7JvtL>4a8)nN$$PrGBS?Du8q}bDYwM{a% z7;U5_aQRY-p1#vUc{JB4zlPjAe==+91?AD)Ylmi89nJkr&8&|3%j$@IIfcRZNbZl} z@>r56jNHvqn)pOSx-JR1(9ak$Xj4ySoUl==CrmOjj`+s*jL{9VM6(uJ>&NEGp}XoYPn3*%b~>*dx-We<(`x9RLCr*$w`4qv z!eHF2{3r17P?9M4D`JeroVNH3B=4RfwXeAI@fzebKV!)FMg5p@s9ygXXJni?#`cWS z4YMgE#t8RY)X&ElQVeZg-eBU(uTEEm8+76Nbhwi7)%%Z?jNkbAoRab4-)2}bu1L+) z@11VtV}t>;sgoJML=r`3jK%Ebf3$pe93PWIdQ$f+YO-lPj>#cQ9TGl#3P~@o83!H&7Tro3vuaGf1N7jIk(P&w!L>S0I1!Glq;SG=Lcg>-DASM#dovZO<6p zFq=X!PIMqFoq0pL3Jvffhm_8|A*D&v3OBO?CcoE=ZGF-7>~j9k9be1Co5>u<$Wt zY`VrcNUy)2VPu@P()Nte4YMgE#t2L2){qhDf-$6+7q$SAgTpk5cBWkjBwYRfn9LV#LMA4CBQ965u)IQC^M`Vz- z_z&-`AzjkkZf% zDR$npwob^h~4#;!oyGe$Se9+4O$96I15A7jW5 zd7G@o$4MZ?%?M6cv+S&ZPR%}4+WL6c9Hp&aE2w5Xy^eSo6HzizB#JY(boCF6aeCzU?_q(S4JMJ*RNhPBJbDQ_Q=rCJHXzlyGIc5cX0 zT;OVShfKfa1GVW7-cg%=RE9DG&d;4_l>tqtnW4>6tumk~g@HTf!H39z3M5hV48Wpv z85>f%-UTTx;L!utB!# znzw`QxyX z@z68ltQb3}nW7VaweoRZ3IpiGt<3m3{YDg>F&3qrH>B7#c^r^0o)kWYOpB_`$RqUH zdE1CQb*k-=qZ?*Z2;?c;>Df`WeT=cTIG*uxR61T8L0dPqvzl>(LD@W~piQH+i15RNXSEY^*IsUOYfbnuvI!U`r(aWprv#qa~E`Wad=f8}+is=IA z!a;}F)-RhbfR>pO%eHR*`~}bl)Xb*(8uH4|UjWUaF!+wY%E&WFqUgx6n1I_F8uFDA zNYNpW12Wr>95VTWhCE!aUH6R0bFH*Ja&*J&5rI5~I~{vLFvi-`gI@aItJUbjf|sMx z+{@7WwCj6XPszAoaW&%>e;iaYPCGr;ig7eG(`~|5wzY!s2nqw})9hwA1nW!^MQ4mf z=^iw{`~{OOkONPNp&K%y+y`vy%(7bj^uCdC_Ga5NMmNl+5R4PK)6(7=YloEkz-Mbn zG4OeLWy#j}DLTBa8u_C(H67Q(P-eiL76+83@8A6gE7N~N&EyNT%z$qx4BY#l zaRz)!5=GAdEJ|nIkkY+PkYaAh9V9X! zg*%-(qoB|9SX;WR0+~n`m%j+)SNLBb8TF4-iTu{(EG6=)GxsZzC$1i2h5QmV)3{@b zmFX{27<`{iZUocsA&J7s-7KZcDu{?{`W}v+_cKP+Rj?>C&VE&^GaeZkr=GSwV|2sp z5y3c-J1vd#SUa>}Q6F+h>4=^GucJ%)y`OJ6W>|aV(5t^otC0uSRwM6tai0?TvB#sW zkoTl!2CPW7LjE;{!M9e~#z5YbB#Mq4i`u~n-vj|EhAj`T-1&^KHUGPDL5w^uR;vd+ zF(Oa8ZhPeDhS?(mc?x%WUu=+%G1k_G?oBv+gOm>6a!6kM@?E8^zZia9Y3rY=su`DR zV#)X+HM8N?W-G>zC=8%AYcu2HBvEw6Sd`AnAjQFn#{qfU&loZ%tOPTT)$2u(jnCu% z^4-kjXi`eE{kM4v;tL+Gqto^@px0p?YI7|Vuf_7|qVqJJE9`DK{@$6l)Q?y%HT&5- z)cf>0_=xuJb4}>;-G3uW{DHRc$G5&OZvJ<1`oD`AR*nDvehak!H}qx@x?whj#2DeU zuo6DTkRt89yh)_vwch__1ot6&Juy$&WKn^KAH3BJ3j2|c2;z(_!tGvMd3BN~I&v&ZZxM&oOwVr-hir0AxEwOOcWFi*qt`vZH6nNRwmoum z!|V|WIl_|5Aya#o_92H9rf|AaNd7tX9kz9*X+o_@VkXq7*Fvg3q8t9M*HSWW^^%(L`1OCYkIjr7 zf5%ucu0hQ#a&KTCD;S4T7(l0_G2_=rqUemVD28s21G4IQVO+?wCp4)2^mR&!;eePCi47>pC{-a^dYYIMEtK5=BRjMQH{NQXFx5c;z|%3_vtvdRex0q+VAW zV9bEXskYAmbi?csDFYBrm|oUrYe+Gvn9iF7+YW!|ybDq3ysPMAI!&2VQ|ani0*4yjx)fe*E^z&8Q@r8`wT!g%np(=0O9zS<$M_cDXs~7d6S4Cfu7{1 zja@18Z6)$$xzxzduGynR-X$&C3i(WG=D~OCtV};kNB-Ku58!e)NfaG97Ntp3Nb&N+ zXkJ;`mm@mGj~p^E^l2fSQODQN>aGKg$a4~Hj~v}FTSh{T@YxzqU*HY4gExsdQT4Kv z_T?`;p-IzfYUHb-O&^27p`$OEXE##`1}Ax}32sta3pAc>+g#-cVb(dXkm9PRIi z$}7e{W8=mx)arR|Bh-vtwug#tm|Y;CCUU2xb8D=<2?7(7T9ktbiXJ#uuz>=6k$!m(X5e8?fiz(Os?X1oZlEyuI+`)^=_FAY zx!Zw7X_gdHT!{B@G||r((S*GkW2at^i!m||e@UAuxA6-a&<(RkB*qB4_X@_4;)u-4 zn?$;%`DU&g0pCuq%C6SE6R#54L0+LSX>S(}fx5 zC5fUl#-eog3@PocAvzY2|FDIJ0#qCw>+xF97TL%x_Pd<^NhvW6MYzO2=)#uyp9E8Ctix?whjV4TQX zNIIFu+8LME_-qX+-AM>3*?JId`)ac)D{Z}U&1t2rFL(J}Y3nZs54N(ko0@r2!7>BB z*E3-19L|7_BvJGXz@l_S1}PnpK}vTZK@RX|0AzOe4V(cndVTB%V+N$vv3&-h8)gSd z8Gx{KstuXieS^>Rkkb9a*GO*r_bnyzdJZ-6ftzA-n$O?HDH8XKoqLt}yP#ApU zk{J0vBvEwaSd>f;DNUI{UiLGF%q+E$8N2m5@O=IA_`iI2nZ*R2;kb>D$j}Y5MJbO?>-cPSrUoax?SH||p(G9alB;*K7 zwuVePD3C*niv#pIFOt$sxR+%AIU!1y|GW02G6O1i+o5!M!uJEMTz-t2X;{%R1CCP| zxF?_H4A@8#Mb7{%O4l?Yr8~wUrGXvN>(2nlj0v0A)RB7K=#nu50xR1-1JDh#gG2_T zI1o;lu*v6gNO4u$%TZ}y|2Q|D@%&p!iF|AxHS(RCQkBTV_I_uDycIQbY-oa&>0476 ze1osNi=(+vk|>Pa%~Fiy(JZA?ZLAo6O}HF#U*pZp*rnIkE*lxQe%JPl(G9al1mi^B z2GYQewc{Ia_92H9Cox`LS(-!LM$tcoEl*V~T$>osS{22i0irud5y2omDY^E^-!alTp25_HEmJu0{ z!doabcDoNb)|M`DLP{>L_0o-i3ll3UUEXckaV7Hk?Y1jjUh>;0E0@=%X4aRmL|%u& z;QK+&+i-btk|;WIEK0j}$fN-nxVGbpCuH^O!sU>z_ER**5n5gGnvrp68{0ERH_RRp zj1#%j(!LyPhqj;MLk_9Ec96dcltgmq`8Sn}|9f~$$@rbb-;|8k?HpjmcpWvL!6O3n*M9~>zQQCP!O7m-wVo&Aaf1Bh-&e5aO8F|hTt=@Irh&;H9?UAD! zW{(KuDcou2(djR^a-t%s8)ULTy5Bjq%6N zPpDO+X5L6z#*C{!KcQBg!T|bb@mgSkmRA*IV-kkZ@>Wce&%YsmP|W;5eZ zy^gqHWSrW|_KeXDvqvPx2>1JJwvRESNP91DPHD1b5u!uhU|XA!U!Io1wl*U#-$;#o zVTb-~YX$P9)QmHaC31wp_mAp~+(QzDkw-hQDD96S=lP*R&Mq*Ap@!&n)=eW+*I?U2 zMK{c*kf0(QSzwM2Dx`Gr15(-_2L;>+DE(&zhMHya@!T^<8EUA>$A>3xV;|=;`MB-! zehl@K=Y3p~n#pRrlzm*|c^{XeFbM8$!cZU6Z$x3JZU+{%H+IqvIGUw&5fjlOH-vE^ z<92I|gY|lRwvln`(Y9xdZkSylF-F+6TQG(cm-5qj3yHn8(>0&A?!F=#;~OT%pH$Tt zzinbX?!;DR{ECTjp1XaSajWMUFQjJTx_4GV#dQrqUemVD7`xcQhJFg z>*qb?B zCGy+|c=La+v#rg@m-IQpwl*U_T}F+(Qyoj>rKy>F=NDTcFGFGczPdxJVfXwZNfiFc zQ7ol1D@3G2Fi6SekR@*lmqUj3@68#I+E1$!?ie#5>?hl20J>qejL3jQ-a^v3HP+76 zzqcnc#0K#G%Do)z@MZlottRn17Xlr0qIxMm5D4m8uww^SrPhk&d0Hii4%-CG9Ccfdh5y*UFuEU(Uhoprxq(*SZ2Lu&owhru8#XA9FqMx4>eXP(yTcODuuAb!8?GXUK% zJ4ng^ghS4V41g5Z%F-Q>*p&D~hklUK%*<+%$s@`tGoa4w1Ii5O-)ysT4EVQeZ>tPg zOU=aQx6FWb`fq%4hBII)NfiFcQ4TChV*sQy!wQ+;M-JI~)*v?h*_m2>@{tkw+0(X1 zj&7JOBOymPc-A1F=^>@57)WuKD!Dx0jewVSmr*hvb!xwo@vjp%DH+#a*2{`nv>cgLyf~6{ z0dp>XZIuC=sF|8mf3nJe%@hXik0DpiAQu+WDNSv zR$6&@->m&U<>CD(hn4~6nY&!&wG2?q+%=?T=6L6G1}IMOnotp3e*Dv_t}_(zHSrT*)c$VZLqX@$HE zHB+jNCGt-x48A$_s=)L$Nun@vH%saD9*Bq@csSbpj&M1mA${939+S0)tq;#Dvo#gH_C6tUC=XjNjqnEE!GJd@MD=Wr-Q8P2X znQLil3IphaHq1DYBnmT*a$r%Lo#l5TLrRYz`J=0G#{}d~KXS<6N*x$^Qbn!4-p`0U zVyx|vqZ?+A2;_;}X=z}`+SwI5_%Z-ex-W|VFB}<-T!y!$eo){>z};%<3>eTL8I63xX{{bHz?cC!(`}yt=!V%rQU)L_4eXGar$q)pieZs?L@-X_PM@9G(PwL{EiPJlIVuh8)nBE<`+dcgP=Cw( zO9}PASxHJ;4^H~h3hLX`Okn5PR<^E5VGyi(?@jEy1F^RLS9DuD7PX{}!^`d=rKeRO z#Q~^?qm}LnTO*nlR)dj8==I)#M&$0*wnvU`m`x!eM|gHv4IgqyZ5*T*PkMQiNIqUj z(eF#Ckw2)VMqcy68YS|iN8PQEFQR6eC(N=!zL>&5{=YF5f!sq91%E}zu_%q?kQ!tD za1Epwr#!s!JU?0eCg@+sr?C|$nCsYV{&#u9ljHFNICOe^H&DGa_pyjBUwpU_W6(UD_OI(&l^ zhi@KUx#)diYeZ)^b~57-y?)>}GEV-}_KeXDvqvPx2uC({`WQosky1sF~)oW?0!eABDkpbYn(-g?=N7jvR~99W{`Wts$TJ8AHadugkU$((AW| z85xJ4vpr*U!|V~kIMIQybQ%U3vA(X)<&e@y4k;b4jiik|sasK{%U>CirgVAJx75gY zHMB(Tp=LVY{Lu>eXdSty10(NB5=BRjMakumV(0B~Kn{8!MsmoQ-t`!HpkDtu+=$$H z)Aq>G4YNli!tmvL_TovDy7Ts zOmSJc{5~}^@jXlA4=4=2W2f?Y*HMxvI&v&(M`ZjiRY+-I_e*~A6!NA&10dZM>T?D- z^t#6gV+MpgvV8`i8)nOh3`lVx9A2Tm4>_c`lIC=ED|92^`jf&+#$OjxGhVuTrIPXM zr@LA){*s#6I)1v9t$R=yKz~SJ#?48h=!~%_+1fAplNOND&Kt5@j&M2T>=T`|<2Aj` zJ<`ZH$ng=!ZG7Pb-7tGZFivzJEDh|CktaI&kV8t>%lDFe)=rIl__u#3ZJk_Njl526 zOXT~hnZ4(xSs_0_VelQZosn-QiJ~LNqS$$R9FTkcP$A={cV=k8dOd5D5o&T#+e1Y+ z%%+f_A}kHvkgn;SHK<Ek-nx>)(R2{p5~fhAOg zL2%*`hFXy%3PW`}u&6ne-j*88QnNLGr2^6S{}aZAjBVM483*Zg?a@ZY3FU3i7~L?t zKw^xrWL(IImR)?tg_MrSAf*>;ZYDXVfEs!3ifZHy4zExm-*%(374j5n=Cip|t$e(N z!r(jM1|y$G5`~dRIj|@V-H_7m8B!X$A=mjc05UaqSI&UedcA#&F#~d{***i%4YOsW z3_w_NIb>Y!uD%R_lupASCDT_fLjH0EvgytDH!gMWV$+-NZ#+{;%K-BouARfQ3{c$P zSe2T&pB2X$pt!@e8ij$o@!krUT`52kMb7{%O0z4FVxByjR~EPIdRV^kP>ccmZ?|e0 z5U$sq#~L#rv!3lU0NpS${&Bs{1(l4G_x`SAd?z}AU2bOF ze^w`Uxq@*bHIwf{OU5fH44{oJGvl!&QFO*woKJVI&~xFKCx_IAEuJ*>Oa3e{&nE{FCJ6dHxd1|Kdlqps&f1Sd>-S7!#zzZZ%^bEkFG|oe6XJx#nhZN@= z9tUL5BjIw$ek03q2ISJ~Ipd8Pkk-!j8Gvq>9VBG{!qPYo88)(1 z*=6?s&F3@D{(SbB@_nA!+1Yl{j67<+q(HWI@gU&|g3fsm#|P#etEL zCsAiVf4Q_4`LX--$RF6YQj2`S!9I4#M^P~?CeO5s^3ewJecKs%Pm)Lma%?J54yl}^ zLB4)n4&9LXD=#wgL?fSc*^E5mE5{>8GpsQpk!QPL&Rlsh$QV+dwd`W6bcg^;aTn)u zMEMcg`AAPa@_xf|v{634njU$D7+d7WsF<~XylaO%pUkNK4~H1}PLfCla%>8x<=6E= zDi^sSkA#pz9vX0okqz zmhWtVROV}t^1$Wiou9fPgC5qrikH~~yhgtDs@VgI4mjQe&>(dB7#|jV7 zJdMzSih2FSboKzv^C%t34BXF*zaJh@jU+aP88{QTR8ZptwL)}o1f zcnnA}@)9@A9uQUJcn?4`tP!Mm0L;PzcnpBdnYahthcN(B9w!4Vl`&uqSsQOCsr7)> zyT8_Yz+YpR^B7?DfEVWU;xRzu0qdxkYaMJoU_F^p-M`8_01rqdiNq~PW~oFuEUQ9{ zA*Y4sF=MxpueoJr?7iW5#%P8$Mij;{D^U)a5T1t)0%J&JoQG7Ryt=zEe8)X{#+{<{ zjK}R;re%EfpPqJ%qo|m<^WL$G@|t8ub;mDZ#wAE1aSM`M*i?@6kji%zAeAFMWR+Vo z$|2)t>}L3%{>$~V?X)}$g#J4f;_-dS#qCF z*8F}hZCDQ+`IR=TKdh}sUb&qu@|jdjX2CQ&<3sXr*KL4)AZLZ zkXzpv*1Ls3Zhd3eocyJX-1?HZh$}r9x#lHtJ}PGQ%BdXXnwP|lB{TTG`6naqO%lmK zj!oquBS?9q^1C442y6Yv&GO-4(X(Qs<-LH9HWkQATiy%!Z5M$& z{`U6*{!7ISIQKRqZ*lv30Sn2DI#!*>=WGFzNcdlL){aflAimiRQqI`@Z2c>Q9M{lHBG2GPD^qmr9X8}3`U@TaDJQrAmdf<4-vji{-%WQj z^0OA?E%s$I@&_%*Ur%1bQC`M^{M7tsIm(~89r*w%#@|^WZ+ScNfn-K?t9;7HJCa1= z79_c_sT|88g$M8lhar34A)_2JuIM@=&pRt}Z%H%qu;B5f8pb9d50eP z=KJ-?&*d)CB2PU2v>ozhR7}bD{B}{^oXn_WO25ijZo7{p68;xW->|6+>>#mj z$*_h@$rBzBVdRJIGkZWzvg17f&9KIZ;sG$rz|H0!iqDfC0IR$&%Hv&3GIrpd+OXa{ zdXqM+&(*bI+`*RdQYxn8=}C5s)5r{a$e z4o3c;<=}nf`;CnJAsg6ioTq($#c7Tg#S^VGV2UXWJNRf{`bMMVOXU7u=P?b_Xx1q8Zj0 zQJ})S;InP$AV3Xu2|b48@%pJdlfv~-|EsQt+T@21wNNuoJZT4Y3Ki3N?nI7b4b-;{ zsC}A80_v+IkqoHVR00=LS!{un1CyVBJ0Zjv*64EYFvFZkk=Gh$W*l+c?{vm!hBYW8 z;|y-Ja`499VddTt$OCLuzN}G9*74pjZ5&_oeW8uxm}U&PrWzedG8S(svn9A;E7 zCWnz9A&JDueJ*T@6*RtS6;e6Tg1iu74C(%GCNoT5Ao4Zi&5XT;j%SQ!SYt$C46|~0 zhAdbxGsqZH`E>l~>V@GeKD)L4<7&0y&RNFln!7(|#xa($y8qY(9M%z*vHG{!PjFa2 zcl%iVJ{6PHK`?&k_OW_CnNdOaGvyH014tq<<0O{Ki54s!9~!vjvC`jQtcDzQw;Zb> z8$``v##uE){`dqlqUrHYrtbW_q8@6CW*fAT`udUi zTBxTkK5hr~Z7RmUJlPKFR0C?I2@LfWl1K(rY|1qdzYB7F2r8sIb*>nGXNi39Bs0{w z@{Wg!W?0=`feN!S{6ZGYnu`v?tO`=hJJ%pmuafLO|IBobFS$%Rd2Rt2fdsvu>9=&B{jOCjWt5#8o7^0clZKj$|i zPp#p2}yb=beY#BS&)n zXO?}$9*~+Q@^Mql9+2PI@g9I?SR+XB0GO4ahs;a+2;Bz{fRr&3U@2E0Jl?;^npR49 zzc$?>^Y$s&2`VP>gK<0t#N0jw`-jY^Zp$q8 zfLxMD+yb8qo8k2{&F70P)eh4|N#R-cU`7|T1Gu4bdD%SDH(F|+INaWev=-hKCQax3GuW7cz&TN#h8r)PYjgDvB}RLsoNZ`m>KM`l#F z#Xe@-mLw9lz~{oIGO$A`r^}Gfx@1^G7DX&!#wkX=cbb{8_ff|)Ml-BIp)iIyCt?XY z2+P-y%DK~Cl0Cn;s)hRV-gR22Wyj6c2JXA_y4nTqJ}RbeCtIj_Waj#vV5pywMB@MD zb750Xvy)jW=f|+-hM+Lk;WUc&KQGH3}4{FlXf&P(9wbTJ(7S-Gbr; z%kX=pnxN>h48N@cbC_Z|%kaD5??;(puiJ;;hpCwEbKd08Y<>Ii+nLNj*8B!jtVgNhJm@`wBqDL^^Ldq@)uvEs| zugJQf&lL_$E7VFO)^ccCp*~Yn4|QLxE!3@4%-|Da?VxTWGpak|wfox8Wd97w*fqu4 z@nZA0YqaCVxun_J@gnivE_UO^IVz@Ptf-XcK!3rgRF4bmG1Xg05{bLj$5LFQh97hh|r znC=sOc9X2n$c*|vJJSW^Ge{yC$g!!MN~Q4S+^XC=9tkoHold(OGUk!hv)b4G@iV%fg4 zI5Mpi-yPAJBU3|h78O&shAqWZGNXbYu4jsGkVG;lVpF-y4=K;*{4U6;A*hhi6`o|M zIpsyZW3Cyhdx_(rq8V1Vmrygf(aNd@_71D?WRNkW9IOJov$CpjovfWNUeqGrUPh1n z`d9C1k-vH1VLRkEshIMUM%xAMEmWEQ7VKo?$4Md?$gwGJ=Sp^kB){7ZvN(hsvcX<~ zI%|)}JHKy1p5b`pXofXLB=T(TgW^4sv8hWu-q-5Vt;r_nrUq{(N9ZF^p{NM;fjVFm@K*gr=upFfHQojrG)zWfshK!p06vuIUVT}R>D$GUxr_e!|vO+3fV1`tVxWAD+vg(31aQo$?YZ=dfW2QE6D@^NT7r2M1 zn6<5J86P1ts=MR@Gu}!PiCf@vVN+R-gj7~FAb$xlhIF@kni;3J75R__X2uCS9M2fd zum*)>?D2N1N7zc(V5??>ZST8!Y=6huVe3xCterhlADY<=rl9T9z=Q=e)LA(jdV+oo z%ap74Vj9(gBogoJ6Oum<$!pB8CDhq*-i$YK#Jr$cV)Z7Xp?_I(SHLI56p`sa9w^yLT?5fxd9R#S5 z@|~{%mdeeO5e?{LgD?H3jnuSpE47jOdt*K0K9ATkE=R?jD;jRc7-m#A`vfySM^#4R z7WiD)R4xvMB;A|hXKTs(WZ=RY9T04D_KN)A-4@2p9M2fdum**~80N5mWNhk^0C$OU z@5UrB-d?0<{OiYh#?#)>#&Mrz?d{@tG8jK;%Xo^xIO_&8ew8GW!5Euj$&?>hflLlT zg={dTIR|dmWRVZK#|$;0t>dAh8P+IJpu$`{xjA|SfeR^57d+l8BzKe-6s?adbZR0f zS|3*!_xm)aXnkDa>iKp|QS-RMbt-0VS|UfP=FWDQQNPUEvSb|Sy!GD9uy>UgMVhSlvAs4y3`i$(_lDx^Hb(p^?0<(Y@a z`$ogU@L?~Wi(2=4;Vj35{X;j zW2v0f!lGRMfgBPcM`Ot1#qF5!G$Wr-%EGvZ;~AqF)}WA#Gq_8XOK;dacX2!P7tSsr zmCHYeNzVJ?jCM3G7g(+xjh`GhRXZB*nb+2CG(JwnywpiB)?6z1gUqPkkDHnCcO;Rx z%1JJ4Dp&jq@jNE7BtIC*>dxkn5IhtV&8HqfDdq}y=fW5QI zbU^nZ$|04J{2P*AzEG%*^4PbQX`_5(BR%qS58ERDmWr8icBmclU1Uc6_WjMsKP8F8 zRra~CDQ|;MW+|_5`dNMxVvL>hzY~lTjl9c!X2uQPbUb4;!x|%!aW*$P^E(6Tc9zP~ z8b2;|a7AMKQmb%ReAmW>;XShc)iVAuFHOt1bjlQMSWjONYZum!Q8Bf<*fM^c%mDhs zb!J?PBoZ@Da$!@vGI|a^p8+YpiL#Bq9#2wy^=AW4rC^OMC&L=@(D;rV)`N}w&j>Se z_f*FtM>DK3q9BJkeSAms7e;bO`DOr*H;3fSd-ROQMd=xD-Zxpx_@M%i9pi7Qm>=f7 zZWqVjks0;-^xU18k*y$!#8pmWsT{3g5o0yqtO2P^&>+7IF^0@(QkfaY8~K=WX2w}_ z9nToeu*QgFoWVV$Owh1*YLm+7J|KrwUibki$N2zTm8H$rP3Rku-A;4RTW^u>`TSB2 zdh0FHsS&~0&|DoG@6P!db!SPl!{ z_i=@9mV*=@4)_c~5BXqu8T61jSyhBX82P;w%np%|=6HudGpqrnI0Vd+aW?lsYE~6= z9~=T!IqdIZ$tG9>W~;}$fp(tp{wa0{>ph$$*DYa(u-?P@$N)c&5Y`)WzZunJ_+ zI0UR4LJk3$l~|P>qMMO_UD50i1#2De5NL)qprk`&bEBsvRz-io1F*L|3Itfz=4)7A z;K2VxQyK$)JE=w9^Za5h^3>&%w8+bT8Doe1X)0#btFQ4Gpg|r_W>mM~21eeBBoenE z$%Rd241i2~p!tzH;oE^6Qp{HANnAh6Co0G>0M^U~)fjo4k-t&djNJF7>TGG^mE|g9kv$@6iNU%0biPJx11*mkQVeE?Vx!uYI5JfLP1j_yf02WDh8B zxf}oRFAuQ?^uGOW{Nq&2DF6T113b6ijsFLkQQZc+*aLD%B5@0nT-a2C9x{m!bKk)O zAeEqpJQVT($n<>S0UjeSbHCXG2Io571JDd>1W6Cb=05P{OXS%55uOgyfib{Vv2Mdb zzpPndc+2{FpgISAw2^Ooz>GZofa8&)8P<@I z$TPUn%7GtyCoZUt?nBT+KFEL6Ljjg@9^mmdY)gf?=)v(d&|g4~y%olvlI-d^ z!Hh3k7=IVPkQukNFb)e7j4N6gC%YeH#(i#Qyq1co{M{?exXta1*O3|Zt6Ow4mZtYJ zNg{ETeJtm?OY|z+l&5d7?6}yV|EzELSPr=|1QjyXefd6oEHBE)uT?WcJ#^ObP|*x) zP)Mj5+$GAf9D94+m(gZ0hLo$90hV%{_jo%;6N_h1m1 z{81|AAD1oi$H|Q9?wWWD$ZL~C;ua*a6z$`0D#0SoNqJz06bk@6fro5US%x)a=E`gA z0dYn?tA^PFeAgZC0ceIbWE2m8SsBL# zvOBboCo`CQzn(py4@o5aFPhC^^Usxw=v&A<>_dvV9wUbw?v_ChnO5-zBaJrlOXJMQ zGymD)bmVA;HDo06Z0?f8iZ_CcvA4W18DOhe`=-@xk2kVqVfdJz{$R$|bGD18<}+jK z1U`D^482OT9GxDMfjz^AWSYt#%4)frEL=GuBjBW-Ca1WIe z=Qu#VkvhA}nd929-VrX4TW9PyH@>M2>v2CcvkU7iDyHIFFW7~3wt@V+BaD18NhC(@ zb750inSqo`O@6k15n>E$>Xe%twoyjjGR4d|^^R|y9@c1vHAWQ1Fng!m42CtNaC^Sj z81iGf26u2pCKz{lurPe!xqL0-!=>KW4&9ZvjMXxJ|EH#Qj31|BnoW4#j&XM~1L(IG zm~jJ=NJdy=Q#p7;7OmRZz4beM@P_>P$rmE%!W<6XkR2b8VGTL0{Vhi7HuAiQX5=Yl z9giH%u*Qf)p23Y)rf=9gq5Z9(2S6$VJEYi|J>XZ8uhh|dz+dg=X+5CEzdo%8EG}W| z0f(uWn9sa+9&n7z!2LkEYnZ@ilSE<<@Uct>@lH7y$zhQ`>}Q!5LJq5^!68PTTVLca z`OV0qsyH4wnqdtYi9DMd?P_o+$QXNzOVjHyl0(Y%SC6+}EBch!lgG3NZ`UhxwFmFc z6$NAK!FzktCUyt!0aQ%i-v-$oya$pQK>u99j60A-V#Y}>Y$^wD$jlK~aiweRezx|i zBEuTilud`3afFeVo?>R~ZQyvuXofW?6vi;eZ#o=g45`F1q`b=F@#d2pJ?*HL@rATG zTE@-e$7m;LYX>*BWBex-^Jqm|#($9+K>ygnjB`jL8H}+hP9)#M3M*v%%nydqoP!tD zNs5&jzMlftgCXRQzF|igxy#7Y-Zmo-d&u#~(F|*hD9B;%HtdK%POIo7H7W1qx%Bl{kh>o%DH-F{Hfw72qCHZgz`n zT^N4i@87h@U%L687WvY(Nm}I9cGkB;-kFNoG@_qf96v&4@O|#S%RpX-B$9y~o64Q) zkaDrW&pWrRF2fpDSGg=kz93TM@4aV6o;cF+$k7aIj7a3!+~`A*SwY6wTgGvKt>UKN zAj%SQ!Sc5`g40BwcuY-&s<*8JFyF{5+uOjRI z-wtURKYRXNE#sNXhie(%`(<4_#;d8Ak6-O$7snZ72GF>D%y<2h%w~g$gRw{I6~yl%{4PlTj+SkXofW?6vi-nBDV$^Ln?6$DIebVc%xzq z!|!USXFRc!p7B>jiCV^OO4>56MaBHQF~N>;Z88IB#}mxB1W6==F*cP)Odyq&PRJ@z zGL9j=y9C>!T#*;dGc%4`<#@*2NJ~&CjA4%6B^g7?6@-8bQdtFCNpkb3gB-`!JCGiF zZwAM)^$w)O_JXnXc9b(c>u?-v?m)_*Vy50H7;El8`jpH7`rZv@JQaHz|BLP?$ELE< z33=hhe&5M@d_4nFIeUg&5<(8Sz`u>dx`C08n{P&*|GDFlqZ!s1QINwt*uPDLb%d*F zo5JviYZ`99o%>JTi5Xz2oISUuofm%oi*_V;@13q4$$Px@hBnH7oLk#&ByU5-ycXBn zF3Q`I86L3jt#g=lS0ago|3w~vO=XP?Qn)lfVge~=ob*m$l1+oHpOpidKWZ*}K%$XH zEHHaON{-__0L`#Qkm3O_XO5a19M~b1%Nvl&D>^bresS!8Ht1UxzoQNMp{s^5a%<3^ z-d4*l=+{s&lV9(}$TdN~mdxOLxXgJVpF2*8K+0S{_IdK z@}@3ZL}Cx{xv(j&ck#d;lIt*Ihg=v!4teOQ z#f*Hgk-t!Q-gKW~#E_+Ickq3NXofXp6yz|cKeafB98%s|x{JF6eTP4~j18;u$atN0 z^vUXPe%2yS_ceuV)>eg{b;uCmXCO(n`9 z@PWIdPO13r$@d%&@ML$n?+prD4G2P~&zF3sy<=K(9o4BY?z#U3z` zB$D9)*i@EcAeGr1ltjWjxnl z{Nk)LU_6{8lEE08BCPq9dyvyYP$5&wjbx}1MqYg03^iw|_2WDqK( zjAM^CyaQcYI+3TP*!$LGEyX$O{->oF@qINriY2L-)k)9TMQSNB1KImE&w}DVR7WI( zA~uz~Qy`VoFvwdWsE`pK`xt843X#8i(G1nQ#_>?m46EBKP+`tr;S*2;++oTAcp`P@ zt=0l+vE>QB@$mv`JIfP(S+@o=)Jm2o{9@b!YTw(R@bgnK`@W55sBLe5!f&zxb)JWz zzCaSmfQn6JIR#QqF#Imav32F}3+d`VmZ2`_C-TylEl{%@4;9U@Mu7qq=0p9)1|yaG zfZw>r_x(dE>*Uu-el>9)2deVD(2m?wv2C)89?Vg z&5VzcL^2p-Qx3n$E=W1__*q^GG3MV@c#|2YmKXW_Vl(5+ZynDV&9DZAWSqf`R;Jn5 zJFonkLFABf5)$B@l||EG9qGI^_XjQVJC0A%B5#-asy3{*q*t*+9ur6J{Ob9%U08d_ z48C(-VdTB2Qb-1JY&PAn`0T2kKjZ8fa%epn$B@N)1lwsw-sq~Car}>tXN+c8gF;~p zvoeu}%-tgyLq5k3x#eMn~ri@lYpGNdw9uHUIJeB{G>wSjxCZ;Cc>o0fW6%lOk;_uDaUM8!O^?+H7`jmZq4 zxfM=<@x3IGm~j$IF;>(2lag7=2KiamZXg-scj@ipnX$*npS@vboO;UfjL{5hP$-OH z_O*`>GKQ3HAK)$#52t>DIR1#ND^mAp8P{ArLCd&*!b@7lza_fu7_XpWlB(G<{+P@F z`oJn?Jeeet!5Ev$S~sLJ1%s5Ue0~??q7ZUOPu_EkJa?bSPuw&kkG|}9&lG0 z-|f@vC@QA@Yu!1l+uc6Ru1RL_y?-kszk?(aBd3*4+EgCBgjAlxgLF5PVGS8QttT_i znJV(0g=bBR+v%@OV7p@%w>{pK)QswN^jtn_r{{9;^b1-pJxkbfNvC4YWInFva>k9$ zv_`7pX)uRP>lySkNcrr3tZOx_^yfZ6P-(rDq?}REdMimWg`k@Q>D?(LkqqS6RPIiJ z6u+gN{k-$XA>^<&i0j2jvpS0W{24Ry1!EkJ{EQpTu*Qhe*)SJ(>=o>6NIBB&;x0ko z;g8lbVU^c3J>I6B>5anA?b1eh!=dA~QT|d@y*K^Qs*+ulM^iCx9e+&kO|h;PWJdie z|I1MxNfL>x>~mog&(`LS=1W+R%E>fjgGMsSA)|@~>dea`pIu}|K5eq&k)s*b@Kcb( zTy$9?hm_}@0q!v6tEd~vT5fhOGrnpW$x~O4W5yjUBl(_$=Xu0%TSoH7hF4_9{cj)1 zH&ZcxR1=Kb-#(IOkr_b8-}5&nXtPKnG2t2wJ zWt2l^zS4w|#~JyK^Je7kC5}gqW>`Z;BG2GPE6XX^JLQ!oK@Wgbrf-nSSy?*CP8Ea) zSf_8>ng|cDPT#KnK1e%F@LecxH?V(7#Y8UaYB#X2Av19IZE_-(P9y4cp_d-LxKn$y zd2QUA+M~_N#`;Rte#Ev?^{AMyiXOGARDCj|Qhhp8r6OJLP#ux*zvzizY$_8BNEv5- zwk`|#A*`OO(d>u0S495&MYA8eK6Shwq8ZjWR{RiVIYGM|JS0Tx-vWBePL`FGe^oADPyE&hUyyRtb?{>>_eD9(e))me7}i zB7?ChLl2q|wxLCE=z)|k-`b_@9FJoWta7#==~_$@$#4j4D#JdcnCjtc9&%&I zAs`#P){-3}>wh9&Tx@oTf^Qw~5NL*Ve3A~4!5yZA8}=^#U&~R@;Ui3IBW=HQXJm6|> zONANr>ph&00#C=&wVr!KrK}ErsD`MN)#1zU>#ueA+5be?Iec#_rqR4dxKbL2?@MM> zs{Htycmsb;sv{Eq7aaw#DPA#IB90aeA;p6(B>gNsP31TRYgDZV*)20`iu~!TX1DbH z+|qMqZh4|4y_Ef5H8OcI)p_jo+n=Ys&wA;u7)iMxSw`8CKtwDCqSKWL8FJNY|A= zgJdAZOmIJjV@UB9J$_vDB9TeI@dXbF*DPm)^(y_3hlGxnv%%-Tdy=E?e#_b5u_JeI z^bNTEZ16G_#yqnER|QdVCMpl^bg3KnFZ`0@kTyj(M{90o{N9Kz;?&_M>aPyb!I`3I9erRBEVMV z{6G0wil@yRw8Ved_llNy$qC)H#HW66YfRg+wc|9zQ>d7zM;^2zK9S7e+5a;p?j?z2 zAjYP6)A?K=h7=CYvjRxvwbzhiVkJ|^ZnX-T*`b;uk6mnLntRgWOwYK{3~R(FF%Ppc zD}Z#@Dhzr6q+Ik1aQ`Vcs^8nAF#PQC&$J#e^y!1Ikb_+lIBY z^MJBs2JUm6`G{LURYo#A0GopGY`Z;K@PK|n9V(uGwfUtIjrJ^!t}PX09%z|zy5R7o!v9FLI2uI zFKL5*WqCdF+D&YcH>6^|Iuvb(yb+nfw`e#c4=0IaAjhT><&d&Leivl*wlc~g3+kO` zq&_2Ww%m+7G1BqK(F|*hNaWev=&X9@gN(7aT>1{MRnEFS-VCxXNnFp2txNk=-+7T4 zTbK5Gd%AI0TbK3^#9!yI)-3I>p<;&JXwHl^>%42p44`*^bqkZZStOB|F)i)WrtslZ z4D67~{jQL5>OxEVBv*xyL#B?o!N{YGeD4Y~a&L9VBS$l=F(Q#?C_Thar(kdI82N@| zNU>l-Z_nMuJELduM?nv(a@D?3Pg-nQxlZd4RkpsMb%S2Es(22j3JADJa7oIG+#YYM1iBE}To3h=t^>7!d;HSFTBw8WvxOQ%#T0+p$PQ|2GJ|0J zHimjXNhF4v$k7aI$VlWF+-T85e5#GTGaoxDj@G*rE1h=*SSl~mt<{Ha1=^Ud^?==h z{#p;XdweGjdaDQc-@j<*0d=XEst?j70xU$FClG%Dtc4;t8w0n5mY`Zc`!66R~kB$2qvK9(ZN z`Bl5HDDySQ`5_O0%*UTkw>m-97GQIZ~jND`7iA84QDSpQzM>DK3B9UivqkX-< z2r|ar%Ap-n3G4T$cLy!`M9cWdroLLn?pHc$!+L)5dAqPqrDB>lwq-oqU|iVfGQ#=| zl1K()Y$~T=kiw;Tl@xMnh%sc|nJi}PHS)6O%#0IL9nToeum**~80NGy@-69*${HD@ zvMgG$A9dw_E19wNN=b4_!Pt7GBs;5vcE;ZN$8*eBbETv*6_Yo-@~1!64(!WbP0$YPhbsx>)){-> z=Kt9Z?Cq(T^S{@zJ9u{>Gx(l*gONW#63IZ0P30L@NZBC23$jIL8Rd{!mA+);-HiO` zB{TA(O^!#7W>{lHK@PJ(&NFt%X_dYVB8QYK7Xj`e`NDONcRyLX`c`Pi`R`JDYok0Y zuAMf@lM{;U#`#~Vn96qxK8PL=Vv^R?wDW-VWJdiSTg)CXjU*CRImv}h#2(k{{iATuY5w8)?P#G^(2)7F3OkjGLnLxx1zA#X!w@O?J=Jc7P5NhAX~Hib*` zY(HqB=L-<@kjgF3kj);I$RUgG|B#VSGxCu)%*fMDJ03ZjVGS7tIn25De;7m#DVOR3 z+(Yu5-s9a&){UhEa_jp1gS7>6>-zk#pIS3=>s;^OQ>PiZW_>=Jikb334ZFGC7BYkH zGhG?^M0^@Sm#NA@50M z@QokH$m^3tV&py-HYf0UBF*NKS&Ee>W(;e`t}?743*K4CVeK>WlSSuE%dy?2E@iue zmt)ZkYm7+78QcfTM@J8$m^#*qecEg#~5vt z=l4Ek7v=v_F=I>EA}=H}`2KU{UkvPfNFp)vB$mp+4ok1Hcx~YK@Bm09$|3&@c>rX7 zr$tOS(a5KsGkbt%p5r|L&9H`y^nh&cgUn8gg2=JA{1QoktxA-C{(NEhCzC(YBCoSJ zUWZ`D6yrhEZq0xFty>gE2P6%FIt-3@KaSXZhG; zk}<5A3lf=eoRROiXlCqQ=Xl0whBYW8;|y-Ja#n`DQx+r!kwcE}_|U*DkL|@s4yoL! zp8O)+w3@h(ky{t!o4)fDBeyQc4)#3A$gPhqoQVI2k!u#@Cs8pIZal!qH48O0a-0X-utrI1G2U_-UHAK zYse@b0JCx|hb(R}D(C?rD;>N8N_VcrvAoPnh2iggxj^dyrT0If^?$#a z?2u2VV%`|zwnIL{KtAv|BY%w~k`eUSRHko`;;fVIr|`QVCv}%m4w>S^B z3^UH}Bl5P_&5REncRXV>!x|I{W0<4*jtMe`lsAzCxJ#6mNW4Y8+i}Ev?R@R)>5pp} z7su)ukAC(~yZPF9D(1dhmFyTN8;pMlI|;@ENg^4Hv8h~TfmCjifmCjWgdF{Z3~R{D zgA*8eoRROlVMgvd<9Os~hBZbMGrrS@?tWBZ{$2izMmwLfgGF4`WmG2N9FH8$u!f98p5cO7nXf_Sw0M*kGg9+2~+$iKOA%C!0x@k4L6J9zaC&9Fw0 z;sG!#(>KVlpN!YQ2e>1Xl^j73=*U=*{(cTt$5f!ueWCc6q z|Dlfbw`vO`-%ApSk^5ZO6i~O}yc|+aK>aNL3^9f^?e(6_FxtppyJlt_|GVQEqZ!s1 zk&Lss(TT6i*KcEQF)Y$YKLc!49&8x;YGHV-rE|56(>8b2GXDLQCfcy>Ga=tLtf`oD zjcpkxkr_Zg`H>kvNfOCmj7{OReC7?QTpWXZ`6(I4kPGVcV#W=O+;zjuIIh6)jL{5h zP$-OH9$d$G1$4j#say>^NAlXSISloNWvm`s{3t{1WErc!Sk;)JRT|otiDKQ5L{WnP!EtqGN58p`9cGvGB`v28-fa%dRRb>GV+gZnxW=j za6D8r!x{w&RG7Vo<$Jv$l`Ec*%HTYFaAEkUN_xiUo9P)hJK9Lgc+I7wc8rs#m@X^I z*)bkTW&nM0{%IVKdyqt8#z`#YiI$J$kF|JKiLn|x%7Mwxa>&y%j$xfPPat(0dA+dH zrsHw+9SKf99-|r77?H>`xY5dt40|Wc>m8htK`L`{NaZEZ1thoko2`xVjw8Ehqx{X< zdJiaWYwH20sF>LWk#-(%n#{oc!dmu#T_lkV55T4}Cui&EtxF$h&X1=+${DBM1(_f6 z07&1R1DLSO$hX{K_JF)Hj`sjG!x}+~2f(b%$RNAjIUwi(kn*;6k9WZT=Qd8gY4_7}+vzR!Ql$UBil zGLU0aG>GqPfmEJ6g_MJu-v!wxUIsm6;ue8C%*bE3%ZxmtisO-^8P<@I$g{c8aa$x~ z>@Cks18h~EJN%8Tm9EXwBA-`Yk9^-Z4YbIg{Qa;U^21cjiK!7BrjU6d#*l+Y4CJsb9xn2*yUmQl8aSRYnqiF*g)z*Y5d(v9 z3@MLw0T-k)lJ|U#hKR@XjCVZWSsT_jBlL{NHMC{in~JIU%YAl?6UYppgU&JIhe#qB zjIpVNHKek-0;!DTkWV}#!y3}tXb>YWYAEt0;b!DTtsIXW&9KIZf*j`PMuURLA!S&5 zyx)_YI{Q6s9N(Ssu$FOLpZeN3-a7nuyExuW#q_Rj%Xkl&0d)45e=uKLOA^Uoj7=qu zA;n5RKUoMV8|3HTej8#8Yf+E3%s9o!Te{4QQ#(1HF`8kG5rr|#IX&728AB=)G)QI9 z^x+|e;hT=l)FN+H+)0c4jaBuu$P2gqW{3O{D(3Ci%i4u?7cztIl6&)kygErF135Ou zNHh;mBS6YW#*J2LXYM!vJ88F}{lHVGOe;wM39Hq+Cu3 zaF-}6;dNdw48L>IyV|f$Ss14c>n|VEBaeOISG%yTN5%Y9))skvGK24`md6p+rAQ(% zav#g|o!#jZQM_aZi?~CLZmXo%Dw3?(L&h;=T9cB@INHdIOPd+zyy|$yXofXL6vi+o zHYq6>2e=R9(B|z3+TSE!4-C*U`pt?v_J#Q2SCb&%avQE{^+?83bGH zWT>fBWh9204VhpQmR~cr!AXnt`%bFQyj&wX@G{YJc zl5qw%T8wmFygCzmAIdEg3~NZfBds*u!xvzy@*aR{!zipP2oJC>nx-@n9$;NG{qpzP z>;cwA)7T3K*#k6-rq!vKpVIDS56~={)*v%*#~xu1xIhkpWOx8Jm2YK0p8M&^7a|hq z*|206q#U;VEX($kQ4VYL#Io!GIVmEKiZFXX*hGhWfX6$6Iw-lsI~=H1OxLTn=Rmb$ zYQ49n7SqPR4%lHDNyR)hyQCc^n8CzzfiRtMqi?NYt+*x3;=$y>a7)OriTo9ku;}e9 z<+~mOEXB?XaMRRoD(RoW)3ohq#NE>?d(oZXeP6iSDgGTM~2)IzikkEAG>9iN94JYX19!c z&*5%)#*JoJ!&>nGn8m;p4-bGW_V6cz-~o{G`LzH`aWcIa-@yHntVl*@V^iGOG6|gx zS({Hf=$R6ax8@sk-RQ_vt-DmY)K=>*y;eqP!(;!~`|ZM`HWf4UHCuP7LuOR>uhZl% z$y`Tq;97?12dey2$O9l#J5*;6h%)jfpZ;lD>G$@j#&!o^c}Fv>BZl;VY;Lr-L-pYF z1A8k`{yKG7vw?bSYews_{Zm(u?d1-(*xsOGZl1cwF3J-PY!${HL6k?5L}JIIFY(f* zyoo=VrFbkg4Nzfi&`Ta|Ag5gtP~Aqpe~lSx+AEHSie^}cMF};78;#zt_(yNNa{{`N7G3F~+@_R7G4Mn%k*=qx|BwvE z*pxFedes!kQPZYqNAmM&vDzqa7O!W#X0R>e)l^KEinff`81<{)of(JfNKfD;a|=Y3 z>E=#9%a=opv2(iT3N!Wu^UuwUb3SxDV>H7$v?+{X_Ia)Z8Haj^x+K6|B2K11MBwJr z&d=Vjhnm+y5B1*T)wF^8&XphS0{3q!rq(BS+Xe1vGQ;WiCG+=`J|u}`_#rmsSmSd+ zDu)3`@y-mMghOVAkVB>w3FOg6zV{0=a_=XOM~-G#2R;Qk%!x%3Ii$Q^6YHutTy$ll z7bs*RT_?zj#J%hB_8@EQs>#~0-n`AD4eN8m^d68n)y4zpnKLR;%pmCG+0XJu5L1l% zIjTg-R<{0;V6>pwC2GN}9Q<1g(ywwHH!$+oHkqNuf9`mwXofW?6sRx{PQMzAV@P?2 zNu;X_bqSIYBiK~N>W@f{d_WKNTuVLFrhin`hV`dc^X$TUF%|R3suFf#y~LA{GhFY}E;ZQTURbYZYI(0&;QoPrK5JO!+gH?d7 z;@yr5F|D3SJ0tOLJ>EZQ^V{`)j!f%aQ4i;~=E$_(6*Yd0fM~rd>e?&;@wU67d|ayX zVFXm*;~-~2#7|WoNa-)$KepqxX}#ja3mu$ zgL_O_^}^mM`}PDGL&|f{0PieUL?T_kkQK>b+++m4x}j%WslT4_GxzEl@2hRYIEhP@ zhfqJue}jx?<)A*EVR=j~cc{oCzcf>ucF5t>V%$xsF9+w{#iP+}u6o9eR$2!u1!@qA z5x9`9VR?d6tm{Ggw_(X#M}8jQ4paiS23e5|s6N_!{oo{R;GQ}gqYd1;ORMncYYp5L zoA>ePs|j3`C>O5$F36ZZay*4BD1CsT`iy+#S7xXU{&qOjGj24)I{rv%G48QsZugQ6 z^H|p;G6Tx`?+9BqcTra91A^0bmdYXriV|OzScK7d2uUOZ>Nm8x?-f1NCnxBkPHU!z z8s60wDoT_G$z-mC98CNyCxsYe=lpL4<3uBGzSYdw_n+e#qZ!t~RT%Fe^V0Ko>f<`r zwTH}LwC*r7#y^(%tz---&jumF@f6$Emm@Q3zxF(}-p^Iu8*&g-`Ovsucn}zD z2LSp0|Z-45)i8J&R zZ>@MpJ65;pp{JNN#D-!LmnsjyK9=&vl^FK`s>CyHTgERMjQ8E#kIPP|y>w|m%SwIa zxDRVytAmW(YvfOEHzOZhN?gHk@MR}7!y5Doa+uRv9SkCeRMsvbm67}@>OUj{`6skF zqLLnYQ8PXA#z*hh2JY%h0lUCmMa4Y4;tsoEE8VEjwmApd(6wgNPZ@ebQmku{Rk}2- zYmt08gdDQ?t7D9OnvtLW#*93nvg46+Gb|&WM4rKoR%YGUJNK(&K@WhGYaX=BMN*k{ ze@GI^@PKo)`Shw3?a&?A)=C@nt~c}^@b*+&54cFh)M#bv0hf#lZLIeT!W#8c7qUpM z4>5+-+jI>xE@~q3q^rM}t|l+|c{AG`9M))tb)-`m2N^M^Z0?firfY(XVU-79x_^MA?4y^jJqRMV$zN znNi)$E$jjKu@dEw*Fqiu84<{2!fAU&Ugf&k0}kao-UHAK>#!(2Ae;L$e{W_GIrf&< znj>8;sKby9##3pt;?4=$IG%g-L2VrWFjLR?iBI<0jpWm)n7^O3rTC6fq4hr!MIYBu zjO09Yqq@>*{cP>pPadsdEqHw+L-iT?`Wt4bzCy=CMKi1;odOl+tk*XNp+d@$F2G%) zOwisWE0V$ZC)zyON6+}x5qieUYw8(CwXtRVGZmA4;?|hPFV~8@ZSf%11v4tNu7D#I z^;4!`kh4QjA@l2OVyKBm-uadps{5+rp`sbq!AnBTaKWq`k0CSbYzi`llsy#Sos}8c zcVtB}7}p+E7{2pVvNnz%xl7M@!iLJ)vHHgDJ$7+ihl-g$#+GqiGNVG(KRAduM*ZYF zdy`qp35H+D5OVB%=&(RO*vJot9W))Dv*;@)xWT}|hi5dyI?^e~gUA?LHupjLVTl}8 zIno8#DsT7mc!yH&ZXTs){Lp(XwPST+dp+YbJ#85er(&kwY0G$|!MNHwVjStJKoW@? zl*CdzH8dIbAi^RV#3MPRJQn%c+PJ?Q$zjc#CxY5*dq6^Y$9n*pVI2n*4}e(- zddReSn}b0QsSNCp%E0a=iNu}l@qR^{58SPHhy~U34)OEeO4^`*=I`D5pigq4L{W)x zUwBPRwTX3F~UZQle*W>8kO$zOj(2^{F`j>q$V-+m zdqB4+$9n*pVI3u<2V`@jqg-DHk%#(|IxxUi@wCPgEVitte+$WoFKo)mvd3FuG~I%e zI$k^MzmwiVJ0yJDTkio6C)#*GjN3)U{9e@-D$J-~mBT#jqmIe~ETlY+`ME(mL&#z6 zmLpIf+9vYP?lvQz*3|LH(G2ULsUU~hog+WW~jb44u=}+>Sy@%1Lw)F&$!Vl>(C|{XK)t*8UE->3HFZgZ4E{_q>O?9Tjimh z?nR)IkodPA?=srl`Pn#aSU<8mS{v3A#_EyZn7zwxU`L6fPW-?Cq%yFFtaRH`jC(m* z=XbC{9_#vq%&7fS<9^1#jvx0A`pc{wNKf=Oc8J{OA}@5A9b#}-hdaa>H}{Zb9F!hF zw<=I8UD4Zu$RXvs9OzaBlF9^r9!Vqvc_D3XZl_27P)|Mb#1eYsXR6vD_qkA_Ku!}f zKg&;pm}1;#$U1e`b$wXJx{8eIJ~@{d&&t8Sb!hA&hC0~DXOuESO?b}nP|*zQSf)UQ zIeqM+Aki0wjVe@evm1}aSy_|9S*?KAH5wmh&&1>-yGxi#J!_sEP-JW+mV>H7$ zcuB??3O2s28+)g<_((tvuvNL@*@(Im$q3wuv^jjBp7Ghydd7|F=^3YYuwk6+LW#;l zHISVK%H#1Q$kW&C0{3k)qq;q|bKv5~xhDnG1S4Nv#sYPys&a%ZEit$F?^*%E-&zp{?hGtj?D@iSbyBZMiN3$sGow{tX;1c7`Be`(A zt)CwvGk*B&A@cL>3Prwg8~>Iv&E859iA(Z$EBokiNxz=rvPI3bWA)+3^%VQQXhSi^ z{Qwnn{yy6lz>Eq#bCz0=LDJwA#?jI5m2{tm&mgidKU)uE)pY8Vkx8C<9&@RZoK^fnKYayf(KhIN!wJOF0VLmc#wS-YeMK+0h; zz}=}#-&TLy|vCbJtjUBT_@Xy9|0*?=B1fi_{JY?ou}HLhEZ(%x9af z*bNCK$&Bju{*wH|&sE+ULXIjo*fNfhW@U@K>_{{6#5BhvM>DL$qJkV|^a1`T=pl=< z#|ett6^guu3ahfZa+xF&|JLJug1WQU=RWNiuzybz?HF+1TY9K7=YFRj=Y1}es4Rm* z$_ado`$?)qy*OLs&l<>k{lv)e|+si9DM- zuxR-BAY<$;kL3Zj%CPo$KcEh4)Kw2PeUKjNpJnw>pRaENHO9Swin;o8v0bFX3@__> zlCVX(;z%N~xU7{?RO{blaj5z*_HvPYj(Z=x|=NfC{xZSb{?cls6`&)e+$GHEdVtTw{ zi~NL9p_>DHqEil?$Mda&qG5otK4>!y562K%I76jBYJ zOq&ar?Sj4~nNgt^rtgLapnl5q4N{rDLCQ-%e%`q-g{7Ea)xU+|&G$GvIxfc&2w z?*V9rb(B;*0A_R;{^(c^dFaCl0_t{_$~X_J9OollwWza^__rSKSlaAbJX$*jd>5hj zfUunVv|~W>p&fQ(z*|&Ig*m-Pq5`Ka%<1QpN!M zTmFy-K<3O$U=N5l^1b8D9^gIWcn?4`tb?ZF0WhOW@JC|+Wa`X>pa($89tyBkS-Jay ztVsOZBo{W7aD!CN=pf|*#p8{5t1$d*4ZXVz_2}It{hzYh0i#}+jl0CSD^oGs)?BhX zWWbEtdv=pU__+mpLLPuBN4FTj9*`3)@{tqF9*}m;@g9I?SO-nT17KFh0LZWw1A-m^ zsXUJYsf+<7sQ-}I13X?YZN9X6l=dj_$M%NWF`(LTJ=8_-e4{@KB)L$c90QVB$^%u5 z`+2gqim^rhl2P5(#~C^Pttv0bVIQ)=Nr5`6K;%^?nvv(bMzTvdc-;ogu#STYa+rY( ze-!kP#RU>Mq?{ZF*s7ew_aG}0|JLJOLz_KY>5>2ZgdTa>>t(cY{B8vsjcGF+rv87?D(t^pJ8Cqwg4zd@Y0=GHTgCMw*!>@^2@Zkw;Z>JaRO{I?_qx z+1%)&w1EQKc9zOjIQ&={*q4$-G8kW?&8!_GwP77|xPdmThtJS6KD%POKCENhm#LU( z@wSYMjS8&{-wDR3pE93^lqV>Dwr&bBhSl9?5Hn6s5cvy}&5R>zJDxF`VIA5e;|y-J zGLmEOf`maqtDtYLcOyQ}GucZ;z_-j|9w{>KHo zu!b2GYPN`xqkhV3Ya!+L*8JRpuovY>4r}V(=8Qbb$S+MXBhPH^c;sk?b>Nf8v$@gU zz0HG+vA4LIo{oE1A?3gq>FP$^iDWQdLYq(QO45e)?&I~fVSV@P(%PZhzdFY*td~+T zReRYmPU1?5v3e5jYDWE()mlioTI*-)pdjN|R~lK-n6H|Dj~k(|^P$96jC`<>&zovS zp4QIs$k7bzIH(|pIX$se5ILlr{RFs&l=oZCCM%MGynr^N2I!G58Kp=5YaKoE-tBFX zpQK`nPM)_5>r+OBzI>FhCAm;PIi2&dlyC7#W+{Ex&oVve0kd-O+in$O8Tp|KB5&}H z8F}1ejz^AWSjRyHIn3^gu|edJ@>D9oU81ba{6b+2{|X#C?gyD^|G74z+QTZe!d)!j0H9Kz34{x8HBRgMb?wt0I+zH_>n zada=oGe$G4>hT^X zxwoX=As(-#cZexJmePjxU8lC%h4oP?=A-%N?8fL^^AUWA{_QqD*H zEN6y106RywZ_9*p+KIeEvDpLCavbjgXohv*lOB-GjSg$yHi#U1D`(!2@;$$iu014? z4CL4p-N}#mL1vD?2b=jj>yW}-*5K`^1CnWKG-J4SobUB26zxfEl%S*Zcb;EIXXIa9F(c0pI378gVI3tEQRUW%z+;yqc);|>4IYfOjqkiA+C5Q0wkHvhHKYE1Pi}k~` z@Bql|ArF8|?NX6FAj-&#ubVv}=O4#=0GeSP_!JL-89jtQI?_XW>DAyYx3jF${79Yf zi7PP%z$!mCra5TpGxuiy~$T0xcX*YxixQ#sRrr86+E;`-=&y+1oM8 zf>nOGi0*VDxh&ZC9&f`G;&ySE*0-*d(fd}bukX?N)`kOL>U}H5-I$8$KIyD}{Fs%4 zN~LV9#A85&k&hd@!!+B^-%~}{C$8Y{a(NHV+1+7GSlIq&PDOX5Jg6%y5;`pILO1+> zPsu9tuwPEmtwqT5j6CWW@%ykD!$w}2aQ{wpCjNr^2kqA1r5e9W8P}Bm{lq2W-;IuS zHKkVKpZMk~#l#smT4fzHr9)&hiTI6`1jX$v=`(S3jz^z(*u@h67XD~Rz`vy&6e>|k zNNn|Z7t*Gyo}S{{9cpPui0$-B(6(i3$64Rf+A-XQVv-9bDnSk@UgJ$45l?2TbkZ32 zBC;OZa7K?j*0q$(sD1wG9heE?-)i=%91lmtd z0LBFO?C+D zC-`276AoehQeu9>77lC8mlCg1F=Ou*j5S|Myk^wzSPn7vaUIKvS4F~KP?WXmx`%3 zzL3WNjeqnbGirbIAo<6v9JIi@q#7eHS}gM9WHa)j^NvT3W>^P4i9CZzpwalFnIQI# zUQ$g^46u}o-I1d8|Fs+Ev&oFwA34M0JnGnQupH+h6M9u=$vVSxe4SYil_o+}i z3y(nK$I4^vM25H}U&&=GtGv4{{`(yTbE_YteZ0F_lfGZ+t;(cdHov?w z>F>%hh3gd=Zf7VC@k0#7{YpN6OpxxbZ>MI_lcZ+x#X4#h4?O6| z;_Wodo5z215-rSd_lHOF@z~TS6agAXkit+p{(~h2*Be^WwkVaYV)rA+aA#NnSlKgw zCo3R(p5D(JYgIsL6W1#MVc3&iQUJ_S#Q-dxx6@Prpg7_Q@eD~@fr>QuXgt|Ie=03D z3B93A>ovdJqDAkFgqE>qUbh=dmaZk8j0SLoh2PFl-j0wYsY5-u&(|b(? z0E*HbVyif-)gg_%IiO?ru>yl<&=~kj&`K{7!5OE>#t5V0A_f<=M>j~fdtVw zpcD;@(jf?-Uex%97`05~SB0KnXm5Gx?T=+BO~Dj>O?>lJ`7>@`$U0L)Si08A?h znF;`uZqN&_%zOJ^lNHUFY%J=3iq7f;G{8lz)?c`KI1iU}TaKn1v6m$&E5w1V4U`q4 z>Oi$zCX8L@R3Q>*n1&BK%H?q~!`8&-hN=x0o{Dj>J3 z>lJ`7>_t;3AfM+Tu=E>~a;*L9-Ho-C4RUaG2T)4-X*7R#-K=JD@x5vmPaKUmqqqR6PqZz`(qLk%;VoM*d%`jG+J#iB#hgIy@1R1vOC(1so3%c!N z%Hxdwu@9`2m%ib8$`OXWXiAjBoZM}nNjadnxhcd`BJR11*2a+)&6sQ~iY)i}&l7y~ z!@kP2&i}Z+GOhngR10G8AV)!5pkZ#j)j<&P+Fyo$a~BcE0d`s6aM2-1km0;A$A}=| zuVc*d{tJ44e6p3}q9Ly57-85eo!~f!g9c^z(54-0NBwooq#RJ%xdRl(dp>`gF(r|` zs;Eglb%&bN1_!Udsk%Zl>$kN|S^f+S^YBM!)L9;{JxgYIKPR6^jn;l7AJI6V0Ss}) zjA4MGIMtNOP~Y`i1_j`Im%<7F^sPM33ef*TM8vR6T><8mva&u2U*QVef^YRJZ$(C* zYW#nDErIP(hK|JxP3vmS(Duac4iV3s!RfNw2bf`eL|p9hrA z-9Ac_jmFji8Wwp?tQ=t2kV^!e)$#e~lXcYCKFXwzm|sts^pC!v)<=FHM|~`$VLH}u z&_^mer61re0mpE;V}GNP$7_oTBAD6xNj(__u(s*_15;kuOYc2XtVv&x>H4Hc81_0S zQ4TYL#)py~(9`<|J?TRXr9-$(vZC?IDH;~VR@CSJm*8Yg&2iP+)f~6pe@$5fb``Ht z*MIF`P;A2E7stxkHcX9EqBH~JT+Jcb$m`S09-y*c1B$8{ zVyoDJkJdDrPBi|m&;J%J_C3~1nbyBtsH5aKX7LqeTF={*>y*}mX_%%-jvT`bhtl?Q zTEjnSj~!6D^AGU0f#SFvFuB(jraZ#v-z{&Yd{2GXQ;sm~g-@a!W~s0PCiL23QVuA# z3yAwRt4n6x?TYY!(Io40`hqdeD$}Qlw)ma zTMj6$!qJat6GUUm=|{9_QEbcUN3;p*`ry|F0*bRb^n29=zYfnXp#P9QtEC6^eqE$> zcC#OG{p=zPdj%4+OE2qAr}tqVdresfCtawmtb@B3T~^k?R+~O`s)KcDm=k>+lcFA( zL0RfGN{Sq20uUdn^9UjCkWc`i*p}08Y7>+mtSnD|3XQ)T(6Fdi2zu+Y&)<{au)gYW z%SNcfefU9jxT{+`gqtdj$}g9O6ZPH_JMg^-KKs{?P8FgLnc@A|>T7VAjxQ%p+{Rg6 zJVEbY)T}z3`Go6rh%oGBQRpy-XH2T|SUYy&HZ$n~r8*BNy~F55f@n;+&%cTm&z1I6 zN_s$LHOJX`|0*SY_kmSvNvCKSQL5a4;*IiN&!+^p4R_>t4VmHY_Qk|;D*r9165(&X zY3e1T0C47wnXG_VqrY6)s(`|Fu2%rUu-5>g0D8X-nUikJ)F}@!l%9!SNLDoFIG|xs zFYH{&0mX*j=Px7JWw=@aN2k|P7PXqK)C!o=%|QWl?uCZAuZknbSI7)^%f+w79X0TA zLzq;+9Y9^xsH^7wbMqA|xlf2;BI za=M$;EIt&gW^urgOUgX{{oE(&JWkaxqBu?nGAx%YYW36P#OOJv)U`UJ0AEh-k)^X} z^!Hb@vY7OS>sdq?_G%?q%;7l!DfrN1GHq#2c)2|ZJD;ryJ+e%WE%O}!XBJalR$K44SGQ8G4RJl?2*X~yB+6lyw#R_JIa>p6{v|WK|KJKM06wk?D*({HPiMaL8@+EEWmQ1pDAy|hVc1KXP(VJ@7Pn7Oj=N#zal?f%0Pt5J1%<_VDHI!L?xwo3*cZWN2{4x!5^SzE7 z!wh%#O#TGBVDM2o*#dYaOgUiUxY?Za#bfpU*Jvx{Z8BU>Il{0PK8bReW5>-lvm8)d zF%IzziH&!(_9V?88dL7`FQLV%r?p2ez`shE(#C`D36;6q}l!n4LM*sfRRhG+NMZXW#?QVTG{j3LJ z*bAS;G0g3Iy<>6=s2@GkOIt!bCHihQzk2E!nlLnjV=PMN$UY{x^@DE8v~IpETA9{E zUsjWPaeyPKIW)}VdXA*7F#H>ThDn8w{xGS4f%-$3G|lLvu3Je>D|0=m2*X~jBvN5+ zQ-6p_DxgTdkOn9nJ!cU_Gm3MyNpz1y9W{%qA5^pW$BB!|)O_=wkJYJ}qG3d7PYMDn2G_nCoaOU7caqa z4$lcF!-o#0v3A-aK{=qfH8)~gP)OhU;BZ5~~Q3R>%qqGYK?{7{Kr5iAN zqMpS*qkrHAs{)dvU9SLyVXt(O0$`R7wE+VYhnh(bC~d6)rApq3rW1`R_xTHGG5cy4 zCC7KyR&(5Q*I&w{KlwwpI_bTh&uN&zgyZVOjn`m?Ly5bH!z#l~$^oT&R{*6t{|P}f{w_V! zM~k{3CgB2C-4E!vJXNiL4Kr?1X8E73)Cx%M?x=wJG)(0i9TfmG{Ofd_6#ySaC87rn z35w%NdeD&Ij<5m%V?WoK&)cr|Z&$P`V8MN^R{+AW*Fm9xd=9#7yPzCvi#ktF77~<> zyDDS0jVUFLlWFnv#m>qs?_FKZ@%$|plv#eucgvl!d=L$@e$+9iEQc8!zjA>%PSN0> zv?BnhKS;*UmI6vi4;b^dsPhbmrE=2ezN_~)SF%!`>2p2h2*X|$CCXtgeK*z2azJs? zG{o~KWqD7sqG5)K@}0DpmZGNo+QjP0w2psNP5Fiw9Vn-}QD_+HdwKp<&7aJr9jw%Cj5meXeGuJgt@MDMuLgIw(;Nb8+Jl zCgp(Q=}Nj;g&-PpOgF30qLe{^B7=PX`jhGYwSQh!CjHo()C$+}UDd`)~ zFonVIos#|*GQ-`dxy&(qlqxykS7D9;OLuo+j?;|(g(_B#lRLVeV}xO^gMwqaS%u8f z?i*mi?k*GQ-`QK4S&IN9hO;@Q!yxVFxT8(UlbtF!~>Fv??H~hwBx9Fzkg- zC?H>hId4Q)lX5_DR2E{ZfYDkKS<#sC07Fq?eg3b=@?}XPXZiJ}-7oJfsFd(q#lQZY zx2jh{n@FAGCpXk;-nwD6geM=pZPff#y$XWs&U2RE^2^Uhu>RhDBc2^{-d|Aeo28uP zJ$ujbVEwneFYS2eygz{|`PVeetYJqv%b&RAf#}G=RT5r${msqSNAyXc3%oGHzv^Ex z$8cBLcms|Ia|~G2v>S7rZ1fYVSvhXs-}M|L413{|IEFd5X*ZK&KnIIZ- z?DIFwppznl)THhoUzHQrPU?;EYEs8{a3u9k8s?5`g-)d2MP@iu?MEUtpus=!NN_4c zu>%@pcreT{RxUiJbDU)Ku{T*cPI%Y#93u>SX%ighaL||`eCVhQYiFMmlmm(^2(eYV z8dig57mdFg(6Fc{J>Pct4#A|-PRg`Ct*I4odtRwBt>^DwqE72n9#z`qf)n=+F^aL* zGlZaTxT8LXks01sy+r!RD8QHZFYnH2?Kk?(QC7-}#<-qxgki6A66G*U8*jh`%e$Ld z4k%?gpme3=b%JP2d5VTbvHOsvZG==!V&vt_Srg2a5D+nGIjn5>0~pod_+o}={T_2nI9 ze}c?l@HK5YPO0L{QYGI>5Y6Bii(&`O=f5kH-je;>E6TKlH1q|G9R+-j+ z>|5lN)<r0szGxE&cK}L0vBVqNcqB(fGSQ{{tV=p>|(2 z!PuR(N@Zn?sPrn2*X|nCCXt2W%y8GXPDH|q#RJnazN=pp&bO#_`5#;BU9)c z^j|M3vwUDRHRT^~{zIAN_k6oRo#iPSM$~u6X5dACfZ~M$sSI^h(hKB*48J!y^?JPI zV!=p9xjaf{1aouq#W*gUcO$g|-hRSS0T@y2LwY^q306CI$f*WQ zH2nMJ0FfHd!e8dH4=9~G0BruQDEokAL+i2v(v5!aII9BMJmz`@APjqz6bi`aDcLi$ zu1$mSE`1q|IZn~ADE5?m{$m6a&U92J{nqP|O3E*-`dyjyLwCq$iz_F5*93bX(2Tg^NM z6uYn?o)YQarmxA0X5{fBQ|Wnw{%TUUk5-d<mEO@xBTDb!02D73p;}E& z)VOreDXrtl40nINItOymp`ic{+9LFZQo@0bzFKrUXFejc690Q77 zSbBM?45PKXXu{A8j>ppCYsDRuiCYw*=D2?DZ_32Y+A~j`xB(tjq+%*V;iA_wj+}Vt z9Y>BQ81C+#Iu{(n`{u($aRyAAaU17xl+kBRvU0qqx9d4Z81~X8aSU_&8Mm2v3@B}n z0i{|!lpvbH@prUXG*HcP_i+`K#W~BX=D1Ef2adg-LK-Ib@&Ttzg&7Wg+Grj&!0=Bx zX$q)sPZnW^4RCUpW55NE{81BcgN!r!`zKpDP8#HTjuD2vmPs7Loczci6_~c|JO@&( zhE+Py+D#CRR}N@c)aQ>L&kr&@Va^|251m#L`Epr%WtJa`QY)Z(!LQ0JpHw(ko#hz? zaH8nvQl=@{=(lHBY0^?%PZPqhmm`TLm~($FHE9aZJSo@fxs#^)t}%{T@INwxvbozR z3!=4}1knr@v8eBc@yq**qrfLlbms8nCar75t zc<*~g`Hk1!F}$Di9R-w8fC$=8yT}qKnyU9Ne`u9J_5{~U0Abi`nIr+2W2RlyB@p5% zk!~LCMOHK>)#u+%i}y#XSzOUb&Eo08VrBC6K0imDe5o2n6x-Aw!*@-Z=mv7KUY)z& zsW^XOxI4RqS;XIJ^W5LeVqsgo|8|Ov#Tl+=5np~62ryZg)QeUE9@*)3b-^4azIYfPu# zR+!aJxlxH(TV7e6y1b^=_0eGty7qc%(J+JWaa3+?GJ}L$N6o}!qT3G&Ky-Z!eG&;J@(tKXxZ zt4S@@bG7^I8D$MBziq>lKI5i zeNMG3narTwmV!T~Z5EURioL36?InU}2FF+wr!@j>l`aCqDz=0^|3-q*D_>A1 zK*r7+lnL-(WyIv6p!(If0BJw%tgv32&T4QbLaUMWv^Spu}8dDz7uqf{OPGu;*OGR!*N#s5E zsX1Qyq?+TRKTj(YxBHEb9M_^@{@L)2lcZ~t8SZ+Yngx#G^5(=aq@ua(g*t z;toqzlUkNO%PDaO&@dl9;z%mYaOjaPL~4o#|HSERdW|AM>8u!_h%d<2dc(yz5Li9= z2Ur2wd3t|W+APc62eIW2v)#paA0P~Sr4tIs=b(%84w#f zQ51Hc|8s&xcd8Z8y@gr4Idv-!alkxu?48DMuLg!Y3%t;h@1FKC~^z+C|9+O$7joeXbB& zrKDd&Ry6*u&)?vqlE^_zpHn9Nxh)aOq`!B7n)2*1Sx!lR3k~!5LynZg%+X}eM$*GS zDd_>FTaEywqzBv^Rsf*Z=nyMlW~|=#3|bYS)pxxD5Qe=0r07{Sa z0ZKKXDor*TDCW#!jSC1EL< z;qLXVq>muG+%Q$tdAOW(cHx;gaMQbQ4VhUfBVwRObQT3sVm0&-j5UFP*IStH)X?Pk+Sq zlp_p#S(GS;S;}(2xQri6$^k`L4Dp1CIv=k!HYWS(x0EvU^D?wD8dKr(4Lk!M*S z*KE&s%{zCE_3?!5`L3h$e&V!lV0*r+(}s^&AO8P7-}N31Q`+k*PV2}2`+V2?hL2bN z;Ia?@q_PjF-!``mf&dhoHTp3cg5^et8o(>JKEZ-0ep>HarCS9N`-JNSfiUa|B?OVr zLC3Z}VJZM?i@o6xTcr~BFq+ZWS8nxB3 zFP(DYCo+Sv>S;5Ox0?x~F^MS*^)35HxW5aQQ^RVmYJG}-HyQ9LK6AGk@8Ebet0eNm z{AZL&J}B?1GRar=RmXR4nnQeEPfHqR$NwAyN+2`5Z&mvvY`fv(p|H>Z6E>XWyxqTE z?Q3N5j#%Y}B= z9~yr*g`rd=VTsbKB#I=j+%@C#i?J(l!4ohcO%zGM%xCg=vSWbTi4nsWnWTTE&JFnPASuR*@@}uw5DrEG)&8hd!6!l2bn?H$dx4f9A-k= zlp_THGkK;00Cj6F6aXmpeWJBx1knryU{SvnC>=EbQ2On3K=GcYAX~SD6##4U<;|>s z2&3OT*{Xn|cU-Ojdf;tVNu;-xn&Qv8T~SuHb5+$854g*L;nRc&a_e<6LdM{XFUkRo^FDRd=A>Tc8fWkSbM;k z%O9UV7-|`}m#rfELJaj?WjfUG`AcTgrRb%tl?7wPmdi>to$gqM zL_dWfHq4uJv023N+GX(*t??=&TGo2JL zfQA_|X{VC{29g;H_@UYql!RvqqT#dN8?N9)qcuFtG@U_uG0kF1@ z%wz==Rn+^g)2#|9%5l8{5QaU2gaYz8=$Ob%lX9$`#6@5gC%hZE)1$P9j)EMdxv$VW7$JfLCmp2phB2Ay|; zV?c2RD9G@iFvqZJ`O}!=nR$9&;Ug=@F?p`%7-86RMB*6c!n|oF$AEfL&>f#4o)Uda zPdnB=|8kn$U(2aE?psgI@uI!oD>;t&ak3M~AJZ`TlRtOj_)~-9%w|)O*69S%434p= z-(9hbD>=bG58~x_`CQ2f&L1Q47%La|%VLfLM!#sLmE)*guICtG*potVoWnCDcHgLy z)7p9cvP{YW|GJ9ZVLIzUm7JhB&*k&KGM}DO(jMouw!g`0$n6(7t?g&RSMNW{l-u8A z_291`Fy)FjS-ncb?3uouDObG7sxz6v??)Y&@}>mQ49c-Mf)DsOtpOLcT7Ti{Vfq>1 zpa$4(te_mQsNpQ8JlW{uM@+R`)!uVyHrri%RU2X0b3{;{&q3!loMm#1wMDJo%T^%> z`rRM0N;e4Kuz+5eR53wG`Q5kvrKG%Ps8C7y$zLWpQC^XT2}~()q8w)MJ0poHKTbZP zG36;57U%4Y$sL^ZAvWG&$Qy4!eOpeF4zl$^SOKtlj_V4@KBo6a(yR)|i=5+j1t1K2 z%18=;x%ik+0HCPkdwEJQmH1H7!%Bz4v}L3xTYdg1H2007TPnBZ%Nt!#Zp(ixJff`g z{__)^>il#X=F;44PIZ2Up@2%WSOEhGqOr>X4U01eV)Mkv%{f_haR@-IDH3<_qk6-)mWy)L{rfta<=J?6~ zUZz}4W^i0_4|6<`AR7LQIL4x`Qsx*?zl=?y4YGAnm}6KokLVo782#!oR*uu}cRj}l z!=4m^;~Z&9_{bY;`;Q390bkO8q89sWfZ}q8&+l7APryxSuB5!&ic%%z%{zaqq-qW)n9=`~Zl&DQ+Vzwp4110U%JX>++P9u>R&uN@vLM7(aY4i9Ph4CQIpI<> zCFR=9YRaG7en?6A_M_vRDDOeTbRN6OiE=-g!SC-?({beOC5UEFjz#?(;56)$o0f zpj6la#SJ??e-Xhi>*@-yABeYk=&W*oEqLl6E5N?LR_@=itN_LS+AlQBtYsUW_Sa66 z8FUX>%nH~<5Y12k7Nw&y!1f<}gq?IGJ)r)6mrt;12Rsy30H9~>Q>=jOHF{rbl2rlO ze%C7iVc0WBQUJ_Sod+yl^OUIoz^R@JuT;OE%A(Kz`Vx9`;!E+I^mfXd3@A}j{#FAu z!eOrG7-876KyaKR%@CJvtnF#=f=M}`bZG=ox|_J?Qo7f2UsI(5Mx6Ow zsep|$_A3?O`*gIE0(#Rh2fE}rQP)=!0=BUGhV?eR_3b9o>)ILGh9@W(x|8TdOW6yW{ zlpN1E8+79M6b>NAUYF$AG>` z?KrLXOw{|}6f4J`X|CrOVc3&GaGb+IOWR|ttxalYrZu3bMP1 zWmf!R) z6+r(7BCP?lTXbd0eMVnrnw9dr1+J$YVc2s-qC7kYT*(0gExMYN1BzX+y*!;lA0dWP zVK1YV>woZwQUO^@e^n~r@Jrt)lfL7CQBFyJnTGkjuA>63kQsFEUcm}DLJ*A=kfLEx z+9wB;_Q?UoF-MSBJ{uMUtP3vcf`~Kvbeh`v$AH)zs%7v7FxQo8N>5VL#!z_CPTU!hXW_Y+8r~VL##8KWiilLUF=% zBn?yX>2+KZ6enEAkQx4c@i_~kJ3%ydIYq;w9xm_eg&}Vg0HqB-;E>6pLIBSEq?^7! zZ}i2?Az)hPXliCVkS)tPp_G^>RRIKcG@J{aDNShgkvTY^U6_ zE9(kqWjp2mQ{LCCfZJ@R+)lO` zv9`#95L?CFqdtE+&F+$W)EwWDaE7zo&T+SMUnx00R>_g$2{g>xpRIM`c%s4a&Qj*M zFF`beV{_3s`vxf0dB71FBCP?_Z|T7tdW^pN4OWgzZ+1P$2*aKfg5w+wW~t5tCf?G+ zq?{q&^GO#ML%gzdS*7a7C6U9E9^$mV!IsvS(@rzxPutSk8>dqqV@vDL+Kk||?)~4i zu1>=|e{l^{-s-<;eG{3%@8=7~VqfnMiU5r%Phlu+>0yyBkOS&hjrf#1V1-Pf0Kl|w zbp=Ej{h#Hn3dp?8^$I{3_LPwn0JBus0o#8o6aXl;^dX*3{T^|8q`>E2Ky&}b;>Jn^ zoZ0k?QUQ1L`;wF1u7Cx>R3`;2reWga92Ky{P{6pRUuqZCNq_S09QV24f z8KxX7FL*JYlRnPqGb>stPy3(iDMuLgl#wWhSxS1q{ZtJj@iSVw&jn~Fu%XF+NsXBAT#*w@C{R5lOP&X9?-BTU04H@ zZi4~*--ja00ZS`C#+0WSy|0p$@`8BRQ;sm~IU-RGvy|n41(hE&DF@W6B;6afm*-FD zgI>BwRw?QC5e)tDAS=MWKi{^Zt^oV~{MgU-umbG+^A$qxvjPH_W3_pL2t>frYpdH4QAq9KXDDP z-~al>;oYnN`(?MMO5S4yC@#BY(l9?{eaZ?@-2eI^nc-i%E3AMX1ku>#6b*}_><1X? zWuMRaz$(sK1=%`uiYN)N7QNe&OG2{Ir&h5lp!7x8D*$2GGe}YZ%(?HjG;08$zH_$$ zoA&A}Y3KNc2RO^^93QOrqmtulUw)zFc;b)4oH(vc!`zv%%8BDTWCo$0sUz_VhVW55 z_8zUBCy2(B)2kn8<*SYER~DxCo;bxW+Y8hB^ShLVsYw;x<^L3>6dqNtj(n~F4(Lxw z(Y&RyRU8(1J-x`M(E3lDs#sqmzJD5x!h`JiTiR5iL%`U$s;tAj2lf8$s#YDw^>n=s z5r#dFg${G1`D~A8s<3w1gH=sg0*bqELu?fOSlN~eA^^=V->C^t8wc1rk&iWtN}Nd1=R6*JyA5wiX|(Z(i&#C{QVJfIlw-O z=jKuwiu0pEhTFqBL_i7iYOxOY&(-_>H(7P)f6w(gL>TtMCv=$4K}XH2WeNmqi`0zP zt`S7T9MZPvHJZ*|v+q-i_SD*wO3^mxr6zUOdk&ET!h1!NS!d*3UynZ-RX>wT4ID~s*ZUC$!Iu&1WPBFx$=wM`ZQ#g(9Vt*?;0#Lo1b@F(P5B#5)s!zey+fJDcU&Lpl*f5A%%&A9obouI z%y2h(?EB4V+YTSawmr!34O0;r1+d0dufvoVRMY!;H(Mz$o#uMV5r)0ANtDAJQN4~y zIiR>9FT_)#pEjS@l4|u*vZ68NKL1UtN+QoLzE_#Y{WqUb=JE1=YEthS?LcY@k1Fj2 zzyYxr5M=9SlQpX3oVXsz#)Of8XO#(Q2 zCcsEz4zJ>r?h^HhIws8j#FAE8{sB>M&YKik0QPx!&=kDPB;R}9aUTdzlf7y^k3An zDj;r^>lJ`7?3GR^AfJOy8&zDMS=`Q0T)+!4)OWHLAgvQ={?H7{u_!7zJ@o!*N#yET zjg(pb;MyOQS^nm0YL1JCIdU9H!;HMgk>e_4hJXFrreYTiKI-QHci<=uQ0#968NL;! z9MnTSV_R=O%4s)PciAg!2{-(dp*hdGH4z({3L^CMIqLk%; zH}GbFkAcJ1B}n={L`C^^u}VRV3>{YrV)Ogkl}X=h`a9~R4{8{-$_$aWfP4Nt&m<-q zeVNBfV!>{glj!yIrO7+=_{UDAtiK`iey@?t&w3EFz3>Ujb9jotAU;&*vG&YA&zlMW z6z6$EY?Zdjkt+E}FTo2k>>m~gA}GlDlLgY==wBH*!g>+E$`!V|_#!^Su-8FBc|Hf7 zne(T~ahNumk`P*29naAt*98>1;`Jrl#-^zSjoyP$l zRk|n(e>R$|c|8%ibjZ=dK>-;BSUc~v3rt!YqrW!FN@{5x*OQ7c>{%~J&EY8$7ijVs zroVPU=a}A!Oj85~Z&)#+S=@GsMWQ@fE2Te;X5=vz#l zNl|C2*Rz0z>C(xOMVR4G#8F}~z&=X9LkV}KgK5B*!=wTxFTcup9AWf#kF}B-*Vy%> zA`E-Al1PO)Vfj^)R6wEg5Kox20iH}&G=t;wSbRy%acX}x$NBZu95-#^z;Qssh|;-B zK%u)JTbG!uc|8}%y1!_dI;}Gb@a3c)*O=6@?s}g)&Pr-p3)hp1Fzm%kkeb7D!m_7- z=neIM)7pU7&rufSv(?w*nn^kSmUN&6C>>k>NDvL*r*qv{)XRPv_N!a1raRP*+@;L& z$kLetriWAp5#=|p47eg4_B z7}Z71@#GXW$9wNkbKLq-M~>&vFhysUsuMR}n`=09Z60x)!ahnze{fgln14+NP)M2{ zY9{#nOtG~FOx&kaUHpyS|2V-)c~mFYQ;sm~l}@4@=Gc9LazK5;=zus{n?w-J;P_Ws zTzKqGWgg%5SD`YGJ1^d%%;UmMgVcGP!lR14`2a()iTLLm0L695crAgx z40o@5O_T?DLuHm%uB4{?sr8$cS^oJq$xd005vAG;C~C9U zGm~JK_Z$QfrDc&hC(EeS@!A}M@c!~oob>oxQqluHVXmA}0NCcbE`-8sdcP*aDu~SC zt``Ktu-8FJ5HMp(@S(jqK+km{2taXze2A@54G5AIjlY|sVNt5bfMQ46=l_-9!U1Zz z+&1=zdZX}&S}ujpJIIB~J`FSI-^J<*5wF1vcW=1N3V@ILZIvYWAV-iDRsgIC8%}UZ z*uP%y+ka?PK-vV?D*$2Gi>6ROJ_jAO;e=TOu(ot-3!r{u;Y@7l3kjkzjd8bh%+2mhps0k~%Fx#eH9 z<#YLf;x$V_Uin;@a#($Don*@Q4AlFwDOSo0K5{+f2*X|$1?4#$w6qn#+S*$uO$7jo z{oN3+EcOGUH6Kkj8Y>`$p?*w18FxLv(ox5_ECndGz&?L2!Tvqfa{2Au@02y*u10FP zEPmWkE^BC*=4Tf<)c}~`eZ&fqOOSnRKTGV-b8L^~u>vxi=>3doRt4lPalHZ%hP@67 z1>|$k`hB^>ncg4&$f|&%t*%!9!mt-Up@4j*EpGW1lX9#rc7H=`)i(;fxBmi77#dR^(6FfQ z2hjVr>FtCB-`f?VtO1vPIIOGzO+Lt1)_^rj2dHa6Dvv6*Jwb-O!>qxl#2#Cjwc_r2 zKRV0GTFlq3XANQ43!Pxi>-mDrZ96&&`v952(baP#?0lZ0*dAL=j`6pp_t}KuTb3Dmh@AeYzYAztQ_C<*l;JY~XrX zA`E-dOR|Jn+JOi3>=UvCly=|&#SvY!mP!zf6_CPEI$DB7{7zabTg6G$Aj9e5$;Qg< z-aL1og< zDO#_Lpx&i7og$b;!>nC8&nbfWhC>a0r3g~kM_tnV6dK&sACux=Z3Ps!as_$iCUZs7 z!af7;dL1GRdzF-Q2y^7_-NKW4KSZ<6Ztjz=pIwAuPbe|FK7Y)HlE_zv-NH#> zf2YskDF-+y?C*QI=?Oh4?Cfw6;gEZ_yi^)`|!w z(lANw=5ksqB7hkVC3*(n@;Uqyzq**pQ0$Ke8P=O8@)#>8%$(0k+y9Z?*Q{by+Jg43 zR~o{w7e1l191a>Ygb#6ywWDUvH`5wWdOj3T9G6FH?+`@e@A~|I(BjIvYRd0@NKN_c zr#@3s{?nx-C(27`nD>{>QBxjZr=*j9@J~b#Wa~te<9O|?;r;iYl0GsDuySnYB&Iy? zRlU!?(MowjH`h~+Fzjh9Q4X`TzXn+LYLZDgpm<&*#1kg&r=U~rWJP1j>FhQwN;}7Z z(upoW={*2|=ghg!C;;@;9>9~mr^Y{fFSrVQN7 zB-WQN*HzZgLp9VXQ+>x8WeuHltdCO-eU*l}D}9zz4TTx}ww>}8%6ab{@>vf1Q>~&DmA>f^tByKOf>5()R=SI$JSW(TpsAZevO0 zjDVWdnje0x%<^^#YEnaqj-)Na_n@hC^+R5UBwT{)w~>GQ1Wh71rFW;he__ zM(?R(CAA>W^`s&Ud*PEvg*h#2xS7X*;>u)*r$p?&QR$}nLo-NSLW_(3t)tA;m>OzQ zyL_Ij%+#ab_jbzE92#cuxS8rq4X{(PvT21h!h2dIFFuOx4 zbL=zv^&Tt7xw~A?F`}~9GKpiD107OLjse9fRjSnl^?fdW7sxb%Xv}enhDGTH6hP@( zYS_v*paABCXBTimMS_-s$&-1M8l*#+?+^*{|*680I{ifxb{+@;}u})olO&?*{>!8qKJ_nt&T~Lm-r6U7C zeV>b;F78CriN=)s{QGHfSE8EZCkK70)NpEyn&T@zM~)BBFw=jT;l%Ml!=cs(iQ^Ov z{^^x`H15F!e1c#7pO14dfYMGl;D9jYfZ2n(>4n|s>x{Kho)_nO$`OV==>_FEJO|Rb z7pxr^)XhwKKt}NrQ3;NkxsY*eixoyzy*!E>xJFu*NwBzZgvaT z&o08SmmFz!VaDv>Lv^sp=90(C0cuB3%{{-i7)MOHL}@=LV1er`>rhMTP4qtx(Qud6998Q#-L!~fDS zWAAmO{IcQD{Ca&rIsDV#T+f9)3_r%U9B^isa=^^29$b22jQ;WjE9HfqTu(W|uxGhM zIn1C8AKIG(^k?-jvm8*o>OaI*al{j?{Yq9e{;tp8dP_-U?TTv3r`@8aeBakAm0AA$ zFMc)U0UlM?9Y3Q82gJz%ucr+;ar(n)PBow{nc;5o8WKd1|5n5jk>&VX{{C@Hd1*hr z&zfYVd{1xJQ;sm~bx@)lW+}@7_9oaR)mH*(!i0_g@!{JPpc4Y7p5Gr z_})jD@_^AdoouB%Z;Go#e{sNG1dj}C<^lqF$bX%BTt@Ou8DVUp%fbxQh+ zWQO;xdXhfq6(t0hh7|xf^VfJ*K&;V!n_*QzcB<1!myV%p@1BTHvV-CUb}HsQxJgS^5I@y8S{q^J<9^CDD3fC!)^NP zCXBj<>^n_XG+sG{p|qukMY<6cP?Qt;JxqdE!&CqU&POp7n$bTw!%Br`jq9mE820KV zsG#4&By*edQRdtOir=^Q`QM`1J$|z~gF4@*&Ys<4A;n3eNCbgHl^ z2FDNWpbVlP=_DUT21RR~$ckoAjzw`I)aU<-V84D*${O%%aHp~c-1)FNf<|)5gZ6}3~OmpZRR-5=%;2`IiC5o>p4ak z_B@t2hPfcAw#hM|bj$`Qy(Tc4rW4KJcnB?i(@D+obIEFs$K9spxT4R2M+Lvqi;Oh%5nNp*K>?8?3GU9 z80Nf~Iwr?};tXqur&qewsSjDv4378H;`c|ZEAu$<&(D>4Jayr6WgbUw?4r)&6b&Ov zSLp$z`zFJXuhIh!H%at*4iL=gb*LpR*L36gd_-Z=Buopg|fP49MwSDh5!xXQnRAE*evwqG3_mMF$i& zDEa&Wf^+s)Q8n!$C#uDqknvi zl|=1c*OQ1a?6pgfn8QJf1Mhr>2{DhEoZ`!(kb6Dv671j2F@wgE8T`f+QwD|jZ%J?D zPa-QCE5PUfk`_PcqUQLuR@K2md z2r?WIRs=^-s4JrEh~A$ZYgI&<*Y%1(81_0S6p_zC`wE2wu(sG4iqfL!wfdz3Wu`upy;Pa0y9-`bXR6mzmxl2VaAdI_nc>i;xjn!l{1ZRBkjhY;ObRkQ z7$y}f`!ic|nwMti{kU{1slKONPb$K&r=}n^hl9op;X_+%tR0ux(oAzeQ3#{8$~2v5 zyt2=qM2lDYt2rJvM$PfMCTfl!e%^uO0FNrYR38qAt6yHv8w9_;G|4HC2N>>d{EQS3 z$D)+uZzYVmax;GTYX4}xuQb8NaeLQuj4{F})-=Wg+_IHU+X}y((c|7PyD$H;<|0^aH zE+>ac1@yJJ%B1dTuJ^MiT1hSJ>UvTUhP|{2QgfIXY5R<|wH8-(j<>T_oL>kr6lY1J zwUx9o8dL7`NADZ>C|M(i};xL1s9V_aoP8_@_re zhu%SUc}JLISmQ40+!p+$_ji3@?8?8QrPoXb(Ci}^CrC?G1WS|WwTvBy9mQxa-`XX zSxP9t{Wl%eXV>R{mDHJ*QCYbqytaIcvMk1TQs>Bqw;Xe%7Y)nK`waaA>s$G8g&9#{Vmh2IxNn1y$%tEy$%W;=JOQo zIq-v-)>vDlW{9oQ#(M!-(G1FO*hObZW@t*4R{wOfQl-yyS5v-why&$bPX!vr-_VgZ znBh?Si(JX!pB@3S9t)0hG?+0% z_)sMWEEs>nq#RJ%cmqnOHvc4u#@`KSSd=a&0t&eV*;;v}QOSM&SBRPFx2W|o=@GR) zcK^IUSrS@ZeMwysyq+#J%!!ZFozl9ip^qukUPfBO<>JRrGUWlIZ#UCQdEj%`Q;sm~ zwM?QMW@+;RnD_WelX5`m*cwpUc(vy802-RDSoE}7x|>Hoa~%JH|#9$l$da-%QFvQnP3 z&-Iie40|1vD2EwA<3m{vxaZN8Cgp%4Q$uXk?-a|zBLvgQipJmd`LELA*!$F!S9nTI zdCLp)m5ICMMhD8hp6fKsD|zFb5*KDT)N&WG7+@czO+DO|3OnFRQy>`yfHSYPNl+&X>G>mk~3Q!zc zdp*+#e)Gjxry7t&X1Lqx0&|Qnw+nL&nE38`=CC-R_uh(Dj&mEio@0bzuY(fDFvq^T z-sBii6h8V{8-mitdkjG|gX2@Q_{;8!%CzoPl&?(dc^UJRmApZAM|E0zJwMSf>t1qX z5oS14V_7Fua`-20>H$U82iZC&%rUI(8*gBai{kYDaHN&v1zy*4j4bes+-6#+m|1cJQsZ(+(|P5)J=+GF%dnw9c|CtXiD!myV%L3s`bjS0ht_Sdj> z;;%vhfKrwNN?Cq8xG*N1D)|Un+)`9QndOgO%2Q_fknFk2EdQ&ZgF4GoG>oYGGzt%= z07^&NVYs+uoYymwtRD<;l*?!`Bl76OB$punt){EQ#v6aDY{V8$`gEheQrW72qIRxV z0K%}BMWKLv4tmdsEoRbNCNRWS>2%v5`der$7oYzSEk5+7n)2LHYRZ3atfu^pXB{XH zXc$pC-Uk$U>-Bs~@P>azJC%e&GQ-`d-%yF90FS*gmaZESYbBr+T zWl?aP!xJd&qGRoXrdv(Q0mb>s5U(s{`7W}e8I<3#hc2F$lvifCFH%i;%DOqqEI%J= zug-F>=S~`C!Z1ft?!pc7b)BcD0?0gb?Hm?ftkI`NS%p^`bh+@( zdJu-a@JSrQtmh*CY8qhD+BrJM@!B^8!QhyUq?heHfnq}$VkkW(vWZqkGbnGcmtKWG zQcd~Vto2I8pKYV2ynjze$}yr;OaR3(2HiVK@L-toTgj)2)g39v+L`_4GUYKw-{58| z+crxn`CFN+;C;rKi8D(|6Gf%9Ci( z7pbOv{jF-s&xd9yv;3{oFQ~JeZY`x@w5g-ii5suIX*d)t=50Cro9e0XO7;8s6g;4` zEeE_SS8Qzn(;LoX1$c~pV-2eU_Rn>_0uYA1v>%U|lIru^VLj+AetVfx+SNckqizfsqT@>I!3 zI%o?rOb&C52-1$}97h>_Vl6Aj1v#$g7-86JnZz;7?T-nL0mV*Mh^It44Eva@Xht4K zepwPZDMn3dm3TF&t%|dhdAuXSfz%WYBkHA_Uxo=N?R1ABz1=g&D;Jm~dOelM#jc-> zbgBV2k{Q8#GVcXkE5qLkOr6hZtr`6vwXKxORdTG|X6k%1 z%PsR6Vym>jRz@qM@pn@+EJ`Ou0HuvApx7w*{9S0Whp&iG)_}`9K2z2JZ;DzjpG|z; zsqFWpVV?InQVuh`Z{M^X&b`3Ln^ud$4!D2P+pGY;(WiN=3W(V0dIca1dmR)C$mgIJ zOnTd-9BYf6A-dIxpuXX!hdO=!bu?k)?^n}S>1j1>Ph6a-%<_V2jNm~U#=~vSL#da*nD{l@{4r^?kRHi(y zw%&hH-%5Gh3D;AOFzl61P@cmd|@M3Lsj-))O&XH9oK2lc6|NYa}DMv=oFuN9yaH^7NhEq3Oqa2|p#|XCHCnyJ$ zk{(b>`d$RljDWtT#jFpnDU-fV&KhOXcYIYH(EdS=0ewTmym6~zK>G}b($_tM6Rz-2 ze}sl!!I#QVoIwsUd^fB^tQ;6Of_0`D{U0}2b?C3-dL1GRds!4Z%;%unj2oe+b%>#K zvSkZ>8OfeWEC{_CQAJ3{)nxbJuX}1tidWr~8uiW&G1+OQD ze5#g}>Llqq$qesXz3?pd*YM@TVU7W_pM0J<_8I+z3RaHW-|2de5r#dj1;;rYv{cEl zcHqh9%}Nd^c5gzwvh;jt6wM!+p@2cOnDF6MWm<3jc(pREFD0rKFm#ZE0snZj#BjIL8KxXxzGto2yZ~la?#PtK7=6u1E9DE~Tu(W|uopf-c|K2| zzj8-2t+BRrApRObG=tP#w79j7n$+fTYEp-uoUTmki~l^MPHV4cHw`m+$#ADkg&7V- zUL)E98vK(UBm)#Dg@bH;H%uz53--Ojq{bQj=1Nvli(0szRD@x#WfG|{C+~a3Ok6Vj zuOc)2yRlYVP>wHaD;v;#muIkf4#Q7zY6kF|Fy(+V$8}=LV~zgl%2vwbo^?It2*X~> zB+6k<8rR9B9I(x)VKrB^{snv8fZ|tlqqV6tooGxsy$_WZ#jg?3`%npfSn__$N4jss z>;g)^4*{67UQ|iIf|iLqyX}qs`zqGi-T#W~XBT1EOO7{TM0&&lWSPb+`8 z^&fV*g3aZdj;vsp+t^%wc5EiQe22~DJ@cMom;3zJad`f>vf1Q>~&D+Fo%N%gZR*K7uGI} zk2PfpC>?48O55_TG`nd0U7vpoEw+AGP5G|2YRV%nXDBI8t>H-dRvM;G!BAGIf^wMQ zP^G7z2IcTi+MNTGj{gBu!juCRMBJ~J9;2^a-AZ|Gvg;{F81_6Cl;`u5WJcU?a*Vab z?oEiT(oXm)vZ5IrS3N+x`}uz>)B4GSIm)z79jWH{O4gI=v<_$(QF^W$P&y|DxXWbC z>#0sYO@G=!5E%tnd%^C;Olq9bZ@tM%YUyy-lZr6xl}?bF!!srwXkqQ--HmmQIl=X_ zi!kg(Ma-_x-BFqU7^6RZvsH(2AGuzK z2*X~>gbwpLXn)g(P0F#hIE%PfB9&feA7UtF`9fM5%}@Xq#r|4A1JrMkSdCqDKyflI z$S}{GY@ff3tZO@{<P2~J6Wfrfc-qN4&}hP!S4 zBn1T7`0mYT4 zkUm2@V{!*4Ekq?hNmexeZh)bM%9OSEeji7WSr3s5xHO*@5F!9#xzx z2r~TJB+=`6o}750lA{7TkQv^u^*)K)*$_;2qn1p$&*&qxCw{~#=7so(gebPV_(D9w zuopf-c|K23pixVcW2`NuHK3^E(OPqwAv8<@UA3Q2i=USM$%$Lhc7E;t$~vjf*v_vd z2cc6xtHPTao#J-@bqh8ZzDg-dsv|DIo4XgIWOAJLY=K1z4Cz+LG&3SiFp zgY>&t{Cn?!FK!eYZ;tKxx=d;2b9z6ovX%1E=Uh)Y!mw95L3s|(khJl}+WViYYbpRx zZ0kb2ve?^+);=UFnxTL{X>rqFwF2TNF5|SeE8y*BY6bk+(NO^xXqbuD2RkVMW;nF< zG%Eo9iQ~!uyDVKlhgIyJ2HBb&RsgL2TDP(SN^9!e|5-3Wne@p=A9G523{!cmBjt~i z8I*6iN|Z-yKT!l|_%EsfSd@+{0i`o}fTG3)dF6k@3V<~+q%&XqwcdYU)vAE~eO#{q zgkdk5k^*3k4G9GRit}rGc}g&q_|WV&rpZQQn8Hxxm(TwpS(c7b3!>q?rOF!6{du(@ zj=%0Gh$%G8J2yKD0%rKvc6JM#w}HEQmh&AHfVv>~Hg~`_n?%_MY(M5UPWqzJdOxbV zmGY>!T~9f}uvbZma+qVr+-4>{pxCsBc*3MR7)Oy6&7d5MQbGYr8&yD|9-sebg7d4X z1#!#WYC$A^J6>5KzAI_rR3VCKn73vPa@r{TN@jT9zsY0RpNEfGVafpu2K^C@ci*=+ z`j{vyHd)d5 zyD1tLr8*C|<6>;rjL+#w5TE}?g4*(P$}AtdZLu=Tw+~bcqUAUTL8P)1()DpTG126d z-WNr%@L@-}oFOxU$-GQ*$tb{=OE>8XNHh8hwX6z=$#%U05Qe?*2?gZyj1_DWlw)mC z*h6g9O9KDQ+&5%JGbqQRUIQlJ%{+kmeNp+i1_RiL_`evt5;vg%{$g^GQ2iky#DJrWm){GoI@6P zJ&82T`>Wn^DvPg@84T916_1w&z(*;|0YwT$Ymd;%Xa?n2ln1E%iRZW7T2A=dRZw!myV%p~D;wTH3T@?Wlx3W}OGr?;fSwMMJ!@5Ja?= zOI9>P0a%nyk^wGiwf@4@!+A)0Kyh!R&)@h+N#x#xB}zfG{(YfR5Tj;|RSG_0Z8Il9 zG^Js(dJJ?DypPQAp03Mde;z)55mo@8r%H$wkX>2tPt>(4p!6HpD*$2GlU^twpMx&0 z95N}#+Ik+-$;=R2#d(crt@i&hci!PqRNWs(gfR335SAVh1(gz7*oZ=`grWo#2z|vC z3mA;bzA7QGDu@U{kSY*FB?gedYe|q2coh`8E5kxV21Fa zy*aF1^3#qGa!9fJ_6d+fDo5>8NTTp}Qw=Q2DEImOTr!i8999?dqC#fqHfvL>H*Ow zUGD)HhCS0M9sskF=OGWjy))zikn*PYAkUxj7~*lVqOb?}4J^tFue9q@d@5pW6}<=i z*<9}dt$uu6>j58~@H%-we`==toadZ!z$0Wv|BQJ(uxUph<-SUQ<>fGPSdIIBV&wDh z74_C;R^*WvT#p>Xu%|@@In0<6d?@H4i|_p@gd9?C%Y$rH?vCw2(}}|0_4=}C@twdQ z+97BO)CcuQWSU>-$jxguKccLyr#aM@$cURv~iq#u&YxXU!i8Md;3|ZIKFE3FX9_!j6N!7W+0X8 zY>+u&#*mp+E;Hj8vtBv5^HGd9ba6fDh7Z~9;*0AThCS0s#@UQb$>dl&rOM?{SVPMF zwIHvoWb)t1iozb?H?XLjis`?HX7^3K2Yj+*i8jiAeNgWKqn~v2fQPA>f9g1T0L

7cD z8$ix%zpymzEkw(BUyw`xx#F?_{ui&>*#f%d*L|CJw%JQY7(dVrj%u%*4*!i;?Q93# zziacQw|eiD!-%t|VHSs9>_3b+_>$Pyxv(2EqU&glsX!%EetJ~mnUS%G8##Mo9%ofVOCH4f% zFR*)B>;UUK{~6Wm*}yesweEk*a|Fvz%RS(R<*>~=52~qI%kbG+xTY`h>c=fO#E7Pr z@@^2uJ`9Q`L(B@0)N#~^)MM0o)Kt`L)I`)=uvxOQB4z_`tbp14s1^14hkd#{#$Z+b zaf7WR>a~8P+rEtKV{Bl;3sm82MyfEpyk?xxwH7gCh-oz`i;H{S`Q~%TYxCX>&-8+P zPi>!=m<)OS8vgZTODO;IsQ1Jq9Ac)AIs+#FEEO&r^-CbHzkuLmh=7rZa>w-^mBb5Mu&TjLP|LtW@x3 ztW@%zAjiA9x;7O?2QQG1I-K}k{lX0#9lSwGn#B3u7e)skkYB?JGHcw0Xc@l-WJvQ> zX^mB*!&=ZuyUn{dEZj{-hYg?|qf+>Ls?lL1=- zlVwB-k1c$OM;|aMKDA*jkx4dEdh`LK_=vqa$&L1*LEgHE)djr&4fgZhF1#MR4W%jMN@J{~WGn{H5rrTo!T zLf0NXCnH1Vr7Z4EY5j4JA+P)15AZO9d_Swd(*|A_W_iP|L2Cmj&pUM8CK>WAoo;V~ z&)DDpy;)=)_s?#vJa$1|z4|uaG6KqVAG%c=1^K?Xu!eG{kZ&baqnYox z(93-W2qQxogfZV2wRLdggA0b?ibmypbyg~P9aa`wj0O3h8z29E{qO(W_?Qec8QrjD zow{T4aN}bd$fB5)F&TZX;P5gNWL@7Sf1lbyw3MF>GPTZmqkb}omhp2z=5OrOs}B4x zZhXuK%}+Z}>u=z$2)rV2A?UY@EZgFLtHrG6}3wL*xL*Ma>{fFTNe~J%3 zTt=jD=#FfBU{tuE2<~WFOQHe0#o+~``>zve8Zku%@*Vhe398@ z2T{kV{#w2j-qcrR%Y64D?`Ds%8~CBq)41mUT~_@ceUsn9Bf@;UWlFFcnr2Dv?f&(b zu?kTeF zgqHVsd;RHd7-A-LjUFzC^4yE2hG_Y$7e5TJT>j+ck4A8t-iIOKN73>pboR^Bz`KUc zUR|FHx9K%~my=`jhG0|E_oc5fG z#QmFeCcNQ?5Ux^P6_)a6a)qufctwU7ufJKGyZyG`A0e;nw(S4i5Ayx##qag-Yz<2; zU;o1ZDDSCkAIF&yl;64hnSxr&m@I-{qlflDW3r{_s-Z= zfrB7g#%F;Hl^OcHh5yANCL44WS%;EI-iOH$lLOlDN9PL}@ZUJZ51 z`L#hNUC`r$4h=bl<>2wFP)*B_XErn8;SL6ujU+gxh%T1$HzAD89{7fgDGxzXi&5uM zQ&F!`7g2Xn*HAaXnDVG1X5%P{gW24Ax$JG4XQ}*4qXV3Lm{Y{buyKY<7Q%B^og^=r z@QH>(I5tWZmhum*gswGvN5+)x!?L+9&%Ql91$hnMGBm*g@?E3TuiEg)D9e)%Qts{0bU;xb@?AT*lxkiU1d<7n*T;R1o9p9 z{$71N_5%4n0M%&b`>8VH+d^SX34}1_`$-ZRQ%->tqwpvxR>IW{tSq*uHaz>kjw$S& z*8g)%sRuK;X1mq()o8NWQXi!D{zay_l3*NDnt;5xSl_?89ocNr1^M$w^;d5UAzH>a z2N~+^ap@)eFODfKKsW1?-pkt0pNuK3KtFi$E}4V>#xcbJ^t1lY9Lje1dYB? zsI4%jU>K7nZnoSbdB9hQcbEXLMUEy?*l!|xM)(ipCCTn5aEOVWnawr6>!3J)2cA}U z?$i#neBHyTn+}7uw}gxw))>kIW+aYB%g29ySbPY|b#>ZCyg#I8`64~PHd_AY@us8j zt)Sa#=-sq}^3rwHnxf^qJpJZ@)sD?Xf5jS^e3ro4&J`Ydjh^ChE$q>d~WWFau zOa@5mIBG=dF={<(Drz=rB5E!eVt!S`Y#b$dFq^Bxcbeg5%j~@ith!m*N3>POdCW}; z#~~)43D4gnghNYIVJZJ}yU?|$1Tw^&+n>$7)_=X_H01S1^RlZ}kZ;3`feU;gulKUM zG?YO3(%ptXKSI7UdUXD{3CbV-y<7Mi^4hBAvOpg49j~}DrzQ*~*IqRBwuW;5Iw_N^ zA>R_OH9N2z@_hrU(aiUa3mdDh7lxQn2xGnzbIA}B0aA?0`AAkO_-CvvwrF(VzYQ_} zzP0*)4lxEWlWgsq%a@EJhh>dGrmuKD+`rmY9AesmoNF;Ga`JF;ShhV#3-@n}rqqFG z8Q%${e_Zfdclci%V!D8??^*Dtr`|Sl;H4|*wJ*b>C&7Q?5Yr9x8snzffnDGlqy~H^ z=nj6d|1iYhPw~w$%ZL=-yz>q>TQDlDkjZ5qC~bViAqHi6hnOcVyeoT%!ER`p#dY_5 zUzsq(U>K9d9G1l*VOwtn?iryZ?=mWSjt5^*3eO2Vjzf&{MmG1YqvYi&co=S;^Fx2M zyw~md7y5#=-zwe4=|Z{JO)e2FKjBZ!MN%kF;Hz1@-mYhfH)Ipb$KCX=1Kxd{==5M9 zl<)3(ZzNjYIYY}1%fa$BZf0|m;I&QW%34?soYdloV;}Y2Ev%{!Y;M&;LBf-VpPtTu~Na;`iF@sc{h;!(d{dn z3ZuhfkhKE#K4`1FjHAOckjE0e_uUgl2TzcNuMMr9YLVk6t3YPWy?U&PYIN`c?QeT` zuO!~bzqzh5``Sm3!JFQev|NYQ{9v1w2sOy(5F(zZsngL-W z9}R-?VciBTf3`-?vdvlN#%N6|rE!@tc+5iQ+Z<~s-<@f97_E8ccKj182WwhFHQ~V~ z+OyysXRYdeU*k|9nor8xKp2;A|5P#*j0H*UMO{Y?MSVscM4d$)L!AUe!MKW;4ZL&% zW^>|>UOOBLHb(vO@MXf{n*Yf6?dpevFf8TYK^XJB zZ!Z}N5TpgP9bKsBtw(-&zg>NGp*2 z+!k)L*0;v(2_ulF3;d*EieY4gXb1X+LHlk)6vJ?rWFa&Nzt{s95%8yQbJj^55m1Ia z!J~pNa6~{UTs0bkBLd1@dj04w3CePh2-4A&JtAN?G#B^U8Ov+W7Pc2KjLCvsk}%a_ z4lEM37q;T|0!r~MX7D@)kixkyIB#y|3eTnHu1n>_v`H<)ehp?!yY;Vxm^Q@QVapfB zwEFpNiD_?}Z`!M5Oq+kJtN=}Gq$5w$Fl|?;#=c55GDtL7Rk$6GdWg1^@;xDpy~y}P z1_>ERI!I6}(LsWGi4GFfOmvVC%{0o=q9SJFC>e;2^Lb#Kdfe4w`1Y~Wo-Ak`q4Uo) ztCr`k;~+5z!p5%qO@7)>wP@&59KXdaEG)RuuBpp^-^Q!U273x!yO&M|iJY~+xeI0Q zyX}L);C5cMpka`|CtLT4yyx_Qz=x36=D+ir z<-_!2!j`&?0^03%h7B4H<@%myj`xE>BGk*UAC|))Q3BOy=6g_DaE~xykSK#N=G(qn zZQNeaTKAh1qjH{OrGl@`%3_%%$p1W&`tLzPt^WH%bBDq_JU{EaXl*hO#|Q_t#4%z5 z$irhhT)f$GC>bMM)EdW#?a+AqVh3Q1z@N;?T$JKEaTSS*Z}?bCWbkZpjKGP@J4X0y zA6MC91a?DnX^&|nY3VJD5g5i~2_GN4xD1P!tIJUekG&=5ciDe{?Fy94`P~u6esg#F z-69rV@Fua*2*$$iXMB8z7LJ~C;OIBT!u^lC6AQ=1JzMjKv9R;=!^FZxvl@*v|F?z5 zLp84EpQ___MaI0T16^Ur5KSuOCqfuIwC5`sGG>9KLk4vg9Wqopf({wfTXe`!X}lnH zc16s_QLgZLVpPtLW~G96VWpCP2y)?0-6k#K3GPqT5^;YHvgXIQ z_ehQ+y#kyi)_D_`v2>M1J&a3^#p}LkJjse@nz2WqEO5 z_{FiZamQ|GE~!m!KKFJCI|&#TaD|<$dn6@8>tK$^P69@Sy()6NU~$%OZm#1bVy+I! zE3b@X%vGb|0b(w;FJi+p+!hqrBsu_45E(|KDtyL%P-^gTOrAAcyn)xJq{y zKpUT;dw&$K9+sJL%56E|YlY^%4cumWdTjp;DBH#i*QjW2J&$!Ad0`2XbzsjHmkf1908_MlBKMM37hij(%|Z)ey4oPE~7!`E9El z4!>AAz>GhIcV1k??R%8M%9Vt-tCP|u1o@YMZduH zND#&a`r{X&_aaD2FEt9KSEWUIsZ}VwDvk68SHx@_CAWmex$dv(EUQ<42j6P0VZ_C3 zX|p=Z$f`J0)pl$@{WSmbw~OvNvMPQwRp?qo7NPg_{2b1qPy9N6pwyu5`N3l$e|MW~ zIaCanRAu%zU)>JMhaB`Z&wzX{S*P5HZ_M((I{r@>fSW%!h}M&WmJ z6i|NUSUtHZ(EBLIxCWL3z1N`{&3um6Iu5hSk((bJU=Fr`-VKqEQN+Zl) zDq=Q{k{qFNu2)_-$qZZP?@VrM5RrA!b7NQ`oUC$^mhFwyyjI(7xxL3Ohjg@-YYh`2{d*Z7i9Y z0p%Odn|t2@XzMPwx%U;Of7N}>giS!@tX!AbW1;*|^*zgb0nB}}yR^e{fcZF7qnYoh z(RW(r3NW96Ft&AnI)V8DNHHqsFR@a=-)1E|_AD%i3s@NCrMKS-VQ!?B2(vCompeO) z3?2?5Ft=1|gjoXf!Y@`1Fyl|*bbm0eictzzDUww&N<;EoBy!g#%04GVm{FD&=J;dn zDjR0(hUSuTx^-9)DZq?j<{4)w#e**Am;Mx zer0_oW3IBmw!~b$yDwILW6bsO`(R?O%O8W9_WrlIzCtw#Tb2-*pSyj|MVLkVNcmq7 z#^t+%1IOE2mV%@(Q{PaSRa%6ZI)}on(g<@|Ma;%gQY(=(&c|bkqwMwMrFAdf){p3N z;>pPEc;?wjQb!15^Tp50UfrMSAA!woDPOf}F6r8IZ36RyTDhG5yWJ1B0JIr3jKd~C z{&Kd5P5cPZ=DPXHJ45+Aoo>srAm8UpjfbQ``Ga*jX14*_R-4OKe}?HhhmKqk095WX z(7HMv$~TPMpV$NP?Y~TEjpYFIbErl$-+IZuvN8eYmk`FrF0iYP+tqJDicvZLo|Otd zhm}g+tadIpJb!l3I4uIRxmqI3Rv>2^TIi0~5?~&v)(EpL%nQF*Inawg7n7@X-r}kl zrLYiTcj6ddFdTr*s-$d#cpUWnjrzFmCprwG0a^2hf=r_0dA*^B^hG&imP_W zqc9r0KKALqEps?p4M(^k2$weUI~ zxaS(e*w%regx(^MVpPr-vr@rVb6}!Mek91TW-p%Bw6eri@o2R~dL2N{i5aydtA;gM z6;D)aq}L5*jbE%BR>k;}xp@(#@DwfrGfLqZXOXy9jB=-3M)!(QmKWx3cE*(rGj>CB zNqtB-zTtxaGlrQ%TquR3esCpkEJ=xQ#OoZM;;OSWmn(8iAm)0$COFxZG1o5R>%?6C zCu{otX3X_!N*FQM@4hGeKQiW;Yr3D9>zL2lPa5XZg=!`~9Zq2W@^nedsQ|NRAGmG= z!nl0D)Fv=@07+q{zM(LyvNbi@wcm9L{ys} zGlGKPA`mA@4^`W-{q)nhUP6y01=kSfc87(oh1Ml7=bg^w^1X(7Zv<#FjqDFjhWx$E zu5$1`>8p=y{`{#rJv`@^v+>&AX;SN>J@PxMMd%MC3 zP_C`?dTjzQU(vl#m7M4{m6Sp?n)$X^(YFW=izCd{&IpZ~{ffY>4N{EC`5LT*`;l0w z`iLp7X*KQQAB3@f|+HrjfbN6B)bajs3J<79h^Pp020XdW@9$?)g7m*5(5CyA%3?bv?$3E8^W&8`Tx!lnF( zpF-EBHXv+g=EIh@3J?T_0C;kto|LjchNjh}k$we1yhDUg3o^jgz$91JpRBiEt2MIyw0|ClU#uM1 z#-G9ssN~cXO6JrQN@l%{@<&Gtx)F}DylkJ{X;RtiZS02TlG-$_&FiX$wl(CET+PFM_;3^*%{b=weI=~ zEC;qdpc>75JAWVGjxRHWMtMOP+Zu6=uIQkR%wxKY9z|GN+a7r6)_t}$#tP|2BoH> zWotL^lNT@7jcAwL+iOHX5VCzk)pl$@{aoHU=$`&M*d3Shr{4-)o2*CJo}3D7ulCaR z0fu+4kiMM@`Li0AkPff!v7C{0qQn%}+i}e{769AD4~N7ZgYuV4iaaj@!+`@%y?6!F zC*}0Ye+3Lb`)ueo70RQp*{$mY`L?=}8jj___B^OYGvBdI=HHMBY%hc`w)IO4VcQ*~ z7?tx&SgGJwvJ$Qj1G&}6%&Fx$DOqo;C0TESoHxR~PV#S zU_XA~;LkE5$?mp->~CX~S#P7%eWYd^WO>;(_)z(5LpL;+lvz*b0$ml`5N1wFV-Aks zUP>RbO^%XTZ=)1W>L0^nX=h9FIBk~&#A`M)EJEioUaK0rmw4@v^`RoxYjYI8h}TAS zJsKG8V1B~-I<#!k7RlxAk!RgHwK>p0{b!u_|82%i)=A;>v+wzak z6$0CNCI_qRhjJI=7O#VV;Uh8Q+~Z*SkDER}fTw{)+BC3eHXX`iqpOVT2y73s*|rVK zf$c+3jb^@I1?g>oTY_-CeGJ0b*4pWW?NcDdDBL8^N(CRxN+n+a(tDNDxhWgWkZq+} zBHN`Po41@ZVEY|8VOy)KsFCds5XLW74s7F3=Gsq`!b8Lf+bEf*hNB$PSWdUeQI?nO zk%uiRd%ca_&|FeS>!#SY7TCrxv))E290@0Eqr_C=2iDstnN!wjL-V<=aifXX)=Qo8 zS+6w>@gQD{^jV`@#CUCIqx!^a>+U|cd&zjsv!Dm@nq~jH4>Y`%1J!IzE8xieViTWK zodIl%Zj$nUAdKz%Xh_(uIxJsgo7#x7t(?~@h4 z@CffW)^3o$mq|ZP?*N7!vKsa63+2BZbRsd|zC)dM`a}7*Et_TMfnh#;anI*4{qXrl zJ=1~Vsy%81&wz55(!1k3c&r3cFY=4DnH1jRnF(J=ZVEYGzv9aAt2-}$;#V9;A zoRtc`h?Pp-enmc4J$d)_s40Dr?XhZ!Y)=5`=^1l({QwKXwyRnr+v8wf_{GYBZTu-b zgzpNjw^1^;hNEnCg1Y81Md@vn?`gFZ{^Oo z$!zgf;wG1IBaD@dn+&>CA#T#YSNe)|Q~2Yn#7#EGe{IlkQ#+_;#lCbxueRCWSfp3< zi`c9;C&q^8y1EC)&h%}&@a zfqX~aPs&^kly3I1?ka7{9ZM)yW~zp5qDn*p-n-&VK3?C(eD%~NZncbV=V4!>AA(2GBX%f+rE zy(qb{$S-*ZCQ9Lj?&QG>DEF6&^r9>;y_eTEt899)8=6b%*2qi#76QE(#_P6^S--;r zU?`cLWR&80Kr`2Vz5j5-UX{E?a}D}EzW!3iT!-{z#9Ws;CATeM%;mSqo|tQK+Vild zjJZ-??I7l|ZoO}XhPj4AHQRc9ATT>L9&bDoU>5BojnGJQr=;L(6x}R1ZJn{f4IA*?u(Z}zNgB=dU-(p8Z6p-&=a6F-*#b}1(fGx54(l= zj!vtwaXFN?m*@U-3ZQK@_FK&-Fnyi)r4~wn`Rty~+*~LhS(4VeEx_!y$B@TzSQYPw zYBclxw>Y?LngH`r2xD7+1QD3efE1(fo;+46_?xU$@?B^A;STg_zjwW3FNC?bS|ZHm zAWtt(Jd-%4FM)Z0S|iNorv2gYiXUL)52;nMx* z5_5ISeD{Mj*R+355_64zGQQDY##|%!|0L%6$yJSH&Gjt8E1%;f^r+}!qt zz#Q>&>L!F)v=3Zi0%2UfzTF7SULYyV)Hf7nl@?*9&Y>`?G{U^HB4*<#*(@~9r``cu z*@&KUhm#K)MCc#5pkF8LB*N^cYCE={egdke_B>MscABO9s`EnEoO=+Mr-uCD=CAA3 z+5@1CJ-E5ra)7gm?D77^0PV}-hpBQX-%vE`DCYZlP@naSpxm{4;@*=0ZSO}NJ3WHw zYt*%|tOis@otZOc9+Zb}llE)_FwcwmT@%Xz<|R;#X1$`rT4WVD6>X2y@7_KOBCs za)23siqE27MkHA=XOT5CMumghWV;&Wn*$=uD9a18|KXOE4KsE_b4f*If3md`V8$?W z78)h9qDG0S#1CwBqZAJynz=50`G;G#!kto|LjclK-h}poIDxq} zY&(Mt9enVJXIUS@_B6FdwqI5);P8u;1KaphaPAG<>P9K-Ag1Ap8fANO_wxf>QKQWM zM`RmidD)J1)~{@~u^XC8>d(Y|t;Y#$W0+Y{qZC)v(Ih3zMmR>rllo?^fvpNSCmk)~ zwbyfNx_U8Q(=B*RyteI{({t8q^^#+V*Q`5Msqv8UTFe7~;llu_1UxK7;QyWpXRa#`58i}&4(#ZCkikOX~)PC{PS{RYwH@0}Kf_a>-q`*GcDSYdjX^@!u1X2p=SCKAOZvHA zatDSJzA2nnK>lPe!?#TbhTZNDQ1pj#kC;m%%7E>BxrygADF0G>Vw>Z@@Z+cBFW!gg z)0Wu{(*a1+c6Nzg0OgtH-IufmwypaVH^y>c`!-agneUeeH`VbJ*p7fOw$&w%u>A<6 z7?tx+SgGLOu~NwowFk#EndY!5q&u>0ua?O6c#y$G@fipIF(qs}t2MG+VpqW77b^$0 z@uzS}1YsK`K9t0>F*zQF(j>VJyitX$w^8c#v7#H{D9g(>Z_ui;*~V^YE~)jQPxd$q zY-5;NZ=)1nk`YVtC!WPObDce}fZMugJ~5ZmuHX{ZT$_qy#9U^_J{)4rRnmVPG1ri# zA;Y2=a}`9lBjyTj=<-0rTq~iPU!L~}%qJ5KS0l`#eWd&b2;=hI*pI+`5F~|}`i8=+ z(jv^%ITU7*P7x2<%2RE$^rq}arKtgxd+p4-{CbG@5RV69+9~a%Jpu2KWPZl=h?OELhjKp zmAr#$H1q8f5@O^dz?=qQY-{R-zfw3n_8p`cmGeJX38$u52~RaWTEIQ;Grm*w=WYnI zhgu@cD?wWHb#Psq*qgw-Uab-4CNMAjV&$-A#-GBKjf7s5WAnvN$jJN@*9h3dmhw5Dgsy2@5qgs| z3b<##?z=4lO6@+KnePqxZv1-fSx2C>(UY+41ED#dh=s+-bF*o9VWq_+!n zAHP^Rtcvlcut!K%#VBpblMT{wGaIEhSyPkEY?Q-ai!h@sFU%dnepNQi*p2@n!}<5> zxdO}>7T#e1M-`$;N|^0xj56ERB{d7VuZH2oT+`;=FJ;YTTyl$;t5sD~{i=+)Hr-Dl z=5omTP%n}(*Na05#9Wg81KJ_XjJfL7D&!u_xk+H|QuB1<*#NU>A1U7i!nk~s`V*Kt zgQPH1-%yxUT7;Q8hr+DV2y@qpn2n>PpU}8SFZp2Ee7g-N=5?qO5%bP_#j?$T2(wJp zc5FZWWZRj4yYd1yyQO@+?n2it4wI{B2EZqCW*D9|350W^L07hw1%i72d&Hr%IY^s=pY@b#lWE5avJa zPpl`mRKa;>s75p2YqoY@xkZ4vBZRT7R=rAbRXiM|7?tz3tW@w5SgGV+f^6g$-0A7F zuDB|Gua*dN3dpt#wPX2TJqgU|YK<^E^eyD@ig^d+BQx!`R#$21NJHC*+(5wk@Q(XGZ zX{#AGX(bOOZn`w@^-I=GZF5EtH~kZD=f}Ef#r3tsO`$W6PSbExd#Gk$?Q4YI_bWFz zAibhrqYOt+S|x7u8bMb z>vOG$x_|ebkKc0?=^dwPJGP&GChE?3p85l}v*9tB-a^+L2NQbx_!e@Zle^Dc2$aTi zU8QRv->dw)ys`sI4Hp{j9|YwdZ7=n!1~i(M9SXCB@~xwNQVs*9PnC`K--YRq-u_qv zUMCQlJ87YgJCtV|9GlY$rstMzeF?7v-DG2=H%Bdz-a?Qw&-A>vv6?_{mCd3?de>}%aRR{y{|+;9T3 z^nD@MWBNPy1pw{YXG=D$h5Y5%T#XtE&?b4#+-d{m7N6#S!hD~<(K>htlzV$ge;xv8 z703RuxC7I7t~Q}*XP~mZe@wL{P#!S+Y`8v5?;ok1M(%(#l?;VyH1n<3cK7?;0?c+0 z#NA3(N_xwbR0b{B;Cvsxm|KS6%Fcx`8Kn;v9UoUPUf zv){Wy4!>AA>=olrVY`~_6{92cgV}J&S2Rf&<_I+R566 zT8z17C-o-gN@&yiE^Dra*^i02#?`a_t6{DsP)+IlAOdrE_}c`8S+ozFjD;|^FJT0M zc_&B;GxZIHS*1mosdFgIDvdDju87$N^S!Cy>e&MV%)t=Gwmy78V7>uTjLP|2tW@xiS*he_wJYKb<1>aXkLiRk zFH}o}*#qS7Sjmg)W4aTVSE@C_9N(sh!!K42Yi9g8N_egYo{K^$Ty9M+8bP^$uud)- zL0MRP0Nt)eSzfkzWu>!?-OyZ8voHRLSSM^(WBB~P zsuDMKJ)&*Co^jJok2b_jLpIolv2IG`J&2oD%s@jh2r=Pdymb}+r0z1u8e%~yiYy3$<@9M=x zT!~4Y;CVpl;F>0RnD4ZNH)E`TQbmEzs3A~(_xj3a9MHIbu(g#Xl=mOCv+Y5kGbdQ(;x4eK7!n^Y%19a)oA9s>#jxCM+JKKLKxfn z^BbY}C`d6X=Z~{e!Cz*jl5gi;#Ki{Pd*ipIBhqWEmPl_ekms+>8yL2s8=<$KS|h#h z78P;$#ma$R{3#r7CD(7Fypj7CwyepT86~qoGlrS%YLw#h5o1aIgvW`U$4kC~{EIlNt~H6ds-5dJeFI~zeff2Wx%RL38pWDx zKh8PN{cX4=TMkc8evYZh}k$wGK9t%wC*)Prj_6AR>E-Yh}I^pdKmRQfG}sO z+K%m~pPZAQ0_Brn9~$lwxhZt*>KOv_$$LfI-;$W5xd3ge=?j`{g#2wf*F47@pdF@X z)pjV9cf8Q^Jm%X{vL(46l;pOV605gV#hjp&OhYFD#2syzuGfLqWNb(lE zODRR%7g;nhS5%Jo8rEDrCt475dF9+mW6hNq;7rVQv6ewGYp(VouZg)9mTu8Qm>F}0 zLp9YW9w#t&o9VnBVHWKp<)1(pm+!`N1m+JQDa_P26lRqcVW!TZFsn4eoLUjHag<~V zjf-@0>@V99{~#&fu6o22`)%IZwe};-*{Zf<`{^gEc7oT`zlRa#gzCklYZHP9%=dJP zxhIo5G(?!qXFcn<3E;H7;C;^wpdG4wmx(a@YA@|o9r9PBMfQb0P#zi(vuQs-+sS4A z{2MU+^TXRD_*emRW6x>JpxmeGHuL;sm<^s%dP>p83BO@OtoDpD7f-tt#y;c#z z{28PemGkMWRPed1RPr(Bbxwnv!ft0lth4sx1Bqj!xubR{r*sWrmf80Ljv ztQ=s*pUe?2l=aDDaLAe&Wl!=UFr)18M}!$=xnYJIz$^JoGIm3ANi{BXGYJs3t1;|B z?(`%($tanVPbis3dA{gU%q{%bmYA#CaIKxJxpJ1jA?DIrwqqu1uE~v}iMjOqpL)ld zD?P}An5%fvr_CDX`UurrOgc(nKA*7sHo`30N6LSPFfQNj7YWRLjEhB>sc$IEDlNiH zokL+(X@pr?5wmfWSi@|fZI@lwTghzTi44cba}n*e8x<}7wijWx5yIGf@e{u|dcE^8 z*oTG}Xe)%SX$KRSKTj;?W{j}0p99cdA6Tb{FTnY`+KPx?0Bx^LLBYeI{B)zUw=m!5 z+%nGhgz^sU3LftRXpQ~aOt=oycd^;o+zP17cXevF9LhiS35jh1)9kQQpq0%x$*7qvZsC9AvorknSX-EHBIkontB+ zX6%M08H)n8CGQhp#;|am8yv5WCJDpb;Rn{t7-h~yRq-n3f~#8-b49P1y_+@H3d?iE zT$fG8{b0?tFeQ(e%j)5p2-aM(W)8$$8Hy=o8s=&U)#UFwOkfVl@9-007VRVDTR<4w zmvouHYzmUDnW=9m%qlIyOr1kvR%rrrMa;%gVk0yzyWtH>+3175G2dorMcf`?C=YzL z2VowfYCE={eq1}uoqE(3cB!R&v*SY7E?*@uOD+_1RkM5SpAFF7b8O#rGr;NFZcs)y zfHuY}WX5nP*E4)%sts^j?Y{Be1j>imW$GZz@l|cchQRazMo)eX1S%UREl5F_&*r@y ziuo@3xacO9!)A6Ts75p2>jza04i;eU24QTg{zn4yP>^C&&JSm$f_G#koJj^b(z4d> zxn^w<=J#reFsFjtr>q%W=-!#Y{6(!1W|yF14!>AAz>GhcD>P}ON)@u1jgr~SM!9jP z2s6s^!W_5$d1b?l-OyZ8-^>HY9TqmTF)ZA*y$iRiQ3?mQPvcH<)97L@E2$fC)8e+Z z{a82Mo^h49X^FPkbk1FkkDH<=|J_2Z*rM^n^i-c zHdKqa_ANf~c+_sBcdV-I*naw{-PV7BtO4vp!#i=ag|0c?AoMmbF6Op0*ztW9P?{0= zNPi2^_{zD|8s5TfX`eStcLbC#h;0*$`Q98mzk3%bubDm8buUnQIJzS|Yt~K^_>aQ*hU`6QMUnt&!e2Ma3L`v2vgne=^(E zD1}qUgkF@b*8hZeQIX@-C^x5x^r9>;y=iGLE1O>IhUStwDw%!wm_RRvnIm2(g+uso z!DcMUpZMx7Ggqmuk{fTlotP`Ms%$xHF8%sLiMihWb@{-W>s{?J#9Zraif*vxI+UqH z%yq}WLaAY{AyCcbgZl~0?zP|9Ak3nDr2HrdoqF&>IKsTS#%IGC0OzM?A8vGj@&uPZ zxAp+EQ?uRXUxn#&e;%th9H^{UV?}Q-D8FgMkHdVAKR-Nvm;m!Es75p2>GhIc+z?>i z0%2_HiKztUT_DA%oZrn#1%Hy2N?tNV$@OXArHFShLYP~rCBobu*LujB>-KO@Vy^Hi_G>iEH5ICH`nZ?C?DdcSVuV?=kCdMWVO+imcL>aDKvI~g zZz#+vEy7HlLt$2Fgn3;>%*Ii&OK6;B8;MLd#`;>}j`S)KM}GHHK8@dnFz;5i9otVo zeJ6b%g%OzD_b9oK2egjQ1ZcO&4yIzh1Dv*bv;%0pM?QA8h4Mv% z&uzzi4}V%Zxh<5NMI=cO=HQ&D%~xQ0-%Rhxc0lD@_oHtSX6}USOEZ{0^FpUCSPpCE zjZlqdzC9bx&fx=7S)`sGL8-N(Fy~l}f(DUL|*0;Wj$cy*0vYqLv7A zZ;zgg+!+dvNyqE!Jyqx+D^>DXtAnX1(V2=`iuySglp{kZs0mE1;SJ+dYKs z*ugG`kZsXTQhqIjv3+YJ2-|x>Qnsm$DBCJ6vQ3Rd*;Z*}dw)gD#!+%gXk1`HL_gW> zx9w`*)vFTG#kr$}R_0D*`;4mX*nax?mfF2}y9=;OE#>_ag|3aiN7(jGS8}C3U27uS z8QU{2W4`NKZyjm`3`@5L6d>EJ70!j2@91kKy<0>1;Jx*Hb_2tUtemb~hUx28U$cD_ zK)UX@`}`G9{v{}28M3`7s*3}b1Ka*kjb^?}+us=(Ca}F9!r0cr0K#@4Hi|~!JTog5 z{8d&0+h3I27^|covyK=Nw$&2ZHU+7j+0Nl_Ogn*XwMMq%J}Wu=V&%X#{$$QGqjV-~ zDZ(~N=B`GRnNLNwQI?nOTW#J{Hrv<@%_X&O=-6Qw1-3EFoSH%@JZ*)rjgnb!qZFQB z8iae)0aZ)5Qw@!Y*W#>?ma$$-Yq^Vft?{KBt$4<3Ssm&UuZ=CJT?N^uUhCXzG4a}a z?O#VVymktzIg%DY*p4`HGYZ)j-6Z8NLKqjfaTHkto|Ljci9% z#B3ZTaYEx<7q09pyI^{wUe^86@Q7|TeajjUwqL2*j_s$PE(3cGI(`y%xTXB%4no(e zJtS=3?NP#2H~00J0Sq6!=e2Abg8>G>@VK)*eC?pzd63Bj%=fr=~x$bYB2AJ;?JM&zy9N2yV)oAA1q+rdsNP+D) z5XQE~hvnlQ^#_n*RL-ZcQo;XXrIMfCvxG}qzwx5m8v|r}o?0T??jWyPOgVP$QCq^c zms%s+f4i4(_{GYBZTy*omp6^SjaPu7B=37&LD)vgJdFTl%VvY*C>#bS1qVV&P=H$_~%QdvyI)*Tv8ElmcPF&u#I76 zo1El8eG4Q?+E-X_qhyYCN7#A&hN&|A?@i1Cp{$ZA95t zX_0MeB+9l*BinfuF&jrowUMN8k&i}5WwEROjURP*Dn>icHs$O`>{_6_rA7W#&lq~VgArQ+aZ4&XBoJ(1crU>rZ*l51{yQrbd?729{DRdbT;Pih&hzRKwwJ0Uvb_SN z(}?O8iyyTiY_C&mWVNZE}=?k;z$Tl=wifFLC6=6-v_?BHJj-yWXDp z_;O{hx3L?VOR8Dvce4;=`yR=VaKwMQ!H#^Kc30oiu{DsdxwP&AO?3t7*hd z5<~A))=i!d`VlvE{aSM>>!!}Ug1D(iOxa5fH~ocb!YAz{^lrD3)}06RihhyuT1SKh zy80=hR~ICuml}oAtI{I9)GCx-l}37-Rm5x@CGCX9`P6G;Ci6b=UJ<~TgdbZOnSbBI zAL;F&YC9T|ex{ranK|S(>~O=q*$;%SjeSPw{rJ3uyI5oK45T;o(~w`7@3gH>hnge3 zuIBrZ-i=ewHm!+kW@XIAW>9`2XL`ympww{ZD3?n(T83SfIRS<~!@AX91?7G3Ua-S_ zANQJA1IvNlT&PAf-(AywmOd2dEru|*^-%z!x9W=$PK?TVZB{DyrmR%*TS30+aPGF% zS$$kH?@~*o_W(%A3CBUx-x?8mkEu1%YYY|R7b^#P@uz_64O}y$6yD5E=tY@ohp(L@ z*N~tbab2VrWqIkfGzzI~da)atOKMm|ANQNWni<2)v2K*&)tzRp4KqqO#~e4}rhgnB zcK2u8WIC)Lag)BmS2Na4Ba^2QH`&#Eeu8yV7gH1Brk5T++%(+O2CA7edhtUu^XC8>gbhV-%x>G3^V)8D1|#w-r=!s zl$c8Vz;-oC=FuWLegAUx_lFR#^;$dm1M9WKS-He(-!_|XW4*Sy!BH2TN8>f4ZQdsW-9{q$o}rHM;uF>H2A z`Sz29uAP5P*w&x(m-B6LYyq-8U6x|G16Uo{tH#nMtEO8PW@+s}wpaVDj>LSI9QT;i z7|Kmo9R0cz81C{iv-AQ?pU|YnR9ArX>J7|Vfe6R1Wr-!W#E zZDRzs`#>1m`eF`YTMkl;%6SDV75r3ID*1GfakHO&ZI;yn+5V}P$aXf!ZGm$SyEYWq zE>vq|d(LcdGJLUeU>koj+tnzA_sEgErcmmV+jWJr&>*+ii)>@Gylihu3axCmu^XC8 z>gJIc&oF^)3^V)8D1{@2ymq0~+MD&-m70Rr+RVS6 z%6ctx_YvZ?MLWmJkZtNU=h;<>*J|7f3)k@4P^hNctnGyDFFPhLK(<9UNqGf?adCUU zC2Y?CN!g}0qHL?Q$Tl?+Wm~0@?O7Eu8+eSi(73?lvR*QK{jZ5PCKrZh50rIxI=vOy zUao38wx52q7OWp6>p<9c2o}0F`aNOW>h@nQZ(7rmslf2{4INW4-NHw4-BQ+e zGdBv#gF-Iq)B;xf-;FD70OhqtHCv2qzc)YVh-~jFx%hN4K&oiq=Y?$F**<*)=DRR- zd;pdM+oPZw&3vzG^=(V6z_t^Fv8~Frgzd>7#i*R0%1Q%Prs&zF0Z1jX#+yOi&8%FD2`3l+5ukl;@9%Y@;kM z+qVwgscg2f8=6aM@PI)>BL%iG%xra|6kbn5cA-&XD)9sBZIsMYwa35v%V`HRAzll+ zd%yWk#%p#8U*ff3J5OWQYkEEs;wpwl`PAY#b#AgvJ@z)afNlN$=S* z!KNU*aaQPcZO1Lh_90c!}~Iy{F^w zrI_z3mjfTvUj^^GNPf8p*}jrD&OTWQo9VkD4;w6V{J4}BN76j9`JTR{bKI{JB zulVoCcEd(h%bLRUYsO1brwVNQLN%KCt`~Ot-3x*300?7S+Z-Zn9|S2z<@{k*D) zeuQn5%++HkQ-6tUqbx7m66d>>%{F#Jb4fM&C%*8$z&3`N^)||wW7c?6DQ=UaWY*g# znd?tBv?=BCUPlwJnV+`^X1%7PFL;gX9qz$;%_KdJc&+T~jX$i{hISRaHeKP_0@-G~ zwil{-{N9hSZ9ebpIb>UO)Bh3o-ceC&QTsmvfl#EVD0b|!QK^n z#fAk%MXcyW#Wo^hK?EBrUQw}Q!-}Aw{PuHBk~#0Ze|*=wVExEib8nt(%-Lt>`OHZ& zDLQ#4g|WHsB{H^8kW|@LZKSfTXpL>vNGjWk2HRmdu^KPuYdpC@`O4IB+Z%lAiIwiB zerUNr6BCOr2iws~?#N%A9yQmUAJCEx$93|?_PlEco-(%mdi*tC*=}fAux;`o++qW< zYJKDF20LPSvQNE4uzgTJF9`LHbnQJiFD-vmYFxlNVt8GAQU%mI|Ge_8Mi8Wz+&w(! z(eg?E76=2|zD@4fV>yl60o06fz0HFLTHfVs@1`(vZ5_tg4k4*U-Q`1~^pxX7nIU)V z`PaO)`G5si+B$=6PlE*8eMy>bvzp{Gwj^VFut9_E`0jtr@j>InHfDw6ZAkuHS$1t1 zq;R$j@_VB;>hU&YcG+%I@qSwy(wEL^T_Q|chYu#QjwvPsp zBOOvM4kd;oclBP2dSBW)d$uhx{Jmi?JyxiQN0-Gtl2PyJa*B@)EsyJ!Ss!fwESI(A zApL#6(6#+W5~L0bPM!waqplwqgL+>Y*Qh*}6WbT58RL3)ycbu zl3LVVz9ULcIZ2cma`(M|&7&3;81$xgA+X)oAi?$!lB53Y%hSQU1Y_IBpuzUvJ%7#d zLF2?WW`*ldAZ31W86M>cDcns7S!}t+He`0$PI!^)Y@-{-TdLR&|KHa*+XxHi(jc{~ zzN1-%gmD{D;UU|nBL13RnfQr$EoohYDA8;3_WjIj1OK)#wGq7bGCYHMt$_2>o1)js zzYJquo8ENG5+ko&qh>BHU&+R8--Odo!M5fmoqU_Z*xVIfF}7cmRM}Q-q_VAOjcwIP zD%*+%+i!DXHD1oCJh|JOCe(6kzxaIG9FHIRmsYb|6^dC3w$qf{k-s|q+p$QC;dAM5 zoZjvHmUk`lHDmko*T3dlM`jEJ+qcF(%D<6V-B;9ct~D{-^xCFCu-$)Tk;u2`yYFsl_?0e{R|RpuO>O``E1?J zeZ?5t{ss-U3(%_ZLF4qZ7G{N8I3VxgY7`xNE-$2Of(A2Wc42netIzF$8r?A7G$HnW zoo{fM5$0#YSK~PckiyNCkfE=WtpcX{AT7_cdBDc(OkRgb93oe#Wxep z)vy^i*ZalR%|vs(*cHsoH7d1sQzLUFQ!~YXuV64g%AA-6m^J(8+V$t%h=QN!VM{ZQ&^IORqh@>&-W8_A7C631BY3 z!$@D7{ziRGnpT^RzjgATdc14<-!YgiJ+jO#Q^uMD=HD4@*P-5BzernTg4ShxsZ78u zUwhz#dRq;gy3mrAf2y@$CSb07WXS3e`um%Gw2sL9|Z~d&MW(gc-7YZX;yFU!(3M93tyIe_>o^m5m(vMyw-Q1t|Y+1$$Fh?0A zV7^Im>8hSK+xiq`FyAp~z}(S2%N!pxPB5#p%H5QZ>{l+x(dFB!d)<)Pg}ICO z#oUG&-7wxXg{vH0c9X-5urM-1+Oi)4=~u2;Rxp0N&2FyD>X&7nIg-0+b+b(oqMMvP zxG*<$dp~QQ=%yD(<})|xzaPCIy6Jay?xy$6tg?*Ut=a(3s*4SI2{hFhCT$)8^S^G!eA ztklCVM;3$Lrb_O}U!CeNsM)b;+A`2vcM4gvhpVy zk53qO)q*H}_Gq7HcUs=L`MtfU_sD1Q$0b@mBKA)i&|ACHCr8wK%%hO};|arM;pcCF z-o{m`hM?YeHg|tA4tUmgu1U=p*Smk_i}**J-g*>9uE+a-!%x<3B(@G@AxuYmE zm(L+s$2l{#uy~%y-PCkh<{YILPZ$82?h;%Jy&I!{lZyT>IJJP?q`a zsoY%sq8is1&Gl_CH&@p;p65h!&FI0+Rexhj6VY7TJ-E4=#2vn9WUjW492I6o1Ll!Au^RdvizhdzVb|(z z!wS4~?7Qu&zFLi-#QsMY0p{sS?#N%AiUpPHS^f$gQtRX%cX`(a{9-UyNX#;?@or@w zz`QVX)J)X7%&1@1fVSq+Kl=gmw&5vHQ18bHBY&FF@*m~)-(Ew|mJc2faDe{)_p<`G zCJ>dWmkX9yK+8WiN*;@P58Qci3zieiI%>wa-XBamt$oa4Zc1U~IxL#O+?J#kb(hHlEdhEd}e z)nF#KkK2%``$hX4FU;*Tt?=aUqJ5@@?_>5!vK@6*w9nL@+&;s!PcHCuT2;5? z!xKj9?|jh*gq_%bIC3FyovP%H{MBihM{D252k9u8zKL8+BrKNyFkHJBW{Lqu!IctQra|T}o~E30#}m%`IR{_*K66r;{lyH(Td0AGkVBZ&(@iKJ;te)JeqM zh$TnI0@qHB`_x0d9m1=4U^(GBl$tTF_l{y`8$98-j-)V>Dprq@Y9dc0sYTu8DWde0 zmxwY$&RfMq`tWyE@drcm0oMWs30#YjJUuY=!?>724A(LS4P19sGLi5><23eSRyf54 z$wwA;`WjNWH5&4wLpyax8Zx`|CY0Nn+w`Iv##^e=lv2Cza(WTwPd8=sLJBug4Qp*8 zC0zT#++_Ff0mn^(n;KtO&)n3pk3%KVO(m;wH&w9j?9ANQ&mPCS_TRKm*mEA^OP;H7 z=fYs3v~8isT~P1P(R1SR5T!nqPB!a7%S#M6+y?db`7h;+2`!(!Dy1&y-Ff!=g<$&o zu}|07OePHLFTHyP^j<&anpJ@Q{_ggM_t`sJ>pRb(W{m4SFi-T&r<~qJ6h^LzfsEc2 zB(X$nB?_Nd1!R%4IBb1id{B67=>Z>9Q)c-KygS8NEXc8uXr?MsU*y zjT60?<-3Wr=j_Ymm*A`Px^;Fz7^1?>&yWuXX!Js6m)?kl+jE;ZjZBc9WX za9|Pafjq)-FQo9(@j8DK=~?`3=BCcwt$al{ZH^0LZrVMoc|Xxjhih{;?M*B7T6EK} zs@zQ-;%?;wy@H$eQ!`)hEMvRMYoE0m3VJoa=;Xr`#s)n$oh;tf;|fWYUezcny^7Z8 zRjs1Zt7y=BJttP<&w5;wSz26Et zEY`{E&-1P=n#t&0bk#(oC-NYS@4dp!8DpHY-5yfg0X3Q19wxZZ*i7 zJ=|m0%Dx|06QxH_hV?|fgZ+=KnnD-`^%`Nike0vK2gHD0+wNYyu$;!;P1KBWy|;uX zcS_>)22dEeW`#3)gGg#ocR5&;p7JSCX2`X#nMn6%e&0|t!U6Q^3=;IZliXNr_@T*% zofy3>4I1>`y<#HagT{$o%nFxtLJH6KgA^VK2Knu6KgV$ZdMj4dX3UZQ!aV z4>-LDYxgt9vVsXeAZ>kVBBeNRH+7jA_DFQox5urSo6hbox=M7@Z5?;h-L0i&iEfHF z=WfcZ+3l&3n+{PkrRQ>b_jLU;1@vlup?8i`7#pWuucxM z&cnJ^eJ-PSM}a)jikl`iL2qO4D)~1Pjnggc6aNyW(G?cl2EEh9J_teApx9LSUjJMRR?vFn` z1ic4Yg@jYk_-pO=q*xXehT<2s@<_Jxxw&3ldskmHSG&ad%v>=$!_SH4`r4kGtI<<) zXTYqQt41(4S6Zc3hmFkjgPIAd!(slpAaN;R*6c&SvQQY?*K9t6Ie+au8qBJ1RG1a5 z!K^w*g;~*n*(oPh)gGeW zt=b9yRd>%;_zfYy!+{#@_4iOH`KZcV!u1?wK`gH0qsNWljYwCzvy+8RL4- zUu#?PC5PE!C{L>EI|j2INiFIwJBZR#b`fQUyou!7IcE;EUup-KcNipK4kGC|>~)9y z5&0R+hYT7p*QC7gL8S<0%<^+Gr?DdqDV)TD}uoI+hhoI4b@yH;)uqikqu`Li!rfTvcxEVdhG0(=1su z*S(S4Tpfaa!bNkr72@WaS98WJBXea^GnZ2Q*nYK3*w-z9S+kE$HlN40?~z3e=E5Y^ zky-VP3bUd$m{sSfFe@4`7tM*)csW<%$+=YfUf%6N-p4`9_P^JgExp`yedoD=xr&mz zMl#LpkM12)GlCA9b+TH`S@2H<~+xFQWj-DEC zX1>qsK|TiaeuDz;-zQ=sO8e#r6DMl}(@B>m>Y#wR(+a1hJ4PX3xCAw+c1@5LX9+&fp zZt`Ej-E`CUdOy)k(+6`mowPaJ$;eG|Tpp=mD5v*lNX-z?tNBGIJ5m@Mw3i>Fw>(Le zUezcny^7Z8Rjs1Zt7y<$DJNFr<=lWLH)!+Aa&9I!HfL2F{Z8LuqQeZEC$mAXPRSkl zt5bZT){Q#6pxthr+&GnYt?F_{uUS?eX`{?hZm(5R^K^U%_Sx;I-%hS9A^P}F?+f)t5 za-z2)HDg@wvxmoWBC^pn!0j|@6}%9Q0~_p$i@;j18J+C8M_u zNtIsJC@Q^**63BOqSC8q(AzF2R^#Q|M@jC~hq7)?sdHRAw@=nzk~-dfynGhu?W=^5 zzdCibyc&9?5TmzlbKbQFs~EkNJDN)QwtRO5z4lGddZXU zy{|o}voD>N_t{c76!bP}pRp12+P!G!GK(*Xf|{IYVX_*HEvyxs5BjVZ3RY zZoKyS3C9&-;r<6mexiWg{{V^FVWJ&rNa1Z#9Y&c-=EJzTCRP}^P&8M!tYyqxE2FXo zi{@%SjGHU4*1;2^xwd2-W9ABK8~Dq}T>YpS+vXhRCv@#5VAkxTlZR0l`5jurVD=@c z!mRp6g;~)W%&K!#m=z6}XXM0cyquTv2c7w7GO=be-WlHYI zU!8th6k9XB3mr7;WS@1sYxCAIn3K1eN_E2Xm;&bFo6V1--dUkj`~mGvyP1Chvqfs0 zFY0}|L) zS*=m0gpb1<7|aa~8Zd9Bb>V}?X(+}lA8hyFs2GypQyYitv>>(J?1fB*&)3*SG`no~ z);G&-w$TmaE#-Q&cgts-ZG?rRVo2?FuUJ-+kMvf6#UFNKWF8uBD#iG5a|I{$h!xE> z?AZ)vu9&T9OGIa~nXs&HvS(TV<~}8wXYQrH&$nTH-#LIeDBnTAd}Yn} zov8P;u5RV9oM2u@%^26)>{Lv#cO2%e6h^Mr@eJnOB(z$2F$e#5-_`xbUo;QG`531gW27n0kb~YRKf?16U>+u_NyU<^VN{_K>R3|P_|zU z`Q(-cGh}vQ9#p(lZo`aj7;mX|t^Qk)#9>BQ7^orn%kyZzI-1o_xabm5;h1@{g_+de zlzVMv_qX}C3SP6B&%O5GVAF%5*KB`U!9g5K6tD3X*#5)cTHF0U5nqs*k0VgOqz6i zaRAt!A287k^}c$_eKHs>TPt-K*#2Z8UqrpKAI0~hldwF3ATG}i1VIH zkQO&BkqEZ^oDyfC-sihcuYu*n_GW6vxZZ6}Syp(@+1^26UZS~fTXA#M8U8UwG*`hH+*~cDy@(Ud75!gvX0Eu& z5lfBCb%dHJdWpkaXl(f}fLXH-{rXB_Y~PS=4CWY;D$J^HRG1a5!K^w*g;~*nIW8ww zi#3y%v9OJ%Em|b@JtzylZo| zGnm&cCN~$08x5EnG>Mnq+hTVy8T zgT@JF%<^aSoxol@oJbA%Eaq>*X&2W=MxI8qAQ{h1oT+LvF*2ZWwQ={%;?D zd;yp*u}<@|3U~426aHE_X4da9lisJtGB@QNJ!`Y*rm~rbn49XYu=^;wY2I4yrl9+; zmx*pVw}HE9o=0+fk8eJ;b1LYy<6)$)P4B&nKH6P~ z4yoy-t_Pl_4Uz#4b5S02}ZxIQ4yZ)2;7xkW=++_TB zS{|5p;7QOswEgIssCU2H?mg!dhHg&db)Yx-?-Ezk`_k(7C9$07Jx8rFG$h#))3c@&|Vv1HF*^c@_zv7qT$BKjH%Dh4eV9(F>VfdVO|u%x!wn4dX3U zv*T#_6(5Qbp3biPn1$2Vko+lpx3QZIiBe)BwjueGfcD}L`tBDhb|Cj!vx(2*MXy~7 z=3aZ~c*)vM@Y=hN1DMyw`~7GwdTq&%am;JucC>F{}G8LCaJQm+DK(v(Hh&TkyN%74Yo6LVl`gQmS0(NNl8H^-E125a>*RPGAARSrV%o}X4zOlS8 z>RmKG!V=4gZTr&Z|Eu1?uAQ?KwhK@g$u>x2Y!@Y|Mcw7%qV$xji84bDB58!Mk-kO#l zY-?`P$(JaM%^kdtv3-Z6%C>4Fm2E|9Y^z36*;X{zzLyiLp}lUNT*UJlCERX3w+s2Z z3@6+w$D~0Xa)QoYxf1H|;_=%6(ItnA#{y!MoO-X7|ce%MJJ>_1a%#iPs z-1MK1d5bD$U^~$u!S*YXdzx0PIz3iqY=1ClusvYBxr7fIC$=%mkD1vOV36Fo>_#X^ zet>ud<2K~no*LVb*=0MaWar#w8{IJ8QoHYa6?wziMp!u44H+tRotwnPc?8eRIonp~KG*^5VZZ2z=Q#VC(?fZ|LYh$&e7JykWS5<0e zM{^GI*ejJw0A|fTI=LQ&v3=8`CO9T*VLo16!H&X?yuyI{MBi1@QM+oR?-nRT|*MayH@@XgSoKYT#BqX zPpm%alL1hEPX76!(5BP$Tjxc2b>RcC8VOEaejMC=k~~qZWwQ=gUMl;4CYI$ zLfV}b(M+Otm}q3iKNcRT*{hNyt*gP!Ro?RGG0|Lmzuac#y0f{8uV}6l7r415L_O>$ zn(OKuZmy|QBjSwAHIka?RDi?$a!s|`fLXJTPM%I-4RJe<>FAZWGsR2%z1x$YvQ}j=WKCDe7(F_HW0}wA{4! zmXs9)?W_|Qolx)lGh?PLCMs_&ay3~(%ilZHJA`^SY&f+kmJ`gYsTt#XU)yP}`@&%k zr7+9&4ukm&NiFIwpA)6093#pMxm{mLdQvTGZJ!Vmz}(d!0dsGXPSY#5c)MC+Fb^OCUA4zs5pPEXfD6z z+*~Wi^{gnGtH%Uxu5aV!g&CP^BQ+DBwS@ib{Na;tBfzZLM<)kR7~8jV7=!s3Nfl<* zH!94E)?ikhqr$9czR^#QYSCY%LE$lY+w10v_p(lEMmyL6R3o@7^lrZvFr*Fj< z_S-Uz4yko=&`#d9vZol#vkyqp&Ks%S0rTF_Z<(m~wv5jQ0d4(5^9}*#{$+3NM7_I> z8nh{emXE1j<|bfHvkZT=hyH$HrxG=m5S8ZnkCq0^mbZ_uN4=A6qtg|b*HAOY^`1Pj z*B1rmjTA<%1>Ig_WDX#yMd`WrqV$vxi84cW3X!A{wLPb8`Y)>q!CcfJ^#pTilA$f< zx7-+D&S0)!(17_yuq5Gw#tCN33O_qT@^iI`fEiMF3LoUV)f&u@*@gLlcct8h8Qn16 zQX5Mi4SUC7Mp)R*hUE8j-vi8$!pZFwS0w5EX>P7PU(eYE2fd0|T;V0T zxl-HA|0$ZQiwQT^k_npvjLfx-nsNEWVIH-*e+$5@*+(bup)j`ZuhR_XFp?_Fs&7=7 z6|G;}>3o|`q08M>=cq6%8Ze*AiPd;HNAl$6xqU0-);*?f=GnN%`W-`eO}W-%0!HR2 zC3obnPR|#=e&)ZH4ykqWm5;n@ac3CJqkl@$tvLnj0_Kh@rOK#x&~Upj_{!FmP3Kz#P!O=SMm~-rKcP$N_yFPnk2>c4Y0m5>MvlfZjgYv z0m(j@w?g(GF=H^h88l!%kSa;|pmBm3v%(25$aGI!62?w|K?+YJfV`fl!3>#Qm?vDV zn%gj=8^&8If8WXT-*cD|79Pq6$sct_C%~dv{e+X-hzfh%k@+p8xUt-8EyGe9ie6jn z$Gz5}+MNrc*S^%@UQ2BJ<*Mkl;7;6YnOXxS_ky?j z)gBMFZFm^zYtx00JWoy>r6X*e{9i-fHQx)2?X(saQrORn1;DmN$6wu1Z^!mMdw}hY zH&1>5+xsWqyMcN~pSkJ*wvXjYSpl|VFHKyAdfR55UbK`TU6cHB2-vndX77!9PrNXs z6P6R(RxST`z5kT@+VUG`J0FFStf$i(4AezPYEgH&m?-IoD^X_1he?_>$@98^-5;?1 zuR((Cvm|fZACI-VY0B7+H0X=;JL#9f7Lxs2-u;5^9lXWve?HH|>@4jP2-B_dUn-8&&X58d<8&@=|JM5-)P$yec7~MbE<8MQHuuTb)s@>F{ zsdiJeW;eBOs@)U~ySe1VYP_7Q^5i16J#=#OZ=A8vt^Xr^>;EbwhTa?tyH!_mNB-*6 zs{b+T`3bb!=qS6AzwkkbzC1C@UuwY)Yar=ryVQz_#XV?G2$Ed~KDw9({dxe|t4bI3 zum&=_U!J}dYUcKrC%R$$)iZv|%@!Z{mnXu)o)Dz=7LZt0l1kK#l`zFt41?IvV{WU|+E&58K8|92+_*je&) z*nfNPdr^q#IwM@&=@fS^occyLjK7u6ZL!EwoQSY?fPIG5;LD1G7Ra71M?q9L-iG8p zWe@B8e9S_s5W}5lKKIHh(TS&4aVMVpt9vUt(WyRn;>Mbv$BIr2N-w~ixbR`8UPewd z3AK=h==t}mXV|~}@V%;eO($DY80mKJ!@gGwlT^P~RgZto_iE9c zSdEu+1)f}Bl`93@!e34OxT-{geuGt%MeCkp@V#0|$sPHt)63&J?TsgkaPlu1G{|pD-Ny%w*L=hz zW--+qtH`ok{==kjo*e&yY1QAS^Xj~arpoBH!yU=7^9zMCZ70+A?eKjEXgG%`L%iUP=x6J8I5I9xJ2CH zuZ48ZksDJ^=ny6v^O-3(=4Qt^zeQt~h~ma9VzRJ>Xw0T3xiJIFZEa>`Oc!cq?s5J_ z;9k^e7`_NJ>(SeiDU4051B2Yc2ei0~I`yxuOei{GtL6^~LklsT^K>G`9-Uj#MFS+cI(8^FE@+-g`# z&hroJ@kOw(&Bq(4_nT`zD**i4G1r^2U4Zg&l0AXFv;L#0A85JH#?3 zSg^0tG9tRcptNv&5v=x2tblrN_vqq`<@80+ftoR{cg1~A?SJqug6Z#Pssll>MGhEi}DBJ zXKRx@0smvnmwn#l_Lz@u7;m`LzMJ}e;(MP6Yqx)#VKorOd_=YTWujSBIFd(HxYMg{ z2TQ5L6z;^f{qjE&omg}*cjB4Q=eD8~xBGA>hG*3%E;?~^ckaZAreCTXIk5#b^Y1=R ze(8M`M}vILYdX0Dg<*yRgBbaPNvhcF! zZ_kH*ceQ_@ujS*t_1ycBAb*mQJMvej`gUvGmRi$+zD{oU5AWLSA&mUivn{1}6Bq6U z`MOItQc&;6!i`Npeu<`E`-1$@;TH;_-ZT9Ue|S&J!vjwg1^LD1{P%7*{k>PsyN^Kl z$MG)rKz`z;mQJX5M9Qonh5TOBjB&j?c-jOgL|5@m** zNb=3UYg0Nori1(!1_|=tk&N0n_L^hatR}Vc0Me>K^eQa~pMZ!+1-Xx-R>xppLL`mJX7?rH@XzN3)Wk zl$huYJfc zwwL6@YP_7+^W+?&3*~bQt<=;k*z~^MJAaecwU7CL?Tt$A$X}gyRrNU#u$IoM&>OHX z@vc=E&e$FhV<{cgZCwGjuUIELY$sNa>^U|QqxaqBk0*oeg9mR`M7_NoT}FWI4Lh%! zg6)g7ysx6(6M_c}SWax8K4AS3Y*%Qq!VLAk?`>5P%V|_!M9mo2d+?3TB~$sRzJkKY zwNxQWs)@Xwq!x9TH;B?x4isgEYsl(r&U^~A-g6+a2Esq2jc8mDK*mf~! zupM=S_@oaSC$=%m2Pt;r7v!MVw@W|%#V#+06rSb{`RcgFHe`0$HmOhdq9T{vJ9I}k zjJH(f2YLu|Dx_Uc9?N74_AIyKpm#yCrS!1|chlf=5yeF}IW**MN;lQj5Z!cV zBX?8Z7jE}NH>K|6Zkno~nXn|JU9y_#Qi@-7Oah?yf8y(dVj^r}Wt z=~c8wuWA*QUPXi6u$)+pmvaP9&cU{=qnl|=mDCOS;`OcG*qkiuKLYedD!C(nb?WNX ztYmZ(I(FB|$L(d-wL2pjy~_*BQdscAe?aeuhSO`I-XnW<`~yl&_ibMZdb9kTbf|Z! zD;JXA(eijV%MZ(mQuFeGdr|MO?-7Zhv{a*;W=m;#+}{J=9O>^1pBTMgq4xweV_ffj z1%K~Q=siPWNu5oLzlsfa8MYrc5Y+SF9g+ruD1Z-0_r!CCiD zjLc;84l`)b8}BSj_@Hs37qh~7I7t4?Q1<&7Bp+xlV`PT>o~6+XnO%C@q~$uj=!Wr@ z+ITr{_0N1K9AV)UFeJZIj{SZHDeQGa3QrW>QeT$t?&MypF!!9B=(UpDxz`3Bs_!m( z?Q31`wWv`qLPf7Nsm;Asz0{3#Bd;BxW(N9kwtEgAI|poQZqmu26vpP>Kbo<9nWW0L zY9p0xMQd!UMpD^UG}yk96RV*YLG$F2EEhPq6+3)ons1eRdee&I=j~cN9BkiHa!3B^ zH0-~XaT|Y)0^1S&dDmu+Wo&O7Axl9uD)$H5@8ec?LA@Kl3SI=ZcYkRc1hyA#2yBCT z|LEpC0c`L5)+Zipn@k_F2=#vMJ-o*XVtdEG(~E%Z)jrE#px&*@I+nz88krAMGsgA4 z>$j`mPd+lApfGa%r!`~y3`s3YSFMTCQ;rs8hTPCcmj3f8y?V^gA7IpvgB8Rd+kNL7X3u8ElK8Ho7Z(_ zC(&yQ-*c~}|0uLp^xA?$+-u9rdnX%t?IJbPVjgF^TiG^?z_#Wlx;TWw$gj(I#`Xh} zD%+}!RJIkZv8@_OWn0l;J0T}lJd*uXDY@_Ddyq z?}7`b}q{e`{mFC?|7yZlX*o^qBbGvwi?$c!G_E%%!+w#OJG*q%r-snps& z>z@B&Z2KBC*e*}&!Uv5L+nD8Veh$M;oshHL>kT;DmR-aKDLifgvgLM-ZOH7h?UH;g zx7kKFjJMSA#($cA;o~;K!nh5|&o;7)*dT>N=*M?u>CgpkuIPY?(?xT&s>02+wr;-u zqPf5^4YoVEpumZjj4C^mw!F~`E=nhz+9S# zk-j#S`0wC6kM(qft&>fE^RC^R%wV=Nx02eOzE&GBr#%Z=j(QI}QaK0%^5mk2V*zuS zm501h@8ZP*Rs&|g>uDi?*<)F;HmG;__Lucn63oY|Cbj^~*ONv>q249>t~SAP8mQf< z8RL2%yjUz_|e+(Khw=lDk@Im7QGiJZt#e3Y(0A@&b;l&5~F?88W*t z`?ZV7ZJ5yw<1N*q%;iW0W`u>)W03sE0rq|@Na5%1bQddWeJD3q^IIMKMRT1mz|9qH zW-?kd*X>K(Tq}LAbQ8_>s~k7ixZdZZjm%|L%1Wv@iNk#0RNXazS+kE$&PQQv-@Q{A z%oRwgBeUuo6=p?iFssf{VOBI?u9Oq2p(lYW$;}S6b!!y)&T;60+xpq{H+^ziKNK*# zDq-ZWPEHHmeL^PC0k=*r(S~28S)B#=v&8r!G_e1s9gt58*e35xzEk@(&O$i z(OegAadS2O)XY~j*C3gjtH}7u^+j|2Fy-dzXFmR%k-7Y+8T&CD=Hq8uZUoGleRT3# z3S;|rn!#WWBB{cx`bLFW(HhLEb5xiW4Vd@l#A>{pLzU#5N7%TXhBz4CZ2iwC!%Uw*|~)y9~aFdXIcK_5q;% zC$hp1z?>0iJrDIR)#~Y`x3s)M=~)W_^R7Na9Z~PFNr7goh{{O?dXEOo;rnbtQ18OE z+Q%v|SEgo+>%GtaQIrC6Eea#oe%*d!H`|q@7NuLVMd>NG5oLyahNN!u;Lbi1z5?b5 zg9OZ1NPe|jK5XjRpA6=k1`U{}?Xr^aLE{87W`*CVA^969o?v8#RmS`|T zW*6oJ`@6XfGrD2Cr7AqB_Ai6^601Q4_M|s<%#6QA?J&_XGo z94(qF{yaCAqvPjAqPhHvadXA!sumT^b{MI= zw98b$+-a|?g%>R!m@;l9>TUNkVlZG{?lF2IV73bnPYa~KzZQ96C}7^5Z{%#iyl8g) z?WlLv`99UKoOZJ(QZvT&4uAc#Y&svAr%@QWE*QmNo=Z}Ty36xL=_#)hWrpnd*-GlP z@>is@{};gQY>Z_t2w=O-Gt>4U}zX3X;4M0U9|B)wXKPUfOj2cAwUNrUqBXWvBdKgF8f-7kiPd;H`}5@H z`K8EiAI6TK8utCBerl@=cc15BY;RI>NB-(`u3lh=(*x)To8Bp1n|E#6LdN#g#@15i zLDP3&JAKoc&!~6d*svmCJMW1Jg~0Yp#|B$a?>mjkS%B>Vb?OWP+q2r%c?P!4XZN`X zhRZhGy&7zn`|y1Y>OHEF`7(uVKWfIf-amJ(pQo_Bn!?ES&;rKxCX!mzUEU%}x(`g0 z^j2CoYw7N|4~>HleFobN4H9fOBiSf2(V@ZYAB^ob1`W24HL{lQLF2?WX8BXO*j_gz zf2!FF4AhW?m{-|eH{_kt-POHr$n3J+W&OR}9;nd`<1OWB{$Z8EHp2Y$^>RGG5RyNy z^*>x;0*O*$qH!BicxUbMKD6rn+-ufX*QSeJ8*_wvZA{3X?V{HvRp(w??Q5MZdTn7n z?zN)}25vO++E!}jY(LJniLL7%u&udCC-0;%^6Rjev3-oB%C>4Fm2E|9Y^z36*;X{z zKAsb+@p3+=B$paz=~m;vU@3B6j6SBu`Bx|124UR3sDzQfI^Fbq?GX779dOfc)bn`P zN-bq3+<4l!ZvQowe3g9O{vN%|y~3`pAYov~flpuu+hGHVGR zG)`<|RyfxUNhiALZV|dfd=85W<2ItH6EwCVv&;4t&-mPC8{IJ8Qu!Y>`Ju3lu<$z; zWb92$Y@Zxb7`GvX$0RKbww8(<;9k2iHo#8wnx{YaT2zSx!J^mJwB}wL+G6Bw(QDW1 za<4g9ukkbT+B#}xZg0-^uPOiR2iuyPbn;dTV{`xXV{C_zRM}Q-q_VAOjcwIPD%*+% z+lO*uHD1oAd2&gCS1jDp|2R4An|MR-(tKm`SjT~2`;3x1@>i!B`5eCg+D6CUI$0mb zyB4#Yv3)SXT8il|MT6~8zx<1$-j)fACV=f9kH= zZa8-w^)5JR*+{T`Ztc#aV7pNl*XgMD%$jxUU^(rR>!}&zdRzKOR{n)B{ccEMo`M5o`}JNU%Mcq-Fak)2I{Q7~2yK8f>RN zBtGeb#))mr@*5OR;%pftzq*344Jo{c3)1PL#x`Vj***}wC%4%~H;lKG{td)7eH|`%2C1?atYr`)k%gu&udCCudL?`30_IY&-olu&vriWn0l2 z+p3XNwiOMwopWL}bmJGThH^`4d{%NBHMex{GL5438*e?!7r3`S*sjFGNMD-*4h=cF zAcA(;b@InzHmqw?Rx`G*m$#8h{c$`Cwkx;JR}=M4v&nD)+dW(cw*uSGt_%%Fy^qZp zZ40&sUTIbfZ2#`;yB+l|-z5JTFuXo_-374S`o^YlsP~G@3kwvs6R8>FdOHv9FhgPc z4TX_x%pJydDoHKsE~kmoQ|A%Gh3D z&|teTtr{ORPHbbAKNpFy4as-H*~v3V_KUS`B#yTsb$NTJ`{a<>W!uMQe{QplZWwQ= z>SubNU~FGvoz^ZmiDgoFvPwd88)@e+?xv(xR~v|Kx?7C9>FgD^^P-y)FL5`8cCNZt zbd$qt?xxZ=CQLGN(|c;BR98-~*RP&OL9gZ)o&1%;*r4s!GJ2&JHrmLn8bzg7(Hgy~ zRaANv4SFqeVl`gQ`DitiTf~_&=5DPY^w{6r@w&dp`#*6Zt@?r90z8cLwaGd%<9134 z?Ud_e=h3`tCD${0KTW2MwLkU{==Ey7vpMShuyuj^ptPCyzV4v6-?K`QsP~#viy~gr z^6m5fmIl2G##Zw~y<3_7HeW;ZHgtaw19~S+nm7#gJ`}MxPN6r8nlY|-gK~AQD)dTI zcv3B!q+(>YC8kPD7u_)4Qb!zX+5F%mGs42} zSnRLW$A-tU`tj&qT;^@Q-bR`f#Ld+vKE0i2E{7r9T=&X7yds)w)NF393BQ-F5zQqx z=H_}EUc$%7T!pBa&mB3;cihcS0A|fT^vf-Uv3-ARU@+GusqSX0zENRTv<9>492I6o z1Lg)fu^PJdk|!5oA8qD#z+;<7%&)8Z=OcQBcKhoEnAowRQsLsirM^qTUC$99apN2RCjy1Tb57pB;mG53wxa3z+wY3~>U? zTeshvjC%ibd{9TgJiGj)M}WEL?kF$RJ7K&{AuOle>`&B;alMDdZ?*f4uulF#VdNTh zkincqQj5CFCYJ^2DZ7X=Ltag?Qs)DWx|Vtem^T_EgPCOF25&#pW?$G)9B9yhxdXL? z4;m+!G0QKQpnDE{ndC>*>~b+g`Cj)$48@RRLo}EnvkSBHy~DW;GrD2Cr6x@LHBf;W zVc`%Ol3!3qhtRRCB*Nul#glBLUFW&Ei$iyvy=md^!Ll zb5%=Q*0qtl7|h=tY^9a`8>|D&ozC0&px$@t?r9B}CcE2%i0Q0Te%e$i9$L|&Fr@;J|nlY}oo9jML1!l>SC)Kvl zPmIjgB(&2&H9Hh*o%b_?+0UQ>^CZd( z9~6pU#w@?({|I1))b2=_!z91VTMw8K-I%7q44GY+JsO1OHq7XT@s{fIA|aH)e2I1X zFWxp*i@lu(e=VE^B|Jy$gKKCg;~)W%&K!# zm=z6}2j|3Uyqt&gt;L-9Z-DuV?o1ohyGWx#I~ACVQ8UK%-oI;~zXG!hg^}y{ z8Vu$#B(hVR6Fb-P)%(tU64rY7xu=ZbC`GKIV8m`kA~(M`5vxSOt?FWXCW z)7F{XP5<=y)ZWNVeW;nQEjhj8*A+MqdNse$Q~oK84Vt`{(fbccm0r~-D!q!<=vA$v z(yM6DJ2@v-4`xtg)c1Z~&XFCc*G31R68oiL&r8n@*@!TGY(GBA*_2k>})~Ps1 zzQj5`mOW6JUEPVlM(r>W%#gy%w3ghkm3mlkbCt94StFXOK{Pj4m3;QeqPcE3b94E` ze`_h4>(FCvuGp#Fn;V&H6E$H& zXq~*{EAQHfgAC>&8Me~skV9hubC=ptTTpM;mrIrd<|QSstq05@^)7rwy}xu#n*x}B zUrl@knCEBSt$}*K9=^0QU@qvEZskYIFKuh#ih8#zSGzEl(?Rk$YR0(U50*tZWFSnB zSD-L*ZDIEn`_tA+b(n>#SxlA7q^tev86i^JhK8;TjT1VK>_#12ItVbPte zlT_JOZKSfTXpL>vNGjWk2HR0Nu^KPuSe{%&qIXu~XN`W^{B9VjKij!l)%>G-fbCmK z?#N%A?%Y3Avq~@>QtRZ-?!0S`M;Y5?+vb&;?s+~0Y)f_52BY5bJ6yVg?Vw`oc7Sc0 zmSujR-Yad_H3r+M(fR%Z+j4_BE~t0g!=L=XaL*Qz1;F;oR@-W#-bY7m>87w7DSL>L&SsPBE+6SW@BK@#z0n}S_EwVl%bXtY zF6td)dxt@T?R{%&59Dsja42#_bkm(8+)YdBB>xoM zROUK&)8G7ZdC^UansGN-)*D#I$W1+{nfLCT-uo4AM}c0=FFM(a!q}j1jxl;ikW}ea zjiS=4XpLUgDk{B-2E9Hxu^M`Q7*Eb+&(}YV|LI)n)uSPo^lR5R{i-mwJLsLLpP z&d*cmJwsvSI_)i^_X0^R>MrX==_y|mWrkdEOI|7O=0>}pSTlNy7$oQ|LDFY(lFO=~ zWJYfpg9g1tXiY%I3)y&%MlWP`>D>~(I=AUXH;lJb zT#;^$KlyI9p$4%SiXl-uOthN~$$!gZ4-9(|mRIUufSb#=#?P~&x$^Gh=1T4S;E!mo zRxP=?7Myo0B%14I95>gDg1@U6nd<{J)3^zTIV^MLHNdRdM<;)#F!EdbFN66PNfl<* zH!94E)?ikhqr$9c!2CNWR^#QI=Ojzc!+UpT<7#ia2khDvp?|V$PQ@EbJpr>R4Roupyzay3kXk1{eayS&eUiZ(^g6F}+cKgPU_NPA@iOY&J=x+7pxv8R<{WQ19r$mOlXP*QYNl0_F`7?MkEG)m=_pP+&ev%^27F z>>`ho3d|=cjAWgWG*u^J1M*|hdIOB>;_=g>_cy0r!cl}!_y3ACz2}6 zs&7=76|KRnI!A?B(SW&NPOQeuxg<|+P`M@?*^D%l-!ZO zI{g~=HmX1~I;7Uge=6~=*`HxBN7S*C>ZbQ?37CuSH@%H|huAoV0p?9d3Z4VZ!}j!( zQSZSs=I;W`?z&ay0rT)d^M3B4zn|RXPq}pj^PZH}wE^?8xdBB{??;)zpB0#|Q8UK% z_8wgStpam2g^_EcF%0Gyl3LVVz9~w2ewZjTWV5<<(guCG*g9RG17-_@1kBbXmpYFr zS$GspjKAi0rqE??u`J4Oq6)xnc7d*T(w(2&T)RI%iWkjQ=P)-{ z`PSF1MRO%K;O6=m(knwWm-{Dft`21_OBk7}2sP8A5r)W_;~;|Zk-EpTb9*UugF>SbJHSHP@< zk-j!rKDG0XZb`?`I(ddK@7kI34CWs5?WAkPMm7e_XU?`xM7^JkpRx!rJ1ww^0?c9c z=h~s({!d?z2h6vIZTlB6j~sIS9qR4z-1R)9JB=Ojh&JV8*}AF3ich zHstomjBXfjsky@xQPmq-~3D`_+y#mcTH^t%%yhONsEheb3NLblq8z# z-aKxur~@$$qPbQL<>p$}YH*5ZuE*E8xwdDnC}d==a@0)zh8*U&S?A&avt}Q9+CGJ` zeOK!l%+*M$Fsr^%VOF#Tv+5ibW<>+$99fN*b1k0Syo{&mja~NaU$^i1d41m(v#YmC z>jIc-E4d?ob=p&-@Hx|NbV#j}n_uN!8ydl2es{}Gx-~1g4q#sG|M@NIyO36=jCp__m$2dC`ZDe*2yQW)Fh| z%q>XXZI_{MI{g)cxwSz9=5@3#e9$<-j9KlHC0{1Pu20qPD#Au)M74XW7P4sQDGg>s zvkSAy;ElNrGrD2CrLqcqNmXD*Sh#)@lAjYKn4?)qP)bb1HlqBfWgFOj_t8!Yp2@w| zV)meqqStm5;a{ptMlaM^}UhScvFo7herjT z({IW$IkdhZW4nfuJMvej>M8z~CKKogo34i`V9&aiH;S=+r?|c3aVo3|*!DP3<2&lz zXW^zQV0&fag?O<2w#oOxsJG)ci$Y*~vh|xiVB77S^gu$kVEAIq&+Wms_w_+m zsCT8srF|8)6R8>FdY^n3I$mKriNeVB{s&5`iTs|V7Il|Diqca~6J>_nri8upcyhZl z$pxN*?T!Wsw!4!YaBbwBd{bXCw)+?~*zQB?!Uv5L+nDXnAKrX3akI0DTH$`@XosV4hD>g<18D3bUd$m{sSfFe@4`FUX12csZ})$<3>= z<7eZo(bpy(ZFW{~=X2|w$A6tLP_I^UNB-)xqR*-VpQqCiHa$LR2=ChIYYb-3G4_&Q z-;^?ddE1M-e^Bqa+jORY*}C?kM8F*MvPDVM+tuperx&!`>}1IRz&yk}{VM9c<5>Jd zK)ZOwNl(DMbn-(p)Z1*_+}#Sy1F0F~dat>gcdG*PFbX5rfPNnV^GK3f)LkAWN>6#R zC^O^>B=;|kJnb5j2$(M!Bw&srxgptR&Go<+4Cdqa!In+7vvc43Y5JvT7y}2jtaA)0rQufSdEu+I!`XJ z*S^%oO$Y2)`>gaCy=0bPU&5~=VE(1#j{Mch{$@tq3CHLNTPKHv@~#bzVKD!5)?PZe z*0&g7PIj=DQSX-Rmi>njxOn=nmw@?no}pz???2(ct^nrWDIpsGvzhC_^Qd=1)}kyx zJFaJyzJR%<(~7_NdpCWJXa(k()QoYxqf6@}6qx5w7`YCNW-!kusYTu81)}tn{Y04| zUm}@)Wqa0yv5x`s6@vuK*GW2+vfDC8|D3@bW6*#(4@rE`IKhlrVPuBn&lqBtb3$rQ zDOt$=xYTY9W<;|KbHX+6+=dz5Fy2yY|nYcQ+MQDIgzV7`| zKJ&EMv4N#J0On{VcjT{5KW&yq%b~coQ7h|vRB#6xr?C~QhT!JLMEI1f5e>y zR21L)|EHeX{EK#B~QgZzj9ku(Ap<*mtvoY=dX`z?K5S&VxLc+ z+oT%VXESwUsG)3o%dSYc16);u=;dt`#u|KdmEn4jq`*};L*UA_imUL3z?Ey@dMGOv zY`+PqfGY~VV(+m5}+ z_k~mKn*!I>)&=_m*M-#&eZ~9Bj!id5JDt8BLERYVJNWM60)G&uE5s>`vA)~RaGgX_ zje5$HwbEN&pp~ieW0E^Qwcfr?P6DnkG9++)OY-7rr-pf|D!6{i(7^Rk2U7`8bWYn| zywqId1*v=yitdy#g+(>nUPS-8`-r1r$js8~w`x#!(~D^suc-sue%u-qOpa$M+JtSd%P3RnL4sngr6m?QYRy%Ko6B_Vwkle4t*oh->s4LHgIaUl zw^GbicjtibM&@#-Zst{2U{21tI2kaj_R-7rD2(;H;3k8)ElB~h@Qr|(YZYeU904=e zfZ01M7UQGqq72UO@U_qGg{2Xt<|ZEx84`Nr(e;B(0dqG#c8p&g;TJ{+&2;u| zqcXMbw;9YIcbZC{ww03sbMWe?C6MnKU8f8I%x{yM`~=J$I<%~c{MC+o-x)ABF628E zF#G14vK9H>_;%?)KwH1zgrR`B+!EW5cz=!qwQF#g)2SQdd@m{zU6I3_XO}Xlup;lV z?JY=Bje5$3wbEO*(@MIHHp#z#EGy3XmWeeSiw#Z#+ky|%fa;F+g{#FY9fE5J>R>5 z?PpS%@nHMGxI=4@Z@=-&7J=cMtpi7c?W4_)zQOx1)~eHyvz_%{co4Gvvx7m2Jq(vR(GvusrNYqvoxwqV?LDM~c@bdzW(4 zdaXJ4TD$Rg*K57jx0T|xx6PZrGxAys>ZSo_JMPN0`(RsjlU{B|VT^Cj#}BwUK~Iu` zZDAw9HrFcK!bpN`uEBP%tXPbXZU`UT0Q*nwqZj#23Vm=aWQFM;$)gY7uKK6%i-uKfDi z$e(W3R2#58dXC3Pu-$u(*AnFWeD(ALV0ikqH50-1m5!5N;QhtF>>JJ5wx({3^Bwq) z+hESN4TUk*LI%dRBS|&tDLZMUw_H{$Q{{mq=f<=d{_XrNust+Gg6)wcdzw^h6ISdV zV|#3d2HRT=WH)-Eb7C7W)o=8TV^VVnji}~=Fv!p{zG5dFGP7)Vnmjza*~T=C*Oblf zW^Fm!2y0G&LAGP{?lN}5A(h(5zBSdVo0(LNo2&VoS+%t0GH`R%&+q82HP@@zin&gC zwOp<>*SD*RxyIGV^~%UxzSPaBs>+6X%%P4C0kdi!`g${kv3}crWiSsRDPR`95ioPD z!YrI4VCEVy56z0j_~^zdgA1tL>7#pxfMI9e{XQC^YZ-KYZHq>Lc>*6h#xEX+irEcq zbes;j_41P0%G64KXE5uRnn@RT4fzgeADLHiN4^ISDsKvy3tY)v0PTOBM|vQCrS5J> zeN64{HUWbHbLahy<{;le_n$^HnCsP;4w%oro$?g#x7xI1C5O2Ibz_|GZ8;nka+n)a z7-RK5^b$MaEl8?SPr0R5ddnTOGF9G0(yDU1TemOY1k3>$5-{%~+458S%WG4T8O-}K zG+;it#7x2yofFJ>srhYZNad5No7f45RPIB3VYpVVS z|4|I)aF&BcC%*i-IgWi6g?DQXp+_DxlNxb1Mf|Yx)VgV5yyB*zE1!F6-E>~3xT((4 zO7pdD%EjGOvHRx~BR5T@ZuFeq7fvycK(Fc-y*!J;SfQyu7`-b<3VMZ61if6V^a`s8 zdbtL@E3;xTKDtfH;HJIt{NSGB(#wjUOCAjw^JR&JYukpPcQYS5#xEYhKbPdJFprL~ z_42eE%G9p@V)V|qZzhd6YxW70PB}B*3;F)rY5Ny!avvY}D}r|aanALTzmu2DAA;UN zu3r5>Z>xEGrXb%=p9Ve$rO6dm%mKZvx*vXs_s=?P9mMHfLfshW+thN`9!~E{3S+Ew zY+r%i^(57(r@TQc>7MvnnJVXeU?z3Xwe53U;tkN7FGGUfLL}c*DU$o-!6Zhnd4>kP zpYPGum7eIF=*3IrS0LF3Gq?fqWi#Zv{fX9hKyT8>nU-iTJ7!ly&sgL;dSyt?l|--O+u((uH+P_X5AUzsu7512cR6)qobNLyenfD3S5X*aEj^df zyN;w9^_16ZrMJ9ID^ul{Bo|eGmU8U%bJque;MhvtE8ZRGHfS z{jYIUJZikTwB$hk7l8K9=q7EE?|z@WLICrS@P0OEA9OFh3G(Oc7rYNJzbaLy8(`j} z>opAdKHe$D4lqa8*{}>SM^svT2k*BnI{F!hc@lMFobTNebKmDMPp2@(YVno9Je#B% z^_1smrMJ9PD^ulUl7E-}ZuHcY!TcaY0_MjgS9JX1ZReNBV1AaN0kauNJkdG9jF;*u znsH37qjT9|G1ssoji}}>UyxP(RG1+%3-exw*4Yg+reVCM@+DWk$&ZQ=)?DKSshksJ zN5znu&za-am`jzoxvq_m_tu)LFgI7nZuOgK%{7mkYoh(j5n6NgjUO@eC!y%ctmvw_N?bh2hDU}`}4}w<_0pDFI+O0 zdXDpZ0%%PO9{dOSe(-bbF2H>1vza5>1NXVMK>pVBeYp%U@A$gBGhmj_Mf69$J=?CS z4w!!p@mdX-%jK$j3-8}mq~2c+a{_f^oNw1r3Ew!(Hz|y<7VJTT@{p5As!>llSu4He z7h0Jr*S%~my&Lkkz&WpL*fQ78kbt={$>|;H==OEI&0ubxp#if8EelU{PB7!8`bDU5 zOtRZPPoiH*o1%%bo9W`s-2zpZAu|iJ+w6AP4Kt=;yrvpmZ}f@7jIibu7o_^#lX#XP zCAu41=5Hy)4L4VwC@UYWx%{}f%Fgv~sWn$~ZmzU36$fd}wT+u=$HU>bjm(wvnYpx` z!(1xm`!m3-+D9+vr7+fSmmmhS1xW$3@Qr|(YZYeU904=efY~xD7UQFHPzL90`|Xu` zktbtcZ7LZUV%L4drN6=T0J9?>JH{^_I}3a&?ooq|q4jc}LKbXlu16WnaaI;m!AY<0 z16tb~(Or>m-?8Tw1LltJ<`zeLGgoQ_i(f8cz>DYX;x^bi$?BHH^%us_H9AozXb_Y4V`>yf-MsP5T;EpIWH8)j(0+?AGvCpssX@lta)0!ZZ! ze(V$%q~?4z4#+Nskv8^X5*cLVtY;&!$EsP}C<{E6*&WgqO z=;|wj3rGoj>F(Zi>9XLEgCXAocdQA0VgTD-eC!y%cntaYrq*CR9bwarvVD}P-966O ze%H%FYX4?W5*U7;ytNnd9Xi{5EZCkrDW){qyR50u4*47Rbw*FH{cJ!|8?fE8VVADR zch|_&o?zG{Ep;>4UK5)?0q?&sV|PW)_D|}@INz;bR4>Wd{zGAmwf%C&cJAI5k{b1t z^Jt~FTtq8VWq*=APyGIIb5H`<9+)A)_E3^5S~>->Jc`#W;#ILF9a8J%=6jW?%|6ZOEqc^KGM};T z7AU1}koQNvho2tT1N62_Nh*)_@R%>{k-u_fU$p?e7P(_ufZk5!*ZhNgA6&M294Kwy zr{H$b>l{`(4(~T>ZK%)bElJ%N=X>+9D|$|ESqfvUS6;rsZgypoYSdG9*Gl^Bb*)U5 zH;_!aW?tAP&lS+SHA8~log}MPy|$w2z#EL-eHj|`E;?c%;fc=avJml-ZXSsJYDmp} z?I91YQ*njNEUuR?XFIN#hViNiONcY@O)B&2=@GVy>?T0y}HXWya0*K1a29BXf12ZlbCv$IOZP`mX@9 zY9G2Tio#gGK4%%s{YeU#g>MART&pk(=Lnd&2FwGpVlh6tQOe+)7cG14e(uw|Q8}yc z52-w{-q&2w9@rF*;bX`6#iQ!&tsxtS(jm28?*CnxT9xw*=7u>erEir^T?4d7mrWaj zeAnrp)B-RUt97O_+ADqA_z&{;HLHO;q=8G8`FrP}dknlw3v?<0*^+!j?F{!zOAEL@#gxDv^ zkV(%~wjndi_PSZ!vwKsFX&A4m&^_-uakdfGoB)GVc2?My8B#gtuoe5&iySPaQ`}r0 z&eMl!&6QG9G1nLOO`Wvn%FoU9Ige#~t+{G&bG1C&C&tKJ8>yT59Oli_>%Rufs(tkG z4hm!a<_TpmA15hb7QPWMbFIQGoFic78Ze*CipBWoE+~V0lz+i9_mLIbTq>V?Ur5xT zxHtEE)&5y74&uySgEh&t_Jf)STbZ9~DD}Z*;{#7H9@8$E0 z>j87^q#;$=mN|E6ALOsu&lM#Bvx`ZMhJaaKaHR$Ey)f)e0H8hJC14+5Uiu{>3h)0k zWz7H%^GfQ*INy_>mh8!4-b`VP)#U<%c_&FV>M8HmN^kjuR??5Hx3-jqU%S+7T!&b| z?3N(`vw`HFX-CJW1zuw?H_Fg}Il85#geU8KB$Mj->TyhVG^s@Q!Dm0(iZ@odUo!9X z)fe!MWysgnyNUg3$jrjLY)z@`h8fc^UQ@$@zYpd6)dZTos zIdp%`H-K5Sk6u1ZVT>^_g25a?Qot;HBVguQg;_X9z|1vZj?9Y1_~@=HgY)aYD8>EJ znpH0A@9ha0FnsgLXxSYw-{fN#ImZ9(Tggd}qG>N&FP~naOl@W)gL&O1OR0_f#27%^ z?)1QM$oIIJ|C9#IGfV%df%XfFmUlt^Ts~hi1I(|(4%P$Axw>C&jC}8kI&lop+8-!; z2rzGa=oyLk7nt2+GKYCTbz_|GHLpI5;xGqM7~^c>@(f$%lO)xsr+iu~>E60pnJRm1 zwv-&&ShPjpUOX1r8xCwT%FV?z?U zbf0?$GbDXXMK{-FFhk~>slp7IS(x3@%Vsysn1=D1dhL)ln{SyB*4!ru@*-WV-fubk zMGHvHUN@wAKGDrD?6jri$i0>_)MJ9yYi+sL3cZ}rRqM4=+-s|>Ha69I?e%`eYbmwM zT{QCA4eG|3vn}U!ehao$H|gcO6vpcA6vf#7L{hLVY$Vv`T4h@pNwCc|*#43gi}BIr zI>QF{$THxmyU(#@G1X&shnRkJd)q&%HrSSwFov%_d_%+iugi?>H;yl&9#M_>;17a4YcMe%*{2a;OPh>bFHRs zK3C=!geCuFFst^_%Nr?-^_we(!5m0Zz$|a@gF_o^S+$9du=Vnn%F5IdV;RhE-K?a&c26$= z+5wA3Pe;DJM%T{`n433T>W=ojuw_DZ$%;Q}8c_81(H)C%D+L+j| zV}QAE?9x!Y-*e>{wl_|nR9Wf&GvBd4@~q=9+fx{0onGKMHq<3Zs!>n5lvaAnHMBBS z-bXU5s^P@2OP2t1P=*A|r${!MzxU7N$SZ6^9g?8|b2XYip6Hxl#!JPjY(ov1@WY$# z0`>?nLzZCYZX*FRWP7LXVy_!AvoPnlRwcV(#x(wei~)HLbC?m<9701DVmB+Go$z>; z67^QaZhjv+SV>d3xuT*SXKKw=jGHUC=$n6;D{Y%%uA76+3|eyqaC4pQ-#g66Tsb>h zNtZdyjmO`3hb^;eAHAHP!dSlt;~C73Bn8aEHv(p^RhWfy1k79mX6LL}4Bf#`8JwZs zqsQ*0yYzciK4NExd!2!n!+N;^W*0toj9)zZZEsNFK@B>>*2|WYIX4Lm=D%~Sq)`b8 zVSu(-uYWzGXI@`=9ytn$lx0hq)q!G1mRX8O+s4s!>n5hE{sZURp`# z!$_u_+|w-SXcS;RpCJMBMUp+QPQJRSTRej~CPM?}Ry2J)(K*44mzpgzq;h(P?R7&c zpTn@dZpa~nRhS_&3v-hdF4+w;reRFR&^+ZMILruZw#<;qVG28!))u%)p~6%_nKRH+P}OOz`YhzZ%ZAm*OIu`Qf`(HG4h%#b+etbo!oxQd$6s# zNiWx-Fvi#M8e_XPNx`}Hr%q3Y~MXP4~DCbKQbTrK2)sv zQ?T81#Pa%RKRCR4ALOskva?sfcE!==HNf`r>-TCP-^0pY_zs4Ben*@J+rEy?&f@*I zo(~S=Z1<;bjPu>2dD=kti*H&w-E($BYw*QTtgu~6%^ zGTdwJrhWgH*9vg2-T&ZMOY1c^?zNni3Y|0ZT4(BJ8fSZ2FTW39TXmCO?nPm&?i{xm z+ha)zwuOxZ+gz(`3nK}(xdz+gvtltmy1B~WrnPGR$o>6>CB@#p*&Z_F#3aA(wQGXy z`C{yB0?I$d_f`om8$bu#dbx#-HJjS4+l+1R64uhh2j*wN@X_G;i;-`?U)^qkZTD&2 z8=~ERnR8#{PuDLY6l}ZqZBP|#=Xmqb75P5j=CHJi*#09gKL@rKA839W?=N1&CxNrw zo4PU1ci_mEQJn3`6vjx?+A+3glT@Rg@?5R-mRDyJ5yO zj91Ns#}A${n8R60lrNI8Ei>MYWZ^+uX2|`YuD9%I%INhmSWCX#O*)6vC0aMxb2qJT zkn}G%*>gAfd$+Bob<=(Brm*gL&KS9A5Ow3n={;7|<|F7;{i2sgQ5fUfe}~aKkEEbi z7)8*_wMwtBilCQk(7PZj7UQE^uM941t<^*KGK-HL=~ifa$o%`S2eqwU1N3g>W5@W# zV?&2!FIM-VBW%4qy00>|smYAqLBp-3{s;U|fzo46)s`dQ3qF;O0=xP0}PwPG>@&2FIEADf8r%*S>`JOe= z`4*>lCWSH9scA282)&!68ugU-Y9)PerIo32jS<$8mAl=ubDhjP>S?qimb=_Pl#!ceQ8!+k-aBie8NI4s^ztGKV}-WA$LI|pDd-hO z5%hAc(krYY=;a#pZqJIv_~;HRgPYdz$bEM?;F{&^y4yl>-K&t^yk2$C8^p(s@ry^^ zs@?9*tWSs3^wZPFm8q3`!06o(YAubtmUJAHcCtOX3i&n!tv&^Mtro3ohW7W7!2?+S z9P{o3y}f-4Rsy}#4vZ*|eBWO`t{CXeYaJ5~dS?_~eVnbIP9@%OdgG}Z<9uH^cjO7D z_ZEdQR{N00p!YsWHR>rp&`NLlomQsGPr|IFvg2p2k?ux--q#rt^nN5c#HISgU41Sy zdVgkU(EB~aTEY{Z6TNsjl3fDE=!H}+)lR_)Fi6eWY)Gr!D!q`Irgw1R?4}pfFkVwT z{|wCgTe(ylVa+i!q;dj`&iBW&3@K6ey^HnttffxeT#dbyu4y;wo-i`kKI*0{hxvAw5udOrR_&vgk5L%w_wPdn^Cgl3X5kwF zGuJB2!Z`wFt^sp&RxHLxm#7TRc}(Yf?)`>$?t6E1K*+QymY%0NRs+mQeC!y%czkJ+ z|JjmqbPTPRcjqq3rgq~ogZWb7qLQI@|6_o5NyP%|kniZr8x8>G3&r!dMEj*HeuI#| z>9q>31iDvcVR(s^8JIAETUAp!FOk}Z#$=kC+s z5`%eph6c>0v@AT)Il+vVnoTjJX1^LzvtJGA@>PWyGP5wdJTlF0m@y6GHRZo&r4@rY zoMlMeua0L@`3fYvXyjOV`eW{I8$ zA8h2NDC)+P)0@-O;xp(~{i2r>D2x@l_bH?I1xZ1#Fp8j;Yn5JM6+ti8p!Zc)EXGIo zOBq~P=lplwH=?gz*tCoK`N^7&lJ)Y9w#w8dKV$UX z@GUA$zGHO+l+H=gZ$!SUH>$H0^qS1-(i-g_cl~7fej9vX0q7mnt8rP-dnfon3FP}# z?i;n)VX(=PDA2oZrR!1TyH&*GJZPuSqEe_E<9sKVE|kXUeNADEHE=zn*St$nNsZDS z{It?rE}@n5vyWYiN|(&L-dJ6c(OV!xf?jiy?yt(#IPMn3=+$Lt&|8W+#uJ?ry?CiP zeGRGL`V^aDNcA@kXENEaeh+a}jA&-*?bpmQyXnO=jMvnr?iM9Ey$BCA$E7p(@ii$( z%{eVdrTXo{Ijy*HMWw#nT=UKh+N3qt&zXw3hFPx|0<#Enb>!wsUj3k?)?6>Rxoq;p z8k_4rb@RKD^12nATjQxw*=(bva^W zuELj!O3yjW2l9D-!IoLIk6yN-FxKye{ba7ThH@kY%)&PUX0BD3g>wYVTm$9`S+N)& zon9H-ql)|PxZmA9^m@4+n?fSKb`M>C-32h$;bX`6#bd{|vttXDrekQmT>QN)v=81DJcBvOkP`SG&L1j>By7^FQ+)TF>5s!)!@mjJ1RlgSi$-HR>tr zwbEN|td*(qS(3x<&x~5qIutNRWJtgqP4ZaHT3xr-i)1h-WN5(LlBSO*IwzR%Qn}N} zNx%%L++C8v45|Lc;Y=1C^gx9f(ageJc8o5&Va7C!$>{Ud+>>va5mv9wj%PX0TozKy zN+(t1ZaR6Z{&uaK25>jkC^dOF+#%fbj=O2+>Gh6UH&x(nsS#3T+U`=xs|<&?}50=;d0aS6D^R%Qfir&WgqO=z1uFGn}5E=>E9I%z<4x zYz(n2+>JVq?7)7-TV9W?9Z%I?b4Y=RiQu8nk(WAiinL20=oA9o<% zrW5;32EFx7Pjx{1aEtaMknhW{?(_q_wG-bI1HE;QY_mna3n%RA0!q7WdKCwHC#*bp z2=5=UxJ_wJZ$0Y9INyIiJ#gUkwxBS^+M*Vtw>?QU>M3{7O8Nz6t)%+|k=*7}qtb=P z=Rxn|3<-K)klf#UN_uMh3yj|P85;D?X{eL%MCU{=UTThtA(anC*#(=B%Khos32Mk) z6?=;PYRJse+o_gKcGHV#7_X@uWA`@a^dhWOFuFlQJWH77!jD?LbW&mNro*Muc52<^ z%H0$kpY$&`mE&#-FLlUH>!z06P3K!y4K#97Q|jgdr}tz)o3GgRs(#VSZ7GZu`u+%` zw+~4{uP}BsMk0UXUN7kedQ;D*If34`+a4E1zPn!e;15ba9=~%1^rkIraS-p1ShT@~(>sj1 zG0u0ZPi4z;ddE;0V;#|&(L0Nz8l}5@X(fF)td;cP@M@iOeE;=6FQ=UYy|x(=^cE-C z@wQ!3@URF*Z`lkDdY7-%NqC}jq8BeUU!{OlzVpboy^z(|gY8H|22D`uW%A~V7>}_z za$I_=Z{tb-=QwA*3R*m-O{&xc?S@$v0jxdeMw5IZNdM3KneFsq8pdnNed3{i_>MHf zniJHJfsG$eunc57(iu^9g1W;Ioiv%7%Q<-U9<8}XaC7xuU3!$(TyMF#ww8OO)0*os zH&=m>;AhFql>Q=;fglMvm7VXE4tqDPR`95ioPD!YrI4VCEVy&&i6# z_~=$Cg9{r!_?G+bX)ErgKVBE|r|tu{=XELp<~4lm8js`%KX9f;>~uP4*2}~0C{r7J zlEFOmiB9@)@yl*Nd)mxlAM*WYOuPPoIcC+A&S>A%;5Ezl@n;e30rSyzr5pkCAbT$> zVKdsB>Q7_X@Yhb#2rn_`5O?|m|QA(e}| z*p(g&({<8o?xwS6O!sTube_A(!KU|UxI?&UH+R#Ji#4saZW_nkG}dwK0V6l;8uZ3w#bSJPNy^}+jUIo~ z{p7CITenB84e^gV^(FOv1<-q!j~(L|kDk8W-VZuM``LPVMQIy0wW4Pkz0+K5q$ggk zyFlrWvvUq0-&2o$>kfK1Ti5eNyQ8hs804>3asTF^_sP|s_Mo?Bc!W9fy=9GV0_fem zW5jjP8)AQcAKst4!v!zCDPBh180UN0>9%z^z3V89vECSPALq1okW{0d@-D6PmXB#= zs$AaHMjEsGYx5Inr$Mi4h6KH}NS5E7v(@K>Fh;LOh6cS?tJp|*qI04bFEyKDNM*aj zcBCOSC#WGmSoab;(vX>@ckhkY)@;*Ut*;w4+2b}@#$uE0mfwzT(!)NcZ-l3lCv1FPmZ`B~PEZ z1JK^za^n#4ozOntKY+RKo%dbP{$^prv4C^#g|YPkvrUoXwt%_GvhJqHcdKuCX9C*Y zeVlIs=54bU?#26$9Xry3!@QlkG0wNA&d`9ve1^gptNR@Wa|B5>>M2KRrMG-jD^q3P zsWy^NbpK^;S5E=vUKtWF4^;j{E!;G+IzZz26S)p4eMYEJ3 zm3R=_h^n_mbMrg1(S~jeqgSUm)A_V*DBs}H`97;Blns`ncv1< zyG`9J<7{v1U-3IO)T*2G@&gKEd~3oO+h0ivwuOxZ+gz(`3nK}(xdz+cvtltmI%$(K zxK?|vyU(hZ(5cP7)gjxCd;H8XvK-jX$HN%Ecx>*pVS@8SI;7UiaS_U24~$@JUy8Gl ze%QX=28M4%<_SW+i`Jjr3T&Hu&g+Ku+D_fZfz^bdZ+fsjY_FXS*lskz#svA!E6-mD zh8M)0z6G{FkMFk!?;jLZtpjKK4s~Ok@1Nx(T5z`SQy61C)bIf|)Xzw&QBV1WR(i|d zwDPw{=Xe{*t6z_iBm0l^9@eK%?~!FYj;rll$)&Q3i}Tv1281VOKm`IX*=MZ{*(X>Tl5OoF>1&eo19R-O8Dx!PYJq^vY=Q9G|0%l* z1g2rUx;r#pG=mk0O@$Cfvf|_7>gLEXEtGELiKb%g#>MPR8llew&-8zl)t= z&Av6PDyTlx%fBd$VH+Y@RWNy-Q5A%DL{$*xS=Q=YlU6|sJcWBiRZ!j2&S07qi}BGp z(PDCp`trfQa?Ozbxh%I;Il3xj<+K;&PPHkEs!)u=T@J+^PAOU^qqGNNt{L$2wP0cEbRfWg4w$hWYJp(|0@HnTVs0u%B_%uRQ`1-}%5ACDI4;&B5 z57&=%MO9cjV^vX9g^16u3!*BN9&>CZ=nt6QAQ4qzV$HU@@&1L?yLIJN;VX4xobRIR z-?ryf;WvemZ|7sID&(@WmDDKRxl=2>WlOF6?J=&a=wEp&Nq_IjZ7(BAw-+Socw6~f*Bm+J-K0&+ z2YpSrT{hG;XHI!P>EFGkv%hxDl~X=Q+Rw#ebu`7Prc|W4_&*~W zg`Ez_7CC#1BM8XM)|8)C-?F==U>e3|IaH(YB3@GvMzW}$c<`EnCV%$0jiU(2w{$aw z*>C6*P<1&bBM2Rpsk_6>MG3R=5cS)esd<6X}v?dM$suFqR) zZ_pJ|Yt66c_v|X$PeF8GYqh38X11n0O3e0}f@v7TY3osOHLocMBUxAC;*^@QpQS~) zuzv>bKaO_{uZv3@*og{A%?E&{b8IEcVv9<4yKHONXf~T!zDFLXczALA#3y*3dac}3Xciv2~!EP2@?r(QHk-&ipBWo+Rh#H1AD8m?rm_-le7&@ zeN-IzE))177$qilYWgkYyGZzrm&o_IRS7KLc}6Jh!{(cBKwg8|ev?pQn&xp{jC?z_ zmi*8@&A;Ogl$d6vly=JZSn9?&--UIn`k)&sF;gjwd~bNlO3Yl6YSdGnua(~NI<5Te zkxufzmKeS3|6XFuPT5M%H}=eUG~q8wj0MTK!~q|!rIQDRDv9F;gkB?e(6 z>q=Z9Pqy2#pCwImE)?%jey@Z+*obCP_1axGzxp>R!xl}NPxxSK=wWAi9F~viRpv3g z7;~q#8QMF?K4q5w?W43;*fu_5&sBTF>kx;$u>7G_3ogL&$^L`pq1|Eg0A~4|JC$~_ ze0%EVz?daR=T5OR^l2Z#N{ni1z3f9_%)%pqm6*XKh2w+~g~x>TgsFttgo%W?sKgA- zipBWoCemW6?)|pzF&X}HZ1*9P3PySyZc_QsxZ-7SWHeb5KIYPah5g6cDPg_bB~_W4 z#Whx9nn-ricKL8qU=5-Y{qFs~1m1$@pi6(*AhOqcG&PrA=xs zgyIZ0`!d=IB?jPu>!({c#9p%OEe!pQf{R90f9kW{0d z@-(faUlP;GRJllAJIU7l@Je1C%t&@Rb!OVCx`k04bR-Y!-M8@SU`x`lb@0L!h^EVq zB%k{#e~ao+jC7epZ`($8uwm7q6zNHwmA^)HC`~$Tz^bhg6sPL2Jdd4(Cx%Yd0WX!W zcb>$VRLC;y$2^oP6i8}5)I>DsjanU;%;XgcLB2n-yEuvI)t;7$Or9x zde>p>`L7XOS$-J)Gj;2 zrdqdHDNxO)m-|o{<9m6Xm4fjkg}sF9grS7bgoA{$gkyx0s1!`fipBWo=F?*G98gNZ z-&qH3E`N&fc#&deZhfj0O2I-+cx74u3+Io|uY~pT>ZZ!n&fjFEz|Y%GijikdMP8T9 z3p$BXuzSkj*U0yXkRi>{J|I{1NkIGh7^U51ZSZ&G_3PliIgs!8pyW{GJF!JT1lsLK zFAc!^{X&#>lmhC;INv)fjvb9|PzorFd{-Qhgj1(eNUBj!d6rgs%PX|~{g`zoi^l8wh_fPyW_I_Y)0LR)E+CkOu{$RDH$1|3FAzp{YE-Kxb}us0 zG6zR6kfYg+2IvSTnn}&>#ol3dQmGPa!umI}GgKe_gn4|s*Yw9)D;Zb{ihA+V@y)v=14$mw7zFNogmKpQUbM|K2G-Hp$NL zzS4VEQ&bo0uqMz5ID1t0^Be;e;+dS-8G_gc7Fj*soQl*7pvpDKod(NwY3C4nVr{>kgXn%Pjk>y){qqG-lKfWgN+O}@~zj%Let@s4w`*CDW3GHcJ z{I;^)3xm>5`3|CPjPspPaKI#9Q%+GB`M#RSYDySMHR>rxXr;G&O)GzUxNZNhHKkf* zSGWJYrZl64corP&?(d%;HKirVnP1+u>phO0B=IKs%lbprzKH&nJCK}mcdJJ)MAPNY zBx~xFzeP>yLi*382WH<}ShAYZo%F{N%3q_V^dN1nOK$Ov;#5vaS89r_y*9bRJO}UvBi}BIDq{Xbr6L=E-5BoGW z=FqS>kHVGQ{@j>c68kByDZHGAbvygAu%l@)B}{iQc&1Fv>>jHrr$5+9eVU&;g}lzI z)94KHUH))|Z^*agpFAJ!jqXjEj2dxgztUbf`CS#{J8Iq8RJ?zcYpZ1B`_R{dInn-X zfqo0#f3B9&PWg_fZjAH&z@gbpbVK_oHz|yKk8PNY{gito)hOM!Lo4Yn)LQx5b6HHK3hLY4b`k3d{mV!9$8AY;Meq8=b(ZBK-lELR{)p&_$ zx;%lTMU3*ds40_3yIgM*add_`t0~h+D~IeRVW=rHNYCG3R||2fDSzHm38E+FPc;QE zHTx-$?8dNH*zGnUH78yn9d4^71~RiH=JMWa*olu$R(K`F=v(80WiRf#mtgN~@l0y2Crk9PmmJnr z8#$wly}@E(Jagu(O3OdPGCk`=H$r=jS@oGSHJhJldtU4VW{lOjp{;nXjmuzyZx4FFj#zxHh*1s|2d|^ztVPV|6ck%ql^C-wbyN z(+NKbn+XF6V+jLkDnY@lSd5R(mKGC}Z`@s2zh%J&=ZoyS;_)?d_~;dXilGwNQ`nS! zF~%gU>j}BMDTVu#sCt}*_40@5%GCNiWtHImLVL-ktH}uD^~mqAb0E8C^?j@obR6@( zG1|+ypJVx+;HtF$eB=2Fd2JcG{0H7Yc+72_v@+C?oI}w*c1y`ks03{%DD9N*x73Ys zz8jl;Udk&$u|>+D{9{=qC`VF_ddd~F(p#>rm8tS+lFm*e#_>vUj%3cln*=5Qq!Bx_&KW@}PQzfWCv%r&A z0=(4R#{^ROZ1FL!EQQqk_zh%>5o#rX%xonvy_4;g0MjsDuQMH*U*(kmVa=_2Ap`Kc zR(X?ffd?erK9NqC?#BflU-sHdQLde@&m3)UC?@@3RvcQc#20uZcXRz-wD+i&%&Zt+ zT4~=EwxH>ej*f=&(eccR1KT~o`8>muqybK7KfI$pv*Nc7N;_FG?>>9U*KzC?0G znPc?9DLX`nAz9q7_{YRr|RNebsDwxdDYSzLb{?{Z1r>orKGTfrPJwV}z50 zV>IadWW{29bbVMfzY(#J%W?-UEA zeRZRL+mY7~haY^w`l*$}|2gvg&Sdr^wC5|@d;`$$n_Fq8e8*5X#`!MZx7J3EejJ67 z@B66?{REO~)KmVKq;H65qp5PivJO&Y`)i9i`h`hWG>n-K~sd`7X-e0)0!;JFEVvqx(>pp>It(@&1t6MM)F-W2k35F;qeyFO}Ps?ZBs? zkk^W%Ar4!8NM+>*1AWM~CVj>JKV)Xn|LL2U-RNT)#_M(9z`6H1`UtDHLXKuR(CqLd zs@(91ex;l)h-l~_xotl+f3ul`VXtT9P*^KIbj(+HWZ8gQz0jWW;4`!0q4P?+m+R{s zv7a3cT^Cz^#rxmaD)bIk-1sZ+-56>Qk^GqzFV|Mu$%>7so4)xhQ}+ir7+w|F&d^uQ zMt3HlFxIbGAo0=G(3+&MlW>_ZknojojBt{0j0XKIS&Wa)n?@73C-gPEUOL2J?Oi&? zL)Rna^t9)WKp$Z*ek!c{u;+aczSsCl(dh{5W&I#!YR?Zd^sUD@NKsSI%|l+jmZ!6P zCzJ?g=>J%BtvA}^=K4+p%7Mj{_7s!%>By^dT&d5<_q!WcULfC=_POt&z0R&7>+$|e zx0QCvw|zO$YSdFMsg>Sx1+7e#{Ya)p?pn*y??Ezl z{R-dtWh9{Ao8+Ag^dY_S`#+wCXu9lAa%-&ew?MxyY4;B`Z?EfKh@sz~bVJw9RiO#} zpwYxDJuy^5A1{>?fqQ^Hq_T-i0Q!*X^_er7yxK)YAJNRBzii^e>_#8cFkY|kw*@`r zJNyW1&iX+rJkZ&YXqFPB5)ax5$awP_R07YH4$|L+x`!d%9Sl8oR}F*HR(v#P=e?_} zuXGmezUHHuGxxn$+U@O{b$n}ZGI%`h#GEn6&CucUL zZnjzsYa938!7y(1Syl;D@9E`M6vp_@9$}Thhoo?qFrDy|u$eHBFqSZorV@0?ipBWo zdedTTAMg7B>tCC@_tB7;%N~_ZSPv}TzyXz@4~6~tX|E^!%a z>=>&A|3o@S6FQWCfV_J3|H<;5=9Tw15Z#+#cMk0-UlLiqE$Z|36yFZWYtP}cKVtpZ zPO)L9S`xdptcLclW4EkBCD=DjX{UUTpl*!wy~MHKE?x;%Q5gAt(Cs!V!3L6Q)KlK5 zmEQ7htxT2kU8Fa6o*KX_L4K0=$`q(}uW%kz0uz$cOfq%?NPhlP;No3G(`8GN^SUd4 zi%MWcIxzO-(OjuX75M zANSy-U^sRH@aEh5)k*-F*-G$o>|LC$?3A8sa^^sX|`(oaHf84n{OPmZYH;*$b z?z#Pip7<;4}S_$G6q*o{o#P1NtW^ zJcys?TDhlV9$yM~%Nt!~Ji>Z;kL<{%R{JDFe}%cD;l)x4Y{YLRN zCDFcNQOoH-xzZt}eR|T`v&gI5H0?dskNwF;>{QFFF3mTh{od20wRr!4(@Hz#dk1x6 zoNpTstNk4P2nr+L`{Ee-u_V=~ryQ@9-tq&jOqIJ?I7$;PChiqG0VI>A%Ae2V&JFba zN$QHI==Uc%=GLbrESfG4A$dPW`CFhrjC3FCGJ_k;&Ck#uL;Blt$CqBD3H>`}juM_2 zDxr^;nok2El^=a&XZ;{GXZ;|5{8Z70%q;qyo*d6^^f3+N^%}j-`~ycHVFiF$Kp#@s z|7YJP&ya0!5)hKEm!#{;X`jl?FQy8u*Mqw4$5R~)2X~r9z-f=mmHZCNOs*0)9qob3 zdoyRYFRQels?*Ho={>3h-sL~w{ndivKhXOPXG8w{d_wIXUw&lHYwBh4u2)j>^+>O}Z zq7rzJuC-uV&o$L#RtdaF$6U2|vzjzjf^XfaFwhf2rAmO8%2&gWVkZDnx!3Vs>;yn6 zwhzNj0HkH(e&S33WM(VDqc*3ryAog;#_KgHw)t0nCII0|?8>4W*#Cz_?(iV=Ar(A! z0{y_rj?z~1lpJT8IvW0Y`JP$vp5uOoe)x8;C#R`>U9}s`isKxV_HS1UoEvH7Ouq$t zgjw-r#6DbmXUMz$%t5qYKT(}oF)C7NCo7((Zldl!8hz=GqhZCG96xcLk!m)*e1XCk z-|2G<{aYl3orKGTfrPJwV}z50V>IX|X2oKBbWdn89dk}dgV&3W{&=N+iHjcP$9%IJ zmy@p7_tm9PxC}q`J-a1WZZ8Tib|2W8h4u2KoyydfgfR3&0v)BpF*=s-+6UHN0LpVW zJZ0$bdu{R*`L$ zQ>C5q9Z%gD=Ud-B{3u8N8ikSXj(ZvUi6qsir<|mf-g1gorphf36GYXkoaX4aCi!h` z-iw=T=o{UCn5sJg9ZCL?twytGy6i(Tzh3!Upx=db-^%&#t@)Ifq3=ifd-BC$ z(1d<<>KRWAmC(macr)}NHNPeV>AhM-A2PG(FAF`F-RNT)#_P4h zA+KK?eT0<{_pSqdNXg1K?#>3eZwqF{e;SU%^+JZ+Y3mcwp7YCeX2m>>m3Fe?bLu9p z^UaudrJW2B4XhaYs@e4NI|^g{_6lR@r;`+R5-t-46220S5l#}0(V(9*E(;dpqcfq! zq-`3K0~fq4i+Zu@LV-vR^8>4MUkoY=^i3(8!qHDCdFTSdzTfuMW?{XY_F0*lTLeS@ zXc}!Z$2M<|y#BWB5ebx2c9u&;z8loO!17(7}0o8yUG8=nopDv{SxAs2k&aUvs^1f}U^8$c8KWvFL7F;qeyFTei55C5@4e@NwIcQUs6kn|mF`amEATYboe zPgV3GGmHMX>F2W>eN4l6z4i=F{loYF5!PH?oFQ2yfJ7?spq&6n&6lF+CWBJ5>K@@| zo;e!i^7EK8ZyedoD#559$9JK9`OU4&nZZFy`|ZcI>__!-Hq5vA#hkhEjULwv83tY$ zX@d54E$%R9I=oZb$(hxtn>6c7wJwixGBk}V%PN8DJ-UNBg)zRuk*pH*At~G?Oeg## zY$gmOj3o@DsRaG9Vlh6tv9y@&}!z#fw(jPaZMSdqum7paJ6Hg44Dgj<9 z_hdeXod8Jo-M@$Ix?sq4LvZ06I|&Fm*tNgd|A)+MC2;Wy$?i&kX&A59I!j0AN>zSR z5Mj;rKafgsWLE;RKi-F*_hn}SAT?(K^7eC*zK$R2aJib3!F@~v=FD79GP^wGQFZU! zXg~A&4|8U^gVG)}t4+*=1z_xv!PkvB)8eAiPR_KVZWeS3 zTy-nL$xygo9aafc@9AYb3S)Jjyu>O&MUui@!gRtC)iGKUSy&btqh#AN!s>l2E7ug*$yW8_vRdx$077YKx*- zC1|zYNm@21!XA0GD|nOTTkjFTDuGAY9C^@Q^J2r9*v8kYtF-4X_&b{AHL=f2RDx+c z+pse)$#>VWd^b6;WEI|jZjocl|UzjW_KmPG>q5loxF$hvPuxnCjEYrXN_)W*rk7Xx8_%m8lP~IEYC`# zUQBl~oNWJtd2i&Vk&N|-E?&N9&okg3=Dh_QmG*|aHjZ9!#MyAqc|P-=jqiF~FJ!PE zQ@cOft=j}J@3rZow3GLIsGGS_KSxiHoeg&jwPdWT?$XOWDU21`BbKo~g{1J0u$6F( zFp{u{u#T{ZhV^M#u^1oSQd&&;eh&+P_4XdarZ2V*_i*gh>|{YVOR&C-!bdpkQE?-7 zAbifF+d~$nsohtmRx_Tl?*76_YEYxcNaVHm>#0#-*W}p)#`@wXFIc{x2XAEgE}f#Z z_vqP_<$GzfMlbOG$>x>WsTS$#K zdkts(I+IkRp0cl2ddvN^GF84sa_aoWH#zHxBnd` z>GD&O9TzEo3)Y{LuJNnB!?uOF80&9HyU(wg7(kj>U-z6g_mO1A`qNqWL(qQD?;!JDwIHQ^QMJh3bMMfx=k~tL zdk>G*#|1(Lmj(GYqW#mdB8>H)!MweuZUS|4bnVDJW2?|vsZ(7U>#Do-@(c=Ng%(U; ztgj;}{3C2793zY*EF!EUETUn3Lsl%tN4Jj_lQ+h}1gyunxBa-OT9`+*o72C2C}9EC z4^X%=->2<-=C;XZ3a|Bcv-yZH{pLgkWonPEGSYc zuC*E;iuRN*Z&|+eZI$-w1IMs@Cw8y-9Pdvu&&STKENRz)<$M2!F^u(37D_v@?nm7i z=lfW{m`Kk0cnTxmyKgbp=a5vRp7K1c^p;m@Wvcw1U7cw_rV$bOpP_X=m2tWUQx?9&zqMJ!oP*th%#=Cx%L_ z{uUC-H1(LQJXyY5rgyCt|R)uZh+Xshs-SNrsbDpH|v;&@p@f7bCwC; z!$(+itPlAj75nsbtRK%(qMY>$0Q&3NIZFW-3$6cYLYrrs`pk;cs@7uHp8Y=fW-;2E z#-%YUM!G8Py%z6kzck(1u+6k1vtqMD$qfDTqh>Wldy&g?m=zlbD(z&&ebmk4)7v{t z?dWW%xqL7~Up1Rv4x%vD@A2yl{V0;cPQqovK*CqTF~Uj0F&gwQXT@TCbhl_Rv(oaK z0sVV}(&QyJ)m{3#B;S0yQI|#2<;NuJR#*NO=%&7#DgjUqMAD`9uIJq zwolsLf=as~aB?zp=90C`SS5IqU|ApSTmCj-&V05;Y46vdjy$_`F@tAJJLb$L3kKr? zAw$sGLw{yb`-_qis{|DnD(&RVi`32C(lhdpp6qORwtNz+1giJw2goUm@pZq=D#1&V z!d=32!cW3x!a%}U!a$lz@H#6NgYi*a>Iv_K^oa(2wgk;Tt@oauY~`!RR=R;sV= zH-&TZ&7S|$q?ZT>r6*VfBdnMAT~el2{SK=H>#jLV#kO@}`OZ19)n$;Ko-&qIg8m15 zSial*nZfeik+;9@_bngt{d$|>|A@N^s4CX3jmpS~Ngws9fFc%Yz%e*u0v0G(fPkG? z7+4sn*e!NqViyJq*n*-M7}ywyg&pL-_nvu&`ObIm{r+8KoX}_gvR~)~!vPL0aDov4`}G`VLeYGFEWl)A zab9$S@qo?xZVy=^3k9 zFL;hlfKc&JM1;mCWhX#bSSN@tv#PkA0Gpw`UwtYrGLf7B!{X2UbR6)5P&|=GPeCh) z(rG?~@}*Pfz=NO6x%l*ZA=!TBg1Y1|Qszeg*W?8J*SjNd`UhbdDU*|?&pSA>(eh3f zf@R&_q|8CLev=d2Iu%q8r}y!mPs(g~TbvHcjEB`s3d(6bbGx}PBV|50fvi0>e-*;G zyUV1K6FdgU)Wt-{^u%Pw1jK~J1f+0+r$wjfZ}O2% zz2L4?U)3iF`$$gUxFL59hKK#ApG09b|H#CGn)dV&Il+h;7TnD#D~a!^?hlFYNW!0waL_iHN22{5cU z;g4|VdOU!-iiZOT#lxwscsOvSxdo?gbfivh7+kw+`<=o2dadjOf7n97)dn68*&n39-c6s3Q^C>G0d7~miV4zu0I>Q_xV@F=^HAPBfjJ3Oi9ChEB}{N`fC%)Jwm=+ zO08Rl`H!XP!1qvCjW*va-7J%((jNw4|Zo0BG0aQK0xzXo7(LFumrSc31@f};8SI)G1_i1T9U?*%-nO_Q6qM&?lI?+4tW z^Ytl+q4etk#1C#Nlshr zNtwaM;&f0Z2di;7q-z%T)m->geFr&#tUWca2Vva4-Y>`rDgb2aVxnVuVlra_V!~nq zQaC}yqF9WN$`}^&!6K|GIzikE>lX*^opkweY3J+C0dSM5FNMEJPLS2+x9&j*H{AN8 zq6dbdX-CASIld$(*cbyQ=VD2G+qQm4eEWCGBPUp5zK-~w+{cahe%Vo+KDKlW@qM=Q zz8B~OS@mbpi5UO4j^&W=R_PAJ_ofEobl^J@R-?`LVEYZXB`4SpVdT3_7CFIAfO1sB z{|EHq_bQ{%2>`fhcIr3joZuaRD<(B}{b=?bogf8Zc7YQhT)*y5MT+M0_W@Q97w1JM zcmR0W^U8-x{mvpMNCkYd|EB?n!3jD5#1C#NI01f@Uv(5hP&_A?fKGr>aX1Uz|BG(wPEz_8*bK!oCZ=)nn+h#~RlU^SM$#X}1&*m}xb zo!jO@^x`ih#b5f@sr3EJe4mEXHR0YQ#ktb-)|tj_R-d;J+OE4uQgpr=j01!On_CN; z;q=nwT}X;a(sYnwJy?y-TK{(8l`VuLZ4OiE%VJaWHW-FKz1LLwjQ}z^F_kd^FwB(di@J-dbB z+~_eKD6Hl^bu6iAkKa(~e=cLmrEY9Ze0z=XNW@ZBZL-S6n*6!E!F1%?XhInAy=S91 zeeZzBt&!J8C*M5Be6z+?=y>a@&n4np_ph5vu@kUYnht#bfz@d9J^#XwyHe@rU>N>< zV(;KNK^=WdPL68$5=!XB^GcY_y8*QQ=uG!NKqtT*V9#30MCX4Uy#h@tcs!DiwIHx)`Bzly@% ziJbt1Ut#o0rJlF2^b4Z!Opq{whd#@tkI}-G{-Kc@i@Wr(8QS}mKeg0CDt!!#FWX#* zodAS%s$@8HladH3e)a2FTXLVGhdY}5F&9Qp8%R>TInIEtLhJAARu89d%U?`V941YV z3*|oT&9D%YAPlzwNiX>;CD>1%pgaufbEA-;7^#}VJ< z+IFJSpFU&(@twILMlAg{;`H|CZhk~w&%LNeeCy~&QR#a*)Ov%{Z`zM0zUN5Ofo~63 zjW*v`mOI>+O1}q$k?&>qsPqE>%25p;sDxhpNF~hX`CgXX%>yIo{s$<1eSlv_Z^-Xw z@D)qHBEYrm0=WAFDE(DE zEIIt(rb6lCSH)BR5Q=BK=p-OQ@tGhOu=Eigbs5eM{Sg+n^w&6SD(=$9W@ztM+e7xX zq|(Q*qW_OjyiJl$0wPq5|3|18|1*4?B^OvP{B=2V3!&W16jJ78A8&GkA?qGJ!RbGy zUnXS+Nz)sCt+6$-lBJNeM<8X|p7O#m1VZz^W7p#J6yqtR%pKBnP-ZBsCO7SVWm@JHSC+9+~@8UrdkMZWj${Y-p+N))GuT7TSvyteh8_zd&+yE)PE z*0%<`h;P%OD&o7AyEq;AUJa|!=G(1Q=ZBILY=kiKed`lB!480O6#D;4=*1sb!ff7g zmnG+C|fvnEdVa*-`|>|`Fu-&!N%ge=mf0+m#tXB z=6LQ;asoHN3F(!89RmzbaAAifhacQja02|QcwH<)#XFJ^PNTyE8taGf)k4_`5Ej-6 z27fDdC%|TC@7KG74%U{O0K6JDmRDvL$Knnlv4>Hw9Kx zzLrgwO^YprG8Jx9t;_0C^Rpq0JGAvjs`a%1nSPk8m|~cam_(R#m_!t{zP>0H1LJ>S zF{KQ@)x=sKyX*Hu594DlE4N*1{qDRT*7{xu-<4{8e_8)87_OF_?@wVhf9{>wG*u?m z`r_}F-0YDPiEp1(i-~WWPRpp)``%wcd~esUIR`uNPdbXzeVq)6Z=(;%Pw4>R+HtCN z=gkdVk#C(Q7nflEENMFMy#-dI&G+KO&X1&8KLugryTP2B*x`={C`aKH1xg67C{RM^ z@c*#n_T9@Yg>*ozcK}$P+ty%^%V(^0Pk_@3YP~DK>WSezMf3R{0C(RP=fzs@1-MtK z?&Yps|3S6x4|x5!v`2}6q1KbXS#tQnO@&&=ucDGqVuv50e2F`hpyFPCjDAj)YaL;s zYyJ4<;{MggW@zu%iY8_2O0|w*#j!p@7!S2Ea~ITl5;3H>xo43SG1?j?f}aN5ps zn^^j5u2JbvGprGd(_J1mASrHrqVwHkjaUuj0uS8iYbOEi77@= z`msf^7$4PjSj^*ZH>^-_SC*phe#luwkb1!rxzVokiCBFMe(?^{fNqlEG zIS}7#f*t4pD`3HE;ycrKEb;wEnhty?z-qMl_W0T8iB$S`A&h)`f2Y!a3{Z~3n*@~5 zi_cU-c+Y$5np~M7qv#F?DE$!ty;?^^y50DMr9TPa+Je##1$g=9?!FYw=feQLm*&ON zpAERnnmqmdz2B+y=L0tVJ^Wc7U?}}kux9+=rb6lCSH&Bg5&o=$VO45t66^Z1!DJ36qQ>pS>23E- zmZO@Fg)na4>hEL@cK|ZMFAG37B$F|9F8Da;|IC>8^^|HEROS}d_fbGW;~KJ$0^ zBQ9+M{Jwhm!HueL`#*%Oq;h!EvTVse5H5544DXF$HJ>_1Y})XjWDeJs*5v$-HY2_h z;@w2P^OMOOg5CJ{$ai1!>BRR@X?o+ycZu&)^VdGX{j;w94l;+1m9`S!KC|nHd`r`T z@5itjZN5EElzb+cLmGsU?~;SAV!t34pd8ikI?EK$i?67JS(@~d`b$3pW16iVR(n?69C&AnbNYHVcG>HH$U1+ZDH2P&2gZ%H-HkJL%8_!-_)_ zgo@4xLZlM^;H<>2?3&!V=FMBxxMv~McfGdF{T-a)3Rmq$NnO$PZI06;`knhSV5gyA zy`m{u!C2jt+~b!m1^4hKM={@UL2I&tE!V&O!s$Co{rZFXVET$NyB(MUjqF9WNsv#`q zywl7;w1RP$yYxmY*g3_+xNSqYCDvEf2*T&I!fik3i(xfyP_q^_Ek2j5AiqH^u3kqI z;(N}gvXRK&megpnf+jy^5Z~=iydb`-ym>%Yz!@JPzMmZ5cm(rHKYeiw_m9EZD!-BM zuj`_S@4*?Rm=#pAsr6rc5BKSgFD}Ac6DmU(`5x9f0ec@70Ocq=cR&ffct<77(yRvf zH@%Pld>N~agROm&f9rkhfu%V9rL%rWsnU3E;{d>kbv9NyxTy*DK8^s?Oj(*l(LDY* zz+=^}JUoEWeEt-`;Sbs`#3=SYVgTnPojHbK?0v)mUg!KMmg3O+I0yLkg*Q`ac6gcr z>;n8C0nq!vuZrFWLh*<6DPG(}C_mFXjNovi5$u2mqlGmT=QZxdZ7A3b?dp7B=j9;v zJ}}&<;ZYaIf|s-6Bt`E7;Yd0zq?fZIlzSh}fhO&1ali5%%Gda8A(S;6<9SoRlF<8j zE1i1#`o)*pvq=x9SGb=vs?r&_i*|f9J)C~~O5)Yy&n<-$SxtLl{{HybvN-+eD5ncJ z{q*UG5X{eL;s52e&Ic;P=13^}`nzw~8?($XnTv$CG_Hbl`u3dU@4lktsdX{ z(Hozi0Q}Zu*h{lpZO~)V0O~o98BftX{uRI`=3kFcG@pM9aL?xjP8daxc@H>fK(DhH zMvut^ys4d^KgGdgJ_C;H{CpwJZop5ORExt85&#~9U*$)nhY%Fc7J|ow5!}#6HWf@R zw5jNKDsEH3W@yXfVy;C)$y6|0LPtk)?Rq(O76m6MIxYw=;XSC!z*LfmCB-?_`fF-& zUA7I4++NC3_?=hseV9!p!D^%K`%@kI#J8}q*o4z_WBtosdTJ=7q*?yL=?#XK3TXD- zQiwR+|10LtF_`xqr>lOP>V?zSPl`9he8(QUbWX!`FqIatn!bZS^sV2)QuuSA@6=jz z3wA6W^2U*Zjum`@Nt0Bd=j;HHdGUfV>|#eU1JT;(Nii z$;9{l?SGY&`1Xa>X!AYyq&L272~DLRgpu#`8j09(846I2YWU$w=*3S_!Ys`TfPZT$ zj>^*}jV#< zPWPB?egpGMT}WDk)4^jV!fLFuH-D|)(^5FQOiz95xPc(68XnmIVcg{zrO9I=05Zif zAu^3I=`m3;u`v-bae>FIEsDkXsCL0(4){MG^1jRWxF`dU4nbQ=#`i9*JEftY4tmTU z2=9}^JEidaLpLW=Sj~?rZ$(Xu<;i3EnpttLUOgnf)oY#;-;--}3PzqBD^<2dzFYTf zPJHvN#xKR`=k|>uzF#d3BfeK$7!-=rD?T_(e1GzMmV|sad$V-C#CI^PMw{=N?W6In zPUta{AdGxhcP5XS0Z@)=_%J2(;+HF7mgWz@zwsD*+a{8!be{+(VjXSO|9Ws#R%OLS zy)4=309-HzkEsOE^Jd=-nG?OxV~hdb-J95*qItY2!C^Bfn$K4OI3&Z$2BYXPe*qq5 z;j;$A=rQJiw;ul3gyP^a7J!p-`%b0V4fy@0Rvdni0Pq<6syH}8=ubb<cKq#-Y-jUh&o6g+IsXJ3d=PR_s*;N#a@lhRz z#Y~U2>+!zJt2kTBF5YjC>BVolHgCv2eYlGm-UtEVsZ!Wl3co&GdMJgVX})692A3nt z2^(O={cKy8`1b7bocQh*wyPoX^r!DG;@j7tIq`jK=cdj${Z9Gw#P^y(^@;DM4u_m@ z`n`Gr@x9$TocMm=y{oIl_bOP8Hs4-#Iec+9TFxd2Bj5g>WH~zk%25r!O9^2_m=b35 z>Va0AS@PwMl36qdSU<^blVld10Y(Q_U}oU~@MXPqvm~?d2H1V!0$XMl-2t~P;kS;N zg%98o)$TYkv+x7_)c^8y$t-U5x8m@Fn+|4yUlpfj5qd6K4UdAPQ?m%gXGPOkQG}Tt zMzS+02n%Z#$@#@@7T65!{ru{;t}~g%Ibulcqru?NB!Y_3plfGZag#bUyuYKGrBKf9 z0=Mv9C1LXHRI2@{gAd=v>1LVLYbS*p3FoaxbwF+PFuK0Hd4-ySciRf(FuzZi162Dy z_U#wr^gwQC1I)kjt+j`w#l5ha)v2o04F*^WkMxpPH?T7lWVOL#OCXFpv_%D~{i^_( zo|w#-f|#(FWSEqgM3{7-_7jU@F+Qq?u$bvb-P>X9$E7)U!`iQw9+iGN817q!`$8c+ zRSKV!!sVu^-%?o3$L$fDW>|@8fA>)<&UvT_@$H}ci1<$L)4dV$6zhJI_#SrFiTJkF z{m==gn>rpKzC$AKltsRiZ0b4V^bH1siSOC{?1=A1$#GpIzE8qxwE3QA)*9a*g|+`2 z!pOJbuxofo^A?~S)$s3>(2M`0gjpK@WB<_IfD64rcEJtIsk_n8wuuD){z~vDSjx9c zHTw5UD2LsRF#v-tOrGXX>yF)x5P;(@OVK=j62JzjjtLaa=cfVW@^81pd9k}O1F)ww zGj=y-0}f|#=x)pb{QaRcy8)kb#EQcY5&#Z@Ulr#`SVTvM90Z{_aDtvOhp_58*+CE% z)yqNw7u$+2WB zZryxC(tM-+-FP>117TD7(Qrp&_jvQ6*Gcm&gAUi3cgsk4?d?@YXL|Sekgj`4^PRmq zRlxjnQhuJp0Mfj#(H>jOuij0}hyKMySk0d-6Y`kDC*0S)4KWmCRjc`H5XN1eZa^OM z0w7Zy6C%?XlO7Wl6B`o|6Bl^Q%c59}kLoKd=KJ?@cW1iqjE%lI#22N#x%`)&b{X)D zMPJo-2-gfwx`W{ZQrI+qWiJY=`8&VFrkyb&k2znWHaFY$=RNf9QO-fcxAW5LFsihB zeB;Y+iSN+gSBdXw_YagszWe=LOng_}Z$f3+{;C>w1ezSUQu2iRQB=YE_oFQ%_ z;OcJ38aO2C9)I-JYZCc|MLp-wt6?nkyyniM$X^&QB#{TU+A$LIS4;WJ_JxwjN0cnF z6!XKSd=U9_Sj~jWMr0~KJ3h>Qd)ZKsWvu4kLKruAnF*OnENWW5Pmej!5s|$mWHye z3ejyvVKx7wt=P1IW@IWQJZp1&@B`v|u*zsC^0z(h4h%`_9)BQK=MI`p$b%8YcUa@u z`p9>B)6vBDjb)>V@AFdr!Z~Y+?J=~A0BEU*JtfPrIkV5ADzK_1@;;F0T^n^OII1Dy5H+lJMD zcff6>Y^;ADz#my0>faCWTsAvg@Aat7;Rm-B>L0%%WqIKylYUHbZ;I{-w5SPW2x}3@Of$Vm2=h$isscgo=Zfyy3uKbP8#4q0!TG zgU%QT<9C_U58Sm9c~tuw?x@pt2N?@i9#8a8i@KpBNQ++=HoJoP%cT6Mgb31NiB7B2 zG2cVV2Q3-|)#g_ERifIj;K6A60W$%#p66nhbH;5!>|a1FHSjbKB1uTN!S)_Eot+_~N%M%`nW2>hgNe zMHE)^Wmbw!t5lV0zrv>4TtD?0;@i9VH{v_1j0SEC>K?x+)QoDse@cF)s z(T(`tF|Q2qZK5yc4{vvf_&)AFfcU;6eUTcP&xt733FLh)%f^xKb6F?bB&lv#4^BP?v~&mCk{ z+_jI*(B83A{6@5pY9GUjYp?~7hLs{jD)A4j0HI=7X_c7T-1KdyNSdEN@2%~xZz!Z+ z+D=vwm2OPZ)H$r@x;e&Jcvx{PSwX+y1USA_Y7N44L3}M{9*ME@}bO6ZY#Z<@i#jJn{iV2MghzSddOWG0ge6UE z+Ue?K1(qLbbKLZ;#CMCVIO01XU?*8YEqxo}yYuO)#CMlHyQ&aZ2dL&sM^0 zUgu+Nu6BVHlma+7vDz!i3iJW)jI0OG&H!h~=PLrtoRnk7tiS+pS1B8lC*YU^BFL ztc&|b7qWtL#L$*1c28=RhF4c45R}g=I0rT;W6eF%-%R4O9JgwoPfvISa;F;92hCbp zkHpuo@s~a8%a{l@V-2a;V{SW<_qiQ?dI3WCCKkVhUo#&LqR6#3aI`1I6CEC>GMnHH)*v~T9m^oek0`r-@9Qo+I%0+TZZqs!eT!JVdUFt9TodYfO1sBpH@OIK0yhy`5w)z z;ieGz6o3!F48J8XvV(s2`v9DpKjNNL?1KO6eCGzmUF_Hl?H$|8 z@{C3*b_|Pm*}&`koCCY}u;zx|olR=n`o}VT5De#@v1KJycNq%}sqN^gP`y1pOoR`) z$4X=Bc_T=k5#P^Nj>q zPf!97#yzO6Mb$kAAX5wz5|a$8Zl)2Y9i|DU6{zmHMX?wk)hbwwOZpeH^QPNkJ=5~3 zy5nhntIq=BdxVtVD)J-o%~ee=i+sP5@`3MB zuo`W?x7tm_cUNI`PlPb?y@J1tKjkw3%25qJQwhEJWlEUM>&>&~niN#GKES>^Kfss@ zs%}GoW)oLGkgD4hVECARj;y*>fIX#btnR-6C$czHcXhzoA=2yy{K0T*4nMf9P~G@d zaYhfJcs`tZ^#~Qus6lvRgk0SS3tQd0&)F4sbz?KMckD`o>w?s)$FNu-v+(g$2okdio)7ox&wY`UImdBo2aX}5BhE>yg12GxAMb|uB1ixKjVh%-eDp%c;iF0KY3qi z(qhcgQJpaVo0NY&=sjuihUfJl%y*OWL5o{qHP0`VrrK}QaCxd;Cu2cYo0^Y;Fz(-% z)>QlP0GXbc%$T59?K1^2WiiDtB|+_%^l>-gge4%gm&4}P3F^&-9(cd1W&&-fTa zwLhZ8AmV$gK{)Y!y@~;1s;I=~T<5$H~X%H%I z2SYd^b~AKh>1;m2if858M_Aa}4-B&}?%Ky@Xz$p|9yeM_wU1%N5j{frR*fX$PjM!H z_cv?qWWye$#YF?gZCc#QNO)3uB-MWTS_4RnTdZ!y-uwo&UrLW^e@%8KX>nWg<=Zg- zqm=*geJ<60bk4`~nBP{)2Q8k4)lA!`OSRwH^|77ZdSgLW8@!7i!nl7eenEkB5$*$I zdSWtTf?~DL6vULp6vLDRwg0dv7UQEzhs9Lb_H5AP)>~rlG}uqIe>;9PH?uiBY0+2p z4#K;~CJ)7MW2q+8Zl}voSk0fQQiq!M^EcK0zFKv-+dEqm-%Ga4Cce`RD#BAhyT^Y! z6heGQ2EHJ^oht02qo^Yz9uwb3pA93ve@XdwLJX+(uWr6Ve0xgyz;_(1Mw{;m9<}fV zH(2{uA&h+MtEu*r0m@Mge_IK?_%tQV=6hS!;o20`ejvbE`eR{m1J(W@fKfA+KbC5L z7{KY_3mUQ74+1=1%EsCs4LF*`q4viBUcqLE7gW@&!{G1;9D$eF16h}PMXaR)x zBS*E+zfa?h5UR?KVZC~Ug|7X!4#i#j)Ml+hYFYk5E2;J|tT>a8P&7+8o0mlVDbC~{ zZCQuY-`kS3n6qaB7rN9)7`pN<)qefs<4KE^hTgG?YiTO9sTR#)pa0#MRMMh(M(;A1 zA0p+Kom!E!*l5qGx|r`P<%1S4z-mq$DoM3}$n!=-^$a-MRG`H~2;=^}mPNJy3?S1J zlNl2ft9_;*rYxoyrX;BS7e%ocA5|tSW>EbREj!)c6q^{IOSK={C}v65rtly}U)2`~ zPinQN9fp}v)mvI;C56@ey}@GBw&YOlUm8<~n`mQ4e4i;5PJDY9_*3o2IL;%!Z(T?u zzU!^iQ0@EtxI%ny-l8VH{iXa3Sr)|ivA|Wtw;<&M-}hiO+I+t&pTTPX8HAB<*Dh51 z=>X-ZhR;w!FaDPjX7l5M>u~M`wLbwMziSH&I-uGQ1z0J2fH;l_9!mqT<=`;58%4Z| zKO1n)PB9y6e;(jq7Khqj05~^GnjKzA0jtIjZY$J2epU4O5gxlb9)9Yn&yP?sFd1Q^ zUUKatENt!D>p2#8?PD{vcWlX_ds|CK^cWU@+3Au!LeVVY8NSYe_m|Y+-nO?P@m0D} zf8dO#M#8nR4%F$a=NV4ovsxTJ=ll{=;ez>aD)t1!%Ot*UL!S=8{0CBgS(Q17kFVc! zKIT7=@KfvEO|=N(`?K#0>R7#< zdyM$rq;rP&);%QVf7t3kd>@TBBffS0#C+h}^xS{*J$-K^zP}28=&M5*`JP~U4iE6H z0m@MgUsnmecqb*y=8ppOC@A)5fU$F8U@!m`dknyQ`e1v!K@zZMhp+|`Cm^ME|=jsvq?vjfg zVPT8?kUd}A#g5I;E~IBR;ccWJdJHQ%`3OZjq;bXw6=MKZPwQ}ve^n+e>P|7cu(W}( z&?cq+NlYSLnr=D{y-JuwwZ)`pvp;D_Ec?uht9Ut{fM%_}&UlX6)7xRTi6E;DUc(My+`sP*K!J1-+yF8?F_|$zvD#+}V#;EQ zVM>D9Z(kIP@lo}F#l(N9{5BwFeXLEbB~<%=EsEL{Eo84UHjM! z?HxOLYmc^4?PFNc$ww$Yd!8OZjS#8CKj`xpB=5#`te{;{ zEXGIG4Hok@rhLGn4(npCS=}Wo@ZYKF9%Gt`R?q{&`cct+G2BrqkrwGqdQ%t%$-$i! z*t8+X$O`Ox*X6pr`jvts^eU@H65j!%9pFiz-Q!nYI8J=qJxCO8Mg!bSAz}>wgVEzFSNAz;|m{jW*xDt~tyK+CvyOD&iYiffqnIs^PmSp%*_$ z39~e}0sieBj#|Tk*|X^W{+5H+u#`iO4|T_9>cA}r82}$myaQJm!BBGfOn`S;G>`uR zuws*r;s~L9{wKgjQ*2#vUK|db4>(zx8U01qzb@B{#lc@VzyGXh^HTR!?j=M@ktx*JU?PY(*Y(d+0IJyxxi` zX34|Ngq=P2QFmjM*AmfVxHo?=|BaM?)Ugw3e)*-ARWSdglnDK6~$tFR8wFv9`0cu-dtH3 zdwG&^SCn>O?W0FKE&PZc6AIx39~fm0ROkg6g+Y2?>*)Z zEM<)Iy+C}X4tPv9z#dLEaNdJFro=vAiAD4HQUF_)?ZZ5V2Y70eZC9KZJw_jJM`>pC zmYepTGogb;^87$2aM6$lk?(nWZ5nd~tL3+pjG z7aJD0$6zzG)ly>V1LiRp79TH#l#$2aB*k6S2PE;G7+9;By;h8nbnBP^(uQhHk zNwe;h@1HUMkCYG641?8FFDY8V{&QFT?WULtviQ{edg!t}nSdaM5_FYd`HJlFh zCBA?34JEz@OZkh_#u4A;Yo-$475&6~;JYfUMw{;lr}NAT{(>;_9l4yWpgKS~s^M!W zp%-tdgjt$)0RMOIqu^O|f8YD)1WQ>tcw@?Qc=#6dJ~{&|`6L7Hv&ADEPk;$5nn&>7 zX>(>MT_Kve-600&#omV(;NOqMnbAyJHyCE61591Aw2tV44Wk)y&3u`Eq42_H1P_P-=YO&C3*&S@ zt6`5x^QES3-;k1RCUig6kAD6R>4=(NdGmKD<~Ne^^%{zr-?zkjGv<$!@;T9V$Ari<#-ztY#l*%$#KZ+2QzVOlSNp)$ zBnIxRoz!x6tm~5VNhs};2aoRgt9}N0OcaEtzp6oD7b!eI|GOAg^QRYxO*6Pa9^<;I z9=A8-40+5YZ!hBe;oChlI@P^?2J!vG_#pAkl?|pF9~KGS$YUlYJ|n(gO8ND^%^;6i zKEE09U0uotzB|HdwE6y&<_^1+x*Hx4M!ug!k;ilaC`UDXS0(h~dnjR+W){HzkH@e_ z)BU~2EP$o7`>ONq9XxysJZ2%lb=il}YSCkM102VqdHf!LudfYZS7`PE{N?g18Rtch z*#~&JG&6e40l?N8DGnZkIF`+Bz~`>4$KeMF0FS}1_`VD1sG!Fn6i*1;K#xJVU^osh zK7t;Du*MYGV-ObBW3JvQc8|ekXshMH#yiYoFf2ZY4k@D}9GoO_HXlc2A`~xaU&4M2 zLix?>&Vjp*)Zq%e-oi);tRO4*FC=5nYX0*?psGyd}5*!e*LLi4$suC zz2!}s|JHr$7tD8;@|(;OHDA^&*8uaYWr_Kq`Tek($d|v#V=kT6o!PxOvNwNiSNe8U&1NW z?(y8C@5HzD;Yq~zyI1wgBi|WE+=%bpi{}yFEu{SPZHvfb;yb@4z71ZB`M`H4SdBK{ zgB~Qx9s^Q++w93qYdC_BL08Wr*Mvn;t?2t?G zI0x_;#J^uivm5aG0P%wafXCohxgbIaig#>5xr7oFdpU>DV=&n!QT7;wh4q-h$7>XK zKL(qjtrqjT!`!8Q42H$$&>>~yF*r%_Vq%1?$eB-}#~@VnW1i^L=T=6Gnm28&%3nL$ zMDVRTKn2CPY*WQ;XKRx0NdJKkL!&*}KloYOTqmCF>^W&_= zrVU6WkD207pX;RAP9F2&iUsklTXi(@Dm<*Fa~H1?>CT->d|$sY8uvrIon8y_nAd^B ziEkq*Kj!rs@|axntHihMO)($%o&l@T=6l71Hqc$7e#}e=Bj0}4$zx^#l%pE{KcE*s zR~gOb&jM6={H`XsLoC2+%{w!9NC4PhjG{Xv0xV(M;sNzf^7(53>l=Un%-kUfaGW$V zy2A~?6T~>V!%e`uZKT-^cr`%$;HHB+;8#Tt1feMO1at?4ilZD#R*hpvIS32u4)M=k zo9N-TG#uotnV_Q+vcdS83;gd~rs_)kKmK$6di+0G`d>&{o`_gy!HBVcrd7U-v*I7i zXL0TM4oUM(pJL;N>lw94T(12m6*fbAKhJHPExJP#aiAC@g4u3(6517>rjk3dZsidX?EP( z?lk6Clky)Q6{XpK*tS&650&ykn%`kHU8agw(6Gk?H<$aSf-F8Y{}aMUO4I9P1vvnj zyqM~kpqS2>f|#)ZM2B^J}Tt{-fLyJOSbd8vurYU*$U+LI{dKgxAp!Fe(n3fH$0m5ga{GHUx|o z)({SPXB4*~U^BG$cEc%Q?WOJlhQ;T|A!XEED4=C79+DswJ5}-M5eP*GiO|6Lc8853 z+1qYXbv6aas*~+RR-Fv9>SVi-RVTwxoz043F+M5*7UST3@kIG*dCj49O()viYVNpx z*0Yhe{aZkFVi;Sk{EI)?@#apiS9p77wToi7`z@-@(l_dJw;wO2>b$(CJXNP>%>gD@ zoe_VTP<1{XGK8x0&FG5sLw#(!HC5*o(`rTEGa%!lfPfw=#* zzrK0YhI7^QLu~|M+}`GUs5(^u<*0_Qt%UFbFD1<8LjZhXbt}KLw zt*qZyJ`{IlVKcNVYwrc!4pL=d7|9a6dTA0oG3WoNzR5 zJjygs3G?}W00%$R@9i>jD#>)90)tGKRc*lG2iFKP#jm2p!%(*ng7jd&{&!HO7^U9N zi_`c6fbek1@vKLPu&^?n-t2R6%M_cTEmOa4(?pq`qeg$lO6>`q43(rB-`LS%{{pLZD z<=dZ*9fl&DA#FQKf&KmI_4M4!FK~5R&6f%kn^yY)iO^!G2-n+z2o3n-LmF`S!5KkE z_*FDC(h)*<4k8S9A{`;5SN)EUMI9kb@sxFhu&_G%oK?&^ilSC2&QxNn#5?S-pl%R~ zT`Rca3PT>lMe0%?61iaqM7a17K=|L{}Vtl+0K5>}(F z{I3N+rF$TZyLX-|>~RA;HX} zycHO_*HSSAEEd#Lb|g7q2d-sgz1}PZ6PeIwgOLoDPE6?B1RPBe6UsG zD<)|8GD5{TAB1A@?M11%r-)3pdO{Y}7a+4JwuhKSG0ZHA?IUJU41+}tEQ-bWsK&rz zHk6M1Em>6QXFLNWiyA9!J1T+w^`BSwzGP8RIbzd(KBcmmTiQl0n@ds;)cYUG zChZ@}Ch#B1rfEUhM8Ima%jQc#*&K&3Zfn`tlUO!q0LoDfAFG63e4-L&^NxBpocEHa zPo%POQo?+`Il%6jcgC}_X{EqWHlH{f4nMeZuw?uyKGWkU{G{u*i$I)#ClR`J}>TXzwW>RyR?^f#PNw%w7X; zFo{pRh0nl4h*aVqR24#bsF|97KU$0$zM`rsF{YrZ*bZb>#W1TXwhLKRF$`6uTNI0d z2T;Reo^AKdm8wb~e~or|-WVWNRYeGk?JD?JWjF7MR8>#bh~dkxsj9AS`|qmi@eft? z^dG9K|36e!lY**Bfz@d5tIUF`dI(|M+8XPrs-6LqqZYoyKp<7}nl zzdqBxCoE(B-nUy{nO(z6qrM2e^Hxj4F9HEtM^O|ne)I+C_OV?wUO$F0qXPks&Rf0k zHOz~bMh63~*i)Pt&us<)u8>P{y7(~y@a0Ttb_3o8T7w^KKGZdS-2gYhju{MtxIzeu zcg0a%V^nby3&Oy8a$O@VY+YCCalN?f8k?c5m0ql_HD1 z-x}Tv&kXiFEuH~^J#s5~qtQM`m{C^zAx$(cf zHNyjzQ7@%d%qz3^=rCRY_5HS|N)FQ<;H|q9MThADaOw9CG_n~S#s}cLJ;^_CUUV2= zz&_H<=rI0(mx*z5m;k_A*z5-U5NHj4u=(IH_*MR?3n4g;#z)dQUyRDb3c@Hl`@ZZj z7%i;B*k8X{+zx}y(AG-N0*ApcoE29(3{DacUZ>;L6ojIsB%#9~6is_8UU98l!It~W zeF|nqaHsWdyv7j!e6Hv)eQ(&?+gDKutA<^sD}#BJ>d-ZY4wGLQVE#-g z|Geh`y2jAInc#@|bEJH5m^!eU^%Wi|B0iAAd~mVlQtr+mz7MLO6W?D~5U=sIb1mtb&ecE7i0|=LX+H=j zHdG-&>`8{!$F_oqX4d_#P10C~`MzX94x^*7<>aV_ zFQJ59yuK1<^ML?AI*hp>xkF!oCzlwAkKD}V2LX&{(L8=Iz&&kza;3o+!vH=qa!6zD zFdT4-G&8!xNWh0!9EN6%0=$pSZop55&BhOII=BOVl~2or5R{)W7fMj{jx%^Xj>+q+ zLfCNy!os?PurRr}-2t1Sy`Ot9cZi}!%lE7#5mY>lr>UPUXIFA2Y0<3mOvm-`*w!|I zz36RF)9ckFE!sbP()BT~61wiKL~rXdNEEeL z2~_(g-S-pUPo;d|+Xz;p&3D@|ZD4@*K)hc~1!3g-sG4fO8bCP;H>oJ07hhKivs#P> z_`gP5IM_CF{|G3qvgOk5iHhI!sOD~0wTZB3({#Go-s+jC_!H}=U7h>ROgJ8y zOSfxX+$1Xgp#9rDm_Jj>=XZ&Uzxug#BIX~K@Js0-C!5mk zg*h2cC?CzHd}tkHz{{!7XSzFWa+wE4~s zT*4ft9fXnZtzF1rIs%lV8orYfdhxxKFsnr*!2jhij0!U>UVT4p+_mq$7aC zoCbJgVR`nLkFx-)vS=P32XL6_Q|2(|0bcUhR14=thq(wiMw%HN<_h4`EDjEn0C)tO z-GGlxwdL@G%?F3UuZrUrgz^(BLMbYa4IqcX=%aJ8!yqiI!7+zY)6Ob^V^nt;W2^~KWMFC`s?!W$lt~W z=j7y7tQoY@fK|^yv6)xQvR{Vw@C3#b!(Kt{BS8B6h9nR zGvS%&Fd0?OO_(##RFE~T=0`&qx4&67Im}dmOmR$zOk+%XOjJy4Ohimv;4ssQVlh6d za9GTT#Ti?F?3n6OGp=WKls1>aYs!^)fetel!XKq@4JrJ2>pT|BdWpQwrqkuiw><0XuI(8g>u=(IH_*Fce2v5-uAy}U-uD}JjFoK^ePGko? zm|R#(xw`F1aa#&DLt7l>b{ck)IxQG3sUs*Y1t%#wEePQW&G49JxEVQ#SW+Aot!rn; zLYbb|O5rJyLYX<%7icz-ngB6Yt%3>ihI;Lt9fp7O|Q?0Abw6k$Ge(X8DWvmlIo&w5Oj zG9REE)$j|H(2HNAgjp@p0sb#bX=vL}{coL?@3;(y0KL~{WzkZ80_^%EnLP?53t%%A z&Es`T)?+*@$_Lmb<6s4x7cE66#E$DB&5V{(3a~qigQe&K?!#t>VGiT%IQ(Gq z!BX(+c6@?)B;3;m!yEt}*_gTOat9b11H&8uTEHcrWgqFZ3c|Afvcn)Otiw3>eOlZO zgU!&^O6hvO%waG*WZ*!h!{8)wG};tA>55Psy+@rEgrfh@VbO_|VA=tFNb&LK_nm6C z)L1BSeric{7@cx%r1*z3`P3;b&4h1rzLDaqT4#~sUoC1JgZa7V#Qc|cM8)TJTJ{L@ zze@R__zSR_rcK0WlPw?O(f;vU6G7Irnooc*?sB7EP=@fn1At6%Oo&WlOnOXIOl(X< zOkChF4~k+jKB^b6m^LRHJH3yX?b74xf-)%Wmivru#y@+64wI$`dr09+lg=bkSj{KK zh)uiVLk_e1k{$QZr5Ex2XvR_Ed&S{;{Nq7r8F z6))Ry=cX@W?qC40&BG&j8#dl^ZvyZXi{|mB05|+~g}FmzfUSaC$?i}Eu&XpPxh8xar^y_*Hx_??H42gkpF6E_OH&dhCt7jDF~X?}4N1FY#%1-1H}+G#^adKks~d zV`1BIH?ji$nkdaL>M~KKa!dvHF^x!?eRqh`+`6L10?gke<-c2=LDD?!HF+=QyGr>W z&Fiq57k5P~SklM6O20@GK^C8yzYSsBzmxsQ3Z4UG@?xrEf?_&j3S!D)ieX9uD@ZGf z#rUY+!(syJ1>e{Ao#oO~s&!9;l`9%8rZXfT72z&Yc>U#J%P6eozn8J6rrG(E6|69_ z=k8m1krhlSf0X$Cz571#eRyUMvVw@D3dHy30T+nxQy<@x6*L-PNPPd0@>jI~Oni5; z8bN$-l=6Y^4X_$*zN@#q#H?U5gpuzf-Hzk&OC&%!s^PaQp%=eT3A0*c0Q}#b4d;Iy zL-G@rVL9s=zC8{*8(9GF^qYxK89+P91z3ee^Y}b~lZTtJfVKRf>0hn7)nq)x}n=8FzS&d zy9>fXyG#A3;&vBohPGDDeEF-hbU1@yJTroX(HW9+M9Z>|Q#6hJ>G%aRME{|eEc~>$ z=Z2(uk;K>Em}j1vVH?vnH(@x}t{R)^JuJBtriKcq?NHc$_qBvv3rD+uHEb?8T>-v}U+6H^%zkgO|7K&h`@*(aE>DM-Z;hJ2aV6R=#*9k8C4~Ez+LwaiV5#)=n*=&iSk1TD zDK;&?Kb8KCgZ7-CwHxt0tf4#c-N0xHm41lZ0OEW0x9!BYvs3vzJg{)dd`^5H{W+WX zt}EsHRLY~$Pl|p)d^eHuf$#gU8g0HC=(@AgPlYh@-JoGK_9mVJl%pE{nG$;O=}MT* z*FR*>b!@$bm3{+&_eWn~rEd?=jYac#2Y`J}-;+zf5#UrQ8-Mzp0FPJv^g9FYC*^|` zjDS_+2e%ch0KdvVTOkC+fk`0rP=fNC(!&TYh>)!S=Pk4qm>n)|E5K%G?^v6-WPfTV^K}=XoL9F(fVwjTPXMbQ(EXGGQ5*9OjS=S}}iZGXN zxipZLCUpc&QvhVVzkcZFyl;=8+)KkAe&O|LUPn)tphrn3pe)b0g%$OXA!%pxhU?{*| zESkp;2e{L`Azq@VZvSY&@1<<4{jq?@DQbTl;N4O_)P6*+J%=CMR;Ydas<@dSVPm@g z4lY}SQnY=!l5imdo);BHF#45T`a zsdUpcLeUwv;8jrHst(-V?yX6Sm#=izjWsk9Tt6PB+MhOeIBD^DcvP+Y3ns!mw`WxQ zi>f~+&CNJ6iNpLhQhpy#j;604bI%I%!=-%CVt-hTX7ghliCqX45@u9Ry( z8gMTu8*Bd*VCL3%2yhzk2`L|H|6B(L4nMf9Q2Y2*@q`3~;spgbgBVItto(;JPGIe0 z^r_=yb_js5u(e;Q)A8c2eQbvIj$O9L)q@WCqo~n}-+j!M$5W85yYW{)j584`dweG=@U*;757h6Os_*Zux>Vg;)i9r&&P@8b=bY*3>FFWYoKJ_T z7h7JlR&mG!-)fmsIc?{2n2X4auRE*@r-HSF%Dt4=DTh*irW{J80_8x;u_zU+`x(0l z^xQ_f3BNTn%c04G{f0fe$f@A>Z)u;cj5?20u$|0jbDYiwvq}YvW&}N9v%?%aQJPk~ z8>a%_Sw)PeIUKBa;dUKZ?+Wpgb1E2mEtpe5mE4C|?|XUv;8bw(=^55FVTEAUyPQ?O z?c(J8^Bl%G*88qipY$$Ehl#0ojm=+FDyTqa=pA*2Q$ZC%+v;!ru48~1pyL;FHsO}S zeN`%$OSoc62U-i1y8#ObH!5qixsdRe3yOfk;QY)Y z1`7UGN(I=|7P$aU*#9n1lL=>$3Vv95O&{Q^L3Sztx|#|GCEnuhRDfp0{9@xT8zreA zf;Et?5TEx^TYGwA&DJ7D-nHUXxo zUil;IU8dat);q(&Dy(<)_`$6AxIR&=YqrPFSnm~9{p^L(@Xt$zS7E)YS@lWp&UBcV zdgpy!nC=6&#SHEqWQN{5A91kvA+)XjX0VO{=3pJan3oCfl|H0`{VL(GZI4y3-ypoH ztkLF8!iPtEF^P-&{C9{)ShaDUf1ueZxL-UdVxZt}qu|D-OrWM!GeQ_;l@UJA!z!x) zaUUO;{FEKsKv#qN<#D$MH<}Uii!31to8AMXXtfip&eN`oy}oxBs2cLfLdkB>~ zDKAqFr2I-bkP3Ze*Ft~q&)7|%=Mmb?;7VTS=FA`H*Z*D#4*fZS2j0cod={a9l+5d9 z9Qg-k75Yy)-V?LKyp&&>7QYXN{s5n%MvqQ~S?_6~A6V}r>#nihzpov_p})p2fc0*( za6Ic>*DI1kyotwS*88wkzd&#X{(0{+6D_{EGTBmYKMLj z;?q`bgnn}30hXOYKN%eg1%DfbJ~rj7wF03J)Yj?)YF&I_!A$*C7a!byW{H5Im@fpB^}J|dKHnAx1Bx0u?~AilGbRpQcE!UPI;9mm+tj>a z>}+igJz4y4481YzZdrD=d27VkQqCAM4E6h4^@CrFv*mAiV+rb?w(66!oub237$w1- zGwv^`D|@AM+V12qFOV5u=+0mc?mL9aVU!;!7g3(0Tto%8auF@K@BNJ31bRNF-Mrlr zy-ZNMI&3d;jc!+~I%YnYEcX_M+nx0wt=Z>%o ztoID7KI#304ii)F(KDu~;C@AB=shm)1_bvQ5+r#=;Kmrmu}^Qs~H;?zar zi(v&Ka-#kktNzso;)`>iWvr;zCtv(bhv^wDu|KLy_047OrEuEb<}l;@E#GhUKRNc( z5GsFCZl*j)IhOJu75mC#lqXT2KHbmQO`vCP+Rec-bxIHK+~4ocim4p?-zv7hSN7y- z#C~2fzsu$0gjvP@wG~ruvzgX>h?J&X?9Z_u=N#!hD-Xwh?M*jWZ^x*WtoNrDV_EM` zy-Kj&RYEqh-cwpdaE#ABzm4@)^{?j1$v@vbH5Kb!*{V-^=c2>J)cf?+eJb_~k{R*T zV_EAGzlm4}@<`Naj&)$4?RKmKU5)hx zRi?T-*3pcZUu1qq4;AY$YmXWLG1;&7HhzI9P@4=0l;!Vf_LFamL@$dPi4*?Du9&#} z+@llxJe<$dI@uNLo)%ZkmFLsL(=X^YeZj8miqFr8E7l(w9I4m$nIW#&z4Ez7s9)Tw zPp+7O4inWS_H@kLDW5HIqr%fuIBjQhm^sLduX{`=hkkKFw3{5;k}T`>wx8eX0lPT#Tit!xY39>Y2>mK#Zkc=e3YgWw$NrhE4VxWi zfwW%SH2*;y`kAtM8C{}tu->N*EMUEd7yOI$etmT!hyJ6mudMg!@&{S(num9Dh!>dA zjrAU8)xWUlH~x90hR0d&Q&xS_yAT~FrrsGIJW-+VO=jrb%-o36eknrR>Tmk#7+}`W z@rxNrSb5YI75c{s|6RLWh5lK>ipm;oo+rFltF9gTSBP&~wQ<_NLEKk6?f*-B->Ofk zpmSC)0|kF8o%XS*y}}$=hdrHB0Z<;MruXE8apke`2dF+itgfa4Gh({CQvsS0^NX!? zbdgF0Fl(oMpj^Py^W~8&38ch_F7IKLVSIY(!nZ{cKQCi{yPWKr(d)alnffxhvq9!U z?3$G;Ok&sc?0J0Hg@q}dbq0j7Yc4Ldhh4DAaKE;C{k%!?^3VHJoHZQvYg_fnHLKEL ze!VEEASl_@civS}IBn;1m;q$Q-}h!Pr-F`z%Dt4=DTh*irW{J80_8x;v8Wf&`Dg5g zUSCeTX%Vq(Nc9PQ{o41s%caC;dW(>HWL%(Dlpkj1s+;$^a9dqb_)IJUA+tx{B3mF zSDUe7ajXL`(!+EKFCIXw1Gm<*V;$&ftcMJm;qF*RGh%*oZ?2t_SdZXFbLvb*=lLkc zN4fBDH$9d~b92Ue8TsCccO?oNoM6b`$(`xzWnu3+F;KiKXSwUY9SBJ2Y*u4Bdsouk z;$5reS4fEZ>8$!|D-~q#I^29=UcEkfS0EiGUCB6nVn4p_(ac}JcsOnUahNU0jBl{< zFplQlgvvvd<0zj{uA=NJnw4FP=HQ>Pn?TPn+Rfd#hm%(-72-EHiDzM=WZ`!Y3e|n3#IE>|Iht^D;6+ z@6x^;&1(s5tG~HU#{hGmj$h1@d%TPU{+T$b(O_L^!g0OYs%S1t7++bV%?gCWUY)R` z`FG;+R&7LcP2%B}ouYa7E-wQGe;b|1u_>K+y3H2CSc4YlcWmO|hBX*30>6F`!415& z$PR9xtHB-1In&+2jb_CBA|LjPUE3P0gIOYg2kU_LG7ga}iPoow)n1j#x5a=fUPi}t z;))w;e_z?FZgOX_KFQe?Qx6eWJmJy!#AYL*?26Sx#1+$5*uDz&y{-Bms}yBd z^fppQp?*oLKDpv}I?VN%68ahYwJw!b35&3@u3w>Pkrv=mwsV>4*kA;$NV0W|2RT_Cz(sM9M>FXyf_S* zVMprUj4Y&>xe?+gMmS1Bd>Uf^k^C7MB{a-Z$RP;m}|GyeaG5zVRE@ zd#JIAb-grb!++{W>?+1Tf9*`ldbhLcliu6tFfsM+ldFXa{XJxc-UVxM=pQDut^Vdw z9RtjNbo^pANbGG4t5!{gejs7u+q+fhw;&8tR$Abdu)~IUbS)v5^X;|T2>s5)9W6VB z{?&xu1`7T*3Vm#9Lw7)}4-d58MjghLKfkg=A68dGf8=+!hd!DS^NXyyBfo@x1UFi) z(CO*tNJeOf51r=m%i7T0*gW1w-|6CePZNEp+U=L*&f6X1uXYxyqr+@|BeCAQL8EKQntM2H z?{b*S$c(=)-&l_IorKDNlv^o}QI4eSD%O?9XtBQgXY3}>^91cCZBWXZzaH!DH*kG* zj`g`4k{`T#C=#)LlFYlBAFc(niuD)e+U{Yq!(3TYn)dHFj`g{Xyp1h&JUP~<@BhSl zul!Vr_3k%i0qebfNIllO`fstnQ;_VNk$yev>i2d5>m6>@Z_?PoKX16{E7z}P)hE4= z(qUrief8N873-(T483P2UW4oRON6%7-@Kw@fcZ#AT1+v}+bH`fM8*0aguMaakudg9haKzPiF;eMasA$lSc!(%?@b)Xs!y^1xS_X!g1?nwADi}FxDZBJ zs)$efu*$m*xK9sE=nPfY??6{$|K{y(?mq3K88N@ukS+DpX&+|o_B^mP5AE?#9#A{& z1MSxs`L@{DhxA(}t{JtW-N{$olR3+#en$`R)!#S&p}1zOX%ph_=#av>slf?O1-rY6 zYo<@KGbin)NtXR{16TC&`!!7$P6a{cxaQq^ z97QU~P3E-DD)V7h2mib}TO&3*%yV<4X_Y2%D%i2i+c-NuHK&5nCp)v=Lt+=_RIohu zVon9kb5CZy-<36S;b(*VGFqH6{veLSUg!89& zvQxoWtu{h`67d4dPNAQaj*No8jY1!r+9*D7RYsiU{>3OhP&@4d^N+VfALwf6do~Vo zcj%)TF~7)V6Z)&rhgloN2l6G+Q4W0|q{N4=?jIcVHp2fE-`lb=Q;MtSlR7u`e#o&t zsE+vFyO|wVtjUnVS-(qT5t zlvoeE)+t@m1IeAXcR9>xGUE^WGMQsN<)I(`qufe)jB+I9Un$Ea|lSWo>kb`$8C z1G^cUH~;eKL4Fxej^)t^Q_K9RtjQI({*i6aE_i zgo^cW!U8G7RjjWk%&M$3`=0Q_gIRX0ZzC>f)kduECjMyIDb{Pf^EOcMw^6KPQ@W^I zaCHxqi6(q^9>{C!t>Zg(!0y-VSO>Zq>mld*xI5O-jF?|!ww4Q3ti!Ag(*v{MhFxYJ zrU%-mdEXYVQWP`#mrTjNm*m{8_9K0hI?bxrIM#oiD89Gww;gqdMR_>=`aI!SZx(kI z`&h^Rk2>h}<24lDs~K9W9_p92>XYxqNmFq~{iK%z2M>kch zS0FR=-qDEuC_l40P+9%WnmPuU&2*$0w}d{=U#nQZMmRS6D;4WE35zLfw0W1X#L**m ztUuCfBi5g5c8c|Z<%$_7_}eJfv8mmX17f%&)fzsp1I4lVmK< z?pQ}NVt$c}>m5|F4zol6jpRkLV9*X9x}1lV#yyYr*+Xj^`L_7AWijLaHu1fCvs!Fy zJST~>_nOlj>#r7x?~P58_;c5R9?ruFK69)`4ievcvtqy|)bC~0Ki5foFXgmZ|EW*D z=R=1{P$(Yv;d6{LJD$vy+-ZB4!}KRJ{=S0?$oFbH>kumcQEsI?MmdtQt5{cd6>b#k zb$`Zg0zF&NZu$<*l+|l)55N48`#IK+7ydpv!RdpD_10u=($$d-W_9p0!Ig%vncj^s zQkoX>H^+L8$;FH#DU))n=l|ZC_5Sw3Jvi1Y653XOvyzU<&1!_r`&vO1 zU^djP6#9e@x1?cJXb}G@VdD(mJWNkl_qPZiC~LHNhp_pI*FQpEtIeUW*(vn9O)6%f z;7_H{$EKXb_%shZ^&x;x?R+&4lyN=|ec*%;JM@9BhJM3Df4V#L(Ttei>*rDTROrL3 zo#uh^Ds1l31MSm%6w4`#4)fjk-`5s1dN&l$%rU3xKdWLTaTbhqm@~niapIZz#}6Je zy@-c1Z_oJbnGLfpV-Fm4uhB)l{=$0VnKw3=WA*yvna$`hTZ1GMIJbUy|7?9Sr|o+V zvn`qNb?0BqnP32+awp|w%7K($DZ9!9%C3TuGQq%~v7128iL{#!cOJIwwXwTj*XLK+ z=fAEgQnvoy1IPqZ$ef_&!*(#MgE!rqqy(ECX6t{XX*ZW}CMbQgn34E$BF+RSBWkkV zj@(~Z?>tG?aVChpFpTx~o>_|Ze!gHa>z&iH7VGV6)lYb#GXFgPiMXt{s!w{?q{GD2 zyUN0}l*rqnhu@vd(0k@6&IG}Pww3P2>lk2;((#Kq@K!M+_s-%f^oJ1oWC~KDKawz) zvPPSu2}62hpbR8~_!EhXTeT7T(}??8b_)F|{}wY)@V8OuV>5_n-13|}puC6lF0ST* zvLY}KGh%*`M?S@?!}sqZSOZyPj5Swa{4y?);` zRoM61cwOcC>8<+Ydw1cRAY|cJes4JKWxWU_WAgC7ElNn3oo2 zb?{&jtoPM58#vazVmD>|8n>*- zdZ!!mH|yGE%Dey6-`%Gw|NP9Tf4F|2RiE@8L5GQ{cgIJCRjiLAGxTn9hhu#jp>6dy zr|TGCF4ysknZ1yYvD?u|#d=P{6RXy$SkI?hqs;<@uX>fSW4$PGlvNvp_&&ty8$|5; zYV|4h*B9_HQ1G`>>|@hjDI9oz3j-=t34 z+Z^UVGUNOG8qTplnNazYax>*Yij@Z`&rx>86#G+u#%=;V|EAsC9b6`OU4pKDC08b_ zh`aGGH;>5Q_h1BKe=(UCU$_whvx@zu!;a=+v%{R%Q<}DJ703Rl{ys*%E%7<_YZZIS zde<*_oAsVka5KmL{wuXvzoKnxvEII+3pmF6tvt(mtNH`qSLdH!OnvA-^-1p?beNcW zPkL5a#r{4rL+{_eaO_7C+E#z_n2rIoD6?k$VzwFJW1L?RqGG=tVb!#cRP1-vt;qkm{q_w9x;ysKjF?~Snfrd~ybtr=^lGAS=V^7pDAvGUZNRt1teHMWyjS9U zr5|mc-7kM4=cNP7+4-t=5a-*z$){^*rR2^wIrFpg-QOn8*S`6jIjDcps$Z~34R*eh zFIN1gJ~`h?I?SO024CLSFHnEi&g)5>wtLYNv}DE?+IkHK`%yyWK+3O_%P3ZM72L|M zT!(`F*w5Hapyy@U&9+mKS(5zO*>CCotQ_pi{z-7??)iNP_N!!G<54;r%@W}PlcssD<6xh2%*QwrWpJ<`@4cP%9_IXq^$s1om4iLjpT4Z0$KQ=u?@iO@v96E4 zOkur;TJ>Aht;Ii2wr9zI>XY89=rA$$ez>x^3ieH8hTeUStiVv-PD0!2Z|>GHz>L!I zi&^csk1=k^G!^VM2xpea!dL8cJs&_gR#~IX`h<<@^BRl%@O%@kHiEl_W~bnO6X|21 z;BTYg#-?_Q4yX;=1GQUpK#%oya06Wp?xWkQyF0kijF?|!^Bs-Ui5+I`79H?NRXlyf z!}dV!dLF3VonQ69#|Wi$OqOK&)%juHkn0^LCUp8_TEMQD@1VG1zA_~;KYg9d*(Y{! zcEy%a;)}TxnG`nynsrVZN2q5s6QxRLpLT-G~0({R>%g!ggQd(5%z z9QrrrmS(+=dbVP{V;`BrA-<_@J=R;*?>e~-|NPiLp2a4PC9Xnvt?{??|T@8I-uiEYoeKaFx z;C#&%q(UEN?H%esUM=u4_vwMh@kYXLi!q9Su2^v+p?5s?y(W)_`zCms!1>|sboRaA z@8WwCJNWe-Q$LyWL!C10d(Xaz@3qZZ-=WtJJR-g~YeABJdVTV}J9L<4vn1BN%V%x$ z`;x>?+q)d*6Efrb_1?^}{+&?yk8&&JG0KsYUB$Yxt8k-OkL~jlb`$8CjCOOn%z@DE zvpe{O_N&aXK4n9N#5Jq!L9Ba_xyQN}17TJNpS`ANJT^PbM@^(@54UivUvFF7C{rm8 z>peNcXx4k*)qSjYnWsBB){o3C!+P(l(vkJfo@_S9bdSk3SZ`H7`=+}5^Cc;MVZBv- z()$G+CZ^u+HjGlS{*KJh`^plI^{<4s)!&TPF~CgHPP2Y49Ypwludwe^_aQR0yI5g+n)b`MOqikD zDV@yHf8E0@N{vH7^XZO1HhKPj4!YwX##p=hU^NH;tE&m);i|gsP8euLOm9fwHAWJ~ zoWwADc?JDgLqD8#kjUb30o1TpA&g?HHnI14SaG9uAMxo}X@?Yj*CK&4TdSGu)2%b? zVxRV&?g$D#kkpy=uH=x4e&W+N##Qvv>sP!ZKAj?I^ndD;PsbWs+!!1wIb@-~XMj(N z#7^659cBVD<4c{hjdMsQLgiD+)sz=0R(9o1%C4AlNS2?mn?TP(w3{S8vs(H*Z|k?% z=QKP1;JZbSWm>-rIi!eYo@1G#heYjQGd+{PQkqt42j`Han~NL&ERMxFBs#+|*1K`) zeXRGZr@LA2qH{{IevPKL=Nz)V^Gwba$2y?)sWZ^>35Msj%&Y+9CC_yi?UM=Iivr& zhuL^jaRUX-r!EOLwMj%kxlhg$3xL}5f55)8?F<8SHNz~=)zIA;2F-}+EALbOtuhSE zCr(uRkzpcOv@X2#30;vyF>22R8|A&g3gLv5P0@oa++{ zz8tIMp5PK?b|R&8*35A%bBAqbIpEX$y*-Ln7rie|=hSiVuk-(@e|$9ib1rv?Y822<_%fxtF0I)&%->jXRgaqVmMM zGegdAM}`@ynLAkKH%pt1XS2iny^=I7YXoPQ>a~51@gu%*CYdt0CF|Y4R&1WWmdj{A(L8kwQ@ ztMZ&-_7K`ue{-LX0p=+kKbJ01=l{+yMGE@-&-a*CqkU}YnBup)X}|bWhN(eVBYmLC zFad;{m6gUw37f7zsxnMt!l+@D^W%4sVVY{cj11F~_=K`khH0h$x`#Qtmal<==2M2j zrq*czw&l-l+#dmk?K?)}1UxSSxTE+Gby);-HNz}e(#YMN7BnNKuMF@xp)w52U%!9f z1HmXQ>@6J5vS^n@s4=E9Ix$z!hXLAeoAzzdtSf0aOFX{$tfV83l{KCB7s^EZeDlQP zr=&l8q}q}s&VLea$Je~CO)K&E(iyjK{d-pZByGjxd(7!_RIg7S-<=NgHlt*i?78PG zOY}CO)AnhH8BAvU{pa^{h8ahwJWe^H@-gLl%C4ME*_CrqhMDj)b`$71hjz2~+>OGc z+Sc(~cJ7zFaP8~&_LWZBcN;RyJk7koGCyh1$%oAjv+p!%+Q@^PVYv@IsK5%|2XOeAk*Zrsd+Bc2)=TF1hvEHga={30VlQQ<>`+Yqb(%Rb&(}b~pHA5Un<*p# zp#K5XMp=Pg{Nd~XJTuJB4nSA4L!LH)?#>QqM$GRyeB-~89cbnRnYGRa(4ILF$yP{- z4<=HO)qanoZ;K(je2uG_#ZzZ4&OAK$TYP7SAW!zxBc;VtqjLOn_*3&F&g>T=*;9Al zw>-7)?*G(ZVKiY+efFu>5xqWn>Qp++^MaBYa?D+^blaMQPTLn9<{UEP?<;kfGs6Z# zQx2sZP1%)WQD)fuGj+d68EmGv5ZsZby*$F1Vbn8UquA2VoB=+i&c^z!+AohkcHVN3e_r6PORRUB9FJIU z&#qHg*9jZ9{-=J;(5C$J176)&Z&jc4o<)a=srT~4w^U|WKxXJ2lz9mTe#< zF~B^lDemL!qm(k2aA*Ei*YUeZDGP`nTfdByvY2?A*!SYL@KWNE>eoHYcO@JK z3Yt$T1)JJ3O~9AS4%3VWp6&(Irg;NX{~D$)XMnDzlon6(xjUtx88LmucWK-Jp5{F# zG0gi9UtG5ge#Z5&>#AeYQ7r7)@(R095~Y{qezl@tv)Ac*esL z4(szu01OG4makIwB+danz3_9Ve_9EE&qq5yLH(9i{VA^{018&gkstN@TlFabPS9Z% zmzIQcyg=(jzw}J#v|XHD%}!=`K;kG)I1dSx11i5%E~h+E`Iz!O|7p^xSq;&8lW)sH)( zCI7s_Z|ON4zghJu9F0r=?-$gjNh0c&x5YD9Nyv;pcUtGAxTHu;Xj}cwv^oZud35|@ zE+hOq>&dIvC;B0jR_plP+(fwM<)ohF50~Rm+MzLpQb}q)3Jy-=1K5=Jmh=4ypgeQM z4^#pJ_t>!mbTxMN-7f0x*x@$EI5Yhlon6Ha%uq)@GbD(*t`&Vi#M(o5| ze!nYC)oz#TQ?59OoqS}rT5A8-)aU9}kHZ@fJ6ST8VDrQa)HH{gE|=i&q2#q+%q@fs zUVIqTD0f9T;(i^!n@0(I^a`AvDZCmx;z^Ck5v%1aVW8l!l+&@PJ@EsSK^pc;ptkHb zuv6lpsv8J&)h{dm?d5L2L^ERM^gkXI6~ByNh2#Y!MNsxD*Uqjv>z>YUrv-Q zf02FCpHSs<^^GZ?RIGebeP_xi6_Zbv`x(0l^sG(0sqQiAU54(f;gj7*wCS^}e(yR7 zGS^B7pA4}6cGWuk-*(f$Z@YZx{Zt)n#U<0baVQoRIw%^{!kFnb1-Fi`MIgwM+${nUsO28ty;HnoTb%1Y8aUk|uxxve$ORju=6E9P#k(G2an z3@ED&()+(7Ss;jm4~6WH%1dz?8S<}4x9wxx?Sy@PDalGEF&82A4oxn&wfjP7eK1)` z1BG`L#3&1SZNaENESY$DPwo)||E)Q0de;;@E(g5(-j*Kds`RJhCUURz5!_}zMIR=u zqZsW`HitQ&fM^wwfYlscSFm>?!DfO5Z?d@OnwB(BEOD`^-EajC@W*T2ui99TYrX1k z!RtvGqgDy7tob+mIt3w$B|SDJp4hK}**TzCdZ66J66C2 z(noNsh|e?HOSXGkIIFwoJ?7n&Sjhr(;YyT`<85*1G;*r3@6_Rgj5I z&CP-GG8;Z~0=1`&fxQRVS_56xy2X1pYaPxKXvrO|lDl|(A_dB2#~Sof3T+bUBGa?D zrLPJO$jDgdp5UkVgtU&^-BJdMr8PFSxe34~{9bff$Bj^%ZVl_gR%4&E5<3!N*2k?TL1Bz;Jqx2mAnLf_sxOyU1Mi4gtEV^`(LLQpLx?z1sQu2giyPGAGq>Klwo8k$;ZI4#&qrVX<#~9gGxTCzOu*sy>-^_4eDQ@GLF-Ip6r+Ae4!bd zUjyZ4HK!DyItZl{palMEXdPHftTVH*xC4R(t7m7NFj(+>p}Ej{^&pau3U)`=oY<7? zv=^Ompj?^r9W9`|hvX>IH}GUTTY8|Y(r^3v(B0Cb8Cs_WC_O?Rx&Uf!4zw35ahSX2 ziITB%veqLH32x5CnBtUR@A)kK`IDs$6ia$+N_fqJ^gz3p63S?=eip{~X0t6lD!VHE zzP?Z0Ej^l{c|FixO(T-qta&}Gk{14g*YAHSN_NP@TF*=A$HHdH%UB?jV7g@U;PnqP z`WYye^w^wpFzdRW?H59Npq*ht8K2VHv%{XOhu6bu#v7>;4$xKUZ@z!wZt2kst-lDA zcWlt30QCNf5~9_ae5~fymV(0yFplaZ7%w-A>p_TOiHlA7Qa3?dpj_Wa;Sv;RC!8?G zB6VzWVRcnp-z_iQE$$BqhT_fQK)D3nfy;fM^pWR5>xUynI!7TE_x@VJXN4ITY!`gt z$6D7VM6tBSrVQFFg4RHJf`jsPD5F?6!jWMOT3~ApbXDt#yrYEA?6H281Y<*4UJLwHu%{P#l@wN)xIfok+tN zdp)W8z{D_5B5AK83s2pBuluFP*SG9KbI_hq% z(G2a}2*kS#16%Wz4$uyKhgmd8r0d~eam&vV%vqAL1=8!_C`8 zh?18}vDU*M3Xbz*%=lWcS~N?)?UlcQVo8rpIWCQ=hnPS)&}q0i(7pr>V?2M!mL67D zr4Q+T%H7hV8IqtwkWzr%xY2Y|Kavqz;X@e)R=Mz*3+ekMbFz|UoUHXp-x^1<8sX8D?`hag)&m_aMH8>oXzojPjZb`83yR8 z^rxSnb+`0rhD@vJ59xun_eC*kBjc-@igYW=vADa23O234cyPR+F`TvjKF(>NSXyIK zn>GoQWuN)_9;m(D5}2j8tu@e9t(|Mmxm#;AL(4EgNwS<_fLewD+HbCt6FC*aKYVLqZyi;17$tTGte3+7n#eDzQ0!z=_a>jaWi)l ztk|A0d0)Y^U8h3pkdQJ4ilsF+?ctFSwsJ@G1^YFua)m_~0by+YtGTT;tgdRk{O#ZF z)*8)_?)DI*Z=jsPsPhoTsHN}xe~EOTJFvKZy9L*DV$60#aN7;my4T?{^a?~95Ew$jH8q?s&lTwv6P}q?}80D@F-zJ8IZ!=6_HG%8D*lGe@RkQG$74B6t zoZGBr3A9QwBZ~{PJH-z3kD{X0vF@zqkVb-`JsC&+Avk3Zi+i$FSp&t&64;d6k319w zl+|GPh8a+_{IVdTH!-}4b<)nPaP!I zqP51qstm7mbloICw*zO zHpB$V`1MU(ya457cm!uZV8;8lxIkCMUH;1L;-VSa%}JnSWWG5G)H>8adpOBq?#oz? zm5lQzYki}f;FkV^)dd%PosN8+mJr2~9-C$P&GXwKJrFOenxCHi8mL{%0DZm3sgweA zReI0$Yu)YFXohyf3}`={5y^@`D|{%Wz^Y~Q3mrwtj-jme?MZ@}2Qhw`E%^Q5L`Yws z5QTR|(;sM4R$S(k0+jv_t&0)LR{6^LS_al$Lu~1Ru1cSL=`eRo|D(;^=L6c^l1NR0 zTIi*~s`XM{ZxbcY4rZ;B-xM4k#+d4{V1i6Wm#{fd`2 zP*~g$6PsFx8mKKS4xE*FyviX!SH-=#bgX;Djo>y*Be~DVjhume$y` zN2o(gpv(~B*&{&vwt5&_ukWz6hSgQAKi+q{)@X*7C4lnw9~wt?n1f!4Ry`-Mno~S0 zuyna5G0yx|Fi8a#_e!=328tyvHno|RKUAcH1e)5?{MjFixb{$t~HvWT^R!9aZI{0jABLP+{jaeljjxbQp{y> zQ`QzdJdZI|W5JzU$0CQ+3an_LSXyJ#eqJw>t&*&`YXNJIG80us2D&P4!_D*E>&Ow@ zNW9D`ok##NsAg1I*`-d`^GF84TyJB1L%5*M4=6g{9k z&u{`sgDZRT+!LOaK-LWtY^`B+RqK7b+q+lmaBig5wLq)vGd{gClTa=|rlY6fe^{iu zx{1Z@{!DPf7RJsW1dGgIt(U#8XrNeHV^ez~52!t7544XPW&#gix3vbks`Uc@&hFM4 z&Cn7wkke*ox}OxqZPuPN?VqX=OIL0ii#xHT;D_yuJu3+IHVHkE1NsT=}yRqK5b-Q24+&GDdS$mx#9>VOajAJQ7A<&ZJ0#JX}P zi#v9dVDsIKou&xx31O{IO|E31@UDVPY)TH{IUYc{+s$)4fZ8AiV_#cqpsQM&<%8U- zbvR3)_4&{$xot`vk4Uy^=^IvUa{KXhqGZawtaao?!6W+^58e`7HIb$Ne6x~)Vo8rp zEu{eEwu6jN6KXF-g*D?*TY8|Y(uc(D#( z_Gy-;V-tpMu%!pOD*dH1RoyK;njsg~lOa9O?x@jpY(m>NX(^INBHhLlEN<=ORanV( zCmCa<7rgwLweFOzih*KjjZGQ*<`XGUE?@aX3e+Y`0!PN0qEZT5&&vaIN1i%r;la09 zyVCH3b=W;V>VY`t(3A`K!MfP9lkx+3VvcpQZcTS z)<9RaHXGD+x7KKec6|?&Y|gjDfcCqp9Oj5@B3-~07I#r)!T8r0=hP9r7-uL_%KO^C z8z`36*p%$F8NC#s+%@JK=Ri3wPdNjoaZFX|8|bRmA!+KlTWd5!yAA>_NRO2R_+~Cp zOWzy2iF7-!v$!|^672Rb_gs5=ZPr2!#|B|SE^p%tK<8(Dgw%thw8IKYtX z(^N_Ux+=YAw!H3^9?j5F3Q*jQQc5K21+DNQuZLATbEXIsCEq+?t^EfJE_=k-aE##d zgDm}!(Nzr;-c^u^O?k+78?rg@)Q14-xA4#kP`kwgT-?K!9_Xs{BbO9#xAbU+=Jh}s z@!*>hK+WraROa~(jhBm(ji0dAHBSj9d&XGevf#CAEdAt5RSgtNdTeUfK|oo3hG)V9 zEAw;SoZNxy_uA3}U6uZ0>w@l<9?j4?EkKzV#+??RHiFpjy-0W9Ig8saQ#DpH_$6bF z+=9p6veuh&RWnd5t+A=yH3rIzVeYg5wMkOIvq}C^83yR8*6ni?a<|rKhDgA({ebWD zU=^{7U@PbWpS5p z7cAMFamN9{5~&AsXM8_>ZB#6+v8i3(1GO7KKPFoD|jJ+Mi|=_-8#U6p=f(PZwGK7u8X`H%FhO%$UxWB6Tv z(Q0oyRx|fv!JrO|Z&wSJX*UEpq&^{vB`!9_b9wLtDC=SHMJ7A;MLBI>AngU8pzVO|5DvR z!M=dl}FyTrH9p3=_dxKbhq?qhL*m8e__3lFMQzx)KUsi zdzSr)XAM?zLRZ$htW&UDcgDEC3uc{NJ$${|2k zwT@LhmAkb@Gc-2`+AEVpu>`Vo3oZZTFx$5itv>W%HG7N~Tp7eTYldKdqd!tg#Pk{l ziX|>K<&tU_x`03#x8g1!P;wVPQU<&oYHJO2RqO6cvbbAoG($U80<|t6P#cf!yIG`b z-kZgpd`&QAFk{R6f))F))~D{(FijFNnElL*Z&sv`j5xg@%q#q)9ufYJMlmmln8Yq_Z*tFMC3}LJIHI34Q zGRiEBy_mv@%6Hn^(gR(U-dXywyQN1nv{NNeR=(l2M}Q*GLZt6U^F_Mp16kZxhXtz+ zW;}UXaMw}Rx-cP%r8PFSTbDpt=$}VRfHF$Mw|IcHw%S?)UDf*IfoJa3I>JOVWI8tA z(*bHTs$M=5t-cRoHB+Xp#nNpY%9u5aVE9cIw`=BF28tyvHnn?|KyAqeph(Z+0>>J& zR1N{UDsKC*=k66Z+(a|9eh5%|sR9sM;X~;gsEq=qEhW}=!&&Qce+Xt6$yl(9;EazV zeP@!M3hye&#HQBW2Fladw~#}ASb1a$I6mNq^n|WTf2r&Xw@XjW(7GjPqzwPl#a<*! zprvnEWsd7Qq!jPbqU5PjtaaD*f?;DAo9+~R*D3_*d;AWPkBTKdHnk_+f%0S<_XvS< zeb0}Q0M{(Er3bny{et7)-7P(up{4I1ZRYz7Kxl;zc|A}YsA_mgti{K%)?K~}J{iy0 zJwa{$-CO5a`psr-1BG`LWMWerJOOI2$N_5E9C+b{Ej`dx>9b}!>|W_3SOU4QrYW3J zjM^1^?_8qQ{E4jQkm`Z~lNpyb5IkGHFZ}v>{n`eKB`!9#hgN|yXOk9%3FFF1{AR24 z4XdkaE?*q!UNytHRdNO!iY_2pWsd?zG0Jixye`+VUZPd}sjTKdvjulfV|=|tFmf}C zn~4y`5*M4=%}JmJSS?C!Z^>F;Iw#oW55___1efmk6Ir6)^*RO$?<$B<>sr7f zgIw&$K<&XC;H-nT^gvgouN-jQ-O{5OT7m}38wa_k0n{>b)h{Alwl*wotzQFJ$qQ{6 z+vOLWdX}|bmM_3Sv9!jf9EhL90m{mwoRNXr?ML8|6mwP50J^I6wiGwqtu>mVUAzFb zTVgOZEpd6RyZUd#~&U3ecDc0Ir16|d6#-xAU?bm3AmcD_qhy_oB0%}()bMA?Bjk>Y8 zs}k2`C6n}E+?GbL_CVJ9dFr|bilsF+^{W*^dX*);&ypVpfmM529sj49%~Bq6lAw1MLA2@@p@VE}|!kJ0MW7cQ3}9tp)qNWUaFkqF7pEQ(LDTDA|cu z+yTl&OP-noEK_x!%GW?wwSE|Tt-G~GGc>;j$_+-ky-jns3AKL6_`xFGZ+%$Y=gS4J z2Q$9eAh@PgALNiigeaEQ*wpehP%ad?9|F|IRDsoJ+FAo$)q3QV4er%Cf)$a)S$KX3 zTBTiue?KK!P3p^P#`+*w;ZMfQvFovtH_oxR4P(_aP%Lq=sU>Kjb}0yyCxZDZ92oq- z78mHMxMrp;?iDxOL^HIc0hE&xKM@RsR``%#1GPTig3Mz5)StD^S3z)fC}ZB5f+wD^ z^gV0TGf;R}^b&X4)cV&znX|y>Mxb_X1WqnCU*!;>tI~&DbG!6thSui;+WqTD7Rb)m zQH(P6G#r;U6+4TPEeEmIJ*Ehz9>UmluHcTi!AL0^=hQP$Ea|bSt%?hj48th}sI5i^ zJQrq54|G-fhqJf3*Xtu#5v|XMR%t`h9d?LTkzuUn_*;SlhA{>|5j>l*2gKd`xSoMx ziHl8bbO|WetL)c6Ic@MgFyOyuY;l3Eio3k^NcV~x&WdQ)jcAoN7YC@F8>gD}S-K)4 zSlm&C1n-SxoZt{lJD#;Z<6GZAv9!i!3YkWRxi~Pr=O2; zx7KKemcD`7vgJT%g%2f-sr3bCj%IO}3=ph7mT}Vv!B*c{>nFqO8z}s{K_)h3{xvV9 z4U}~QxPJ|l<8q%5n7FI0HPBV9^YoqIZmrP_EnfpAZ}R*Qpq8(J+AP)$i$%%U<5}xV z#|1Y}VBCE{a6|W=NGS#(iX}ZZwUh#sK|yl!Fs__)m#sCdu4=tJ?i6=xjb>;$1gPZ@ zpq8(1zZR`JOky?Tr*FX0Wtzg6D~I5Mkt}Zg>FpmewS#yK!J z;X;)|fUauodBE*jqZyiC1GDi`3OvLLgjV=a7Z9jDO%v@D>zS#nb-MO~!~SB-+f#7- z0+zl>j|K(`?<&Z|rW}_a&;!coHs1sLfh;|+e?wb(psUi495U72ZjNSXZVr?SYq|#( z#R6%=enlsUbdDJ;u49Yf%)LRl>E*poF!Yzs$RSzPR!8Yq_5*wilBfpR9`lmgV2t^;m+YikX3RqMi~|8TF?5hj`uacp6QEpPbT2-MDv zKneWixRz;`Po&#?kj3p^N3g?T#&JyqYdvDEk2P*+pjcXCGsTZCAW&8<m?nvCGhK6M?|_|$64IP&jlS(jN3m7dY@pepL}R&pjcXC(_WV=#01Jrcs@4*Wwb=P z+k}b#wY7%TRjs%E+r`~lqZwMa1gOpD141i&=u`>R<}4gb-H5HvPO{eLO9?JK&G@vU zV9vWN{cnUQysID+o7(6$P+R2{h&MUESjK~bz$yh6sgweAReI=F)kPfU)jveZdS_Yd+oJ^&oM((XO)$+@mcHE7Mh1!{JvOyLL7;XM2dIrq0bBiP zOAmBa`lHRdxm$WPL(4EgnbOE7QXsU#hrAvrPigQX-SIYvb@v6lwd9v2zQ+z}ky zu|1OepxccM6y8-3qx4ev`W_bhA~Te&vVsHOtAur7q%A$rRq3;yE$eRS(F`r&0A(f^ z&vyW79mI680$IA8ms#B6xdks@Va!}aFwr&Ex=Z0e1I5xBo7x3E(0+RZy)=kWJCOp% zq+P5s4A51ryEm)oZmrP_?fw~1yS@i%w|Gj`5b4HUV{z;E7A$jvvFSj;S=BqhuNQ^} z8Yq_5*wi}XK*=H0X$j-X``Xyz!s@EH4?>Lwy3cAxG#Bjqka0x^ z!OfLf+-L0@8z`2z*c4ag328uW>8Kyby>DQmTDG`ASH<0Tz|G=@n`nlXLxA@CETY(| zIr7HgB3*&UEbg7vg14S9-q!fZ94QK<#BAz+&@kt%0s; zT{*0ddmTBP715FgS|zc}eLf(x!iV~NK&>AV|AJVjJ!7rYe-*6qg7L1=gn#$9Gc0`( zLKNOrkcmw#hXA!3!9Z;;Ah70BTY8|Y(zl4;%-zzX8CpLCC==BAR0-5hl|XI!L)Pq~ zDUJ)ni1It(czTn_bjICb^_Uzmi zYOa0J#6aO)1u<$pXjrtTdV$)E2H?qmY^{N=YQ6kcQFm*NW@slvpgrtI1s{E7?Cd94_y&u+x^zTU<0l z`fa0;7J%B-3Q$YIK<&z~Ph(MXZZvB>X^7ye&+TwaY}Q!8H#G@8%xhzs8Yq_Z*wp+Q zD9_yStplL;)B*5oPg{DRtJ1Ig=5V+4Xoi-Nf%XFOQLLACtM|wXk*>v87I)=o!Bo+V zXRZkDieRl15u#XHV^dqqPg!Ec;wwX-{26>@2+S8@YYlW&>yKkfyIX5C!_L~ z;DqiL7tPT6Awca^3Di!NK&=ay>b6MtTWc1#Y=Y*j=hDgt|qJR(wA4<^9!h)09v6?j-2v+F8 z7|>GiZrN6F1np~Kv$&?$&uRK(xVw#N&(t8y&_E@w8Do@l|ZdWIOv2}TXtowN4*hD-JNm4 zH^ChzSo%j_n;R&+s~{7bT1o+G&wl{5@ep9bySDT|SEYY=$L-Ri8Cs7Js6GDy)Vv<3 zjczYY--4Bl?7>>^DZ`Z$Crmh{-v=J5b!h?P6zKdjtA1ZFQ9t`ZK= zRp}cpO53#y1ZH&mCpyOAw-1(qmK0FhF_q_%@bA18Ogb12#NqOAmBa`gI30 zxm$WPLrd;JnOQ)q9Y(SQ&&dRVnf(9}jtRx);f*4iV#;N}60o<4#RH(B~-#abFD zysID+o7$)rP+LqCs3mvcfQ&0uh5@=Neb%9w-79?rOE7?6#K9LnXq9&1lQKZG>M)Si zbo3Lx7k_)U3KKb!=h8Tc?DuL!@kIjVhOZ+U>#nFR*vDU=HN7~Sh{B;80%*h zJoAyo-I%47fnte^O>KE+pq-sU%^%hX%+vv1_+^#K5<1ua&F`s!9Z<7+Ud(8U5|+@?!H)mu#!0^GhR+8xM~G!or@5~(i)pGkih91D7}6j zS^>`Jil;}|&4J}#*;)f#)jH((3HNFpVWJt@+I~Peb1ubwhU>XStIJbZ&G$6~$4z5= z-B9pchCn#74L@$uiSf>x6R!-_2l*wM;O=i=_`(`iFsHNsmprhT4d339vPfz_MQhwF$() zp5tukfv!rQHRBm~OOIw~IRw~)U)IZWrhw22A4=aq?dcGYgJLa`tTFDc6@4OjFF9kv zcYZuspl@koyLFi#FE!)~av9!jfcBKQ1I)M)l zQ~|Z+d4LChTca`z&{eG;*1GO)H%BuxHwTI$JZ=TlG7M0=f^XSEl#HE*wH`1+aC2J5 zZj%J7o@MDbO>AwTSkhxtE+hHO3DnMM+I0*1uuq{2%Rq4AYzu{i#BTO_yuI}in zGLjME;6rW>t2SM2$QqHZLpm0B_yxgC85o296?8mituNkaZJ_Y3f=p~`@BaWwPn6;* zl&$j8vVFJ?g7xDeTWg@JTHie7X05}yRa$2pt&#`MqL5O6GLpy7RnGq^(w)i3;%>{{ zhLs$anQ>_W!HypFxc8mEjq#p}r8PFS=Y@f?z&F2^45%#`15BN2tx73CSGBG+;a~Uq zb-0OUNDkp?n816dv7|07$r#C2Ev5XZ%>Bj9zl)NNtgQ8!9)i!ZF+TlMa7!3V{~IBS zB|SE^IY4Y>Kj&-?)K-uIR&HfW4|G-fqqA4KTY5A@%jQ6FM#|<uzzcxZx~;mNd{R z>GpCL5UAyApwO?%h%wJ5!F8`$`pFyH8Yq_Z*pyd?Z@`rfP`(Ks zBLvEExmyBUJIj_H=&JNHQf_s(^gkLo2vd`Ras^K>PmN;Ku5?1qh;(I&u(<6%3cf4K z*d|Up7It3321ptavD+CaR?@(x3<~lnAW+^R#Nq<~eQ1jdbX8pQoSVgsUb?+{`FWr+*Q zFrkdHrp_Ly39H92TTP&=Y97ru*1c+mbE~v54YbO>0EuKPw8Dp66;`=8UJU71?i3~a zmSnBB-xe%TnsL}u!Te?&xT+^13hye2(Vol}!YD&`)EN(Dw9kHFjNa#L>9HGEr4QLV z!QIlM8PZV;L6QY7osFsRN6}FOYUekg+CYu-&r06%W34|F7M$i}Tw6kLSwEJ( z7$J%!JvQwt_z)9l->?s5l!aS&!RukImu-W}AwXB9uN5%G-O{5O+NB_H(zE_FYvCBA z2SO`+$m@Zc*MDsw)+%LL>l6b8zm;QrI8t!hWR|`fAqwv*$i$}IO9^4r-pdZFoM!p# z2kg?#mLBM;^!rjwb+`0rhIV-Zl=nz;*8(W#M$RxPmx^@jE3mjlqXgSjV*KTzU|2Y7 zJ@lXU#{Wm$d4N@Mba5Zcg+Q$G)GLB z1{6aWsHq;oD8@=~a)))vUQ=tJy;}R6bGX*1h8R>9jtm17p?wk!51`WUDEC@Om$fE~ zTPu54Rx+U$W7_-z7hVWNHlLEOs|AI%rtu-PDOOWqae?Bx%8m@&;I>8P5TL!{Iu%{y zXh%jh6h{V5n$1sDAudoEG2FJ2&}w)cR&!=ofo1A3<_Q%z;VFxIv~O1nis8uEG|y9* z2JFxGC)7t6!D!A;9L4ysg{d{ZY_Hb6A30oWR6{uOL^v`~q)~c+oxms}eG#sW{iX`( z+E%ZJr(FGZ2+UBEv1XjWc@qiKX^&#NT2KtFv1yKXh+wNZV|hjGGp0!w~jao?orW4DG+ACewu=3J}x`(R<6-H^5ZW2wN}fs9V;1P;8z z()V23&4R+a3e~V_4u1$^6du6cNw6wI&Vb{mnbHI8mHy1q2uDkgYA9Y06!$Wx;pRZ) zQt2Eor2EpC#dUu!a7$Ch_wNOUd}OUd2vH2Jv8iMjpfa)&sNB#4qi&m81MSsXZ#T@* zTB90@n*+s29e&CMRPHK);(7LRB=_&KbY~?yH)pNADhSLT#28RRVAkU`kYUDF?`}ac zq{pT*ybmbGrSLp2KxODVFxq>Y%rHQErN4cus-vYxHI!Bg&|D8Sf%P(PyRBO55Fy>^ zmMm_Ai2|cqGg@Z}Jmp^#T2GtV-GX9hjZI~c0#GzP>Gg&P{<0We%)|R&-5hRe4YXJ5 zu^nqVT5D88X|w>vPy)*4)I&`u-Z*E!?zcrqSGFyS+wrQv$H9z^?g$*afwkWLM|TT~ zp*1!|Jn_>2pm;dIS_75z4LpC`)Ea27*3A>^I9h8|LrEz>;a_~^1VSr(NP3{sXc?HS z2U{1nXRQ|$5*XN#F{-4%>Rz?r=9f$Ku%Pg+LK&6Oez4rg=S;&Ec+3J&c|jQX&SSew zDL{LrZ!ooiqoqeR6gLOHDTKiT+*<-PUnHQe@cKeJmrgA1!2tsIbY@&0DX>gA*82Uh z9u^eVI!wc+NYE@UkYD0)=Sj_hSv#BJ0__zywthp$iW|pu7NcJ1+L*v7Zs_@0c=SRc z&W~MLzSD;U=IzdyaLT|&tfm(sis8A~6f-pPI8~sy60o>H@xm*QA_G?5W{L~6S6rX( z8aYbXPUyvWDTlxx!fPXG zR3t<(q{pV1wtOSH{eYsa$%D#(X$7Nq8yK8ohfEqkd!>Kgwxy$`M>UiO=Rou6Z9LZ* zTH!-p53AAyd~Fp<2J~jFKLrbX)ravwH-XRC1ht*!`r@m?9Xz5W6rBe`SzG;!bbrxQ~1kLT#V}*39LRsASUj(-7 z&-lwufyLWbft&XrL@~6+rujT5jIH82K{H83Fq%OS#W-=XsWtxAUacQ&YwKvOQ4QtV z2s9sDC2*ZZ5X^wqCoc%;z8lEmHu@y+U>M_L=UyzV+XdEo79onEH8#x)Lxcu2rxA!^ z-0{>D7gl@4?OmXNqs6t=c`Q1rfaY8+35+6XOozCw@(Ha54rVpm)D~DYobgLzflsPe zg(L4IL@~t0rno_!hkOle!)KL7HbpQhjtuLyA9l)o4YXJ5u)T#Htu?BlTq=QLmZ809 zmH>sD&w|#jeT8(lhO)R*=L(!YjIr}_f#-I!*6)_}vY;4RW7F*24%2|yiFV}*3phqJi5?+g4eg7NSRfpNvE z!LLgaq8M6Z)AZahwwgm;BN)wd9L3o1vZ*!x)?TgiJn?a~)~JTk4grcf^Wb)%xT{N0x5GNEY{A8G#)}GX@11)~c+vJ0XgpH8#!O+As|$S{m`lAwbc|&J7P>(E__< z4guP$_0+W`9IJI4SJIsPFoDrj#H!tICA4b&sX88sRUIiX-517VlLRJjqr;Ia5TY33 zVpDNspm-UHMz2Nim&Je~N>)*f!Tn5e@nw6(ebB9>W5tc;S}6${wGxSvhl>D}dl{hU zgXTt_^ID-~wpNuOeT{PhPqk)Dab2L(S(bj_wI3}ghVas(EwDu9;ht)TdKNH@=<%%x?L}Ui#jrv3lo@n2TMPDU~dbGAw4#g zIU0ccf@^t}9;oqam-~@$fIHfl(gW?4KGHX}W2KMdT8V2TKea)vAPzp{=0L^G2hJ4M zMx9vPJ~0BFyD;iU1ZFQnm`+=BxVHs`cNNO0JQs#VjK<=JlR#xa8t~XUQ){5TT0cLP z*0EYgvjj>j1+@~FJMLlyD&5&X{vo8>-Ic{%lBy3Y*{eI_jEn+ZE3ww+GW4;a7+Paf znRF2-uAKaY45-Yz4SbboY7Mkk>)^@h9IZ8~p|rk%qSKisz=+p?N=gBm-APt0u!K<3 zt0!x{r@6q3y%=}57x=aXOaE89J{A;1dTfgR#XV@W0L7W$ss4Z&YwnTh8)&cAXX>VR zwAQGGlD>iFEQ<*&f#TO2hY795_hvQYeim4vFJrfj0>3|0895|BA&Ma`HkGa@pqT29 zyP|+*S9lcvZPnSP*09>Eb=cyZj@3GjYh~VI#4|!1d?;U|lH$f^A?|ceB?#$WhO)T7 zzZUp&f5tJN1!lRoaX~ zIa+H}LwGJN*qFeT6w=RyxX-fpWvzk+vYPId1*RFqc%qKL54?KxJ_;eyg7`q@Ebi!H0;@$a4lXNjmR13Ny~j7yf?{ZmP4Pop;nzUXpuPjY28te6eyk3> zmUFMnAwYYzesJ)aqqRmgl!gaTq|w{RAwc2v{FHr2ViOko3qxyFWpV8f%a;hHsqC~wMI1*zXpn-l>BNb(Ck05 zY73SL>DrHFad*TE%sifP;jaS6&S0&do(r|07+Paf@oS(mdmm7lSOMt1+teCpuhwCC zUprcBR73G=pztrgM+Yi5FF@tyCE>YH^7sVS`e~MaENsLi#^as>8?9sMGZCV&^kEt{ z#iIkBmmdXQ@UkLbmm);rU4=3#le54gCUp1>`5LH*aB1%euRhhQD+d!dYz4Slefmydj z0+VNCY`0pVK7*y-wW_}b#gHDG=788R4XBK}1S)P0yg1pE9%!$d`+1&swDhQk5H}Kc z@Ia-N0)$rh(1jEzo@DY8aQzMo>-J2nb?g&?-Lf!Fd?PT`I+p(SU;Qm8ysJ^KxI;MAhg1VydG!{gR*K@+X?IF9IW-Fu>#BGVthPJ;EszdeO^Ko-c_iE zO{HrEs5BpeVx%BHX8=|iWJ(XTSNi9rZ#r6fR71)2K+!g*=3@d2q%_s9Y!K4@nVZFZ zb5YGG%;QWV7<1dSL6Lrq)1vwQl~(;aZ~_ zB43Y3atE4Iwts-ZYCP+2?`sHAV8^2UN^9UL;xM)TK%33c!KG1?4aLoY;=NsNn**U0K9s(JN-L%117V$9jI}QOT^N74QgOz> ztOE1wV(GVdgjrB{SD_j+Vv6ei)6J@jVEhzBp7gKtmz0&*D*z0KNQ4QrqN*mJc zegX@mbQzZR71F)&VR2Wq78qTU(Z936M`u{;F`dFJD2CS9RM!6hiiz#`QVA4~$jxC@ zTHjsH2_=t|Wv!3A7dY6;cp}9h)_MHy61Z~aAVlF^g)%C)`>=?0YdNI=#Zkqg(E=>@ z$dn#vuk?DdE$Fbr@vm#2;K&|p)UWEzV1OzIVN}$q5SjTNJE7_?kYaLWlV7BUv zZTtl;8q3nJ{$a2M#gHDG%3UQ;SsoQATB7`56L`$)kjx=Kd!;XQXuhMRM>Uj=Dxf(6 zHbDa_59~X&5YnBh!Qys~6gZ+5W5@9VyDVX?*N+=)K{2$(rqToiiW?v9j|D1CK;X&V zrq)1vwGJDxz|mTx8cMzfiZxGYv~hw4RPNwMtP;}s)?sm{oD%q`F5`sD0!!{>t*>4h zY(X)!#-?&@1d667YYkKe{Q%$ZGqncVtMxH`p<}g<(@+hwvpa!NjLKYt(QAwU5?U>) z&uVVXF@&XS)R6I70fE)eu(&RSD2BM$6xUT6yB($h#nUyuWe1AY_h__n6k7|WJ}i?4 ztoDlAJJ}+~iW|+fQf}E%D>G@tvlUw5Lw*gba%*#;vQYB(AB*8}T0%F0v-&W)^cR@! z0ZU)B-w+E5?fi?pcqM&s`y!;94jpug|ENbJ`qniWy5ji{BmxJo=*<&Ti`uqrQ{eYqu+ z+&qA_c6SM9VLOE}CQB!<|1g%mX4-HI3U=ocs$o-^x(+CwR`ab5P+3(H*!8U`JJ}nhX94R z?AJh%&3Pdk;DV}0Wcmi$D{gO(fsPgz)e!H0&`^_j4XCuQf#ymGR;@|6kZ#0K7PrQ7 zfxg2SXRjCdTc_g4A+y$nTTl$GvAHuB&f`AhYoHi>%vuA*b79t+zdYU48fdT9`u4$& z)jFE%tUO6Tt<2?7Y2Fe-tu?BlG)sUn{m^egucyazouL&zXl|2Lc>PAS z2!He#%1SmG$yzT85a>LbacfP1Jzui)r)mtfpzy9jHEfpPcYyg)2^3F3+0B7UixBv< z_)(csfc8qiB>gZ)OOI+Ow>H4soWD840F?{_R9b{fIte9rk72EkPZHQ`9OK2=0vCT* z1R3VfSwk%-hV5v|$2&p3Zn~xWMe)iz20@Bt&7Y!x+Uhf&6e17SSKeH}pWSE~dCZd&NzAImprC zq8dsL0gBgW_&s=_lD>h;O=gzGLb{-tEbjM51g4qInDdOlyCYcZuBRg`D288SQ|S~0 zikBZ)dZ6;Q190qiQ+lAi(g)9K>1gRu4do^iD6%Tw-vgl)K9o{`=EzE`_VS6a9+<;g z>lugfmj}#a49F#L!#tLLQqEx(6y8;+hD~MU2~hO8^GzmDJWJxo4#2f3<7G+#+AICW z#;qJJJ*uI2Jy1+r&Tl&a6|V;>-Loxz5K0zVz*=`{FYx9<#vVNcCLYU&46~v8Fbj$y zJvPNT-imAv6zx>@dZ2QD4@_ueN)NPGdhKX_M@x@tDD6dHJZ4cU&M!Xzm2B=iPDnRx zF^ju$qrhrQ83*nbc-KEav`*MXdQma7#-=i7H&A&b4-^mV`Ozit@e)&OpuJiLcPi{? ztx*ld&4K1P!UWb!X&~;oB&17R#^Ub&Ebx~VjLWo07WU#s*7})Cqy@#$8k0Qs-a|apxGFY*MQIpAIj!H#m(dL3v2tIS?kAj1ZG~% z7~53f>3jv?<{1c4cvqo}%7qjbF)1ErbD)yVfhEfym)RU>uk;&N`Z!v8R6|KAKrx<= zpRNIwmwJ8;71AAF!{XkbCop0ya zzl^k?7+PafNhv@vAeOZTDzAA1hhH(Z2HLB21Fw>f)*97N{2C}Cog0WirIi9yS}9r6 z4re9nekq8DZTEZyMz;0>`cxEXjn9LWGF%^SK{2GqrnppYK`RBQykQSCXA+NM>ym;e zWJ-b6Ug@3UEsmBR)ljaSK%oe`IZ%1xQ@V|iu5?=#xBe)B4}uxXO%Yh7yeG7tHhH)O z#n2j?N=gBWc;bPBzy(-{w+pvYfSdZ8S_AFXx_MVu$7)S$x>Gg8pfYZK10fDRbg2X? zm&$(YgmpoC7Prr@0vmKBOsh4xG2GJOkRgy&8%BuTG~UG0pS(WYg2HJ95kf|+AIBK*VK-cKAI&^vN>vHzQq&IRwcv0s(5|>M4@ELPJAXNdX8XW zcXnnRS5#ov{DicgPLUB76hnG!D#;zFj0y)TBj12;)18zV257JJkmxpaqVTT5G;H#C#UA|F0VpmTEH2Rd7gJoIz2bH$p5C$IMsuB&{#evXw6E!5TLN2^ zhsfvd2(A2kvznjWqFB1;eHcGv61e1GUSx@?geWX-D5LT^8Z2VCEGKB7Ipbgye>vo% zsWq(jYVEfmr=zt-HIxJmRJvz@N`eL|V>T<65=yQJWvwki0-N_|eBVJ}w`(kYeL@sN zdTc5=1SooGSbCt6Lx8<%CCCH~v{(AELAe|)J*uI!zJcaYw*(ESENaeFvbq`1eTn~(yy&M(t^U$hiTYUhF<}dHXrbK=~FVL0PWTKSc4~y)*97N zvNTD7Nxlj6p4=Cb^s=hFr^3DD}C(CXO5PhYZZZcUdO`Cfntd+ZhZrlKEhSIgmmjh zvbgVV3k)93xcrg8?IT$0w+}~JPzj`66Uz{q(leFj1lLwal~*&HawAo5cP zpmHGvmdt%xW*DHo()$IzcC_@UhSF#OiX_WjhCpbA4`mpj(q4ShL|DTou-1>l4PhrS zJ{T>q?q-(093cwtDpbR!;`Kmr&&kpQl`cbIP)}2OpuN&BN%xndrAIZCT ztmn&xbay7RxT#JEoHLa%@w~uw$32kE>ky(CT4Pgr#|J1Hrrc!+RAws#cH3iW4YXJ5 zIp+^MT5D88$uK~3MFFek@lt42XBw+nAnR!1^)nbt=N0H2kQL%adX2WAu()B2N-rQR z;{8{?p$9H;JtLC_&|WpW42*ZQny7~2xxj+l3C-6=pfZ@Pi7vF-I+N9`+*x3k*^FiT z2n^Z6;*RY-+Ja(uE;dDW+KLAYK=C>nzfBBOn%lq)%}lL<_G%rREy2-R+bTH??GT_? zAdVL!1}fJ^pwMdt?sT$F7E0!r%UXBaCh*KW#^L(~#uv;6zmD5C+Ja(8k4=$(Xsv=U zwu+`F_glfLEJFgkz0#B(Xs`5G}l3l=Q=|xe5f4)t8#5DRYWLx%!Rey(okTyD`SI}0$Vp@=~EJ-@UB8N zY?^Bo(1=b#(HY6>F9OXgXB1oWRXQuPIjr_dpQqe8$4Vc^wG!S({*}O}Ecvn}%+Sh> z)jY9S;2n3yIco$q*-DsB%S?!3h>K10jx>y|<{K>$jH0a>1HZps4V%jJU_c=~Phtubr#u#J4(#{+IhjL%_DUbQ=%!=cJeq5z zyzPKmiIj2*UT>420Wu6w^e(N0^hG)dCA(x|tqYGAm?H~gu^9rld|>GZP9JMQF{H<) zat9CW$W21NjRYzUMBwbfru0C2r9ac^mZPOdHIyqSP48eyyul`6J>$Vz zSGz25WH!dY-vt&goCV2!&TnHaD7>psMiFhi3=%Bj-8GgTsEoG)?mT8n542bMjmLI6 zT6$DNNjN}}f@x^7RU7g}XyuoK)f`%29832kCu4sffw2o&+#SWoSx^jdv8k*v1r*OW zxb+Pb{jvO_3GhPZUu8-G+AFSK&lpFGi)tu6Q$R7Oj9cG8(MPx$S`Vlzq+61k#nt-> zZ0yOnG(zC`ZLIavq2nwlhSu0L8+lS z4>Xq*i(+feEvEFa+AIC#hYprLj%yXbqmOwo8)^k{@S%JSR7Uw+dMK>D3$VDS(~jpa z=PSgRkWFB&yR3CqLKNOrsD@3Y#}%jyxd)2e#V-Z|%OyK6Qwq>ttqZN*=V&)aHIz#w zP?#-@lT%1&V#P;{|g!H6oL z(jo*lsc&ixv{&n}PWv6LHL9Up8-Yr{6;MejK#_u%Bc*&8C6v^QvDO*Z3w-U(m|};( ze0S5KS<+-X$w$SI9-B&+AyCW~#+}_j5pCQ(3+%VhlpbiW^vzdKcC7SqtcbZ5PXePj z6FdiXsq;ds)jq6dnGXV6m1Oj^OkgF?wMY+f!%|MLpcvv}(+rU?wkq>|!z!{l-{}Bn zJvPM!+AHp{y3-shZZy|fxm2Q7%2OMlGUT7SZk?3y>bS)`I;pYEGWDyT3Vhql}Sv2H}YZBCg%{Fm2(L2=onLa zpuN)j&7JFL=}`^E&24q&Rtiu_-#`%r+?O(HpHT94Io5i_U4b+F8Gm{vFjY&EKC%4T z7ZWU%yR-`p?HU@`J0zrIXrZQIUnJWU6wRKI6P=XT}tlr8ODwq%~Z z?K&0@E$s6_i=}eZFXC z3B~myO>7CLWZJL9)AlsKQ?Oh$y+pEP+7+8!FOfW%c8z$tu*Z_;-2Zce1%*AQBV#gb z(}ynnu*4l-T6O!YSGe#4m8mO%mW!t60PXdhvCZZ=)^p;xk|G7ZK;I8)CG_AZ1)7Vh z_ys4rPqb9r_kD{k>%8>4PxlwCo;S5FPo4b#n|f-G55>CZ@}#wWGksx>7*F&2@@&cf zFTZb|C0`HM)DtZ$$~({gKEz8uQLLkzbKg|Dc~DmEJ2C_7Rv-_ppk+1?|H~&p%c5dK zJs+VwMCo+$&Fls+CXz5l@ebc_2p?FL2L`}g`7X+99?;(K3G-_VM*N zNIxSF`S{UKzb;H``PWA}c&I-U&Bi%!W|eeN<(-GB14R^!*Z>&rrSWx8~=mVSQW zxXaF0J@tI!8?{bs<)V*B@osb2+={WJ_e1)bqqc82rnGepJc|7-hN17TS5Da z(6k07Z8a0hw|1**#JtUA!ff{v+K=UTzIGFSpW@ zWNtDTm)rN>VmCn^$=8U3b8^~fTwgE7gyiv^xS{4?Twha~X4F7@I!H4;WIQeY`gvBW znqTnoD-$h`*Y!PBtFM2AUEURDm!^xOLa@Tt-NEteFNPT^O;ms+3`rxUjn!hw?cWM{C&$bq8 z`@OItUA(5BNvij@xMn%8jVOt9@s7+m(%miSpekse2~BH&=5$rTKrNMuiT;xa|8=_X z^)6f1mM-SeE@s@`QZ4(g6i63~2<6p*+V0D2R-}uc2}@^s=i)TVH5Tb%t&Nc${OH(G zP#sDS*fiZcj8Pe53adE_W)xeS$C~K@R(sP!?4-qxP7kO?(sRGvb!l(E^)wD3nk%i` zVB_0ck705he!l>y+~onyp)!8KFW>y#d%JyW@3m^qZ^ijMoSoA_E<))a(rsiqFxX57 z(o>zBvvaUYXTUw+4R^!t}y`j-_s+*3``^h3pqF2BF0 zhCXTAkStvzJ@qo1w+wIgvzva&_kv#SazlMzn)xLM=J3*|K8vqZ`HHjtG<}-MqsNp$ zI&dpA>2EGkuH*7@@lVPj9i$^Oj`Z>=P6t^CO>2PWp<x5sC4$3I4ho`iQ zmHC=_oJ&jT;FI>shKT?7gnzuNySU<7jpP5bjS>INNkJ4GKgB;bm2MoMayJ1~o=^kB z(p-{v6F__8|IF*2j*fp+BWe7%Y224v6fZk2p}jRke|+#yrLvxRx;Jwj8h$XLitPnHmSc)+nh{YlOlue|-ebgOGs zr@p(L^-2BqzaBd&FCsA?{Y=u6^W)7zs}47TYes?yKk1ZK_40pFZZ2E23(8Sn<10WV!c2E4%t z_@HmGn;?%6z4X|`(pc8jY0nU4d$<)KNIBO_;C z7+%0jFYZ0l`Grqvy;P_z zHUpmVyjY^+=o4!LEVbbjlbM(D!0z#pOK|8TGc4hyJd({%!|z24vs0ex{T&_fs7BJ0 zJ;(LWX9e4k2GOj6=-wKMJ9B*dFy?Lgi6%^lXEdsUXIrqE&$j%62mNMqSMPst*Np$* zu8;qVyS|7q-E}x9= z`djQK$YZNEh%d}ql%|eN{AG@X2ucy8=w#LPB`snZmr^aT^tG}CDo1`#00QT3&l_Z;+Q>VoFs0PaB-|v^Cln|F9*4PU&GB z{Y+B5XQr%LYt_aYNDouUjHB)2{T>qq7C7k@VbmY(L$<$)x+p7BDN1V}a%r z%n58Y`#~u%iwmK97U97Bg-`~jJb^MW4K@Q)oO&w=?cc(TP>G$hM!pFH)4l?QYga?4%M|31Jc z_i0@paV;jJXO6u3=8_k3Ub*F}mmBiFt6n^-HFZeA z7W(!U!;ci4<)!z`I_EBy>kU>0u<_)~;3 z;H6{8fHycmK4g)uAp_oE1pL`=v6~=|TgJiJuEfV;M&CcN`BGwE1pFVS88r|e(`?mt zt`JpwQk(<+mtW|j_o43D3Qs-t!=1N8=YTLwTV8Z?DxeRMR@Ah_b)%Rvze(d*3y*7I3&#V8wr{HyG zeQDc!;l;90pSZ8bUiz7&F46JviDmn$)y@l`_88lYWQF;IJ`VxoV@ zhOY{EAEl3M0PP~z{00llcKNiQy37X?*0Vifi?CS{|04+ptzLS+g)_xJJ%ArgEFZ6; z3w^xJj(qTP{bUOYsz><%o8nHL-vS1T!SFoQ6i{Rfeya?aVWycLfcB<`w4s9?ogPq) zq`vU`%6@l`wtj~60JGAC25iM+*trWG2r2QQc0ACWyTmUz=7jy;Jmep|dAamvt9FKd z1_uyVg44r&Lg_EkjbwT-I6!)c^cx%Sno6xidXuqi# zs6AIP(ZAKFuSgFx8cvR}q0w;NX%``_*JbK<`2*SmeQk(*FpzNR`hr!rq)5*BAdFaE z43H1PZFb~?^mKSAs1M}>Y?{Nj!WfnHC}4dTh?YDL00#Q}Vdev%z4;)lOif4U15_jF z$=|%HSW|rusl9bm|(}vUJNtG#7Rg$^jLW9`@U;NDqezlMmbUE<@^Me7kVm z#z+U%Nl+B7PAH>!;~B=NtgNGtH-?g1E5;)=X`0NR@lrrxUK=yZT;Buxh&dsI)` zr!WoqjpIs-p1aGqU9d^Q?E#?jYKBJ_p=>5A2WBZkd8XtEl!0lm8JO~%$-p!ifm!xj z>?X*gig9qZz&sxFq55&>B0jwlnAJ?P2ul1nQJSqal%e%AQNq1X` zOrxM_eH&`}t)V&JmCV#uAFw%P)+{f)^yZ(dTrJqvMV~!#T*1uS=@FW*M>+bLq$ekH zo)?zf?*b8+70Ha_4D(Ed3w13*(;A@FRxwa(tzx48O~S7TO!W!dGup+i3!f_9{PYfi z`GQd1wozcdvsnXZ*m@$Nk)_e!_L*?jW}m1GMV&ZKQ_eFPaoTv!6blM!N0)7ED({j2 zl@(w4%iRCQaS99_X2vPd-Z(uou7RWD6xB%T3WY8;X}j#mYh1QrR=VSXqDPXRgvYa0 zxopF#yslPkyAXQ6KZk8CLU|tL>6K^BU^8sxDU@MrFv7Opx7baPM=RstZ0+j^Wjj6EP3^(qw=p`80e-yY*V)b4X@R&ZD?`zakQtt?R2+Yd)+ksSwyw2WqgA5 za+k`isZ0;j&wr_U^zsZBea^@(*GJWEQAO0f4Snc z^Yeb(e!CFMn=3T8-E8&%irew`rdUu=J&IdwuIOE!9-Yz3!(ohK78kz#hE;i)5x6?R zj9Z|+ajTbZ?C7{<35-`aCe@xUGELz7G|Zn4HOeH^K)~cn9=hWyjNN?WZsIf5}y!T#6UZf`ib(Cp_ zZ-`GjX{I)2QBk!Dl{ipamzio=?qA0B-cGs^PG4ew#8fx^t)*eMI@cQLwE{}d8l5h$ zUZT;64hN^W>5HO@NeZ9$|0@i6ykI6uMyDr3!nzh=KGTf+QhJ0EyI zf9>!{MKzK-gV%zec2tRdi6Tktle5KK05POkE5RYmc>QO>T~FgyVZXkecQgBKCi~`Msw&^c}~-T?z>$y z{ktOhn@!156B%G2{Y=u6e)i?Qh1XU$Lk5T-Gmfxd8R0D9lT{hqGf)4( z8R1uA^;&(!X6KA>jaXg}=-M4SVyXoN^`(q}O=SoSa2dS_`sw@~41obEU1h+VUCoRD zwD;QGU%OF_q|R}=$j~LHa?>-~Xx2a(^Tyxi#tyY^64+|q8~X*9Sn|K~=d{wF zty+Eh8Jxhq)j2`*Ae0Ux{YWMVgUu#_bRFpu1|vcA{ua9l@)&L$oGn4b#N^4?ZQS`{ z-H;$gn`YF2Kashl*{V%FDylZECMSqRXQx^gx}EJ5yTMa0_FLV39(mmK-$soM*pVkt z&k>MqZKjlY^_o8pD5AZ0)5oP~U$tDPHhPK38TS`l@YL%a-ZWuPR~J3tY=fX`&)ex6 zw%jQCvT$C#Tj15V(Umm)Qo>J5;_K8#f;dJ$lhg;cRq1~q>|k>wh*M<7k)F^kNDvnZ zO>2O5S;au@fr^Rchn@Sn1W{UP%>P9DXxBTy?{S z@fpy!t-ht$veMpnJoQu7xSW?Ny68C);D`ZOI- zF{Ca6^#=V+(sT9WtY+)Co^F9aeM4p(t@m~g)X#*bH9$+2N5McXor;O&=M(<7o9_SH zm0ayC+eG^~{nqtV`C_jSs5=N{Vx~adYqKIy4-zg))@Q!UnRgthCv1#Bb)|zxL4D{- zjZI~;J)oHVjN9%&W%wDesPi@1b_d!UsFB5sIXX~Ljie_(S;<@}E3Nr}wmZx{d2ve~ zoeEUC!+_!uI4|;Z*k34{u0BWREkb#w#6T9^~kOKj#PTU zPuX8}E!sq%aP7SNtk+)p=fYcXqfGZ%@Nbd_8`npGkUhGBnTz6g?G$$V}Et z9Mr6$&bWlS5}MWkEtQIaS~e9E%TFTwn#e4nJYQNw`*=8aQ_Ba%Ug9=;g$>akwwh4( zeo|zvCmc7Tq$I#XDO({sbu8n6IHgb9kCnyE$H1_cY>2 zeM=}KRi03J>I^nJuH`wDk!mm^_2akLO^}B+!FK4P3I}4`KG!dGzi}r-YO24Pog!07 zvsJslN&NNH#vG~d_WWeok!o$kI_ik-bn@!BDx*{Bi!QYN5S62;Uca|X_X&*O#wZ5Se0Au)f) z|2|SndRvvd;T^P(?6teSoL=DtuAzGfW$yWeg$&9_UHc(m24H&Y_3}m3af!uq32}cJq zs*yC1L!M?zmg~hQ1TxIZ6DXk4lMPg+E7z_FWkZ^BWp>?X*ggmG~6nvU`A#lDysUAByT;2na!>U z^ftH7hwMq?r4QZsGG)If&icGH`9@5--9g{ww<7EJHS+3NbBr!Lw6LqbWcKsiuSV0D zEng2W`kACBr~6+y(z~o^g~%;TW*q5(mK?by2~BH&R!YS{t+|Sc<*U0*`>M$GQ^t5V zqkS~plj-Kc=FbtiEePe^4n=NTn-!Pbc7(EpMS&bbIK{2`>SYD~;y~_9tX^`v+w2_3 zJ&0vmr$FxLI?aND>Qf+NQyKCB6hl6^TMH;!hOxLJ14lhK0~u&-G6F0vTrIiVR$r12dx0+}-hPRoc$5ihB>5oYOD3NWs5*`x-t+_oS>gtH{-6 zda646KU}-!rMDfsbn~y9+;yM0?@nEu(oQdUw3~Aonml1+e4NW{nml3c)D0G=x*hd} zOIr6_S|_hwYFnCod)vC|heDhSUT#Z6ynH?4=x36;#N>k|vpxxLjr4Jl%sA561Uje+ z+F?S|8lW9fF;F|9Vq*E1gkN*vSG&RA(?06=8hW*!(=()xL_&GFp!D(4X2pg7GvT8z z$BMR2^P2MoSnURPYHr%mM2{dd3hGDs0h^-Rb`~Cl0mWtPD0;ns<^%00#)TEG%bRIf z?adEqpOklWe&9+bd1PJVY+|O@pS~bJz^uGb0u;}v_aQ$3AtgT4>jgAdfx7baPM-AiPY|V@9 zF)8ZAw;Y+O1M)*H(~KJMCo;J-TeTVsMAaJR;rwu77VwTnKJ5xyPk1l z;g3@u+tN|br%%0`y+K}mbC>dw76&Aj|_lsn=J&t;MNEKcOE)HdZ<Dc_ga#Auosg=U3A#Pu<&>=>LnSJ~Xp-D*rWCeeIoTyCb@_&|BPD{Al0_ zFa2uPfake?ch?J-@V)KSyuDt}eZtJ`WxVvW-6~wFvfo)>;dC)ekxU`_?mv#z+tnzq z?%k{Z`wB-~^=(xHYk&WoLq7TIzn}DB%ZHWMQ@2IPrzA6u^!6tXd1pe?8lbtTNYk#V zm{`6V;ny??N-5L3)TezkyWgzBv^$T{Bxpb=n}C!78riJK08I!F1q7{~>h_ZR)0^2C z5x;>HML~Ti;;|{_CSQt(2a1dgiJb@j!bcK5fqcM@KxWku>6S z)&BF!<3|+n^g1`0m0JX$+5HjER!E5tH348X<@5`lpKki!+;`o#c3-O&O+SMJIFq0A z!A3&qAJT1PJ}}tK2hvkyJ}?;hVAHqQ4bARg9Gop5Y>nwXJK5~Rp6!qiwwY$sfIpF@ z*{Ut}6IEMTkn_R!m8M&)IV!D~z0p(88r$vYknOIz_muZdhvp5^XV;t`9Cpx4-!jnW z?VG>c_3op)dPi<;ufMIGZqBxfUizr%Ejr)Z?yTQy;@W9VpAfytpl*$4HO{N&uAO^! zyEm@7-}7Dfi>zskCO~oenWQd}yxzSl6^?K|C_!c%X}EVX+#-}DG_5q-lZt^_85I-D zw<7$Sd{9z(5Z<2lvFm=cZ@Zq4kPrG1%KT6HV1Uhvd=N&MVqo`N7d>8Zi(nA3akjZ{ zaInqJT?#{pWq%Xpi)$69TToD6$`{x)pX`P){x%phH6BO4fYn^sFpBX*p&Rm+0aknS z#q$@Mqw@u-k<>Zn6}X&yOS5Fi7ceWg48YY#YL^{Xk$PDY6f50wS+$jIg|dSSbL4I! zlxI?&U>Ugvn|*`woXT@$Fd}!$x7baP$1daGY&ZA2V>WxHz7Y6BFd}!iX@+m`CvuZC zTeZETMb+vT<;bl%b-JZ(=!h4oXpGzPaihw4QKLKG^GCCse+|;RXth_a-s7du?^)#M zYA&huyT0vDRdMg27mJ8bU#u?8q`0@s&eEHl^>)t5oqNTH=)M`I9XZ}4ul{Cf>U=Ho zrP93{t}VE=IgK~>^{7QZll0_-UwZ6*ryL!#RjWg09BGOb9JzG~O>2NwPsKp3k&21s z;|c#; z&e8P!Y{JuQ5 za=v!?ee<09dfcU-k%ufNV8;2yhy3|InXy@*7zJ4c?U8|O4fs!Ns6QjC%r4RiWp**x zoLok_p*$3W@v_VFZ?T&|?S*=*K_0J7l(RLTQzv)-%QT~I;!`yL(JL{T*C4JhofkTM z@FpFs+R&QA3`!GY3M z6PsqUFpTj{Axu4R46z5RIi*q*W5dH{?7?bp?41cr>*&}+HU80&qq)+e=V3AivEbWc z#5vz)1C5i8RyI&9N;?ywc=m(+p(xMYKZc@JyFx#MgE-^E*XrL1Wi(00kkKU97Lj}X ze?-$C-(ojG9`}udv%T^8pKBwSW+|hSld?9#Q?D6ZwUs6LTHXKq8J3dKH^(KXwGrAT z8COb`l~P~IIhEE%sAT=2 zZ*!XIrN*u7o!4KlrI!e-J1hgOjWFd_-Srn~ZG`KyXSQ25o7YAdL_d?%C2mf3cgsB9 z3o$*I%sARwQz?imXyJsWH9#AxVxShOVxs>V!hap{WxY$4vR$e-(k`ZjdyaY9&Vo7A zw%8CW69J8TEL^#_5xUjP)o5Kbt&KpVO?TKBuXy?rqM$mI4zMYv5}1#hZeSyJeohBK zrJD`dEW=INhz8o54uYLBIyN29`rlLy<*phimYd&;ZZ)8C=>>{Tx5bF}-)jEdJ>$N$ zd(r?h`Wc+C!KFFgpA*V>mwq8Vz+hd*yL1J4^)#5Tp5J0Obh$JR&KB>-Voo)kUDjHK z7dQCJG@}OMb5feETIxQcYW00N-nR~(Vac}SaiuD>xIvEGRrmF$+0485xz}-lN7~rY zjrV2WO^X|h9^>)GM;^-MF; zubM-P8;n?@MXpWlqWgIGUF`jg7dO~RKa(`x|7tVn<;{^ak&{*1O=cWv&}xqN7{WKw z8lVBqF9&L|Dkl2BApFGt2>26#nT64J+b36QO6< zM~7lY)8Ynn`Oi!&TXTqi51SqF-1j3n3=SZlALoO-gmMI)^c$HEq^C%ikgg*0fx*ZJ-()vI z9tDkq!vTuV*_f7-d+bc<&#N2!-Ar*N%~s88zo^=KE9ZmV$7Wb8FZL(DN2?p$uHScA z4$22E_uIN}pOj8-A78-z6RmC#eEG=OY_z&T@plyxVq$9Ok?Gy8cB0h{+T1?zz@Jt( zNR$26g^jej!Hq|K{uoLR=x=t(bGjTopwB$wp7r`DUfp0n{Y+9HNcY$A$)SJp>IQLS zMpbgTf3ni`{~)1h4fszC)Q+lF$_IpBkq^|>4c^f%HvV4akfn{84&vCS37o>>rJdwGT8KBOMH&eW9Rsln$_|GzWmn-2u>?#wm)wJZFQM4q&x6 z9fS?fd;?Y&m5 zHvJ4v;He)t9Rw0e|B!AYJ;Gq~=32UjOa}%d9W?$Hy9x4WZX6sAP<+nBth(hqV24;@ zp~c_KPEJ2dvsJ5{dL~zGd3jC;zh$0jiJN!v^2_pGdWBTgMlPZy7Ao{#)g^VcLV8eb z&oizxGlbLr$dk!$YWl*<*F(n95(`eL_GiKp3x$uYtm;lnEL3sx_L@ygEX>{Qnz{rn zvG92C?Mc09iG_Y6nxq>&F>fq&-QA;~N$LY{gHi-LH>-%|!F@8LD*K0XI(SHETB)l; z#X#*(6%+llXPNmm=|Fv_#fx^~e5phF3C($lh5R-|`~&OQ7Ah@B`0C^*zjHCP;sP}f z3K7e;A({t8ZFb~?xpcHBs2=45Y?_PrgfY&Wiw{4AhgIn<0Pgx^<^!O;`9Pca_&c7U zy;NsEOz0lAAma&4-0tU^ohNpWeg0)W_>A$denCtC?=+!TzxTtk9ziwmk>8j0q<^>3 z_&Yg4eD6hKzdnC@pc+YiVZwpf%*8U@#IPKgl|FW$*~cEwR^{%&_GRjF_X}=R`hVxm zeWW*AwU+cV5Fspp(?bZMOb^nHq{A3&-aSaqk?Fx;q=!!5VmCn^-Hn5@-8~$SSy_6> zvufjbL53ct88r|e(`?m#X(_7qeMPF8uAMZHcIN9-RXd|%E$zIDe!*!%W?Dus>rr(m zt={0b(rM%)TD{@o&HdpomX^{x_35?$7Omdke%e~7A+6rfvcGG{7h1icZ?SY=d}w<1 z4MWyw@w9qF!;Cf0H(cFBZ}c(!py{-FL)6OO*A=JL8$2JpPIjOiuilV>ekQ5^r0Z!t zG$b>x-jIpRs8*G?oJ+D0npRpwR>eRqyNZeaH36+0y{DHEL!|nanU=lv=dJlOt(Wfm;6l4Qw6=rW+7Z7^zEn=%yEd7} zcv{tmU{iTy2o&!RP@_D8t>S^$4rC8l6X%-Q188sd z7<>1nqq7I9k<=F&-HZRL@MK==fh!$>mjcG3+X6V0r};XGhy6gapT{qF$(g^qZ>n$P zz9*#nTD5KTGdO`Ys&PIzN+=yf`i;y72Aek~(p6+WFc|qD{#)!O$m3Vz;A~4l9gFEy z#qyxASW@DmX+{miCq$a9+Qzq{Y9Fg}J{X^DmZehd>Azj4B_#q}50vRmOG=z+xboRu zT2f;8n3CzeXi14}Q{KFMLQ6_aDX{KSe_B$abNxe~9?+5!-mScjq@pDyMjd|K;}|U| zv1&pGZ|_-N`ikG1Mvb8*C1%v0Qzd23g2)F8=x37pz@XC+e|5>kOG+#wGmf;~@0<^! z2~BH&wob)BEk?ye|0>C6eN8@4my~EqyQo`eLeo`uc}a;jHpJ+kj)c>nHr! zjS=v#oMu^2aQqbT*sQ`Hy9vz&;4psUh2Q+MS$XX@V7dopzys|K_&n3zI6B}_jie{L z*}Y`BUWpYZU{>a^11eL<1C=`upz;du-CRQGjWsziQ|6v!2BtiLGB6D`hv~^vCab`#{0g?0lkuwAH+$L#Tb*eJhP`XQ@n7GJ`DcS*BVyH!>Eb;sHqm@Vtivb;G^ z^|(JR{gApx_t|Ucfnd8znO85Tr5|oapG*H8&F!9{eUpcUY3YZ{i|$-GPfI^^$sJWZ zkd}T}bs)vswY2oZ>GJt%7K{zj8@Qwm%fHb}U%&I|$D*|K!(+{R`X{mULl^p)r02>t z_SyOZ)p+TLUS!5`HcjNf97bqb1GM2P25OU3O!QCF;Hv^tUHZX`cJb@|KfmkSm6m?^ zq!qFu0@H^usObGB`CY_XFJ)|uz&ufJmIVdJPl1U|F@S&r6DTgdw{Rr}D)Z9-AC|c- z+wnkq1M^tJw~h`>R3quhu2Zk(y_IcfZHGA4AWgB&3!kmJh)XZNJ&4ywU59aY@jZl; z9(6hNt`o{@qC7=1^b9sbPo5+hdIlr(Zhed01bI9#4$d}0_DIade(^^ZrR8N69+_r1 zgZNyKW(vLOqG~7Wap(%UmN z{mi>gE_(Ae#S1#+=VcWl>1UFjjo>oxJ_HuvWfew{8Asaq+!wTwqXLN|8*OgmQ_#&%}@p|{_L2)zS@OX`%XvDjTKs{mGe=MLHI2t{u~ z6x4@85u3^_HBc-D$hXu$(KEFjjbdQ^k!C0Y?G449={`F;6j6<&Cx2L?Ti?NASp}Gt zXZt{&kESl&QYWw^;u^UG-EpCN?DyBg|KP7d(qCzEL;4wE?qcF`hqXyz*nyuRB-$d0)H{t}4 z`N=FxnJ#^v^r3YWf;%TK|C-iO_{-w=W(uvNkfy+=99TzTPU>>$t+bB9vdF)jYSTIj z`?6kshIJH@Z|Zq2HLasCJ9nAh3uzsN*_S%xSx4(AlxwzfRik1qditq-ieD7#C={Td zN$LZq;VjRg_JfkzP)d8 zw&FMP(UqE>?Gr*ud?-BtYq>+gHAoMIU1!_v&2#^oH`D3@^fNes2Z5X(S`fzF`;Yzg)w3@@(mxq6Ew62c6DtTy)Hnf^U#xWCJHqvSip9c63 zTsOakUh(9~N!MsKhxIoOm8(XpIlRmie(y7_=1{f3U{^0%&7o$2un*N}HHX-()l&Yl zgPzv;dNje$Bzdp8$j`eYp1>+6N(orZqt8qGF&nLB&M>*Mwh@9!e_9 zE~Wfow#D>NnExOs=PWGW@KJLbH(Oq} zF(lVQXjsv#cPHGnVWMT<4zYYg8e+9spTTCwi?9vGP>!d9>QSI#Qw+k{gFpph%By1o zcm`M?Pl0vp2m%$@r}dC$YZi`aJKY7t^An09S#=eMI)w}X4F7@-bk}m>v>XCZT)^u4^uDBwoJU{*Y7DU z0@3c%Um1_kq7m0VOc-?LN&|iPhEa)=Xc34TzKfHG)1nbkgF=P{=5D3exqS2T7W)3Y z9EB@&r$rY*{fS`rxVOj-Fe{hw|3ln& zKt+*!Ut<_;6DHJAQ4zD4BctH7Imc1NG3T6fMlrDFoDm}^X2m=z#+6mfIcHIfn8)