From 6f31995d86cb5c7b441a60e1604b4a2462a8df6a Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Thu, 2 May 2024 15:42:10 -0500 Subject: [PATCH 01/16] Update PurpleLib --- .gitignore | 5 +- build.gradle | 2 +- src/main/java/frc/robot/Robot.java | 72 ++++--------------- src/main/java/frc/robot/RobotContainer.java | 47 ++---------- .../subsystems/climber/ClimberSubsystem.java | 1 - .../subsystems/drive/DriveSubsystem.java | 65 +++++++---------- .../subsystems/intake/IntakeSubsystem.java | 4 +- .../subsystems/shooter/ShooterSubsystem.java | 5 -- .../subsystems/vision/AprilTagCamera.java | 44 ++++++++++-- .../subsystems/vision/VisionSubsystem.java | 1 + 10 files changed, 92 insertions(+), 154 deletions(-) diff --git a/.gitignore b/.gitignore index fe88022..580ae5d 100644 --- a/.gitignore +++ b/.gitignore @@ -178,4 +178,7 @@ simgui-ds.json src/main/java/frc/robot/BuildConstants.java # Battery Tracker -previous_battery.txt \ No newline at end of file +previous_battery.txt + +# Odometer +*-odometer.txt \ No newline at end of file diff --git a/build.gradle b/build.gradle index 574dd00..04ef164 100644 --- a/build.gradle +++ b/build.gradle @@ -97,7 +97,7 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - implementation 'com.github.lasarobotics:PurpleLib:2024.4.6' + implementation 'com.github.lasarobotics:PurpleLib:0ed23bb51d' implementation 'org.apache.commons:commons-math3:3.+' diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 42b0ced..14a55e9 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -4,19 +4,12 @@ package frc.robot; -import org.lasarobotics.battery.BatteryTracker; +import java.nio.file.Path; + +import org.lasarobotics.hardware.PurpleManager; import org.lasarobotics.utils.GlobalConstants; -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 com.pathplanner.lib.pathfinding.Pathfinding; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.PowerDistribution; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; @@ -30,67 +23,32 @@ public Robot() { } @Override - @SuppressWarnings("resource") public void robotInit() { - // AdvantageKit Logging - BatteryTracker batteryTracker = new BatteryTracker(BatteryTracker.initializeHardware()); - Logger.recordMetadata("ProjectName", "PurpleSwerve"); - Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA); - Logger.recordMetadata("BatteryName", batteryTracker.scanBattery()); - - // Set pathfinding algorithm to be AdvantageKit compatible - Pathfinding.setPathfinder(new LocalADStarAK()); - - if (isReal()) { - // If robot is real, log to USB drive and publish data to NetworkTables - Logger.addDataReceiver(new WPILOGWriter("/media/sda1/")); - Logger.addDataReceiver(new NT4Publisher()); - new PowerDistribution(); - // Battery Tracking - if (batteryTracker.isBatteryReused()) - DriverStation.reportError(batteryTracker.scanBattery() + " is being reused!", false); - else batteryTracker.writeCurrentBattery(); - } else { - // Else just publish to NetworkTables for simulation or replay log file if var is set - String replay = System.getenv(GlobalConstants.REPLAY_ENVIRONMENT_VAR); - if (replay == null || replay.isBlank()) Logger.addDataReceiver(new NT4Publisher()); - else { - // Run as fast as possible - setUseTiming(false); - // Pull the replay log from AdvantageScope (or prompt the user) - String logPath = LogFileUtil.findReplayLog(); - // Read replay log - Logger.setReplaySource(new WPILOGReader(logPath)); - // Save outputs to a new log - Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); - } - } - - // Start logging! No more data receivers, replay sources, or metadata values may be added. - Logger.start(); - + PurpleManager.initialize( + this, + Path.of("/media/sda1"), + BuildConstants.MAVEN_NAME, + BuildConstants.GIT_SHA, + BuildConstants.BUILD_DATE, + true + ); m_robotContainer = new RobotContainer(); } @Override public void robotPeriodic() { + PurpleManager.update(); CommandScheduler.getInstance().run(); } @Override - public void disabledInit() { - m_robotContainer.disabledInit(); - } + public void disabledInit() {} @Override - public void disabledPeriodic() { - m_robotContainer.disabledPeriodic(); - } + public void disabledPeriodic() {} @Override - public void disabledExit() { - m_robotContainer.disabledExit(); - } + public void disabledExit() {} @Override public void autonomousInit() { diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 989db49..2fac5ef 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -6,32 +6,24 @@ import java.util.function.BooleanSupplier; -import org.apache.commons.math3.ode.SecondaryEquations; -import org.lasarobotics.hardware.revrobotics.Blinkin; - import com.pathplanner.lib.auto.NamedCommands; import com.revrobotics.REVPhysicsSim; import edu.wpi.first.apriltag.AprilTag; -import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.units.Units; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.GenericHID.RumbleType; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; -import edu.wpi.first.wpilibj.simulation.DriverStationSim; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; 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.ParallelCommandGroup; -import edu.wpi.first.wpilibj2.command.ParallelRaceGroup; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import frc.robot.Constants.Shooter; +import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers; +import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.robot.commands.autonomous.SimpleAuto; -import frc.robot.subsystems.climber.ClimberSubsystem; import frc.robot.subsystems.drive.AutoTrajectory; import frc.robot.subsystems.drive.DriveSubsystem; import frc.robot.subsystems.intake.IntakeSubsystem; @@ -70,11 +62,13 @@ public class RobotContainer { private static final VisionSubsystem VISION_SUBSYSTEM = VisionSubsystem.getInstance(); private static final CommandXboxController PRIMARY_CONTROLLER = new CommandXboxController(Constants.HID.PRIMARY_CONTROLLER_PORT); - private static final CommandXboxController OPERATOR_KEYPAD = new CommandXboxController(Constants.HID.SECONDARY_CONTROLLER_PORT); private static SendableChooser m_automodeChooser = new SendableChooser<>(); public RobotContainer() { + // Silence warnings + DriverStation.silenceJoystickConnectionWarning(true); + // Set drive command DRIVE_SUBSYSTEM.setDefaultCommand( DRIVE_SUBSYSTEM.driveCommand( @@ -115,7 +109,7 @@ private void configureBindings() { // Right trigger button - aim and shoot at speaker, shooting only if speaker tag is visible and robot is in range // Click DPAD down to override and shoot now - PRIMARY_CONTROLLER.rightTrigger().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.a().getAsBoolean())); + PRIMARY_CONTROLLER.b().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.a().getAsBoolean())); // Right bumper button - amp score, also use for outtake PRIMARY_CONTROLLER.rightBumper().whileTrue(SHOOTER_SUBSYSTEM.scoreAmpCommand()); @@ -172,9 +166,6 @@ private void configureBindings() { // DPAD left - PARTY BUTTON!! PRIMARY_CONTROLLER.povLeft().whileTrue(partyMode()); - - // Operator keypad button 1 - PARTY BUTTON!! - OPERATOR_KEYPAD.button(1).whileTrue(partyMode()); } /** @@ -397,32 +388,6 @@ else if (DRIVE_SUBSYSTEM.getAlliance().equals(Alliance.Red)) { } } - /** - * Initialization code for disabled mode - */ - public void disabledInit() { - DRIVE_SUBSYSTEM.disabledInit(); - } - - /** - * Call while disabled - */ - public void disabledPeriodic() { - // Try to get alliance - var alliance = DriverStation.getAlliance(); - if (alliance.isEmpty()) return; - - // Set alliance if available - DRIVE_SUBSYSTEM.setAlliance(alliance.get()); - } - - /** - * Exit code for disabled mode - */ - public void disabledExit() { - DRIVE_SUBSYSTEM.disabledExit(); - } - /** * Get currently selected autonomous command * diff --git a/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java b/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java index 5b88384..1666716 100644 --- a/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java +++ b/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java @@ -88,7 +88,6 @@ public Command runClimberCommand() { @Override public void periodic() { - m_lClimberMotor.periodic(); m_rClimberMotor.stopMotor(); } } diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java index a09b008..0ccb693 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java @@ -19,6 +19,7 @@ import org.lasarobotics.hardware.revrobotics.Spark.MotorKind; import org.lasarobotics.led.LEDStrip.Pattern; import org.lasarobotics.led.LEDSubsystem; +import org.lasarobotics.utils.CommonTriggers; import org.lasarobotics.utils.GlobalConstants; import org.lasarobotics.utils.PIDConstants; import org.littletonrobotics.junction.Logger; @@ -62,6 +63,8 @@ import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.FunctionalCommand; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers; +import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.robot.Constants; import frc.robot.subsystems.vision.VisionSubsystem; @@ -95,8 +98,8 @@ public Hardware(NavX2 navx, public static final Measure> NAVX2_YAW_DRIFT_RATE = Units.DegreesPerSecond.of(0.5 / 60); public static final Measure> DRIVE_ROTATE_VELOCITY = Units.RadiansPerSecond.of(12 * Math.PI); public static final Measure> AIM_VELOCITY_THRESHOLD = Units.DegreesPerSecond.of(5.0); + public static final Measure> VISION_ANGULAR_VELOCITY_THRESHOLD = Units.DegreesPerSecond.of(720.0); public static final Measure>> DRIVE_ROTATE_ACCELERATION = Units.RadiansPerSecond.of(4 * Math.PI).per(Units.Second); - public static final Translation2d AIM_OFFSET = new Translation2d(0.0, -0.5); public final Measure> DRIVE_MAX_LINEAR_SPEED; public final Measure>> DRIVE_AUTO_ACCELERATION; @@ -105,8 +108,8 @@ public Hardware(NavX2 navx, private static final double TOLERANCE = 1.5; private static final double TIP_THRESHOLD = 35.0; private static final double BALANCED_THRESHOLD = 10.0; - private static final double AIM_VELOCITY_COMPENSATION_FUDGE_FACTOR = 0.1; - private static final Matrix ODOMETRY_STDDEV = VecBuilder.fill(0.03, 0.03, Math.toRadians(1.0)); + private static final double AIM_VELOCITY_COMPENSATION_FUDGE_FACTOR = 0.5; + private static final Matrix ODOMETRY_STDDEV = VecBuilder.fill(0.1, 0.1, Math.toRadians(1.0)); private static final Matrix VISION_STDDEV = VecBuilder.fill(1.0, 1.0, Math.toRadians(3.0)); private static final PIDConstants AUTO_AIM_PID = new PIDConstants(10.0, 0.0, 0.5, 0.0, 0.0, GlobalConstants.ROBOT_LOOP_PERIOD); private static final TrapezoidProfile.Constraints AIM_PID_CONSTRAINT = new TrapezoidProfile.Constraints(2160.0, 4320.0); @@ -155,6 +158,15 @@ public Hardware(NavX2 navx, private Alliance m_currentAlliance; + public final Command SET_ALLIANCE_COMMAND = Commands.runOnce(() -> { + // Try to get alliance + var alliance = DriverStation.getAlliance(); + if (alliance.isEmpty()) return; + + // Set alliance if available + setAlliance(alliance.get()); + }).ignoringDisable(true).repeatedly(); + public final Command ANTI_TIP_COMMAND = new FunctionalCommand( () -> LEDSubsystem.getInstance().startOverride(Pattern.RED_STROBE), () -> antiTip(), @@ -242,15 +254,17 @@ public DriveSubsystem(Hardware drivetrainHardware, PIDConstants pidf, ControlCen m_desiredChassisSpeeds = new ChassisSpeeds(); // Setup anti-tip command - //new Trigger(this::isTipping).whileTrue(ANTI_TIP_COMMAND); + new Trigger(this::isTipping).whileTrue(ANTI_TIP_COMMAND); // Setup auto-aim PID controller m_autoAimPIDControllerFront = new ProfiledPIDController(AUTO_AIM_PID.kP, 0.0, AUTO_AIM_PID.kD, AIM_PID_CONSTRAINT, AUTO_AIM_PID.period); m_autoAimPIDControllerFront.enableContinuousInput(-180.0, +180.0); m_autoAimPIDControllerFront.setTolerance(TOLERANCE); + m_autoAimPIDControllerFront.setIZone(AUTO_AIM_PID.kIZone); m_autoAimPIDControllerBack = new ProfiledPIDController(AUTO_AIM_PID.kP, 0.0, AUTO_AIM_PID.kD, AIM_PID_CONSTRAINT, AUTO_AIM_PID.period); m_autoAimPIDControllerBack.enableContinuousInput(-180.0, +180.0); m_autoAimPIDControllerBack.setTolerance(TOLERANCE); + m_autoAimPIDControllerBack.setIZone(AUTO_AIM_PID.kIZone); // Initialise other variables m_previousPose = new Pose2d(); @@ -259,6 +273,10 @@ public DriveSubsystem(Hardware drivetrainHardware, PIDConstants pidf, ControlCen // Initalise PurplePathClient m_purplePathClient = new PurplePathClient(this); + // Set alliance triggers + CommonTriggers.isDSAttached().onTrue(SET_ALLIANCE_COMMAND); + RobotModeTriggers.disabled().whileTrue(SET_ALLIANCE_COMMAND); + // Initialise field m_field = new Field2d(); SmartDashboard.putData(m_field); @@ -486,9 +504,11 @@ private void updatePose() { // Exit if no valid vision pose estimates if (apriltagCameraResults.isEmpty()) return; + // Exit if robot is spinning too fast + if (getRotateRate().gt(VISION_ANGULAR_VELOCITY_THRESHOLD)) return; + // Add vision measurements to pose estimator for (var result : apriltagCameraResults) { - //if (result.estimatedPose.toPose2d().getTranslation().getDistance(m_previousPose.getTranslation()) > 1.0) continue; m_poseEstimator.addVisionMeasurement( result.estimatedRobotPose.estimatedPose.toPose2d(), result.estimatedRobotPose.timestampSeconds, @@ -559,8 +579,6 @@ private void aimAtPoint(ControlCentricity controlCentricity, double xRequest, do return; } - // Adjust point - point = point.plus(AIM_OFFSET); // Get current pose Pose2d currentPose = getPose(); // Angle to target point @@ -715,26 +733,6 @@ private void stop() { m_rRearModule.stop(); } - /** - * Call method during initialization of disabled mode to set motors to brake mode - */ - public void disabledInit() { - m_lFrontModule.disabledInit(); - m_rFrontModule.disabledInit(); - m_lRearModule.disabledInit(); - m_rRearModule.disabledInit(); - } - - /** - * Call method when exiting disabled mode to set motors to coast mode - */ - public void disabledExit() { - m_lFrontModule.disabledExit(); - m_rFrontModule.disabledExit(); - m_lRearModule.disabledExit(); - m_rRearModule.disabledExit(); - } - /** * Toggle traction control */ @@ -803,12 +801,6 @@ private void resetPoseToVision() { @Override public void periodic() { // This method will be called once per scheduler run - m_navx.periodic(); - m_lFrontModule.periodic(); - m_rFrontModule.periodic(); - m_lRearModule.periodic(); - m_rRearModule.periodic(); - // Filter inertial velocity m_navx.getInputs().xVelocity = Units.MetersPerSecond.of( m_xVelocityFilter.calculate(m_navx.getInputs().xVelocity.in(Units.MetersPerSecond)) @@ -826,12 +818,7 @@ public void periodic() { @Override public void simulationPeriodic() { // This method will be called once per scheduler run in simulation - m_lFrontModule.simulationPeriodic(); - m_rFrontModule.simulationPeriodic(); - m_lRearModule.simulationPeriodic(); - m_rRearModule.simulationPeriodic(); - - double randomNoise = ThreadLocalRandom.current().nextDouble(0.8, 1.0); + double randomNoise = ThreadLocalRandom.current().nextDouble(0.9, 1.0); m_navx.getInputs().xVelocity = Units.MetersPerSecond.of(m_desiredChassisSpeeds.vxMetersPerSecond * randomNoise); m_navx.getInputs().yVelocity = Units.MetersPerSecond.of(m_desiredChassisSpeeds.vyMetersPerSecond * randomNoise); m_navx.getInputs().yawRate = Units.RadiansPerSecond.of(m_desiredChassisSpeeds.omegaRadiansPerSecond * randomNoise); diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java index 33eed7d..6527bc1 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java @@ -71,9 +71,7 @@ private void stop() { } @Override - public void periodic() { - m_rollerMotor.periodic(); - } + public void periodic() {} /** * Intake game piece from ground diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java index 4d16213..d060b0a 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java @@ -400,11 +400,6 @@ private void feedStop() { @Override public void periodic() { // This method will be called once per scheduler run - m_topFlywheelMotor.periodic(); - m_bottomFlywheelMotor.periodic(); - m_angleMotor.periodic(); - m_indexerMotor.periodic(); - // Put note indicator on SmartDashboard SmartDashboard.putBoolean(SHOOTER_NOTE_INSIDE_INDICATOR, isObjectPresent()); diff --git a/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java b/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java index 0866e9d..62494c6 100644 --- a/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java +++ b/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java @@ -5,6 +5,7 @@ package frc.robot.subsystems.vision; import java.util.concurrent.atomic.AtomicReference; +import java.util.function.Supplier; import org.photonvision.EstimatedRobotPose; import org.photonvision.PhotonCamera; @@ -18,6 +19,7 @@ import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.VecBuilder; +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.Transform3d; @@ -27,14 +29,15 @@ import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; import edu.wpi.first.units.Units; +import edu.wpi.first.wpilibj.RobotState; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.Constants; /** Create a camera */ public class AprilTagCamera implements Runnable, AutoCloseable { - private final double APRILTAG_POSE_AMBIGUITY_THRESHOLD = 0.2; + private final double APRILTAG_POSE_AMBIGUITY_THRESHOLD = 0.1; private final double POSE_MAX_HEIGHT = 0.75; - private final Measure MAX_TAG_DISTANCE = Units.Meters.of(100.0); + private final Measure MAX_TAG_DISTANCE = Units.Meters.of(5.0); public static class AprilTagCameraResult { public final EstimatedRobotPose estimatedRobotPose; @@ -63,6 +66,8 @@ private Resolution(int width, int height) { } } + private static Supplier m_referencePoseSupplier; + private PhotonCamera m_camera; private PhotonCameraSim m_cameraSim; private PhotonPoseEstimator m_poseEstimator; @@ -77,13 +82,14 @@ private Resolution(int width, int height) { * @param fovDiag Diagonal FOV of camera */ public AprilTagCamera(String name, Transform3d transform, Resolution resolution, Rotation2d fovDiag) { + m_referencePoseSupplier = null; this.m_camera = new PhotonCamera(name); this.m_transform = transform; var fieldLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField(); // PV estimates will always be blue fieldLayout.setOrigin(OriginPosition.kBlueAllianceWallRightSide); this.m_poseEstimator = new PhotonPoseEstimator(fieldLayout, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, m_camera, m_transform); - m_poseEstimator.setMultiTagFallbackStrategy(PoseStrategy.LOWEST_AMBIGUITY); + m_poseEstimator.setMultiTagFallbackStrategy(PoseStrategy.CLOSEST_TO_REFERENCE_POSE); this.m_atomicEstimatedRobotPose = new AtomicReference(); @@ -96,6 +102,14 @@ public AprilTagCamera(String name, Transform3d transform, Resolution resolution, m_cameraSim.enableDrawWireframe(true); } + /** + * Set reference pose supplier for all AprilTag cameras + * @param referencePoseSupplier Method to get reference pose + */ + public static void setReferencePoseSupplier(Supplier referencePoseSupplier) { + m_referencePoseSupplier = referencePoseSupplier; + } + /** * Get camera sim * @return Simulated camera object @@ -121,6 +135,16 @@ private boolean isEstimatedPoseValid(Pose3d pose) { return true; } + /** + * Get standard deviation + * @param closestTagDistance Distance to closest tag + * @param numTargetsUsed Number of tags used for pose estimate + * @return Standard deviation of measurement + */ + private double getStandardDeviation(Measure closestTagDistance, int numTagsUsed) { + return 0.01 * Math.pow(closestTagDistance.in(Units.Meters), 2.0) / numTagsUsed; + } + @Override public void run() { // Return if camera or field layout failed to load @@ -140,21 +164,29 @@ public void run() { if (pipelineResult.targets.size() == 1 && pipelineResult.targets.get(0).getPoseAmbiguity() > APRILTAG_POSE_AMBIGUITY_THRESHOLD) return; + // Set reference pose + if (m_referencePoseSupplier != null) m_poseEstimator.setReferencePose(m_referencePoseSupplier.get()); + // Update pose estimate m_poseEstimator.update(pipelineResult).ifPresent(estimatedRobotPose -> { // Make sure the measurement is valid if (!isEstimatedPoseValid(estimatedRobotPose.estimatedPose)) return; // Get distance to closest tag - var closestTagDistance = MAX_TAG_DISTANCE; + var closestTagDistance = Units.Meters.of(100.0); for (var target : estimatedRobotPose.targetsUsed) { var tagDistance = Units.Meters.of(target.getBestCameraToTarget().getTranslation().getDistance(new Translation3d())); if (tagDistance.lte(closestTagDistance)) closestTagDistance = tagDistance; } + // Ignore if tags are too far + if (closestTagDistance.gte(MAX_TAG_DISTANCE)) return; + // Calculate standard deviation - double xyStdDev = 0.01 * Math.pow(closestTagDistance.in(Units.Meters), 2.0) / estimatedRobotPose.targetsUsed.size(); - double thetaStdDev = 0.01 * Math.pow(closestTagDistance.in(Units.Meters), 2.0) / estimatedRobotPose.targetsUsed.size(); + double xyStdDev = getStandardDeviation(closestTagDistance, estimatedRobotPose.targetsUsed.size()); + double thetaStdDev = RobotState.isDisabled() + ? xyStdDev + : Double.MAX_VALUE; // Set result var result = new AprilTagCameraResult( diff --git a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java index 364b82c..a8700a7 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java @@ -197,6 +197,7 @@ public static VisionSubsystem getInstance() { */ public void setPoseSupplier(Supplier poseSupplier) { m_poseSupplier = poseSupplier; + AprilTagCamera.setReferencePoseSupplier(m_poseSupplier); } @Override From c9065684aa0c52be815a4b97e21dc6cfdc509b35 Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Tue, 7 May 2024 17:59:46 -0500 Subject: [PATCH 02/16] Add URCL vendor library --- vendordeps/URCL.json | 65 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 65 insertions(+) create mode 100644 vendordeps/URCL.json diff --git a/vendordeps/URCL.json b/vendordeps/URCL.json new file mode 100644 index 0000000..998c261 --- /dev/null +++ b/vendordeps/URCL.json @@ -0,0 +1,65 @@ +{ + "fileName": "URCL.json", + "name": "URCL", + "version": "2024.1.0", + "frcYear": "2024", + "uuid": "84246d17-a797-4d1e-bd9f-c59cd8d2477c", + "mavenUrls": [ + "https://raw.githubusercontent.com/Mechanical-Advantage/URCL/2024.1.0" + ], + "jsonUrl": "https://raw.githubusercontent.com/Mechanical-Advantage/URCL/maven/URCL.json", + "javaDependencies": [ + { + "groupId": "org.littletonrobotics.urcl", + "artifactId": "URCL-java", + "version": "2024.1.0" + } + ], + "jniDependencies": [ + { + "groupId": "org.littletonrobotics.urcl", + "artifactId": "URCL-driver", + "version": "2024.1.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "org.littletonrobotics.urcl", + "artifactId": "URCL-cpp", + "version": "2024.1.0", + "libName": "URCL", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena", + "osxuniversal" + ] + }, + { + "groupId": "org.littletonrobotics.urcl", + "artifactId": "URCL-driver", + "version": "2024.1.0", + "libName": "URCLDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena", + "osxuniversal" + ] + } + ] +} \ No newline at end of file From 3d7d3d4e831c8617a2caefdad2e6f69aafcc46fb Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Wed, 8 May 2024 00:42:31 -0500 Subject: [PATCH 03/16] Add extra AprilTag checks --- .../subsystems/vision/AprilTagCamera.java | 22 ++++++++++++++----- 1 file changed, 17 insertions(+), 5 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java b/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java index 62494c6..dd72742 100644 --- a/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java +++ b/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java @@ -23,7 +23,6 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform3d; -import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; import edu.wpi.first.units.Distance; @@ -38,6 +37,7 @@ public class AprilTagCamera implements Runnable, AutoCloseable { private final double APRILTAG_POSE_AMBIGUITY_THRESHOLD = 0.1; private final double POSE_MAX_HEIGHT = 0.75; private final Measure MAX_TAG_DISTANCE = Units.Meters.of(5.0); + private final Measure SINGLE_TO_MULTI_TAG_POSE_DELTA = Units.Meters.of(0.1); public static class AprilTagCameraResult { public final EstimatedRobotPose estimatedRobotPose; @@ -125,11 +125,11 @@ PhotonCameraSim getCameraSim() { */ private boolean isEstimatedPoseValid(Pose3d pose) { // Make sure pose is on the field - if (pose.getX() < 0.0 || pose.getX() >= Constants.Field.FIELD_LENGTH - || pose.getY() < 0.0 || pose.getY() >= Constants.Field.FIELD_WIDTH) return false; + if (pose.getX() < 0.0 || pose.getX() > Constants.Field.FIELD_LENGTH + || pose.getY() < 0.0 || pose.getY() > Constants.Field.FIELD_WIDTH) return false; // Make sure pose is near the floor - if (pose.getZ() > POSE_MAX_HEIGHT) return false; + if (pose.getZ() < 0.0 || pose.getZ() > POSE_MAX_HEIGHT) return false; // Pose is acceptable return true; @@ -174,8 +174,20 @@ public void run() { // Get distance to closest tag var closestTagDistance = Units.Meters.of(100.0); + // Loop through all targets used for this estimate for (var target : estimatedRobotPose.targetsUsed) { - var tagDistance = Units.Meters.of(target.getBestCameraToTarget().getTranslation().getDistance(new Translation3d())); + // Get tag + var tag = VisionSubsystem.getInstance().getTag(target.getFiducialId()); + // Get distance to tag + var tagDistance = Units.Meters.of(target.getBestCameraToTarget().getTranslation().getNorm()); + // Get pose estimate based on just this tag + var singleTargetPose = tag.get().pose + .transformBy(target.getBestCameraToTarget().inverse()) + .transformBy(m_transform.inverse()); + // Ignore if single tag pose estimate is too far from multi-tag estimate + if (estimatedRobotPose.estimatedPose.relativeTo(singleTargetPose).getTranslation().getNorm() > + SINGLE_TO_MULTI_TAG_POSE_DELTA.in(Units.Meters)) return; + // Check if tag distance is closest yet if (tagDistance.lte(closestTagDistance)) closestTagDistance = tagDistance; } From 21b4cdf00dddbc458272e6d14e0211b6549375ca Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Wed, 8 May 2024 00:42:39 -0500 Subject: [PATCH 04/16] Minor fixes --- src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java index 0ccb693..b4aab4a 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java @@ -165,7 +165,7 @@ public Hardware(NavX2 navx, // Set alliance if available setAlliance(alliance.get()); - }).ignoringDisable(true).repeatedly(); + }).andThen(Commands.waitSeconds(5)).ignoringDisable(true).repeatedly(); public final Command ANTI_TIP_COMMAND = new FunctionalCommand( () -> LEDSubsystem.getInstance().startOverride(Pattern.RED_STROBE), From d552a561ee4523ad2dfbebd500e4904636cfe508 Mon Sep 17 00:00:00 2001 From: WillisBurr Date: Fri, 29 Mar 2024 11:31:09 -0500 Subject: [PATCH 05/16] Renamed snapToCardinalDirection to snapToImportantDirection for clarity --- src/main/java/frc/robot/RobotContainer.java | 2 +- .../java/frc/robot/subsystems/drive/DriveSubsystem.java | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 2fac5ef..07ab9b5 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -143,7 +143,7 @@ private void configureBindings() { // Right stick click - snap robot to the nearest cardinal direction PRIMARY_CONTROLLER.rightStick().whileTrue( - DRIVE_SUBSYSTEM.snapToCardinalDirectionCommand( + DRIVE_SUBSYSTEM.snapToImportantDirectionCommand( () -> PRIMARY_CONTROLLER.getLeftY(), () -> PRIMARY_CONTROLLER.getLeftX() ) diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java index b4aab4a..79a56a8 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java @@ -622,7 +622,7 @@ private void aimAtPoint(ControlCentricity controlCentricity, double xRequest, do * @param xRequest Desired X axis (forward) speed [-1.0, +1.0] * @param yRequest Desired Y axis (sideways) speed [-1.0, +1.0] */ - private void snapToCardinalDirection(double xRequest, double yRequest) { + private void snapToImportantDirection(double xRequest, double yRequest) { // Calculate desired robot velocity double moveRequest = Math.hypot(xRequest, yRequest); double moveDirection = Math.atan2(yRequest, xRequest); @@ -655,9 +655,9 @@ private void snapToCardinalDirection(double xRequest, double yRequest) { * @param yRequestSupplier Y axis speed supplier * @return Command to snap to the nearest cardinal direction */ - public Command snapToCardinalDirectionCommand(DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier) { + public Command snapToImportantDirectionCommand(DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier) { return runEnd( - () -> snapToCardinalDirection(xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble()), + () -> snapToImportantDirection(xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble()), () -> resetRotatePID() ); } From ef66e9d6f8ca865822cf8bd8d6bef36330c8d1ef Mon Sep 17 00:00:00 2001 From: souchem23 Date: Mon, 6 May 2024 18:09:24 -0500 Subject: [PATCH 06/16] Added robot defense to strafe and block opposing vision target --- src/main/java/frc/robot/RobotContainer.java | 6 +++ .../subsystems/drive/DriveSubsystem.java | 39 +++++++++++++++++++ 2 files changed, 45 insertions(+) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 07ab9b5..d863bb3 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -149,6 +149,12 @@ private void configureBindings() { ) ); + PRIMARY_CONTROLLER.povDown().whileTrue(DRIVE_SUBSYSTEM.autoDefenseCommand( + () -> PRIMARY_CONTROLLER.getRightX(), + () -> PRIMARY_CONTROLLER.getLeftY(), + () -> PRIMARY_CONTROLLER.getLeftX() + )); + // B Button - automatically aim at object // PRIMARY_CONTROLLER.b().whileTrue(aimAtObject()); diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java index 79a56a8..fa02ba4 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java @@ -4,6 +4,7 @@ package frc.robot.subsystems.drive; +import java.util.Optional; import java.util.concurrent.ThreadLocalRandom; import java.util.function.DoubleSupplier; import java.util.function.Supplier; @@ -662,6 +663,44 @@ public Command snapToImportantDirectionCommand(DoubleSupplier xRequestSupplier, ); } + private void autoDefense(double rotateRequest, double xRequest, double yRequest) { + Optional> objectYaw = VisionSubsystem.getInstance().getObjectHeading(); + double moveRequest = Math.hypot(xRequest, yRequest); + double moveDirection = Math.atan2(yRequest, xRequest); + double velocityOutput = m_throttleMap.throttleLookup(moveRequest); + double rotateOutput = -m_rotatePIDController.calculate(getAngle(), getRotateRate(), rotateRequest); + + if (objectYaw.isEmpty()) { + drive( + m_controlCentricity, + Units.MetersPerSecond.of(-velocityOutput * Math.cos(moveDirection)), + Units.MetersPerSecond.of(-velocityOutput * Math.sin(moveDirection)), + Units.RadiansPerSecond.of(rotateOutput), + getInertialVelocity() + ); + return; + } + + moveRequest = Math.hypot(xRequest, 0.0); + moveDirection = Math.atan2(0.0, xRequest); + velocityOutput = m_throttleMap.throttleLookup(moveRequest); + System.out.println(rotateOutput); + drive( + ControlCentricity.ROBOT_CENTRIC, + Units.MetersPerSecond.of(velocityOutput), + DRIVE_MAX_LINEAR_SPEED.times(objectYaw.get().in(Units.Degrees)/Constants.VisionHardware.CAMERA_OBJECT_FOV.getDegrees()), + Units.RadiansPerSecond.of(rotateOutput), + getInertialVelocity() + ); + } + + public Command autoDefenseCommand(DoubleSupplier rotateRequestSupplier, DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier) { + return runEnd( + () -> autoDefense(rotateRequestSupplier.getAsDouble(), xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble()), + () -> resetRotatePID() + ); + } + /** * Aim robot by given angle * @param angle Desired angle in degrees From 2bf51d00496b39782694574e27db021d6676e1a7 Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Wed, 8 May 2024 01:18:30 -0500 Subject: [PATCH 07/16] Merge branch 'drive' into develop --- src/main/java/frc/robot/RobotContainer.java | 54 +++++++++---------- .../robot/subsystems/vision/ObjectCamera.java | 4 +- 2 files changed, 30 insertions(+), 28 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index d863bb3..ffa07f0 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -101,6 +101,7 @@ public RobotContainer() { } private void configureBindings() { + System.out.println("fehfehfjehfuiebehiurghe"); // Start button - toggle traction control PRIMARY_CONTROLLER.start().onTrue(DRIVE_SUBSYSTEM.toggleTractionControlCommand()); @@ -109,7 +110,7 @@ private void configureBindings() { // Right trigger button - aim and shoot at speaker, shooting only if speaker tag is visible and robot is in range // Click DPAD down to override and shoot now - PRIMARY_CONTROLLER.b().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.a().getAsBoolean())); + PRIMARY_CONTROLLER.rightTrigger().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.b().getAsBoolean())); // Right bumper button - amp score, also use for outtake PRIMARY_CONTROLLER.rightBumper().whileTrue(SHOOTER_SUBSYSTEM.scoreAmpCommand()); @@ -122,11 +123,11 @@ private void configureBindings() { // A button - go to amp and score // PRIMARY_CONTROLLER.a().whileTrue( - // DRIVE_SUBSYSTEM.goToPoseCommand( - // Constants.Field.AMP, - // SHOOTER_SUBSYSTEM.prepareForAmpCommand(), - // SHOOTER_SUBSYSTEM.scoreAmpCommand() - // ) + // DRIVE_SUBSYSTEM.goToPoseCommand( + // Constants.Field.AMP, + // SHOOTER_SUBSYSTEM.prepareForAmpCommand(), + // SHOOTER_SUBSYSTEM.scoreAmpCommand() + // ) // ); // Left stick click - pass note @@ -149,12 +150,6 @@ private void configureBindings() { ) ); - PRIMARY_CONTROLLER.povDown().whileTrue(DRIVE_SUBSYSTEM.autoDefenseCommand( - () -> PRIMARY_CONTROLLER.getRightX(), - () -> PRIMARY_CONTROLLER.getLeftY(), - () -> PRIMARY_CONTROLLER.getLeftX() - )); - // B Button - automatically aim at object // PRIMARY_CONTROLLER.b().whileTrue(aimAtObject()); @@ -170,8 +165,12 @@ private void configureBindings() { // DPAD right - feed a note through PRIMARY_CONTROLLER.povRight().whileTrue(feedThroughCommand()); - // DPAD left - PARTY BUTTON!! - PRIMARY_CONTROLLER.povLeft().whileTrue(partyMode()); + // DPAD down - auto defense + PRIMARY_CONTROLLER.povDown().whileTrue(DRIVE_SUBSYSTEM.autoDefenseCommand( + () -> PRIMARY_CONTROLLER.getLeftY(), + () -> PRIMARY_CONTROLLER.getLeftX(), + () -> PRIMARY_CONTROLLER.getRightX() + )); } /** @@ -295,12 +294,12 @@ private Command aimAtObject() { ); } - /** - * Automatically aim robot heading at object, drive, and intake a game object - * @return Command to aim robot at object, drive, and intake a game object - */ + /** + * Automatically aim robot heading at object, drive, and intake a game object + * @return Command to aim robot at object, drive, and intake a game object + */ private Command aimAndIntakeObjectCommand() { - return Commands.parallel( + return Commands.sequence( // DRIVE_SUBSYSTEM.driveCommand(() -> 0, () -> 0, () -> 0).withTimeout(0.1), // DRIVE_SUBSYSTEM.aimAtPointCommand( // () -> VISION_SUBSYSTEM.getObjectLocation().isPresent() ? PRIMARY_CONTROLLER.getLeftY() : 0, @@ -313,20 +312,21 @@ private Command aimAndIntakeObjectCommand() { // false).until(() -> VISION_SUBSYSTEM.shouldIntake()), // Commands.parallel( DRIVE_SUBSYSTEM.aimAtPointCommand( - () -> VISION_SUBSYSTEM.objectIsVisible() ? -DRIVE_SUBSYSTEM.getPose().getRotation().plus(new Rotation2d(VISION_SUBSYSTEM.getObjectHeading().orElse(Units.Degrees.of(0)))).getCos() * 0.75 : 0, - () -> VISION_SUBSYSTEM.objectIsVisible() ? -DRIVE_SUBSYSTEM.getPose().getRotation().plus(new Rotation2d(VISION_SUBSYSTEM.getObjectHeading().orElse(Units.Degrees.of(0)))).getSin() * 0.75 : 0, + () -> -DRIVE_SUBSYSTEM.getPose().getRotation().plus(new Rotation2d(VISION_SUBSYSTEM.getObjectHeading().orElse(Units.Degrees.of(0)))).getCos() * 0.75, + () -> -DRIVE_SUBSYSTEM.getPose().getRotation().plus(new Rotation2d(VISION_SUBSYSTEM.getObjectHeading().orElse(Units.Degrees.of(0)))).getSin() * 0.75, () -> 0, () -> { return VISION_SUBSYSTEM.getObjectLocation().orElse(null); }, false, - false), + false) - INTAKE_SUBSYSTEM.intakeCommand(), - SHOOTER_SUBSYSTEM.intakeCommand() - ) - .until(() -> SHOOTER_SUBSYSTEM.isObjectPresent()); - } + // INTAKE_SUBSYSTEM.intakeCommand(), + // SHOOTER_SUBSYSTEM.intakeCommand() + // ) + // .until(() -> SHOOTER_SUBSYSTEM.isObjectPresent()) + ); + } /** * PARTY BUTTON!!!! diff --git a/src/main/java/frc/robot/subsystems/vision/ObjectCamera.java b/src/main/java/frc/robot/subsystems/vision/ObjectCamera.java index 36d41be..28895b2 100644 --- a/src/main/java/frc/robot/subsystems/vision/ObjectCamera.java +++ b/src/main/java/frc/robot/subsystems/vision/ObjectCamera.java @@ -33,6 +33,7 @@ public class ObjectCamera implements AutoCloseable { private PhotonCamera m_camera; private PhotonCameraSim m_cameraSim; private Transform3d m_transform; + private Resolution m_resolution; private VisionTargetSim m_targetSim; /** @@ -45,6 +46,7 @@ public class ObjectCamera implements AutoCloseable { public ObjectCamera(String name, Transform3d transform, Resolution resolution, Rotation2d fovDiag) { m_camera = new PhotonCamera(name); m_transform = transform; + m_resolution = resolution; TargetModel targetModel = new TargetModel(0.5, 0.25); @@ -94,7 +96,7 @@ public Optional getBestTarget() { avgX /= count; avgY /= count; - double score = Math.hypot(avgX-(1920/2), avgY-1080); // TODO get frame size from photonvision + double score = Math.hypot(avgX - (m_resolution.width / 2), avgY - m_resolution.height); if (score < bestTargetScore) { From 3509b0f16fd0e9ba08083a05d3b68e83e795121c Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Wed, 8 May 2024 01:31:33 -0500 Subject: [PATCH 08/16] Fix typos --- .../subsystems/drive/DriveSubsystem.java | 73 +++++++++++-------- 1 file changed, 43 insertions(+), 30 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java index fa02ba4..ba77843 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java @@ -658,46 +658,45 @@ private void snapToImportantDirection(double xRequest, double yRequest) { */ public Command snapToImportantDirectionCommand(DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier) { return runEnd( - () -> snapToImportantDirection(xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble()), + () -> snapToImportantDirection(xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble()), () -> resetRotatePID() ); } - private void autoDefense(double rotateRequest, double xRequest, double yRequest) { - Optional> objectYaw = VisionSubsystem.getInstance().getObjectHeading(); - double moveRequest = Math.hypot(xRequest, yRequest); - double moveDirection = Math.atan2(yRequest, xRequest); - double velocityOutput = m_throttleMap.throttleLookup(moveRequest); - double rotateOutput = -m_rotatePIDController.calculate(getAngle(), getRotateRate(), rotateRequest); - - if (objectYaw.isEmpty()) { - drive( - m_controlCentricity, - Units.MetersPerSecond.of(-velocityOutput * Math.cos(moveDirection)), - Units.MetersPerSecond.of(-velocityOutput * Math.sin(moveDirection)), - Units.RadiansPerSecond.of(rotateOutput), - getInertialVelocity() - ); - return; - } - - moveRequest = Math.hypot(xRequest, 0.0); - moveDirection = Math.atan2(0.0, xRequest); - velocityOutput = m_throttleMap.throttleLookup(moveRequest); - System.out.println(rotateOutput); + /** + * + * @param xRequest + * @param yRequest + * @param rotateRequest + */ + private void autoDefense(double xRequest, double yRequest, double rotateRequest) { + Optional> objectYaw = VisionSubsystem.getInstance().getObjectHeading(); + double moveRequest = Math.hypot(xRequest, yRequest); + double moveDirection = Math.atan2(yRequest, xRequest); + double velocityOutput = m_throttleMap.throttleLookup(moveRequest); + double rotateOutput = -m_rotatePIDController.calculate(getAngle(), getRotateRate(), rotateRequest); + + if (objectYaw.isEmpty()) { drive( - ControlCentricity.ROBOT_CENTRIC, - Units.MetersPerSecond.of(velocityOutput), - DRIVE_MAX_LINEAR_SPEED.times(objectYaw.get().in(Units.Degrees)/Constants.VisionHardware.CAMERA_OBJECT_FOV.getDegrees()), + m_controlCentricity, + Units.MetersPerSecond.of(-velocityOutput * Math.cos(moveDirection)), + Units.MetersPerSecond.of(-velocityOutput * Math.sin(moveDirection)), Units.RadiansPerSecond.of(rotateOutput), getInertialVelocity() ); + return; } - public Command autoDefenseCommand(DoubleSupplier rotateRequestSupplier, DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier) { - return runEnd( - () -> autoDefense(rotateRequestSupplier.getAsDouble(), xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble()), - () -> resetRotatePID() + moveRequest = Math.hypot(xRequest, 0.0); + moveDirection = Math.atan2(0.0, xRequest); + velocityOutput = m_throttleMap.throttleLookup(moveRequest); + System.out.println(rotateOutput); + drive( + ControlCentricity.ROBOT_CENTRIC, + Units.MetersPerSecond.of(velocityOutput), + DRIVE_MAX_LINEAR_SPEED.times(objectYaw.get().in(Units.Degrees)/Constants.VisionHardware.CAMERA_OBJECT_FOV.getDegrees()), + Units.RadiansPerSecond.of(rotateOutput), + getInertialVelocity() ); } @@ -1023,6 +1022,20 @@ public Command aimAtAngleCommand(DoubleSupplier angleRequestSupplier) { return run(() -> aimAtAngle(angleRequestSupplier.getAsDouble())); } + /** + * + * @param xRequestSupplier + * @param yRequestSupplier + * @param rotateRequestSupplier + * @return + */ + public Command autoDefenseCommand(DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier, DoubleSupplier rotateRequestSupplier) { + return runEnd( + () -> autoDefense(xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble(), rotateRequestSupplier.getAsDouble()), + () -> resetRotatePID() + ); + } + /** * Drive the robot * @param xRequestSupplier X axis speed supplier From 676578190121b43a336a470a78d8e98ec1876bf7 Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Mon, 20 May 2024 17:36:43 -0500 Subject: [PATCH 09/16] Change fallback AprilTag pose strategy --- .../subsystems/vision/AprilTagCamera.java | 18 +----------------- .../subsystems/vision/VisionSubsystem.java | 1 - 2 files changed, 1 insertion(+), 18 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java b/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java index dd72742..762b1c0 100644 --- a/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java +++ b/src/main/java/frc/robot/subsystems/vision/AprilTagCamera.java @@ -5,7 +5,6 @@ package frc.robot.subsystems.vision; import java.util.concurrent.atomic.AtomicReference; -import java.util.function.Supplier; import org.photonvision.EstimatedRobotPose; import org.photonvision.PhotonCamera; @@ -19,7 +18,6 @@ import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.VecBuilder; -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.Transform3d; @@ -66,8 +64,6 @@ private Resolution(int width, int height) { } } - private static Supplier m_referencePoseSupplier; - private PhotonCamera m_camera; private PhotonCameraSim m_cameraSim; private PhotonPoseEstimator m_poseEstimator; @@ -82,14 +78,13 @@ private Resolution(int width, int height) { * @param fovDiag Diagonal FOV of camera */ public AprilTagCamera(String name, Transform3d transform, Resolution resolution, Rotation2d fovDiag) { - m_referencePoseSupplier = null; this.m_camera = new PhotonCamera(name); this.m_transform = transform; var fieldLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField(); // PV estimates will always be blue fieldLayout.setOrigin(OriginPosition.kBlueAllianceWallRightSide); this.m_poseEstimator = new PhotonPoseEstimator(fieldLayout, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, m_camera, m_transform); - m_poseEstimator.setMultiTagFallbackStrategy(PoseStrategy.CLOSEST_TO_REFERENCE_POSE); + m_poseEstimator.setMultiTagFallbackStrategy(PoseStrategy.LOWEST_AMBIGUITY); this.m_atomicEstimatedRobotPose = new AtomicReference(); @@ -102,14 +97,6 @@ public AprilTagCamera(String name, Transform3d transform, Resolution resolution, m_cameraSim.enableDrawWireframe(true); } - /** - * Set reference pose supplier for all AprilTag cameras - * @param referencePoseSupplier Method to get reference pose - */ - public static void setReferencePoseSupplier(Supplier referencePoseSupplier) { - m_referencePoseSupplier = referencePoseSupplier; - } - /** * Get camera sim * @return Simulated camera object @@ -164,9 +151,6 @@ public void run() { if (pipelineResult.targets.size() == 1 && pipelineResult.targets.get(0).getPoseAmbiguity() > APRILTAG_POSE_AMBIGUITY_THRESHOLD) return; - // Set reference pose - if (m_referencePoseSupplier != null) m_poseEstimator.setReferencePose(m_referencePoseSupplier.get()); - // Update pose estimate m_poseEstimator.update(pipelineResult).ifPresent(estimatedRobotPose -> { // Make sure the measurement is valid diff --git a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java index a8700a7..364b82c 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java @@ -197,7 +197,6 @@ public static VisionSubsystem getInstance() { */ public void setPoseSupplier(Supplier poseSupplier) { m_poseSupplier = poseSupplier; - AprilTagCamera.setReferencePoseSupplier(m_poseSupplier); } @Override From ccf5bfd972ef7174d58b368b690853e9b33441f8 Mon Sep 17 00:00:00 2001 From: rachitkakkar Date: Sun, 26 May 2024 13:46:32 -0500 Subject: [PATCH 10/16] Update build.gradle --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 04ef164..5522ec2 100644 --- a/build.gradle +++ b/build.gradle @@ -97,7 +97,7 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - implementation 'com.github.lasarobotics:PurpleLib:0ed23bb51d' + implementation 'com.github.lasarobotics:PurpleLib:90fa55fbf4' implementation 'org.apache.commons:commons-math3:3.+' From f22ad5eb0f4d62772c17191b0854d758f3e0424f Mon Sep 17 00:00:00 2001 From: rachitkakkar Date: Tue, 25 Jun 2024 19:02:39 -0500 Subject: [PATCH 11/16] Add score podium command; update bindings --- src/main/java/frc/robot/RobotContainer.java | 22 ++++++++++--------- .../subsystems/shooter/ShooterSubsystem.java | 9 ++++++++ 2 files changed, 21 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index ffa07f0..88810b6 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -101,7 +101,6 @@ public RobotContainer() { } private void configureBindings() { - System.out.println("fehfehfjehfuiebehiurghe"); // Start button - toggle traction control PRIMARY_CONTROLLER.start().onTrue(DRIVE_SUBSYSTEM.toggleTractionControlCommand()); @@ -110,7 +109,7 @@ private void configureBindings() { // Right trigger button - aim and shoot at speaker, shooting only if speaker tag is visible and robot is in range // Click DPAD down to override and shoot now - PRIMARY_CONTROLLER.rightTrigger().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.b().getAsBoolean())); + // PRIMARY_CONTROLLER.rightTrigger().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.b().getAsBoolean())); // Right bumper button - amp score, also use for outtake PRIMARY_CONTROLLER.rightBumper().whileTrue(SHOOTER_SUBSYSTEM.scoreAmpCommand()); @@ -130,9 +129,6 @@ private void configureBindings() { // ) // ); - // Left stick click - pass note - PRIMARY_CONTROLLER.leftStick().whileTrue(SHOOTER_SUBSYSTEM.passCommand()); - // B button - go to source and intake game piece // PRIMARY_CONTROLLER.b().whileTrue( // DRIVE_SUBSYSTEM.goToPoseCommand( @@ -153,6 +149,12 @@ private void configureBindings() { // B Button - automatically aim at object // PRIMARY_CONTROLLER.b().whileTrue(aimAtObject()); + // A Button - shoot note into speaker from podium + PRIMARY_CONTROLLER.a().whileTrue(SHOOTER_SUBSYSTEM.shootPodiumCommand()); + + // B Button - pass note + PRIMARY_CONTROLLER.b().whileTrue(SHOOTER_SUBSYSTEM.passCommand()); + // X button - shoot note into speaker from against the subwoofer PRIMARY_CONTROLLER.x().whileTrue(SHOOTER_SUBSYSTEM.shootSpeakerCommand()); @@ -166,11 +168,11 @@ private void configureBindings() { PRIMARY_CONTROLLER.povRight().whileTrue(feedThroughCommand()); // DPAD down - auto defense - PRIMARY_CONTROLLER.povDown().whileTrue(DRIVE_SUBSYSTEM.autoDefenseCommand( - () -> PRIMARY_CONTROLLER.getLeftY(), - () -> PRIMARY_CONTROLLER.getLeftX(), - () -> PRIMARY_CONTROLLER.getRightX() - )); + // PRIMARY_CONTROLLER.povDown().whileTrue(DRIVE_SUBSYSTEM.autoDefenseCommand( + // () -> PRIMARY_CONTROLLER.getLeftY(), + // () -> PRIMARY_CONTROLLER.getLeftX(), + // () -> PRIMARY_CONTROLLER.getRightX() + // )); } /** diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java index d060b0a..3e2a440 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java @@ -82,6 +82,7 @@ public static class State { public static final State SOURCE_PREP_STATE = new State(ZERO_FLYWHEEL_SPEED, Units.Degrees.of(55.0)); public static final State SOURCE_INTAKE_STATE = new State(Units.MetersPerSecond.of(-10.0), Units.Degrees.of(55.0)); public static final State PASSING_STATE = new State(Units.MetersPerSecond.of(+15.0), Units.Degrees.of(45.0)); + public static final State PODIUM_SCORE_STATE = new State(Units.MetersPerSecond.of(+16.25786), Units.Degrees.of(29)); public static final State TEST_STOP_STATE = new State(ZERO_FLYWHEEL_SPEED, Units.Degrees.of(30.0)); public State(Measure> speed, Measure angle) { @@ -577,6 +578,14 @@ public Command passCommand() { return shootManualCommand(State.PASSING_STATE); } + /** + * Shoot note into speaker from podium + * @return Command to shoot note into speaker when near podium + */ + public Command shootPodiumCommand() { + return shootManualCommand(State.PODIUM_SCORE_STATE); + } + /** * Move shooter up and down * @return Command to move the shooter between upper and lower limits From 5ce4ef582ca1fccac5730f09d1a45837ba6b14b5 Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Tue, 25 Jun 2024 21:03:09 -0500 Subject: [PATCH 12/16] fixes for flywheel and code cleanup --- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/Robot.java | 3 +++ src/main/java/frc/robot/RobotContainer.java | 9 ++++++--- .../frc/robot/subsystems/shooter/ShooterSubsystem.java | 2 +- 4 files changed, 11 insertions(+), 5 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index e5eb14c..696c8c6 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -126,7 +126,7 @@ public static class Drive { public static class Shooter { public static final Measure TOP_FLYWHEEL_DIAMETER = Units.Inches.of(2.40); - public static final Measure BOTTOM_FLYWHEEL_DIAMETER = Units.Inches.of(2.43); + public static final Measure BOTTOM_FLYWHEEL_DIAMETER = Units.Inches.of(2.42); public static final SparkPIDConfig FLYWHEEL_CONFIG = new SparkPIDConfig( new PIDConstants( 0.32, diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 14a55e9..e56de71 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -10,6 +10,8 @@ import org.lasarobotics.utils.GlobalConstants; import org.littletonrobotics.junction.LoggedRobot; +import edu.wpi.first.apriltag.AprilTagFieldLayout; +import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; @@ -26,6 +28,7 @@ public Robot() { public void robotInit() { PurpleManager.initialize( this, + AprilTagFields.k2024Crescendo.loadAprilTagLayoutField(), Path.of("/media/sda1"), BuildConstants.MAVEN_NAME, BuildConstants.GIT_SHA, diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index ffa07f0..4d70f2a 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -10,6 +10,7 @@ import com.revrobotics.REVPhysicsSim; import edu.wpi.first.apriltag.AprilTag; +import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.units.Units; import edu.wpi.first.wpilibj.DriverStation; @@ -33,7 +34,8 @@ @SuppressWarnings("unused") public class RobotContainer { - private static final DriveSubsystem DRIVE_SUBSYSTEM = new DriveSubsystem( + private static final DriveSubsystem + DRIVE_SUBSYSTEM = new DriveSubsystem( DriveSubsystem.initializeHardware(), Constants.Drive.DRIVE_ROTATE_PID, Constants.Drive.DRIVE_CONTROL_CENTRICITY, @@ -101,7 +103,6 @@ public RobotContainer() { } private void configureBindings() { - System.out.println("fehfehfjehfuiebehiurghe"); // Start button - toggle traction control PRIMARY_CONTROLLER.start().onTrue(DRIVE_SUBSYSTEM.toggleTractionControlCommand()); @@ -171,6 +172,8 @@ private void configureBindings() { () -> PRIMARY_CONTROLLER.getLeftX(), () -> PRIMARY_CONTROLLER.getRightX() )); + + PRIMARY_CONTROLLER.povLeft().onTrue(DRIVE_SUBSYSTEM.resetPoseCommand(() -> new Pose2d())); } /** @@ -372,7 +375,7 @@ private void autoModeChooser() { m_automodeChooser.addOption(Constants.AutoNames.LEFT_CLOSETOP_FARTOP_AUTO_NAME.getFirst(), new AutoTrajectory(DRIVE_SUBSYSTEM, Constants.AutoNames.LEFT_CLOSETOP_FARTOP_AUTO_NAME.getSecond()).getCommand()); m_automodeChooser.addOption(Constants.AutoNames.LEFT_WAIT_FARTOP_AUTO_NAME.getFirst(), new AutoTrajectory(DRIVE_SUBSYSTEM, Constants.AutoNames.LEFT_WAIT_FARTOP_AUTO_NAME.getSecond()).getCommand()); m_automodeChooser.addOption(Constants.AutoNames.RIGHT_FARDISRUPT_FARTOP_AUTO_NAME.getFirst(), new AutoTrajectory(DRIVE_SUBSYSTEM, Constants.AutoNames.RIGHT_FARDISRUPT_FARTOP_AUTO_NAME.getSecond()).getCommand()); - } + } /** * Run simlation related methods diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java index d060b0a..87bded1 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java @@ -223,7 +223,7 @@ public ShooterSubsystem(Hardware shooterHardware, SparkPIDConfig flywheelConfig, // Set default command to track speaker angle setDefaultCommand(run(() -> { var state = getAutomaticState(); - state = new State(SPINUP_SPEED, state.angle); + state = new State(ZERO_FLYWHEEL_SPEED, state.angle); setState(state); })); From 4c56fc1fd093de0e6454043da3a47e74064d1a80 Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Tue, 25 Jun 2024 21:21:13 -0500 Subject: [PATCH 13/16] Tuned podium shoot + added everything on the driver station --- .pathplanner/settings.json | 2 +- build.gradle | 2 +- logs/sim_2024-06-06_18-30-56.hoot | Bin 0 -> 371963 bytes .../pathplanner/autos/sideways auto.auto | 42 ++++++++++++++ .../pathplanner/paths/Anywhere_Center.path | 2 +- .../pathplanner/paths/Center_CloseBottom.path | 2 +- .../paths/Center_CloseBottom2.path | 2 +- .../pathplanner/paths/Center_CloseTop.path | 2 +- .../pathplanner/paths/Center_CloseTop2.path | 2 +- .../pathplanner/paths/CloseBottom_Center.path | 2 +- .../paths/CloseBottom_Center2.path | 2 +- .../paths/CloseBottom_CloseMid.path | 2 +- .../paths/CloseBottom_SpeakerShot.path | 2 +- .../pathplanner/paths/CloseMid_Center.path | 2 +- .../pathplanner/paths/CloseMid_CloseTop.path | 2 +- .../pathplanner/paths/CloseMid_FarMid.path | 2 +- .../pathplanner/paths/CloseMid_FarTop.path | 2 +- .../paths/CloseMid_SpeakerShot.path | 2 +- .../pathplanner/paths/CloseTop_Center.path | 2 +- .../pathplanner/paths/CloseTop_CloseMid.path | 2 +- .../pathplanner/paths/CloseTop_FarTop.path | 2 +- .../pathplanner/paths/CloseTop_FarTop2.path | 2 +- .../paths/CloseTop_SpeakerShot.path | 2 +- .../paths/FarBottom_RightStage.path | 2 +- .../paths/FarMidBottom_RightStage.path | 2 +- .../paths/FarMidBottom_RightStage2.path | 2 +- .../paths/FarMidTop_LeftStage.path | 2 +- .../pathplanner/paths/FarMid_LeftStage.path | 2 +- .../pathplanner/paths/FarTop_LeftStage.path | 2 +- ... Note (Left_CloseTop_CloseMid_FarMid).path | 2 +- .../pathplanner/paths/Leave from speaker.path | 2 +- .../paths/LeftStage_FarMidTop.path | 2 +- .../pathplanner/paths/Left_CloseMid.path | 2 +- .../pathplanner/paths/Left_CloseTop.path | 2 +- .../pathplanner/paths/Left_CloseTop2.path | 2 +- .../deploy/pathplanner/paths/Left_FarTop.path | 2 +- .../paths/RightStage_FarMidBottom.path | 2 +- .../pathplanner/paths/Right_CloseBottom.path | 2 +- .../pathplanner/paths/Right_FarBottom.path | 2 +- .../deploy/pathplanner/paths/Second Note.path | 2 +- .../paths/SpeakerShot_CloseMid.path | 2 +- .../pathplanner/paths/close bottom.path | 2 +- .../deploy/pathplanner/paths/close mid.path | 2 +- .../deploy/pathplanner/paths/close top.path | 2 +- .../deploy/pathplanner/paths/far top.path | 2 +- .../deploy/pathplanner/paths/go sideways.path | 2 +- .../deploy/pathplanner/paths/shoot far.path | 2 +- .../pathplanner/paths/shoot preload ring.path | 2 +- .../pathplanner/paths/sideways opposite .path | 52 ++++++++++++++++++ .../paths/test 180 far path opposite.path | 2 +- .../pathplanner/paths/test 180 far path.path | 2 +- .../subsystems/drive/AutoTrajectory.java | 2 +- .../subsystems/drive/DriveSubsystem.java | 24 +++++++- .../subsystems/shooter/ShooterSubsystem.java | 2 +- 54 files changed, 167 insertions(+), 51 deletions(-) create mode 100644 logs/sim_2024-06-06_18-30-56.hoot create mode 100644 src/main/deploy/pathplanner/paths/sideways opposite .path diff --git a/.pathplanner/settings.json b/.pathplanner/settings.json index 6347820..77ff099 100644 --- a/.pathplanner/settings.json +++ b/.pathplanner/settings.json @@ -19,7 +19,7 @@ "pose estimation testing autos" ], "defaultMaxVel": 5.1, - "defaultMaxAccel": 4.0, + "defaultMaxAccel": 3.0, "defaultMaxAngVel": 2160.0, "defaultMaxAngAccel": 2160.0, "maxModuleSpeed": 4.5 diff --git a/build.gradle b/build.gradle index 5522ec2..be03304 100644 --- a/build.gradle +++ b/build.gradle @@ -97,7 +97,7 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - implementation 'com.github.lasarobotics:PurpleLib:90fa55fbf4' + implementation 'com.github.lasarobotics:PurpleLib:cf9cba2e03' implementation 'org.apache.commons:commons-math3:3.+' diff --git a/logs/sim_2024-06-06_18-30-56.hoot b/logs/sim_2024-06-06_18-30-56.hoot new file mode 100644 index 0000000000000000000000000000000000000000..9e1c07621912b084f6b0387666836f52f6de429c GIT binary patch literal 371963 zcmbrn`CpTF);Zm$oMnv!LJ#ba8*|4e^N4*yLwK4UETI`XUCxYD~lJ` zapV1I7OzN6L69YtVokUI$VYoOexqGbm1~KUG2<4KWyfV6Ipw)HRuzBnA5`sG+VhrF z`K;hXLe<~EOtu7?JmNVlOTq461eczijXZhQu_*NAYztC>`z~Y6dt(^~L#y%*Q$>0F z3L*8Q_%W)H@;@@zT(RUIH8G8pUmP@jrzO8YlWnAi^ueC$g4J~i->~-daF~{oikmCM zcizkoebeK&hjv@L-+FfStYdt$eey45d!BXbqfc`vS(4OdEhY0}CK1?<^Tn22+5_`= zmcHelZ!}V>@nP;9LeE_ITTJ{}nSYWgZSv(ziz)1e-+H1jK+#S_^t~uovLKb` z4;ND)w>GYoDkd5<%Lqh3T~?@Nw8huGo>H>c{*RkT0BgfnP_kk_``?JdtyM}StMR!{ zP5yREI-im?hhz}eY?};>+r{<+3sxDQ@h7Ek>#uFIqz}^WC8xU#*G_`!pcHrzUminU zCoKYC3;y;V4JffLNo0Yl9M#Ayrt--3deVgQBS zay4Y?&FSbw|k#5(rO? zr={z1UyUazO|JyMf}@9 za+B!h(lV-S-lB4jEA)>ySa8-)TY3#F=gB3O1{sNMY|;&PUcHDa)-jH_SU8nAI762E zM|c9lwf?~?T3WY`bE~PHuBqyDOa6}Hx5_C0@IP0k&=f`g5E8J7zKVYn{FQfyNfD!e zXN8j@7H{PFQGUj)7Lu1+RmM*io=?5B}s&i*g* zQbcF{)iT(ub#D7P_aFVEZ`+f__?Uk;P!ixNk%py_7IFZ`+MmsrJCZ_T}b=rbSYIABfrDg=} zTVz4rsEFS`Tb8rL^VXVp3hvfb4^vr{ci`nk1eYnR+)kp)Zcs#!?e_EFCJLVYuiM)xp>izr zQhs2w5K0#l>|;%F7YNbiZ2yF{89u_$M{eT#-n5D);D;9kv3$Ji@yFy?eCzPXG^pNxj)4EXg--^FE}L`9 ziNd~p{V%?!_SWkke@d}pC@QS)Szdx6FI5b{(M~vl;r+lB zrV@ubfufZP^LzcnA;Vk#;RxQnyb!^?g_Ed~qnZ(pNzL@mv9@=`A9`ixCbSZqfu_a| zYL62w&&NnPA537)yvqAe5XcvT2a)Ti1+%ukpM}*kY}RCwYzjOZVCzn>E2V@=y|Xg~3qC1W zK{F9F)vYF5WBI~IB(Hq#whkN)73?W0tk#;ZXr7&abbmta?fq4iMu!7WGK)dMQe6m> z9Lw()C7dV6&E_lOK_4?KnRuwzgfwFCg|!RF*4^~7h5W|UpA+cuKGqJf5Hz>{9m}9t z>sIK$Bf7djD{m*qq|F{%K+Rh{BAO`6R-HTq$M^so_6q;%L9(S++2L&9kE_seSRK|o zh`pA2v$6BpPrZ%K^w|&5u%8quoyUv{YppEmSTJz5K3=hNntv&~mj*4Wr; zB+Q(cxPkKZC$x(wPajD21H?jir711y*xO0kN8)Hr^BpPI&w-r#ZsQDAL zEDpNhLN>iAzKmc?9em#;*gY=3Z=y)rlNgBg^8!Dzu?jA#$j0#aUP3l`)`t-K=-Zxu zrF@loCp}@Q@t=mXVoI3!Ej{A&yPkVS4_?vN-^oa`JeaUczUv63XBxgN@)r}2!_1H&`qRY%z^f1R+=!c&IxIGoA zh<2(UeVd|3>}NcHu};5ef@+VMuLz_@eD5qhF{-Xdz6VE>v0x)bN2YhS5y&jZt&8{4 zb6tVq;Q&3lD*NhkuUghj>$s;KeeaE~T~F=E!Y|zYiRw%ybyrZGO1bSq)Opw+fFA4P z7k9!K#NuzF;zlNa6a5S$I2GAM#T{RcRSZ$_`gj+66jxR$fJlEcB$B* zOo&XHaSe>G_{?`<4CQzHOfZ|TZ{(1%aqhcP{806We55|u@|@S~a_le-QX41TH$W4A zKClnPJzJcnQ*pWP7BP&xY5aLG%Gk++c;-LJUqwyU-{O1>8OVcT$u{|EO%vIA+=BTu z@$$ZS1yqp7WPeYk^8^wjgjK?Xt~y*GtI9g%a!f2j{lbbyI%6(1C}6)c1rdlxoZcg& zI&9l8s3>-4dXSNEhSy>BEM1dIM$>}2M$Fcj!&pN`8PnAOBTw$(O2$T;jfr5gz5Hep zwV3|G6OI*eM~^`nCztPqV@PfXq#AO0v=Iu-RDDNnSGlDV6^>zTFB)ky!|xvTfN^?g zcQY9$_u2-)s5Z)A^fX^lMwQ#bKJ1f?`HJ?bsDFAnHe&VSbl@@A23G>)?DR4i>+aZm zLUr`w;_t8#jcyk)?SdAi)u`b!$;dKz%Ic}Obk2U|PqdC@S$5~F=Yy7qCVNH9^JJ8t zOl*bvv%?#p{t2!V^tWAYi`6+V=YC9p++5^!2o`q=5bQR71S%Lga#BIV5%4nwXj~{* zkVwPnDCrV|wu2t-7(`)4Dv;;T+4m>fdH4SBkV_%w1fnO3^*I2PQ>&68<%}dqNU>&i zA=OrYJ=Bfp4w=n6WXyK5Z3UpnR{hUJP^>nC4g&T3wjwK@{3lUll=&1G;kdl=@J2G4 zI=Qb1q;|gF1TsEiUT-0S#utr($dT!9yoTd{uITjbtG)gyIo2mT|CN~3N~C%m@>e7M zu(Ya}+5ZbJvUhZ$n;L(nEp=o1h{J?h@`6ihNJ3IcSTl^r0b-RnOcFjePKOx*%r)9;IkzXn+#x@i_j2daG$fE*>@TBf zXLl!Ck2UXOe?V!=&j_(#=ZA&K(8}Q|A&o}Hs}Z7`iT3tO1X5R7`#zMvCcCrhef$+(0?X#IHeGitR>lv4Xkx zJOK|g1)e6#?cX|0e)5o7+=E7%Us@No`m20;I{EndQTntfS{wVI!=fjZz3;}y)ZU*r zy5MIF+wEidxW?qQLU)utC*4)V@wT&kV3Vi%`}W85LzJxb=wkZ3R`pG7$_;w7VYJnR zlaU)=H%!Lz-rlmmP)@=a?&61$XV|?f;V^!d8@!o38FfLI2oXd4WD!0WW)|$P zAVll=+iphEQ(2^6?ri!ja@kSi4n&{Pw|kLM#11->Pe0Hc$`fzNusqap9PHNIpkWu> z5W;iVyE+FjMbdHP6uLyWQFwVmWPdn)iYLj_Z$TmD0~YvTei`aXBu&PP?a@#wvsy`> zvVh!d6q>d8as_6QSMoJ@=WLq-$CKrDzkoS?;m9ruR|oBlM0jgdX*D42OdQFjjykd# z+c3-LZr}FMfO}HH=Acp%!+9qG)jIfmkKPrZO)a91L?MSDkI2hWbp&Z_YiT4>Ci@G& zMapzpI6S9D?A}7k+cOU#W#fM{y@~j$PJ8Hs@9la3bK8|Tj;U8FmUTg1l|!S@NA~9> z$EmpK3-c8{IA^-P2a0peSESeVgOA^##>E4V-vPs%>JCt35SL--<>EdudaO@!T7&TX z?pxUu&StKf1*5MtY%#IXac*-i<~!}Z2~X;0@^a}h2&uq@i|V`u+y->6&nl^aVwZ01 zhZIIs8V`WqA?$)tuM5k8J_4Qi3rXCgCsxVGleJ_@7(vG5({}MNzU?al?<0#Fmf+K5 z^A$OA=XqMA_xEsSlMY8>7H6VPK+a<*R_6Rm5hfHfdhf63$V1TpmUt?+w?Rl+cojS! znXf3PKG7is4ZV}1M$8lVShGH+*V;ITnB6p*>gXsW_l?tZ{G{guKqc~gUIS$W!jnulVjT|vlljCT6 z7#!y^OZ|oeE~zSFH&x!+WLOG{Xm)W zWv_`2w6LcxjsSGA%F$R5l!lgH5mHUDNZ&? zd#ps22k2g&Y%Hr(@=hbBR?`yjcVJgd3j_9JksRCw$5OhOkle{c24L34RU!KIMnCYT z%@~Wsp`Z&qwg;Zg?)tw_>-EjWxiI=MtH4L0tlxV0+!Z~5;{F}eiM2F&*W}_n&6D0b z0Xp;NxZ^HZGnC9n&Mm_uw~3FevoqQ-p<=hRT~u9k{gVQCK5dOhp;Zz77{)})&~9?< zUQl}oj*QMcuz5FsR7|H_rA;yqv*1UoP^RX)JDVw5H*g2MsRKhVkO1y4P zX}SCNmz;h|H~*NziudSuCvN>6bihdj^MdGCXVFLEZ_`F~#H_qTH-WaMa}UT?GZw#z z{Dw#3H{qAT-W#9M?gP@_eGr`!nT$rG|<5!TIGDo7~|+2mK;hTWG$bTiX4k zeT2p2abXwb>xuDvk046|E8ZlVRCeWOvUNzV{OoIaR2y@#drEZ&#oK-$d=<6^D$(a( zyn{md(_^=iTh`pztpty?W^4Zo`mlAM`HGQ>Q;S( ztp?&K!Q>>Nb1`2LI;oKRj2@f6uhP9DTZCxK|FQVBjJ4wz{toS9WAx$OMe`L2xA|4y zZ7O@-d__$tZ?gSpLV6S1k0zAmyC{)Z&YHd`k+5i&28dr-YG@aluc)q(*NRPOGG7t% z4r3jdhA}b}6Y4U3PjwsJufQa-*Tc=f0IaL_yjofnh zO<*dQ{qqD(a&-ygP)x`M8r4(EI zlqDVdc9sV&;`5{;BD{he%rMc*GJ zzvN?I_)-m3jEYM&cx#ot)JIaljTXYE;XEE98}sqK|Dm}p@7M!{ztpQKU6x0Rp5WPV zKdiRg0kc+rR7bxn^UMpo7e@~%roPBPS{QC~WPX+9)sk_)+hwlwu}6ZRZYllZk5R#U z%C!74ia&GX`!H$;zB>uekiW}UStcS+8VoI9SU$&5CR7dA(eL1kgk^uTrx$b#8Epu^ z)&Jx)h0C*bPVjur@rtD1+SW7)7X;EnjjE~(*oB?HEF+`fi=W%}P$5sZZHKAJN?HD5 zgd1Yh7Xy-=X3JxM-*9q08ClJDLeP4E%|a?(evKi%PB2YQ>hS{NL&#HvlBeTmx?4XA zEx+i=kR+~v@j$z0AJN&{D_TWj^qAtQ2oe9tOcx+}wJ>lNVOQU%OGiVZ%@R*Ebl5fv z#^Ii_H^?aC)pejtLs6mF_0IsiU|C+%ipLfHo!lQ~opa?fi0{wxeh(y% zvwF1DQO_z)hE+AH)Kp5U%}~gnAn9>c5Xw7ETZ8cThr2Zto_};kBEmanF`^JI=8Msi zZDZ4QOqe?d(Yh^Y4^mL7^S=rF-Y|?P$}hNp2N)StT2V#1+x-kU*q`S0_?;5f(CU_B7UC8r2cpT9#9Qf9`lz<>?ib{o*-#v&uMsd6g35027{ zV~=8A++L21(TIBWb{;5{8gky`5O`pp>3J4XfMiao|-_kxN-Cj zvDqJc-FnAMFJh0=gxpM}5^yv!P>xf9qt0}LaeW21hr%VhE7&m3dBMkG@~6+u1|8z! zGtpFCo7fQtI`Vt`<3NXVXdEc+ITjfPV_a_;PJn#>FfSO7_vT>0dH$Q;p`0x)=TWC) zWdIZ_d?`lf0@3(g2uTxl&xeFmekS+|JfC)EpMka;?|9+x3cgy0gQkDl$HAc8wyq88 z=oMtFAWuPTM-e*TCPsU7Z&jJMQrbRYSFo9IB#9;WS&o9ThXEyg>LMeh|eqgIizJleBBK*q3R z;_MX5^Gsi{`HF7p>tB6$vW9-CmA>iyIJyVgWMl~a>D`aVV}c-hnChC;t&F!kVToDC zhnwlK>jzI4q?B(~C@A`sv`<2g`lClwZuHdk-iI%%=$5X3R&$b!+T~Tle5&)Ry4RWN zI4ai7l`w7%nRn4I`vaGme!sS;+F zY&yY5lKG0Ta~>;ZQBHwNY&*dF{52UVeRnm%CcbW9QkQbKiZ~vz*;D@RWd+Sb`7(4C zz#p3TC+aLWUr`ZF5k_ zDerqLpGzv!tHGzP_cTaeR`t6-<|aI~2@^hG{#=tL+;g;W3@tHD@d3cZzL--*m?qU; zhfqG+Fd9pIn)u#5XldJNC31$Y^93QY;F)N>plA&GP}~aq0ljzM_Rv#tuIyT|mH7Uw z)ihy6Na>rHkc}xH*lT7T3r5b_|LUluE^qXW!~hU;y#Z3nt=0y?^DWM88RZ<{)o8(o z-FR34@ga`!-3;tYk2|CDk7G;WxFW+I#r3AzBsg9ki75ebKD%;2oN+w)G#M+uX^H^$ zR8MIP6*nH{=AcWFDUeTv8vTk~K(S{U!ynb7&2P4oK(>2Iz{mF2vene3npMX^myzbr z?@*{F`mvk}@uDL#5#F`%Z%dFfdig*YpuZZjg` zIX7YiZ7TiPI4fAbY95qWX)}Ebjvqgla5##&3D7Ljxf&T zK{P(OCLo&JoDxXb8Qkh+Fmh58MP!uevSlzDIRQ`-Ut*A8L}L#64Ji$PY3l|yG)d>qAnXFE{Sof3>9jzgz}^i zr61|b(92ki^0HfUV3H(+9)!^&OM93I;m=qX2~3e6zlfu0=E)yd<4k=2!6-C4kWqRD z`kc!iMIoM=vjRDHJs*K+D}H7#fI@-~aCro2@588Kgm3F>!FisvHX|P4Wi2r^1WC2& zooKL}5yi^FkXFoNTebAJz#$v~$wh*d#E9U^p&Zb(^;bWLVQl2)Oq!g)@z85Mj+K+1 z{$P1)Su&0~{z)e<6bcKsE?1Yc8`-og=ZK(grtNBU8O=HykJ>Z04dYzU=a>$Ns14k<+Lz^@HjXU*=)%Vf%Q+#79r89Rnkpa+k8nQ~eQJ2IH$E zvPg7UE7E|ZyoF6@y)og~3KYt{9_>V)jXnX{2v?5BGQh`%Lqgn6k`QBK)e-fbTJCsGCLQ}4_4 znbqvKmt@n2!HYwF<50@w>!0(#rsCrXIRcuS z@%l_DMVAW?u^|OjjmQ?$2+_H4s3DdMH(Ef`a4F-tz^L%`wKtum(-&{dCWjM%5WcX0&9KHctZ zu#{oGqTS#(=zVCIl`Mx_7^bmyb|gqXbY2CLrPpn<$=Jub%a4I(WzFpXze`XnCnNXH zq8%{))E0+uZmmL2#`3Y~d6-f1^bMo%{A}0(%fW4k4J4M-RlXkryT&ER4eC6rXn@fn zA%sIl{_1QMjCaGVOE|i9)pC%;b*hgdk|JL?&VjKYs|zO;&wNFi&8v3uLvh3Vp5UW* z#AzuR8JdOTsKa*D+EVe+43QIzy=AHyWaOqe<-*8O9>uZ1J+|l|i2qYCDj`Jm9D6$; zYS;X;jK;?Ht6L4v75QqMlhWCN9e|XVHfsgcow{Wd9NU^0nV9g5yCawef74d_2zNta=4mD>7s%yp1dcg=aMHYrtNnr2_)-8QVk$AvE}wy_jNyPfzfc_Bs}wzS-5NMa>ursjuod; z#y*kld7$i&9h*ZF5;%?zW0n&+a~**){I|;zs-1iyM2b^oG{^o3t((cWITD>GN{{$q zi8h32;n|k%;79t+pyRPyBcjiXq7f~*aMBZOZ1}1d zXOiexITK6pj}ApK5ZQesMCa_uxNzvhdG?R+JY>G2+mlcqx9Tb9DM_uKLJPb{Fkp_>=v$`35NgCy9Y*&>o+REoSP{@lRp&NVw4h<-x92) zZ|p8K*>)-!{iK?&=#fTwc-^=3wsubacdzI_^GuxxYoqtAC83)$7SN|Jo3|>S(JSSg zu&8)4_ObeY{fUgjqP8@6PSgDQ9i^OR+#Lm-~AH)s(J2`9*>`%mBvOLgm^~&=o zu6MunMJ9brQ=(}5l@JZPZyunOugb$F=nZ*E$&B}q^3t&JV|qTi*ViJ zw;jHs2fPJsEd%soIDfX^%U`KbL`DAtG7dU^nGBrvM(-BF$!KzM0i^Y{`g$^&yyr!O zV_l=HhQOB#JnbJV)jJ-6;!MMhl?Z2rtRptcgO!(2$o9nc3V0gIZYbcn{#@AiR7kOT z_GT1nb@PxwvY&R?fcJjvX{N{5Fk49(JzbJB(w->{}?WtFOedAkPgch7|fuj7TK)Pn2Gy zO2(TZy=b%h#i!UU(?`3vVDS2_3hVLXIfUw(`=2PFnz%~>q+F5j4#D%(pX9;lcKN&W zR7Y9z=_(ivr(98d@>ZP^#s-5U2vK%t)Pp6@5693@z`i3;P31AqNEkI`sx_nqIX|@! zFl%JBOOTVDbvT)DR{AXVL_@{5YI`BD$Ts2kL|s;z^K|fe+{ei}cA4!NS~r1%oADW) zHQh13SFo*&@ht0NioVX9phKNt0}3pjqn4w%$52 zaw^d$Q!kIfl#aQ|DSA}vD#sSfg*d*#X1{jmTL_Qxcfj^0^sp!T5yM%-f9V?8oN z`#fR-Wv^+ab+cKMk6S6c+v%-i;3M5T5C_9(cAX7!hIewX*(2Ar92i~Lff)o-TAOD= zlZAe1bHQAE+Y022FXUr4xi&7@nA;RHp`NPqW}c9s^Q8U559q97D@)%;Apw6Bg?b!Z z?x9ex>{KolVr{Is1%2|1cLv}9yw|bS+WfosH$wEDtzVwQEhEBp{!{#dz-QH0j z*al5Y!G}=D#A(q}&f%f;Rn0H3Fw=($t%6slVwN=}sW{Urt1fuWxBQk$f9{rWCtBw>;@o&YAn{D1LPE&zy&(+!rZcR7q7KY(r8`Rqq#r^z?KwuK<|DH*WnU zf}Y3}?B6P=d|TArv+!hy_x$&EdVFGTZ3Fz|N-@g6$XK|W!sX(CMC24+*X(E_hVv3` zT^zJL*08uirxsD848G2bfI42}ZLJ{m6Ygsrfc{lud=@ad6!tH9+wvPec1dZGHED3z zZNemIacM%lzGUW$82aSOG|B$~>=nI;#z35^xLc4kSioLLNhMLtER4z6JJ%caO;ejU z!_}^p8Ah)44z)bE?iJ3q1Ag1+$4c~{wRK<-xhlGyuEN!zv7d&lZ5mHcnn^M@rjPKe zJ^87?&-qKnJrG@$zZ9Lavz~a;@QuBySI(ahO=N1Bz>TpgGhOg6C9EYo);m$6KAMMH5k4hrP>p(AaFDZwo zZJGObXvzC><811)a>nfSNE$8mv$`_&_5!J_>X;`K)pK^vUbuRGcK8^w%JrOgsD95Z z7a5vTXn5fm^e`v-1`XOV^sEPX4l!Sm_#8GfPLcTJ?R8lkGi9Fl6JJ~UkV{}h4kz=l1_Ddr68$KWYjy5S*%Sjx@XvMtj9_51?!d_xX_Mp zW=?D!R?l^RFOGvAuQ_srhYu#_K;=8#G+5p7B+f1v6|P&U&-1}|LGmk4dq})qSD6Hs z2YLbrF#7pL3=FBhJm3cy=bbKuXS9R;hnR;AzX9`*g@5n^CLc5P&#mZkeS1~}Et5{@ z9fNqWE2|Un%Nlu0h|tDM+dUEgysV@LNS~`sK(E@6G>jFi4>}A`*^i2GLO5zBy0fTH zmGhiP>tV7oAb(nb6dYCX1rx4GU^12ZJA=88@%MCxX zvCZ{)b8OL6QB+V1vNCH@AU)OF(~}|Ri{UyLd!oHG)}wshVI%bTnko4^G2Pf-Q%H|!p2v=kHYt&~am&`?dqxt^>Q9NV5M-A{Rk91X7TOHp5V^T&l!gc#AvxyV! z978J_eVJw5du|zTKa8H7-g_8H;QL`9%Gj`AD?~ckmzo5P^9>HrIBVMdJWOAyoqY_h zy_Z{zz~s5X!Fq12jx9&8 z`n}`U`*YILYQzuTJ{3WlW(0nni`y1wkh)bOh3KO1xX8oFWyA|#ioPS@z1jw z$d8LvKv2=o*k$OcqP7z43o^XyArp~5zXp{a_-j(oQ-k5f1?ovK(S=gO`8^3R4vC~qh@bAi9Zf0byMK=OD=q4ED0QPKzKvXyPp`g(QoL`x^57a0 zIc*hOQ(nt1lB?}M9WSG+fclhm#NXJ}_S@E>R&sVA{&IBXIVgJZkQ+q7;jOGhe0x0? z_4y97N3jukvB@7}&79>Q!Z=wS-wLDTyatuBX1S_RsZq>rrApf9j$WKR%_Rw4s8sc6 z0Oj{S(W0mF-oh7HNY%6jKY*!8Rd@xGP9>KlgVa^4^hi1~&g?|e?8#y&wQpkjimeCA zk=4T(is+^N8Mw}P_Z5;h<;Pwkq|5GZ|v(9-3R-$|S_(jZ#`9ThHincj!L3Pds5f+-y z-B<&ja+=DkP)Qnn2b36R&9|P0Z!Am4c_5l|k+_o=6r2a4gX1aII;GqmbOSzUn>J`aOwPz`piWE{qXrpbY=yWqT z_Ze=Ge#v}b`r1X*jQHJs9XMl^EuLwJPjYQQ`|8ixPhcGIPcB2!)h@MI68_w6|Hk;n z^1jDDungvpiRcD*M6<{0nd-(v`G`gvU%{K0Am8mD7oewc`+*vI zpR|!vA4Ko_jUGL4sfONw{_wyhH_OK}+P9*c;g~0hj>l_C;gdhDrFY3B>`R#~^zvrz zPlIWA@#=){`?d7S8z-*rRXn{M+^Vb2r1)~>j+7vJ$Evs?^Be| zdH4w7_j2|G6HZl%;5T6EuF<`T@)PUZ5YEZ&Y@=|w?>R#n0i86t{WG3k%N8E4+0jBT zioe!}qY`V$_$l4Nlaz?M2=aRlJeupC@7KDfRpylb&2q-*x6S@oOVZv79;7n zeP0Zcy04dl6pdf74)N#5`!XnA{ZW_U|M4f=TT8=d_(!KXXBdm4ILd;xXr zn=TNeto`;+P-Zeg^f9Ki+So+G8RR|};pNdA`W*xa^yIs&@8S-M?!{I7Cax#eqCo3tmM}5gk zry7)6p;KA=kI+c1Yikfsz?G+RkOAtBB&n4@!Sl%!V#TI(P9~_1=AYdS*SOw)TGv6o zy#ecxRIgnJs=rT^wYRLCfJ_vDUb|sr3LjfHdC9-T^XMdq2oocv zv{=*+rG#xg zbi0E4j#E}`i`!eMudHGD1M2JcdaEF0xmzF|jxx9j_-`&UB7DZvZiM%8V<6}5)t+l1 zXQsdi>9E~ZA7Uo{Q`rrqoyz#E5bN|;ov6q3b+=rgamO#&t27SpfRK z{lOP;a!Jm!lWFtnL*4lRrGKK$gX^;{4vsEXLUh?Wa^^t{PfWX46GzHZc%-yfG-m`)iZ9{xb%hN;*ps{rxj&6?b zLILpCO$CFhk#9DYA*p`nK~y@s^i2R&#?(epA@%GF)|D_;IiotGY_9~Kys=UA*=@RR zeY6liN=2JjJI=$AU6Qef{-}o1sq-oQX%B5$`_V7y@1@iW{;Q*$KHO;^@P9&oDQ3`i zV@fD}wv?w`b*Y>_Te6vWb(Q{rNPgMjlu-H<>UgKslU=gmpa*^6RGF9Xzf_5J@XeG? zsucZmT6)2yqdKZ{#SU>y^fZkj29tv%K{@IWC!z9hT+^ax8 zOS960KJz%2_jDuW)HrPWfeMwcayhl1nwP{1zC}yyfcPqEiIv?b?4*_|eS8amNifR4 z382}#%&&!6-ZdZElQ4>w3e_2Tl(aiR?}(%WDpdq^U#=1Btvv5e>qSq+@5;N-==sU( z|BzcggfoR4n)(ud%ja!FHab1e3`V@%S7ywoQk;19Vw4&_F=HD_y-Ixi989eo5x+~W z3WoC@kiymyNy32vGSiZhnLKtg6S)D86TX!E(fp6j#BRpA-%o=f@lWMeWO)y>|ns&jfpd zqAO?YvxR5jRM}o?X=LVGmFT|k$He`R+2Mr`;c4S){(?~&RMO+pGa$OP_~vb@BycLc zXhna0MGVl39^UK+`k2Vg&#As@`nC!y(gm3|C>1)!$|LsFE%#e7)8Uh|_W{4Cp}Yb_ zC+w}v2hp{P7HIP7vfBNKFJTE$-y`gBFV!!XeC2|XD8CJE0RDUVsv+Qib5{~}&(=3I z6G>Zp`aXf{vkcQ1;g=5jhk&Yy=rJrbSF7kk|DxELM={c!_v?X_v4C?CpfoBabRvu2 ze+!k`?u2%t(xZwf=tO!WvKf^WCT2D_!ZuDBqP$#3js;bVSR`~3mWV9V0LwpKR{6#Wsm;`nS9jP4Vg;ccJo9fz4=vYV7ixA z@(8YKSr$%-B&}%#Cs%HO5{I$Ao0)5ERN(X#>K`x-pi$KZt`CwnyY*O)o;OxaTF=Nm z>VKfppvLq+#9rm;qz-_RILs|VyhG6>4ms|0^#cehjGc-0$H&TwQT~JFT&SE;yeb~j z|6rndFL5G>VMId^H-wV=C@)R-!|Ei@+NnW#n?SE2l%Ehr{heIPfA&3qq@S6u=-iHP zxOW`GbNT6Y2c3plj9oQgf8HYz(C4cnN&s}@kSEBi=fvWK?4NgR3}>Oj>jE6Z%~y1H zGdvj_q}~}HEnkLZ8k}ag6)-(UOm_iu`+3$r9HoI@)T5A2?!F1&mt2@ae9tro25=5X zNsCcRP{Fk>V`C`?efrK6!1LvpR0B`{<$rY0ooui45A-gbzQhGA4?K=(glFAI;4OmR zIPJCdrjG*v#${4A{JRFz$B%-|AW2Fi6tj-Dl zk>ZnA1?)lhde{Cdpj58Pg+`?Y;eH?$Rra=_etKR3PMxe+PMTHYE_~ec7+qKp~Z^Sk$G~c(N(kgW$o-LX^+^j3A$kbELzR34@;QpX; z9(|M1sOmhv;iONLK z2;&djh_~?_V?Q0-SVP~eBx!sg$JbC5Nd#9YDJx6SdxE}4Y0QNsMEqANf=Ybh(h1)! z_ycmGzl!|u^;EkLJ*lOnBc@ATK|0yc;EU7-Tl)j3 z`LKGy8Fc?!y)vHS8>hJ?qEl6ZTO8sG<&{EwbycuSKkAF4mUp6lx8PP4ff9vOg`m^% z>Txx`NlR3ffv*B=WPad+rj}1t^C+o&KQ}uL-x=k?KLJpe?Rz#6D77npDuL*i`Z>Kz zUk+EEX1<~`qd%&`I;iQ{b!eZ{XIf9;0vpF|@J!vl7vE0EVH|Y^`d2-So%q5zw&O*N zG-sAO>I~j(6rg$6%wFJpRLBj4aiz~KjJc!O?-X(h1Je|UZy$FELZ9oDE+IsI{tN>X zEpZcK4}g-6pG3#e{h!ZA`Q)l9eRDZ_5;aAxz(~%y-He6KG$GIN?OFrv#*+|_^Lrf% zqSTl*(*x}bvRu}J6W@SjbSnO4<~byFn(9eK($luqFX6keD-q=<{P-pCyyxGW1kc}^ zoBRlAk8bZ?xVCnpdhhog3VbnGWn?h>e(uJBMy1mO`p~=B)Z78rEmNvYay3nVYXCH>bT!ccuZW9-oLO%;sUT<0F}@MQ zV``4?h9KG|U(CmxBmD;AiBU}i<5QG+m~VRyB43hGj5)J*b?}jOV6?=_=<87a30jiL zUtF>=krd@j2vT42rUZ=I-5*2$yw*PJHh#ZI4*0r_YpmPIKLM3F?$0i(!I!f6b&7$0 zWkD8NVmCWl`;79K2RYu`_a{=SH~zSQjI2PVe>K6Ju(_Cn@Tp#>Wyo1%kp4gAA5fhn zSH0hYNw^xmNJ=1@bnQvtzQ;bOA7e`QV|9YNXPsH--FS1xVHlIOnvFC&^<}*g@mU|u zdCBwGV zi1;0iy!o^c+#rV`(6>E@zkrORbs^(e6HV=0u>VivOWXJ)jVwB`Lqbx@7Df7qEE-#TwL^T=I4-3f+(SSw!L5QpH`!@!;i~iO}edR(sq; zdu$d-t?~2bTH`Zc=A(Hv?`tN=OBy?A1L5yA*jGYkrKdR7^J!^d28M6*qXxs{8+_hJ z{l=;$>-jjR&_4#ldl_E=M$4<1XjCqW!_B3Sz4SS_FYM3SMDWW+MSDVtW`5c3dw_2| z>hh4{Pc~O$?d6+RB?7(SNv{Tl?z67qE;_olekZu+2~N)kd#TZ%`9nIKa}Tk3Bex>H zge%jbyO!AZUzP#oC6A^7Ql*FQ6FBDhZ%L#!O+51zeO_{eF@e2HVh&&%K@5}b84n_m1Cu)lTpw*2>U#%B== z=5^qf&NIzJA7%6i!k zRY=-BKWr)DuL%QU5g&Y|nM3iSzAJ9PG!pPFi&`poIu)wJ%e>A7Ltu|BS#^4temrqG zCCsE!f|9r~DA8Taj9qaL@kO_8 zuBUiMpTewAa;6@3xL0T zlCg&XCR)#sc;oig(kG18(CDnPz-8MBPY z3wx?AMn@Nqx+I~{N8Q2{a#j0?%aD{2a-zMQfEHg**^l}$3y+>bDX(++u29+WvGg)> zRjl&~hO23+2LMbT&8+~XoMxvR0PwuFCmjHGw6l2-+QwP7R`zv1KfyI!AGMKO%YE!T zAc^Nb8SvEIl)>=qEn zZg{$uSYZU;?>a&R_SEi4hx$AVoXg?5J*+!{TpL}dbpcg>u+wayx@W4#LYkaZMvPzK z$5{uej9&hon5u7+5XXdR>BVlaI;?h&gzNJcej0MsdL7bOMHL#f1r2ly)~y4p1s!n^ zm7?rS1mXo#Za8Ml|G8>AjNL(8KJm}}G+KkE9zNL%q{gamgFtG|2n(XbfYx z1@(>Um~6QI@w;k0(QgVkA}*&%N#k>et>;A9j5C1R*P#rC(o~LD0Cg(HZ4oAwr)vzL zR#~&%L!q?sc^UA`>$dZS=Y^?moTu8=qGk}yV`=xowW_p^;LA6?)MHT?)0}nabmXQj z7x0xV5sb#vVl{wXWSbkXe9Eon^A!+kzAEGzddjKlI|^D^gKv9md)XFo?og~CdlRLIG!O>x8QG>S3-w97C{+j1Ifm+}Ny()v)|Wwfba3ay*7%2P|g9dM>AXXD&r*j@`o{KSiWm=bGQQwNNC z?>_6fyI{K%jEpz1phoWXd9{}Jh{80qe%Dt8 z6MI^v&#fx@m9Xfj-+ILNR_{bo)`o(kRa9SH$`LB4zIc|JiTd5bm=G#eUYOkrS4MTV z22eG@F$VO%wRbd>`tMoo^9xE%y08KPRoyruBvdTlpgcW(ryas_hHEizNJ^8EF>016 z=q-z6C;7z|dgG|QN%sXxIRvFPlQFtlCZ9)7@5WZwK&o#W@KbLb#a9abPl1*8X5kug zEl+RO)KGop%6J7@z3V7364fkkTlNV|WoE`purjGl@P+Hpo{{-fDyw?hZWtTw`(g>d zz>rjAok|(wH`L#n)SZd?y?^A_qW&jy(-7ZlA9MkuR`TVwRNu7xz9F8b!ah8E4P2)# z2bTltoc&uWF+lI9o^a)L`$WOD-98GaOlQPpgiV2~%-aaR%bIJ~!cr zOEzruwCYCY^BnPeb%!@X%_&9oi0{8+cMy|TKU7B%C2H1&JZ!Tx+HMNloH}RZBy{_= zvI9ngW61{8&(FP%ZRS?}WeW9mk59gf(`eP91Bf4E%OzAP+rfNA7XB1p$uDF`7~zNdi=jdClzhTy6Ri+USb?~VI`RB3I|II=2uhPe==m-=@s zV|JCQ3fl1sPlBLKmv~O_JgXL?r}}wn++g?$CeE_*)~OUw;`ulM`^j)WvkcqdcKLi0 z)Lc|^BN0584H8W`um^k0`eWf-So~LA$4%$=n z+oL7Z7dth$KMtG!qB~rbdw;DY@eB-p7Ym-QzAl5&V7{U;3sNeWU^KE%hWqG(Z~v^b~HTCXdWEoJFF-P8?9I z%{33P;tE~(2E=DvKfDo&@?Aa*rpKyQx8eSh((_F%m_9IAgZA@c*H}S`*WG}pA!|z_ z+Gpq{&{VxfcL+q?UK$C{=8OXDL%#nTrwP3_YJUVA$2t9e&|`(fddG?U|9E=)xTemm zYZ$^;_z)951Qaw00RmD8hzOQi2m}M71+^7h)DQu+Wh^KvI@W=ZKp=<-9}+EEKy+wp zEnx2swoIEuz<@|aofc<0oq*_Q%k)O-^uZb5d0rm&I`iN8?cd(lUVH7euXAw@Nz%C0 z3kM_9>oqbu#I)!BNh(zC1KVfhFz zm5h2H$pyXTmEwq3d_3o`Z2pt>-9K|0^;s^IMZYmMR7gjyp|t9gDGQ%yH)f<4!swAA zRgzI280G=viQH|D6kaUf=172~nNj!{4%!lUhn+{$5{cqWU9&yPw8>EL^$Y*3q|EhjMVYLQnf2tE z!&kpb>9w7jVi?P$wJ!tH3Y`@|d2HuRz*JINoJ!#`rOzHD`q=3paP}=9L5p}HzVDFH zVYRXw&9n`E_l1BUO_n}@6dXc&vY?OKLCappnz8nLPqbLViN>O(K9wubkBj0L=tt|H zoL)nE_IooaM3c$q;8D=D&2Y2Ae&N}rGW2(S&{E0VgOg-rT^6x`iK7wlz(~TB{1kNa zn)|OPe*A%YC8ckV+1ZQE8#M|0q1t0p#mSU@?1A7Cj5@6Wo~>nd;V_yXTa=W(eYQFZ zYx?sLG|$w5GPNh=)2^Uq)R-ol~`;sM9R) zjYhbuk`J7ES-A?3#NILuL6X=+WrC3uPrD$8HRXXp`-QFr48q1PQ1ACB%0;Nmh+Ov7I+fDIn956@a4%qBu;Ubt)vnL>$)(Y=B zAYW^|h};6FW;2X)*EX?HPRCCw9w|Of$E_pe)fIeiM z5#P~myOFiy3caS8Y4yAHKMRMDwhMl@R@0a8MEYENMBg01o)CPOgD+JKHXph|@0b!& zdPm7s{hA>E0lD&|9ffcW53BE`N9r{f1l8{>+_$woO5IJ$RKAgO;2OPU(l|Ih&!P8b z{#M=xps`ARq3b;yiuh+s= zwmGhtUQ}3xYR~WJB((O|xPxSTW?H@nq_9n=;=$B=b5Vb%??aHBkIsf`f2^FL>d?-) zhxm?=zpHm4o@LgCQM^M~Y1TuESB9VUhp{&J2AGabcnbPtRUs!pU(tn$A*v~lRYQMIb6^KG7+is}HlePMp0iaChUUI{tzFlfQ zE!w=cb(Cs~deiA1)-*=yT*32^@*MOzaj*l78qFOHcdz`cE25I}OaUH@b~RPil)b&H z)WC%A_fLmR|97x$3g6EX_eLKmX&tE9hWKfj6Vf}p^F%&@Hh<2ohImsC%KDi;Sz9OY zT^cO^81%_7;PVDjeLH6!Cf5N&VLfD$GaMWbN)>#&IH0XHmar>KHsbiZQGsBzC1fFk!{a5o8 zH&K&Z--#hF^{!ru_^f}HYbh10dR-CNGqoHoWp*h;RTZ|LpZn5pVD{A8o#(`s2c#}H%uSN3;9Mgc zu9-RyKBM#>n=z5*<`dg7J&!Gs!$2jOlb!*pR9(9TT-j{)f-CPj?;Hqls3^gr^S{u* z>}NU__|KAUT|$`Do^OQ1aru5|&*4b#KCu6+=qIE}8o9umaZz#%ZMgjhH(M6YaQ$aI~iHh5p zhhy>UACMds{yRA6)2@;vIBGaM{TA*-lFw&`=@0!pZ|OF&DbI<%fRQKopdotUz~K-% z8y{*%Kf$GWw||)aDBt@$^|Bj1;;JZ>D z09RRHR$)FpH;Mbg_&=0N{TrX&HyjuKhLv3Dain*l&%V*%14@4M_@$kySNjI@w_u(|g?VsgC;15Adi1fRgIou^KJA6{ zmprXmNh(e9W3iE`FxjRJDy>-Ahj}RMHE#e<0{f?*P)SK=d0(NV)`+OjP*Sl+^2Y%6 z>d|_%M9zEd0BZ8@lzfDiZ1V2_(%yPE1&~(daR7>cJ}n=hdZRwP3{Wj4jG|15PQ^^T z$0ZpCA}~V_&#giZw4ap9nt-QDxXXa%9h+5SkD9Ps+XndS+B`o3{MY(lAiXN^(WhYV zlVY+?FacbYIN7YvS}1$5!n3^MIDL04f={39GbDHyvK?uml(uzD9Yek zv5R`DwHIDTPxWW>dYPWu1sni=OKb8bwEy70W^ z)4vQ0E`mRY@1A3mlRsFy3$CRV9(=go$rM1S>hR4L3}0S|nrZ)#HEBDx32}mmDb+!e zMaD@FRXadE$QuTI;@~Z*fFEGnMVv^JZJF(4Bkwe9Tj#H6gI3H8ZlV=E7Ehz0Jcrdw zK#0q|Y|Jfp)c-V$ac8b?Mw&Ma4>0!=%J@1|IoEWFNiN&x0_bB^Y!(`l$4P2M`p$=J zbeXqueJ_k3H|!;nw42VQAUvt@Jq5zUf33z|qzu^Z!R$pL8(2_|$81C4eU1x-U zFedwe2V`S8uN_=O3hAAg$kQ#nK@b_Q50PW>#<%;)QLt`z!Q?Yl#E^sHz9_v2zZj(t_M`#Ry)yRW`a3#udU<*lM4 z9%tpAVcx>Qr)b+~BjFYZBS(Dcg!XHncsJp;@Yi1 zBh`kKK?|yQe|Gqm8s{UP8F{&;}88A`ReE)R;sCw00iI}REwdMYXx;5OI`x`1oqz~|} zSU5u34%O9AF)aI4#e`A9a_dJiodf2EfQt@nS%3PZ~u%O1)D^96fDS|zoJKn9`(W)qG!#J$5IMb zJ@~Yjgd!{ZdXgMn6YjLGAxBn6(z`@>S9OqzR#b+a<{;X#!S*urD01jR^lxv^px32| z*Z%-K-mY&F;koA>J|UaZd%F>M3Wr#i$Y}nUqr(W7@_DO?aCv)jArYQ=n;%QI>?u1i z5kG5-0*k*Iph?hbk83e+IkTc@s^tMs3WTGjS|pBsx&(p}2WA?m6wCY-fl+wzCFp*L zM1`8$HN$@+y8Gv^sQcxa=|d1%Txbw7^X!zPo|L+8iYk=;{*DEMx%T4JUkOiHbNvxS zNAm1J1#A9_HjmnF2{ye}lS?Q$N`=SS=yc*7Cx*J3lbk$GE9Ok4VuJY_+1t^DW&Auy zB7DrUjCT5>c0K0uac}Ehl1cxhvK@NzI(7%-il230_rLN?i3Q^?n4pRB)Af)Am_%9B7EdT=BhFy9p!9 z*?tfhEsy_&1($rmNcOjnc7TcSkuRa8-sh>1v9PNhu|pJc{+KQUAaviE{r; z54&=oUipbkF27v)iQb!77ft<@?uo&?|0NTre3{}8^bBO_n*RNyhWH|1Ea&c@`X#*` z@=`Y*ptm!lUYm#U&frwd_k0xZb*IJ zJxXY#$NC-~qBl#tlyB6qZZkAH49CC6e#?uv|S z3$LZLnd=M(XhmV*YxU$fBRwy~irWJ$hiJvwL%i<@BR`e5or*E55_`Uk{=R{MVg>n z)RT3i5VG)NgAS6)>?Q1T)EJw^{1Oyc5cV#uC^H0X11w18gp_InqXk{a8TQ~E;VRLPs2zzc;ecKc*DNj0IOCULk=WC%9??+x#Hdhlr z00FQvJ|e%evNY&cn7H(1^2_zuH;viacW3t_B3F6w2GldLEI0{OhZ*b<%~4oU^+;9` zHnZ`(8XHs}&=rXBuop;<4xti*Pd5qepN{tw1%qb%m?&@0R>j+cpz z@XGuZ72UP*b+F^VH3$p-tb7d7Z*>@h=*70Hs|cZ}>g;tw!$0TDBQ$)yGmi+9M)8^3 zgvb09-A}@wXA(DR_PVX`+cz3>lxFo=%f4CqUaGP{%T4-rd=+=(HFGlz@f800en~f`J<@l_{geAd_lFK z&ww>;JR>imCX0UbGBB;UbB2NM_Suw$;Coe__6Md2XT5}eovwXljTcf0LvA^s{Qiz> zJfun=>p=NJ&c?HSMEy|>e3QlZQneZTb10RPEskm?SBc2>@i2PoQFaBcPtHti z1FB`KUJTQ>X_q^{xfQE&B-)SQ>O7}!pr&+Hx3|E^J3Iqp>32`j6v=SVc@))>GZ_j} zV%E-r)Vaj<%Td&e`no@$DBhi?r%}|G%T}O&J^PPOk@~uv!+*u1m&*rsf~mXH55kBk z{s-^nfK*v^MJHVSi#e~8t5y~l)kN@(ZXuV@zqzKwB}nzFhed$z4UdeDY9v>i^}&^J zl~s5Kpw;e0?SXK8W0s9o*&(MgQI&B+0qA=ibQR%6foFV>X;AnJGD+Fp@_Ndo@p27D zxUY?q9-`c4^x%L`KuH^>To^ zZDn6Z`@Z8VUq^gIN*CInWL|8K_{rzxiJ;nJO%aT-e>GxJK6eQpGpR@tsj%pCQF0LE z+q|L^{j({#$jrpIO~KGa?A{dAB&+O6bMCiQ=@|<>V)Tz{iyIsBNT0uphQXk zn&5_`BX2!)0i?BI+c1&pfZ72hG7Mz*A<^ei6C5PB(W!obI&3|i4V_(HYvfV&Z9mymAiktgy^-RTpY(Krz4DY5g}`6>q~a5} ziiXOQ$(7|DUxb$CR%}}b*OaHjzlW=tTe+TG6>hnuAUbpF6W~{VbO)J|+-&=RbSuAX z8#?++N1%X^7R%PBz&LnkLns-!5r1ricuUIMvY`D09X|}+lj0X`KK!q6-HQGNHP6^=S^=OjJO%Qn*l@9xNLk;@uopb8 zNv{Ve+lxMd)DC^-u_$EHRGxDKpZB{O_+b91-BI+|&20*m>T7+1p&Rip<_;`+hob-| zN>9lMT)9m-YJgJJf2@P6$IN5~(bsObvxQmJC4U=I-OoJCbe>btgi2)vZ&V|GF6A+p z;zdeM!8lMI3*nX5>REH!Qq9 zdXd=C{0b${>-g#B`Gw~+?YLFb-JqPQi0Xuw&0_3on~^-#%IUTRKLl*?TIesCF-I zVVBdwE3vH8qD#Q9tX43Y%w_ArDBRqnnnhDg{`>pT6xPJx`zUJlIuy!!0P_Fer;b40<98I_P)DQ>?6yIsKOMIY z!zg*)3+%$?Q_GNisiUEXXlD1@Y(YW3>_#;qQr0GJ2hFLHn#{1*8^J7Ie*D3e5M<;dULG~HeZ@gJXtsZ16At`W zI-cI5-r3dMu(lwDFb{?`y@D3@I`fG)b>cbs87~NB~0TznmnRO9-)EO+sl&@~jXsnGMQA?K zE`_lmMXjY&lD^KOZc3$Jo;8Q~^gx$a;re*I@)WtUR{doLt|m9{AKo;MlE3y$z3;~rq;sTA?)x82}QuvYqnbtPR6gdilOpiUoR&AXTB_O z`Y#P%2T^V9^#uHK&m(5g$Ft>N%1mB~F$_`FL6|aSOm{zs()<3-nb~C~B5mQ?;iYGG z_)Xj);Abm#xe=&=p2$j2n*F#QneIhqYM)p6 z5=c!Q=^6kj%Oq-mno93r8ts!Zf$=kcDr$kyavP35M5+P9wo!_AVD&XJBi+Bj8AU}$ z-MvnYo=~1y4yH$1hfV1I^4HyA>@_*}lQGG06A#7|{RqS9sl5F#3Oz4jkBVb&LG`V6 zO@nm{#}j@)*vSAovlM0c?peQZW|-Myj(eHT49e$01LUbcw`=n>y)sRyxqB1F?3SH} z>B!V${nYDaI!A@QXi_-QKk`Nt-MLEtcgeHcbPTQ$?Lu#IRWEAnfU7dKC3>3PAkRK* z%%ylicmMvw^q(e&J-)n8{~!C<67gGjj^58d1^D-TyM_o<`7*m$xa#aeet~PZHSauJ zIYSu$)uH%cA3*I@$`n+7X-iNy{ZrJ$`>)0$+~LI#Fiobf2py+?1fKO+=>Vc^#fQoR z=--XPFGX}wJfCHI2d;_pUo+!QCnj<105Ux`UdjfiTV*p~pX1>79~f)fI(&(!peHrJ zq_6kf1WeO$6a8589k=2FLT^>_M-gsKUUZPy(~cF%N6FRU@Ri&71HN5j=dXg)>d3$g_-#?h#zSBbvd6}h(eiRpg{ggh`^d(nKJTvuO8xRPAZ<#<@W_rCUukn4QP$H=uKe{;!I#=FTWH(`HGXn2fGTQ|#Sf z)bCRX5-Cc(hcPCiKfZwR#g7la0U^sYLS$##=<~pxCdF?pGD+vJXpi%F+lb;-x6AfW zqRFL~GGT0#yQ~Hy!OvAKq(}4hkSVM=V{bAN%_eVqJ9sAKSDhnI1>$(56CVC=xvj zQbCSkv8mjWBKR9K+Ih?IG5%|v$l4d!OV*9nh9 zda8OGWdADD!w8X8?Ug{dvS)l17}-3=u|xFVH4)!MAW>8i_b+6WxchV?Q7e0e z$9D^_&9tH!esRFUNy+@NWVknC;o(UC%8ptrx-ahLPhTt?)UwL1_5qYV=T;p+MUPGQ z5~!pR(1B7VaKSrNr^e&gkgc(>u2hg8#8 z()Mn|w_X%(aXdHo%|nU+W_rT!|CEXvD2w?TNCo^+bkx&h5@QNCpU|2nvxtv1jqXtr0WQA%5HT3Eou@REkdJ=LlqyR`T%>cKLP*m%i5tx6Du|Y;uT)6{1C2v zV|m52Xlq@t7RKhus1h>viu@|U$=tz8MtqK=w;^7EYeY^C%}(E>c>tBVKmG(dasT5X zQaMX-$_IiR%b1yjOx7gH4^SdrAUgwzEIw{}3Rk}+PJwYom{UyguFq5}e@1+NOgMOo zKBGi-ZFHY(iYOf`_o)V@@*1x$xN7IGXvlkcmEei>k|G<;v(_xLhi7(ig%KtFU2J!k zC~bEtkb}~4-9Z^BJznh2P`a+9Y#8jT-7}dnOS3h?_z|lNJa-zr{!U2swQ0ow#pdr+ zq5K__QVjXTTW4jUZ|^<u46N975yZ*n#U3p{S z92k+e&wo^!HnWR|bfa+H`a*w@R3;u+5f7YKR`!2MbvoFoOHq=<|BMJTIuq>a0N47o zO6;5JBc1vK5On+y`wL=^&GSowt9W;X4(zQh}j z`ulY%$i#Z5st81-U-;-03T1EoCw3F%|CB0FQ)x}eAkwc6hM=XzyFDQ2^4BWggL-P+ z{tfb;O`LUuaqF;d0(->j+K$82{Vs9+pRp!KBZef)eYnAZZ`@cD5B8KD2F#PfYW|#n zs*gt$;vg{pod<_ONsj5p6;KjzZ4!eoaM_lF!RIgaehyBeIxWzdz}0IIg)VW~4fvUg zZC@jk@bEv8sazM=%ydL^@Cha&zHtoUn&(LXDme9w2lQ+2R4^S0Pl=@ihm7CjOrPdH zvv&tqixVJzK*1=dvarGQx~1nw{B0g({=J?gjH*R-Yq46;X4e zn&Qo$m9~H=d6?rK;8!V%3P9Al(Y0OFInIMtJLFIDlHVfg^)lOUL5gnD+DwZo6P&(= zQ4?4n2c~{V@wfq|Ya;;zU6(FWe28qIf0sTrn1 z+qj`&sD4v@E{xm_(HV?xGb+O&Jx9MDbdS3}p%TWz>Ki&N`qk|V*J)8_*R{ZzBYZy- zC1vG#4x{>I1L4$B^{)9Vnwlj0Um$yZrZ^JeUEW^N2rpMk1`+;d8mAk*YqaMgzNdUk z3wrNeRCATI!@VSa2B0FZ%JTqfTPW)%pnUzJYLKV1tn7m8hpkSh;o6k_6-LL!^X3|) z3d~M6Qv8^>tPGwJeYOphUvbnf7@i)MvPN`-cVCCCBx##dC!_tSvKorlhG*KssH?VP zcz&&&QCXg%AM-Gg9?k{O*BaUA@^lifo)SqePYKYw*5FPt*gF?d3!KGMDJ(D?CKNnSRsN0d-av+d+Af^sQE;_ZINfDim-98jja7BwZ$N*qxuDluUbGfck_WCkm?HW;W_ka zykCIkb6;~~Ar(8=6&t5^a}6IGr-Spm>>kqToa6E&q#Dty#Mn6rCksSk=|8eF9dWcQ!Dr#0cEb>CZJ{C^|81DRxs9?p^t3@QDRerYPvfzLj_@{4`v!SXNpdNm8vLub}cRPQ1FaebO2B%K*OB&Yax`?VjU&tGK9Zc+Kt=xrGQB`+GV2h!T= z-Hc8QagV^WRaE;MRJtLz5IaxOx%UoZ(c@RYiD2SS9)M2Ee-Ld0r{iA17(Rho{G3q~ zZ_t;JN?D3pDAH6G9*Exe4Mm$VJmS4M(2iI=7=%n?Yumwz^&a;mX0K*S3HDp`t_s`< zFIfud-O_=S0z3N09YfKMSbDXzO!ZTbEqy?|Zu=%U296w1z?1i>=01JMOf*|#ShR3h z(bjFf0Hbj8NvtVR6-M;%7mi8>-7RS>JvYrXuZ&$rZ^jBr2N>7odt~FZXh*Na>_`t> zr15s-sTR&((LEznb@OKB!ci${TW?<>y@J#5^#O!ld&Pdbi_q)+y<@SaOJ;5b0d@VL zJ%4vH{V&kUH)DZG{3N$#5xuTTT)YK~Hk#FbpyX<=_&PA{S!c|UXarH*w*ufQa(l%QuHMJoV3eiChQa7-NmV0W zX+MPgiSt(|Y2ZN@Vd{NUjA)~he;(1DQT+{w_6g5GNzbwksME6A#VV#${$eK34m#TQ6h}e>WEK4>4U+eKtHKeb%Fd6 z9cKv&?bs5epiJ_lCJo46btU;awVr?X&|XF*PR^IHXd%C%39jy&B~VFuS~?r9z7w{= zV9$>uzE3K%R(`-iylKwaMDW$26PZxS6xZDwElH|&WMndbMbhDx?HWUP_H%DE-(l^4 z1Pr6U_+U*3cMmDHjm+RIA=Y#*@)#Yf+eXZeP={{zpC z>yDei^YFNF2-;i1ZB(;*T}f8)(KPUuiwA5`5bUJ7zE1C&-nPpcG=qW#DPw z?k>zo){-sHP^d^O{f06*INKJ1l2X2nJ2Lfr;r=ScJM8*yVh>arzO(2mcFlg*{cshF zwf=AoNV72G=(zj`48-un#5uIoKAnT2WLuOrpl@eZ5_UMjBJU3L*=n~&38*_KQgw*` z?H6pcRD4^?NNVZ29`wX5Wq24xMXb~9A^NO0oo2yw*~8iukac(%-zIm;)964pYaGaiCrE30%Jg{{C&XRyKNdh zwjLaaz@qluhjAA(ao^bn_*PEn2jIR@_8i8>M^S^AJM|6bhSi-Ljdq%r1_#2kwf+ve zByDYsKttrNDkj{AeG*!9TFyh~d^li9?Q--Heafm%w}*bUlI6VZixGOlncaIQpNz_7 zVJ!xF3h&Wwu0Bc+RlX2#SK$YJy{Zi`y0k32)wgh_Xgjz+<`+6>?94o*KT3~uxF1DC z(=WZ6-fA63rpxv|LDUjpmHQmFGo*_)*lAuUrDj6@R zLMFp+4jbqdl1(Ig88Q_*^@w@D_yq0^>|8d4Y_LP|IIL$er#1# zv1ru@J=|B-2%9Mtt4em@45bpKx@|}N_Zq$ysh-C94NxkRSI7k>RbY!f*mpLkp{n-C zC`A;JniG;5{)iqIb;<;_luB7GG$X#175+0)-7g>#QiTYcW?qR539<;L#^{;q(07iD^l$hWf z=C7#H`sNfqI@PZi34y7zXbp@a>wZY0y!q86WOw|Xl7W;WSPtV}SwGXgEh*d~qO`bN zBmn!ym$DCo(spG&qiEZ-USPW2pmIg}z7Asz(7*4M9R;L@cWWWEp4pRJxcW7UQN8Y@ zM=%Pt{vQ?=)%}x&LQQU-_fS*2T)7tE0h|dlA>~%FebCYDp+BG|*~7PB8(rg&KV?iUC+V?eK1%4ZEHCsX zWy(4mo{v89TrS2S)4wy*cVp*CNRA=+4u>oEVol$M;1+6Ad(1vF!W*+gQ0K<#Ly(T` z1?K`JuL)*0BQJaBJTe-kxw!^#h^!Eja-A$^W&(SCReb+#*z{@rLRic)H_`r!I3 zs^$n>k6%~Xz;$&t2S}A4)oqTZVea}aD;=(#;*&gbRlDA0Gkf{cNEMWyJ)ssuC93T* zq>}C7V=qyg!e>$G(IEaeBr>%-|5X@A`BPPpj?6I~Mv<=wM2%&II#PCNn2#T`=_FTS z!jc>UT#(#gZ3lRvQp2NpNtQ(3rjPR|OqhKsLX2 zFat7sCK+TvHH&(2cO2^|If;%mF8vES;+QaYhWd>6;x;6+U$zaL z8mCu6x}4Fkm?7z#+>d)3%lqd+RIhXR@C0oTT7~XMpf~%Ss{qd_e`ihsN_%D}X%V(U zBooQLi&6WA+yo@|;(iQ0%z1vy^mA+dl|p)cvZtUVpFSaFbkH|%q^BAzee)uEq!T~f zkw>3L>2J$OkEH|9y*tZZdVk@pQ~uhq3kcWTNDjSEpXKT=6$LF@IMxg}%w5Eya`xBH zdg!w}9a}EeBhyFe@RSyAZ`6~qD^wc|PfqGEG9@{O{-KagRngb(H;`xI;H~p8Ua{nD ziKU~K=K3WVCtKw^$tV$ejofskCsGwhFQKOFsBaqKYW+k==v{B7*HiJV56x4S;Du*T zUZELva6FzLxB+WkF3cOEHTgCYAFSDu^jOKb=E)eK!sN3s`aknVyrA_f1>(6|_r1sm z&!UrG!*$)n8yQGd^;XndGaJ2*Pd7lpm8&IlhCEVJ?=hDG}+wV{Sx&< z8v9-r!mYoL3ztkH#oBxQk9*K0xTMYop zPf?@Lq+S+U_X!ItvN%J#XhjxR|AG-|Xm=h6aSJ+~0Yv>7k`RJvs!e;03I_#9#V z5kUG^PqmUDskg^wq4BI`C9)yXh)(Su3fJ*f)vZ9kB$(R>jeKUqhHDqch7Z?S^U9C0 zYDQ^3lsD<}yGD%2_j4DpMW`cR5e-wS>|>c&RKnUHjgsQO&qGIyiXqv zWgS)n{IL9ECjCPfu85>#yIGTnOu7e~dXY)}@&qzCRP80d74_KH@|26mf$Uj$Boq+fn zu^x(Wi0v?7zA{1}YGz4sXOVYP8EcJA)S%|XhUD~Iugd9e_6b{^l4idM{C z!-UF3zlWMi^;=-GX}xQ}7bmsdHPDy)SO+?aFVW+ll8mK$@M9y~@D6y2jgp#u^h#>k zp^GqPT)5(Om(Cx2-RblD=uMC3z9(mB(cb#y&UfjL*!9PR8T6>ca$}<(GUfJ$UXP(y zQr?!oX5h<{ct=*zmj)FFMZOFp@96zp!laB*6-LvShCM6SZM;MeMb`R_tRiEpT>K5K zsm?iUP|z>sSif=Kg7mjb_5GhMoYS%#JIzKDZFk6lNl?-eMd`<@>S7Q-D@sYA>K%gB8c?bfpPvI#*$vO%!F5Kvtrn>oO9zlj zz9}Xasp8waQNASnY8>Kob}!k3c$Z{VJc#zyh?(wH@V-F2KR2bBy638Inad|qLug4_!qWmWc9u@wf-&JK3mvVk_R#_7w}o7+saL-wfS_!0>sA8ivVbDsWZ8N4 zf_>|5)*6)LFH#H>rl+FZVPrabSey$?H{62(RG#dZj5-fnbVCr)B4ncA>wi!s@FRRedn(ew64c27a zZf+r?z^fw;G*78i$gb?tb&07VCi}J37)M=V2p6t?SIW?3_ON#sGWoh+2Bz?UYyjoB zIoQK^zpbncBkrHZ^v;^>A%?4bTFHT{A%~-c>t&;=21sqiZ3>bOYyQJD%x*Gni<)dg z{!*&xT(oXM>LrI!cM;90yEr}*-lQed!d=FG|Dq#lX zS(3w}NO}XlifY8$oN^xlCHHQZp8+PDnOPG_uY3NA>HUsEl%y!>hH?c?PH!VzFp+o? zb#iAXpc0LKu@4%0DkK4(2WC`NNYs+~1g&p(X{v)!?yTEQ=y?L$13<3{T)_p+>!t#s zM|GNw3l@EDyr1idm0Ozgo$Qee8$+lIN5_Lg*@ch<(b5@zlW45G{8TYeSb>8hj$)km<0 zAUw(PnHV(mfOQ`d-Cp%!Aa;$N!H4o7QRlF1jBS6LG6*!g8=j!f`|?&u)VAwnB!x>w zf0>J>v71namBVu=D~Q>&uDYaP)6iW?^aA+Xo=NsdZ%E-l4{C8*Khj$oQ^JwHr8P*8 z{U!J_AySq5Y^X<}?A>V|aGgHH!7Zyi#VHDvHcq_e2&f*vi$+Ivme212>g@RGvuH_; zO9PCZS@{?-t+qbu1}RrBiGGB5%XL#M@NaSd9Ln$AB;JGgH2Z^t5V^Z=4ir&ZW%346 zRp}IS$8s9NG_o>k|0$+Brv2{A(6ei<#Siq!H7#7w*Y)@ab0fI)H>OVyON+2(>5R1i z9hJD?&Yrt8i-Y6|x1)m=o>qvZH@y~)8tRyw+ErwmxjqoLh0ZVjxl{d(3&#S!bLyrH zdM4AAJiPZ3J-!ji{BBYFfWtse9{nb{wcVhF>)ga!h2-jb^4;z;tc9=gF>Z|WfN@q8 zm`lHj-u|hVBaB-%`x?ko&i=SBgPs-)j(n)J`cF%PJmF2eKFkEH)8;)D(Ih9>} zER5Eb*|Au(TA9Band1C1qNvi=po-8-^sIz6mR}jVa8i>?mIxB%DKxfAb+CJ-WmA!s(9su-&OHmzk-+&T{x8u zrtBvZeStsMpAD$WCQdJ!VqL;I0#q&BGEZ`q2694Rw7*(mhj_!Z)ksZo*theLoKoE` z{S%WvU6^}|pz6;GFQX~4_5NXi%BoIQ18VUd?hSG^rL3JqRk~Zr!N~8zIRpH+^*dxl zwKnm-I*+JU2F=(5zrpUj98evjX2rz6N~^CzQ$<@7Kx#(jQ#pmRxWA-8rz-h*8N%hV zyggJ?r_M5pLLI$|a>;0^VMPE_$`@WuXy4flStwL|az!emshR5_s&rJh1R;YXn$<=gc+Kw^=0z62Cd%*`Hf78FenbOV>*=I+0KXh zC+pqOQgx|+t^({uUCTuICH1aB$W&PN07bFli~0a6H+_9J=*uZlG2OGzcmPc%o!-~S z%tS{_4C?o7tgJ+%U!E}yqtQ<5vO$%_QCSB5US_jEiYV9KAEdaY8lz|?OirPE;ZM%>U=O2zHvLkXJ!Q_Y0Y*{`t1-_KbGGF z^-BW^fnO)_T8&g$n)X5D*A%YzL^lxgBD`w99n=gAL1Kf*Ot z*v`!Bp3X3O-n3KzP(NJcn^9EwdzsicteuNpP*g{ZOBO(F@8A!UtHT=Uab`PRGU|g= zr4CXJHN`BfV?!m}zm$a&RCUHteLksNvh-6Cvqw}e&qt?YR9R?>>=dU4`K_60nEckx zdQ850vC_!&l+6OsPy4!2eaF*5OcN_GEe7E2g?Ax5<0IA*MDs3mF*1pNmW{dNRXS_{ zqJ)^W!2ZtkV+K&8Bo}M$+AJCYAptUHV4txKEoWT6&GLfl*V!6|=8K6dU>tLKhP{B* zu|a@_c8BOOpDw<7+=y*=r+9$mIr;7nFrU$d)2Mx-Y2_$HVw|cu2=u)VLRVu^pM;AA z*k9N9XJ9MJQ&%{{mE(616Uyp~`VK^C_zk}S(xqn#k*eI$@i0RF! zmX%o4?Zp(DtQmN19Xw;xVg^b1{F;>AAWFWZpADoZl4_x6{<*I=PW9Q5f(dm`2p8U5&G5yg8BlKyjz>#Hpme7ZrT!k$L`dZ%l zWOMa)I&TO&xU1+3cs1*nMqQWD6vNFY$&+>F_)cGF>+rS6#onaMt76 zlol|q!|~VPdM_@d8I0tm>c1h^+&iM#Gqh@_&ToK>e3#%0h-WAA%aPw!ZI42yR!Y67 z9}X)nY7`*KyG<2EjAn*3is8x$EPI(;r6N`@D&^}Mc>v{+=4=M}LHCP6-(%6s?j!Vh zGo3Qosem5fy;}6xNUrMlS6v3FeMRckAa(L-vKpj@p6F!w=e{)wMI2Xb@Q16-mw9M@ z*`DSMK$USrgiu*}iw^m%&8cGGPv2(`{I+jo9>t>O=|4}d=9ao~rvJ4^a~P=6r(7ASlyaL;l~-gt#LvAEe+dN6#ouUz0DSz# zxuic)on0^rDD#qA(CRmNl`z_et*@d*SsxrIL94B=`TKzCNBzaQ)K!V^zfS{cTdRC6PMdYwANywk~|IAHGNe zM;ql+1y!U8@r{JBw7seljJO`#i|lfX{bew+(@@p~pnaw3qXaa`;k6;?T*Ptnr%Vo9 zlQD{hFYPi1;e{G+B?y(IhTcS-{i1w?>lQV|pw8u;9SEQQ0l+cDd(K~xb~&%7#-XGY z`6_g|+}-mWJiVgEhDgv-?yM4m77HQ`K>rulJStxN&;cY(sM<=A+&1|s^29ZGZ-P;0 zF=I)GTwx!Wm#sH1gPKOgYCX8C46Q}Hp&?s=_!HGZ*y5C{8pPP*X7W4=zS3Z1++$l+&pz z0Z*TM)z=|@()T(#!e#9)MMpGNS1#dq{rote*-la~cOX@3Wm6+c6)XL-;M$=J947V$ zyx%$ws^Z2cwMfMl=?jSdMBAV{h|f#nZUw0RG-ahahAM&B$c- zNSldh6vbjUW5g80sTf;%&@wf$n=>~<5Mhm5nLPTs0ODEd`(zx-E7y7zU`cga?jZE! zn;VA>&MI(Qk9cMI76Ub3VAo0U5%Ad7`~7ONo-luWEmL%gIeW)zjqZFtav@_(AEzePGT z&41}5`fN4Ecp{bLOaU{b=WD)%B$IX&e+TwE$GdSai+XeY=P;HH6f{%)lG^cUW}?y$ zUx7{siyzide%Ee|Xb&~NORG5m{2e)=Xq4<>x-%v!sPsp8`fltx0nfaoTPA|fwSU_k z#@+^}elkupC-7h#o*ZOu+BM6V+k@i=Vc>cFy4T^Ty83Y%{na`>e?^a1ES$dw(bER;;VImndVYw7j$BFL?DGmO0lE^Z^^gt=*F8l8aD4;$-+3lEXvrW)(*7oLqIWqtOn zo<7(0hrLgN=y_4xmh7-JI(`MPI^fBDKPO*E$y+S1r+Uxg==-0y$IJ>3tpq- z`fqNX7vdREZ&zsA!db~u;rc#c?j4W*|7m*nsHX1heHcOl;i4uX+ypTR0m4NL7ZuQ2 z5)up-<>C!3VnDQNX$wjn>`)6Kfk03bE{cj45glwDi?q{XOD#muV5uY2srVbG1Bezo zzB5RjF52A~Jv`s?4g?$V zy|QE^PdC^sR8Z+gqaUigTojy2+4G!yyQEZ+t?DiZ6|u!RW~zOd(-1_7vgLb_r%>$4 zM6dZc8^#Q+?rSMMY8qg_k36INjcJreF+Xzvd87|-B$2V=u&*yXUvO`1A!A>qwgn`O zn!Wb}kzY;ZaY7_EE-68Szw!J6*;AYcKc?)~OXe3Tc+lqd>WAoC=k&QyXL_USuyP-| zVdpXk%_K;rhv50Caw3>KSxd7@Q%GIf_UT4sR~|Ts4x69OXz=W>PVfW5KahWBm zf6ZzrT-SZ%C>m!F{E;eB%Nj>hDSZ0kg3AcE{x$}jR%_x0)PAJ817+r1H(sPNCC*7{ zV5u?iHBX!we7_5jjGl+jk|*obZZ}4B{j5dg$#D1)84+YIBjb9op8@lBg9X|K4Rq`h*o$UNhuLp}abHwk6Nx)R>b?n5vYo9;fautJxe#5a$hR3B zuejffW{%%T;DWi(Lk1{b?7O!E6&YHqQYe#p`Q`J>Y!xk83u9raDwR51*c-5wjE47a ztI&3r;vglAa{G6HzQd(sJ&c@6EwYQf+0a6Q>@O^|=&g$$Xy$aFu@s(pihg*S1*~;2 zE*FoXqRjtRD5>_m+H4tWpB4#|;K^0y!L#pZdJX!a`n55eAaM?UraeZ4)^&0|AY%-+7=(1&&NzdI?3YL4cRck2y z04H(;ERPy3>p+vQLn(kRpEYa-(CD3f2uG9U$w%iyxGDuz&o569GMz6D2qiJL{yS*{ z!k4D~3W;g^84kz|m?GCQ@X_zpPoi`$LV=2o2nyz@h|ArRT6 z@MDoNl^uB^c?;ceWBu z_NG8Cj4^v+k?6TcHN)M=Xu@$SNh0-~ilRd^lU6yROZWSC^nw!cXPJ4#Q|pJkP}J0F z4!Vg)D?#$DpQyauHY_v3pfe(6r4 zR3^9{hWH6*9TUG)!9$nx7KnR*zn*6`A>K3V89-UKhF(Le&XBlIk*Z5teGIOr3X@T) z*tBGjab3e}hwDDBt`V+&g^3_gQS&CVA;t{L%Aq}<@9of(Sr;z|%979>3#08_KF$p9 z;W8t_6+%!INv#^jm?B{EB-LwS{4M_@SCTjI*keEu3;@errbZ5 zfV=FupJ)?Jn+0)LgdJIun-p${y~u;~dP6-VjO!XF4l*gGTCocZzWjDbXH--!L?-89 z9@tB$tzu?0uq&XSM6Rd{Q{vDu^}0%t!g(t44k1rt)+ z?vA+|t}baq{IqHvFz8@;#Z!C5O`R0%aM$eHi%*dZXQ*XLai7gGL#-Xm|o$lcfrQaP>VOTbjN`yj4@>V=l4 zU`i}lb{RXVItqzq$2M2_(e=i0`kPdI!Mg9EgM;K+{>3`7Wv1;vO^&8Rckhen z`=qt&WWJL$-DCPS%lFZfqs7yf4V+*TPsJHzyEM3)fMALN$M?Rg+PX?SXL9h8bQGQ25Scq35;$zKU1j9!Gb6Lg_d%<(={IL%ez3mH9yWi1)7q^e)2Xdl(~y zmr#>=>C#Xb6_aWM;NL$Mi|W6e`-vnnb6(m&y;Hh`L?OKQuXSdG7o6bNqb2KhItLM@ zy?+kx1Er+{N`D;s&um*FT9R{dn(3a%!ym5g4>^nBs_YqqD`)=Xm0&tmRKDsLxK3Lg zyx{t@bWBO7s#m|=R!`zp^gg3~O}%#z;QubT zt^z4<`Ww;ct_l$|P(n)&FwKhVH>0NCG;Xe_sjwyw>6Laq0!Y#plqi9#WI$I%pjdy( zzGJ2#&vV(8JxI%-z0WNSm0rlHEJv$PzQKd5*xh3csP3F&`N36n)>8-9@ViR5R%~Z= zz*VNP^MLDyVl$N9=kK%!{I_O`P6AaAYZ%6i>)EkX6(_LH0Qpy}i9Zdgg`fW}8J+g~ zTnqk$4|M2B(O9UN&Yb&}QW3J}w0fpvA|3xy3QnfG9fK*6I`7_?l)7&fe%J&0>Xc0@ z;Mz5%x6q+h(>iZt(i}e54@`lvDQSdhAkbNE#_HoQa6tYY_197TFej*xQLmKu8sJ;l z`KhSM|K2!e!uV6XA6%RDXVM|m)Tv(qRTutb8mV@-U&o-R7hfI^ph1z}Tvmp7v!iD& zQaNOo0>80Qfqg7F;U-}+MMVTcQ}Tyd^$^OlS{ayn^Gej*&$^<9%S|PJgU;T}TRF;Ir5~PxeYqQak1)2Sb?^`Dk zp!}H$HB8Twa|WL&R%pR_Fs9J z+=;2VpXjPv*DYTIN{+hjhalul^=|@aV^-H%EUA)hb6@`R@+nvBPy3iFtW1}K(ea!6 z2{4^cmjP%0oxxz-AJ~oGKzKfP1;W*P1a**etGJH~niY-jBm@2W?*n11S1TBehqx?+ zk<(v^GduYUus4-{*9Pg0m-uIEBj|IX#LtWO(RV11y!CLBJ{~u!PP<>F2RL?j<1F+! z{IltRAo>rlt*)=;@1qY`Zyl^-jL*E8BUg*JNy$?qYB%A`F+s#~oSD=;3Zv*dCucHp zlHN0$@nVkC9~|Jh=D|D$(%gSDCZoZvZ>F9+BirOFC+SV2ZLCo-{SRbTz^{d7`h@dN z!(Sb*(yhVdug4DO(0e^g|Jj9-icgnZun{564Y!4G^-mr`yl_XA4+_mrP(>hrkpkEYxCePAzY>R>m)$s*D1xRdWTdNQk^RintDp=vC+#y2}9xYK??iCKt&FT`KPjfC0wSbcQtP>g6mk7 z&-ZXGkzYRv*TKm)CAk(K&e;H0twUrnT;q&20F^JiR!~p%7u`IbhWc9ugQURk{+$x7 z;=8QsL;ULU;AW&MdHPKvrBWPz?;uhc16&qRRjwtfaRqehH9IZFKNxmdyc(*Ay|s?Q zhhy#!qWmMy5lGZ6?=v9L+aon8NVGLR6RzD6zDaOR?#fe9A_LbbMpQi39TYEYhpxy*OFZ5(xaSlWD+x_54F3)GO3p@lU^JoX7eZI3(8X(EW z%4>i=(M<*87v4tZNS(vSFxC~1HNi8V(+QQCW#uT|)GAF@fu?F{4dN35JYx_aGIuwG z_+j34@D$04yoBP}eO@deEuK{-fG2HNc>py;o8nmn*E@y`E?nQ@xiGzxhHXHqF0-K) zsmi_>!R)=5N`atsU*4^SQIPy+BYB!cEF<=bEuvflmG$b=F(qohGAoMWO4r+y^f*aT z9@r=R`JDHGX>Z0fMn@+x7XZ^xxfJPHX;WuKRFkpN-vyZxM(xvyzPzM0W9Z&g@0otY zyWMYK^!#yWZyLE)*m*X?)m$lG4A&RD$CXT{`bQy&oHcbzpeS#Zn%Pn<9UaV;s#%zW z_ytZmAbNV=yhBu!Y2Cds6r~hy8o@r|-bjfD{#8YyHE6%<-2FMN_}TqGV{|Gkr~Uv> z$+M&i5;SYo4>Hi#mz>{@p3G|Mm?hc#Ul9hPV*3Ie4z&ew#Q>#biD$=13fII_9VF%{_jmS;1Un4m`Rq}XhK8iEYJF^!5e z1#a7M=IFRmgo+mDaHX`N+syrK7|2n5ju5URmNYiG8o2c}B63wm9AcJ)(Rwr+t|fyS zXx}LDsR2^6`t|ZNH3` z+WP_0I zf#i2v+UcuPr@ryY51~gX>s!RfST8@^k<9mf?>v3w@x+zk%`SAoeIUs}qA8hG9YW6y zO2@)JqeD4SWdn$39qa!K84bzFIjQtDr4>FYmGD%^<^j{_^{iZ^kIudo#(8-MXK+it zoJwCaDy*OU0yS~P+C-O^_dBfe@_9&~{X}*OnY}n)fTwE+bs_u zPKpDr*Wu6!ZSZC~RLOffnLmU z+E-Ig4VgYBL$t1KT{A@w%zYM|3`W*$dH|ZGgSB5GI=hpvLYJ=ojH+GVMgyVUjGhy@E(<)Cpp<{m7jwp*MrlHoTPp%^h0GxOu(7O6V_Zh z(>j0sC`7`qTXGq7dS4mXNXj#Xoa%t_{!VuoQ?-#z#InfIb3M+?|2fcvGT*sYV1XRU zhrN+LBW7VDT-zpeM}RaX=MG#Y4lB+glXX031B9QHVAGJCq)y5tV2X*$1x?L^&m`0k z&Kskm2F#*^Zvn&8cT3MA6aW7N&=_C2u9$>xS{F9}_Usf+Uy-LeMAmwo;7_!@!2^8F z{&`BkzhSZ8gf71l)r&(1rT+x__fAZ{2J|bI^MHPGz?p^c(Gb=J%4A4T_ckKamC6k` zbLjyy&K&>8ye6O*uh_tp~ zFo{EFYipUI^)^4;Mu)N%@9SYU?g@7n@GK7&f;{=r$SfGAB9l@8Dy2v)qm?(zk6@$x z-lu{*aAJ+%W0-aG{JS7WV}If%^yyY_O%Irw7i(dZ8)R9G_)nxW0qBY5LGp3Zj<#;) z6ZC}ZbVQ7m>l|B!^7-M|S%z0lm@q^5y*)r*vh7bGkH5712#htHJDC_zsVWk)$U7?A zg*+?o@>-`2bA9<(F)^6^Q~Jo@X-*MOh;gp!^HI9Xp5;N9TlC-w9vjd_AUrXPEG z|1<9P$8=A6F0{ux*+PFx+*xT6ZlOCRo%BvBc`CNCzAB(sc8feN2)DevQyOqtUmK3w zpQkA}Q+#^clR>;=s`eIi(e2ZZda>A*ZlAVWq6pG)Nh55maQ<85XzEgRBf5JqzdHQo zEsbR5mZxU?;U{;+DHPN(zN-P*kNkEbIQ8XS9`BM zw0-q9!f6hv@&iu)d>b(70=_5!BO2B5a2#qhmQ)ZZUA@K&@nZ_X9)POTNDdPyQ<+!4 zgg|-M2~040|L_b*MGE%&ICRLixekY3E*rq1y?ZBA#C^qg{WU1`t?BVJG{k9j3y3PZ z?eiGvAIDyAf$Kjzv}?(gZ*=({z01&8vHApZ0c}G9B*m240LeeqOlBG_NNs08qBYicqeo@?#y3{iV8FF{QQcZMU} z*!rUZ+T}m*fp#luOKeDQ)l}C36Hj1-@yr`WBr>X!iXq4un`|9*#Ne%Og?5SzyyxhM z`Eiw*GFivwetJ2Lrfkn_gnu#j6ODt?dK27p-kF^ZqH)j}p7YE!_U*^~S#ZtHW2d1` zy|+CxWS!>36r#jFVSWe-efFDDO~$^g?Hz#64HcCG)3tIt9Ll~fK0-!TnBN3Edp|Tw zfV9OW1T)$e{=Ebpd2z)v84D`A!+>#Y)ot}g`p)?-AW!fT_N|*=0~IVK7)DS zl(o{n44lqN$`>G&t*ereN%VovK+tcm>OfJ`<=ka(jna0bD7J1KoG4qQrHnCISB*+n z-%4478UOfF2^7)n$%#Yv^4mmfKwsp~Mu5_2{rSk$eqGN3{{77vB7izo$OTox%|-p<4UT(|iWj9}=2=}h3I1Ga4m11(^v+0964B=xOAA5xFG4m5JjX_~z7^4aT^=L?z$jX#n$qgnx zt%ohE;dy1}FiJON%+`o$mG#blH4?3pCpBPj+G0<#VSG^9g-dImOZqRsG!=GcKbVi2 zh(o6Qmh3L1&v#E<4oaSAv=F&2#yJfl@7rj31E30obKkx4@+Ls7tiO*-7B}$35_F!u zqc?&&&k1lF1yRb?8*&)s>TAQ`s!3h?0p`h)yBhi9-e4|nHOr8QVpa~a*#thUw#QM5LEX!i_#1jg$6SokZw z29)tjlVmZy@VnyQ`3>~#VN)6;IVn&4-8dUYXw%;l;p*t;hFLj{VG zOqvtOb-3D30M{bBFi+r*jLEmqe?7>1E#n24_R~#(euH~lH|XmQa{2>`a#0xFDSp6P zAB%Xg-j?QbDD%sD3UoI``eO3`#{ z3K=bIWfMIA(^j7h>>EkOL_z)0Ovh8;nskQZur zj`nY7BYda51dvja-ILLL??@}c3rzeZWcQo9-J#vVD$YoNv77ZfaK?H}2VA@Rx$EU{ZLQ$#f@}LH zvm$Eqlx?CCg+@(kF=h70{0c$oSoxB@fZB6KeHgCyUHY(QA}{cAFeXATfj`OAbx3Jt zCc^HAb|{LS8;|rEmO4KmT{URKKq?maNEktg5}DQepR6`)DT_tGLHx{=1f$=V;+4tN zlzQ6>Q?_dGS8U0AK{=0%94{6R#Z<5G+*YefqiW7~H!I}>{Jb`Nub zYph0e5_2bXRxxACc{d*-f2vFmhwGw?QgEkfs|O(*$>U^jmvDX6AmGb;Q{BM*J3aka z@Oe(DQOM8Uk?e>=y+)-+kw4`M1L zK@}z2=wp~Kc7G8;A9wY;+6FoFdC|G@mK^-2KsSecFM3`RBo`g9e|c-8D_16cNk_`p z+je`=Z1#xqT%ZYG!(xa#qIB7vfnK<}D>ISFoK;?nI=B5&v!Bvyudgl!rm>s< zglB8{*AJ?NG3nt^)k_hlXmT z?;9O|NboJ*E6V`iX1(wf@N-8S{{i^c+J_V9$eQ9Dxbl{EbilQc?eRCb7Ul1lglow1 zBot-zvU5iP%URk9s)`e&iY%e}6AZE{xVCN@M*Y1P+EBkbvZNa_;VP?5!2g8Th4k0v zexgw-{hMnI+Pw8EGg@j;s#M-YMs!&Lv@z-_x*(8H%UZAWVEHQ*$jNK ze=H6y=y&)LuKqQ8xN1TyJh+yx@ec*4Rkp-Oa9#h^2pY|rYI+Rg8+X+Zir?H%B#B5D zdp?j_dAxCWzLOP??bK-=c>?2hdq!tD?g^bBKQnJLqkZ249AN6X`vT!Zso!F7P0|hH z=BwQcQeFZJK zw$&ZcAb)YiqHA!~U%7r9u3O9s8@aN4qPTFa5Wckqq{y!?`3SCFj{>kw`;u4BfPY(b zCYmBT=A_2%ND*58O`{vRmHh;scf^(BWUSD;RpHDwcHUK7M|gT@Po1LL4Mj!q&H_?i zyeDJZ0g)N9?_WXgsfpV2IB_7a9U5&kSpH4QQwt+!am9#rulyLEGgriSz>@cJHgmaC zw#$&{vZ@vf#^4xt1;#RQ@b{QTbBYG(c^~Rk%!P!T+y#|5h?8-(mAo>P59*)xhGUvt zLw6To7a3In*Rk~;bT#})EGZHW%s_grZYvs)|Mu9f5xBl}A8RL}aS5{5&wY*zIc?X5 zG7IWsYYRwj&T5W^YrgOK2UNZFOy;d^bgy7uU=l#1k2_^pP^%HsO^)kPH>eyX+!(^vb?sz=$08Nr%Y1;p^oTjMt*BPmCtXi zs0Gq2$GCGZ?{Q5V=6<5=mz~Fur(4jA*oHELI>z%T`MB@0Rdv)*O&@zTy42R(dlRl7<`2F_u6?hC-$z3`1N^)QsB50J zm|?`>e{BFY_WJe>097b3SU_G`n>>m@DT9Q~C`zPbxx*gJjnevM=H>8@b3i}DD zMvK({fOc~It|Hz%W*dMpVR_SX;(6?w3nSop>P{kf&g8zUL8;k|c~Rt|omt5R@*^pc#5F;Vj#WniBe*UxW) zqWqp6+l5ZMy}bwV(&O2BXu{Gj0VmuQTmOVctvL4%mQ01!1(f#g;`n0mByHjV=qmF@ z05!a7{2I~WO0cxpVCz_`-$(aq^>zw#4$dBpo-APdS zNp3kv)!4*7ig<~$KMoyHX?LF0#;cc*DQEm} z7vL{imBH)-(Ons)RBQ28qp13@U}nQ_jeCN4_DL;N)*mzqo_2L!!Sz9Ey#b9|*}QLQ zZre;r(O5e{D?Nd|t7yQA=u<^n2%>nbcLc_|oMDtcx=+1=!mW;HT(I+-`_|_H<;2+_ zEC`+dUKaGExv*UbKFfYnV;9wLZ^N0hKc{{Qk{aa!-vejBu6`&y^Vl2CsA!~kNd;VQ zivsSG>qMU9K7dvjYthb5Lx(pojoMkTN);YPHyE>BHD`!<&a3u=pu`$CnFi)_6t~-v zsqlW@H&}Xk)k_fHfA%t#Hs|fT9t_QOms&93CFZ7RxC#zF0?*oaAE9x!;H(-nK26f( zjaL~sj<3M8UV8_dXdu>xOB*NH%*T;g%?WTENE5*(JNqL>QCoB7?;ymQQvvGOMI4~i zT{SPK)p7G0Sr<L9u!vz3TIN?tkm)AHZci z+PHKN-4v;%Pf}05d;nr;mcEya|4wSCe2(}Zip^(Y=>8){on@hTc36Ea8C`|V#cL_P z&olZm;(1}GPQ|>uQ))98z6GGo${YSbpJ5vfpnt4pU0d}pWO{G#z-b&>ES0C@&@=4E z3@F*jJtOp#iq&=^h~g#6j9nFd1d^=_jKz&vhbQtBo;mrrA$SVG`cDj8uuPK)yzKm^@5GZB*`vV&4NzCuH z7D_Mv>+Tj9BYrZu18GU;%@c&wy5g5urhO{m5Q-X6^|gSM`#LR{jtt^{kNlndn@d4z zZ1IbFN>$NPxPc+Xd^i-T3X=mGK+4iR1#lIwl^;T>E$oMDh!jInk8=?H=SgGVDJ}YE zC!7?Mk*ikt!&u}n4p3rG?%Oav9UMqDFGnMYHs9&HHHs=YIQFMlWS?XwGBQt>J!d+~<1q2Q`a}(8cm9=fV6quGjLg@||B2p3=zhgO z=#pYSg;DxjLMj^Sv#&fE9cl5?0#u(%mIk0~2`(W3bx2y?OhqXh?DD~Ljgy%szdOi3 z0h3di>qlK0nDGNeF%K+#A0sAuF%yiv;j1fRmRTZi9nw!c=)s0+J@9i9a2ni_(2te!KJck-*q9IF z*Ig-TAbI(dJP|cs6#9xAFqw@mzQE*^nTNF{Szb1Z^rQL(uOYqh!w#fZWo9y-SIW!a zY4$RwGd%UqUjRzPqvK-ivcCwPK%!4WEl03+Bst^gyz!<-F5=lg*KjG`;I*2Mc&p=U zGPEgUrz;1pw`$fv;*wL@MzsE!WL83z%ENR^;aPg+D34+Pe_Y5pFPB#UkrX)V80BeZ z&!v%`h6fk#M7-HjDL_$K`!cW#C9WSwL65^dw=g*NK`vU*?5eUjrI0{UC)v9n1HKFO(VLxt&bw)h@XhSO_GfPzfYO>oC%M7^Fb^~e}n)pZ# z;UAm~)MJ{G*$qb6BY$X4 zpa|E8AU|mX%~NM}WdZ2xkc+EusFQm>W=HE4c3*En2j#Be$Ca}1yzIiQhwanYP8L4tw-(hYVf`%pmRh1v~0jU1K zdkU8VTWtk%DTt{^LQ`&W7BZ4fvNO&a9Oz*HD?Wq4|}lvoQ8n5@jD> zwB|kzO_+@TL`t8uX}7(846eTB$V76ru%dRswKF*IDqQ!SmmY`f{#6AQLRwyGlhCtd ztMywMC^^#YqsEi?jk6jNC}A&l1|=CPcM}!WcKo$)RG$^6$C;WUZUCLB^WOUah2Bay zyb^`hU&5g&&$Vj-v~*R5 zn1HrcIfVk~Xk|kzYFb_-SOeE(Q8u($q;@<3S4}{!2CmY6*JN^48>+O(pI_#l2BT8( z2&rVe4gM&}|0zJxsXbx+{8`dB3WT+Q$m~yV-&d0q1!b zfvM*lix1bk17Yi^{h6D3CP2Sd>ijO~KPFYAqo(v1ffCBEJ^Hl@u9LHl$0(J~`JcT& z`Yd(^11a`eb1j*Mud^bI4e@&w8OkC47`9yl#Y-aXdqIk1L?&jS`UJ88)mUMuCD%6h z><%c^d_JI@jLPOCcA&4lA>bs8!E0g={-Pp82culBhNg!r+ZdsplGQNjTNQHj*{4#A zGk?>zA<@K*Yt&oplczRqN z&Ojz+eFC%N>UbSs&!~$V0(JwluhxIEK!gQc{0gz4%^rEGfEVri&s36y6Xz8Vb zvkWLV`y3p4PgHKgp(k6X8%WT$w(DrVVfV%M0BU|wYTzQ2pIxdrLX=95cuk@syt=6W z;80EG_C17f((;DI|CnX@tBXlZTgb>;$jAbSKxl{OhWrj1==MWSt&J%X@J z^zjuio^uW~0}}Tu8H`_b)F?qy^sg#RzRHr$%!t7t#W*VK&HWh1V*647(z96U5~g`M z0k}T1iVjOr(`alyRQe)5AH{cb9ej}f7p(}_Lesw{lbIPet-1)7%}16sz%{&c7gPP+ z_!H31^yP*)WNPNymV-SO>psfYwF+C9>(+5yG+ciZAAoj-4Yxc1f25=lqt~}~&96-B z#isVKlq}bUNH5}-Y?00`O-?KX<6_Dy|k=PINV(N z^2SKwxVImkqVb{K6mF8-t_$*~*L@s{BLwuKlTCVCjd+_Vc=#`#K46BB?Er;?U7!N7!)n)P#e*iG+MUUS!>@u^K7U zGie=gE^O&`2c*R6mB`+F{zeTt60mF?I#SeY?}Rf8V#gAw%Le<4^HKcgym*vUalB#~ zaISIu9^n~{^E?oK=zfNnz+1z^`}ve!RB4C>_*>?6L1<{{$e@&5S%*zZ^j_61lLG0* z@IIuUSklL2Qf~D}CVu-PWMX~vyc9IerXF=d_-6BXA~kfJ?YWF!wmlOxe+kB9e%6?C~?{nB1*l^GZh`tTFfX^w96?9luqS`h|!YO zU+7V2>G93QDD;!3A^zzbD`OZ;t+~0+1?v=f&g9P62xrT9>aY z55_n|+|9r=-f68m2~1^|MW9La$c3S4a=h1x;tgSbvm%Pu)fRLjo_oyg08$m!SDc|X zDIA^>*$(8lW$31WzPF9!0xWdC8prjfDv&+0Lnz75QLOEYb^z$6k*vLPf7;XjBaHF~z zJ>5`W5J;}th~!N;)mv#|SdIDAhWvcioP**J*LHpbGw!<@Tjm8n$OBef~ zefUg(oYg{(7}lMJ5Q+C??sd9t_Q19Z3K$w+%h% zV@1UPJ>PtmxsaZeHi75pWM=DovHw*|Z)6mCT?)e=Hafl6lTE*Nr_cRF_ZxmC3E}iN zgu@pd@~_atq42XwCW_|r_I?V_7f(`Z$e3|HED(R%=XGzulm0euZ0d{AeENh(TFI_K zqPbrbjd<(m@cB9zcN~j?XLDY9?iG5r^!w96;52*~yE30Xic@&Jz6O8Y_H)eg0eZh^ zYGhPMe=jJx^UnQ#GTOe3I0c|eb6yJlX`R(0Dy@dn7td29-*^)lc^s?Ysj;0 zpE&?5CB3i-sH9f?;w=Cwa(}EN^y+507s6#6$yy4ZaI^#=+`Xe8;j(#6*$D3(;lGbM zrSTI>;cDFT0405qHXcDnHEW<4@tQx!u48yQH-Roi-YN1#@iki(q4=c8k1A1oX`pp0 zia)B#Hc|2R^8*hd(^JdskKt+%1XJhjQ(9m;nRtP!H2m8f0zm#D&)m^sN#G#>N@(Gt z@80TKEo5^;d>nKtg_AQ(-;?+DAa}Fo@aISr_u?6!4mH-kx*CU0yC41v5?MSv3ha^Q zx{t^>AgeF-pxRl!zqdi(W7oHDKz{j?{tZ++>!WpP1Jq-#QXh`SXB*9GsOk0o9Wwms zY>4*1ITDe@s0;5KPA_LkZM!7XJO1RTalhuZ>=SgBOQH~B2kR3l#eDQrP$D< zly-d@vhQsdp~t;zTqMXIt3BV1>OC$Ay-=w0&>f88+&3?O1@ zH1?_9o|&aLhszKjtNM8fS}Kja1NgI2$F0cE8)v5>J~!5WJwY{PWQ$S0#x1NJsWiRw z^WnN~R1r?64j4stFb22S!?Q6la2>TIYfCX~&DXOmP?=Mz8pha$&FyHju}6a5d3z-^ zlTlr0ug4^hZ;h`2&&%80WhhCOKM0;X#K#z(-_LD@bbE(fOOS~z=|2UYcj-&r(WkZH z9Z;#QhVvKj99XJ|AVC!Kvuyy?t6$`X{Le@GM3mofQ$33Kk<d zv!PB8EtC-?BigV*$Br|zk)pqFQExmOK#Vbx{bR)kxF}@7>r;@AF(Wj2lX+Tvh z^8Ep>r5vu2R<>q+c{xC3jvmjVmgsI=YXqpVo&E}dIyMvlQU@xyc`!!s#Avf&f4hYl z{o@{cAfB05W`OBQoEZB}ZFl!q47u!Z{Hw@R+8_wTp{ugmq-ft>kq;S7sdGQkRmd@J z?u(DpTT=h3UOx8|U9Qft*Mnw(%LNQx-d5IA^j@D_ej1*d;+ttyrbO_EA!gx!l#qes zpSZBGOms)Q{cxycVD4Y2(I4Y*Tby}VdpZY3&Z7-UMrh{`d-T|F;>ByMh@X9^=|=uK z`8_N{iTLqva6Q|XjEkV*jVU8`gifz=27YC|tOD^f$vd_a{x*j_Pq7U74jw;(=N%cv zxMUdC#oUL{S`+jdw9~GN6q9!NYlZG0-!}5(B=D~|eHjCFmUsIY84Yh*?+dVa{Ct%rI3jC3|vDy^h2x=%`C}X1X?!{N6Dh1LbX_gI?WC)pXgAUY!;b&aalC95ANg(#89Qwo;n~K!n!+bQ znHuGj8oK>RQ%GOQB#HLRG-`VJO+1ft5r_8nUSCF#4BPxK<4{}W7pIUu3flC0~GONWh`nkmGRb)r~0^a6gbU~ zRs@05M{}QY5hug_f_e}Y)g?$H%05$IHt3*pKg_rV(y>WMb z8Q7DFbPJH_v%}hSWZJ=IWXf(exk5bBl46FFmaaAdangIMHU;oE#a}?7tS8L^%GB48 zlZH&)W|K2A{c!NQ8RA>@wl`cY0gj8n$*TU=L^{+^8qy8+*%qBE;@v9#f=rt7zkqz< z_%{H`i6}b=pe&zgIiG;G<~s&~lX|JnNa-a2in%f2N16_)?z^$G;^>0Al_?l5h&#;=0(7jb#)x^V^)V( zp@=7{CUC0j=oo=`#MKKXkze_1!V%=p-unX-#nybg67gFy)D^@u%jZKG=vS!o+Y#TB zQYU0mH77D-BHYhqCaO;b@#;RW;lXpL;&>Ass&kv}f~VM&Jc<1K(j@65Q%>xIOeyK4 z_wdSEXri;awgjEtlwny1SMe4fbn3%PZs4S|J|9F0&H1RFUo-zON?H-mEMtNAPXUmb zY+pPeDgNfY3rCjKo?E!x7k2Qq= z|IY}c60VvaBV4t$UVONA@A(arS9EjTVw5!hloXR^&TCM?7}aZ0k#@zr*m`JJeqH+k z3guM32hX&=L`MjcTWZ5NOJ0diL#D~RDrdNI?fwPrarS7pG1`lJwGfofPF630tJL&u z1WsLYT)PJ#kF8U{HqFWw46{;K0=+l+U z$pwDz)9c8GSaI-dmgwDor~8$j6C9RzpijZtloyu%PS1*#+MW;4p*rD{ zhzZJ+A^C?IuD$j3F7MNuM7|*xr|DxTtweNhmOg{aW=}4p{I36*_MIkBHtXBHbf|UZ z-)C^>Y~E{3{$^vzB099~Q_a0+bm&yzv3W1(L%e(aT@|m=jryvY6F2BfHHy@$zni6} z+|&BzE#zwI;6I%^CMlov$JfWK0!YBi|Z(c^0% zs>A~RIg~1TJ?0roU356eAEipW+~HcW?m!z{d9DF@aP{|gMyn>WSPzgYqF%oesn{BK zHlb3w?a=|%xFl{q;tsw01eDTHVx9-N zTEp3G6XeSOSbhOeZ5}s-=*qDktqu)5>6M03HO5s{a2>bpFcQ>($c66!e^t`CBPex` zrW;Vb%|(3}wa{ChNYB{`rEwgdh(YvN$SYECl9T7=PD5pI*wKvay+MI0WWUy~=K|<2 z?WF@mlucQ?8I#5fo9{~TYW+kf8Xf5p&c~!~>r^3=w#j87y2riP3ZTl*>^d=NqXN54 zI8pgT}X-A>N?t>C=KTWE@=LFx&~*m>_4$0e5Bc<3fu>tR$@#_=6<4$pjoF+K%E*1 z8?Cn_gbyM-$vw~qD%mm8ijt-^mGeQfGW-X47JO35tWKX(84pR1vs(APsA#0I$`9z* z@3A4hQRL?c^g{i044FE1eJA2uwJrw`-^RKFBbU>9law=2>*9pg9iID%*6~1l`C>|> zyda#0@cF)*x>0>!=b zy4q9l>QZyZP)%>lUVy8chp2A*0fj5n|~u7>wxm8fh=H}IqxvtSrmVXFkF zG;_#%5Qi?Rv(%x_J9^^K=ea*P*$@1`%_J=ce$fv$q+;>;lc--R(XE0j&*#xXa#eR` zULMERbPj(FsZgbO^+c!vNK*J#;?OrEO)ac1_| zdL6>o`TQS@lBVIKWE^NTJ3wVu^nOfB1Dy0EolJ`ZL?Zcrfh*AaUB@55Q6;#DhBo)* zGIuOKIScb%-o_ZRyJM{M)Tb!yu`~Ut(F@sQXZnMS&Va*0IF{{c=aSJFSet95XGWoI zQ-N+T-}+%47pCy(O>}dEG6ZL`Si!GQyxMN8J(yf|`Unp)avZ+cpr=PM+`u(Hbf}5D zuW{~znEu7(A0^`Uw~*;m^B2HmGYS5vr{^})(g*4z}+7nXpw!a+&3JaMG4swWLnKlWoQ<>cNVS*9ZO^2I=yk> zCb(WnxsFo}+*uJi(z#$U8?LeIE70Z4&?49x12tR^>xu0{N<*$VJi#ECXx z@Z;UWQK|OV7&z{l*@Gk5u0{@3Kd{XH3S_1%SH(gSQZsiA!e`vEG8L(I3?Xv9lB(?U z3{qlih}Mc*D7P}+P{ah+pGTJrd%B*3Wo3I;KUfxJ9P@_jose*QG-SCU5Rj~i3;zd} zv!tErV5xogZ79FY__zhsk4Pa8ejy z7yAdD7t(FPl(oGvpYAn+GLPkwt7P%cCmwXK(Hs1V0GUQc0y4p8`^YUBUD-M}Z}mYc z|AU|B(=FNm&(phyHF;;-;}8-E_axlHMNPu}A_PPQigfrH4z`|i(DBR{J5HY;KlXahe|bL7 z+Mm7l+G~H_mp2!rGyhRVH%0pAPXKKBe^0_FyR1>P%8Rn+bMv==z5CscS3yy}awl6^7E35_O7xR%R2Uwogj~h^A?)(+FrzSLKAG%;?IqawK{@^HmFMugmrE zM43*JhpOn7OqmzF5zq#m;4^|21&2LFNh-0!@1aQCjP)~|ZmffzTVO_;ntVW|6MTO_ ze_oS+iJ(KmiwUT7d~$Fnr7{(at2^O)2fr~?svJq)f#%uT?SdvH8AG3u&YT@r=eJS) ztnl3(5hS0w-+3DYotQ!WsSB^D(ve@*yoXA!?7F!bmFA8=xJv0|ypu^t&rSXci&KVT z^vP74``{0R6xYAm2c+im=cU+mbqp(l`kZB-B|)DjMH%gIS=d?2Hq`WKb}yjfE#CLR zwB%deML-+X!x;pXSNKMvrrbz<9c<=mkTUHLSXPZx2j|t-Fn1e!*(&Nut@C*s^rX61 zzKb?(`!wJfHl6Hg{hT&cWUOl34o&r}AQbf=Ti%B5{T$f}q~zV;t%S5B4y&Mk(||C8 z*;G98DM5!;vQMB=v)4``Zu&E{T_xsRO^~Ume znD@N`xmy()6*SwTgnRllPCH0wrQ^pMZ2Dv>CX>=jf_}5Wed@tKsW7Lk8wSvq zHASchX<4_eg=zkUdW2il8FAS2R66$ql9Utd*a}WSTh+Eqxa##~q_)H!jKL`G~a=VXE|E%vE;)C|~e+r+R+0BOf zLjRglASdSPvSA6kb=lC=)?D2|^c8!AJjQ%}M^7P>ao_0}kjmj!!u$q}xDKQ&(RW9X zzcIPy8d9ZBDt01O($`_Qn($d6jbP=ZmZ!rLzx6Pe2+g@|X;{>Yx)}E3vhfHlu2Y8lFgA#wW_n)$qyY$CbG9=)B4W zu#}B3qlLQ1k%XsjCres`gGVvtyoZCZBxm2IW=LA+_D&D-EAuvg3960Opv^?JP1-zz zftKmhLjWCFG0L2>xmkG|P*rS1A)w;zU2+^~|Kvor!&A!~6L96K726&FtFF-946BUk zvtTu4-ByVPBs|Z+L^rknl7-n$^nX3lN~cWSZG{^a3q*G9w3x;96=5-9ZUC1P zbHlR3Se&ljj*?h4+nM9&%%97@Ui_oq?D>xC+jJYG>G!|6Yw^$SIorOX`}7u9^U-0) zx9NSWRR@|i^gy|mQ*)!2-nVLNx#L6eCR5mTBW;?uG}xzzpwg?KZ3T44uNj6{=zC_z zGJA(9RkGgkhhBW=LjP?kNI68?{Wl%a)}9Jl=*8KP4y^$iOyz_zE;%`OQ zan|}H&%yCOYLVyU+McQC#b2*h|25DbTQ+CzFQWI?O5Puvrf`{d^L`C2D*rL+0_4Gm z4JOL2%~^LHG?fEYr|#4HYoFxQouN!amc5?f6q=MaMVn52re_1WEJNA9Wbq-E#Z#6F zPIIBgFx2E^RthP8NLZ~$d{))b`(WBrbov#Ly86_cO&w`7Rfs?;NAm#M@i~VB&?eQr zzuFQ~;`H?zE0NNA+qt09X=%R=dcV}7GE+m05iVXJHQ%5NAW|GJLFEAP*L|MjMvI2x z?f@XW>_UTpJZ#ku5;8v`Q;Nma2FGDqWEm#eDBsGvC_?=Br7{OVUn`!2QW6LEb!e%_ z(o?9Z#Zt2t>D7myz+`jch-e`HoHM0EOM++Grm6XZx}95*X?SGV6Mp{UZWFp6J6q~V zn+|c7NX^7lZoDQ$eD!FR80tq{?07(%8r2@huxY`7g@aAKqH@7>HZF?xRD_ogLA&_! zS}R3&2<70Zh;foak*+k`5Jr*5S}twLIEj174s>qLZPOt7p@ftU~C=`Eu;oH1u zXxGUg3pF%sB9IUAt1=Iw_1R71@B@Fq{~E$WPLz2eT>B*bG-WEPSv!hMy?XBi^0TSJ zCILhTzc=(#BI|k|7Q(Bagkf;R?=RVhaAkFMJjQ|JdkDtmDt5<1rlJ`IhME6YXPiVW z|82mU+4pxJfalhyf2*V(E8=hIFd_A=Q9@+jFXRpqC7w~644&ItN|3yfHH1B%=9()} zGUIfd$}Mvzq)Ftx z8-=zmyrNUQV6=)$={ZMt@?mg`56=mTF43x(q5HDd2-nYe39=BM>G;T*G?BlrzJct$ zVNP@Uqpq%M;N@`b-#ajxUc7u+vQEbhZo&`C6vv}*BAVd&WHy>|3ZCBEZ4n53V&8OoKO zc3r$7Q6xQY?y7rdI`?F>H2E)%{`7`wl_0-x@wt%cd3)fnJ$;?M@%25l==}KbyWO@g z8#;fvu8KXz_g}n8(#2ef&Zk7?jTznDwCAiceAOztpShtds;ODL^Acb5{9%%QJcxVt zW+^Rdw=cB=vZ=1Y2b;|aq(*t&Zy8TwDru=z++wTE7Yl-j& zv{e^pK>l5-D_z8YcHcQ)6!p$nTp4L%@KKHorO|(@;5c3f)r2xr6hsMHH)Le-JHYFFx> z!hT61sETUV+(!F+?-rpc^2V7p$UhVGgDtghL&V^(7OCQ0SOmy>%*(&Ex(?*Q5)G<%VxlApMpXi1Yt_Exmy zlvptYpZbh7l2&tO@2x?kh1CAu zN%3>`rfI~F)M=N3>H99vu~_iK4hc5>`PU3RHdTamF^zWQctigG8F_}`%M*RO8s2OC zUpa;^@AViqHl35%HzB^M);0vt{r$Dj)W}MyLMGQAS}nx1_LntV5ua=0jZI^<99UoM zt0=;rohr`?gy*D7pmTvzpru95>p7`NWGz<&A$#*N&vMdPwrzbL5{>7j*up%ot@1=B zzD@XV$TV6veFmAnDN2BOrNRov(XX;)TH3T#z~&&6U2Z?TH(Baj0`Cluo)?n%lC>`c zI8CRV(h5gduQjAD04;^i=e|C9sl<+GmR--Z(d;n+B2oPB^;~nSRoX_-J!1ONnus<0T7_NwUkQ zj9kj^KNgFc#s@O&QPY~7(f`YTBO5j=9oq2*@^^HN20;_|RTln@#0MpYf)-a`vlYH zg`c*ERHD*BE;c5irJ)UYGn zu!Pq}Z=$CqaiU$#bZMR+7<3G!Pr|&C*{s2LfY-BQ3CUTP%6q_Gyj{}PH{M8~_i{$l zADcYr)5NKlcMYa5-Wo_h{@j#6Z%?I4qE;b3T0eyJmWx$vWcqaB72a@@yJF8cy&tmo zp1#zF#Un+HK0sz4{-KDzJjL$ab(1QRm+4)pO6SwHU0P65Jt-ITVg+ zrci+cY8p$OE=Bo{p2huClcuG`4w=^a*@OMN$71{8hnTbuYtZ7o+RRyw7c!}yrUy`Z z!>!OFa7y@La|kUC`HMZ!ktZyt$_Dzp(2itr5n0FTzQT-5V|gJ$K=~On(7E;xsY{uf z9#lFYQ+m=tXxb`#gP%|Anhv2%_v5nH5rv|(6qVuI^tD#9_pYz z&+HA8r*$Eb-2TTt04MV=`XG^#@8Us;IQw*Y79{e1wD7Zqi!B)+YTf~8(9e1fZEDeP z%0cs$nLVix`mXXEmxMMYRmsYzC;V-(2LVlXNxTN=RP8_&G36ZiQVgGrbi3N3Ca%W8 zjZ(GQylrI$G9;Ia!{pSI9ELXU$m@V6g9{G|5g)&=eTw*3uTl#L?YUwO9Kk!cF$tO~?hWGH zGCSlXAblIlITZ1$cB;@5X@QJ6IZo|U<1n*+=2DGKJ(I(j!!Vi~jKhrO*dqlgwZeNp z8r2(E?utgmhCWa@<#bis+Mx%FY|V~3ux_>UoN0u=9W35r|ijo^i=Hc zUjnF9e7zXZ9rYV3NGe5wb_DVddKd#x>d<5g&W`+^3N999r3&Vd3hD|&PsQ~HPt3^< z?`+iXQaEQIre>|{4Wt(arE=l(*W`LECcAyZ`0TOuycg)N8?L=c=TX?|@+71$;imB^ zUM@0+P16}UrTw57=UHfBI?i}q0MCw)y0C>;blGTT^}u^w&Lfx|%esJgMDNgygHqSG zXHP>W-i|d)p5Nu;;F66D3P4ljxdzrraaw}4kk2d#9-7&Pv&`g@%4R%js82@c<;rj; z3Rg5WwlO0zbdWK=&~IZrNFEJ2vXSuG~tA6yEZch=U8i-6H(O! z|2A_S&$HZv_4EIu8AzMMw;}Uf#h4e=%NxlBQLWd$7a(eL>lv;O>RajVjLw@*BAi>* z%}48|g#I|nS+;wk!E<8aP6!T{JSjov>-XMdikHZoB#Vb;3%^}N7vajOAG}f*?@L-4ylx`e&?Jp30((^cco&*`SUd!<4S?KS)UDFS)|yTzao+=YweEnH}Ec z$zHsvns)N-=Fqd9vDdpf^b{pbpCmw{=vzuQElS^Nl<^ktwB+Zq>}7QOwZ;cWwJIxH?2 z?Bn7t@JSJ6YRC#e=e^TADL-dv-Ha1!@lNl~P+b)A2PD)Z-mv0$wSeM<55LMnys<*h z26Sm{t%yZE|mqXi)ZRoGM)`GA!%_P+t0J0}Q50a4l0K`0>Q z-69@Axvep7fJ!}84%jt{^)o}jBPqw395JGEcoSMr_)qPi23S7izlT;?!$d`p)xrtd z1XW_og2x$FAV+Z&L)CjhL|Aqd% z2;y(HOUMNOkt?a*h~Jq}z$gAXflLTfO9Qzn;D5?oeHykr*mMU_Ny~e3SpC#5p<5}H zse| zR|TcaY?nXNriuXJNn~2Ox)R|X)(|GVTV=DI!gY2|{V=uc-T)-YJCVb5G&P6~@p>xt z$q>&nt3~r=j%%fWswK;^!9M1h7=t?fe!y15KOWU*AiiMQ28-$;TTE|%N@)VZ`D`PK zXZatJfc->Wh#cY9G)7Odc`~O$i8?1Ef-mIc2gqxIj$AOC(O&2lb!gyJsns)$g<$z zoO&&}35&uS&t)k7pS9D>DV09aic_j+)Xm0XfmtT*MezCHBUgAws}f=FgU$wsoMeV`MC|Ew9d9g;ovGcr9ww%jqX*L zW{u8N%nXjEE*hmS+3SMEEyF?}8|7z%iGI2;GoG{`-oSfp<4N{)TDQ%#CPFW8>*K_!AL{_v> zh)OdC>%^2lHu`-REOH~GzMxGF%M6#jsZA{3rgV_ntqws^ywI4}QB?G^9_9j>W%NYv zOU2nr3<=l!0Fck4Zlh4%FJB$Oo+mmZF=O(^i43^(WyBvC>us9*1s7eb!#7JoG$DKd z?D^TgZdg>MaDy00>&Av1k%B+$oj5=#E6v0r>I zYVLGxQ8Rr!MaT8M=}QlR{=7RI$m;*Cx6tCk@BW=EI=A?ySJKGr5RhvWdl3G)=etF; zC+{y`JV$uk^>a%P&|Qdldjyc93$N&n=62pAzXSAfA$v>i1DC}+i#)fH(myUvViv2Q zAIU3fpG-w9-o9A{^=lDc#s2yg@B@M~MZ7B4-O?R3_`TR3r`dZX9bn18T%7RX;R*4hoWRm*jVe!3#`YDn`ToqM_ zO%rMjuGlnc%7abn$!$*QtbmqB1^_x!WUvF&r(5O&p*>g4PDAKyzCBU}FMN{>N;mJ` ziZ(yEDNV(*1lrs;^h@u%+Mv zp9f0p6)aFPJ7h}`-X_lo0`ysT?Gl3OJiL1#^c|VtFxWc=PnA>i3}K_)79wgDC2mLl zkxP4#|IX%{T=?;`XmvG_vc2Lg#HM1ud|RlO#B(l%Bb-=SH)&IiLi95>WlNoWVd#Q1 zaT!4sWf_OCnBUPj3`xDu)mllYMzy0OiYgjY8Y%ys(P}-j=`+`0nD@OKt%DTL^6~D2 z(DP>94hXGZ!4VVGP;f;As6`>^1OM?2dLN{^QCDG4`bqpw9K_^vU6&)%{5aGv;%^y+ z`iC=vnZrPEzaOJltoKhq_WrAKlr(?GAcUkb+y8HzK8-@|JEzj&9PYynepq~&9*!=x zY{=kaQ8~lMG}q-Woq`};<(oo5GiA1zG4A?mHB|m%KASl<%1>$Ghlvp%Bm7Xv9mL#E zmM146Q}EUVlqrg6Mj~Zn)oSc{FZ(I%q$uR(4N~X3?8Mc8)$-uX9>%38BTj#TTqQkWV0Av4fK&?4=j0+c%I?0gH*&ODhfjy=7n zCsOgURdBPUv@Z@w<;+<#jvbc*rul!b)iQgU;+;|c%84jwvNd}W#+?i`ECKtqEHw^t zbHI`)us5=N&LPpiHF=ffouPu$%+=*w;u?hW{^kTf87;|qNL1n!f}>3GiJApU+>q^_ zX!Gv|t90Sb_* zckyj#*Zh4V#y1TC-Btd$jId*Wm|U{QZMKdM~`9>%B^S-hmS7Bwr_C@&4ct{g;#4l-vONds8>} z1J>p&dwd+|rsVMa$pHE;SL?zn0_y7xLWjkhlD3AZ!328PBP}02NJx{Usd||Hb%|V& z5spPcd!vOGr`w9Ui|GGoof7)^BT-_G*i4Lg1}_0Jwe^4O;zkd4g!7GNino0J{Mj`9 zGa6;>?%jaSt1WH>6@KTPi25~y%~4Q_-_&5Rqc`^4`O#L2w+g0Mh>zlm zT`9lBR@^>C|B6Zb!J%#qsWK9~+#ArJ@+`{;s*B2;e*maU))1iMl23$yN@^bH%joa3 zk%UcP#cSjo0IQ51Yc;VN5y1 z5on91Fl&g~!ty_G1OoOZHVn|B#P#S)P_;;Jxs7%{(C3QkIEdexlUGejYkecD;U9H$w+&J$1kR=C|Dib5 zO-f}=xBnSU>D}()i>8>X#AO8K?94ekOwcfwPbUDKRLgXfN_?8*h)(Z+c$SA!Z}bUJ zs%?sWFxt0aq-792d38@8q~gt(cA(VxU!28ImG`cgfmSA!!0IjM9by1Y7;tfgDhW-k zn5wpq-pauMH+$+BRiAYzPZQPFmW5x8qEUG-*xrq(vYH3`Vf9w2n2k*%L-hSbRhRU) zTc9e;i8MjK$c6bJr{+2>3=N%0KTTFbsX5&T2f?&$p9j+OV=ij2SYQoiPAcAR9XiD; z>tVrZcf%r?^cVZ4QIqgiwm&ZVrb@;Iv~xhi^W*%E2br^`2w<`nCy7(j>PC1Q$$A_Rv znzmBP6zjLf6PafFy|S@sMPxe`bK+iDFk~A-_Q1|_T0b$IuU7@?;rtcv7U06e`@@-Q zfEq&__5s>3(}I(W<0#F-$&t{X%12Fw3H4}wk?r~kNZ)%q1g)2QUsQws$?-gh*Lx=q zG8bJ+L-EGsnsQK5EL{TWix*yzpvuz@=TK%*iMkRFW#65}VzcTJ4(PgVuin67`Fp1j zZew!SVsYJ5F%QzuNKF`UneYBAXgBhPo{QQixqJxHHB^xU+g_XJVL&+hI?^FXt?SB4 zKy$YkgAjkfsSYw5rj6*Q`mqs{EU##G!Jd&LqZoy@`Y2oo42S-C8HcXL@%JH6q+seV zLGXxpD7J#^U{(YiMfU2y)xCx6{%d+_plJS;M99o7cz*@@G15QdM8|_foY{%$=X8yy z5dWXb(VMuCeC&ttE<{Nz&O|hbhDrWQ0E@7*i*Uu;dbJk~k!oyV z2IVjZA`Q(1KB7k>tJme@t4x7AeU2{P?dT%@^;HwyQ+0WpJOIq^PRIk&$8WHSo*zYz zi-rRh9~D`mUQOGJZ@B#Z=D{&~uJiK9e@PJU+qr9ypb}w3cPxErN+S*r)Hq?SCtCjZ*^v$I<$ECEXo9z=dF%>JK{lPS7rbnAd zH!ExV3I=i)pX(?s8&-j7pL*Dnm@10Knk>Xr_fg@Pnu;o@tMLW&mPH;-P{Xpyks*Sz zE;Sb95mcXC6$NP3FK^qDsI2Dqe5CZqkXndAe(5B|x&jYaOU9JY|EBRKauT}Ydh&?}8xD$d- ztHmL3#2$GjD$0+oS&c=vD^KAl-LfcFJ}KH*u1E&7D{p-ep!_FBX4A`ky?}~peRcqv zHc;h{KIP^V4ZwU~xNHZhwQ)IcG(X3CjGleo-Dd{Qce@ZO=PcX@ksu12pE&&_$n4B6 z8|2aV%9l`+E&t_o42$)NBj|_fXf5_+eIdOJiE z$7OQtId12X0iK`t>jmTy=eEhGRhSX;X{L5ohPxOt#XS~7rZ(=%K6J@RH2{w}zcVH) zqxh`q#Dnmt^t;Ho&IkY5 z{>xElh)-`L2B*#8Xc01PbSOgjvmJW)_S`oTMECtMCIAOijc^LU`8zTp>U3VBXWAK_ z8-~R-Q*zK$M^`07ybEnyD3Y&_8igW$FX|DleSPOF7DpnSm%!nbj#gKU@@m^Y2CC2P zKu2rqomT?dEYgChB_^mAeb(;I5Mo!A(vdmK;+|WeXjYrgaa6kS4ThztR5Uyb{yZo5 z0O-V>(%PZIXxa zCIZi((J3cqm|acbuL5d_edvH)|Iv2|o)A~O-3Xh8{b7$in$r3nb3Pj%h9NxYh$kdD zX>G?ml`OoX$>ZN#cO1aHCwnV!=DA*r#nr*8UAZ4N)APdNC_{9%3VU*urMQYJwmWLz zC`qIn8{%~hXqh9TGgW|#Tdbs>hj>k0Y65H;UeCQr=Z-Es?^nc&B$>+qoy-VCosv)E z^HKcBCui8;|LA$04RngrbwN^XHt(O1RJy$BD9nFImxxr;tk*Mapnr&w!U&80vk@@~ewf)yF6Ln9Uvg|lgDZ?&CA{D#mIxeJbKCit1)qO2z&p_&` z&tieRG4F>=tiT`AVAIJXZ?Tc7Q+gdX=h`%E08{(?aUi34W#!m2pg9?dUKX)1rFX)6 z=#LIgTHP_a$sLi`cj6C`L-oa2lxklMT|!TR4$L2&z~7bvRyU9_gGL~em7m{PLr+nD zGOl_JH@R18dpqbhQR^u10kl-*@jCAPI05;;&>!q(XKp1nJt7KPLywk51mi8Z%iNh< zhFj0Ad5t>|9#sA8X9|~XcYFoueS@FO(xOfa`@0Ln`l+C}xtS9!g?gr1kMc6p}K zqVB8bI@He(6gW`#Oma!lICammDt!%#s=vl)I$dN*hNj$2LWEE8%d1dRw|XnGcNqeU zP}AN7!N+uuukifSCE_U_{Vzn{u?-X-Bk@`JLG2LlH>t-pLdt~ubr7%i_Jt(u`6QuX zJ#_l0_dzS5ytk8(em2r`84S5X{`3w?`fT0gFVv@kI}Yza5>1QF1o~N9H4N15iw>kp z7nnW){f@{?P*wF>wj%$qTL_Ssmt-Qny27^{i-y<%6_6Q9)eqz-Rb5Lb_I%@81u5EA z`>+jb$8TICMnli`q4qF^lK=(1XcsXogUY3k@$@5~+W_qXcseC*$>Pg-kICbA6l0&# zo{I3nK1@TN`|CL{erBGt3Gwwc>Fp$F-j7YGFn)V+%N^oAk}!_e$u@>wLzVNz7Kp^z zQ7;}RBsV#Zjqu5SZURGJXbU?SVs7Xe=&kcSKofi$|B6g+s=*%k=eTk-)GpHJm>QS}DL+Z-GvGM`W_=)cqmI!ODW%aW&9d>|PF zQd^apfW~X;xF18O-I@m*p>yovKIkmwt`h>9V|KU%Xi#BtCyZa?I)auevu(;?yg-f= zn$}IOoJ31BU)x_qd~SEzXB0oBTX_=YkNvDqq5S!cn-Un~Z(x4}{y$V&x4?Pda(Y3E z-D~qFYNR9!ZpKV|UH zJ?kgzET&NpWjRo)-XRZ*@0YZL)2~(QnF~R~uOb|pQ<=*OAe1ogLuQz_^gO*pjpD?K zRTJbBYcM+ljqY_k51VQv@-%SrtjdCQA7^#AyE}DB|lo2}R7? zqs9)ZFigc&%H43`Es`2s{l*l8y~#QF_zTD~@pa?0}~&BW65o)Dfgu z;&eR@D9_r|UZnC){1pfB?942xHyo`rGKGflW3g!oX9N1gXGLid?sNYM_SC%n$Io!W ztT!g0%{&|a-x1CeUns65kR#OqIZwVY;iH1Iz9{Um{ac>tg zqqEueYe=%wtLszR(@+qbi*swlW8f@^_Davgvd_6Z+^kGn_Bfz@8%#+gE^mD(EVsaD{M1VGB`eS@`xLC@E7!{#3ex#Vtr7 z_Lh%ZGFu61^=b?Ubm6ObE(GNSUTKm6n#i7MBj}{AG?&@+`%(Fh#YaV|#|5p#)K>bY zCo+ZoF%66Savw)9ou8A~?xJTp{;zb8lgvGNq26E7gRc7AAQ!6C(r(f-n|jCHhoti4 z@>c-eYBf7Tl(k6-fXdiM#sF2OoK6I^BQXW~NrDf|wt;HXOVp&l@Dgizo1~wBX_;y( zgzgIcA^^sTzxr^T3=x**_a2bf(g)nBCg&|YYbE(fyp)xM_+;HREZTbS^g#7LmB2YO zHLJnW!1d-)L6VE%A}n5O4H01RmAk2+Id%W+6D04<9X$=_cyBFAp?>sNMI4@GE&kJO z&G(gFAg}r$2PzfS6;wm}=-O&NQhDbI!D&{XS52E5_Dr$hC%vKcU z@i=<}DwQd^W}xZ#17{e5v+k4@T1mx!h z2D!pJ+3lVf$J*e_Tr93(ao1B%lS4{1*z}30#RHz;u+~5n-r?LZ6m|509E)?h?qn#< zt>!=}v$y?IxaYB&cLt4qYpn+5&-~Rr6!HhU{SL^#PBA>YCF)e7B=U9(1W+-VUQLeB zy1i0~>|x)nbV2xy>*dVcTU3^Eg5Gh+n1oM~L(7&!rz5_Fh!>gd-Ein`n(WuY=Ii#o zKz?3l)JJHE-jlNw(CD^)9EKdXt5!_Jh?27mRBc6C90r!ipgCwF^A)F}B~4;I7tqG* zS;;uzdb5&o7W$iw5K0{=%wjC%^uU=~BL7l)14RY-iNWcI)IdGxZwaqe(4Lw))=q>A zQ!3-A{2}?mD>@4e-6?$9v(5c@7>H_{H~M1JFAHyBcFfECr0D&ggZ+@Cy}bt&jb-h` z+Way8D~wFh`4yma;8YjNOqf?QGVi$C1(~_)T{nPd&e!emIQMw^dJ;tUN|6&5TS7PG z0co`1GA?l!@o;Vo#%F=j-1n)>+^zCYMR=`rb3AHarIvWZ;-bt!rgq)i0%pYju}K1G zrm~K)Ua99O3f0uFXD(xQCk7$Y9iMeq5pO@=j*GaiF}eXJojG$MVRWPaFJQ+Gr(1nu z7|sz5_j8fS(LN1}(wh|?p_?wqcJ2NOYnjHs4$&e9EM%Q0%@&H*Y-Er1`bQ`wyG2Cu$;k=gzTJ2zUDWwmmpK$*XgH zlit4LNA;klye;M7;FK7b$t*e_-H-VDO)JV)F5Z(VIHz-g3|EdqC*5k>f;{3Rm6S$- zQ_`TnfvUf=BkEEYRWDqg=m?$5W`e-9XyG47lg@@itRV{(Dlru5v8kr6Mv6@>V)GKB zZ&@a|4@r|vqD|OzAAiu1)H8kJptj{!R(ip-nVAFpa>njn@jR}Hxjx4+)L#Ts;gb2T?XYWOy z_)+et-lZ!khu%<~-0SWRPKTaMX=zW6g9%7Z%)%?$^BHe=Dec+jkoN?Nj8|K$NPF`S z+)nH%GH=<6JwGq0s=}UI3S)=JI?1KWuK=p|Yv6$B2eCU*XRSIPb~fK1w z;;9bhrh=#1t1|&A=TB8ZP}w%tY&Q*4&jy>d(5ay492X@G@06gQP6JL+h>!ieA4H34 zZmp)pA>rBI0T~wSY>O@(+%IN^(R+9QAd#}3_K`w-O&~iQ@qw=4NWX5E-igxdN=+(^ znAjuE2I+q{VuP9*_ZtUjPthQ+0@WXUR{=MUKlg$i4BwPWP$!ogCV=gepK)*!&5QO( zk=@e%^d{}u5?S*q78{>iD$%;Em}X>8uyy8uyh7c|)On+&ADhnbJxd^o`cH$f{n&j0 zwCB5s$FSJ3@Pj?z6c)7(C&`mP&SOv3vWt^A$awoaUdNtp`VO>yM$21?#oQu}5467+ z*$a;)r|^=HN$I%oeM~wsPYT;1UTI#f8y3&nCBpaOfDuT~ceYCfr#0$QE+lEKZ!INB zv>W0)k%^mbpN&jUMw6XTQ&#>{9B<~GQ8xf>>JsT8DaTunMeFF9YlxS;sPjVndylh* zsU;l~m#X1>nM)S@BswFmLQ69B>1f`ZR{9u=>{_R4FwKZy+T3?yA9G|rJZqpm70Wyi zB72Cc1=X9y-dGFu#)ji7yBRCLm5)QrkX-o~xLCpW%xP*GbYrsU@&J6=o=SoFc%?{Qg}f zE*6%6tbBAc!zf^`RUh{hU}$Q0oO40^DG$*~idV30vtir3i>E>`N@*hpm{Hn2djV$Z zZ9M=pnKm>|qHkeoYkp+Jd-(ne9C)d@M{#5+$|k(PG`6u5<@ctl)*=1*m=_3dJi8kQ zyCUxK|Kh5c6_64Lp+;llnX_@p-CPJIO8G7rw!M6|1$__7)-lsl^Ihm&uRT?~y|ieq zZj!D z{eDtnne2SAPe^a1wRVk~Y!`1vhE@hYQ4{y-@H_`_FI(XcWM9#KJ1q9K?Hiyym4fB| z$aBTrGGL?xk^U9_B!D!xN*agt0)(|MCZne=fcs?JH19_3p4fD`W>3+lK2C219)PcB&O z0o^KmP)$&NW$bOFnt$YR6n)xyD*rTCoqREiHtTP#N1L7Rg?xie4Vmx356UwBHiR#e zwpCHMBH+g(Kw9se8?d2!X5*9jJd&SxZpo`I^q$+exhxcwx|hri5>&ED>;dC#U3f(% z(Se5Zj(ZI~ed3|@Lj0lpQ61C^ITwZa5xvu1%5QS?8pdM5oh%!WDp=!G3Q3o&;tr9g zY`(Q`1@wr_o(j#6_bEX0dhI`&fO;?H!fPnpP;T!Cop|v|#^#lu>VdTB6u@R;-r+C| zPQid{Fxb!j$M{|nzxb=xnIWN+pw06v+X~uL?8r@EdjBmemNw@52BYo!k8mtNHgI(aK#;81$)LxMshLZFP zujnW`mBWG}CEaWYdMEH=0aRXkF9>dCd3-(&MlBWIYmn%$>;%pY>GH7OAyMX$)?qZh zVc~N#5 z4NkZMnV%a-%}BJ%sCqd|Fwewau{n(1xj9)G?fI|Ip(xb>=XHo5pBjAyZ4xJ)K&m$G z5jJK-E?#c~s=l4+l|;4ff8K9I{pwU78B!I`N{kqX!?Qf7B4RDE06OC-_d}yv4w53SpqJ9tg=X5X3@Q&bOJDNY4-%t$x8NE^nV~jY-IQzN9g8;f|PlKjPz*zzDecROKIP~)GKSuK&Yd!{dZBG0REdJK^lo=7P zDK^?P8Pse8N;+wb6J+*!q(DV&?w_Rs+WzP)m#HZBIoNY8f3Ty*K$=HfF^0Sg|YV)Rwyb z2OLGU{cb-Z)so3Pe<)fy-en?EW>>%CNF`J}WUiypXCqNkePjI@LdIr0_tWO{_OAEn$w^MeKVH%sPx+TmVC|VeRz*OGh~GYscR9X0eFw3rgSnXnzH9(*6Ih=&zk}Uiau{i?<3>UXoQn^6d71NXTiw zCZ?o>uSPtP=v|)+)0C(!>gW1-df&;Cb$*a|a()*+Iz=T}CBcaxT5MCVgCq_?oNwrC zE$aEYpVEs{j{88Tgt^*bS~NQ^onXYf!g~twGCd_95`9w|?>8)7=2|{NO-Wsmh?lXC z4B1yas;egkG+LpXF=h84OgRJOpT_jm$#g*EzWguy|@T zPz;+cI}rq-Sf%_7G+!-j#iCp%?}MbCTZ}spKXJ*4iC?=_45-fb_kF0;=C_ikBq@Kr zeLRHvX|%K)j%ZDj!4cZKVF%#|sa^LBpcA5V%`opwkljt`-+7OSbbPym_*G zs}zfIp4%~zQ}5ewkZDr9J_(`*92rC=**19sEY-7t%WOI^Wx$wQR`sbcXL;Ei=0M3< zctuCgmpSQUm>rwQN+@NuSv>~&FRkSl0R7?Qyp@=aT&ZwJrwa2+mlG+4lS>!Ij8z$b z7o8f)4hdIOYB1UYrQ3Y8}qQwyvx>Fr9LJ?J?qKThE?G{#2a=o#KnbjzE<9 zGhCz(f5vAHUVkqRj8?qW6N%K-5pAd`xE!bvn6-$Q(tt~v=i`;3g> z;AUArNXKGv--=OG>h?Ujk56(Ge#s>TiYPvZ>hKk@$dIu4;W$jhd8S?gCP! z{?QBJzs*MA0-IdZ$(($JVdDd&zBp666xC0rzojQbwVk<}21808*kDhkrW9);&dSxW z^Y#wrmO)uBXO5j11N<-)7PfLLJ;cdVz0pB8M#_eXga~?{D>S_368*B8xoX9x4tnA; zlJG$9ME5((PCRd;-~1XJx#Z(TXTkq;JvLP>-iFk9t$H_$ewmQFcS3fFlYFF*Yzpbg_iHGoE6bwz&m8ypR`hb{oaA45p*9iI)8kL z*W!&GYsG(dg1@XPW|fM518-^GDix6ueSH29Winkmc_EFn_#7kOW#OxaggiJRHBown zxa5M2m>(micDjJA+0j6Ouf|rpfrn_x5s5H#yEl)6IJBn>7 z-XhYov1y6F5lD5R$O+-9CTUoa}>Zx|w@24SO?bU`%G^%dRXew>m z=DR$IGAY6@8JIyVjE^)-vut0TspSB2j5hU~d~4rLMfQ14Wr?F8&3(L9s!7XD8G@$$`5g(^G}l_Ol;U;bm*dRvHoe6K zRM6up22?Q4@dosjulk`>tJ5QYEM8XMfG6f6>|aAo*YaBwaF5e({i!5h!n~aajG7}) zt|FtDcXE}8mwvZ&E9BSRD}$$<)4Oaik%a>+SW@zSaS@Q5c2f#vVugnCu{e@g$(Z+> z4hd>1sEQCE{qrto%t^1?*HXw=XuWDfHMQA&=mekjhky7gTH^NfC5X=Q1AS>R`0w@5 zS?qZ<3_K^K6)Z~R{M=Fs?-{-Alb|SPMpi?`+kTkT!3@;TtTC{k*;VR`_`;H>S`3tP z%sOzI%g{0>R}|+s*cXhH`w=I@@_Q;qlEf|zPCk{LcQl~C=G&ttMZo?!G+%6VeGLA+ zJ>n&xYU4A5MP-r94W#aK|8bf~)d})`0)Oi#o=)Ij-6*#O^jwp~Ku|G%OFQ_B+*j%V zebSP~1N65saWz4w&L`@zYnY<>8lWdC8@vFGQHjqGl<(m63==ieI#))E=Cc-e@K4We z09ErxZ%$xSwQaB+HCi6u=mJr)M^vbE@LLr_bbEO@Z5bPu!bo~ydJQgSEjx18Bl^fl zK9F@wc8)Q9YIB0gwP{|S;C`6>0GBQ-cO*s}JlteBY^s!vuwlM%?gfk{62qoUCt+E?Bef#%l>ujo2nJKfeAvG{SFpaDgS z7kz};W%q*)dK5HkU3ofU@rH-<``ZaX&Ofa7_yiA?=e{?6LLcn$diBp8_;{&d%but-d0znfR@w2f|9_?g+QPKzHbDze?#321NNw<`fn>hmY0 zs_o_Td$6_nGWctfxYkmq{#mSHjV zcp;EV$1@@n`ks}~1~eim0Zh5mW?Nb`iB4TY@5~?mt~iS_)fxr%h`*X;u|fR5PG%{H zsr0JPHdNYvDY}C4X9Ht5*iOpHL*^wLDP^l z8D^Q|Yz&5TjjZk&KwE;@3FvdYycB0iTfKcOm?j8Bm@(E>%{~lXl|GU=Ab7INs8lJ~ z>IYIjqgi^=w5Z_{7tYBwRQ$*loDQDKgQ2-YK559*6ziIZ zmJY@H}2O5Wpv>^R4jE)DY1-sUJlm3FS5=UlL9x~de&rWD)%JIjwoq5O%lZVYso!R|PEy4r0L7Y%Vr zm^T*xE$>dIfs%;Rb1+cqV8;ziPdv^9q9=!^i!ghVfb9mPXXR}Z!V~NqfsrhErz}_t zN!0txHBhf=jK`c(?&?aM2(`9RcK|KsHRb?Xq!Td1xAu?#2U>05MiyAHje(G_?My;F zJgv^?6{7xl%MdgCwXQv&8rCga1^LvHl%-UaA}nqOs${tw3IVhu@Vg*D^LucCni}!O zl3bd_oSe2HPKcH{M&HIMv+&%~7toQCT;?|7QIP@OktQ{wB+YP&BalzVe?gnA#@+5% z^tm3VBT2>8k%7>O{mdCI(>CuBK@pwPBPbfiAFDy4^s6$odFjF{x?Op$*cP~H@iIJ8 z{z+QE;@yrS?#^&!1O1;;)2dBaJQR|^4_&-jYRS`i6wxivOXK$&nip?@Y|kb9d651^ zSBb+c7G>O)7$Co_EUHUbyxFm=tc(^oEZ*$MJ~(vMNSXR$mwN$vuw~|bf=ZTVbXM9e ze&39n@s*Yq2q+U7P9&Q7W~;)l|PO zrc2K!{cKx}ub`-?Mh!Aq8sl_4bZSQ$51Eow)5+ASJ3ER3j3lb6;I9x>(s6AKk2am+ zyyF5<#?@zRk-yiv-hlj3FFOD=yBHH7ia2=?r1I>RRiIOD>)a6Dk>yd3aKAU?Xus`; z={gv#D>hvUsEbN$1aw&h8=J~r+nEGX?U5!2Ko54zqteokr&GwN9FOA#p`@v3;PexC za#GLs0n@}`bjxW5Tk?7*TfkK;{zF^j}nn1}^>hurfG59Qe(S!2L4cTV`%017MfKr4w z6^jSQ!Z%SzN6$@TZEnEc8)dGW?8lx%VY5Nl)5`vU3HQ9|=LcwfP71_REc49)(NA2i zVbc`8fEnF!BidBF}!k%}>HkA6hY>C4O3x(i>x8Q+aYR@T zviF1jztYqpIAU5H{V}3N9;={;f{gdghL2l}HyW#^%@V+K!5ezJbd<|DsmRuqhm@|Uy+5mUMJ_o<9YpRI31 zrP4?9@Q$cIU=Mm?E%iTyO0zYA8%ZgJ)V&A!AD7eyXz6^!N)j!8YL*gAZ2%Bn34ML>q5G}WbPnNa^Bb9EY`zWZsEK$Nyx>x?$j3F!T z|L`c{xox2rVF}5}9^_ZI>yw!L86z0dwgABo;D4~T7uS44_{=@@IjlVCbto;>ez=R` zP5SXaZorr&2V4iV>rCJdK#PNR;G$=+Ir5M>B-~>5g1_fn9CLdSp!*d*)A8?aM)xB& zMPsqA=tw#;sa@`XX~te76JF%)j-I@>@QUt3d>oh46)!jRb8P5Pf9&Dn_1g3#=$Bh` z467IZuN@uDo(unol0ui1q(o7y^pR^f1uNqIKc2oltf@O)7eXT8o`gFBCLuro#h|F5 z)RK^3xTt`(Vv96HwAwN)sI}NKmV^WX0Zb4SEw+H@(5Y3RGaYJ~7Q#iK))DL3;;!Qa z#7bMA+0nXt?2NnTaQNPJ{#(!Ye3$oozsvfuvJyV4KSAe`>E1o?sB-cwXeObh$leKv z%Zs#MlS`YSb_MOm+%*>|w8#F-1z%HW`|-aEDa`cAzY9rE#9Mm=iU~avak%}SDLFhx z2MtB>rxDn;-xQ_M6idJF5s{4Va<=5a;^Aj>P0*g>I3{)QwvkX}Rb)?4Y-Q(UJxI2@baon0r(Yx?KPvchkRi(`20_LQaTZ3{_4{-PFUZzqVy(ThN4bQZh$_(#y@ z*R;cxgdWvByHW0PUD)do-WYq@Le;q%d~XM#?2LGH0KtoA?;~-|zA%a{mj0;`Roq%( zL}|J9xGr?iy7Sqj$V%CE9*uFlO-M5R#W^+APAxFsJD3L2R%}yFlCb}jIFE#^ zPYiu%mdb@IDo&1^8wf6BivDpD_NVJxs5nI-ZZD!ZTG^1A2vRq=r9} z1N6MlHzV(-tIl0Oy`v2`5c)G-Cc4*t;n+TOkYd>s@>W<(=%5iHKL%lzrJ?s#-V0Z> zZ&Vd-2s7|=;TuEe5BRB)l$S zmqRG;%fMbMwQklz=w=yWgnG}tBs6>HJ%-QHmL?x))~EEKRZEU&PSPwpnO$GQa&Zpt zM)w;GUhx=-=SoT;v;;w@rB&>FjzKL=17BU$~-*-}?J< z;Awt8k~+icwEHwUOwcE6rmV$YYs1h4Z9P9oNim@_FpG>kFHPkm8Tiu7_$6Ou!w?AES#L8lUx#tH+-Rlus(SNJM1Gz#EXPd zQO^<}&T)5jGc`u3xJm+-2G1t!*+SO@?B4RQ5qNa?ZLOxfMR_T~;OD%_@)DJSmuw^({fOl&-5=4ce-5+t8GAl?NlqrG$O0 zg$g#xIZ=VUC0So$=)XL_iSRh>e+S6~eXYd;Ock2>m=UX^A2WY_@E&%&I3NU-9SZhB zWjhlC(R@0KhZ@xm?J6xMh zYarbrj@q{P*v7$Hsa-{%(-eG>csiRNv7FC3JHcLjZqhy06-}B!Pt;o}kSfqug5cjL z$Q2~yys_64LglFhi`(J@nhtr?%2V`C(7M*SNP?u_Q2Wplv-l{ZC(0Uz=z09HC8Vlq zl&u}7=+aNNtzAW*hK;P>6G8T~r#EI>$-a5v*P%|)lyIJ|PCHMJlEUBH3wzn6;{{}I z_Eh5e!005d2J$u&Tj z@|%G%-zEDe%sn~xw!pk-mmC$5{NxVyRHB<@LgIOTQ@i zgNEYp1*Ia&zGo{d9;)N~6|soFe5$jFDx%xU%0`n*)s-jVh zSg3x=OI1+<#}+7Q$*> zpqZfkfnlUtRfOa}>yc)o%j?2)F#oJK!U9C>5+3TDTYbcaHg$ZI#Pt4h|LD_b^YvT- zGo~SOEmSoZ>)G(Sz1dm`)eVNGY>cTnr-_;9znu&M)c02=04ndsIB06`wqnYRIlpFO z%F0{*#zvd`zH&F(M7*Z-D%wPD99@foXac^2PgC^C)kyz?xdZ7Ss%p@mG*vO&0+`Qy zYpQ^zIDHONViov5hm?wQr_#XQI%z#~e>d8=!1RLXBs71x{T3=>bb0R$_~b5J(J>^C z%SPkPE&K;$ItQ3yGdC?BSJcu>*Tr*$)4PyAu{gi&{vVMvtHp!kxOScyQ0Px zc0SR?S?AVsm{{Pp>+6Vx90kW8bjA9O5JXkD)C9Up6E>YEMcKkMkfPYBNU@#@AhsC} zkw+&E8$}sl=~3hplCQz5SbgFOx*;|)W6RM6YIhHoNpWqcGV%ENbMqrIwU6An@N zRxMmnCbJW1SBO~I@tQ^=)+&gOC*z^O=y*b-(rrQiPrvmNC=?_NB+*HIgSH%PU6{~H zpgZfeGF1MIO^CL6bK#2ODw?|ciR#kG+%gnzV{Q*QRE2kH;IK^|VI{@-?_U;^qAk%S zpDN!z>GU6zacZRh1p>{F_rCxNpLY{s$TkWTc52w^RBkINT3I5^dTP!z5uvtKh(Ojl zc@Fi*=sm9%;w9m>&K(75r2-R=xZQ9t(!~mQZu@_1bKG-GcjhHwQxoA zKGNoPkP1@2a7Dx@Ct?8k`vdOij&Aj%w@Gj1!WHSs;y8aGF!mSRw@?t)hLt&}NO)m; zDJdppxekzGPK$Rr2s}|%OK3X((LX|D8S^h_u=XD04?QHZ42F|Fm@(Z+A2QaPt3M%! z3t!Lpgs2&s?);v5Fg{=n)S~~Z6ieXUyE7>J#l&(D-7$2JLX7N|oFRAZW9s!}tBAVh zprPYLw#~dni5MoTLI3p@FK1Gm&5xlx^nYo&LG0UyqdU>P&0CdV`o)q*_X(f#^z7H9 z$gACOgA`}{-|m9qF>Wy&<|p-`^_{|Ui5N3)eJ6;K`7MnkVjQt+Gojezw2B;xGM$16 zpv}+gAqAH2(*W~j9p-hf=XMf_S>lJ7^`**bjLm57m<&b zc!}9#!Y%C9BoCF#&&;w@Zp&Lv3=*k5M!yL%P7r4Hp*eU74@l-L{QeHm(DY4}L>>^X7z?NoEb){TXH?uG}9>#%I7C4Bq(fQgmh5 z!WFS4dGs+dmN-5Jn0dc$FjMNjeU|jvqh2~jOxr~-9iv2a)yusx*x3O!By)4NkXl!b z(>U^olm3NdPX*1$t>>G16kWI%Mc20(LXOh@^l)4AjGEljP=Ak}7&R;YGwCQ*uB*wm zb@41Sf7}nEYdts2A1@@uc_uaXnx7=ts%|P$oFm` zQjqEGu;*#Xx&FJvP8lU8l-TLfp)U08^U$20y_SfaZVEL4&oAEb#9{2Kv!rSjMDBGE z{Lc0fPpHl;iGgs|D-TXZ-h#()%2FscLQ{M$(H%}Jo6~2=X<37M7ODmOj1;J{?9ouQ zMWraAI@9+0C_=@5{-P(6n!B#4BKqZCAteraCfU8-U5}dV7IES9^}$dIZ~Ke$LDVUy zqbeSCdhO74)QOd?OccKt9!?md zJT{HQDu0-PPMXMqc~EVWl7?=RlYi_TODh zt4F3Qo;HsnQ|q<>^vUDSI@t4se@uc?O}RgS&O2fmput)z*jxA|*jn;A$|*KLlbej7TCJA{lZV=m-R{`f5Qrkm{2sxj>rT%pWB9Vxw6Nn$@NJ7{H&*XQLfU7Op7!@i8A8XioW69)u$A z6m~(gTyGhJPj31+$jcex9)Zu;51%1=ef5XSAk3fKD2lpSse=1;XPsI$}gs zRfF}EyCmElxfj;wB6w-YS!O|S-VB5Ay8V*~XpS@$RTE31&8w~=j%I6TJ2EPhxYr@j z=(1NpoxtW`Zf&0&$13p97O}Bkteh+b7Pdl@!K`6cfrJI{7tBhi^6M^dM5LhHTdu^N znK$5z-Oj(ZApu1${x*_fxA;w!il=t7gdAuT!WBKpahLsX1${&nl<>b5^t8@? zB0W=0r-E~dc@Xl3wp_9-o}G*~b5wmqMdfTbDub$il{x^NxJb;1uItoF zDSPL_?Vjk3VEU zHYhDjE(ZC^-A-0?pYK;Z^ojK)-7Lai^pm0`jO(=Rpu{2fd;)vJr!kEEPc^WlL6H(kE8VYx+R~0lR`H8JlIQe*2R#$O5G|#rgrDmT?o~> zTcD*-=I|&{0M$gX{GU#U|DfLm6}6=CqbZW8QM`p3!XqY71){nRdA8*-2rn{-S;kEnOHP9Py%Tl;sp|ds4xq{rvyK9ldwtUu3dK5`djriQ z@_lIzL&}z$+ki?Y8h|}J((pFy2ksryBP-9}q<}h9c%TdRysSoMoj0>pIcVN9?Of~w zx$jaDif_&nNl=uX(mm)CZcW~c2ql=T8$ebs?X-dbTlJSx)UWG$pbDy%H1%buuHj}t zRh+l1nuNx$HhMzy*(ojfvuo-i5uWR|AG4zp+(7RQHdHn;^US-Ri{`u9uSK6({dX+K zJPX;rjH)a<35g~&_Ss;+H|NECG}?i+Tt4+wd#~ICqR$j?(S4~y#!>)fiIsmsN^u4g z+DCsx3!aOk(gDf4UoE6A*Kq^gfZmBG+)3PvgPfayQ`2$sAh?&DO=ddk&yg>qAwFEV zq9+0C^P14*xdoYz;ZwsJ=>ne~yyKWLo}_sNx-`?!2SPdgr+&BCPH1pM2n}}qhWr5z%Yjt=tckDpE z5W-AdKgMoe-w!%Ut9!AVr>c5msTGWp=EM|wC*?co{&G6k2>0B*hg;CX6;3cOm*thy z0qCM%v@x1KqjC%T?^)7J`Zjmv2Xw6AXU7=-uy|O}HN>2A(9KFS{P7dmdzQC^Z>5`^ zc{~fMMLtJ9f~v4AH<&P)OX6dzD3nTF|99Be$__K2f;qo9=v?F8F&K{c69tzW5&!FR zKOraOc)~Ff%JUnKq|l*GpuU>;0eyn++ccyiYaF*P1tlL)5|)6!DN>8O9=2$NLJ!A>|$ zI=ICTN%>{ucy3)hYbqk-39w(~R02(jOAj!KB_h3@BC#b(9yIeWS0+;=BQH<}P@OK0 zd1T6Eh3|rDt5xR=)u2_fL1b#o?S`spt@{g5l?;n(h}0SPfMf^eaC4O%-3E zcQR7bj)zf2Jg)W4R1?mGJ;PooQ}}$ZjWqkY9xtLzx?U|ZkfwEak%4e>Uf&}dBhA4J zo@3CoH}7)76R7KbT zTIXL$_DBSp2A&eDrc__m0FN=Y)`-eKTq9XhkF?y-+uoZNu=XM2A zn9((NjmW3B%MZj0CFh*L#%h)W4PsyE^d5rCgt5WsI%9V+d|I}-yMvA!nQ|SPc5Qtn z?0NNk2UK%ff?k7a%}5Rg*;O^!n)UIyXC5eM!AMoo;Gsb2)=2dGw7P5@~s zs}YqN4f@g#^u1i<4)%XP-ibB*7W}2^|9RU@{NXT_{2Kmi)Awyo^0o4#O>d3q(1^9x>7A}BldjvplEa}+@ z`_BgdWv2nvWe92^td&?z=t%Lt45lJgCnTV`FZSw2AoXHRGYkKc&J&S@OIBeTQ`@(p zcg;Cx^3c2dJWpRlsvnUty}!NS6ndwrc z$6@AV5ccK{*jr9!11V?usS3bfc>D(Tn@V;=F?6&Z<6OG!DiFGqYdi+NL3FX^Mwy^2{ zWBHAKuawaP2tgswcR76v`~fFnh)zE@EbC5d7H`yg-^b~2I&}KD8TNaUKUb5z>c#re zsQkqTFx=XXX*T_vqb}t!1KBGC??@oD?9B=WsDmXjX|NASnTsU*{DrHa#lQ8%#?-@H z`cFSfx8fQNoo`z_*SeAL(5h((X|n7)){;-N=IEXX2oplH`IJ*mWmSxx&Pm#jo8WWF z3j*YMm?Jq!I6F6`9&p2d@^a?vM4rz&gl0rftM`C#`AB~%$a^VNEhO-%^)7D6)6TiK zwTIqO;?+NoNHN)W0A72lAB1)|biSxu>Bdqqz`wuL6)fF(Ba};!u8;nZN-jl;HgCj{ z1y-$rd3HiRQ>4b2?MO2TW2K!=_DI44!FpPsx+eWPjK(oaGO-SA_ z&da9wI`?2bcoKSDN&zJy1CM#sWHYMdyATdE-`fnHlG+?1ifg>Sbqr;Q(Gt(vBgquO zntX_t4^E>hDlp9^!?8CZ)bRdG<0|ACy3;6ljVq}hH8&;dJj&OqR3$I{CbxJ_WI`SIXvR2 zyi2bK&;OP=gXbbalpXQ8dd^J{wY{hEG*my#9AbKZM@%bJgN!lDpn53beic-cONX|g zp`7EVq1t}U{~c71UCOS3s5KOH#GV@%c5JA@cemZ!*vl(@^v76VUp_}sxHi6NRNewieCp77VeN^?! zJi?rxK8w96_Y0{&lY8!Spz{?QtDFE`>&e21^E&ILFz;*O8`1iG0|Gfgnwp5?BlWr6 z9X`mC>+yTo_wN;2smM0N`%2(c%&G*?+%ceLMtr&MA*NXtVfj5&TQlTKNYz*pGY*y% zvVY_;xAB>mUxTW_G0cW)qTeZ~>Kk>*NNRS;_W&hqPy7x^ec8PCee|J;> z`P9x9Q#Y!I-Edq{xtDFG2MDeGcr{umx=e3t>rV4_(P3De77$G*RE<0!nq+$Gtcgsu z{+mkhj7T-LkMss>JE!ojbn2dhL^?V>nC#z2ii5n`-_diU$3nq(^mnQ$ExZjWMOzE|Ft|V_&1yz`A<@u zFZT7P;-y}RilyRl;zny%Q_4Tq`Myf9r}tR)Q&Btzi@~eCRd9nM-&nXJhdo{~LloKS z6ElQv;9X7uuT}BKh->Saf)x77hu-`1a#T6Y`DyDS4V+h;Hlj2ALVMStlajP=0?dK1 zKtdf<78XbxD&qgtNtHKB_o>zphsqooiuZ57?9Ft4)s|?ql*#SegJ`+-uh&%*!l8yY zJ)vk;w(lmz^R=m0C_SmT#!Qu$MAVomm6?+}UMIbjBYy_!9QKifMbzev+{ao%U78qz zFFMTcPGr84AZFT~QmJopWf6%s$=o33c8A5~TjZ==nn!TB zdza>sBFpVm&M7KY(y9)Oz*rHR%BOM-az^RDQq1C;J!coLr~=|pCG?!V#c0mo)~isx zSI&r0fWjstVz^D%U~3+Xl@YN63s;nh(EUBa*FQds4&iEjwvf#6O?Vrytn}<4TMtf} z6#h!*D$!mA|6H zxA#tT(TKa~O=@)A!WA`j>!_=WVpytu>L`XvtjqwZrKYAgNHOQeFaVx-CkT4$x93w3 zxwHQXN_fcE9Sk~j`n_a2{-9tJ#o-iSQbZR|y-N-DJbNwN6bt%&>EzkXn_JoHEF zv!~;5%gT{Aq{3l+h>jFT2UpY)``mj0qtyBKRNfQ;oKf&_YvZ_2*J7uS7wG>6iG*hN zzmUvo2*)?3&R(wqV&{vK^fI!k?1k{fhW2>lS;$FxkGXyLQrQuD^Y~wn$1=hfk1jS3 zN822|%Ix@2(3?WLh;`C*pM(}c-YZAw`v~tUevI>>=QMwn1>UDu$sKM7a}ntSecg&< zi;o&|3vzm4uSpBI^_X59zc4ZT5>yi`A#-H^ShQxGUaq!o$vFb2TyE^86e?iM)LXlN zH1*b7fIqAHR78<p0|s#k8ef&QR{7p2LmdCBU3GDz>cMkL4U{N zhCc)TPT9R3pwIinvq^%_&-5;X{oQfV7DAfkbP6(;%530lR)7#$To)YrZquVk{o2eP z2$fyOHz7*XmT(wf{prffNb-xL189e!2A_=xbLY{}CXm$EQ?!!m*WV(2{itV*m%;E|3_>*^{r~t5A7IRUVPXS_%vK^Vaydf#K0L}=YD}G z8C?6brQE3~U5y%nE|r^_@kJW9 zwMD4Xx)NqSx{JBYB#U3}2BEjr_s}^abK-9R->gqx1)uL;S7Q^5COy7BLE|}+9=;x! z9Ccm;*m?3^-AROxTb1)Qsj|f`%qW?qbHMZ^-&jD2n#1o^VCKu~e-?oz_iPPnH(2TR z5TG>o!~Tj$FW;R4c|`&28VG%Oq0p?1kvv1BjYh*Oh_q2QjPVw^?Cr-m$zDx709D~x z>v4k5O1Lxt`0e*v-bSVcrOH&ab7&(MJ9kPK(}hLcy~@}OQZ+g=3I{PlY@lUDVL3WVPJia7Cb+Q{AJ^KI`Z7J8Q_3Vk(Omi#c++d}jYl1_f$aZ_9%A$z^o39YYW z@k6SogLx%-I#Fd>N;i{zZr$q_8T<2p(g_!jS>l)WyU6K8vwYVC6X{ON0GqzNbIARN z^+;*Ja?zK)_`%s!u4F0Tvs8U@9-X}oCiL+s{M^WRIth(2&rU_E7eDw4GCuz)oHlz5 zd6HA3m+6!U@PjrTK>ABUCn7Za8Cp1v$^h&@F+g_K^+^a z&)T;zswZ9bINkL| zrqYEgD%6&Fql7p$H59609sgr=E0t9L#Zf)#+`eSF968NZMw*b*;ffhK1rnWJ_~4#6 zY5&;M3RQixs0pfl1;x=6s((y%7@@}aqYGcqkG^*9fx@qI;pbWD!_>bgy$JjIhTSSE z|7fLuI)t}-Y)pKcqzIhKYbDu;pIY4P1XX*zpc365*of{MRn2sx`{b?McxVRj3t&E2 z^TiDa#ict=!~Er)YA#KbUh3fn`UXxJYSH|$$7Ou9^d*;O*n91gf<9@DbqDo{IWOnu zOtduDs1Xq-7HwbvIC-2qWG1IJ??0BqDWBuyMb$I1_g@E5{P&CV(dS(YZ`lA;px?qz zEG}}|S*2}4rdBVl9r#DmJeigldFqbx&4j!nV)BnQ_5uH%b2%qaz8?lMBM2&Y^5aB6 zH3?Uqrcipp<4&Y1Y)~c<)X^Zp4ElV0SRD=gNjnb-h^d6AUJa3wHO>K0-3M+QL|0`? z(dDd5!dWEh?jimFkhn=n5YDB!MJ|Z2&!Q&uImW3x)nsRRyq4% z__jycnKku%u7g=~CjBwkE3Xe?cj|&e%E76+a-|roJa(uIP_2EOnStrsS{MV>K~GU9 zRQrX>W~dGw`Vvs{r+&qnQ&cO}*of0j-2H%Bs zMwhIH&tIoC%>AI4%LdTWRG}31f%8e&oPKBTscFnqicqeQde`Zgi!;I(Y)|C^({mgH zfQsroZK(eAad{G)UYqz|H2@X*`M;nl4-3$OQh`n3NvbDT39yaXRx37-#}|+Lwo;HpJo3M0|UV_!t`w6@$?gW?H< zUk4zm-xc3Ro%Me=BG#aFgwmUW`G`C>jf6uQu-1Le{K4`74){v z(AYkhYvc0V-=w?FY4JG+*_Sq)eNs+u>)a}94u6x*Og5!x=;g&j2XC{V0QT!yAA8=V z!0t)}y&gR3eV1;!-Icq2DZJP-X)WNle;n~M!aqAy zjPM@m*$GBCJrQ#rNbN&r2{Kg|6UkQP;F~nA3<1|A^8nZ_bX?Qk-bX%q;7`d`*rN_ zB>FtQOPvO&Y31+|2y^>q>Iu|P=(;xKFLX-z9!`%|UI_*LQw1GN^=nRmj>S?qQ*LHR6hlcAD-D`=lo}Iha>NgF zuaMK!s^@-$s$qDHgYFA1DL_ljNBjfulTN;gL`{Yz0+3g}PlztJt*euv%v~K^Uyyeu zPY#}DHpfa~-#=%I!;}OD7cylwNtc7YW}cCQj`%R%jy9K1at4@zZdTZQOd)iXA78rq?K1gF1524KpJ1;3WUsoLVhICc4I05xfyJ-H6(-x!iXvo+8& z0^!?6)CfPbqkaV8?WuuF&^)4f8}`BInxP&zZT6`4LZL*5O2Bix-LwKungI|gF=iTh7eaMjC|3fi`$$9`CStGgsf{LLTsjg6{DF>5A%tHa^P3tqE!!;X z1O3<75oXvQ2+bWMd!8<068sHjcNhr&P<>1@@Cze9$322`WMU75?Ji5uJQ`LNCZcq6 zC>q+9ShgK06-x)vy0%lShp?8iikM~YY2X07c2A%mf!Buaki%!Hb66t-zI~XFCJ+C` zAK;~t=|zZCaBnLYb$aia8>YOoev1v{mH#NgGWMvEDuKRP)W+OP^?h>WY23Hg1pC>L zKsRQ`eXeHiFgoc3Ky~sXgHil<+mf)OWW%)w0m?D6c`ZQ62PSYc)qi+l4jn0MZb@PA zf4&R1t$9d5$sh!WT~*M(67er^UxXsq%!z8af$$pbhn*kHU7mkylP1MG4o% zq|kGliqs1$$(WOD`tMN}dT!Ji6!^%p_=qS)TQCCQ1@F8W(c*Eb^;>x?><7~(*C61-zDG2V$c^g(^@iJwo)Vp@3k0lfI1#C0AWF^%>$9n zazjw2i*@Zx>#%!!W+|s;UynGLYYQx)M8D!Qk0!KkuecIT?i9yL0?>Rx1e<^wowNoJ z#fr?Ggwx81%$-m*i7aUHA{W+vW}JPuCn8Z7xeAe{tjlLm=!yve3e8bWyalI+GB2W| zJpNHAh56x?ew3%jeinCxy3Engn2PAn#8OP7_WxbceygeRrZk&;4*^j572`Uvr0924 zQ{{{~cZ=Y1aAZS0R2>S>WCV{Lu>iZyYvGMn+9eJx+XaNC@O568Fb{DLhDo$F@Hw(q z)yBUAob!8hE~Lr&aCs?aaVR`_BeqV!!WE6O>BX5LO0)8Xa_o%3dVU3%yD8KAAWh{y z2bgmxsshmseouwi1R~F6Z00WDQPm9lA(Es`KN2-U!upLwyib6D|BIbXm-o zl0m8{Z}cP^ss_pEMs&&cyoczr4(;F2da9y_$+!#JmL4d^ezI?BEI~tQr;CvPY+YCs z>Rg&O&zt~`D=(sW3Bt($iex;Zyp5&VnRXaNkL*F~cyzUv8mXZC8n+$5DKYF|Ah8D~ zLFu^dEF0at;+O!4a&})@hRzB7HErm7o6lS*d^(Q%7%0%t%Nuzp=(V!%L8zv| z#Ro#s=trp1&XJE`{luE;o3nUVwnXcqgp0Q&RnFdlN_yDhw{S%#1-4KU*-mGl5Jet~ z-bWJdo%bhe?(TVi9(}XvZhsz&UR>&Kh>L{F{RQU&Nz+mH@e`QKs^ziH^Z;pCK0{W)Y{}Vz>+{ZCsFHusCLX9i+e?dyW7xHt+r!85+awqh1TeKC?4?mUU zAyV?=Jz!rN^~zzO=kjXa2l{2Rr2uO4>&$l}_UhBQaZnAiHmShg`k0+yk9Rh4456;I zjO8N~i|Zl8NCX!-Lsgovr5mBXOX@(Tjv;n18YQY#7=cuU`$TA8sn?2Ps4o1Nv4T|1 z|L=;rfAU;T0fAykjI+?>RR+8Rr?%^gmE@EY!V)n|i+PNFkk#b^fm-+%XG}}i&fI?) zq(%=^c!1Q5m270X;~f!?>a5@JWDrg@UeC!eC?>gE9+18+mB%7JUy=h-dFiZ{|Gzw3 z(5Ku=Pa!m4_Zx-goIJM;n%64*Ahfi{p!ZqPUy0GCmY?HLXfwZT;rlR)e@&TG9w@0; z@<0JiSy}vc)Tt}!XS4+O%Bimq$k~_~Ma3J+>1N2EZgN_Wlq%fXnJJ4Y8$?UmqrI6a z&Cl}uGf~RPZ0!iZl(w-gQ1v_MbO6_XI*s z-gT5@W?Nu9K-n&rx>22U`2kOnDR-R3Bo!VrgDu%_^1H({pI~V+`lL%65e@cP#pTRG zuJ-&dsLE2EoS`b`3Q;K4_LF(;G$-n}W6puUgnqG<_$%|;!A47PD_7WnU)rl;=A?N} zw1QOmTf=W4l)?8HZZe$pvsSEWg<;E46!qaxb66hcc4fN+_C{_q=8XGC7m#ZE+}jgO zcN+6x-s5qOA^OBt+@pd%F`!G0>sGymh8~okZv>>uD%NTc&6UcSbtd{kkL-necH|&X zwzlCCRbLhC>A;;&ANiP#Hh&`jV1dd1)AiFk@z=9fVsol=PdWi==x+iMy6?IGHxAXZ zAD-}ONzQwGxDlYnOEc=RPga~9fw}eAvJB$+q@qbe6&>9-KaGmYT*CehbDsG0K~ywT zc`zQu&%4ouJ~2gXeholxv==F;O~t&BDA26w=y@F#W%(c8j5aOYISu=u;v(j5>{i+v zhn(Ev52GXIFVAI?)7j3fi*TCbc48%IT2E_!1=2&muEIbjoL;#bLPzsm6L?Pjp#j-H zDkwljT4!dNy&s&{iN!H}Lcri$c-Ipf?${)@?x^a*EWL$i8jjsaXPf(_^N@AbWCbo; zyk(gW7*jSb9)d=bz6gixrbIY~_iinfK@h&q3u>TOwx(QkQ%~t(P0zwhJQeh0K%uW| zz&m_PkMzUd5$AIYs!3^+m1IAYI$24Y#;|)2X9(ta!nJVVY?2%bTef&!nLTZ|c#mH6 zlrM2!>!8=3bHsy7pgO-Am~^qIhU!e;EZF0F>S}H*@*n5RIVh=i%rs2+?M3xT74%Rqzx^jWmBcUo)(~Ez`(#dm z)_K}gpoXTcM;HXA!#(t1x_xfF9FZ>n#76qMz_1kLWa_MP1=G*$qpoDHUpMd+MUmU8 zo}-+MN5UV%sYVeR&%iegGw^E)wo^^a&IfX#IXK2X56vH12mQd_uLoM0oQ@BJQnT<` z!U$#0yRs||IbF|eTu{ma9ghmfA|D zcuL8zf$D5+D{e(eq;Z^PAm!wx)?y%hO9w#o$dbk#0F|wA^8hEVS@}%y#}W%+KYeP< z10^-`LV&b~r>KI{#E*(bQRnzI7tkk%daa?ve&@=yO~`bn(kY4TvnF)Il#?Rpu>$PL zQVY4jq$uC>2;;bLMXf8XEDQm8+WB*+eS-U*Dd3dn1Ykv|)Dj!a1tNYUaQ-g)5R&KZ zzTk`6z0c-ineet&Y7qTIuns;)Pw`D;&WZYR6a_K-yn@+f39)U^yuGh6jAV3;%){LN@!2tsJY#ml;5&fyf!v%Q;94Hzj)lSc4J=kT_c9*qKjUVl( zrqY)+Y`uxn_0Ls$fcl>V@z5N5RE24;tIh zb)6?4rO&pA^x$M~tUK(LA4%cV+7P2ergN)}QcPpN$j*TBVOOAdqTqTSIxj<}K%~kR z_nnB88e5Fox6ZfMQ=&s&Va*WcSQLCpRI$ljg+%|w{~GNy_hgb;#bytz5>`y042TNt zS`g|tG-^XZ1UnKD`*^_=_#EsC3P6@OdWTr3r;k$>G=IC%gL*0?{6i2*l-GeWb@PA? z=F_!1nETxpjlhKE?A^*n=OozU+`)%eg$kRX)AL&;nxuI5>3vAk-6d-|R7*6qqktb5 zAVG_BNA*gm&V4FhMXH?l)~c~eSRQOGR>^gRa0!xHdT14dS8q(9^Tht&&Vi`bJ*QLP zG-+m30;fI$txP|!R9uDXh;SqnM0+O3U_a?9k26(nwtcV~R25Ahtj352kMDxLtn!XO z>~~hqA%CGu(=l{j;GHMT))?FD1I_=r5j=!DrutQ8Jx=^<7dR>S_P+$^aqs>E@aY(A zS&Hm`byOnzq#+k{1Zy_dN*`by|5!=SYYvGLw$Kj~mhlDmAZ)c+eW92bn#`x~fpu6v zK1n~nsBrrHomzTc!L5Gb6)`=p@$309i+-Arqqwn4Lcbl!m0vc)Y0ra~VxgK|kfnlZ z(!y8TNmcFYdkd->YXXnHIVU-pz@zX(%2$3d(O-83Pxc(6-(NI4bzTO1UEcOv3@GQ- zOO^DzNhSMKj^9gMeX%%#A_dK4t`*Z!ytCc59GNP&w?^XkNSkx^BGf9yDG`3pbj{41 zfI!)WZ3VFRel+JxLX+f!3JCvYl+_VaohwJuL7ymiwE#}97NxVSbk6*&RRmRARI(DP zMIHe*sHUf>gP^*cH+Ba6FR}Ie5-UYl7TzzUR1Yb#zPQl z{%B!@_4aya%0JRO2u$l}luW)i6;UiN~WfC&2ko^}5^|bgdH1&an3J_H} zoTY|lT}QTz0;yb^-J(GB^V`^PT3l2oglbz%qbsS7CS59L%0Crk1*l!#Via03C+J^31s!u?nZ2|x81O9@(l^!6vP**FW_#Bo-s|Kgb z{H8=`)CTc-aGJBN&I77@&h<0=d92H#_;ROp7zyK!{v$9SbYHg;<|Dlx!63!?3k#~R z6GWR({p)r%AE53SV$kUFO|7%A?|0LEfJWQlH;+ttSN@~~DaZHMnrKcfKE6E=j%rvZ z@av@meUCQ-Y5t2}!hZbga5hx;-ma<$!4cS7g~)j=d2 zdZOS(^hwsl9tkLSan`khe*wLq$r=$P`V`9bpep!AFf>^iuQH=| z!q<#}SRNe!MbF+pV9AW^-U><;tdjLuQl&MUH(~R*udZe0@wKP~sERlFVee`Ms%Yv6 zMM&b)|8KtJ6_}UExY)32EiV;&V@qrl?2WRsuYO2EvDIy9s|oB*YrewW4&>5ak$QYSvi*ACyY%tK%h~;=ztV?ewk|WA zwoA6eBGNxbGK{caF;lR6<>IGXhg1g|NT@22dm)mVy+%XfMdr=F^qgFLz@7BzMEEas zgc#+%74|N@o0HseaW|>Xh)#J?By-^}w+AUvee!SFh$ORpxc?y?flBN429Uk2X5Zdk zS9-5W`RWo9vSQ8zL-X?0OdaJ^X5AUnLz)f|`&S^HGYFSa`sQ>)E`;YyGIwxN)MUCs zL|I~L%i%P%M_?qUGa)Z^!l@=Z(i50I%nU-J&K6A-Y4UaKr7(X-=*uQeL6jWU+&NcQ z(ER2zdnGZ-@#&pHna0IynKDls-CV%a(N-D5lhD0eLlwzUIQt`#cK-pSRInx)vU1HV z6iY`(hQRW|KMK>5H7{MQhNfw4FI8^UW=IN3MO;EI7R9sCVMAu06qK0vv(6Qni<<4o zeCi|iGRA%;W&?HT!mnucq3&hQ>kDA7P}F$9{-G(rpF$~wQ=MA0h|7ERP|dd=<3n{$ zGzdOz!R%Hv-cZO9Prxs*T;ZX{~_q^9bw>mF{~nUE*%d7|n-mou~psQyy*b z0e*|XxB|6{&Yeb=@L$+@6D?|pHHVh;jj{Q)eh@vc3=Bv0Ja&~sDD*NO0@Njb zH!xyFd~+y8;%w4dhXE>li3y-u$DH^KC|fNHpoDEwW*ElzDKQM=K@C!XDlVS!z%;)U z@Fn8+ON|#0zsj!RhP4!K~)N57B4N zj#q)n+VnejS9skRf zsAI)_`7dN7&)!%ImTD>l06NGC&4BQ(F2W71_uBGbP!ChjH16r*bE}FG$?`(AC&J5$ zBG-T>=L=ov$Ij(9v!VLbaM}&3?g~;?^07os zd>y}d9NFG9@Q}_JzOEyEbndxXmb!ccy%XeqCLM~hTl@b6&95)!K{J2)h0Mcr7-~rB z-9vZ3|I5?2hc$g>TSG`7gj*8A9U%z;!$k~;iq=aK2}VQ(w2BrrT)b7r0<{*c?U0Z_ zAb<&?qS6i^wzRbtX~#iJJ0x60YaMWUruZFChag()`1PQ5`p_9qpO3>{zwf_1`&oPM zwb$PJ{kgDshx8dtnsM%pTcMZdacSQ$hM2p68K1_Ec9aGKCn5PQrhqwHRfl_1|fN9%W-^8|Tek1sx4Z z>)^k)ejSYJ8z=Mb(Vfv*-WZSS74->Zv=pUu7tvj)`OpQh@9wE*LM|+lq0VVz9s3?# zy0V@|oksS=cLtb5t;xolBuPgyKZX)I!^@ipZEl97deP2hBzr?@%D4^qR#y>%ncyaF@ z(zL|1auxg+zO)L>>#Fj53q@I{^A}R3gB(YR4SmiGP6Tws`N|e_PjuW82T|s;6d0-L z^)BxNI-DQj59op0g;Ii=_+KS8QB>>j(kehJ+%AB>z$1Mviu%)N9@=mI=R>%2-u(6x z)U$^o0HLi)sMV}faRWGB@iwbh#udDNALubqED>@5gg}%)&4xe>C-n@^Kbd*bqbAP@Z}g?5=wgCt0hDJ8dJmOCvOsNH0Ib6JSPiw0!taq`PxK^t0hsoEoOr-?27Qlcw6uP2l8x@dt2X zS>IcTOtRJnE2tZt>Xz_vv$T^w_#Mo9S`VbO+8n zk?W@G@Rpt}!q}zlX=Fykyc_4JW?@_cLRyt7ocHny1CCLR$F}9jQ}O1-3kdmessP8> zXwbm~^w`BOX(yzMA2^Jd%@t2^U?{mm+t9f4&xCRsk^J;sEV%Rab#nB$(JIgYT9?L` zV4B|LO3@FiCh!WN)d>ag*ZL&Xz<8lek`4d1?nW8;+p@Mc!e3XAS4YxoJ}*te&gSK7 ztI!Ybnq(ly>sr1=&==N|I}lX1Ka+U`Ur2(Y8m*z3d0MLYuOn!Qv;KFOoQJco=pmL^ zatGH3lj6?3Q#6i_6&o*OMsvm|nH#|GInU7fu{bNvYfex>9R@ccX^4?z%{h#yS7}EG zMwInu?isLWYkDvw28m=pj2AssCy~8Sq{Y^(bGu2G0)Zs)^4!Ho)7jHQpL%6ADTB7n zT^`hp?CUU&+yCHCKvTo&`FT`hZk#0;$hvNGDQE88k?E1Tp_k__B*9&aLbuVkgYMq` z!u;{vBhmHr(I6m)UmXOp;*&At5l_tXq&%Fh-`mD{^wyGRjVtoF2;DBzbK-ewPXmRt zvpl{-NbZ)?K6!K<`R`lZ`uMra80RfkQ9n`Qsw#?+DJ@#RouHQgeMJ>rjvDqxna9~@ z?E!NaA4AI0Yd!QilIhybK{B#}?2`}T=B|QS;^yPKp`B$Arkn3CfjL zvH?}cr87{!K{KE%w-Te1pdD@v3P2}vdys0p$k{+enf&&!?NpTZgE}#a>KfpBpngfP zvx1Rcn1M(j=u!`#I=cWD79%s!$J3=-b)3tXriW{igEvQeqRnZ`#`Q|g|Aso2iT#C|@)`G73cvOcokJN>HPK zsIzZ}#4wZ6R)FCxt*@1Uspj?tjGw;Y=(mus#PzfnG1Zjmu3>rw{Ph;he&BiwTGIIs zD~PtfK2HetnQmUpk|pT!ndw==k%H)dip(XnWPLYdK1H9J?@b0!pS?z} z6>E0E-;ym~k3t9cyQRQ?kM{_O+Ou79OHa+cg(~B@#G}v-r``q2w|oU3P-ljx0?_b` ziW(})!c+_ zYQ!#QVIp-OYA}2iXLiWIGdZnCEf829E znipqqVs_P6wQ{8A)fkc9%hl)x|9nfyIMe(X(*QI*db2SYOuMt}ASLh)xQ+Zx{&o*a z#Yq}H4oyebueu6<*<>LzD65Q}Sd$8InhzSScw7SGz^D^*((blv8Y5*K@QOfDIk&Xc zRH$Mc|lE)6x5Pycvgv^m%SfDlRKv*^H6?x z#v=4&I`*4B%n7en1WxbCb1+fEU2AdhPYp*vJPUW%8v}G2y8Pwi24t_>tYDBzyEpPQ z-Tf-7gYvLmdVdC^SELvW0&=g=zk*~=ib--s%<_E}J}CWAEP$dKmnSt)blR{| zz!dMY3&nf=)b|gj_ysX$W}lN(-k9-E~kvR`M0{#u1*lh)o#LAMQT6Tjf z?UTrVK&t8aYhMK`-$`vfbl$Z8ELd567x)9(tQ=ho=tuHvRe;9JikXA=;kn$ zmkZIa(>?Sx-?+$#AbO*w>DfA`ls<~OHQ(e#@ADkVs~^(L-FBwyKOXI&Z!;HZGGY;O zUhKsZ{1NAhn3aii)$-kNERVh(eqH09j1Sm;Bu zb#X^aDX7+U65w@(Xz|rfzF2 zq3>jt^fVf&Qj<7*c#tYpR=Qn7rP{Rm1XTKZrwyWTwiYIilTuBKAF&{5I9KY5QhBo< z^Rwn|cKH#nUO}of)q+4kyU+GV0=oE>nFj1pG2Xw{a%!+j{=LbETRb$zvqsVkhM&vTI~$&mbKsIu|Jv<3dx(!+t&M){Ib zUi02c2B$RLrWkN~H|s$)aniG1eSxNSZIZr+n2)pr{!p5G|Dl~Y_0@c_0-VMKwM!|J zDZH&5oFr#fxFXfe$@yZWy3;ijK}tCy+{YND*1KLts+NH9TB6U==^!rEDP|p+|HvpoSI{8dXVgg*yr!!kzkiED->PtqcSIh+FL|(m9fJEDi z1DsT+ioGEfvnNS$G7Y&K>y0frxiKHc$-!(nAvH_FXaDcp+?Lt@#`z7DdUlSVz(7Rl zGOBQ(xHmTp zY)NJ2D$K)e+f5HBDjn!=p!Bv~$z$lUSsaK%()4D*D8y5_hxNd}w$LpI{!2vm6WDyE z;04MTa?#I0rT9K<&4q!>P}1?ewtix-W+9(INQA}A89kTCP4jbVelW67f#1g*<&ScpvXTB9)I6UwzNFpiJK z-~lH+_d7L+ij{l;@=tn7S(p-A$y6m88tnTvpsj18+)>lK&?G1_ZLgJ~`k`DK9#EWP zJ@;-#fA$r$Tga$k6|X!rcUv+2ZuS-3iVB*=rt|c{MxAF)5B=5T z)TrD0@6X+zEbAS0Lq2oQ1-1M2f(J45LD}I!7^T;`wI!6OB+kNKO4q7)*z!sWYBRg+ zDRG;76KQH<;X+EU33>5w5J5$jdB}7(;Rul0Z+ydg=+8@=#`4`LsKxVQF^rn5TU98j zjJFxaQPKNw7w=D51mo?0?r{evb(hrwPAqja_-4(kGrH&1A zS4|~n$PULHT)6wQ3Cec;vV;J*&ljng`7k3~OouAJ?h?u>hCLX2d?6{C+r}T!f zk^v_*kL}Ws3TRH(@BpRf4@&(}Qppo;4W-xX=Sd*c)W->SRA1T6en5rh@6I}k>ThvQ zdBDHjeFcmiVbgu6J~ik#j0HX8mDD^Fx4i2HrB`_R{esyWI8qZ2`t#59Oi(6$#KLUM zbJs+49A>vzdqYI!PgombVRTK&M5exj&Ew=g8Y`;;`&82aA3FCMM(vb7b@mmAHam(g@}2(&B;OWcZbzgB%UN>`!L$1_(YTjsH4fiMf!it z$Qu9+iX3F3%0iw4S|_WF0JL~OX(p(xI+zRS^iV<1$#)iHI@^SS`(dD%3+{NJOAJoR2dW!e0 zsJ-iks0`2^hp!u;p=0?Naz~rT63Vpxf4V?kayFIeXH3l+=5&r6clHrc9eYJMh>m>i zwi+>AkB;BK-YVPvG372#hSmo1ZYc^(gjc+kBfEC z@4VK8>O&spp!1U8`E2<2IE`ZXKjiU;h-ryj8H^c|HrimEo*!}mlDG_7vCPU3f}f!# znR`Pd=wI!7ioNHo4r#)QmVe!9L`OW{4gsg+f9?TMK~^Ahl*MnCBc@pYZY@o?o^ymb z3f`&HRb!d@xJQ7rrmHYH7Pg#Qi$v?coWX{hM=c9cXKam((Mf7!BfTVIr39Q*BmM^R z*Sz|Oi$Z&f8cI+-x4**=>x0&KxEQrw7LAFd1_+1_RoBQYi#9N2qmBpIKgie}XYP zJbC_YK$r9TmJxJNQt>*B2}e4h{>VLBC|bfg+>D8`*8BRS{^2!u7L)pxh{-%Wh*%%& zy2@<$k9)$%-%CB*#XKEVRXdUCU(W^uD81>xS3O`Vz0rFdEmhtA8e^&!|2Tw}%GwWk zBj}%BOhKvC*;iC(!N_;f6jQV0?VXrCd)ko{#4PH*z^snWz8K^2+RkkH(5L5Tr-t5PW<7Ii=nZzOHX=5A?t>)DXr@(2@BOt8b1nd> zy{7xTlWs-##alBdreo zn_H9H@zZ7bcNdV+d4AoW;I1p(w-%Y^|MbL6nFI@#oo}a4r?O@HHgCb3RlG$D$=|*{ z{}GDf4<>8|^wQZq8GssCS|O3LCRWHmYVyK-q*9BIm8Fp=>=Q0JX-pq>z4I-#ga%lYY_-SrZVY*DIqJRc%`J8-l)l^Tuuj?XbqhP*8!#hXoL2 zx}y+E39JqEaKC!fzMVv2rTN|g((3Sf9qC=m^AqFfqFY~exs&d+q9aqaB%gizv3I~} zSo@bx5wtUV?aK(d@W)O-1%LUVh5R{3Ry{=uSt~_HTQeJ zZ~>Hi%KHsemD$+F2(7x>W2OSkdn^`cy8Uq04ixZ-Z-#~Bm!z>}U?tQjrI6~FFdwY6 z8>N{@l`7y|B>6SR+FM05QjR5CdZAUFa`0oM8e^L@luG(;YZn$pRh`$HMtk1dXgLGu z#7tE>K@9Wkxt*lQU|PZ! z+8m4T7*B+CuK9!+o@1xX;68pSjaj_14O8G=dv*lpmTOlzGdh2n*nnj`+0q(FA$um- ze?*ZrC6#$-XXbrz5Vd21Ri;4a6>491C?}6)pU2|mnshh})bE8KLz%*5&(UM8n&*o$ zPipNF8VAi`&z32U7nl8utCFBd0Ji<5SE7@2NL!VjRN28S&WhhE+O zA~2Qn>o0-+-YZV#D34$A0%K1)^W5A zL_2%4KuM{WAHjZ=^9MJgp?A^?ak}dJ_TNVJR%J&kpe<$*#>p#WY(h?j=KH=9j;P`f z^74`X*{uK+s=k_{2K(FVqSBCR@1!6RLZwGI(PkY#EfW5Z4O3Cr`XjkDC{*VWpTtZ= z&=wY;M+_NaOhn{6_b|_9=b5+Bld{HAq_S(1?||xX(%P%kXidbUVNi8^nwyC+ov{oW zq2GnPYfvR==d~EhG-$rbxNnQN%9Jl_-U&{lhI;|%^Nl6jAm7okM|ike-Whyop#|SE z`-;xIe2-m)KzchDBa!L#ZU4fUC@((;GP_xP2FPDL%a{krF8K&_Hmmh;=cpRXVSHg7 zU=;PgUl2X_CQNyWC1CCuXj)qH#ufVYm}%`L7&))pS+SKKjFGdi@Mh0pW!)+IyvdMQ zaEac7m>LYJhcT;VG?(51>XPk&0I5svwsd_rA zH-PG)iK2co4yU&iBY#SMW8^AobWtvTpe$u?7yU$(*s$^%jK;3{L4>r7 znyn@(zcfl6i0t2o!8ZCqHquznnAlJxH&BR>J?h*97(*Qe`BaeW`#DB1a>)=>k#-us zw&Vu5yLtYEpt>PH5BR^Bnf+tL^Z{h)_iywORD0(OUqH2Pj!@FBJ(&MD7zc#H0P?r^ zs@n}{6Klo{nfhEKO95?q7~@a=v+qEhg|SPRqeXtDR&s@O>RM>kA?WiLomRIHY>9=LQ$4YM%r{YJo5|6RCQnCQm?r8S{4`s3YMm7NV-QtG`85w${8H z(4wpf19jh4B@6;9N8T1lZD_Y-6jE1JXE$k)s`#lVlZv(8OzwisYIwINnS_*G%HJ%9 zrdE&0PceH!>w^Gj@>N^{j4xi!#Ypit#q5Id`0#)ikYi?LB_+!D5bS3LI#cvHpm%Ew zfduusbt|KRprhH_Zz4a}5LE)`(Gs>VqOLC!W1puQy^copsUmyCG20__Zwiz+K%a5B1v5!OBQW3PbIk1XI>6;JaWBOY83q)3YB~M!F7eYE|2#M0X6JDjFx81zM=VOhLii0VsN@EE|;WejUU?%-g8~<^kzBza3@DgEA7x|01gZHeKz)8c=f1G@5Ck zOcs$0`=C2zC<3SbeIo4hC}$({cvM}H;WSmJo-V?axSkGq22R%GH4)J6h-@DY8P+G0 zndp*To&N|>Ui|HFKwqrOVh&C>Paei})X#Mvs77#8`*FqxKjBg94D8ugB>tmA(EzUa zuMB8!UYqU*@m?)@4x+Y&D?MObdvqC)iUlGhmwuEbM)57KrBLL#TPbtA?uZDW+|sBM zwbvtsi{78R?Ql59wfXpWsK>4^o9SH? z)%br{V(GFZ^L;ys{>7MCHU*<5)poa#u5==P?8^7)wj`Qq;vrMWA99$WVdjIx$!mVf zXn)FzSP}CU&jzpQ~2I{1ERTStAm|+8|hOk zYmNeH%sD%>W$v=om$oN#Gj&6hnBjo&QM(LCWv{jJ!?|nSsL2=(W2a;x2a>Fsyx50K zyFc}UB)6YmuOOzJ0_nPb3ThTNrog}VnQ8_3YuJ$kg(Rt~_QYx!yPnU$sP|kmsKD1b z3p<0MUiZZTchbbs(ln++OO!$TpkC7TRQOBQZMlt>tY|N20I7ZDqk}|>&t7;PeJ(m> z*bV;;ymz2}>qp#|VN}&-4N|32&$Y|QXvt2!h34hoc;f|__FQX-1k)3e_n=9;V!$6l z2XfEBsOG02Q6DFb4@qOi1_i#ho7q(XWH~pG5BF_-{x#GR8!uf7|8Y(C><_B1EKOV) zq+NG<9-y(_rBHwN`_W6G{?wi>^m#h5G5|z5&u$qgs9wEmJMxcn{f7|rj?NK`pxfo1 z6$G_&qFn*)I?giz{4+pv!2v`8WhLH zU){i8j-ctDZ5TAm!NYc@eNzU|Hz#qSi6WnG#zOel4d9SCTp)`8rTaM!%$X`HBNgt7 z*HT_X%(D7NK7bkm(;>;2gNb>}7>zc|)wu;wr1(dZD^(;tu`3v}liK5`!a#|(jlnov zDY}Y8PiziGre6{rdV<=9HK~BgWh-9*>igIUMWil2mY^oFYThB_pZVE05^J{adnYqy zRYNb4QS;U8D;g-LQHm*d)@QMi$y$G|37HBz*VRD1-$$7-r3!^X4uAF)buiATK3+c3 z7q!==AbnYr4Fe$!^?Zh)MK&>J*Q6_&vD561*LttU?CSJk(by7x$ps_w$E-|-Klh)* zI1N?jv^#5I@S48cYJ>`Bej(yf=`e39VX-jlP(Clxc@hoC3ZI_|>R&`SmplLswA*tCZsDyZ) ziA6w;4Va37yrs>I0R00sH&MQU=by=xpKn+PXiof4AfRiKu3}E6TsKOv5Cz%*=8Q2$ z-oY7@_Ow3)bJ9`2wE>m>*Zzl4s%uc|iJ~Ivn$S|4_o|iX^RV-;;BPwkAJEj~Gy95W z_fC-qPWa#(0bEG>R>|wkK2)3!gYnPz#o#%6R-z(V{>6OyvF@>ZgSAf{8szBgc07uek?6X&gjG5D+B*B<~=mHYdkuej;;8PeY=&kv;Z zmVx0#l{R|I%jf7`Fx4e|DFXESjx#Jkb$P?c-&f`JYcRbLrfu6RqWmVGZ|fWo<;`_0 z7)#E`bo9g0`F=U=sI*g^Axftb)a!_SM{! zSbQ@d)KEc3u&Hu+P`iP(53v%veJGkUb`Xj5Tvg&gvC>rEh|b2O$6nH9jZe~#cfc#y#o)S#cpRIft zllsg-FvbQy#oS5T;`bxH^$UYLWWJiJv|t|QdF)5;#$&Ecg4D(6Gt6PIRWe92PYZJ( zlPFI-M7Ev*P63R)(`^aRP8@j)l=SC44nl4MD5KYLM@f=86f)*Uv;8);=v`ofa>}}Tv2IWYE%VQBtYIVKrQ8ao0Y25NhWv>pTHzp(>U_dk<@|7iTeX9#*f<7b?%0`-A+pj6KtzYGN3`>VzNK-2z_?}d}+PZ3ukpqaPw z3#R>T`(16K*-C`b&7d|}>RniOhd!v88RYM5MkG=Q~NG;F#k=fIe zC)bnFQob<}BQEHwf}dEz?R2erqPkQ^=`}p_DI58-1d>At`gdawGNl$> zi6VDZRl<=XNXWZD*f9z^T@(ceok2S4%q8O9l@g&|s*@IKrX@oh3BdL+yM zdsckT8QN0~#fqh3hjrNF`2wO-&O*F@7Cz2*p@%@)&nK%-{AWsZKtZ^^w$P+27} z9#EN}(gy8|3lwO*v{Mv}sN5!2A)vhst%R&@2akMg>{8?eIjR2~u=jNhO(?Zve zk?PQQ(U_?H#TkjzDvhkE52DVj@oWL|z;RCrR{ZuEK0}KC%6802c0oLj9ZjV7Mff-O zWu1e6LU23Mr)H%=C|hH!6G9c86*B1?UV9hDle4dAASW-#a#518QODHj)kK2!<+dWr zncN!GBOcn)3uBwSFP5n5S)5dyIl522#yn}%JHN-;O$7v`qn=;e9dhVlYZ78|jO${r zAZXO`J~0K&expK#9v>dDW5Ml#%f}GZWw?JUahEo)C`S4&OJX>xTsh^CP$o`p=dUP9 z$yxjd)UJ3K9syFzTl%8_J=ijS65~|ke;m+Mkv$%y0_@CFK&9r}2-%v(l>*s%dP4?+ zKIvW;i=Y{D!6||&-J;t8Eq`cP2pGE`v`?qbU2|E1P@;O9#qDVuj>Kpv+Xp=Fj zwi}bXhQ9~KypXl)NR;;PF32dRNfeU|P1ZFJGt20+s|$OdSZ)U;mlX-b$g(lwG;%-7 zAKXY0)xnp>ZqnA;c_Kd?oY-wyo%rSl7T9kQhWP<5^h$;YOT4OpL z47BJyKA>H<{iVcS(=%bjn2f*NQi3`s{gt1icrD9(8pjs<+5jFyle0Gguqul_gR{u- z>7)?l>qFKyVsE-9wB3OIvh#;L)arY_1>2+#m39MKqDs38=yq$&CW5m3?@ltZv@{)r z()x}(9Hs@{L06&Gik>c}&q>8REOVZ5g9KG|ef{+*RJHu*HJq?&`LTxx>YO^ooQ2sn zLbU2&MiYuEEg4xz`rE@i{s*FV1>C{`qu(a427ALY4;-4~j%8LDzsh=uffk>LI|1YO zZ+wL0UmgAkAqNC)`Sf%U@!Rt8WIUa6qGs+bknFT`H`sF@IZ3ak<}}k|y?DUpAY=Q< z{a?cPz4>nz&$)k_b5uu9Inw4nhia95n$t|DQ&!fFW0`bQ+Hl};67DZGU0dM)75_BP zpRNGOL#OQI-*q4_B$IARlkE?N$jCp@5C&xLp(6@<-ei7p&kmyeV@r~7%~Sm)CWfwb zv1fG={&P1aX}tgKLaH-6lm9;aQ@IWipc{H*MAWj&*{C3*x(}k3foS$&nFpo!+I!n- zBAo=LkZwT7-Sl37)`?480lmexRuMF5qxb+cnOqbf7(-vVYLZ=nze~K}H~33rj!5|b zn;Q%NY_4PwQ1M4W^P%apW3xZ)NZ-2&-rR!vbMk8!p{Vy~`ogJxLtX#^&T}P_+ zQy0)alX%6;(8{ ztm`YFQU#vTe}`1RWj(7${$pRYVkDIPL7yX)Vm>DmRM+sDVKm$MIWPu$OHjW-n8Pom zMt7~@6`)i9WMOs=edz+z>@n&~lD6*-EJer;<2C{D)x@rXH zqkT=r_u$^Gy%`4R`15|uXm&?rI(W+0`!0jXuilj4EH$_VyMt(xE*Q()*DiVjO%hbNVenS6N-%i(mdZ_tc|ZI(x@ix6xd+o&*6Conx%B2Z7F3rI zavUm;7o2z#jpG+jGl~X2 z6Z<><5Duu-*SjIULbGivpvh_*3f0Amj>0&VeA5s9sWHFefN%Hva|fnr_|ciefTsNB zjq<;G5rUf7mNu}@@?XO|9+v%@f;v;5F$Zy;F?TJzH}d~s#yD+iQb4C+gK#gSQ|Vu! zXl~DA*j)Hd3!Vd>g0EogNI&a>nExsFuRzS^7qte0>QC;@M(dUGb6h|t+iUtDlQH*g z4B2h}kNu#1^zD-vGF#pfA#=VBdd*%2=e{OT9mG7c#=ZRh4P(K0KAt0%fw&)F{C3M7 zxOcW^)DtIF-KlRuKdY+R6P&yvVnB4N{Tfz85cbVtC_m%;W(h`I*?SL7E)c!;1Wlfv ztltT!I@umTP)A^L<>k9&ziu-_YN>wWrPKsM)p$RN`)zhE9M zeV?yKrdt16FxA&)rNB7ke1sFX&toa0X!gzzp-BGaEdVOZe=JCtJ04cpuLsj#dTpNg zrjTqS55Fn&p8L|W;7Mp~9sQ-jmdiFr@Z1Bq{qur!Aj@CAy}ypW$D=(QXSyH4J8_bRr!Gl4J@?=Hvs`Y(4AG@X##?j(oYv+)N}^2GLDA-5`cu|d znhSV^^r2v2?RrP<+?|f!*&{=$k_%}_Wr}PXMymF|D+4LNX0g?jL?722(B}1#yVa$} z3x%?yHid%e#>sX4#FX{1r68Yl79Yt@KqiH*b~T`hnNM#Jw4i0-pn{4j`1xWmiYk6S z=n17h{3b5cz`dlJhO=Dt7l0HSD6TH1E(2^EipFea?O3%bV z{V@BAMki0zuoN*p%6ieJq8ufF!Whl~Riw81j-jHW?_A%4J6ByD5BJEal0kw>8;kEl zJJ!u1A7uZrr?8facXHm$L?#!{(;TX^Ag?n4CF!<$uR;E=YV*z1X3kN`h@EuO#j=+J znm4~H3(!Ra{8~)Jf}jL6^h$Oh(mS)B87RGKTj?%Le%3{!H-`LblNJ56-8UOCr0>*e zk>2#m#!^aT$t{X&0H;;sZ8wOM)^i23V|B4n0%)?KG7UtnS}r&ZzTv5dP-=GNYY58r z{tA+e)UT<)ko-NB4fp0KZZkOj%64TMT9c)Oq_$9=7XExe92B|PhEu~JKIDQtv;S`y zwNEd2Hx&9GBN?kSF3yEs*?z+5s%s{#uNK;ZtQkfN!&T@K(Fjs4;c}jdBr` z-*TY}OJTi8ulH25!BnU+ zy8t?S4Z`!HXRo#f6P_yL!k9VxijIf;sw^Wo6$ok-aF=$h356!zhqcI*%~l7JQ7SSf z06CTP(1VQa+|BQxB}&fh$7gh6-yBzYqNSf^B!MVjKG;WF&kEZr!aS|W&4zo|iEx}_ z4q4e292)ZSdEj~Y(PJw}p8jmO=4zigg>Qn^PO?={qrSR_w9g=o)?{2{*?%- z-X?^x;`L}(`2UvLg~y$W?ePm%(JDFjIwbke_GNgoNIhaOB!-pE#mq4r_6?iTYj_vV zLQ$!#=rSHxX5;O}faYe8;c3~rCf|!1Vk!Ub9v&jfpO$|CO=b+%c%+}FzKo7cODcw9Q>;oTkVV5_-<3Zs!-u z=Ppi))10I#x@LrDFA7~Vcgt}sc{RNd?k({b74++V>avR>2Kv-LjG!#Xrebe;{Qb>6it_g@0<<*xdk#`nmj@~6M<}P)2@eF*_kGz~sm~g^d!0_Tn4mOo-xWaReEn+V zUnZD=sH1w(Pw-#QdlThbYis?1FhCgpn+nyh(HPmSU%6>K1+HKisKCznpSAr0WTB?6r4pj|Ze$jwNrK_;MquR;{P?cq=%tTcm z5ywUU#lsGauQc9kA?hC*dw@lqXk7UfkX`d7pQHYJGGicue!2d9*y{Ju?m7W`v9)h_UNbB{%)X1kb~y}GkX5y{t{;%`Pr z^F7>*fXZ|g3bdqqJPpqdgJ+8t$DHfQx&-9knB0v!yzAk0mqe*|Du?YFQ;69N1r}0SB+GyY6(th zsn}G4ktoai2TmFL$%AhLso?l0A?UMwsXOxjq+M5mqPVf1fb#bliy+_DbnOrgN_*tX zchHj+on_b^%~pL89vxkL?GlJ`WWdS{%3ANEkgsI&yTu6Vd~qGmQ`0g{aXyW7Q+$CJ zNWEf=N25wLJ!<&ZN$ca`pWjhxqTMy6<(@+Rv8tDsG5O6|%q5|k8x8-|`D^iz)I`s| zqU*?a<<36Z$j;spG(X$@fEbCEXx*4cwB;K{(oMw?(7D$CLmV7N;fKs&bhA39g1$0* z&ToSYeTvm83ky=t-J_V0A2`Ob&b>7wS6|u&;AO*) z@f0$9N7maMm$^5A`0v*}C-M|hUP*;n+roYZsg4wt#h zox#PP>E$waH`J>O_M)bLX>VV0A>ogoElelq#PU~ea|xRCf11=}bTq`8fV^`wYB!Lf zuT3JTvvR=&HVJjSdruRfd85(02&$G}9{|+0VMR8IY8mv8rb;#EzBPJ^=PsuMF((w@ zf7@D7??U&;FkzQ~dLrGpU4>N5EH;c2wI$&&>ZB!nLOQ}dr+5@}@?^zjkm`{QDVa*W zgHfsd#Lg}7@BYkE3uwfahcG4z=g$Yz6C2k;lM8=E_I5vk8i|^t)LO6~G4Fx#aP1x* zDJtN{84!}M(pZtlz#d#fF%31X<)EZ0tkqISy?(wej74@T~SSx?ag`~Q{$ap}fe;m-FC7*As!$6L&k;b4U674`5=Im|`7Zd5saP$8W zP>!N4kyvpKG+pD8(1+8`T2Pg&IBo&WY5s`~7cr;7pIL#7^Qi&wYI*fK;?(|!H=B`2 z9M5S&qHQ@!l+O`xj|R}KgP_oP=cOXpGF&zYR|=O zTPZ*5v*)+ae%F}vyMQ{98e^c|vavLz%BtG%IsAji0wq+G{`~I*sI;qp#|LP1)}=QP zv@KScK*;QNZ5P}pYPOs4_r@x{`2Ye^U0`+c;_)jYRYy3 z-80RL9`?j>$UB&ZmP}kp$Lw1MvRWaZ%9SUAf9rq@Pl%w~&1o4ZKcsgWM||m^*KR0n zjSiH6f9rr$hDN`B#fs@2j|=Pu)GVy(MpFXv<;;0nuN0vv3V(Ausxs9#3TXPfUTdm@ zF|XAX)02>*gQib5=b}%K5%5bz<{Po8UWKtb{ITz3hxd2e7L8wQa<2TNgU?QZs{>;hoC955EPRELO zK+@VYKJ$QW<`y8;v~(Q{{?8j_IO5gvCK;-i85@hhKe@ODI*p78qey&>skRvI=WjLQ zp=&Bn81|=1`PH1GV479f&kWz;;vNj2Ch72)kf7t0zOMi}V|oRB_WGqH9(~qyW#=&` z@6uZ42+OP5YCQ>(;1k)+XWvo(|11Pe;{gX^XNkG=kH$zWZ6g=vygTc zIQ89R;m*QZ_SY5gPHldKhk+x8{SlIfaJN9FT=Av0sJUluM|$oWkGUJqgkej>Ji0P` zG5d{-p)FY}8EvFm99mQWQ4RaT(nv1&*(}kmZ-KV1Ea}R7y#N$(H3dxEb zx_g20mg~)s6m2Qo7_B+;ig7RzW87yt^Y5QyPAEgub!VRUQSA z9jjg&xIpguO3!v6XOdNn%55*=sz_y3&F(??a|84~q#cJR7(;q{dX@_QC7y9yq-((X29n7(k9TjBWEMNagHYx_S{@iMIfo8k!7yuU61SpG z{%P+hK;@13M%1~7<&WaonFa7S`LuA9R4BjZGZ*-m1lBFb;A`!jkU9T7ej=z|;5wQ7 znWyia+E6n#_Ll+%}1R9 zfc`q|KvYS@u3SWwuRY0ys>T=rIu-m>?@mUC$Ep!#qO5+o7-;EC1%g_RH;PezuqK&} z`o}hVr$VZYwXW5qpXqlxo*u)?YT*N#m(vFQr<9dEF#SX3I;^wU(UgMzXXGb@5~&H+ zP&+E^I?=*Kr_{qWN}3<3`8YEanUfY~sFvCdpl=o?1S3;vNgU|wI3KW>OvB?Rh^VWy zay2x$Y&Kwe+y5X>MS3ecTm+%d^r`e1l;z8(VJv#whwj_Yh1VcG+ZL6CpuN$C5U6iU zQ!r59=v7!V+wu}#`wDGm=kc#_sK|D&W%Syv3$#Sh7W~BPN zMg(YTk68+6qggf&tkPwVL6y74$V}fnfjf{nVjjvb=5ruabvPqwz*%PYtX_W;AY!X- z9-7Z@^F9roH@YXlSW@rF=bkW9 zui$@Q(Jeyppao~VY|)(%AP+s+2_ygOpP17iJ!=?~$8|9shoqU--+5C^N8-I9OkS6E z5p!-frbL1Lc=g|+Nqp0r`*(t9cHr6+l=S=XQMl_8IXDXqABdR8PL@OX#@r1^%0Jyn z-!IBdzTQb6;wFb&hs`{G&i}``yN;>&^0GGiwN|?|YXHbxPfgu&x~#0sNxwk9V=YR* zwf|fCH=3@`T@)pCo4NtzKe)xA zM3!$a=OMe{;yM;6?LWx|Pua92kc^zLRRe0`*={}lBAe2iPmP}dPl@a&q%TxYG(fy1 zUzLEo*b%f5&CAXVoQIlWEcXII+tN8?Q}5b> zipG_)Qe@v!BlD%=z3wZlHB`LH#XT8a=KmmEjpA1%K3zj489rH~K%K7DIuzgKy3h~C zcg7#82q~>A>P7Kc*1DzOnONkkq)awz!f}u)@sa!jQb)uC5g_$9xwDp_cE9L6kWwa| z>I5{kLl^*PSZ5)i+1_tt0;-sQF@cF{ZR7x&qYTEBcd;G8Fgki#!AcbpbQrAq2IjZH zKX*nZ0`x#}6rlEs-xV>cwz@3@blJRe2w><;9Y&)PO08JE?3&Yj>WSlztAy>;r_y)B z2O(8~?LsP~dL%YRpna#)M$l4wvyuzwU9OQ&q%5ts-7F;4?8nbK)L$|f|96nu)A~ag z_}9o)fR@@0?+3JXT&h6SEkXJk3~I=Iv4$4PTpQMbnbcZ+3osQWkHzU2^h?M0!2iX= zcnkSoY)J)BwJ{tut(y?F;fxS`zy&4gzqo5DkNDFQC77w=&tknX&_nMl7^8oj2>UJ0zvh+<-;hmHjJ|j&|e$-E3iB#!`;C&O~4AnO1!4lVR@w7?Njh)+f2-y?-tti zsl=*s3vlpk0aVp;k_HFo)pdCkTYE9)ncQ#wx9#> zxAqwmP=7|V75)X`nkLkLEITa(?SFZ96LUsSS%eVPmRAJhi)+I;`D(<$Xuh|BIeKIt zCP1d6abBq1*Y^lmZkhK48yfrx*9+6QrM3$vxx-hV%aktVuLt#nd!=bK599GKHJ~5& zXTM}aO_D^GnV7X1mg$ix^yL4ayoh}c6xsD4lUe2(qkld5XKzg%MNqD^CKv37WCE-W zC%;{$ME>ywz#*;ZAIs4H$+nWuA9^Dw5I&+|VD zXouRi4$zn6$(S;Y<~AN>rlwt2p!oW%fGAz>#S2XEP{TrtqrJj7qcS4 zHCqg1b6T{~NX~z>0Z$E+?EB~FvHkqcDAalH-eLpubZn`>H1s}T8_B5IozE=8FUC^l ziRaJ4W0b$1%bYJkM;EKyP7wOZqL*A%Kn7U3yne0_3 zMUZ5;-*_BB%QA=O6H|5F;dB8BrMw%Wk2clD3GGSDF+zg)iHMO3Ixi&jVLOfZntY9Ij zBu;l(gY?GqcTxMnZ!vaL_ETQut%=R+;nUQQ`u!=ITGTcF-DnI*^QaXCWhI3Q5pkg1 z*B|cQKPm*|Zr`}v43XGc4*|H>sA{o^S#Gfy1{43j4#QwIhb2Ie9_JY|crIQcL{Q0a za2JMYf4%E^sKi~752n-Op7F@^eSUQX`5RK6@KKZgl~;98#M&6z%b zIBRR#q*VX#ncz5-`Y(ltn2c6?cm+D&wA>s+M)P;76yz_G1Y+y5Sy#AlS9hf$y|FtD zts6a+p+M_?{~?<>os4ZPOuf!K0PIykyM9CUuHz3kVa7Bk>!6eOpNddXbBsR^?wv(y zW*ST774wPbv=3(*P-`LURTS^YRBoW4oW&{~O6rT^-UhTJ;FbrN7PcJ+DajV^Cm_{4 z(1(_CxI4c^^Ka?uLm^2}d8Gv{@qeuZEmiG!bq3@7LhG{{Q0*0413_7fmfU5!ujNi6 zYObd~9MI>@PjQgy!xnvyi7pAtLZ5=)yr9IKyzXs7M-?@a926z0j8viicc!DXsDH;H zBS=}xqB6-iD9PChQJSwa))^ZIEfo)FwwHJ%-Z)pNLxHXXj)Fl>@qWnM-qpqkqP8`_=qY;4aL;xmMNyl@>r?k4k?e?` zQR(lTV_>;~V}Jki+~Y7YOpFRyMlqwCxhXD7>O!&X<+xY0N2nH33Ese@HDv)a%u5P41Cu7@#WzqXS90=CDC*~ltDwHdbNzm1y><`8 zApZAP9vlWA{rBes{({($_erQuT<{FcvvQ8a!KvqvIE40Q%gOW5EYv;5VJq9Z^&}E4 z&xwI`S6e~=Mr`5vVSuNo4rCBzmn1RFd6xqS$o!=#LoqY*KCfV15hFVJ)i#N z-d*@-$ljZ%9moG%ha406(Y?!G{AwPNuyjxNPH0YsZa7RX$2OIm@4&zDpI`MYe$ry~ z$+P%PioL(v4D|fT++NANi8sfw9&ZvBahu!`XpXhxIz837Cn(-Sk5CeB;|18`Eyep0 z#?W2=N(_A~XJ6*M3HsmUS{KeESm$T!5S;TW|2rzOnl*Dp&j^Krh${SeMZGp1!XDi! z1Y+6W4MdTL>Q~`q%lvcs%*1CiQebLyg2)Ck^#}D{XOD9+7E~MU^4es?nackIP=6qn$6)_uU&xNcu))46!)5U zk|yT}Zx}uc$D$FvJK(i32xBadCy2AT1xt|;yI_rif~y1ntcK9=aGeAhExpWw@VTjX z4{>3jtQT2Y_a~#Cu7?%iHiwte3DOKE_sqdga(NaDc1F%zQG>Fct8Y^;CfocS}VqX1YXSX~Nk2Q*G0cW#)I0OX2~=QC5V*(Cy+gZpfC zGzAvkE-OmUXq667q9$S0L4cGXd@+t+z<8hC3iAV6B9>8x0nF9_>Mk+UHr=NVFtEK8oW_=vxPj zqYI?W-dEr01#O0o$1v}7UwNsY*|KA&ix9qV-T_Qt;JZnXsrftVki2g}7{;YFdC-?q zvMXn<=oY}x5s4Sdb9>iGVIDE|a}AlR0uJ2<6C2*mSb~Z=a|htF$+U%se$0QK0Zps( zueb%UWj#00WKEqrSq_&)2`&hp-rxYr6&0|0z(Y>{kEq9JVD1(84+5-YU3+#3AB#C(;YyIeOI9W>=|t5tbWjko0rg9?|AyyNGn_-#e;2Q!j~}5P5-XiogSx2 z+n#Gu>D${*C%%IH)b{Jv8v5X-_Mt4EPQ0g2(k&!3HZK3rMpgDjO7Fs{Og<6dPfw|S z|Qaui}O!;&2`_riW z(aNY7C_lffTS4~KPh!OuAT{TiR!OQ&tAcq@ZC9Ous@tPBAyh5NiUI=Vq$@X>a%di|BnBR!>B4(gir7P*&zPMs;OX zmI{f+2qK}HRWJ1<^wf3k#SpS%6Vbda?w)9~o#!KjqOe&lBkqhjMVJ8IltdE?)uJPP z<-~}w@2pAisSow`LQWa_aU-R#iKu#tocf~TRzP*+EssA#^`DmtjzP8LWieEhmX$G3 z<*)Mgp{z_Pr`sTuOIT~sCv}SMFxmH7^BRCD+uOopsybf)Mhikbk^ywfXtgKCWY582 z7045{F(2>`)b(<}Xu&9G7TW3ykvhH;aVEZ=GEs2LR;NrL`otp^gD0Iijv;(3HF9B| zG8K80z!UH;kE0^)s4*BEU+DE5LTmRr8DP5Jp*15Czto7qwXx^7LskEsjuBqy1|XLF z8VRUlD-*DxS+8-O`B}Z$pHg{dV}${xhc8`?l+7MtGyJ+$~!M_A`NV-c!2NWB7~3RQhB2(`n%9rjbNbseQPaprH&N+$3e*7|>s z_}qGa42Zi|Xvfyja8t&xizH^nOZ2Jl?g`AT>Ela#A&kuqSc3fh&et*tat zf~sG=6seky$IF=w+vt{#@?Yd@)i^Z#>`#ztR!YM=prlw9=0u@PeueSCbf~Hxr=!}v zHU~VF25$;O{6yW?%exM(u%uM}>#kuU6LRmRQhZsPazBJ}H@zQvYE8cc zr$wLNWcI<~khwtW#LN}lYO!Mjz-BYcvIRv5Z*=C?$fBauUm_I6Q z2KT1A+&my$(f1p+N%S-3$Qd2}Cp`|^`0s0UuhL=t{xiD&QMX>AM@-6Z&isu&XgPGh z6OW>j7ez$PerMYdcBYwZ`M}kKXXO4?>)LUn@Vrld;g@zcdfePL6pjr{&chV#k@e;Xhf*1e-QP{Jp%X_FNY5S7bUeksL>+4dcmiRGH(I>LXOe%_TQ(l3w4a-)p3o|G@7x(lfp)c|^_VlJfUJ zmdV=t$?Uypt(LWS-t1kh=48Slk`*7nd70AFUXK2VY_&PQ>&Uj&Vpu{k%EI$+Q{2{Y z$CV@-kvOg-y|LtyB=V=qDoH|&wCGIIvv%44N+{>mj{b@IeN{UJ>S=2QLxjPuKJHH9 z#Yl*@mFmss%kNO!(X8#@qjcSVq&MGdH>KQB@3I&&@s5iZXUjDP?YJ0Cv5a_O15qPY4hzb?u}+vBDq*-~Nk=ah??U;Q~@HM!l{pK3Gfo&71W)GPix zVKBx%euoCZ6c#0?1b6nS3&~&B;}fV?^L8k3k;a+tP~6U$E2>xiwEts@n>uqvac!T> z^`*G=zgG5=p6$5He3G@+yUa&F0z7vT2vSGSodg0W)H9FrYu?lKI^|+MRkvw&)(TJ8 zZK6L#>N_1@qd}-%JW7_91J}&$v+!y7Ggk!P!7J;3pp*+|t|%3WkK!AW6|>G`?El_l zrP<}IEKH#oZZU;CYNf{aiW#!Y<9lD7O{GQIxSFakzPq!V&{M4XtBzy^m4QZ*jiw(} zlC0Jt?MxJh7N$^3fBZi@+gUOsE)n*ESL83Bqv|If=w_}6K!b7hO_FJwj$_rYN*IA!l{4sfv@jc`ZHWGeASio0LfOe2 zgO(9`s()|>G30kRgW&h#Ne)%U$(y;NOcur67^V>E4P#g?)&MTC*|OKkkfwmiEeC>7Z0bZ+*6cx-m8LJwG6St%raw%->arfl0a_N+CE$-r_;VKA{Ks za?^oR$jF}Ew1SH7Ey0m6B9h^7F7=V&u+zzp^T>8ocAN(Y9ACeS5qEg~F2&GfJuD)q zS}q^FhPX=x?-4BLJ)gWvya=g@B6kwsnLnJ7PvCA^A2sGjWbu&TazI4{9oxq7h!fz27OsNKVb2zyJ(LbICp}6 zxKLuM%E_Q_P*22VXY8VT3WqI^PtY%mnZ{0Rfl!&;LN2@4C$}K>{wF80U!A?f;Tpe; zXW~@;^a*JiS%?0Hj9jeC&r{L&l}{o(=pVCqA&U^_Nny_gXvWtTZlN?yUO9tNq^jDu zoyq;9Oh(3uN=NQb^U`wyX78_Lo~|YJl)GN3Itrh8{m0etc{VAco@yU;`O*#cPnzFS zp-gYl9oTzTC!D8_IUnfFp)zAbF6W`llx^m}6Y!k0nyC#GULCmga0Im|c6?PF>~o?j zj-yA?UIQ{UE&WR)s<%D8wGrWe66!7iyv?jZbjeV$><45T(y{Fm0-v*5^Ac>x%Idj{ zN<-w$ACZ0S5q&P~y9z|7U~f4hTT7v;gY%xQrK)UB^A4e^hGhRW)TrwCm!lt|&tBmN z0Lp}|E)A((ZhOG=S-h_kp(eXdmLb%Vuh_Y0iknr7?#D}H(BzjdzXZ+r_FL=V^y<{u z1<=fI#gFKet+^0%u8q8aL=7Qpec|($nQw&ylhn4j^&q6{!kbVXktRE!rt}I22(xaT z&Vqerp7%#6v_`2%p_kaQb0oAxvrfRNRnv5bu}@~5LQe}XN!OzNe6tWe$<&3S`tcLl z`9wb1nfSvXZ$UrnOER~lZ){@N<8Y7<^ZYbVHQ2LzcPDacD|v7pg+@pI1n{CY4>tik zR(tZt1fD8j|4!g6iTrE=suSnm%}4X|+SK4lci=iLRBaa=3W3RLSIK&+$u3VHKvMO` zTQ7oV9~KKgpil*V;l;qD#+ucN_|f^b(7d`=1V-0>m)!y3NP`d4=A#=6V6HQzw_&34 z8qAS2`PtkEBhqga__U!VS?`2`yULc!df4~XbC#mdWmlCSK=qxJQmDonxo<*MlEw*b`r{PP9~1)=~Iioet(VCtOT zFxEzS3Tph1BBg0bC3b|{j}!bR;!f|pB~s+{C^S3;I9*P#!)fU-mzms!lc-(#V-r*R za~mJRu^?d~N^(go`?G z?kW46H$c@k^%2&YJ^1nfXku7UkB;WEqq4CKJGcA~(0lp(7o=}rSQ`jogLMKVW%+Ql zX!HD;E4m5stSd$GJ?Z0&%Ow3rKqRh@;e+zY8=ds&^VOc6o%GbIT{`d^J!_1W4E#pV z3I$$15nJd{&YM}a<9K5B@rt(((4(A&$#W<1Z0&53qL&_-bys?vFU4odZbzOYP~4FA zTYM?vFM;RB>CtVI>0B5H<1Ztp}i5H{9@u!gsCSb{Y@&s;{OaC$8d*9GWAqmXuPV z?7R|`)IRg7cZ%L(yO=XYI7yX7e$YIf8v|i2+j|#^pZQg+BM9`I>-{a^R2-6-G@ouh zJ^9(t44%27e)Qc~8%MQQ3zK{vP(`w8Z4m-x9qy@sPoq)=VG&=!h0pCH-Hm`LY*_;u z+I*udhG4Q7#6u6^bk6TDpHb@#x6W=w@xdjz=yHzgXe69oOs{`H*zq%40wMhUMK2oC z^8VJBz)5i_`YdXCr@r?%SaQGTG=!Pfh3IEn>)1Dhh*ZP6&(Oh`szm3jhPZuTj!T_& z0^u`+wNP!c^EN>B$HcJ#sJ>dz@sw(s7F5hZrW?6Ehw=E>-e++1e_Kd zl!MgKF)x=Mv}x)=7M#i?l~*Aw+t-8In@W1n50zi4h6z-V+e1}qv{x-CGbMCWA_B>( zyl+w%E9k3s~;j|by73`b>%r;H= zF*wb>`Wy1>&fkBZ>9XT87V_MyODltFNk%K?PSTc=fd$c$tpY`5?mleT+rmW!NUD&- z1)pjw4XsEjMR+s;N#(UF&l1k8E22Jzdd~9?F)SVL^@8eVRW`P>PNK*_OZ#jlfKsr@ z)ft)r^&$#i?RI!AfSO8f#(GnTm_-(J5E9U z_y1neF|_-_DLB=BEAj@+Sto`TqN6I|=QlBqbH5rvN33Jj^WgN7Q3PSTTaFdn(fD2h zCgwi74$y40#Q{>%K%N2V2^gf8_M^7415kDEZ7|Vmjwaj0YZ2aBrWBIB#fg;;p}fZwh(gVIHYX}n zv%Ml3!ibVS6OuYH9)qM3pZ>x^`sUhj531gj^sH5d!!jWJiiE(Q7?b-#)xLM!i^}g- zh5rZf4dEN(C{(qlJjxk;dNa^~{6|ertD)L13wjNzp)*$m%0%DCP5@=yfqi9o2ae~> zJb)tU5x)V|r5XM6NmcVz{Yy2aT5w!cY@=J}2(7>c^_N#=BGQ(IJ|I1Q`rtpUakt4HjzZl(W+%fFgQr&SJD`OVI-czdfp0sPdz^7oe*1ndb(m3Wu*MDOJHH zQ4Qu~cXllJC-Yf5iB|uZ*$h%x^jmmvs{JOa8BSYMUHuV%lU52<&gY#lmwfAn>Q_t| z-BEqO3L8Td*G)V`Pb`R%LiNhSWF8TvAY(;6lYO}7+Xz&hI0>M%(R?+8ud}3R6id)w zibl28*7(6`gmoO~t6A9xfxgrwawp=)C^_?>njYN`q5g`zk|;I4-Z=-6ej8A_Vj-lT zmsU_q3>Ol5kZF@DZzHKzPjI8KdNjWCJ*j+kn;%0n-qORM$zaPRF16WhQ;usT`Ru3_ zdV-L5&##6{x0rpPZg*gV8hNT&YZXXdQqNY?>fj%b;lrnIOolTy&yc2HLOZIXhrbj~ zJ6TF5r|^TF08dwOY%y5=_K_|w*^m7%ZVl=*yz5c|NFtvpk*Os;QCCLkx4XHxLv?!0 zbrDp{qh=lq&;Bf}wZ)0)Xx!2!;4FJZ90=+^w~u0;Wm`lmP^qxm9*#;Au8acwohjW| z(V7VDSUJ%1j5vt!+#A9z2>-s2Au{i=<29RlDI5!kM zIcUmaHm}F0?g$^}9uH0JHcxl*nO(Ca7J>TXK0x!$g{zULET6p}h)$>I&}NHH){f#w zRcv4QEaiHOh@^%2aVq5L5bl|VloE;)!9AmuZ$X`UYYP+pYH>K5>|3fmq;Q&I*RoM( zRznp!%8E+pL8d9m$%IXn$17 zvxPc=`@zo7Fk}bk^p#WZSSQSx3{b23TixD|BUQ9)zcKt#Y0wv}s z5j`>8k=dFl%H1$Oz$#%@ndg2!NU~-`g^WfXM(XLoSkVTl6TJ~^-m&67y0b}O`&YWp zJ~Fbqiy9@zXMapunB2{ar;ndRIUyC9vyZm4(F+Uv=)f)XZk!1BJwQ%!j0928f-Ng4N~q@-E$|FSv$C;jff^V>sw z!_mH~o^iH6eeHZ>grST&6|3>}gldy{y$e)DL%%qXs%Fulb~Lr4%j*ZI?zIK`K=q?L z=UDLi=Dn(N^4eY=RSeY>ZCV&O)wx%%CIF=8qvR02y;+K;bZA1wRH`gJ*Tl4+cPt60 zWRKOl0F~D#MjfftvFgAi02mu0SOHZ(xgDz24yHmcv`Vh{9Z4CaetyV5eqtQ?hxW9f z(}}9+NPzkkw?_o}$czn0zj>g7N9kL*_hOCUbZal4G+S;JatRX4&WK?nL1L4KE=BZ_ zp@%F=sbKv{Hv~GTzk=jnZodLWy~@g@>1QrQ98_oOu&Y!~Tn}q)6?zf>;omBUxxY=YXcmOi2}*JtHW5Z{krK0CoJ@*@uJ{@x3Ob zudWPs0H2-Sb^uJ$ETIbt1(kJ)2z0blhH+r`N3p<>=uWGdpzj)})HW-( zI`wNDfnC(^A|)}jAXxSv^rJ*F?gfS~st*OjyDV4r=#u1kuq$A?d?(ovo#$m5D=EC8 zB4UbBEuZ^3RG&{JdqDM#yk$@glq*4T zm4@{kp{(6OF%+u$(2rw))LzM*hP|SyY%Y+hoycG?Ez5rlP&&F6mjHm4=~PdsE>S$i zj)`*(y$|v<6)7DlReO9B_6A3wwV9}Xi90U`NwsVIRj8k(2w{dq{8#{0e&ixGRA+wK z#|KWA{BjjM>2}MWK>l6Q!%3*Wuj2)Vtjqq57lhM+cc95#)|!m9Q@hw1+*^2Gj6m*1 z*&xs0ry9(d?0P!-tcc&m09v*-4S>F3_yxIh{4d2ajOg*%0o4wj2EA8WeS!$O>a3J0 z3jv}ua=(IRzJttxs#J^kju47Q!(Bnh(w8YniRHC71tVswJjw;1pVWTf1=Tsvok$WUs6G6QQ2$$pGg$88bqx)<$>NV# z^Hk-?RO9|GbL3pRG676m+~*Y3&ED`7T@{4UAJ`MIkL~i=`wfSgEB5TsE?`A?9iP32 z5ge(n}`(k)Ee37d(8rqm0=5I#6M980IQ&gZfylRj`te45csE{#XrA0zgi zTIupkI_+BwX)FrV&3j7@`zfc@{ta}qcE2ma$$R#+x15=~n4D_-MgJR`qO}!4(2N{t zXEb{)uaK}>98-jf97F6$WNxY8{s!}&JqtW2dTqm*nb#Z7o-EEk%DV}VzTQ`a$aC9d zzcGFGrck0f5(v$qUr(~aW^c+^M-D~kSoHVZ&2Kq~p7k=nj9_XJ?QMnAj*6oRu$T4n zfpWH_q7=f0I?GDb>2P%l*voi%y*g^#gww}jB()=}$C=`fvks4R5zb?e0$xM>3+}g3 z=yX=V9^jOevCWeZir7lEj&W3>+| zI=H=;3;T|XVyFt7>}*8x=XxXjM1jl!nR?%30ehpz?(YFp>y0Bz;dC%J1|yO^bA=HJ z&)Wr<4zi;>(2%sJwl1RHh>sVK>GG*E9)*|rddD*9=eZ~liS>&^C{(}KOt})DjhXDr z2-U$Wumy<@2f9Zp62C0d#KxnqUk_dBtPx$)~UYwp_%I{|< zL73D~<^rFpmv$El-+gxLH0(Rf-dhOM>MfI_7OK=fn#zzraIp-O;@57@V21qaDjwLY z9uZ)jDBYK}Ky_&Q$@x(I{mC;9RGlx{DhO$b$>$DKtrdP7p&D_&7V%|#b3EYZsQr=t z+R`RAr7!jHsz>^H&*M=jclc`zWO4RNF?D482d@fL6#n;Ign8{{4)~~>7r2as)gd!i zw6+E(%Q=W0`%XJnxhZ~u3H?wEa$QkS0M`IMDcl^7q9As6b^#(?N{n=e>Z(UP93_g^ z&himzDtS#Jh2l6)^1x^N;(?SKv=7RXPwj+i+pnS6`m7JP6r%Xi!)Ms2zQ%CefpDrm z)S(5;6UX&1=lGW<>BlnFjh4dx+vAkbT z&b>IC9PNXK6#Rg-^8 z{wh)(791$2_?Gku4>;ZX{7E`RGR$1zeXFdHyP@RMtef~8J~!I7CBx^^k|Hg94(X56 zTi>+D!p=amBxna?zGM)27JDq+fjsk7w`!ni|Fl4kf4EqCG8gdfh5lW{V|zx6fI;Q(|M&H^!1 zji=wtg=+iLBZr}S@53IT-`*k&$4fN#T?|5|&-0d{{2?DjD=_>Q)+^e9D>ITaX_Bjn> zGP3VIe(VJJ9Qo`@9YHGdZxy2?d4(thExkF}pe2?K&0G<69K~!KCCXjQm5@sddvDfB z66(r4e_@IreINr%G)Joe-IJP)Nb~5;i;#6ZHK!2r_GM>h-a9}0CyFsgo{0(LYV2|Z z+S?)pOj%VGT68{NJ{3uURHxZnLh+*BdF*J|A263`NVPgQp$hFRx+6#JEg`=Rp-h85 zH~_Vqlf6Dh>*SLK%!Efg=0nw7>uE&(ozGd}6yLahz5&(u*tJ|#x=74J?=;f;&B$Nz zb5JBgJ*%q=BYQ!0eFB87dcS!jEZDMt7*12V6l!oZuttU%(e_{0B9d=obv-py-Q;P) zj1=zWM-zOSy44(D;@%Xb-dwf0d>;ynqej9#k+pyI)tn3XpJ%3|NH%&61Z06gMz-k_t6_Zo31HO9VMff%6?+@@m*y zVzgH%Xty<5#B8WXb0UC#txqvHYOckBP^w-bVgWkc&Ce7lD7(X#8Bt-L6$?gOY2(7FXT~3x zJDoaxE`*B5bqe$&^JEHyeLQU)!bdo!W5i8CMNhy{dD)S7pxRh`^E#Mz-e!&eglZV zQoDya@jQ230w{{K=&jWGmbq6BBGZEfg_)p3bl6RXq}^W}LQ)f*zk=lU3y*S0(_S-k zMIQkvp9~|>tZm28X3Hxh2O#XZaXW;1&w2I5M*y#I=8Eo$>L&I|>9dKPuOF-FZ|>Up zS1Pr$pOXwk9a|!_(q~2g)evIj&VE#-et6lPG&!sOGoYmKaYv7LBK&zn zou7>EDvA`JI@Qv@Mtg1FFCnMOo`rLuTGg?`iBzl4WZjccotc8jIVn_pZtZKx)D-nB zQ-x6f-tJ84o4)*N5b*^$z9qmZWk4MRd;gR^6P2$sayOzXpXBLbtm4FfE~w3zcjG~(~o&)J4lzbe}1PWG0fi^E2;pX?3@LVQVqSxrgx2{IKx z`h__JGeuMKrjRf%8ILe;%d3i{a1EGvY6xSGX4I@Tx07xr1&jQ}NfRN@KYO3!gn zS`mFphN6b+B22`|@x$^l^mMh{trDxFRm2QW+bXF$KoxW{J!x=R&-CQc3jvoJEq#Bk z5tw9+%Kfo=4y>-j@Ci2gPGWj8zh(uY{JgOT9>}!p*kYvLQ_=;es&Qc|gmvd!mylD9 z{39E)PIKeMaGI6w%#7p~Z3Ud#qx#zsUv-1WY|hJ)Nz7RnJ0cL}@03`u%rL;ST(tquT*W7HT4`H}Bb_Qn9(tg)qjVI(0A@IW<`Cl?&;{DtP^+%uWqPL={5xe{RRGWI{`XPaY=?5r46Is@Vs`fjys0qJp=dGC_f6;h#L_OU?AMEdCqbm0G1|_Kq zoTDpX|Fo-+3si#c41+0oGgm}3R_*irCYq>&tG?xc{ny2>BK_={E8?kr=6^pa5Nl;l zCjvQ2DtIK61;%BfB%OdSLrFie)NDi#X!Ak!T*uGGp<4fLz}tv4o|Eha)s=R+iQw-` zZb*S@zFC|HuV?s9pmcB9{GU+h)v1Sbkp7h?N(UO=g7<^CV2Vv|ICUqbhV(wqdrZ}ooNg9}!-r6dM z&xn^AG*so$U7p)rSK^ncUp*?QV%v&5Fc8iYi!t2BPKx!R4=Xaa3a-S&W8n9 z2QxoYIs))!zW=uj>4yw8Bb2z3wH(5{)(R)0iT!Wi8^E1z7nf<+=NroAq9X#?7)H+) zE!>Uxd3?vY6yIWyjWX-BF|QM;a(%1cf@;>PWNZo6nFKaKk(l4B2TkhRj|&m1KUK;l zsA~V0g3WZ_X@MQ8i*%`CsCH(`JV;elpWX^p<&kC2pgLkm3kKHQ?JqE8imZ3%BC8mF zwGag;3bRdwwLS1Z?qKwW=><%xGB(D{beS)Lc?16yoLkDw1Rn(Yry>aOUG+a70;JWV zTkeGPcuw&kLw$?235m)C0ugGukZNGgyO)0=mk3un?vn8 zW(NEQNuvSw7xMm4(h ze!i5Zwg|l0^VeT}=*6P!Uw-wW_nJ0I+#-7Ej%DjrTTUQ-L20q;+tB<`F}aR}_A?({ z9;XkDGS+SFrGvmU5c4GoEj#a>-$0rz-O>{z?A@8z3ZLq0!b|X(A2If7G2N~O$N%rc z^wSu-XRhc+mJILKEJsR_byq$}q))eAdz8N+fA)55>g&c|p_+B`^Z}@H-gtzPY;xN! z2yMy>Or2N0y@>2x;|3!Mkb?EmB_cv3#;Q3wPN(Rz-t^{<*_%yiMxzLkQuwcY1$)Kt zL=@~R1Mk2-vo`rO?4R<5m&x8SSUryT{LJu-V)}-Y;5`MqhW$Y zz(g;%rxH+ZyaW{@B@VN*31^d+b3+uGyshjy!dv#Wd`#h0GWX4h)RKNvN#X79>)jEl zEvM-t(tN6K{)lkae3h_-z^fMQDnaq)>Tw0dnVz}A>qm`&N$6*yt^5N7AG5y#=(o;X z5l0+acsbNL*Ud)eF0Q$<%yR~Rx!q>C{MqFQq;H1`+Z$|I+R?r+tgNnJ5H4oE6V#>pa-)iZBi z1j=RB)XnI}h(eF>d(YXJel$;HK(nbne;3LROwdAe_Y(;;3lo+JBMH&I*V5F`d{S)8 zL7_>03gje7E!%*c&TyyDC5zn0mxR^dM@9ou`7NLM5GLk7MfE0+w|64^%>PI+Z1TUP zTSqOiT@GB2@Crfnb+9qb6pC3^bLVyey}n0IiBRoXHO~xHhYu|PN*45A11M^5&*qI# zo$SwQrIr|vxoeQ>lzmMr>`Pvzp!?lEsRbauqfT^z_-HxsyM;k&`_?ve&pz}JBi0?f z`9E;l%6m7H;FIOG>mk(r!(}Nz;s2q;GSP5L%CJnV;Vz}fbVTL)8Imf{Hm}Ewh4|Xg zQ|nDu2~$+;x0R&I5k7i>`p2J|z|+DmxBbxMt{s9ox4DVgkG4(&Fdfl*#XvJl>HK&2 zT+}xTRoN@fyOF-uzk}H&T?Yb?X?~_v5{^bW&|``fmkJC!;E^0`X&d#b{r?>j&68J-+G8n8o~@OPILD zG_FOV){n}MqR{jEhO&`pKx+elZWpi?pwJF}OdA4u+d0hXHh0cJ6xy||{4x?PXR(m| zV3dSGk1zLb0izrBYV1;exuXE_<6|Xi#Lw;g^&F`R`o36!nzHV$sX=`8|MXy;8n?uz z!=7uYYsI1G)>DZ1(=y+4n1~n$e`vnLmLwz6o7(hGDAHI^#D@T7viJRTuqS?c!H2MC zWj=ya<2HsoHHRZGrQPe}EU2kN(y##L5i?h`%_l<*Sh2NA)&`Umo3^2fO0p#GJ%N(O zoSM?8%O(dU)B1CdQxSak=K{E#5SKyL>R*P~eLq_^fg&pVCzN^b4G$b7TFzoE3cvH? z0s3`F-G6n`XE>u_BZ-&kGoT35k>BX$kTdURU)@Qc0p(6l^hD83g=44{)`}?AAPF_Q z4m^LjZuU-tdpvFH7AiaA#-xm#YU0J4Cwyk_lkEPl75+xAyG%^BUu@QQp?y0lmJ z{sy{J>CBs8;1d*{Dg=uf46_RKDdphcJ_5qc)zF#5aEc-AP zLcYSs8TK{XYFyF3tu@(W=%1gd=P3b@FVzO3s-h$Nk^f8a|A(T6)7xxlikRzDhyESz z^d6+5x{tnPLjNS6Yz;=HhyQqpNT%yarBf8CuinKAP){^hcu`W81>a9WRhGKscc%aK z+rC9pUmq<7CA zrKrGjX`NzcDSm3!DdHlMijY`NK=s}w6-H8J4`idzku**sy64^Ia0~fgkx3CMGfHTJ z{WZ3_7eJLM+Ym}J?@R*hzq*?K06bePZvj$wB!X{1-UF=~h7#&m*#O18=7)ZAD!sk) zJtU>?)x?6l&VJnxYJXnqh~{ry;lqHEv*IrZ|JP?PFudJ4%0z@O;&H27m{2`%+} zU4ir+eh!!dQtZu6XQ|R^S$yatnniO86lWz!MZek0*ViJ|u{h-;G zbO(vpFkfG&FW)kI2bULjRYkdHpN`(qOrQ1e zYkQ+n`*VAPku)XYHU6mR&e%K-Rm9PBo-ad1R^2n$_qm15MI^tv8WY(oQ|hvTT~_GX zQi91%-sA1HobEM!I;~LUANFHZla9m!(618gXj0b$*&@`*&hK$Xr2Ymjiy$cwdaIzS zESGpfb(G%&^s2LhgPN$)p{J7$6yCBtDYlFh=86q7!;)IgY+RSG1X>&PYgHN4ry$;pCt>RUXPnKW~8$KoaatVBvPMKT~ zK5EMpfR^#32a$fE)a->um2|utM1-=Bzq+4k)TVrB?yh!&qGJ}{hZIfjt}P(0N_m3| z>ys4%Xf97F1fq_DDjtOD7d?CsH}rim%)9IUv=@PT+K+fb_4n*CrXzknF{r-D`*pCy z=Jpw6w(v$jAhO^58;iixNU!R^hrV#PFjREuhN}R>l$j?r0ld)1hm)xxt+kh!vE^uW zpsvF)wlD0tc~wX>H;SqA(E%4<6d(PsE|gTTcI8jZFg^dx139H?xs16~%Jjo=sta9K zxCA$#Ci7m89MlwiN#zPcY;J5uO-+Xv~W|Dlz&|wb|7|Y}Ealqku5S^Dh{%=QCHdv8>HDcLGGV zNK}XY(0wdv618X5x&*;|MZQBY=y1}lE16bFaZq6!nmnm?UkKH!?Pl!O!b08>2>-!Z z0jDtmy)FjMJm^oP?cC_ z*7NMrn-n@MhVah46i>2OZ}VP)`n9WinD~3EN-K$E>ZOOd*re^r0!OHhd|?$)s+wHC zTJX`HEH^QI8VTWoJFX)F#J4#tv!nO?1XBX+Z*uQIC<+rF0CxoJ5bQ_G8;LK#=U9*M zl~8TpCJcqDHN75N&)WT-Bdx;W_5vmK#BqHf2R$_>x}y5LD@|&enY4_a@|)ETD05{b8!1Wilca#D zu*Vx?&xwrZR#Ka+VdVzcUmCmU1$*A@KNx!lr8@~NT!%OY(DSQsTs9AfVno!kIZr^H z#MjE-flu+%ZZpp&v~*&+*Bevpd)VA>Sz2fa-sb8^X0C`1#?yYmu)fwg1whA4HdowL@TESm zp8NK`0{W>z#pFLM_|eq`_k(?BZ<9;`Ggnml#6g>heqmF2+a)58zM^|J>dSWe^}m*15zC|LQz^g1^OY2+P;@T`s)q1Qk#MT`rOBOCEf>n; z+wpVUq9+v;-YR%fLFT59*-v23JyEtC<_?V`X3~_Dd7pu~UNDdZpIOa=H|WRvy3Gz3 zP<$W1D(;uwkfrykhs^Gw>GVpvEC1w9u?gv$e^q4OE zOdvbp4usE?$pLUWt`B8!zH+e#NexFV`VTN|=)F0Y(0BXWlf$S~KK79q_WFXG&eSKn zd~gJzvd{anNvIAyV1m%d+dPO$OPi~gz<#e;=|`%v9PZu%`dK+evV$|?-{o~Vp!-`M zWm^DhLGU`%@A*p!G{@S$?xso$=15)0XQBJd6;bqi?G#$llx7M?^xI_%ky4C$n;jk5 zQX$EsFX8_+p3S&??8>dC4-}I(C=ok%}@S$EC_QBw4=+4I+rLoRmK*wDUyn{FcnT)uUGJ>%bLzN8UX0nnOH~0sW8j|C0#qA z2?C&7H+~O5vv?CMa@t*|jDb@_=!RXCX|=;dqz5J^eo|_rqPpCd%b{BKvr8CMFTU(z zBmeBp3TAE}t9h_bO6|1c$56Yi8yJ?hIJi;%oUJ0AkyxsZ*UEs@0ZEmPTJP|h+KDo) z-Jy0uAa8L2IG_J0h8t7u{lqM`LPkA~PROE+S;PXta!lIEBl* zZcswDnV*S*@bl?(cgjfWxv~oOe76OIu)n6O@P}%#e##LfIpV$o{m`Z-U4v?L)h%DB z{x`qLnN*8;j<2I3Hif$%NV>=}20+IHHcp|?n&VzxC^Vg);R1U{^<#wUGx3>OJ}*$C zcWxGu4Dng%Qf6}EE-BzNzsH9INV#^42=Sd`TH&-QX08e>F+UTS!93O}F0-^lyrr;z z!h6?;Cdb~X+X$#)UrBt1_$9nF2GyVS%~%J;N1{bg?UK~&1)l@$S{yH|Bu^cL*AmMZ z{J(vlL*)x>E8T!8Yj7CMRm7!%dG?!MP5ZTFWzWwrV8$LiDN2l;97Xch-hE0h6=&$H5bU z?Tu$pHT-6mqbQy{6I**sWnO|vf9A%z(BiP{Hvb92|4to2`7LJ2ZD9Ij>>Gbzsvi0R zyLhtvz7K>o&-*Zt+@`b@5V~`Jz=o0@)h$Q$iIqQcfnIvw5iDqFcFih;FKGM%keK3b z|A<0k68GT1HNKL-B}7>#ck-D)RxbYG@2r)Nf6uq+1J(3k$S8jRVX5(~x0yaCVl5Bn z(jQopf)sbMZkAfbYB~cKG(NY`e=aL-rf-F2XTd`mnR9kr%r`UtBAry2O#kQFRFPH$ zRrO}65&yS6=E^hEy~_DOCo{q@;g`7UVV+@##t7UG{)8{#|beufasoJL<|JkkXxo9nNGg3;J#l_9~9L z1o8Wn+8D&I()Yn$8Jg@1q0A#yMRleu6mt;CnkAG_`k&`(%YaCvYaul2Q&rIjUsN*c zMKu+?>+}~0mo{_&JL`htN|^i9B*J{cB4D~yblkWA;H~seOs48p@5Kfod?){c6B1n_ zZLgr}Md9s%nL=q>*=tZ#3Hxhw&uG;hkkD7)M`Qf&!`>8nV-DF@$ID&8Txm^;qZI$5 zp6vTOR4b#OKxj4cH&Fg=8~Ed{V9!>wp`7B2E&SambvpKF1ZW!Zpn=K1OuG@K#tI_b zP-=(nh8Uc1nsXEOQ`>SJ098t+D~Q^g_;<6K+F$eNWEM)zuTBQ1>_-#zC{?1g-a-Cm zUUmSW+Lftt#*kJ;^f9P-9Wg^y)l|y|Do?m79#pwf1prW<7d?k+ZHCH=0O;MRm7oC~ zo;))Os8{*V2Ub5Q9)PMA-RgtjTIs`{#SE$AEWQ{jp9@34N*b`GA44JUj#>iMyd#b- zl$F3PHXs!D=A1%=3NB4{$5hO3IDzfq;JsrzQ$WwP1gQR0w5psK$a3>MjJC9oH*ta0 ze3J#K%7xK^5Zc+3D0M2iY&9A%85=61{8_xUYD9_+X;vaqkl2T*b`V zeCHv|nzqYfDV)BXobVv0>VNdlLHVpIqkx2Vc3dow%3dx0KRmsASd(YAHlBn8Lc$?| z0O4p70t7(_hzg#XgoELr0-|C?8xXBlwgqb)?AQ(o350`~a8R_ig@|t2Iu>nr2V3hv z00pIvI?fcoad$Y?V(T{>t5AZto1_r zsl{pyNkt}hWx8_usRf&wLa+5`sjG@>lbE8O&rC&8dA#|bU?G2-pPL)vZ#Dk{QOMJ| zAA$byUET+f>1$8=JrV!So#W_=@$15)Fm2b0cEYru?-at+X9FLh1}k(d=h0Xi@Xy^W z-3?G$!CA;B{qXrbj9-H@DGR2(ovpZ{?5)3r>1}LSq(=CZ_xc!2e(wXQc3s(GL~rNy zc|qqpSx?Y?eN8HVRByLvkOQ5)_YM!@9Y4F3X>{9^DIAfu7nMU&x|R0@(CL`v)nZ1H z&Ff?^O?<|OsWWMx8K(S*W92ZdPt_;EbUDAS1}(wM8pNbgsl-g7cIW$`P|xKNY-Dx6 zCn}J#Qbhc!#6`irVPyicO6&4 zc3Bov6?R(~G?A72*hr)}{p1!;psFI`HGzD5%^#Cfzl!c-AfWjr)1JU2x{^VHsk+gS^P_Bbdo9* zmDJJwrS_4tpV1<3eb~DZ^iTC7*Z*ojoRsbzt>o^^lwU%iq8R0ui0E5s>D|Uus{77fi4=}-a+7nuXlYe$G;59Kk$UVAoEXO z0R6gm&LdLKr%9i~|4e1^7Wn7SE)6Gt_Q0PS0kpEw7K6n^-9;>Z|5W)JkotT$osBO) zaM^QKNsJctm$kz5{-8}p{>JSd?mqP82j$m4Qq|Gj6xTW52>fSjpus1SOy!H(&6%{T z)?WS)Oi7#-Cy7%I`*V|?>eRY>iwLRa%Bri8s&{F*jZ8}%7nntT>)Ti~{a1|<)qBO$ zg(<1wcs&*apXAxe-645n5Q=Ek9!rL4>CaJ{D1YaP_Yy&BN8HyokUCr%kPlLq=K97` zQufd{Obq{j`f@c)e<-^Zj{lgAxiD*^|3L3(@(Tl1t$o$Ufr=k?6!o9^WGtJ~FW+(r zoH*Bh(hE+8Q~d&f)T)pD1f0ZO>SpMVblJqvUusxP;nUx^r?yl0D*Zqj;M?z%s0e<) z;8hR6*JOlr0{-s0@B%VzP>Y8Vf85u|$fxz`=2wX+o#I*+l+u4}{V$N|`^N z=E8LTr)IOL{CBHETM=q%r7jvusog&VO~fsB`3C;2y&49pNoYo@W{n`8Qf<(8&7z|f zCldA|J~yyB1NaN(G*Ei6+oHWlRV1)XBYt~_jTsa7FS4VEm5LvN$`R`MlmK&rXO0=f zV(#FUZJ=7XeK(_&j-u13Y5EWMP*csDiEd*Rcuc zeJ+`^ND>9}pNPDP_@WNP`KH_mL>guNNs1#op}7j~zC2~xK-^ER{QM4Dum9AW--D*Y zU%q`GrW0XrAfd+jPc#j$?&4fQpy(VKBgi;`8iF`<&a4H_y?)D455xQ?a?hVK?WE`& zv+x}(sx_Xq*wd?fg6ZZnOV%RyjQL-e1*Fh9%Xact9DA)7BumAvACbRho%AS@@3MPh zY^O&(m<3IFrdK#%+3Tg484;@r@_@|ZBTmbxEcl@{x!vFB+mwL=SsedcTZ|^rX!?ZQ;1bS4Rdjca$ z5#pYX>?QM`=t8E*=|)Pt_FOR1w>b1L7Om$7Hjt(8z_Ux3ItIleAYsm&C`=j$;>;UqWPCheBg$azBAIT%pOG0I-XbJUF-Wd-E z(;?z@jpU!cwMhz4g31;RC29(K(+51s)0dARsRzT6+W>0TR31m0%5z1xnf%@T9>A2_ zsn`zF2eHq4%tGa?I?I#~MIN z&UC}jD7id>%Xok7`Y>>3?Q@`X{Hk=+)09v+kiGDvLeKx}EM-2s#@clFc)-GQ zvxwF6lXKxKwY$dU7Fx5E?|SDcEh>Zl+(3)zt{cz6GHG?2Q%L`_w)D+=QxOYq0_9Gv zf9EQ-e0fEj-%fh!w)XZpm^v?%+#Dy^- zsHe^SdI-XoJuw_Z_@>YcOeC)R9}&r*bH-!S!n_Q>_=Pj6B4~F3Oj)1CpMvRE*GeaO z3-6%G^{kgDez&k{5&YZF4f>Kl=MSxwFtwXnSHu5d=14UZwf@0V)I=S=>ibGMDO#)Z zG$8duwZIC~6^H8vsZxETadwyvifUqrKTD>we2DlreV+6Xs9t6bF#HdW6huB@Q2k^TQ~}kZr2A+I!P(9xEGC(3{RDMf zBT9t-b7w~qN?j&xy-rYdU&QDE)f`>RMXmm5(pv#FSLBWY$ig{UfO=WcF^EQ+uHQ!O7r6QtDER^eZ3ALEpG})gaPWnhLf7{@*o1pmC$W3CzAMNl*d@=8h32d4?_7`;j-CL(NK>lUBWD?4>gzM4?%OX*fh!#zM zOg3V1Sdq3G>QU(ir-+l{kCJDADM#cMituvTkDlbO@I3fEy1!2!)(HB>hO5P>-ht#) zhAHmr!(d7sTd2p9Fr7)`vn zHW%_?&1nKbs%3`+nl9{VP+-%YYNpTlH#DxWESl^?O=1U)4EtxpA^wt|hH>H16}zkg zqYugq(C$!76Aw)qJ#-0Wavb+Kfh`kDd(e4~PXpFL&(GhfVA?T2E5JNfaibfdXJNNH zsx;1D#%NEpM<+q}n>kiy@(4!jkh{Jyk6ipFpVKm>>U`1NSEaUN|+Ak z8obDqBNU9nG@<-+RJpkN{r^DtCsPA~=rZ@C$pa)v#r(515WVjCMf6j7Ufd$=dFtQ` zWUsfa^M-hv!eHnBa@ojr4z3{E0V03hBi0=GZ~b7JApCYDtuV97iplw)H9kS^0JZ5)P=o1NwhSe^?320Qqhg+SBRPRmKu7T*mF|iyu@` zq8ZV#!7#npTI`ST7UMQxdZ$3 zZ(2(~%{hxeeKBeQ7)dJ8vxw2YOb_=ydcdiaeW)ULq3@tCkNkNozhVTk=gxnZ4jomm z^@6+SlMSl?zNjdGOW;kHel{V`i5k8eAl3S~A*0ffPh5KFRJvo^+bk-GA|lEIK)c>@ zvQYZ1mpeF={Dh6?2miwU^bq*(>b1I%zq2+g5{t{)a$s3jqEOPJB|689(koU8xPY%t zHyU7i^`L@J@HxCF6KK|$-NKOl2bJS&P?ETImQC!<-gH|F_KHe_e~V0w|M3LUDW5V6 zDgIEete2_1UveH~qT)m?27QK-x@h39ia3u=J#HG1e(|Qj9Dvf-%4-0Ms~!}AslU&j zg-pbp_YT2ySglndKHt~OA??Y%HVPrAr(YltD|Z%w#B5$X7Hz-b1(J9Ab-z+9_BewS zP)TQDDiidfXR{5`H5n4XF8$^ojDdKX{F{F+`XAOOYQ(R!vPd$=Vilu!8l zwHWLaFZIvx0*&40ZS--#F(%wYMalOoX0F zhfbr(drk-Vs3JcE4A(NNLt3 zg1HR3w$5SG{)R;ypcl=ivJl=nR4 zjhbq4IqgZF<7QUt|I z80~T-32X{w*NA=L-K>qUt_Gsg;cmGc^K7qx{Y23f3tmM;9qz#GY9B)VcMnh#;IJi16oH5m&hsPP)h-8=M3b#nV*F$Hp*j1Iu2*6NHh+O#2e z?_iDV!m&&j;^I!>Ee2Pgy>xHM>gfu@tFA6dbSkAAyB<46 zycjx>Q$)IF1O!+sP^neUxvN93KLm6J}NxZNts&f`U8;^ zd-^99C3Uy9C=^M_VmKVofEqO{szg2nbPlT zQk;Un%&<|9O!xk3HUqvfjhjl9nr*cjfZy>`1fQ5PeYMjBP&W6_Fob&8G2lY@vmebG zDUy09WGx~Y`ga^gB=y7HAj;93RD?p8XAba?exuncprrawi1Lt>sM8|@k>2d%lVw9( zWIH4^Ho)}-P*$26iO$UDfyMf>os3TWJwvfrI5on9_-dm9u$U(JFT}~Qyo$B?-;su) zX$ku(RI2?8uN~kkzhe19rPIn<(4_cuT7-6#H#w3ah(-02U}XGlu|Epxh;wqNOqTNd z5m1?^`l~dUnzP+vp|XxceP}58UFqL}^zyN%p72jH$*YKbQHGie|E_W0c9;&$aU%hB z_dhk@dEzs-e586+s?7D_7JZT zM4HQmcaaAVS1R3-7Ehc^>8vA}A@w`{CWdK64&xr^?T18D=0DNUe^U7~(A&M<3qKEF5-tQDbZVPG=>T`A>8(kzP>@{bAtCqjlmz3HM6qE4&f+5zd1Z2Mu9esSro z+o;lhNBI64qz*Hov^Fx)>?S%-HpkQYp`FAs&R^m?hX4 z;tu32YxDL*pj~s?Tao=i1x%=-b;Q#T{fE&nSv1heUkmx*g!6TNGa}6uWF?|bIlDYUp_3hrol_96w#}!2tDmhjW-nDgIMLBS3ZZ2OmVJg344zlB^NKI7w2pB+!GAq{4MMOm7bMp~o%W zK6ieh88fb6GsC#fQdLb^nRfD%k*eyf`XlgnSn{X^{3qn}V{pokNB4q%gNOVmOm%Ye zahUcOR6=N+{D~hZRbAs4AEIdY4Q7LtxsJF9w6y>Ib4*Li1=eQ-)$FKJftA%sW^CHK zmyc=IpW)wy#ll;rBv>xDr9u=suY<$PIQlN)CXgzM9HS7$GIri1@n?&ZWr4pcOKJ^D zofN`cH|{KReT3#O@qoLf@JKiIOq}jy)W<#i1T}p!&=d+xWktpPRMWfte*OqF-lxq) zpMh+fk?_wtyMt8-3)6Z&8Yw%U*n;JFZZAuNX$tvhiBx z0(<$T2p3ph%;P#-Av?m?BmmW{Jf8zp2hy_ofJ(hqkNn5`+(uwpG?nE+^Sue)#tOu3Z&fW^iWJKUkOzz1#2l$CxHhDc9l{)xrBSFeb%_}R^4 zSQO`bG1rqngosd*2i${bsOkAnbkVc7m5Gp1#&TxvCw1@bp(kPgp8rHoc*ey0Lbfa% zSac`!Q&?=ZSNUF8I4@a_xF`41_t5o=e)A378@}FINavk$ZAUy=^0fTt7WzUcMPPlL zlfK%|kajm6rrr7oKbUU(xXXm^jtbsVG(e{6!TS9$?H$-(Mc>{u!}^T9g%0{|$FCy1 zX#NwSKQ#Eaw+k1JYr@bszbmE(Vf^Ydo>*+Oea?=d`(3eLmR8fAYk>-Da)@I3!T4Ne0+2kiMpC%r(Y)itUqFY?!>2L1*-sjjH_@Lw9h zGlEh@XL27=%9lypU}~0~b0JepQrg>9WXj1olK`SMwM$)r>W*Kd0H(?P-F;O3iIxo^ zSky*&QTh${T-``JoSbSG%5y0Fkl9Q;>vik&h+f{eK@Ffg$J}cu`s823y|LxdHO~-7 zeq6R1*_Zj6-H^S+Z`_5lm#4DV0%z`2$Zx664TsL`@&?bUxL#y$7~};Y{`Ax6#S|*y zrNc=XRSZ=})7lW<`#kpS((rt-=jv_)hxX*@Wi=@1xw&0@Ebg}4HBzE7IV%)_K0F!+ z%Xde9g!|C%FIdR1r}F|dRwCJR6)?+hG%_%CK?V~vT3qE0lCyWpusA!*5rdFq`xdmV zBJ^JU0A+OdXGJWc|5{|`L8HaJdMSD#!d$gfbbq8w_Z1Nv&@?!=BIl*GkgdSd(A_&;5&j(~XKIPkH%a*Z;lA!Q$%q zPt;?xpPWrb<9@NSz8Z2~`ilaV-RgJ_lKQt#JybTX>||8dW%GBXOe@6uih)U#b^-7e zF(o`KJ|A~3qMV%7!r!5GGnd*tkf`^U&FDsZ)6yA)zgXcK3iLj2v%<)g9tU&a?6c~;>8?%fo^n0_VmECo#%fTrg3>Xj2L#OISlF7 zHk9{Mi)VQU08_vJdx(B!{u7Po6Y;&p7$vhjrl7wT%ps%E?pdTMXRY`imS?7}ufmpc zdn&kdBpu{4r9YjTg+L#Lk&2kEUHP7Ojv zFILKsra0Se8m3nEEZRPg-{;M6@2+)6?Na0_rc9>;U5U_i`5q~%EMuSGkRB%d3I%YV zyVL>U9vU*xy096Q=nBGU z%Z5S+bHyp{KMz50E$f*R%>QX~{r$pqUHl}g8jpH~r@~&Phj8-wPjnliAlGK12beuB zyy(5ub(dTIGk`2j(MR6tq~X?G9>b$8^RiZ+>!3yb_3$-c(2c1*VUJ-s93%7DONr-k z6h?~f=>N=vEYr*8+OX*4{_OxP-R3`0bj`sh8hWUhl=uLKC7ru`fj#6~Y?nOh zr0KBQq4r)vx60l--;RtrMkSl>&^fE)WRVY|+oziWUb>2ka_KZURmmtcvKF@=) za){CskpApX4Zfh1_ilxW*yDKDB&QN7b57CgFdgixO+i-fN83}uN?JOK=NJk?ba$Vp zLWsdx|3MNPa<0JOPBW|X~5Ty-w`z`!!y80L-s_yDV z`4dhz1=He?=7uNSEk|-72~*;`KES35`(NE@ z)AX|SD%Ae>?iS3q-~$|>SB^(Adb)eBu9ncNqd%yGo~D00gDP|0nE^{`^`s{q*UNlep@)BzI$21*RAm5pHcws|OpC&Ux5M=7 z(p}(*x8>nP6(Q9$t_p$atl#Y@C|@#hl&O*tO$n5Y^5&4$j4b6U z*eg)h2B1q!g)$B$pcM<#VA_!x5rI&tiU@34s!o^CrX0`nRwlk6?i#~i-%tQd%|C>r zq}sf-I^Z`<1#CmAAH7sCsqX)`3e(IwbvzONkFDuq6hL)Jg-}LgCDUaggSVJ2bB~4i zoNhe^)O5za2QnMip5{R&tjCu?|EyxoVPN79h=joOm9&J7N(J^_G86qa?-eItsxQzn z>iO90MV37NehV~_kSoR5E8)1qyCcS?0i*-B(=iLjN3W=`r8VNCy%fE{=UH71v}>y@ z0i$Z4jUHemuPc*9Ws+|@&4s^)+sueBjX#3Ly%`l=WNGhH-NxLQ^;+}*wGW&dMkJ2t zeRqVzOI!t2!W7eQXy4@1iUzuPhDk9Le~eSj;GuI6=IUO3O5ph)ttT^E6VrexF) z=wt83fVzA>R|kq2r$yS1mLyoD=0utUYqp!jqKY zN1POd`ZMpKj25lcn+1G&Gs~kViw&f2$Br=U)keHP`r{{$C6Q@E>t(wupvs1=FdcUZ zd}SRYE+uJvK%WTW^}lTl#+;?jY|i4|iy1yhg5tWqECYHbN-pmhsh^D z6yBCFjT7)#ZX`zZach(?w55hd!t%B50WOqt=$Z^X-I+7-QRHV`l@{`^%6uw-aQs&r zuxWX}i$6F?)5VEV&RxS1OykA>tq+{cmIfEX^!iU^nEbU+1Qwii)~iu-5md3wsgh;Anjf z0&+_|Im=m6O>jMCZLFN&)6c6-{Up_ zP-2$HE08Yh{d*Yshb~8lVv#G?c@ZZLb=okb-`UZ(3h;9!mEc72K@A7m;d$~vX=U+o z=JLRQVuzqi!P9&QLR}N0g{k?94ka=DA;yfHW+S^UAg3`)s~^(8u2ukkUQos~OjWk3 zMX1RlpIH~kd`pNPqf}Jo@)+s!1HQ#5(=R#A%x6wXG$QS;JBI;fY_1GKPKA^E;BB>^ z52wX*$)QZ}9N8Xtm$(mlfcvJ4e@5G<^=@EjQkBjjd4840Ye;_jSt<*Ge)k@qX`K3< zd8qy1PkuaXs%W$VJpa0t4}WXlXWsD7oBJn*8Rrk#CGc1EDqTUIncKo8?TFW_Gm%qc zP0PDbd1CoxZ%h-lA{pd$=(s<^RC!Y3}XSAPzgbli883-L_NedP-6`@Z%a z)4KBDzk#Z`(p|wo^^vUyS68i<&tazeaS>Z#+SN5J00HLJH^J(iUsPaK*R%RMQcb(L zi{U?w^H0ounW%daBC!X{fwU{KhH0p!8J*C+S}j292=nhegJt*pCtR}pR$=U!0uD3R zhcAo1YolKT>^-<+>p^;kRdVi|X*w8{&3~ffM%SDo;>yAqLVF@UznR`cGTdMG>Os2M z^!~-WSZp13w8H(JoYrRgJwgTh;k|77;moART_wyFnw9HYa@ks+*tOjl75#&f6nFoW_o4l$lHcZNU3b)sgwBS z#B(i2M(7??{=HKtXi=8-`m3<~EGM%WmN#3Ku$0F0$JtDoq7spdhMsN9K1i{yY{ceQrs(twsH0jiF^_diB zwl6&aaqd+PWKi;o<`rc~o*%hQMD7ixN}(c!j<1}vY9!BJE_e(6g{f5+2`A5+f2WO7 za>lscp1qvR&)W!jGQb3D^w(ucWsCO0+9BiXvGGABO<_|GSrh(v80r-GxBW zCv{o$E40QO%_c(c{Iu#kSSl{}Q4%3y?** z%W^=prh}UbqWKY0B-JUd{R*3=Oy;6`CeE26h@3w#l8)N9m&Q=0{U=LfkW=hKIe;3f zS1B3x?5-_fkG)Tw3HEf0tl0DDj0*#_Oh3LEKvUeW0+ZN}QwY;OEvo@JJ)Zwg7c!l^ zu2Z0*`l4DWN_X|=J9-M$DR=o4IhB>K*AX!iY7LyHPqArFf^uh0LBHr?ZX_3&UeB`^OVH#vd^ z)S2GCXw)g|`%W9Q=UgR$f7PL42r|j*EHc{j^aP?iq~H5s&%Ac;cI=rp%l;gukt0*7 zgvnuEy%s4+xZ9CtiM9vSb413|gfrdDzYjx0PErws?_O7vO&V+1U*8{2j8vSHt_DuM zPxJ>U-8ubZ_{+jwQ=sOw5?c#qL8`w3n|?DL&didSkvt@?SEUG;(F`WWuci6q{91s1G0KjW`ZT3@0pF_FHVX@B(6aV>GfE6%y_QIDV7s`38$Po z^lfoZ2~^e}xFr^Q+EP1lZPTB6}Dl&pLZ(^5`1S4pQT-33=pCNluD!5qRY<|p#A$;KDRGC~&MzExCe|G_ z(8Hx7r7oa-VL%LN%yDWuL8zN=xznP>`(O&&cj3m8GqYl_kG=_7FInf2Lx-yWQAs^> z7S2k}06~TenNCXouR=|i`(HD@=96hd_WdDO3ZL0M)<@rj%qmUikh`K_ixP|Nt}gKI zn*T(Q663BqY5lp+>BLiSMW{?R%RP5SeP9(kUH1&T} zFb%k}oZ0n61RItIGFfEE3zrNb65BuhQk6U1)caUc4E$GP(xu41Y?pNvk<##A!Te9UEPn0PxEO=YZE zdLL<3*mFv&2rNI`HxL`NiZ3K#gECW_EAe7Uamd+3Y~F?>rUhp7t!D7T6-CIw%W6d@ zmrRQ@qFPad;ede{?0P-rGc0zG>cF7xypj)8@*u@kpsJENh2UkI>JEgV(HmW{xV)&= zpJ+)>_^y)&xus_u1h4s94kD?p3{f%`FN(Nc@IQB~MhaTDoRuS0-p0mO9^n`Jh3{r0 z5Ei`;sZPrym}))mk}&h6{Pp;Z24gX&ffG*r3!ggr zFzkfJG994mJl?l4bI~!W2G>$aEgM{YDX#GZ*D1~(Ok0zhza6NiwPVb@3tL+b|DFc# z5G2rBJpWIH^oQ+o>HI$x(qBiv**XhT!#@OJ;L19{T8mwMUFI-w`Zuh;iUOGGYnjpZ zeVv92TJsblHtjleNSg)!yd5?lB*5Bf{3Lfuqb zlE7ejzd05PKBSflVOo0G;XxJP{MQ8)7<699S3wuHbCN8k1tP0F5NjJ}7!z+YXte=Y zf0(U;*!s7)V_@^bB4QZ{Pt=7XK4&Bmssb^QzhD{d!) z07KK#CV-kz6&1s@*&KuGWyAJG989s{ztn25Yt_I9+1yx`rJ*!5K=EWy%(l) zcWMh^%6%^PM+J7~wy_|Ag9Q;7P3hM*G$YnSryf0+&M6r}TDJ8Uq}a9ngsBX>K0GH2 z#;(%h2yaN>y}}XjVhIe4#IB{%90=2S>is3~KY8Fw=t}Fg*uu1nIZKXEvIzT9m>QJ_ zT~X}1&zZ?$sMx{~kY#EE)H~c5D3G`D_CK*Gx_O1sb^G-?7v#@6lZ^QC9GM8J_$$ZA zEZ$ayA-w$9B(rIucrh&BR1`2w?|#i?!@`MS*m=!0gt|(uU0uG=Y8Hjn&5Itm^%(N| z@J)@p77i^cx~1P>Q8zflqeYI(KeE_S3zx9mfgRD~^u#9lacfvI-EI12!(*e%!egx7 zr)>gSbhup0XS*$&3=;lfO2nq;igI0(=>!&K{ckK5u@7KRpXlpegfsn%k|!*3caMFa z@vhqK3-6?riQZ@EA=<`uj}YCaTD}RU2hWuVU^@SII)?}mxwj}0DNCM>NJDRzj));!I}+RJANTL-Y}hbIR$kc333yq(q$(P8Sl@ZmM&mNYZ$J7>3V{ z1L#DW^51>2Y_4LuJy-f_5O$(UyUDqI8INa1IsK<%Mj9zkmH%0f{7C;y#T;^Rs1cP|p6$In;i* z)w~Evv5j?6v?i7GM@`MKpzKdNX$TJMA_ablFLcvwZ!GqAk3z~3$G0v1Ivi^7rU$g>1g z)WrHw3Q(f!zPo_*U;0=Uw5OcrKzm|K%6-Itb}BU#iaL-ibD{WRmRl)8$zlrjA=G1C zn=2{G^dU@LSXu`K#oQ3$2u@2XK&q&O?#(4iDfEnIEhMW1&8-R{iPAxlZa`{q08xr)X)Fj z1mGW<4e)~cqVBH5rZe?_Wi+uZgopAK_2sD%DSAu{PUOZ=BO>w5dS>nwS_ctHyK&_i zL~7O7G6UsE+%q7RuYc!z)U+TdgG$=akTt+3OcqULge$eFjsMvoB1wz}Eb?9ZJ%Ik5 z)dq}WR)bp^EV<^u?a;{q^)4ZL$Ng{JXtP7P{AG~jlV5J3%`B_md%-11=|0S@1p5Ma ziyI{QQ%M&>%_=fh!e7wBLhoBLea4w-?#B`%sSPXzK*^NuJb=2O>|_D|{!1brWjb7E zQGw_S#Xks1CzE|Q18DK2#0*GhRD5O__Pt$-+VQ_?VgwOw&<2vX!ar7piWK{Alfbkv zyg`9Ly1^3|hrN>R%s6~16(x(|fE^nM|_vD4ZKjm`R{V!)ab-33_eQ>vIEFD`WF5=qvoHVyW?r}pL1 zo(|uod5A6@O1cZ-y*w2egbtPE`Ut6+``xlikdkzrJq`76S2Z)rD}6T;BAfZ{WGO=R zHY|2UqG!5G5X!(`6^KxUhA0<^Wc8rkjY4T{$52dH8P6B*N*!bdPw zr(V>-baG@fAG>BAeT(Uw_usq?(^=!G7$opf`xR#JUM$OkPR`GNqUy1P=fa@JB-KAL zO^Q!03P+?Pc}W~}Ug^6=xXb20k-IgZEtt}Ge%<{La_%sDb16}K$XXHfRM%=QpqGw5 zRd&%;{Mks7*T)N|i2k~qDI48d8ulA;&tEv$=-Txgu*kpfme56itSow0luG|QV|4l5 zyK;JSb$0Tzcx?J!dM_WFZZtQ*f3>(ImHzo+Fj7~hr<+3uFIRYyWy0>MpnQ5g=;z!Z z8SUAn-B%@{dsrW~KGTtVdt3faxT|Kq0{Xn0y+0#Ra_Q?Xgx=|Ou}niiwfut*uxWm3 zTrhxMkdz3>RIy%uUPdpzTAlGrZFFzS=f!SU0wvVlY!(tyxu+%${-Gb2Y6;ZzrV$e% z)g=XIU~%mA0TqxA9+a~|>GA*{L>jN@E<~hlB0nJ_Y2B--O68eS#Az`+1j}hYjjOQe zB`r6R;j~K>!ZiQfA4p*w7sAfSDIr72Pb@&cf1iygU*0PQ^TzEfFThgvr@%h~P+sy> z08FL7nFMt?lN&-1{d|Yamm*DaB&9mAY|nfNQ%U60Y9hp;{)&sr^Vgj;FqPN+U?lXz zaRp%vOP?QKK^o)v|N68B{#z4{V$+w4YrGMEhPTU`lFE}we+&O|dt(gzcQ#j8$lvsS zi38GU-I7xP)2uXufcz)K#%OHHdD_OKq?{?&E<-xS>S{S{YPs!E1CbR8*13^oNs)3T z7S+C%Ts_@Az2p!HqUkS>@Rv(~DRTZ3wcQKH5oBML_6vs$Et$=7R9@e|wiJ8L-Uv}( z&)e;(T$ol?)PqvB_&<}e>37zuFckj`e+DJh$Si3nsr8(VPbF>GFkWRL_VunIJqVR% zb%K3MwDSen=Ll0o8q#=cgc}F!&3}(e4p0T&VfkX$fq;kYiOGpjTflpA7;giQvP}8xa z&#_p-4M6hgjpLX(4(W=Q2!G+qL@fr9q~;!&SKr8837+!%YeS&s^>a3~Xi3g1{{#Q9 z|Gmo0_C;GI%*dRo=YYNk#TtxEPJ+k$w}R5&w{77V_<4>HEh4!(>^11{jHG)&|GYdL z>`hE$gn`oU#?He1()=ed6860wjNGXV4@I5sm#P7&x8+-08gxk&u^?1BS%^5Lei`Vc z9`jvh+{PK3kY$SdAv2}}e_J7@!<<5x4eUO;R0P+sJelCx{@381UvL!F6rJ@jV)0vz z3>;M+5o3&)V&fgm6{zlz0@!nG8@MnX`R_qQul$X#kWx=CYuDpK-Q(_Chm2-3PASoH zpQ&0f2zV=&522B`hD{#W^ii6PO=?bvGwJ}cg1x2kGmJK_)gl_j6_=sUx28(x;AfE z9&tVg{4QAzGup*HK^TtK+Q0CT)3t4JXj{enC%UlBPCbIcW@a8CqmnE>u8JCk9OF({ z$`8;j9DHVvmCNbO>rn45;?o(&b<_3v*92QG{(MCx8p)(Z=Slqr9lcjwDtEagS~&Rd z{1Zh&_JZQI?tbrD=oRXf4##IA8tWIw%k#+JBrb{*kg5E3`p0H6<$R@TgQ?R#@hU>C zO)SE$o&Ebo1aw^ZnU+ttiNu#LMVaYF&$i{inhB}RyX|Kky%+B6IJg6*q7!9&`ND0g zM&ZpGMB19ObP4%uM~g2yb4UwFJxIDYW1Qtm`*tVs{}di zys{++IlXqXB%I*0V;YXZ-!VM24gO27B!j()s-U+BX+uR_LI7vs;ApzO`mflux~veE z@-+4zvFPJB8$&r+cC6_Z5d7yqYd2H)hQiCu(GB3;P3Le4(y5J#Qj+O zw~siMHcb!XOp8%cUDaw3HSBcv2B-bW6AY(2tWRMob4geW({Yzw@f3eT*!T_7A4wQY zhj>=i^zw=6{_I70VA}Rm_$M%JZ|~QWsY1L|3Z})Xlt@60RNhDf)9;k1B?MKr&Z7qL zd+T&N$ba(bI!0%kx5dFdr0oXTWGZPMf0NeA*sUh=152)wk};rIy+=5`~v>B+kNGP|L&j8@R3y3t;eXyY~+7#LYW@l zbN8n*8KOQg!1A8nS4HmPoYNXCHfzIo5`0cd(j>Gi?Jh_5?G9%&AnmGM0iKMZ-($q| z#)%sN{-Dw{|F7h)JpSrK;fdHfh^*+6(x1vSx$=w}bEn8r%gn7e>U;bMXWys%?SOP= z!g?CD_YTSPMVZel*D^CAbCSvPy3L8k*Gls%nYpLfz7j~sO0%N~zGc5-9HG=3C07~c zn*7CRGXAS+@Sm}3wM2v8Tu{!w}aY;Nr zs%(6)Y#ZRuUWsG`_08bfSgOdx>B?4+Kkgn=4^AHxr-RdmwJLiYnHGCR+=FS~w4xB& zvo|nhZZ?!6e7VWaVA>J67kh^1++lcfh6;iHyWU-xFzF)cB}Pxe@DoVXy6!CG$km=@ zMydHzC-zkKF2*e5ZS8i4dmm?+5$;7RPM0H6MTT!2csev}WkkvjybIHgetRKIyOMn{ zBY2USJ`m5`2_@5cZu!liRISarj2`J%)?=Dzv<@kXw>QI%%bPqs=m8?h0@i(qVH8#| zjXKFqt0S>#$+Ux)bH)3Z<$ncf_R^!?Lj#JE14l!bt4J#RvUMd@N0SvC~pvVm#-rzQV@ zJf*<8`ldBaV_kuW z-glm8*Ygq<&I{>*+$%MO^h~Zs_8meco&9fE7Bn7CrAT7E>bF?z;_vn@p<6-)m%s9& zNOs+p?+~fy_X!Ap_p=0V3S{9AokAd6XY!vBNSdE%qUgQNSw2ADDvod?nw+}U5G&n~ z>fvPjQ}#So>^6oH<^SP98invBH zJ}v~bp((e70U9hUkWuZ@ifaVO{a2nAl%1{!$#V3+|BNSG=-^pQ5r4H)ZK6#bTNmYE@!3z+?f|v3Jb*>ibA6-RK*Lvh%1*!cT7xO_%b0$v?{15$VTwz-6yaW9GR?odK zEgGxxC;o(DQ5G7fc#&=d0XeE$}W;=a>bko0h2w!w3UW&yZ zUkbp~%*0k1(my*`R|}cOZCH)Pi+rOmaWdH~N@jFwedSGrA9?ztCp4v~D`wPtQksE8 zeL4gw(B$d@IfFE3x)?of)r7gi)G=d0=jxhwjv>@=L;O4FlTC9D_?tf5*9%UD6FdU| zb**3RB7$n_n4D$iUKM)kUnl;y7yOkD>Ug;nlCe^H~7y$YVaqC0ED1QVrTaX_;>%10)6!wj`muPph=uIgUVRwQDozjbl&)Wn%b3FdK@zyn z_o?9_&m+#BDhMiSuuw{gV#em72eKf@tVf#!M(@3d^ruCI>hFV0lZb>qP`PTCRsqwp_NYKI)ro#l zBKr!P*oB5%ze`{OD$3QI_CW1(^et>maF(o1r5{l&omyHz=a=v8 z(%P(r1B9VwFd2*DnG`Jzf@;A6RSz!7Vkt-H+C9KUL2=fr&^ZcB{H>M57P^ zxtLE-#Z_vLPEw!dV}2;0PS@Wt5>)4k5i^7?i#(N!`aiMn>m>Y_TlT?SU-w}Ehwte&D;ovWF1|SsifSG0bA|X%1&)CewRiNFFpZWC z`NLGD7_Xw<)5|zspvrN|w1`4EgE!400i$(mFHrS76|4ZNwA~hOpfX;V#YB*sV!wxJ z$?#+-T5^j+j8Im|F&6wo&Ykcff87`N^O-T%WZ=U8sHjl}(+f%s2ypar`9LMF+qRA2 zDlsMorZ&zr7XKwkVw{Vm56(s)kS_pY@}vjoE`HVyagq z79yup?RO#G-r@|VquPaq7zoz4*g|kxueC&A&+Xkkm_0h>TZbUjjM2NOX?cy&i9*Rd zBsJ6~rWI$nXnnP*MZ*+o#Ggm(ad;0LjC?#^cOcQ;iJT-Px|i!KBuyBz)R&kco7!1{ioZ#CUELN7gnlPkJ?L7dVMjcmB zr=In(3{KYs88Vub{JE9hWYI^TkESp8GG=X?x=F8>*lz}H#Wyj9WN*OY)53%KwCMb- z%9=h(P+e5DNpXgplM)vIwFE5-ghL)uK_9nd>Bnx-G4NFN{??wD< z;?98ft@ysPBEwFE4`clqf&BWuxJ<`5OI7%~ZFCOf<{tzkX^%}ui;7x{1c9uE>pTP+ z8SU-B&toQ;yQ1l9-6R_QX>2NJt0c1*)&H=`#&R7 z-tUs_txmAClP?lI;Weh?!DcSHBv?x0eN>OoRCqhO4V+^L+ z&B+%TnONpuXI(g3TV#jQH&ZBs^LZzD2yI{%-y}g@3m3%TCtWG!*3dp}F zJ}4Db4OTQYfvWa1XV0S231@m$#Oj@)x&}a<>G_-ib?I}2ZyaaWk^8wSn~D;(@8q5CnoUM~-O<-hyd*FLPh_S(Pu zCggBF*`Wr}b6%8ZP@`7wKhi+IJcoM$InRmmpq^owLl}&U8Jct~Df3dPU3`(IV@T?+ zkewz;jW8plfvGl-lLbm%F|D9PwOS~~mUM^f$KYxX;Ksn!q#VXZ42QCNQNMtt%>jEe zM{B{pM4Y-B>}3|T0MwxI$Qh7#pj3tMFk^NzhL?Wq@Xmg_tzZ^5M}(^aqOPU+w~RL2p!|cL0~HE^NU5Lz0OaTLuN+l zV>H@-dubJro_Sb~gUdx56L%hKs#{m&((Xo(;&%Bp6xncR;VHNdi`?JGOccF6pTkxCcz7km-#dFRTyv{k zvFCl8e;dJ`>*l1gAzt?6zYRe^yHgG1$M{AX3<7k?V5Djq{p5%kCe5e zD_52O=hPK9c-9sqb&jlP!;#`q({DdgK3=~MtT1f14m_Lw2N6GJru#LKSIXU&_@1 zr=|KMKlG`*boexIzBGztM9HY=4<N^sXsk5`|!-y+@i zmmq$nRDwNYq+C9N;Wc0UTuJns_AU7j)|@HK`36bn43D7G7+Vo2ja=u5;n|8=I3!rB z+I9m{;1BkDi8`$rXGBp}vt42pGB^4vv5A1RY4lE+s@YE+>3KnQdI`QrjF*++Fm=CY z%xP`?bYQmw{S!+xTF0O&ON|?x3690NB$42Z#*S4ZO|39&Xqv`R1x*kfdJ**>Yqk{q~dR9Q;WUoLyO=zbDfOl+G7eApzT90L+C~v zuJNGYviu$|3O1IpvWak3(469FG}p|Xy>0}&=WhptfpP2xpKK$3-m7Uctaa>-kl9d8 zk1u7k)%N(3qcAIY2RRxRv<$-0cAz2+7+HY|=uF8`Os8m$f;|&>)@F23*QOoKrHF1d zE2a}YOoj7I>d-o0tEbUeE5uI7c&$Clk20oN*AydT4zqCvb-0DC02P{nDkTQ1n^^(n zwnuAdT&nyn-58ftb8``>I2`a#jBD3`%mMn5PIDwYqm>_Mut~u=S|?(>{W~3>@YHRP zJCn^f+c|`&uq+R5Md>YR4B|{Bsdd0Aa8~z`a!p%1Dsjq)7aAR?ml#(O#U5)lG0Ai> z-3N6!6*?)^kk4V|1GQnTggVjOoR6UjJ(m4JG&K25UeS4S$eawe^|ElVt?0a)1~J}@ zk8^|=BOGiLJ*so)#&&S>9p9odoxP0rs1=puxD;yK6P1tSs9ja-0Uq4bmx71=rXeEH zv@N{Ah02U)`@IFn-q7~|QV?Usnb11S_Q4|j^%omJ?s+f*?HF}gu@v3ox8@nj^rVPp z&;Yv^RQN$qi(-w4=8g*(RNIz3*O^*mEZHq_pcQ^2IRqv-r(>GHu6wQ!CvIzrA(~R^ z-g(@Qz5`4BA-#s#D#F8+Rw9-^ZgwX)MGbMWXy%ineSbRH6w(J_VB+LfZ@^~p zW)a^KcPH#`WcLMsvPnI@IRwV;Z7aYT)81YYK*1u9WjjDlveSPIWl)J`zu!^iyy0=wa_MU<3VLIU`!h>6uB%Be?&d*-eSi9R2E~pX z?!q00Ex3TwNtFKgBY{)zju6MK%AQ4kr_RylouJ$N@`hv6sXOMT-g|T}xe()jl#J=q zmwwbj{{iY4{vOdP_Grs7N~!mZ_&SN}1}vX?$;-_CIP)H@L0Zk3s%Uz=@z`=p zO&`eWJk;2QN{fAOg}P1s3#Mt>%jatP9B)bgC4U%w|JVj&&XeyBP$iSYz=HWyNp@q& z_o&3V6`DvbjjYT|gi%n~Zy}()9b>58J?*H19Oaxa15y@tbqbL3j>!el?j6mEgs9a& z`2^b3#v0M4v~hoq-IG6&OrDi-+Hc@#_)}jqQD=CVl|sa`-uWa3Ic=jAHSn~mpM+8M zqC?SlkW)O|yq~BOu~TCKe*CHD)-6-dK8CGJFJed|jNlOPS!-?*5p~vbW-ltS&GLFw z`mHVoo`I8BG@~7QLoJac5;v2diJ5d9el?R<0hnF)|?aUL@fpR8;e77}#Mik>($ zsr0o_wCP$UH<<7+Qd$cknr3;xSEzHh;7K5b`}W>gj&R1%#cBei>^^h^$p5)#BStwf z7-~Xz-gx9u@^l^C5C+Xi6%1&mS0pY&c#WPLLWLwjRcTx3A@-wYWjxlvz>h+k?D6b1 zWQ=TDzXhKAq`DL`HWo0CBd5})mQYTc+hIMzbA(yB$jQGr3ghHk>h0UMedZj!31JEcM^SfRViB zEHPE@7X4KOqhF*~Fc~@f&#GbUVY6#!NDVSs9g1g%OUz^(icHd?BdOlLMnl5h^@PX} z{A>jB%r(zVMNSJx2HD9R9r@^e$l19I8{;pr!N_b6x(MT`cPd(_BMsl_66W!_x(-IR zKW`zZ+bYVh!KwI2@(NmxK5d_zx!1!FEP1}^7GmN23Od23ptlG!?mq0a7oMWJ?jX#V zKP}H*XnGfL-m5W{5hUx}D{QPgC*n#i!riNr?VA*oXv8#IE&5gvS`;tD88RO2oDZ7n z8WW&pt;?Qf^jRyMwVKMS7B*RqP@fk&U-;AH*xw$Uhj8ZZ1pAp<{$VZD(0sHK)b}5& zwD<11n~#oWzm%Y(Tf=h9z1O-w5X;$C8w>14_1V+Feki=aE}Q=&I*M>x&Q;8{C9`wg_C?Ve@V>&$8XK-uH#YauqY zA3Gc)qp6nJ35xFCbpMhFX86DT2tB@0xZ&tcE1xCC%zT5E<1^vMY69_vFAKtM^wG_& zGe0sM-#c(fQr}C)QPqeTo}ZQNf#*in{ZKMC^_;$d55Gq&`Mr|P!@;Uf34Kg{cx$h! zn2zXsyDdpnT&VXs+e_=4)>pN)cO>@c(ChNjY`LUEW7HfA@wJ6wa+( z^c%u+In~Q4-0*?$A)mt2#kISU)3I^DM3AJ(bH5**dL}ZZk44T$n*l4UQON&zHF7dl zdOze`pzP;T&XLYhbKd+=l9YZ_>Dg)7I_b1)N=lMu0D?5vJmk_=nEg5B=O(Xc>cclb3j>?yyKad9-a+eY zB1|1T<3)T4f=hfO+8oa3$AY=shM-KsQQBFfzNdUsR zO11{!qk4xd3@+!#32&mg|J_3$0O;e%ALIbdylHGZQ0<&LU}EpmfIMU2>UicGE;s!Km1xC>)!l+sAlGo?x+4N0KS`4n3iP;e5C zgN^g8XM0>y7o_;_q3gk9RF}O|4^Lgoeg(B|$%&Pq z^(s+P0d>jR&?LqQG~z6*1D`FH1FO;HoZmFq4$Vf7h4#TGTC*tWh`?zrj7`O5ab)D~ zpXP`18I14jeJ-)>1Z0WDzEeRT#ZImk_|F#0l-P*WYhHUcxQXxLjp193=LdJmXB81u(jsXHbr z1SPCWGt|H}In=_abCTJ4ihVboM?f{3yaPZv%Bf`jc^-R6YDpDU>@f<)F@^jJ=_jCU6#xr@0VNhG+^3w<|LCs$!c|7uSX z(2O*0pD{6`qEU4RmAB3~Bu3H(0qZ9$($b6~+>9rGF1`@wRqxB?myz@+|0VV?T{4Ej z$?p7hD=@v6`xS2RI!639kk?VrdlckZ+k?e~X?)tp3Se52QW6N`&VviUsP#p5I2j#A zF63er6dRAAPmbg>C5#_3Ucs2-*^od+Rq?cPYLoGqHjZq4aSYV%WILJB&jVWtn%ri+ zZP(o9RkTI&%TR*#%IOOFfXDOL6PxMf3bnTQ?$jfMYMb_kiay$-7U^m>PrX_(TFFjr zqIY@Ro7s~61$_vpNAfj{ZyNs&qjuJsj}We@E>0)Up5z;5~ZR_`t zmgPEAc~)|N3x~>c4IjNkd8eVE^;Evk%c&V0FA`Zu8v5$GqpL*S_pBEfNDVv;sHWJ5`cjqA3 z`tbTn3NF61|5M`K6z!M--qucDkrJ3`0yR0xXR>q{Fz1q~oMxe0^i?U^QCGQH&|~fp zCm6H%s`Me+(f8d(j|`8Qoj|0vXib><_r96{YSP!>n1!j|l2uu#l66V1FL?L8?&=AB z%?yhK#X?t)`=~U>CWF3I%?|yjG|H02)6`j;#%jHZqzP5(7BrgMr%RzmM^s_`Xmn`C z89hc6s!5ViPdYzsS|t(shQn?F`~}qwK9p2l!~7b?f12eI>dB~gRiKiWybDtLdhbX8 zczTNy4f1}K4T4d2NXQp3UTji?k|!fFqZ;yT7Y1BGA^zmoFj1ifpV=8G#O;uUk5b0b>e`qeb8of-XJQGGGjuydrULK2!*bt&>-Dd?{THq+%Gk(j71={xh;1QoP{t z0gUaMX*iS^Z!b(U(PkMr&R0k^qKj$$s524hH=R_Y;*Ll`@%R(Qb5OiJyc_z|Ik$}i z=3b2|0#j%Bx+6SG>WAv)t0NdX|H_CD?YcaEODCd@wFlNhbF*I#gCcgI$5N0vW8PzU z-h44)KN6L%*pTe4h6829uxal;3uZAmp-Q5heLERkK9*g`ks~L=roh5l93u44u`R)C zHG%I_PF~S!=MOg8<>55v7CNe4plt$m2c7t!&h|v)Pebp&qq1+253>i%z020Yu~~cy zG87~)T}3ckb`0T+y_Z~mlKM&BChW2F-n0TR0u%a4xWgnrfAi&;TbrMiyn3A?-L-TRVS9h$O#RKCnNWKy)Pg= zRs|%IQS0VeZ71{T$&V-BM@2l}zJZhCVb3>t#rx(%~z#c}LQYL!n8%G#kc}msfaHi0k6>+V0ue z4|Q5T@z?<4pZEHrki2&O|G;RPyrLa68g>NJ(4`U0$spv6CJuu$mb>AgVD-*CjJv_I z>?MfyE6o&7-G`zbL+RrVni*Hli|9?F{$p1w=`W|Di~shr|GVM;!Y1)FW^u3Y&0^BOiB2sNSJJUATScCYjG8&fxn9$8noS?|l|0)PLLbU_W4?2SAeoNj zEhJA>@w1I9DO~6lc!p11*5?-_ai<=ASjqdu!4$6i)jtu&sD=HjsH3ut`*T&asMV#y zWa@pS%BO=*FRADo$8|&}V@_qbgqm+S!*@cTT}hS(0$Sjg_XZ@l4EL?4N``gs_W{$f zN0s2tmMTs~xK%mYOySnKqL@$uTFvQMP2qiS%^g6_*GuX!VOiMQKY+W^hZjLTm%ncx zJnxMBluh9(;s3OPyA#|@FLYE^n*#0}n+rpzBeC}~*zyWqfX|*!N_9w?R}qwhhWM{u zN(kor<4-Y7?a3Wo@ElA0cC8)zgBR&Ua!18sNNK^|4Hwi?&zzjTMZZCGg7hLxqdCYg z8`EHTd9H#IWs&K?o|Be;j>3msyv`upS1m9>@t-m~Frw~M_XFU#X-v~f94n$z#sPj? zkNyxav4RxUGCn6htkTIV+Tod#KkY!C`7RqYn7Ygq)eI$dNaD^BNh1D?RTxMUR z4}Bd#=T)f#c4J~=ay@n5`-ooy|X~v;^L?MExS0jMDhZZ_v^1uI{rG?mNOtMR+}HcsU43aCi(zQmaoqsN?O; z&!p30q%v*tt2*B)4u8kTU#~b%z3XO=NFk7Jp8I~3_h&sv?>}dB!&4EZ97lLmqw)fU zHzmjVfzO=g>y2cb{6F6}#8SZ{H-I+{@vNUiAc4Y1Af)q>$0_jX`Cl6ji}uip4+*>> zf%k8CO5_z~VYiHSDNPu3-2iL)NJpiOP=+F0`w_`ZY ze)MyeHbYCcC|w&0wQ&pWMlbU`K-%p18fQSy?8UW^jnN#3gVxaPisF(u?29Q8heGpl zJ}S2eKE)~Ze*al?So%v(Dh9dSV;78jmJguB#*_hctv;|K4Pf{sItW|pq(4otM@6#^ zAzJxF4$?%^Js1dQ|FptLp1PbRLU^(-t>}c2_g_7Z-Tu_NrI5i5{WJUB>D=Z5Kw6^o zgpqM!D-SB#dnM2=V*OA%Hr>JG_Fq)$o)!aTo2L~)T8yu@7UH0|cP0KZGvi+h91$QQw^L9d? zti49fi`f5siSXRU_mnh_{KGN+0PkyiimlcjiZ}+Nw0IQSn)tEza~vs0mk6MPIlE4mu}uPM2N)?e;$*A@r)GyGpdw*%Fun>ejz!RT6bY zy)$N`&&_+=xx`3%u28O|H(uT3^OV$*DmJ_heX5IlaxtVB=c{03jK2fpuzi1QJ;qV@ z`^!+!^odWVigGU9EnkK35dIhnu_XP#$vzvgk8+xx|2`T-;fkoAOF`(i#zUWik$D*> zP+c^6MXDh|A)Cm{H3!hm!nfiPot?2k4Cv8+_=30s+qY1+YNnBevDcO7H~>+0 z^nGx2Z1RdGWE0JpiCMBs%$U%~$}jGrP)5@cySNk5)L^roX~5X}qSX=-jl))R8ff1* z-UvEc2jhYP(|L6sii`VShLDlb7{vkY-NDluq2tokHXgC5Im(Iv_C&VKp9+}|I7EYY z&Mddj!P4W+o6%94A+H1-%^eT$f#&KQh5^2S?T`wf?>!QFQ>9_+oB~t|>AeL^zsuU} zyA}PcuYwjXw#5gcDR7NZ5lbfLdJ&?lkFc>?b(tc&jGZ1^QT)LR??CFkDdJrP2>DIw z2|`2{KK_OpvVJjnMSGo|mKaE_YuHB$(R$rQkCWu7VE=az0y^*xY_1AUtuq6 z2byrqI@}I(2F}bJGgMJ1GBT9usZq2YrMPNb5B=s56F?wV|U%MnA@( zh;Hgf`E3GY7s}tfkq&w1E;!T#wIJMMp$m6=)}HtVTkfI?e?##>US} z#LcnCZR2my_WksC*Fy<&d~Tvp|A!V=G*lmXbPXoN+HlrBq2!x-h}%-_1kd5< z)^=cL$KAXPaUQ7t6C4NrlaGf5%lGB$VBAskA?|K6-B+P7dd_+cZ9X6D$4N2btl9u$ zGXJ1m9q&CdqR#PRe-vkWj@f5XEjR|F~C(o04I{nthjR)E;eucOv;Z+SEM!{PB!sC1^ePg}ENFncf!KP4v&zp2Y? zXM$vrHb70S802~891aDKbtbByDRZ?}+CSJdO+j!FwzFQIvpV?2!AGmoazi!S57!g_|Oq4%cp^#B|l|CjIg#IzwY!}%2^-LJ+U#Zdn zG{2DJO+eEW)ALdOAwS-JT&&4&M)ySZC$LE4yaN|-3i$Ohfru$jDZ`MQnLH5<$($+>V!N`!MCh`w zPo$tO`*z-c#U<+M-enz5V=bc$P$68ho`c;dqC2%RcqW&<&V|d+tno9j8tHs8bv> zn@jrOIyfJLu|2KRzS?oZXuy;k27$fs+ZnjSX{tPMlVI)atfXJMmiDX?(|=FaJ-sTT z`~ALKJ5}^y_TiqxHEMdWxITGB&k&jlu8D$q$yGUs-WgcsO}_`MDX?y~&~4{s;`a1r z`oGi3XdmR<(N{4)W9t6`lkfB02G0UxyoikEglHa&*XkmTR7euJfkVHito53;TSZ?B zv$4^Vjq01GzYXjmuDg_ky>7!{H_O!Hlfm=tZASVzZVk(_4W31un}NKk|2v81tv;iq zoR7_$l8|$ecmUNIg8XHq@YkYEl2_=?VjNz}Vz;Dh)I zDla=5WPizh8=^7aco6eT+kq4>2Ot7u5s( zZ%*GPB0R3Gm_y;>-dQscZWMnn2d1p3IpFElOO1UVyW71fr$rqd0-UnRD|$>cH;RI& z&2DXFJ$m2XzL*?M`-c2bX3kjON-85?m$w9C*Xw)v1Za5j3T5Wz=>T0m9H1uXD&bis zJYOXTG@#C3)J7Q7_UqLs^eFMzIx5t2V#h?xZfQY2sWGgQ0L>2TrPi{4*;dZs7w1jGDI6 z_c6H8kVgm~6vU@O3(Uw87?t@}R4<4eS%>9v^<(2ys~=X#$kjwP~H%a~|LYx^{$Ce$HZ|LN4zhS2$SEZws>odoam>2(O$6c3aIaSE;(o`RYrJR9z!lJR8+{8-yQIb=_Q-hdb~^MCQuXR7iCq zbKqy{y|pXqG=+~FKADL&O*5}hb(h*Yi@kaUe+<<{ErRvHxhg;Y8PR!0dKz`aJ_aW0 zXeHuts$&+_NYG_zRK-0~d*rOQtUKsA>wLO@3Ubz!766j*y60>_V)wZ;5l(e@9tXyn z96y9Vtmv~-m*qP6cRG#vnzHj?X;WuwZ0?$E*Xb}v%QdWqPO~cGEQ)l zQ_0h?SrdzK_)cDtKuSZo8KkcK?~P^{b4TLMM0^2rkq(3mUuSrr_rfsSARY@`yhJ;x zcV?O}1BGPAIzY1cO6@w}vj*|Pk&~hB#NcdyGl5RclRk(>P!$ycN0*Ix=u&;r30q`+ z>tpFN8v8ik%>p4-Z#KenqU2;Y1XA%!7jjBn7KI__!lLU{7hXWrZu2@vt&84@eS?Mq#%&L%PP#fiit6+ks|tbAcp`0_cJNJI8m1;u%q<0= zWiPui^o9hHT?tyH{YZP-dL4~RRgwXu>|Z&7#*HnLzcfJSlw%A)LiOAq2ve@8svYP>#*Gm7 zggops7#~dtF5sxC@OTME#s%GnA!I+s8?bD&R_p*KVQMp2793s_hjU@%ZxBsBXE}Oj z2AqJl6}}6jDVVi=+h+SLt>;fu8HMP1tbH}q-4K%SC^HOvFvW+@6H1M0E=~%Aq@Ir^ zrQM17pwsoWIE?_MpIE^_c#*iW2+$c#Y{)Bejr1;Q+a#a7qC+Kxqi7>YlRpqqfbixU z@eG7-s~4k7`Tnv(G8*>YO#Fc)E1csJiGA_RG1|8^C8Pr*dYxgh-w54&UP4Q{PV=Ww zok)=a)lGIL-xS#}|N+(Ym4*;%@kF z`cN31q-nUrn9H?17;^;=a4*uZuh>PqZ)g!b(;hCuG#Q^c$Uxm@$1=#1Evs7#Da^}% zA1R}soFh7|RoP%ua3jf+zVu*t@`^s2ovy1d&YyZLU^#W&FyKSJ|F>CB?^~OACpe#; zNft)_5SlXe@`-f+#XJ}_7YDQJrXGE`hYi=P^kxUagBBkuQ}yo3J@6DYRwt2X4=3cT zp6c`-E!#@P`&dq$-h@bgtn^Fi)MFCE<;D95|DWoMK~&w>E$GiEl;rv3DtYRBBG0?f z=Kve-g#Buzx7f4|L`Aqx9V(+I^eHa%5zboyg=>82pJYKv1I}dZYV2*3(tnkH>aFpo zN)qLg#i+DInj|D+k#3DMFrBG2N03q0s^1G^z?%v*U+1%;3pvx1M&LQz#{UC3+anJi zB=lCF?}ym)kVhUPQAbr7@H|n^r1ZF}ZC4 zy)yKf$4}#uXPU~<3qUu&y5&SU)1DoH7_{#G2{a__O#cLmHmqK4;8XPAkyUC$8xAfs zkV1T3y#>__-KZ5nO6-+7`-op0DyJ@+%065IBY%b!bw*~h=ON{>q1)jY@v(KgV3b>| zDngX+6P#-g|1l|(3K@LQE4@fI#TIoHTF8R89{7xn?{X$BjI)=8K?_>jb!b6XHMat7=I;^nsCSF+rp++k zFFFv9v7hK@MBFCbPlv<}N)4$A#~f zR;qNYLlHn7DGmfKr|2Ge_6cgpWUZ_8raH!+%rDU8MY9RT`w!$!e#z_q{$io2Ok4?l zu>;bZ;khVX2R^=@aIqf@zOz{1<(x zS_zsQ+UZtGO{%`x+KpLiDi8LeP~(s~jJh0UIJ^rwqz(g+0=x4D)GhjK>t0Nqb1?R@ z9cSwXY^HVYy;khofaoAta@if;jf0{8L&tpp`s{^aEdkAUUf+r3YN+;I44}=u{Z6D1 ziPen@4u*c&;o~sQZD!&0%bdJIne2so0p0zf4MuL@2?sREy~_kg z<3T4lATIbLHkZOjW~>uoi{{)7P>_}k^I~41b4k&-KWV`l6<o4JM#9;YEq0rbBvk>RP;kFFiqWb$o{)#7=Fg(xd z2Oy=&!ox&97-+RS&30R7n==V9!PN~$2EqB%VY z#s*o^VR%Mo?17P8tBa$l3lp8)G0c}L1|XeL3t&^f_zBDnTTj{VCeacc-K?O=D|)n0 z{NhX>!Yuu}7k=zbRT4qJqhvHca-oj`4zhy+@Y_nsF~L0)S~t9CO*{RkhrRDKi{62f zGtns_Pmb=eNk`9@V%|0m{RUOP|B!%wm`e1v?j=h5`b#co=n3H3y|2P4ysY`db<(M4 z1;cj95W=NT54xfH`IwsJRQ+ye^>TPRW!8C7q1;Am8*-MsJkBL!yZO5+7}p-+>+mwo zM4}KsQ@6Nj%!Sx^E=syao~F8HC$iNC*vov7YxJRvf*XcX0ID{Nk_b?~OK=mD=otH@ zp-waPKvm$kt`A0mjxoE3p8Fys?OgmS)petQ5V^$1Ghr-#a_|a;>*hVK!!S70e6GUt zA4QF!ggxpTw8MXmIdacBtfDHaC|0X84bm3ibsVvk8J1x5J=ZpY9tRkQPl2JASD7Fq zY@H6%m5S;Fl(UbQVuoW8dsIj>lPEYIU}H(Nh(+(vX`8$vGKv;#1Z_;|MjvWBy=+!E z0PVS7gtoO6e@aJm#gO+Z8m_8fUnGxMA0GDcr#i>>YD84Kvwub)cv`X?Uu5cB@Q)D@ih;Yv> zb(pSZr;~-MGcF|?VeE_?UPYeimFx5DyTZtaFl}CJ6WFw+B#Eh`?mNv&6#9MK;UMKy z9B?0G(<~eIi`qclD~UA(v%EZ1jj{O^B!`nxS7c1$HcSs_XT)@p|+M33@S zdyZg()DJ$hZ_s_;L{DO5^W+r`PQE(pE~?+{sPu-26FjlLnsZK=ur@C9Bpew{Kl8~^ z_(^CF8BKy*Cq#3T9klSg%3#A&>!5l8Pk6+E$Dvi@Su0SLiypBUk7j&;3n^7ll`7@G#g+o96Bg)ohFTX(a?wwS6hd+sbCWPvuz~T1U`(;}zWs2xQ1>FWM|{EVVC; zqs=}`kKJrG9Y~$k}?3z389z0jug!W@w(mxZPKbjX{MkQ&` zp*1%HCfCkE*nTW-#Mn6VPaeWBBA@NBE8$kayD+Mc)xop-;5+uUp7rOeV1wT}5{ex< zJnI@7AJwukAn|mO%zndIoQ~qzB~93?G`%OzGmfC1jY+Qd`XK>|3vN4%Iv-EIsg~-f zMW>YTG&BftD5Nvo5>Z@TRJb1D(-VG!5Nb7w0~p1ArZ-2Ie!|cU@0L zMzDt`JojweWM6{#T|a_N+tcztk+=*w`-UJcNAq{bDO|yRT@U8WlA$AH6s>O$1^B?y zyZ+QsC%a-UjDDq6P~5}|UyM9IZ;Sm-z-rN=IQziiwbZ57Vd?vbzVI1t^98@019Ed* zqZ9pjPm!$AiGF)${IhR6)28l}q6>4MC}_{O$&!;=ryemPo!4Z*$mE>PCgTh7&tA?` z|AFVSX0+((rS{*7(~>0gFP0A;H~WN4y>U$Wborh}dTg=wn~_s)a6PN1mmXh@WY27* z|IqM5Zm|iH`SbR*RA}Uc!|ZW!L?^)d0V^A^>~{1gHE65li)Y42U>xDIM_a&?X)w zNT$k5>Bw2&SH%M%Hy6Diqp5ALX9N`zIsAFTg@{k^`wLZ63+fR%>^L2dZe<3 z#-Zb#j{zp*EuTB6^z+`4FiOhc7R&)A4fhuT8JoT>m`^#!SIycAmX>UO<4o0a?oMEE zmU`(ZqPOU|K_G;^C(1z6yf#=94C9e91;YE;l4kU7Rdd6rkXg^~0r=-pDl>t%_VDE} zb|>r0Vf<8C3PLsItflCvCTG~6Dp`-qcM>as_W64D7+xws=_qab*j8bU}eMJ ztDw5LV|Bn;`BiTw8CA^UIyUwGrsBF1;eIiZd_s~dKhy>I2gvFL_#AT`w2GkHaO5TK3|6Lac-P$jw)Cx7=D zNUDF;})m`!nl;p z1s}FVqc4m@Y60$q+EdI905z7?FG2Gk_1{FFJ;&w;qI}cCf($CpTCsbGN9Apn^7%-r zYgwtr9;}KrfV{%Efg_}D#nOWFFtTr~y+THv&*NJtUs#@80i#oH5N5;ul-1-4Y>oKnb;Pp0PGL>g}6s}97@`dsrSS-3dt$rky z(8uBWI}_8WBa6eHiwHm8;Dc~g!Mzt?X;?JpF9>hxy|Iq?>{+?(kr!do=;sCj)7tT3 za3{=4sP`g5vtviw@T&{a3u95fNOO8WsFyGK0V7^HdNB(uKYVK+!jEo!6GDt=9y<;vxDnon&T`IKnxyy3kMG!Is)+G%u*FLRiol(ao!&0IonSgv|0 zA*1ak^D!zlr3`Ki~LNMbTVgXapQbpBfUe9?SFUATedAn*}WGzsG?XeGToSl+)yAtps(l z+1{8t#~Wp8rL}6xDCERdAmb|mvyCz;IQP0S%xf1H+jwBBs7BWL=(z##4&Dn*fJJM}9u z#uW)MSfTz+2Nr?K58o}t*{78)sY1B(XnrOwhA_LL7YyYjiLoss9IxpVuDb3#9feAI zyV18XVERHBpF73j_-RP>-2)@nc^F)ZS2~nK*Imvp&Jsh?7S1VfIXAEqTlp+sw-%iz zHjUui&gHqCf-rX%H8fDT@BV4_(%44yw_yf{s}R=^LFVAo=Lbk%4{^w1a7l}=vK(Hky2gPp$7 z*o5tu86s9;ExgyCLqnJK&srg)gt|kBcAi##9LnYu)d72Z9}itR7C4RD*#EoP=violf}=2YE~D%!p)$#f)|M{ zgHHM)r{907n+ZJU^f57v%#`2kN9@gOposCR9@6eU{gZtOcKuHwjHCalu^)yeKTnhq zEe-^rcHU1XFiKVZRzQDV-G7vf1$yOWcnWSDUkAlX?>xtm5aZmLLC0Q0b~g@4(>7)Z zwo)ugy8`0g9he2lRYh)1AtChbeEbS9$82ZTLmfrO`~b69;Eu*U{~Qh4vY+1tpu+t% zI9-KqsdM4DyDk$9RZU*e-Hxrx%Wjx@r08MpS*NAjYRBsr4En!^;!P=RzquM&^w)OD z3A!a@V6g1JTZtSM(Z9*OkDpW%QnrkGI})p*ICKd^^2@ zj5_v0HIs5Olh0Sd^Yqv)Hr_RQ``B8bG)8?nOqVO}!kW37_*TAniDo;zFLvuL{=)=*6Ja=K;vso*$72B`FEb~D}woKUx>d0EoxCi5yr@V`dO~*Emg3sDZ z+Hc4>8vE-6SYit-1;nRI1TQ#{`n0;fJH#gRV$Fer=<}R@B#bZ(%YE;lPer3OmoUkl zLk3W3*q^zMCfBz!eb9?0m(Sb24>QiL`!y7m>e-nvz80myQ(pVgVhUFsn7ks@_%gd! zP@$2P4sXz>SjJodi8v{3d@9s)w{r<3lAbpg;iLSK`500w`vVxmD!6Hs^RAkoM)NT2 zmbd%RJdB>qKg08RW8W(B)Uwy)qRq4(_eE5l^}+KZPpZzU?k+j<-3dLX7B}ypVrU`7sh~pOa0sG~RD|3-^rVEx!bkvXs+qz&O zpHkK-oE1n}Rc7OnQRy%efB}mReSitcMklbuT6X+q)EU?4vyiivS&fy+Pz$aA``wth z5Q3?;&dfj|jbg?{$lD>-eq7i%r`yOVI_J9)B#B1^sWdmC+l*ppw(@kd8pHGoP{CMK zY5~Rn&T9r8uLs#6uBbe|4o3Iq&S>4ZA-e&_`dl$QH9v}u!)P6lVTl|1UHSIn8izb8 zKH@ih7%+Rk(yalaM_%{g*}PZ^K89kXSXbZgZ zk1EgikWy#p2_T~^$Tb|ELl4W>Q}Ldvk0yYKBbphva1(Sub`-mlwaj#b}92e$Vc(g7;=DSQt!Jvt^?_gLq8?8@#rN}{>4ofzA zk-XHsE3@ovN(DH4yB(&zM4LI0-ySBM3d#02s6H%aKf{C@b>?uan@dm}^s%i4QRjX6X8W$je2>nDJQWFONG;rf(`SS`JDH5Ez_aZzT68Y!K=CP;b<~f_ zW61<=CO1ZIWW$){&%^>NXA5O8E-B9 zf)3vG#3pKpF|S_iOgBB*x8g)}qzWAE{haPP4`FPpXLq$t^?yvNf64Ot2{z#5Jss=5kl&@>hlApm(G4?cK>N%rV zq|8I{%i=45F0qWo5_A{G_Vym?$INt@jV9AX5wodrM)1py7x;#bGt(}iA@^A6?RoT+ z($^BrLt zFJrs_CY$fUWrRuBdUxViN@@;W6G_ym!tPcAsAT!K2Z)i8BZu6Ob8*g-0m{ia{MH@h zlsFzg+kMi?5>3+LR{r$+%Im9y2PcpLmKHF8ZI z0qSiIp7Ri&pP~VGvcEBZL!U$WdKc=mNgCg2Bkp9z6Rj9XQESC58i*)@L)&P_p z(xNe%rC`HwKMlirJckLG)kaYnVESe1VU);JY--3Qd9L7*QFo}c8pc=2yzA6vVLa{#E=5JvxXnm(HLj>r@8y4(x|FYq ze2M6~^4dh4w7Kfz_PgQX-Iu{}b=@XVr#jK=3@J#H+BoQl@lHLA?axN4K=R)4BaoL~ zexaU>Ea%I$AcWn~qK9X;;D0c;FJ!-C3)tEJUjSOab}t-8bv*wdG&4Ir8XcXln}Oot z$7kSB$!V>mBdJ}!YRS}Xyzi^~UNp1X;tQeb8b+Uq zSCw>bk4w^mU(n-%uQsWIjDqL7A$VSAUF@UVhRusrQ9AYfqWD6h?j@uC#B_>gIesso z+6?aHm%zApL+FK4dZ@WKaM3?+>PbiTo!{G|^!W2!-gkgfTKSpVjJT7mFm6NfB7J`# zCAC&a-tD9N;Kho9Eb3epYZ)-&aiO9x9>#AZV<Wq8@oSP4hgcJDD ztHDO9Gpd`sB0|E)Vt~CM?$Ca~6esQAQ1P;rO)#3SF$x5Py*i&z7%s^40*p}X3XQUQijDYXqujad1T)&3&wJU zuQj8i-yiBSQ7E^*5!CUo&kO+}|I_UVNM12zz#jj*(G!Xv_fN$%-@dPcJO>)X6=YN; zG^B7}GAJ>Q4tfR}Cs z^tqC~6volwVQfOr%o&dX)X1qU!vT0Ljfpdr6R;u)>mdqk;S*1epOi9zzSEeHMnL=Y zzWH`F7`fm+{lrJj@Em`bum*iLxc397^yjiJpm))|=F;Sgd4 zwT?KRDW0!i2asBvdS=ktK6a+3&&S7l_xW!>>sjmfzUy6U{q~P!XOnqu(>fTFCdcwI znY%()z!+RIhXx54x($gYf8a3%I$(y)Z`;{S z!6(fD14G z$idGCBc9y zDt~7u>bjz?{d;Z)&pj2AWBOx<+c+N7{zUkjmW6{$vjFY3w@lO zOBp$3?`YvV+iXSYjaRw%(0K}pTOf(YZ>^Y;p~@k}{q4lbQqPG){O!p4Za~!u8X$h% zlzcOh>fwiX!zdZE170{{N8?TNW3;GpQmP6-nqD(flAT((BIW*;I=>V}4)Q1kPod4- z1nJ7})fJFyOI)DgIEq{&DhAJt;m4S;X?DinKuNx92@6d!ax+Upd1`u-{^FY3=MhGdPN{c5o_a$VvjzNOe{W z24}?WZA??~fJZ5nNygo0``=x|<1RF{AIw|^O}eU`*tL{P8%vOro7)-`uUKbm#G-p8 zjc6!YQ1v93T1QsCf<+$;tzD0JPSFtJv$J?75&xdvv=ehP#r+({($13`!1VO~hnSHm zcK$5l`&@j}km+Rk*i{s2&CObfBKxD<53afLZWMYnRoRAy9^&TrGLyF<)d;G!+;!+F z{y~#ePWq`jlqR?eBhO!itGTyh3$lvuEkLE`*YkFRl`yWQhgfO)2Nfu)otJlqxfhh@ zTtTkAovb|SDeG=tJn3%^H^igTAF;NhQ6@P(DD+d82~f&B!VdtYA-!Eqlvlz^T(8|#2;rZj2- zuBSV)(Nl>pB$h*dnP22uKn)wCFel2mViq$JsWIEB(vE9s`yBIJuy94EfaJb3FdB<` zfDO95l`BD(t3;U~^fY8N5+eVXVhKcQcKrY>Yh1QsFJgti5ptG}0M(C@Q|ZHodFz8| zdNRS1Gq0zII&Noac=WOp*7D80Q}h+lRBUr;Dt&nJQ_q~4-t)qW-;`^o_w%^q$8zw} zo>ky2bshJ>(>w|P4y?^jd;t=s zw0Ac?Mtr&8mC-2@|LcM{cO>;YuNdh3dB_HY*Vw%Fz*sdjEr2KMGbMD^-sistrn!^0 z5K3RxwEyBX6;ICz`y4_?+8*SgW?H@u=qpxTcs&M_Mb)sosa z1oizaBOCzv7PasQs4D7@ebA)W79I&r3Ws*Fp-ITN(m*YdximN$u9oQFEEKxs(Jn4r zU&$x{e%E!k*CF4{!pp$#D7XxwW!pT?L#ThfUJyd0S_WsNK(a}fh!HLyjFh7I9p8%` zq+V5_r~~TN%M>Wd!dDtkVa#YXGU>b6R9wo`b>Ss7aMh{(`r+DXVFf^x{dXRFL49rd zXK)SbFuI`mhl_*^e_oQ#K{XK?1f38?w=1v+`rUY>=0OzK;ckp+SL>?HaGh!kav>;H zak&fC^yHIK^#0Quffz_l;=ydFS7TepM)7&S$e>>CRG=qtmJFH^ZjF912%d)q3V|c_ z3*`X(ws6{qz$XG-e}%F4J9Z4_DQ1HnI!_#p^Mg*i^#&GndfDoRc#%&Uv&9w6HegEB z-!5FyChXCI9uBI|e2wZ!9 zHuA|;?Y>iwc`}^zs)g&N6+S+2y%g2%O|G&N*>~V7Dk!ame8uDZ<#0_>s@UW@!}HC? z=tfY)6Kfi5I+|gtcHF+MP+fxwdG(+o0%p` z@{-$j^!XiCeG>F9+*<&tWG}>a0BT-g7K3U=)Je>VGvTrTMp>T@Ovg7XVe^~pMweP& zYGnG+yQ06I(C3c`-az%AX@q>tvz1%!N-bqx_>nZ?=hww6u&7gK7ok#d@u{eks3XD* zO?&3gG5F=@W1y+y@>3IYH`*d|z_q4{i;Y{>ph?D*rv*%aR85o!yW#W;;zStd*R5qC z(Fabg3z)t-t8Jj9ESX0tAZgOqCv!p*n})p~NZC<; zTL~oj>{aGwQaw?LF{=&yG60%<@I?Y@m%HN)Y#frlx;TX2;0+lGo)x_M36d8MMn<4_ z28KfbufO#{BG_vqdn3@hJoUerMSt6ohefX`PJ-yywjNNba0~Flnm#u&kZ0h}(@gT0 zB;EA){gu>4Z~9qnNW_)f^npk1&$rEF>@lTofN}S1s>);W(GclqX!#s{;xIfcZ6Hra zT;l{h_olVNs7~3MppIGm6K!(zhGvdFoS2=LrqnDRmNfBeM&Qcw*rV+tN}W{=?DWNL zqebBEPDuPcK|x*g*Ljdgu^izkzdlhDC)EbOHxPa)yUYXOiIuzSH!OY!Bw4#Ww1)1& zj}EWkzfBMN-c9}JHhqQ@G^ligF+boXAnDy#Uq(*eljD$N=1SfmkcO_x`Gmx84hrQ^ zyfk#zImA1^JH`h6EAz)(!WTb7(sa3Gt4I@TV4VV*)OKluC@J%+exCKv^quC_WaRAd ze-oaSH)LFRCU0jO$g`aNQW!|}+UwkqX;kI+E<|d&>_rd6pS|De3i+gG6YCIf(r-q* z#8HSvjlz$rk$y+#ad7H!S?-Ze4;6)$dIRXvfUlU0>V!AcD9QBtQeQI4`i7(7c{5SY zC8N=&fz31&yD$Uj6_L#zaCOZQc@lfkalbayY0_`Y8;~@u=Y}^V4Nlb?sLoStj|8~N zYh2^t`f-AeL#`ZEd!mtCg{q{r%&KDkF1W__DAAF|*mzbZ6>7*Pa{;S|1DWASz%8IJ zi@Gl{Iy4DNExBi9YSM8hH;dx+1uwh|`G>A~c%r60&m?el9KB>heBu=`^sDmp?SOHI zXSaz8WpsOc8<)5TYet5l^EfRU2f(Xi1@KgF7mf6coZV-w<~h zIBg5;MxV3zW9^`?8!fJetNMv&7+hDaF`y@8-&llT+H{!f3Z(<@9XFHGnekT#p|nYq z;6?bXRnvDs%4KrS?);BWa=?U-<}{WZ!RC0!=dZ%^_ar8WD#0 zJJxzPK-nd0fInIP3`zBjvsRIMqkFecp?PI-zsw`kim65)gdd2S$96omiM1RZUE!&A zA$XZW#m%ISp60z0%iJNvd7da~idhJum40eJEV`sNQb6h3d9Rv4U%O5fLW`>rnd5f&C_`$L$?9F)?cSP5&LFen58~6D|$SI|ySr zznPIPl`R!Qy3ku}%x$6f?-ihVQs2xXbj{AUEOmr5bje2qo?X$+#YnR!WrI}&8J^h`4DE0XKauy?E_t^a{vd=Hr%52cF zIb)!-Z{Z5x+PKX?ktz2X+=m&D3b^>LuNwPT2_%D~-;R+Qo6*ioV2Yv2G-?GScbmb={b>u2j zxXY20cC3yK*LhE0K51h7SUJ!|zqYlGt@#z2oSnQL!J{)>ec(S}9DeKwhjAoV5B^;j z*fChtcFf{N_?$PyRlsK*E1y#n)$FAW2@qB2<%UcrCd*tPipH-HN>8=O-beoW*9`e^ zbxE*#lB;Gr>v28l$Bh;~4}9Kqz7kSBe~XPmi+JV?@Neq2dJunpdS)&9?3vrN7Z&|6 z`x%t#XyZm;(MO{C=OC)w{Xbyr6E^XYX@soGfTFDYqz9SKU)#DFuBQKJMN6JtxFVtT zW>GXaMFy3z03W|5(L_1vY%vW;|LL~^G+N7<6*Y)gTtCaeb6-n<=Sa7%n|j}NPS;I9 zQ>|l+wnUCeg0iB|$mHGV_TWPVS;5_rzubTC`o%FT8Dg?V` zPiJxfz&AH_V=I=(8X%}SduE`H8e(W|MgTJp_3nAdNN`(+t&9`V@en|*1s4D`y*|Z^ zVeTKlpafEmP0Xc&R=F0lFyfMiBYUyvncE_4WgM}#$$*Ar$0h>5!Y0O$^}FOTn=b#} zJ+!VOe)YfMDN!}QhDD!hs~Ab%H1#%MgF0-z3)imM5jo1dbwfV1Z}X3PfHF;%jfR1L z{Pb?zh}DAON~U*R4&xNi62EuhbySNVSr|rYFwTX#D=0n7_rT8(N;mNZW|X!1#W4U` z`gdbSTO8>@$XCiNsNJ&2~bbi#rA@6GAIN*XSpm?wD)=_oBF}5H0-C3 zJDT}7L+Qb`+A9gK(w9hk7Ov>9G2A&la%OQOGMozDFif9T^w%v(Bu~xrPc8fDJSE(? z;`FM;6O1wK%e~*wv8FTepEB|^b06%O^`c+BEXgkafxhJ&GHNT~YLQq>h*ui5wX|s0 zh2UDEIs6-UINs1HmIFOS@a?y>rZMTsqj_3W;r!?tWi*EjT%ms9tqfSs^r@G<$# z+t#IE$%@BzKhRXJ>6{@~*4tGt0bCih@FE5JB>BQK>lY-5)GwkMx!d@G+lT4Ht3y+= z7IJNAtqw%|+1NJ?Fv@<>POYcUgv=415Oj)N8V{xirbdA;OACGmnf%%e&!Zr>l-J*e zObu!OKzv2^6slz3#%8MI=Me9~qN`4%{y<-c+TYC&2dRqo_uR1PK(`IGlX3it8Q1^v z{~SpjEP4C|Ny=HV*>a!wYwLJbz?U={^8poBU>zq{%^SBK!?o*L+99}d9d$Z#Z7Kgn zjMf|FJbr@e=>wMgfYp$E+D=kW?+`CRd}jkM0`dHUX%yQ0Tw(urU?t}K2dX+NI?AW2 zjxGyGVDPtW-3+QvZ#3UPR&=YDP{T7oHRNEiU zfxq+IIgrw52Zms*5Vi2(xy1mWpk=q8peC7~%OSM%_&jjT88f;WqBM8Bz6ss;52czZ z^pdp}3`zg!Co_mo{>1+~3`A^0KhU|O!T?BeQxYR0NjO_(GS&!Bk&A>v{}SdqzA_J=LjHDX8kCtfi22K-R_Jiw!O) z>2KI9c+R!0PbMVI@r5hejSL0N7#z=P#F|?o+s9$u|X%RC_Iy2l#xuR|XL^9~?43 zeO9o~T`an{whQpAi*75BQnklR2%m|1P*3b-10x6L@l0M_#U!?8t5vWX+23nbA4Z}l z3i}@8`3CP!JvOvf7vBV|x^~|DF1fNCfrntsEYG=4^Q6k}s6mr=G`OdsB7V0e*U{t= zH-!+|(j3f!tM*z*EL>BHBS+!Nt!0C1g2N&K)$tPPP24u_`8yCFUpk16(v9XZ9c4Rb zf_$8m4lCp<@31Q18YV5oZKG%T-Cpd69fs32Na|VpO)wQ^CDo&(v%d_YdWs*uV7iP~ zlZ-C&3_nbcEs~<|osdNHN;rCFs>$sHipQ<8wZrvM`a>8?Ywp0aD_8s(j83iNB+!Fr z#aJ{^onS!n^L3?ufbYBAf+5$W9BcynsiVt9a80&Yut(^V5P9_RGo3`iRP#;IA_d34u; zk0D;EetQ{;A9(j3bBhv2nIUw+xn3dg)6y=%cp+>X!aEw)r4c+Qptb{d7{l7wU64=pG_;2vwTh!J?J)X^hX5N;KH?~Wg3gu6dNc!g5uL7pvle!0gcPTH||*MrleHfIJny(&KCfhWQn zD)U_lzIV^*Sh(i9#(Cm5HX;4(b@;)Q#u7F~PY1osZF58VipV11I~U#<5Bghfap3v5 z;))A-YEGx#sU!8$N88*X>6;HM9>jFc8TQylzpdh0!+%HdEo%nvGeSvg{oTlQ$ab|H zuFeNz?!;7<;*$a+do*+p@IAgsb)$-k1gjpP%!;Y8FlZ{jF~Oll=id+8f%HvNj^(73 zSzhvtLrNLhX`3N`sD;x1ep$B@SuCoP$@D@dTz`?-mr(Y`81W+m)v3$f^Ab2^OYHtY z8vbR<9UXNd;%k(Y`*QLHxM~lN`9TxAb)1FX4@lY$SDhqk46erBks!E6UztPoFD9fT z{eIg!1xVj8>B~d4*@nc8&XTP|Z)Ob)`nJmmc^G@kP0R zUWNE2+AcJT)hKuY{L_VAVN@#3%RL4+G|Ix8LfxoTUCF$1xc0mLJ|5GTHr0Wil0{80 zGocVI^FpfXSp|!va$3)EVf?F*i$Sq^8uVB+bwv$C;l4D-CV1J-%5KPavYZbfb%P5F zIq^ItLadq1ZN{3J&0V!v)5RwoDJ3mj(ROt1_yaEz&vD_-Fm##@eK`ng&R82nv}Q~B zpvoJ~Q=H;NNvGW71>khoV0MLTX`v1S-5<%TME8^=9Y#y5n`56cEoJcYMxCx$9j@3= z4y3<}MfX2Eh>D8VdVdY$oYN4>AiX`0O>XF~o)Jjuo~I#@k}@td6yn=jOW4?@=EgNH z5bBJrgXuGG<#|TvcN-L_sAb`bl&WeM;%>k_Zc@Vdq)US~?^({)Vn0%yil~5mruq7K zxE3Fu@gP#H#-d+ba5E~b>HsNy>=7|s-+C_znWnujfX&gn@V)rra}M0&%`A*wRKjM6 z_eMz{6jiPbUJYZ1Vi)!(&C$)B&`B6+XC_Z=&md` z@(dpGd^{w=ZqmkErDk>$Y4|kAt9v7{8Mo|x_#^fRg|##S{U|TX7Ld&5v{s8NHMwKu zfEbDDC0ki=H6{Le4JuOp;2!R9j+hV6VjP9D$6tf%lliO^torI9CpKA`zbYTAc1Bw~ z;hLTMCC8(B}1x%iyVy+7jTonmvipbEL&?L#hw7mvIzOEA3BE{9;jj z1lnwm@i64)t;7wIBVzps_Wh9s&!fzr+^g~=bk~9VVnp8)_aNG@UC8Vumy(xIMOs`I zuIO-L+08$<_(_iF#ZQ!Y$D27ba4kJeA!lEKFSae{=YuD(7MqgjLjPSYogw;xV#Q3L)-5zV{>z(B8N(Xt? z@OJycI4Do_q1>kr%O4=#64(+8_~G(IP9!}Zv(6G_r}&ckVlm*uDx8MG#Sd+COS8OT z%r1%HBT?)36-d+`lp6^80Si}@sO_fA3!cM{UU;fn`Gue_9}+U~>NTGAgyeE;qXY3> zw))kieiZl3Agbosa|v8jB<(H-;u-&RG1W%w^=<(4Qf-ac4EDOW3Ydz>J*z>~HOE>{;l@7-y|HG#Gz>tgcg!XtZ_N%ALwj*fG&znc zUdo4~QngkHaCQY7f=qkt&Hy;?T&o9E?)bmisHb9|jH#S-^BYvT7O{GFBQauKtrK`*NPUSNy*r&LyLFi^VY)C z)}4UeQ4{ueG1Cu?Z*~GH=!y3Vw6oAB0x4~ftbzD8DgP4~-;bX}N>X0JT_{@XFoz&K z_LK>GjzcF-0DSGVix0$8de5Wt+H!wigGJB2p6h|#Exz4~?PV%cTn$OBWdR}xb@8T* zMXsFErUIldQHXeO?dYoW15`?E8`F@LpMmMe2QkZ1tIh=5S>IM6*e6YVfngL0KfQ=0 zo#p)fK=-Va`T%{8ssK8t8oRh)|GDxG6wPpGG4`^vIqt-WQyU$OHM_Erc6WVAWV#B8mFu1qsK{DrQ74^DcDtw6c4VGY=`s|?wQuS&2Yd2_L64u(k|CC!2B z(-o7AG@*ThpRg6oebDAg$=i2Cx}n1#&1t=$h)ei;%syIo(i1?h%qM{pXQU|&#s|Hf z*zVQWI)4k})u4~Oz&{qn7gH${!f{O^Wj7R zeRR}1wKC)t`ex`ae+Pm=Y>5e3(!PBXX_CQMiIGE!KN+*}c!gYRhoCBohvn6#Q zbZo1;)2mvx_$Nr$=F`c2bVwPLZpCYZM}s}ecII(u zQBC4Q|3;#(lYcq`*V$3-0nqDG~n_xXQ{^*tRqu z>z!D%-Lo-_bZQa)%Z6=h;yoV$;++zYHxU2Ttizj1%E>F9fKDB@<|WYCyCxNrKQb}R z>?X(g^YEOkaXkb@lS`-3rPk|lUjwNibIBSY1?_)^ftq@h{!a)syyLrYFfBS538slZ zuXO=@jJg-SquprfU>4ouuA)U-OgAM=M}9oW1t~v8ixNWjK2?R#K&wAlqs4Yscsgtr zO0mXOOs3u9$8OY-qNSqe0mY3Dj{^Unde5=Z{KG{8;E&`cA}PgpW)_84jq^E7PV+?o zdSuT-la*f?@g_>fmb^!ZcCm~Iu<^8OZ^Eb@zuE_MKDoQr_^;?6X{KeF9)MfyELA&9z|>zIl*diao0BU+LH zNiyDDO19B2e~;~%lRH`yMSH>Rr5EB7aRkvFXj(iJwYYYcmeUEQ(62~L$C|UTy>dDj zNXq`QmmK-qD?^r1w5D2dyq*5@q=J9GNK6Nq-rwggAE1X84NE^Ap#x0Ny-XPy4UJxM zc=k{Aw2myEU`C??cLT|0Jo{q#;@w`ITD`A{?n1q<^~X^7bZh-{Fs47Q*hHSjq<1QF z>7Ue=HEeuTCgp%+rsPmoPb4!uw-=iV4tockn)*R+v+eknQ&szV&6mKo}9VA-I zwQoX0g{*j@#Xo0mi#!UV!={;K=!h)EH-O(;!Bvp4DyN|i#%B*g{{x(Q5AIq{oJNDf zx4{^)a7Asx9glmTipPonun*yNqd}XP@St5xN_&TPw^8;M!;1lk?^!C&q?{bfN?c&9 zRA%*|BRDT{kK3Xj zSqmW4ouaH*)G62NJcJU=n@Z6U@^^0M;eRo^zrjWEE3SEW!}XTGBad8Xa;3w78j^Ru ziu^A|{|%yWjbSgqxYe44mM|xK%F&U+rG{C!`i*%Ok!#DER28G2&&$F*s;Tvu`vC9{ z&TrX@p78wa1}4(JxwHzY-u>1;hRUbeIqIK7@g0RFZHRvuXLZQBH?t-yDmX*#F+V{&dRA}>= zz287RZG{?b>UzQRkKk#!*MK3Dolsjrw8{{;Mot@S>b#>7t_oW}bn11xmVn;nTr32< zqG9DL(0Sn>$VE}{6J4g-(Pk-zd4zYy2oHhi!aE4w2GPnldXK@iIHVdnInPTWGiO)w zH<08;&tt%Ad@d=_yF*nP7233AUIzFwpHgPqpBp{49BuMd?GtQVoZaI>Z2Lk*up0C& ze`&c$q%=!DbuzVQ`E~%GU2YtNCWGUdg=o`efnOBeVQj6JaWmkg-DGYCk~l#;27>Db zoeR&tbpk*^|Bi;<^)(RN^&T5ZGKeG+x=(0(!UnCl8ui1%P(U89^3ppJ+mVt1m zd?Rd|#Y*fjZE99D$V=)HUIb6SiQRc{RhiT@n3#f~Jy_1n}OB&xr^@I?+C^okB1b0d6v`>WN+Dbr>3&sIAA z_32_F;L0uvMf#%HKNf<2r|d|rlTMHPk%f0}kfzVgS^&k>98oyw&OGUi5kRT#gAPE= zH-)AE%1?jI9Z*kseCQ|Y?w0^c`=+vy^t&B)Q%dSf1a4Ol{$5#TAcePN?+waKSo{QP zq`S-ooL)8-m?_+vDSRJmcKm0o2c<8%xM|^s5zjxo@(#a0H63ee7Otov!d`l8qG+u% z{v8;F5B?8~UCuvw5)OwIqGFt(Ni_lI2aI8hAHT7V9c)G8E5EqT1=Lr+lnV%|?AXp$ zh&Ru<>H=2ok636kRiX4Q(`Ip|bo9=h`7C#;9V_;b6Ru@><>%oVCXVw0)pcv+SoG6e zi2sBg2N~cQt5b+0d9{8i8hbkpdx^FU*OGu-lra;W7 zxUCi=-geU43&w!-WN11f%dLi{7qWApDd&~^ZZxUQ5W5+!UAC1xZ{IU4I(*IRdEh5mPI{wIveI-2-CxFKcC$l*X*0#E zFZyvYB@6#P&lRpo!+Ge*!p=8inJH^Hx*S73IsceL`ExiM22s7=BB^h%y$u z8;jN^Hp(Ds(SrgL;TvOzlOXEd>Emb=^*bAQ zTYDps{UfQJ=_nU@G1ND7goi<>$-#QYb*^`F5DDdI?BGFY(a|(1IQ1pQumROv;Ok9L zcJV6?Xfh@HWDQ)^qkr{)>(&!NXteZ&E86!Y16uT1(0acdrp{R>-h!vvIf#9evr$ul zk|?)iyCbP{o*f|=ljVjYW{cmM5{;xfzZjFlmEE-m)i-85y@~F%H`aW@xVGO)fooM| zwL2wMXp7zhR#T=M*ikr3`brR=m|MWy4Zh|a2USh#l>=zW_U;du^ke;6!M}5@oeQLg zQWxak@8&9mQ7WHmz=me63x#^)oqdq>e-^H2S=)lyrL=sMrG67H>r^ zhg=Q*n)h_%s(ZgR39jnnh3;52rfOd&-SZ}AzE%=X%dvOD$;emT`N)lknj=2DXCkHr zKfmOQ@bP@54*C2kO=4Y5i`}Ii&Vy znSkPr%AF>V>W-`Tx=BYPZEz)Y(igrU#G)O!d=|2=Ii#~+_Dyn(L_2;BkKr{(9s z-yC16gsX6j?+(|R!nGX2pJCnTL;j+F^n?+-VwX8# zbjk$5@T`#3aVb;Qb8I003#mAb=$aDB_H zcB9@;%*yl^0?VoQz zM`UXyL1c5BVjF?utZ&W)PD3BpL_B*sYagSc;Ug{Bx71gHQlV&aq8?q^#&!FK(QcP5 z6xzLKt`mW0Ha7@J%5_~MSoBkqRzMBKi81QXCfrP+04X`MLQ)`Jb#EDxcVxsqMSP&P zo7qf<>-6Y-rLWMN$<%f;29m7k{258ff{)EJW1q*6HJDrsa<49SHgyJmr z>&iODbW~nb0XE~g8M6$c-W)xFDRoAE!c0k(+<=;Nwz08EI6RI_0%*!ES`DB}sbwHq zHSU=QW68(_!i7!e&^oFe1qWfYdNwa-CTCJ2q>{=Gd$CYbEBlxNC3&w*%)vaIsgR*1 zYOVQf#2d6CG`S%xwjA+X-sfz@%cf4cU>>#?4={Hfe%w!R)n;|PhL$MEPDAxsQC}6| zW}^G@<^wq=bv)AaKpO+b1s)Fc;!ajlbmGtVCE@6i+IdWc9rP;}|YR88~ zN_x#o&(ozGx5a~r#`UZ6YxEDM3#MME45FVt-%wlF?u)l!S+Gf~qZe2>U&#(8q?T6E zZWy(eBg0tKInfsAPKOv}VYvszJ3@0G*$Ce=CKR5Z>IYp3-n=2`FEGluyFw5iSaHg% zT0B8zw#0vgoSexUyeTJ5=KWc$X%{Yy)zOfbOmDjYmfid{1NLlQN>;e^~G` zpq_JD-GTqPV+83xE9k66`ZWXdjf5{;7Vsy2a(*1kVYboj|5qQ^pmzvfmG~QAuA}z+QX3jIZt0PWp7+rrgo6{D(+fi83~o76bk^q;XKz!iOzTXsQ|B2 z34Oqn&7ENiwS6KR_|CxfazG8K2ASq@8Anc|oML@FEvob4@57>!fO>ya&lGeKLS>ph zjfZ-B`%iMH`YodYyP)38WI33QzP`j2b)KE)x`4iaJ{Rh_w0L$i^iTMsP5G{aGBH$`nwh_6Ro%dY`+sD;|r!#JPc%khcHtK(zkvKyY5q@B>qw zBTEGOf@wc*TC^}^!!(#`Wm^|M9@}^}@6YC(^4GDbYjn06Ol1-=kJQ%$78+3J^Fn_v zs;9o+4y36S3Bf?Jnr_3`Vc@1iec{rZp`c%G-p`C)#)AT=?;H(#1+F7Mc&EWN<{K%L z>N(~c0sQgQ$LMHI?$*kW2HrAH<~C`zP~q+E=}{Ehi6jB z6p)PlK|@Gi(PRikO%m2hnK8Ysm__ru_!fTySEuV2tC9aL8yB-*w{S(XYhU8YY}~DF z5_AtI@Vv-G-J>rIQGwLy8ZIgvj8KH0p4U24aH?zx)gdiNwoUmBtq`4evvHXe#r78*w3lY`yf8LU+zv&Jz;s}i0?A3&O!VmeGC+7abNXs z7~h(HDFQOFmVO80_AR$CjPt)ekFi%&oNvIcp_tA`-MP}Up3p>p)fPrVnU@E4qVLrq zb-%^-yw&9stXapcfF$L~(npZQuyNsWR=VNW+x?Nz2FJJPkP^QH&}^}agRo^gml_g* zp3qee?Tpf;Ynj}a-o!>|mXsv`T_|<;B9$DMgOU+maLfny7Mp4f7b464RJDcsCy0Pl6U-;}GCFD7I_oNRUHa>5@>ZEv4 zQB@#Zr(Vgf1k%{rkq2({iHn=6Ke^H;#JvfV;K>5Vd7JzRTl?7pA1cz~JTmJk|2r;?1OT_=!|Pu0yQ^md&> zN9YQ~zgM@Xf#O?OQL|5oXTer=0^&DoqTU6m_xomlp!hQJl5@}KzW!u7u^I7CwU+M) zUuZPdLek=%wF_^3`TzU1Che8%#}q$Zln9wR{O^-WYH{@BJfU~m*rAACqEZ1TRjS~E z(xcaHXF;jXyAzZWCB_88F~6LB`&(MH=R=VI@$Qj9^90`QJhBvw3houc(-Fg~h9c%d zD>yAY4Aw|Mtm6w;RFEfBcWe(v!|2Z|i_PA7_N7x1pjN+)ivfC4yadByRH$`=y{=A-gSC*d|i{4b&TPT0^uy~juwO;u*kZR&SI0L8&ebyJmzsz^vUX)7M9oPxipMGQ= zL#kJJl5eTfsS8)YzbLl+Or8HI&d`ZP%ZFT{bl;5o6nV;47WTmNMw9qUluy_ugJ*5C zpB=`K92q>F?ecb@R~7Rg5c<^NKkATZy9*EDau+}J^F*WmSCCIM{lMt-&h}KSsb9g5 zLGf2r6kx`jW&satJ}UFfpn2e|jyEvzMN){yWCjNeR*o6k*KRT?;(sm z-PR+}UN|egP6ZXImQAslr1lI(Lf65q`K*}^oGJfe_EG;183 z%sUi6&oC8ra4~y+>L4jx*?*Uzp`?X@+hMdeH77yS;=)2^&wuWb0#Hh0xCXB69mml7 zqP(<+;GeIxLA@D?8?$wI7Y5LpW|!>kaOAECS&f|jx^~xf;T)%(dW!nI^wwiK=_EQ%4R zx^edqT)X-N+u%Aitw}?rx0iN6K+(~U#fbNMISQWryEi=#{^=<{GDUR@_lD<%IXxQH z9*`h`aaiw)iLjqY+Xv&(g{)|`5rHp{BTr$h z4SNVr3G3=+7`K<5rD_wC&hk;%WRbKav7f~u(a$psB&KADpld^aMQ>#ur zH%Vu;3h`((c)r>*X~L_i1nQgD=(S=Jjb%SvwIA7;lM z*xSUxOLw;OeueRz;@LIwY#WLG2aGfKM#2HFFV-80)4V%>1K8`@{r3RgG&m!`qG=Cb zuOnCI$x;twe?V#vfqDV*Vn9usxSsHr9I|?n zQM0u2aXlIP>z5q@srhNaMv&Tib{ejnx~myLV(U*bn#PSkZlHL*_6SqweZ3qYS)x9u z!=klrGBMFNx(M4~?6;+O|1j+&m!M?J zzZ0XO+d^XYGOjahFECA8Q)VXhGsj{sf|YJ$M>RB&4dr>G`YBTeXe!}m=$QoW=W~&O z_?8LHujblsI7q2ZdGU56kox4LI|kbLc`}T~A4QmQ!wV4;Skx*jO{G*dg2xW*9P`o_ zVlbtLCemS4rUnXV&Fl;2tYk!Kw1-sd3oeL7>ICDK=4B8%xMEk$w8`01&NmWAV+_c#Q{ekOgV1euyw_&vi8t8Z_QfP6hm*LjkB#v|1okWaZz=|;w$cXjR{ z+Q}(Gne_Z#%&p3}7HL|{YcV1+`B*xN%pNIT2b@9skzlk~{A403!U{iTgsW~(Q2|`5 zpWWv}k?f$)pxvZjt_!9yxSI`lQHx#;PN|{|ToB!sFLI^$M2DXU@muHvuEDL)9-O-kS!ttptf6>L zM8iRN>Vkg6w%Kng^noY`EwgBI?OM49jLypj$ak>XjoG%YnLQ|bnIs_tIC@nM>a4Z2 zVy0}WKlJGO&f)n69ZbHPmo$*EpYKyXNl$r<+zot# z9`e}wRvA4O$$dD)y}I}zko|g<2*DYX&0b_wxx6?4Psw=?&qs@gDo)gMS{+^>wl_pa zPnupj<<6k+I{;&>&)kn_;Vt&+etPaAx>M%?pk86WD*+k8St(dE^Fn_mT#Nlqc#&(1 zu)Whv2`xP98;{go_wRP6jEtcl-n8NIS3!OP5jA@(T#-orobmfGCki5RlYa8NU9h~M-yryzk51!7JzzdwO96)_uIcTG{*PU1&0G;NuS`ty_;=PFtsMDX0u;5y7r_cqi{VTE*aDDS7u9;ko zt*I5LUUN&9J4zB!6o=M#&HF<#vhq{b2{1Tm?p8aV+}`oA2_-qG$>T!5kn(P*!d1n0 zAgkFd_H%^KVT+!^*q6*LqtQvdBQb$fXQ~dyB9RBv&ixz3E=V*Xhf%LU5gmdd zd%L^`HO*YQfsK@^t7Hh*Wtq@YeD`b%a$+SG8j+KuNi2X)oBI4vC$2e{Vc*T3Z={y8 zXbbw?K?dv(v0%w!*QThG1m6 zWLybN4PmcMG6Svi4uz(VC(HThX}1?Ek-y{*5i6l-Ok^Kg!d|*$4N~oNUW-9|h1r4O zlWtdJKz`@0o#}|*^C-^)jh=mH3Y(mDeaJ9eyM%|i$jW`ff=$lVdz~Ms9-OkU05yDS zogYdS_k+bjog!LhTn?z6vS--4jPVm(JI$0bGDHdipER4}3Cg^Ez=}bUeURLNtaL9c zAeHpkUOyOXg@+d(DnCkfP)gYYsYt#}v(*fqw{N_!MEJHMG4|-f z^YSo^eqqT|kXMdtBA^I2QYs=&YL%Kvv$;kN?fN^8$l*EiMI3W4IyPL6iLkl)2V;|n z?UuO#$@|VR4`M&Ca7DG(lAl+f z%qErb>RF~EEos|;|HaujFintdWf8oTb6gDLFH;|QpmnY~4luXkwSFE{JB_R-6-LFB z51Yabr=Mrgw^hD|A#)a4LXl_2-1`8}p4h@{9MPrMwl1DlbPHDj^!-qK-2F*$Fq+OjZ280D8OCsU#ajcMUyfb+ z{<7_ZO$RC$Z{z$E>F2SgBRN#tPw_(^8Q2uxQeE0%CrWetrld)FXOuq6d6*WJ`bk%P zLZ^r?KdL8N;f;^#m(fi)$8~aqq7{L4>nrJ`bw_$5;}be8#b%!Zy0LiqCZw71G|7zk zSLdS2;ue2`VyY_@1887A$^*%-{A^aoU;I&$-O3&Wd!aQm0IsUC*ImhVM!Yq!AK71O zt0ShW%t%-0R61xeL#N_^0eI@%eSQTg*0enWlB}7WIzp~xtkAC^slp`L0M|(FjEVSb zas#Vul)vPAnK#t4x^3`)`v0~)tRq*>O-BfrhVXv_rLsk49+dL$DX>%RS*!IU5M|2! zNGe=YugH8U-tphf`7l1&9VmuU(O0d2*A{J1(xRGU8zKdmIA)S_y9zrfhTe^cY6>>^g7q>~Tgy=TT|kuxi-i3w|-8dW!N*whaW{ctFFn5hpHO~;vwR-PF_@#$=67byA zoC)K>u1M^qqp5%I!HB7XHtkHi^tfPkNmBzUO{;25RXdQXb0MmLNnp@y> zpl~J({q&_|CD6<2??NTz$yQHPIWpK6Mw{d-fR8QwijB6Cs;KKJsPSt__s}=SmG>SY z&H2bPJCKq5;S>%5<;hnrG5g!Coof)k@7E`2W?|ktiRcmG{xNv!qIyLzrmI7cyV}A! zi8SA1UqOq>R(`e@#vI-`5N)&83IW8LQ6VEPJDXmcoa&K{cP>Y)+wqic_O4;CPteB* zwYwX94=f&EScxmn-X`O1(cz#^>7-JST>g{}6^FiWp;vh8N_N8ZxcRDuY_^L-Epv3H zsN5w@p%rBj`~koW$r^t{*rVLEl5_NDobnIOItmXu@2tbC#=Sp!)J=bHD(~M~a)8cL ze(6_^kf)^U-1h+TPPloFJZ;mC4DxJg&iKn59j8JSD-P3|YF2p;j1MeP-2k_n!-$bN zE@8HdjQ_8Ps}E}O&ekL(kc6)U0t5}1gl|L))+$mzLLd+kl^}j_i^^BkwycY(E40J9 zkPrxj0%0T2m8}@1>$d8Gb~;qq-XsPZxlUJD?-plm4Qy<2w>v|v+i`oH&Sg2z+y63W z&iS3^JkR-^_vL+mFCOEEVt78(?q~)iRrFnYB*ebSpcLg@1j=%mB4i7VY4Kw>06l-j zTtK9sc%=9dEB08Pp>Wyc&P*u5Ki&aAOaHHX13Z;;&H!3db84>;o*7HONC|ePOG@%o zu8O|{hMRH)jJi$Y8=z>=_b3{kyAPd)XN%g9Mgkdl3770tc}nZJ6voIWdPd6ard4FL zA5MFY=BVmShD|)#fanF|m3Go+#B!w_wB3j^fH(6~VG9{u>EE;MBw9wrS{dY>bVMNB z!P#s@@}$3B1DovoeX&Fbx4yJ4m)g26m%9;s=!YBvsxpTwxD1%)z7_FcF7r(ZI9_nZ zR+Di;Q>)A;i9~|m`w{ULcaMNkI4<$tG^w6ecnP{KY?K+POwY&G9Ex_v#SX(!J*``T zRtPHZ8A2C3xqS4dY^qXC;GgXcjX>>JB`VaeGO=u^-IefFBsSolszcCi(Ha&6=EoWj zpiJBR%C)G-vGEYXuL%Sp5Yset7rpJ+5&9weOYT!yAW~pLFIc{ttJnlg5smCNs-_zh&ephetGxwXT4FcX4e5?r9z zlPucBY$B~Ugu<;&oG-y<@!qI>sz(#|N+srIj_HkdC|s1)FM-0F1}jt~<^zKRO{4gT zH;a}p&2zL8#rAa3ELuJ#ym<{MemLVrxU4TA5XM%mw}94^<+8WIxLNIZn@So==R822 zMZ#`uS9?o?59sUMUG;>Xdo=b<44}-(bOE|MiO)sx)iZJvt+}Xe6H_8fP1biXYTI8p zj6@y&LiB7CU&X^vQt4_mgi|Tf?8BPc+XXR1s7|$Yis{7FDiIpFkktWWdao8`4#?V1 zBD}=GK_iy1B07mW^}5IDRFLUsGi8YOSzBYN85CUpEH?H?^MPUrCvY3kh{CRwU1-@B z`@EUfWJkILNaPajgPNMdzvtypMK)^(GiNW3DlliQ&W<|ZJn*jw$l-YJ+%Xv4ZV?7U zO0F~$KvNdwEbKzXs&MQ=@1;>R=)#53Zi3`meS8p*M&>7(O=w%}MIv5Xe=QPuJ6~vq zaK{JvFnVfEpp~0dQJ@EU*q!3BCnH|u?Hflg~|msZ`Q10a02 zJfB{KvW+$QaC~OFbL<`+Rr#jplK8ddyCG9b_!%``1b_?myCyrz7R&IB?b(e;W%>=SQypc z`<%ZFcv^o$H(o&z_lt3)r*r+DOLU~?qn;xIxZVsnQcTA}eh69mpNGp&UUFgvd{~s{ zm-I36EA2fdEczRD6yP5?lPMrZ6+2@tAX86gHXoUe-`lPtP830|s`G?&DE~k@=<`{2 zN{Bvg;3z*Aubks0^{Di$`a}U44gY;F3-QYS70HMnoa^=n{UNS8q_VS4s))W6?p+oN zt*ohdo8UWb!Iznah>wdzCUZk6LsY>)78xzUF86ujWbTYCkP3C3Tlz&je;q8>5qY(l zEqMUHVN((znmDH437BK@-9j>I{Cs?LiQ?=(*r3_1Kd6GMLy?;RS6+=7i>jkErvRx+ zd>`N|9Gj1W<~IjE4IxYxwWJC%=?eWWqa23MM{ZLWY3|gnDJvsrd&W0SgYLsdv z1eNfdEflX&o-PI_&zxa};N*$GhrMh!stz&byE4+T=>IJJqRs5)w?~7$@ty`~CsJo0 zLz8!0GzNgEJpEl{lJyy*K*{sxi3J2-_}O7Sqn?Eo3Qm#(vS7@c6J$~*u75c*BNU07 zr?6;GTR|CI8>8E(^K>6E(b?WBJaDi4vI8om7!PI9lBU$BE|l4m{0Ajk^ym`-c8Gl> zvV)eCPYN{HU>|g<;Fy~)!~V>&S%Z;hY+WzI2S>dCKAx+2v2fj=^#ntMHRo9gqH-e}7t6q#}dsBrEMe&54QsBQ= z@l`C5kBlB?D?{q%zW7dJfBFMX zB|r&A`q85<&iB{sn53lzK5U$#1@mTrswumOq9o}vklEY9!J2c?d!7xx6H5}x$5LA&FugSn)g zcFoZ1h#$zct)Y0!KX}&|nM1U47z_3=)3Ma9#~>A@rtL?#vS8OHYQ2e^rC)Sm5B_)q zc8f2@!$Iv+hSRh4p+LWB{0&T3r+V!Qw6pM!#}MvlT*Q5W@^405 zZ!D63r@>K~n1l3PO(Wf;zd!qO-rucEntz^=F|{qEqEl0*R|2_G~+CP*h3#yRr=1B!?o&f+9-0J_=WVgfm{ti z8TnXs%v&V}D!wBDRb}b4P2^eS_-#rS-6uN7BDgqVp4-Sbk|I2JzY>{J!c8Fn^^$!A zpxCU31}y6JzAS{R^3NxlDBh9tDT_3*Gz8y;%&IQdjXL^%%v;jL!lELs#6g-gpUo=; zsp4=QQ~tSzO+dQwTRp-@IPdwB&T{Dh!+xJgK1Y&dtq_GHdt+x2MO!+oe4LK&5a*zE zdaVi`TIXg}5RaB*g}`q=73qT2 zmr;=;#~cYkLT#A_G`=$|AMr}1pc-|)n_n3Ws4M^I2dKZ)Mfjnnni7$Kpq{VWnSw>P zk1Ifl^W6R#ru8#Em_hv3SN1Zy6Cbp|HLu}}5UIj#LoEb#WP7#^ zP=yr{ZviT+RvkuAHKpf;Xw#-hfgGqrlZzjT{ z6&c_z=)t;q7`3;}ZRF`Pa0(nXfuC2rKZ2<@7siEh7I*OwFsYLT8Av~!=LB<_(#pkK zG@yn=0ozc#Zn!5D$~B2+erobfJ~a7rMVl0^u3$3;gmS%%4WOI@It&Q2V6^}>)!YhB zMgFn@Ig_7P@dTq>6j1aDnso6BM-Eqap%7Eg6*=WW=VcY=N1=09UtW50w|st~u6iO2 zpuW{=f7-b%C(#d*U*7>J)$VovkiPSq>!@ku`k$Ebx;|zW{}RIOi*Lu!jL@(@ z$%LeeVtEe4Z%j>K_GqSn2T2$9t7O15b|z6uoEi+*S|F52Zr%z>xrPOQ&{wwAjGBZK zftgH8)c=}8o$H+38IDE6V*U@|qw?xisHxAO4<%1lxa|$Vca8R9HyGIaN|0VIK9z*> zXDW^|+u_I$2XT22+8@4%_<3#(HuKWUfm*~ndtDjCiAgB937`o_{t}5{y5;&+C~EHC zwG~GFV;{n;k?nEl^5F0-2v;64`V&v=_?1!^JHHD>@uIW!GC-PY_c1iJZDFLJzrPQH zWL>}FqVa4EYtJaBM<7zq$vO7&fs~$C#mQrIY5X$(gdu48~e4u6AX_REp z%}USHA6$vcM?#)VH}iaki@W?_!WuhTT1SsCIz>CU(e%C~;&S;d zig&l3d3}t=(-X-*TX!rsuJ^SMS0dBaYu5t%m!FHUJX3MVbX8UzflU0Q4S+A~w$vii z;0bF8#ao6-Uf@#vT;Xf)d8yJNzn~Z3>Z_~_K&rpLgwp`aW=oX0qnU;!o#Rg?yr7)hC=JS-P;h}>vhKxd{@HY*exO|r!_st zOGK-0hjW1G{Zc86?2;2rB#E7)I0;FPr%an*^lz3ph*DdU&>!f#e3zgT$0pqiqxw}n zicdMF2l}ETi$-wo3O)^ELqXJTlr-v@=Tk|VeYQu<JyAirK(+(t-Mt^R+9tG3OGcule7V+WBhKbSfUN@r7t*DvW*;rIVAAhU-6 literal 0 HcmV?d00001 diff --git a/src/main/deploy/pathplanner/autos/sideways auto.auto b/src/main/deploy/pathplanner/autos/sideways auto.auto index 6ae622f..f71c5f7 100644 --- a/src/main/deploy/pathplanner/autos/sideways auto.auto +++ b/src/main/deploy/pathplanner/autos/sideways auto.auto @@ -16,6 +16,48 @@ "data": { "pathName": "go sideways" } + }, + { + "type": "path", + "data": { + "pathName": "sideways opposite " + } + }, + { + "type": "path", + "data": { + "pathName": "go sideways" + } + }, + { + "type": "path", + "data": { + "pathName": "sideways opposite " + } + }, + { + "type": "path", + "data": { + "pathName": "go sideways" + } + }, + { + "type": "path", + "data": { + "pathName": "sideways opposite " + } + }, + { + "type": "path", + "data": { + "pathName": "go sideways" + } + }, + { + "type": "path", + "data": { + "pathName": "sideways opposite " + } } ] } diff --git a/src/main/deploy/pathplanner/paths/Anywhere_Center.path b/src/main/deploy/pathplanner/paths/Anywhere_Center.path index 6c75ada..7fbbcbc 100644 --- a/src/main/deploy/pathplanner/paths/Anywhere_Center.path +++ b/src/main/deploy/pathplanner/paths/Anywhere_Center.path @@ -39,7 +39,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Center_CloseBottom.path b/src/main/deploy/pathplanner/paths/Center_CloseBottom.path index 63cdf35..218a057 100644 --- a/src/main/deploy/pathplanner/paths/Center_CloseBottom.path +++ b/src/main/deploy/pathplanner/paths/Center_CloseBottom.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Center_CloseBottom2.path b/src/main/deploy/pathplanner/paths/Center_CloseBottom2.path index 2dfdbae..a50e87f 100644 --- a/src/main/deploy/pathplanner/paths/Center_CloseBottom2.path +++ b/src/main/deploy/pathplanner/paths/Center_CloseBottom2.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Center_CloseTop.path b/src/main/deploy/pathplanner/paths/Center_CloseTop.path index add85f1..582365b 100644 --- a/src/main/deploy/pathplanner/paths/Center_CloseTop.path +++ b/src/main/deploy/pathplanner/paths/Center_CloseTop.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Center_CloseTop2.path b/src/main/deploy/pathplanner/paths/Center_CloseTop2.path index 85cdf21..06654ba 100644 --- a/src/main/deploy/pathplanner/paths/Center_CloseTop2.path +++ b/src/main/deploy/pathplanner/paths/Center_CloseTop2.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseBottom_Center.path b/src/main/deploy/pathplanner/paths/CloseBottom_Center.path index 323ec7e..48f6b65 100644 --- a/src/main/deploy/pathplanner/paths/CloseBottom_Center.path +++ b/src/main/deploy/pathplanner/paths/CloseBottom_Center.path @@ -64,7 +64,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseBottom_Center2.path b/src/main/deploy/pathplanner/paths/CloseBottom_Center2.path index 526c174..4bd18be 100644 --- a/src/main/deploy/pathplanner/paths/CloseBottom_Center2.path +++ b/src/main/deploy/pathplanner/paths/CloseBottom_Center2.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseBottom_CloseMid.path b/src/main/deploy/pathplanner/paths/CloseBottom_CloseMid.path index 4e17a69..600d050 100644 --- a/src/main/deploy/pathplanner/paths/CloseBottom_CloseMid.path +++ b/src/main/deploy/pathplanner/paths/CloseBottom_CloseMid.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseBottom_SpeakerShot.path b/src/main/deploy/pathplanner/paths/CloseBottom_SpeakerShot.path index 28fff99..aa76ef6 100644 --- a/src/main/deploy/pathplanner/paths/CloseBottom_SpeakerShot.path +++ b/src/main/deploy/pathplanner/paths/CloseBottom_SpeakerShot.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseMid_Center.path b/src/main/deploy/pathplanner/paths/CloseMid_Center.path index f62178f..744fcc3 100644 --- a/src/main/deploy/pathplanner/paths/CloseMid_Center.path +++ b/src/main/deploy/pathplanner/paths/CloseMid_Center.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseMid_CloseTop.path b/src/main/deploy/pathplanner/paths/CloseMid_CloseTop.path index 737c161..0f0ce21 100644 --- a/src/main/deploy/pathplanner/paths/CloseMid_CloseTop.path +++ b/src/main/deploy/pathplanner/paths/CloseMid_CloseTop.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseMid_FarMid.path b/src/main/deploy/pathplanner/paths/CloseMid_FarMid.path index 00c5069..fc6efc6 100644 --- a/src/main/deploy/pathplanner/paths/CloseMid_FarMid.path +++ b/src/main/deploy/pathplanner/paths/CloseMid_FarMid.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseMid_FarTop.path b/src/main/deploy/pathplanner/paths/CloseMid_FarTop.path index bcec8f5..3fd0db8 100644 --- a/src/main/deploy/pathplanner/paths/CloseMid_FarTop.path +++ b/src/main/deploy/pathplanner/paths/CloseMid_FarTop.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseMid_SpeakerShot.path b/src/main/deploy/pathplanner/paths/CloseMid_SpeakerShot.path index 6140a93..0b90aed 100644 --- a/src/main/deploy/pathplanner/paths/CloseMid_SpeakerShot.path +++ b/src/main/deploy/pathplanner/paths/CloseMid_SpeakerShot.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseTop_Center.path b/src/main/deploy/pathplanner/paths/CloseTop_Center.path index eaf7310..d348038 100644 --- a/src/main/deploy/pathplanner/paths/CloseTop_Center.path +++ b/src/main/deploy/pathplanner/paths/CloseTop_Center.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseTop_CloseMid.path b/src/main/deploy/pathplanner/paths/CloseTop_CloseMid.path index 2a72f7b..5f07247 100644 --- a/src/main/deploy/pathplanner/paths/CloseTop_CloseMid.path +++ b/src/main/deploy/pathplanner/paths/CloseTop_CloseMid.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseTop_FarTop.path b/src/main/deploy/pathplanner/paths/CloseTop_FarTop.path index 00c6698..a30c296 100644 --- a/src/main/deploy/pathplanner/paths/CloseTop_FarTop.path +++ b/src/main/deploy/pathplanner/paths/CloseTop_FarTop.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseTop_FarTop2.path b/src/main/deploy/pathplanner/paths/CloseTop_FarTop2.path index d7006a9..566a02d 100644 --- a/src/main/deploy/pathplanner/paths/CloseTop_FarTop2.path +++ b/src/main/deploy/pathplanner/paths/CloseTop_FarTop2.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/CloseTop_SpeakerShot.path b/src/main/deploy/pathplanner/paths/CloseTop_SpeakerShot.path index 7e2119b..c261db5 100644 --- a/src/main/deploy/pathplanner/paths/CloseTop_SpeakerShot.path +++ b/src/main/deploy/pathplanner/paths/CloseTop_SpeakerShot.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/FarBottom_RightStage.path b/src/main/deploy/pathplanner/paths/FarBottom_RightStage.path index 10a54a3..0ba1bf8 100644 --- a/src/main/deploy/pathplanner/paths/FarBottom_RightStage.path +++ b/src/main/deploy/pathplanner/paths/FarBottom_RightStage.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage.path b/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage.path index 111f0a7..ced6f75 100644 --- a/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage.path +++ b/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage2.path b/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage2.path index 1daa525..f55e2fb 100644 --- a/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage2.path +++ b/src/main/deploy/pathplanner/paths/FarMidBottom_RightStage2.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/FarMidTop_LeftStage.path b/src/main/deploy/pathplanner/paths/FarMidTop_LeftStage.path index b33b598..7b2a51b 100644 --- a/src/main/deploy/pathplanner/paths/FarMidTop_LeftStage.path +++ b/src/main/deploy/pathplanner/paths/FarMidTop_LeftStage.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/FarMid_LeftStage.path b/src/main/deploy/pathplanner/paths/FarMid_LeftStage.path index e265e2f..7dbdba2 100644 --- a/src/main/deploy/pathplanner/paths/FarMid_LeftStage.path +++ b/src/main/deploy/pathplanner/paths/FarMid_LeftStage.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/FarTop_LeftStage.path b/src/main/deploy/pathplanner/paths/FarTop_LeftStage.path index 93a06da..34576a3 100644 --- a/src/main/deploy/pathplanner/paths/FarTop_LeftStage.path +++ b/src/main/deploy/pathplanner/paths/FarTop_LeftStage.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/First Note (Left_CloseTop_CloseMid_FarMid).path b/src/main/deploy/pathplanner/paths/First Note (Left_CloseTop_CloseMid_FarMid).path index 7294750..c2f5c67 100644 --- a/src/main/deploy/pathplanner/paths/First Note (Left_CloseTop_CloseMid_FarMid).path +++ b/src/main/deploy/pathplanner/paths/First Note (Left_CloseTop_CloseMid_FarMid).path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Leave from speaker.path b/src/main/deploy/pathplanner/paths/Leave from speaker.path index 0c47519..f83c665 100644 --- a/src/main/deploy/pathplanner/paths/Leave from speaker.path +++ b/src/main/deploy/pathplanner/paths/Leave from speaker.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/LeftStage_FarMidTop.path b/src/main/deploy/pathplanner/paths/LeftStage_FarMidTop.path index 39d4154..5ae70bc 100644 --- a/src/main/deploy/pathplanner/paths/LeftStage_FarMidTop.path +++ b/src/main/deploy/pathplanner/paths/LeftStage_FarMidTop.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Left_CloseMid.path b/src/main/deploy/pathplanner/paths/Left_CloseMid.path index 4e64e5f..7a549f0 100644 --- a/src/main/deploy/pathplanner/paths/Left_CloseMid.path +++ b/src/main/deploy/pathplanner/paths/Left_CloseMid.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Left_CloseTop.path b/src/main/deploy/pathplanner/paths/Left_CloseTop.path index b65792b..35c52b7 100644 --- a/src/main/deploy/pathplanner/paths/Left_CloseTop.path +++ b/src/main/deploy/pathplanner/paths/Left_CloseTop.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Left_CloseTop2.path b/src/main/deploy/pathplanner/paths/Left_CloseTop2.path index 1f96b93..e8a2da8 100644 --- a/src/main/deploy/pathplanner/paths/Left_CloseTop2.path +++ b/src/main/deploy/pathplanner/paths/Left_CloseTop2.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Left_FarTop.path b/src/main/deploy/pathplanner/paths/Left_FarTop.path index b4bf9ac..a1ca381 100644 --- a/src/main/deploy/pathplanner/paths/Left_FarTop.path +++ b/src/main/deploy/pathplanner/paths/Left_FarTop.path @@ -39,7 +39,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/RightStage_FarMidBottom.path b/src/main/deploy/pathplanner/paths/RightStage_FarMidBottom.path index de1cdbc..306c2d6 100644 --- a/src/main/deploy/pathplanner/paths/RightStage_FarMidBottom.path +++ b/src/main/deploy/pathplanner/paths/RightStage_FarMidBottom.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Right_CloseBottom.path b/src/main/deploy/pathplanner/paths/Right_CloseBottom.path index 1397c0e..0a2dd8d 100644 --- a/src/main/deploy/pathplanner/paths/Right_CloseBottom.path +++ b/src/main/deploy/pathplanner/paths/Right_CloseBottom.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Right_FarBottom.path b/src/main/deploy/pathplanner/paths/Right_FarBottom.path index e966c6a..6f6e737 100644 --- a/src/main/deploy/pathplanner/paths/Right_FarBottom.path +++ b/src/main/deploy/pathplanner/paths/Right_FarBottom.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/Second Note.path b/src/main/deploy/pathplanner/paths/Second Note.path index 8b3a0c4..5142880 100644 --- a/src/main/deploy/pathplanner/paths/Second Note.path +++ b/src/main/deploy/pathplanner/paths/Second Note.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/SpeakerShot_CloseMid.path b/src/main/deploy/pathplanner/paths/SpeakerShot_CloseMid.path index 9e59504..3b6a167 100644 --- a/src/main/deploy/pathplanner/paths/SpeakerShot_CloseMid.path +++ b/src/main/deploy/pathplanner/paths/SpeakerShot_CloseMid.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/close bottom.path b/src/main/deploy/pathplanner/paths/close bottom.path index 277787b..11cc058 100644 --- a/src/main/deploy/pathplanner/paths/close bottom.path +++ b/src/main/deploy/pathplanner/paths/close bottom.path @@ -63,7 +63,7 @@ ], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/close mid.path b/src/main/deploy/pathplanner/paths/close mid.path index d4777a3..1b25b36 100644 --- a/src/main/deploy/pathplanner/paths/close mid.path +++ b/src/main/deploy/pathplanner/paths/close mid.path @@ -39,7 +39,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/close top.path b/src/main/deploy/pathplanner/paths/close top.path index 7d1675f..3223b00 100644 --- a/src/main/deploy/pathplanner/paths/close top.path +++ b/src/main/deploy/pathplanner/paths/close top.path @@ -63,7 +63,7 @@ ], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/far top.path b/src/main/deploy/pathplanner/paths/far top.path index 6d27c2d..a4ee9df 100644 --- a/src/main/deploy/pathplanner/paths/far top.path +++ b/src/main/deploy/pathplanner/paths/far top.path @@ -39,7 +39,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/go sideways.path b/src/main/deploy/pathplanner/paths/go sideways.path index 66bdf73..031d4aa 100644 --- a/src/main/deploy/pathplanner/paths/go sideways.path +++ b/src/main/deploy/pathplanner/paths/go sideways.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/shoot far.path b/src/main/deploy/pathplanner/paths/shoot far.path index 6dabc91..c9880f3 100644 --- a/src/main/deploy/pathplanner/paths/shoot far.path +++ b/src/main/deploy/pathplanner/paths/shoot far.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/shoot preload ring.path b/src/main/deploy/pathplanner/paths/shoot preload ring.path index 1d474d6..17ccb48 100644 --- a/src/main/deploy/pathplanner/paths/shoot preload ring.path +++ b/src/main/deploy/pathplanner/paths/shoot preload ring.path @@ -39,7 +39,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/sideways opposite .path b/src/main/deploy/pathplanner/paths/sideways opposite .path new file mode 100644 index 0000000..8cb0809 --- /dev/null +++ b/src/main/deploy/pathplanner/paths/sideways opposite .path @@ -0,0 +1,52 @@ +{ + "version": 1.0, + "waypoints": [ + { + "anchor": { + "x": 2.0, + "y": 3.0 + }, + "prevControl": null, + "nextControl": { + "x": 2.0, + "y": 3.1339527959172506 + }, + "isLocked": false, + "linkedName": "sidwaysAmp" + }, + { + "anchor": { + "x": 2.0, + "y": 7.0 + }, + "prevControl": { + "x": 2.0, + "y": 6.9 + }, + "nextControl": null, + "isLocked": false, + "linkedName": "startsidewaysAmp" + } + ], + "rotationTargets": [], + "constraintZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 5.1, + "maxAcceleration": 3.0, + "maxAngularVelocity": 2160.0, + "maxAngularAcceleration": 2160.0 + }, + "goalEndState": { + "velocity": 0, + "rotation": 180.0, + "rotateFast": false + }, + "reversed": false, + "folder": null, + "previewStartingState": { + "rotation": 180.0, + "velocity": 0 + }, + "useDefaultConstraints": true +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/test 180 far path opposite.path b/src/main/deploy/pathplanner/paths/test 180 far path opposite.path index de1050b..b52e7eb 100644 --- a/src/main/deploy/pathplanner/paths/test 180 far path opposite.path +++ b/src/main/deploy/pathplanner/paths/test 180 far path opposite.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/deploy/pathplanner/paths/test 180 far path.path b/src/main/deploy/pathplanner/paths/test 180 far path.path index 1ab86f7..16b9904 100644 --- a/src/main/deploy/pathplanner/paths/test 180 far path.path +++ b/src/main/deploy/pathplanner/paths/test 180 far path.path @@ -33,7 +33,7 @@ "eventMarkers": [], "globalConstraints": { "maxVelocity": 5.1, - "maxAcceleration": 4.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 2160.0, "maxAngularAcceleration": 2160.0 }, diff --git a/src/main/java/frc/robot/subsystems/drive/AutoTrajectory.java b/src/main/java/frc/robot/subsystems/drive/AutoTrajectory.java index 8146603..ca0b7c3 100644 --- a/src/main/java/frc/robot/subsystems/drive/AutoTrajectory.java +++ b/src/main/java/frc/robot/subsystems/drive/AutoTrajectory.java @@ -66,7 +66,7 @@ public Command getCommand() { : new PathPlannerAuto(m_auto.getFirst()); return Commands.sequence( - m_driveSubsystem.resetPoseCommand(() -> getInitialPose()), + //m_driveSubsystem.resetPoseCommand(() -> getInitialPose()), autoCommand, m_driveSubsystem.stopCommand(), m_driveSubsystem.lockCommand() diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java index ba77843..3c3a83f 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java @@ -210,7 +210,7 @@ public DriveSubsystem(Hardware drivetrainHardware, PIDConstants pidf, ControlCen this.m_throttleMap = new ThrottleMap(throttleInputCurve, DRIVE_MAX_LINEAR_SPEED, deadband); this.m_rotatePIDController = new RotatePIDController(turnInputCurve, pidf, turnScalar, deadband, lookAhead); this.m_pathFollowerConfig = new HolonomicPathFollowerConfig( - new com.pathplanner.lib.util.PIDConstants(3.1, 0.0, 0.0), + new com.pathplanner.lib.util.PIDConstants(5.0, 0.0, 0.2), new com.pathplanner.lib.util.PIDConstants(5.0, 0.0, 0.1), DRIVE_MAX_LINEAR_SPEED.in(Units.MetersPerSecond), m_lFrontModule.getModuleCoordinate().getNorm(), @@ -295,6 +295,12 @@ public DriveSubsystem(Hardware drivetrainHardware, PIDConstants pidf, ControlCen // Set VisionSubsystem pose supplier for simulation VisionSubsystem.getInstance().setPoseSupplier(this::getPose); + + + m_rRearModule.disableAutoLock(); + m_rFrontModule.disableAutoLock(); + m_lRearModule.disableAutoLock(); + m_lFrontModule.disableAutoLock(); } /** @@ -368,6 +374,8 @@ public static Hardware initializeHardware() { Constants.Drive.DRIVE_SLIP_RATIO ); + + Hardware drivetrainHardware = new Hardware(navx, lFrontModule, rFrontModule, lRearModule, rRearModule); return drivetrainHardware; @@ -1296,6 +1304,20 @@ public Rotation2d getRotation2d() { return m_navx.getInputs().rotation2d; } + public Command testMotor() { + return Commands.runEnd( + () -> { + System.out.println("fefefeffef"); + m_lFrontModule.set(new SwerveModuleState(1, m_lFrontModule.getState().angle.plus(new Rotation2d(Units.Degrees.fromBaseUnits(0.1))))); + // m_lFrontModule.set(new SwerveModuleState(0.0001, new Rotation2d(Units.Degrees.fromBaseUnits(30)))); + }, + () -> { + m_lFrontModule.stop(); + }, + this + ); + } + @Override public void close() { m_navx.close(); diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java index 4c6a898..912afd7 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java @@ -82,7 +82,7 @@ public static class State { public static final State SOURCE_PREP_STATE = new State(ZERO_FLYWHEEL_SPEED, Units.Degrees.of(55.0)); public static final State SOURCE_INTAKE_STATE = new State(Units.MetersPerSecond.of(-10.0), Units.Degrees.of(55.0)); public static final State PASSING_STATE = new State(Units.MetersPerSecond.of(+15.0), Units.Degrees.of(45.0)); - public static final State PODIUM_SCORE_STATE = new State(Units.MetersPerSecond.of(+16.25786), Units.Degrees.of(29)); + public static final State PODIUM_SCORE_STATE = new State(Units.MetersPerSecond.of(+16.25786), Units.Degrees.of(36)); public static final State TEST_STOP_STATE = new State(ZERO_FLYWHEEL_SPEED, Units.Degrees.of(30.0)); public State(Measure> speed, Measure angle) { From 59924d33705cfa10fc335da69061f24301536ded Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Thu, 27 Jun 2024 02:34:46 -0500 Subject: [PATCH 14/16] Code cleanup --- build.gradle | 4 ++-- src/main/java/frc/robot/Robot.java | 1 - .../java/frc/robot/subsystems/drive/DriveSubsystem.java | 6 ------ 3 files changed, 2 insertions(+), 9 deletions(-) diff --git a/build.gradle b/build.gradle index be03304..35b519d 100644 --- a/build.gradle +++ b/build.gradle @@ -101,10 +101,10 @@ dependencies { implementation 'org.apache.commons:commons-math3:3.+' - testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' + testImplementation 'org.junit.jupiter:junit-jupiter:5.10.2' testImplementation 'org.mockito:mockito-core:3.+' - testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.+' + testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.10.2' annotationProcessor "org.littletonrobotics.akit.junction:junction-autolog:$AdvantageKitJSON.version" } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index e56de71..afa60e9 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -10,7 +10,6 @@ import org.lasarobotics.utils.GlobalConstants; import org.littletonrobotics.junction.LoggedRobot; -import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java index 3c3a83f..ad97546 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSubsystem.java @@ -295,12 +295,6 @@ public DriveSubsystem(Hardware drivetrainHardware, PIDConstants pidf, ControlCen // Set VisionSubsystem pose supplier for simulation VisionSubsystem.getInstance().setPoseSupplier(this::getPose); - - - m_rRearModule.disableAutoLock(); - m_rFrontModule.disableAutoLock(); - m_lRearModule.disableAutoLock(); - m_lFrontModule.disableAutoLock(); } /** From 6e1b50ba041cc0f9c390ab6beaeaa96476587912 Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Thu, 27 Jun 2024 02:40:14 -0500 Subject: [PATCH 15/16] Add shooter angle feed forward --- .../subsystems/shooter/ShooterSubsystem.java | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java index 912afd7..0a1bc23 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java @@ -24,6 +24,7 @@ import com.revrobotics.CANSparkBase.ControlType; import com.revrobotics.CANSparkBase.IdleMode; +import com.revrobotics.SparkPIDController.ArbFFUnits; import edu.wpi.first.apriltag.AprilTag; import edu.wpi.first.math.MathUtil; @@ -40,6 +41,7 @@ import edu.wpi.first.units.Time; import edu.wpi.first.units.Units; import edu.wpi.first.units.Velocity; +import edu.wpi.first.units.Voltage; import edu.wpi.first.wpilibj.RobotBase; import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d; import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d; @@ -95,6 +97,7 @@ public State(Measure> speed, Measure angle) { public static final Measure> ZERO_FLYWHEEL_SPEED = Units.MetersPerSecond.of(0.0); private static final Measure FLYWHEEL_CURRENT_LIMIT = Units.Amps.of(80.0); private static final Measure ANGLE_MOTOR_CURRENT_LIMIT = Units.Amps.of(50.0); + private static final Measure ANGLE_MOTOR_FF = Units.Volts.of(0.1); private static final Measure INDEXER_SPEED = Units.Percent.of(100.0); private static final Measure INDEXER_SLOW_SPEED = Units.Percent.of(4.0); private static final String MECHANISM_2D_LOG_ENTRY = "/Mechanism2d"; @@ -284,15 +287,21 @@ private void setState(State state) { // Normalize state to valid range m_desiredShooterState = normalizeState(state); + // Set flywheel speeds, allow coasting to zero if (state.speed.isNear(ZERO_FLYWHEEL_SPEED, 0.01)) { m_topFlywheelMotor.stopMotor(); m_bottomFlywheelMotor.stopMotor(); - } - else { + } else { m_topFlywheelMotor.set(m_desiredShooterState.speed.in(Units.MetersPerSecond), ControlType.kVelocity); m_bottomFlywheelMotor.set(m_desiredShooterState.speed.in(Units.MetersPerSecond), ControlType.kVelocity); } - m_angleMotor.set(m_desiredShooterState.angle.in(Units.Radians), ControlType.kPosition); + // Set angle + m_angleMotor.set( + m_desiredShooterState.angle.in(Units.Radians), + ControlType.kPosition, + ANGLE_MOTOR_FF.in(Units.Volts), + ArbFFUnits.kVoltage + ); } /** From 6a84ab6ba7d5a0d5f8c899d1c17dcfc552b2f8e2 Mon Sep 17 00:00:00 2001 From: Vignesh Balasubramaniam Date: Thu, 27 Jun 2024 02:42:15 -0500 Subject: [PATCH 16/16] v2024.1.2 --- VERSION | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/VERSION b/VERSION index 9d2fb09..7767913 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -2024.1.1 \ No newline at end of file +2024.1.2 \ No newline at end of file