From f7f328c3ca6e818059df133eca604550693444a9 Mon Sep 17 00:00:00 2001 From: BaronClaps <126834072+BaronClaps@users.noreply.github.com> Date: Thu, 28 Aug 2025 23:11:21 -0500 Subject: [PATCH 001/152] 2.0.0 --- FtcRobotController/build.gradle | 2 +- .../ftc/teamcode/pedroPathing/Constants.java | 57 + .../ftc/teamcode/pedroPathing/Tuning.java | 1323 +++++++++++++++++ build.common.gradle | 2 +- build.dependencies.gradle | 8 + 5 files changed, 1390 insertions(+), 2 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java diff --git a/FtcRobotController/build.gradle b/FtcRobotController/build.gradle index 9fa21699dd27..8c796dac2487 100644 --- a/FtcRobotController/build.gradle +++ b/FtcRobotController/build.gradle @@ -17,8 +17,8 @@ android { buildFeatures { buildConfig = true } + compileSdk 34 - compileSdkVersion 30 compileOptions { sourceCompatibility JavaVersion.VERSION_1_8 diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java new file mode 100644 index 000000000000..1b43026ad2ac --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -0,0 +1,57 @@ +package org.firstinspires.ftc.teamcode.pedroPathing; + +import com.pedropathing.control.FilteredPIDFCoefficients; +import com.pedropathing.control.PIDFCoefficients; +import com.pedropathing.follower.Follower; +import com.pedropathing.follower.FollowerConstants; +import com.pedropathing.ftc.FollowerBuilder; +import com.pedropathing.ftc.drivetrains.MecanumConstants; +import com.pedropathing.ftc.localization.constants.PinpointConstants; +import com.pedropathing.paths.PathConstraints; +import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.HardwareMap; + +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; + +public class Constants { + + public static FollowerConstants followerConstants = new FollowerConstants() + .centripetalScaling(0.005) + .forwardZeroPowerAcceleration(-41.278) + .lateralZeroPowerAcceleration(-59.7819) + .translationalPIDFCoefficients(new PIDFCoefficients(0.1, 0, 0.01, 0)) + .headingPIDFCoefficients(new PIDFCoefficients(2, 0, 0.1, 0)) + .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0, 0.6, 0)) + .mass(5); + + public static MecanumConstants driveConstants = new MecanumConstants() + .xVelocity(57.8741) + .yVelocity(52.295) + .maxPower(1) + .leftFrontMotorName("lf") + .leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE) + .leftRearMotorDirection(DcMotorSimple.Direction.REVERSE) + .rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD) + .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD) + .motorCachingThreshold(0.01) + .useBrakeModeInTeleOp(false); + + public static PinpointConstants pinpointConstants = new PinpointConstants() + .forwardPodY(-5) + .strafePodX(0.5) + .distanceUnit(DistanceUnit.INCH) + .hardwareMapName("pinpoint") + .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) + .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED); + + public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1); + + public static Follower createFollower(HardwareMap hardwareMap) { + return new FollowerBuilder(followerConstants, hardwareMap) + .mecanumDrivetrain(driveConstants) + .pinpointLocalizer(pinpointConstants) + .pathConstraints(pathConstraints) + .build(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java new file mode 100644 index 000000000000..edf090ed237d --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java @@ -0,0 +1,1323 @@ +package org.firstinspires.ftc.teamcode.pedroPathing; + +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.changes; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.drawCurrent; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.drawCurrentAndHistory; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.follower; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.stopRobot; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.telemetryM; + +import com.bylazar.configurables.PanelsConfigurables; +import com.bylazar.configurables.annotations.Configurable; +import com.bylazar.configurables.annotations.IgnoreConfigurable; +import com.bylazar.field.FieldManager; +import com.bylazar.field.PanelsField; +import com.bylazar.field.Style; +import com.bylazar.telemetry.PanelsTelemetry; +import com.bylazar.telemetry.TelemetryManager; +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.*; +import com.pedropathing.math.*; +import com.pedropathing.paths.*; +import com.pedropathing.telemetry.SelectableOpMode; +import com.pedropathing.util.*; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import java.util.ArrayList; +import java.util.List; + +/** + * This is the Tuning class. It contains a selection menu for various tuning OpModes. + * + * @author Baron Henderson - 20077 The Indubitables + * @version 1.0, 6/26/2025 + */ +@Configurable +@TeleOp(name = "Tuning", group = "Pedro Pathing") +public class Tuning extends SelectableOpMode { + public static Follower follower; + + @IgnoreConfigurable + static PoseHistory poseHistory; + + @IgnoreConfigurable + static TelemetryManager telemetryM; + + @IgnoreConfigurable + static ArrayList changes = new ArrayList<>(); + + public Tuning() { + super("Select a Tuning OpMode", s -> { + s.folder("Localization", l -> { + l.add("Localization Test", LocalizationTest::new); + l.add("Forward Tuner", ForwardTuner::new); + l.add("Lateral Tuner", LateralTuner::new); + l.add("Turn Tuner", TurnTuner::new); + }); + s.folder("Automatic", a -> { + a.add("Forward Velocity Tuner", ForwardVelocityTuner::new); + a.add("Lateral Velocity Tuner", LateralVelocityTuner::new); + a.add("Forward Zero Power Acceleration Tuner", ForwardZeroPowerAccelerationTuner::new); + a.add("Lateral Zero Power Acceleration Tuner", LateralZeroPowerAccelerationTuner::new); + }); + s.folder("Manual", p -> { + p.add("Translational Tuner", TranslationalTuner::new); + p.add("Heading Tuner", HeadingTuner::new); + p.add("Drive Tuner", DriveTuner::new); + p.add("Centripetal Tuner", CentripetalTuner::new); + }); + s.folder("Tests", p -> { + p.add("Line Test", LineTest::new); + p.add("Triangle", Triangle::new); + }); + }); + } + + @Override + public void onSelect() { + if (follower == null) { + follower = Constants.createFollower(hardwareMap); + PanelsConfigurables.INSTANCE.refreshClass(this); + } else { + follower = Constants.createFollower(hardwareMap); + } + + follower.setStartingPose(new Pose()); + + poseHistory = follower.getPoseHistory(); + + telemetryM = PanelsTelemetry.INSTANCE.getTelemetry(); + } + + @Override + public void onLog(List lines) {} + + public static void drawCurrent() { + try { + Drawing.drawRobot(follower.getPose()); + Drawing.sendPacket(); + } catch (Exception e) { + throw new RuntimeException("Drawing failed " + e); + } + } + + public static void drawCurrentAndHistory() { + Drawing.drawPoseHistory(poseHistory); + drawCurrent(); + } + + /** This creates a full stop of the robot by setting the drive motors to run at 0 power. */ + public static void stopRobot() { + follower.startTeleopDrive(true); + follower.setTeleOpDrive(0,0,0,true); + } +} + +/** + * This is the LocalizationTest OpMode. This is basically just a simple mecanum drive attached to a + * PoseUpdater. The OpMode will print out the robot's pose to telemetry as well as draw the robot. + * You should use this to check the robot's localization. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @version 1.0, 5/6/2024 + */ +class LocalizationTest extends OpMode { + @Override + public void init() {} + + /** This initializes the PoseUpdater, the mecanum drive motors, and the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("This will print your robot's position to telemetry while " + + "allowing robot control through a basic mecanum drive on gamepad 1."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void start() { + follower.startTeleopDrive(); + follower.update(); + } + + /** + * This updates the robot's pose estimate, the simple mecanum drive, and updates the + * Panels telemetry with the robot's position as well as draws the robot's position. + */ + @Override + public void loop() { + follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, true); + follower.update(); + + telemetryM.debug("x:" + follower.getPose().getX()); + telemetryM.debug("y:" + follower.getPose().getY()); + telemetryM.debug("heading:" + follower.getPose().getHeading()); + telemetryM.debug("total heading:" + follower.getTotalHeading()); + telemetryM.update(telemetry); + + drawCurrentAndHistory(); + } +} + +/** + * This is the ForwardTuner OpMode. This tracks the forward movement of the robot and displays the + * necessary ticks to inches multiplier. This displayed multiplier is what's necessary to scale the + * robot's current distance in ticks to the specified distance in inches. So, to use this, run the + * tuner, then pull/push the robot to the specified distance using a ruler on the ground. When you're + * at the end of the distance, record the ticks to inches multiplier. Feel free to run multiple trials + * and average the results. Then, input the multiplier into the forward ticks to inches in your + * localizer of choice. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @version 1.0, 5/6/2024 + */ +class ForwardTuner extends OpMode { + public static double DISTANCE = 48; + + @Override + public void init() { + follower.update(); + drawCurrent(); + } + + /** This initializes the PoseUpdater as well as the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("Pull your robot forward " + DISTANCE + " inches. Your forward ticks to inches will be shown on the telemetry."); + telemetryM.update(telemetry); + drawCurrent(); + } + + /** + * This updates the robot's pose estimate, and updates the Panels telemetry with the + * calculated multiplier and draws the robot. + */ + @Override + public void loop() { + follower.update(); + + telemetryM.debug("Distance Moved: " + follower.getPose().getX()); + telemetryM.debug("The multiplier will display what your forward ticks to inches should be to scale your current distance to " + DISTANCE + " inches."); + telemetryM.debug("Multiplier: " + (DISTANCE / (follower.getPose().getX() / follower.getPoseTracker().getLocalizer().getForwardMultiplier()))); + telemetryM.update(telemetry); + + drawCurrentAndHistory(); + } +} + +/** + * This is the LateralTuner OpMode. This tracks the strafe movement of the robot and displays the + * necessary ticks to inches multiplier. This displayed multiplier is what's necessary to scale the + * robot's current distance in ticks to the specified distance in inches. So, to use this, run the + * tuner, then pull/push the robot to the specified distance using a ruler on the ground. When you're + * at the end of the distance, record the ticks to inches multiplier. Feel free to run multiple trials + * and average the results. Then, input the multiplier into the strafe ticks to inches in your + * localizer of choice. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @version 2.0, 6/26/2025 + */ +class LateralTuner extends OpMode { + public static double DISTANCE = 48; + + @Override + public void init() { + follower.update(); + drawCurrent(); + } + + /** This initializes the PoseUpdater as well as the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("Pull your robot to the right " + DISTANCE + " inches. Your strafe ticks to inches will be shown on the telemetry."); + telemetryM.update(telemetry); + drawCurrent(); + } + + /** + * This updates the robot's pose estimate, and updates the Panels telemetry with the + * calculated multiplier and draws the robot. + */ + @Override + public void loop() { + follower.update(); + + telemetryM.debug("Distance Moved: " + follower.getPose().getY()); + telemetryM.debug("The multiplier will display what your strafe ticks to inches should be to scale your current distance to " + DISTANCE + " inches."); + telemetryM.debug("Multiplier: " + (DISTANCE / (follower.getPose().getY() / follower.getPoseTracker().getLocalizer().getLateralMultiplier()))); + telemetryM.update(telemetry); + + drawCurrentAndHistory(); + } +} + +/** + * This is the TurnTuner OpMode. This tracks the turning movement of the robot and displays the + * necessary ticks to inches multiplier. This displayed multiplier is what's necessary to scale the + * robot's current angle in ticks to the specified angle in radians. So, to use this, run the + * tuner, then pull/push the robot to the specified angle using a protractor or lines on the ground. + * When you're at the end of the angle, record the ticks to inches multiplier. Feel free to run + * multiple trials and average the results. Then, input the multiplier into the turning ticks to + * radians in your localizer of choice. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @version 1.0, 5/6/2024 + */ +class TurnTuner extends OpMode { + public static double ANGLE = 2 * Math.PI; + + @Override + public void init() { + follower.update(); + drawCurrent(); + } + + /** This initializes the PoseUpdater as well as the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("Turn your robot " + ANGLE + " radians. Your turn ticks to inches will be shown on the telemetry."); + telemetryM.update(telemetry); + + drawCurrent(); + } + + /** + * This updates the robot's pose estimate, and updates the Panels telemetry with the + * calculated multiplier and draws the robot. + */ + @Override + public void loop() { + follower.update(); + + telemetryM.debug("Total Angle: " + follower.getTotalHeading()); + telemetryM.debug("The multiplier will display what your turn ticks to inches should be to scale your current angle to " + ANGLE + " radians."); + telemetryM.debug("Multiplier: " + (ANGLE / (follower.getTotalHeading() / follower.getPoseTracker().getLocalizer().getTurningMultiplier()))); + telemetryM.update(telemetry); + + drawCurrentAndHistory(); + } +} + +/** + * This is the ForwardVelocityTuner autonomous follower OpMode. This runs the robot forwards at max + * power until it reaches some specified distance. It records the most recent velocities, and on + * reaching the end of the distance, it averages them and prints out the velocity obtained. It is + * recommended to run this multiple times on a full battery to get the best results. What this does + * is, when paired with StrafeVelocityTuner, allows FollowerConstants to create a Vector that + * empirically represents the direction your mecanum wheels actually prefer to go in, allowing for + * more accurate following. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @version 1.0, 3/13/2024 + */ +class ForwardVelocityTuner extends OpMode { + private final ArrayList velocities = new ArrayList<>(); + public static double DISTANCE = 48; + public static double RECORD_NUMBER = 10; + + private boolean end; + + @Override + public void init() {} + + /** This initializes the drive motors as well as the cache of velocities and the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("The robot will run at 1 power until it reaches " + DISTANCE + " inches forward."); + telemetryM.debug("Make sure you have enough room, since the robot has inertia after cutting power."); + telemetryM.debug("After running the distance, the robot will cut power from the drivetrain and display the forward velocity."); + telemetryM.debug("Press B on game pad 1 to stop."); + telemetryM.debug("pose", follower.getPose()); + telemetryM.update(telemetry); + + follower.update(); + drawCurrent(); + } + + /** This starts the OpMode by setting the drive motors to run forward at full power. */ + @Override + public void start() { + for (int i = 0; i < RECORD_NUMBER; i++) { + velocities.add(0.0); + } + follower.startTeleopDrive(true); + follower.update(); + end = false; + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing B on + * game pad 1 will stop the OpMode. This continuously records the RECORD_NUMBER most recent + * velocities, and when the robot has run forward enough, these last velocities recorded are + * averaged and printed. + */ + @Override + public void loop() { + if (gamepad1.bWasPressed()) { + stopRobot(); + requestOpModeStop(); + } + + follower.update(); + drawCurrentAndHistory(); + + + if (!end) { + if (Math.abs(follower.getPose().getX()) > DISTANCE) { + end = true; + stopRobot(); + } else { + follower.setTeleOpDrive(1,0,0,true); + //double currentVelocity = Math.abs(follower.getVelocity().getXComponent()); + double currentVelocity = Math.abs(follower.poseTracker.getLocalizer().getVelocity().getX()); + velocities.add(currentVelocity); + velocities.remove(0); + } + } else { + stopRobot(); + double average = 0; + for (double velocity : velocities) { + average += velocity; + } + average /= velocities.size(); + telemetryM.debug("Forward Velocity: " + average); + telemetryM.debug("\n"); + telemetryM.debug("Press A to set the Forward Velocity temporarily (while robot remains on)."); + + for (int i = 0; i < velocities.size(); i++) { + telemetry.addData(String.valueOf(i), velocities.get(i)); + } + + telemetryM.update(telemetry); + telemetry.update(); + + if (gamepad1.aWasPressed()) { + follower.setXVelocity(average); + String message = "XMovement: " + average; + changes.add(message); + } + } + } +} + +/** + * This is the StrafeVelocityTuner autonomous follower OpMode. This runs the robot right at max + * power until it reaches some specified distance. It records the most recent velocities, and on + * reaching the end of the distance, it averages them and prints out the velocity obtained. It is + * recommended to run this multiple times on a full battery to get the best results. What this does + * is, when paired with ForwardVelocityTuner, allows FollowerConstants to create a Vector that + * empirically represents the direction your mecanum wheels actually prefer to go in, allowing for + * more accurate following. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @version 1.0, 3/13/2024 + */ +class LateralVelocityTuner extends OpMode { + private final ArrayList velocities = new ArrayList<>(); + + public static double DISTANCE = 48; + public static double RECORD_NUMBER = 10; + + private boolean end; + + @Override + public void init() {} + + /** + * This initializes the drive motors as well as the cache of velocities and the Panels + * telemetryM. + */ + @Override + public void init_loop() { + telemetryM.debug("The robot will run at 1 power until it reaches " + DISTANCE + " inches to the right."); + telemetryM.debug("Make sure you have enough room, since the robot has inertia after cutting power."); + telemetryM.debug("After running the distance, the robot will cut power from the drivetrain and display the strafe velocity."); + telemetryM.debug("Press B on Gamepad 1 to stop."); + telemetryM.update(telemetry); + + follower.update(); + drawCurrent(); + } + + /** This starts the OpMode by setting the drive motors to run right at full power. */ + @Override + public void start() { + for (int i = 0; i < RECORD_NUMBER; i++) { + velocities.add(0.0); + } + follower.startTeleopDrive(true); + follower.update(); + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing B on + * game pad1 will stop the OpMode. This continuously records the RECORD_NUMBER most recent + * velocities, and when the robot has run sideways enough, these last velocities recorded are + * averaged and printed. + */ + @Override + public void loop() { + if (gamepad1.bWasPressed()) { + stopRobot(); + requestOpModeStop(); + } + + follower.update(); + drawCurrentAndHistory(); + + if (!end) { + if (Math.abs(follower.getPose().getY()) > DISTANCE) { + end = true; + stopRobot(); + } else { + follower.setTeleOpDrive(0,1,0,true); + double currentVelocity = Math.abs(follower.getVelocity().dot(new Vector(1, Math.PI / 2))); + velocities.add(currentVelocity); + velocities.remove(0); + } + } else { + stopRobot(); + double average = 0; + for (double velocity : velocities) { + average += velocity; + } + average /= velocities.size(); + + telemetryM.debug("Strafe Velocity: " + average); + telemetryM.debug("\n"); + telemetryM.debug("Press A to set the Lateral Velocity temporarily (while robot remains on)."); + telemetryM.update(telemetry); + + if (gamepad1.aWasPressed()) { + follower.setYVelocity(average); + String message = "YMovement: " + average; + changes.add(message); + } + } + } +} + +/** + * This is the ForwardZeroPowerAccelerationTuner autonomous follower OpMode. This runs the robot + * forward until a specified velocity is achieved. Then, the robot cuts power to the motors, setting + * them to zero power. The deceleration, or negative acceleration, is then measured until the robot + * stops. The accelerations across the entire time the robot is slowing down is then averaged and + * that number is then printed. This is used to determine how the robot will decelerate in the + * forward direction when power is cut, making the estimations used in the calculations for the + * drive Vector more accurate and giving better braking at the end of Paths. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/13/2024 + */ +class ForwardZeroPowerAccelerationTuner extends OpMode { + private final ArrayList accelerations = new ArrayList<>(); + public static double VELOCITY = 30; + + private double previousVelocity; + private long previousTimeNano; + + private boolean stopping; + private boolean end; + + @Override + public void init() {} + + /** This initializes the drive motors as well as the Panels telemetryM. */ + @Override + public void init_loop() { + telemetryM.debug("The robot will run forward until it reaches " + VELOCITY + " inches per second."); + telemetryM.debug("Then, it will cut power from the drivetrain and roll to a stop."); + telemetryM.debug("Make sure you have enough room."); + telemetryM.debug("After stopping, the forward zero power acceleration (natural deceleration) will be displayed."); + telemetryM.debug("Press B on Gamepad 1 to stop."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + /** This starts the OpMode by setting the drive motors to run forward at full power. */ + @Override + public void start() { + follower.startTeleopDrive(false); + follower.update(); + follower.setTeleOpDrive(1,0,0,true); + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing B on + * game pad 1 will stop the OpMode. When the robot hits the specified velocity, the robot will + * record its deceleration / negative acceleration until it stops. Then, it will average all the + * recorded deceleration / negative acceleration and print that value. + */ + @Override + public void loop() { + if (gamepad1.bWasPressed()) { + stopRobot(); + requestOpModeStop(); + } + + follower.update(); + drawCurrentAndHistory(); + + Vector heading = new Vector(1.0, follower.getPose().getHeading()); + if (!end) { + if (!stopping) { + if (follower.getVelocity().dot(heading) > VELOCITY) { + previousVelocity = follower.getVelocity().dot(heading); + previousTimeNano = System.nanoTime(); + stopping = true; + follower.setTeleOpDrive(0,0,0,true); + } + } else { + double currentVelocity = follower.getVelocity().dot(heading); + accelerations.add((currentVelocity - previousVelocity) / ((System.nanoTime() - previousTimeNano) / Math.pow(10.0, 9))); + previousVelocity = currentVelocity; + previousTimeNano = System.nanoTime(); + if (currentVelocity < follower.getConstraints().getVelocityConstraint()) { + end = true; + } + } + } else { + double average = 0; + for (double acceleration : accelerations) { + average += acceleration; + } + average /= accelerations.size(); + + telemetryM.debug("Forward Zero Power Acceleration (Deceleration): " + average); + telemetryM.debug("\n"); + telemetryM.debug("Press A to set the Forward Zero Power Acceleration temporarily (while robot remains on)."); + telemetryM.update(telemetry); + + if (gamepad1.aWasPressed()) { + follower.getConstants().setForwardZeroPowerAcceleration(average); + String message = "Forward Zero Power Acceleration: " + average; + changes.add(message); + } + } + } +} + +/** + * This is the LateralZeroPowerAccelerationTuner autonomous follower OpMode. This runs the robot + * to the right until a specified velocity is achieved. Then, the robot cuts power to the motors, setting + * them to zero power. The deceleration, or negative acceleration, is then measured until the robot + * stops. The accelerations across the entire time the robot is slowing down is then averaged and + * that number is then printed. This is used to determine how the robot will decelerate in the + * forward direction when power is cut, making the estimations used in the calculations for the + * drive Vector more accurate and giving better braking at the end of Paths. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @author Baron Henderson - 20077 The Indubitables + * @version 1.0, 3/13/2024 + */ +class LateralZeroPowerAccelerationTuner extends OpMode { + private final ArrayList accelerations = new ArrayList<>(); + public static double VELOCITY = 30; + private double previousVelocity; + private long previousTimeNano; + private boolean stopping; + private boolean end; + + @Override + public void init() {} + + /** This initializes the drive motors as well as the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("The robot will run to the right until it reaches " + VELOCITY + " inches per second."); + telemetryM.debug("Then, it will cut power from the drivetrain and roll to a stop."); + telemetryM.debug("Make sure you have enough room."); + telemetryM.debug("After stopping, the lateral zero power acceleration (natural deceleration) will be displayed."); + telemetryM.debug("Press B on game pad 1 to stop."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + /** This starts the OpMode by setting the drive motors to run forward at full power. */ + @Override + public void start() { + follower.startTeleopDrive(false); + follower.update(); + follower.setTeleOpDrive(0,1,0,true); + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing B on + * game pad 1 will stop the OpMode. When the robot hits the specified velocity, the robot will + * record its deceleration / negative acceleration until it stops. Then, it will average all the + * recorded deceleration / negative acceleration and print that value. + */ + @Override + public void loop() { + if (gamepad1.bWasPressed()) { + stopRobot(); + requestOpModeStop(); + } + + follower.update(); + drawCurrentAndHistory(); + + Vector heading = new Vector(1.0, follower.getPose().getHeading() - Math.PI / 2); + if (!end) { + if (!stopping) { + if (Math.abs(follower.getVelocity().dot(heading)) > VELOCITY) { + previousVelocity = Math.abs(follower.getVelocity().dot(heading)); + previousTimeNano = System.nanoTime(); + stopping = true; + follower.setTeleOpDrive(0,0,0,true); + } + } else { + double currentVelocity = Math.abs(follower.getVelocity().dot(heading)); + accelerations.add((currentVelocity - previousVelocity) / ((System.nanoTime() - previousTimeNano) / Math.pow(10.0, 9))); + previousVelocity = currentVelocity; + previousTimeNano = System.nanoTime(); + if (currentVelocity < follower.getConstraints().getVelocityConstraint()) { + end = true; + } + } + } else { + double average = 0; + for (double acceleration : accelerations) { + average += acceleration; + } + average /= accelerations.size(); + + telemetryM.debug("Lateral Zero Power Acceleration (Deceleration): " + average); + telemetryM.debug("\n"); + telemetryM.debug("Press A to set the Lateral Zero Power Acceleration temporarily (while robot remains on)."); + telemetryM.update(telemetry); + + if (gamepad1.aWasPressed()) { + follower.getConstants().setLateralZeroPowerAcceleration(average); + String message = "Lateral Zero Power Acceleration: " + average; + changes.add(message); + } + } + } +} + +/** + * This is the Translational PIDF Tuner OpMode. It will keep the robot in place. + * The user should push the robot laterally to test the PIDF and adjust the PIDF values accordingly. + * + * @author Baron Henderson - 20077 The Indubitables + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/12/2024 + */ +class TranslationalTuner extends OpMode { + public static double DISTANCE = 40; + private boolean forward = true; + + private Path forwards; + private Path backwards; + + @Override + public void init() {} + + /** This initializes the Follower and creates the forward and backward Paths. */ + @Override + public void init_loop() { + telemetryM.debug("This will activate the translational PIDF(s)"); + telemetryM.debug("The robot will try to stay in place while you push it laterally."); + telemetryM.debug("You can adjust the PIDF values to tune the robot's translational PIDF(s)."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void start() { + follower.deactivateAllPIDFs(); + follower.activateTranslational(); + forwards = new Path(new BezierLine(new Pose(0,0), new Pose(DISTANCE,0))); + forwards.setConstantHeadingInterpolation(0); + backwards = new Path(new BezierLine(new Pose(DISTANCE,0), new Pose(0,0))); + backwards.setConstantHeadingInterpolation(0); + follower.followPath(forwards); + } + + /** This runs the OpMode, updating the Follower as well as printing out the debug statements to the Telemetry */ + @Override + public void loop() { + follower.update(); + drawCurrentAndHistory(); + + if (!follower.isBusy()) { + if (forward) { + forward = false; + follower.followPath(backwards); + } else { + forward = true; + follower.followPath(forwards); + } + } + + telemetryM.debug("Push the robot laterally to test the Translational PIDF(s)."); + telemetryM.update(telemetry); + } +} + +/** + * This is the Heading PIDF Tuner OpMode. It will keep the robot in place. + * The user should try to turn the robot to test the PIDF and adjust the PIDF values accordingly. + * It will try to keep the robot at a constant heading while the user tries to turn it. + * + * @author Baron Henderson - 20077 The Indubitables + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/12/2024 + */ +class HeadingTuner extends OpMode { + public static double DISTANCE = 40; + private boolean forward = true; + + private Path forwards; + private Path backwards; + + @Override + public void init() {} + + /** + * This initializes the Follower and creates the forward and backward Paths. Additionally, this + * initializes the Panels telemetry. + */ + @Override + public void init_loop() { + telemetryM.debug("This will activate the heading PIDF(s)."); + telemetryM.debug("The robot will try to stay at a constant heading while you try to turn it."); + telemetryM.debug("You can adjust the PIDF values to tune the robot's heading PIDF(s)."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void start() { + follower.deactivateAllPIDFs(); + follower.activateHeading(); + forwards = new Path(new BezierLine(new Pose(0,0), new Pose(DISTANCE,0))); + forwards.setConstantHeadingInterpolation(0); + backwards = new Path(new BezierLine(new Pose(DISTANCE,0), new Pose(0,0))); + backwards.setConstantHeadingInterpolation(0); + follower.followPath(forwards); + } + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the Panels. + */ + @Override + public void loop() { + follower.update(); + drawCurrentAndHistory(); + + if (!follower.isBusy()) { + if (forward) { + forward = false; + follower.followPath(backwards); + } else { + forward = true; + follower.followPath(forwards); + } + } + + telemetryM.debug("Turn the robot manually to test the Heading PIDF(s)."); + telemetryM.update(telemetry); + } +} + +/** + * This is the Drive PIDF Tuner OpMode. It will run the robot in a straight line going forward and back. + * + * @author Baron Henderson - 20077 The Indubitables + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/12/2024 + */ +class DriveTuner extends OpMode { + public static double DISTANCE = 40; + private boolean forward = true; + + private PathChain forwards; + private PathChain backwards; + + @Override + public void init() {} + + /** + * This initializes the Follower and creates the forward and backward Paths. Additionally, this + * initializes the Panels telemetry. + */ + @Override + public void init_loop() { + telemetryM.debug("This will run the robot in a straight line going " + DISTANCE + "inches forward."); + telemetryM.debug("The robot will go forward and backward continuously along the path."); + telemetryM.debug("Make sure you have enough room."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void start() { + follower.deactivateAllPIDFs(); + follower.activateDrive(); + + forwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(0,0), new Pose(DISTANCE,0))) + .setConstantHeadingInterpolation(0) + .build(); + + backwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(DISTANCE,0), new Pose(0,0))) + .setConstantHeadingInterpolation(0) + .build(); + + follower.followPath(forwards); + } + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the Panels. + */ + @Override + public void loop() { + follower.update(); + drawCurrentAndHistory(); + + if (!follower.isBusy()) { + if (forward) { + forward = false; + follower.followPath(backwards); + } else { + forward = true; + follower.followPath(forwards); + } + } + + telemetryM.debug("Driving forward?: " + forward); + telemetryM.update(telemetry); + } +} + +/** + * This is the Line Test Tuner OpMode. It will drive the robot forward and back + * The user should push the robot laterally and angular to test out the drive, heading, and translational PIDFs. + * + * @author Baron Henderson - 20077 The Indubitables + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/12/2024 + */ +class LineTest extends OpMode { + public static double DISTANCE = 40; + private boolean forward = true; + + private Path forwards; + private Path backwards; + + @Override + public void init() {} + + /** This initializes the Follower and creates the forward and backward Paths. */ + @Override + public void init_loop() { + telemetryM.debug("This will activate all the PIDF(s)"); + telemetryM.debug("The robot will go forward and backward continuously along the path while correcting."); + telemetryM.debug("You can adjust the PIDF values to tune the robot's drive PIDF(s)."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void start() { + follower.activateAllPIDFs(); + forwards = new Path(new BezierLine(new Pose(0,0), new Pose(DISTANCE,0))); + forwards.setConstantHeadingInterpolation(0); + backwards = new Path(new BezierLine(new Pose(DISTANCE,0), new Pose(0,0))); + backwards.setConstantHeadingInterpolation(0); + follower.followPath(forwards); + } + + /** This runs the OpMode, updating the Follower as well as printing out the debug statements to the Telemetry */ + @Override + public void loop() { + follower.update(); + drawCurrentAndHistory(); + + if (!follower.isBusy()) { + if (forward) { + forward = false; + follower.followPath(backwards); + } else { + forward = true; + follower.followPath(forwards); + } + } + + telemetryM.debug("Driving Forward?: " + forward); + telemetryM.update(telemetry); + } +} + +/** + * This is the Centripetal Tuner OpMode. It runs the robot in a specified distance + * forward and to the left. On reaching the end of the forward Path, the robot runs the backward + * Path the same distance back to the start. Rinse and repeat! This is good for testing a variety + * of Vectors, like the drive Vector, the translational Vector, the heading Vector, and the + * centripetal Vector. + * + * @author Baron Henderson - 20077 The Indubitables + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/13/2024 + */ +class CentripetalTuner extends OpMode { + public static double DISTANCE = 20; + private boolean forward = true; + + private Path forwards; + private Path backwards; + + @Override + public void init() {} + + /** + * This initializes the Follower and creates the forward and backward Paths. + * Additionally, this initializes the Panels telemetry. + */ + @Override + public void init_loop() { + telemetryM.debug("This will run the robot in a curve going " + DISTANCE + " inches to the left and the same number of inches forward."); + telemetryM.debug("The robot will go continuously along the path."); + telemetryM.debug("Make sure you have enough room."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void start() { + follower.activateAllPIDFs(); + forwards = new Path(new BezierCurve(new Pose(), new Pose(Math.abs(DISTANCE),0), new Pose(Math.abs(DISTANCE),DISTANCE))); + backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE),DISTANCE), new Pose(Math.abs(DISTANCE),0), new Pose(0,0))); + + backwards.setTangentHeadingInterpolation(); + backwards.reverseHeadingInterpolation(); + + follower.followPath(forwards); + } + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the Panels. + */ + @Override + public void loop() { + follower.update(); + drawCurrentAndHistory(); + if (!follower.isBusy()) { + if (forward) { + forward = false; + follower.followPath(backwards); + } else { + forward = true; + follower.followPath(forwards); + } + } + + telemetryM.debug("Driving away from the origin along the curve?: " + forward); + telemetryM.update(telemetry); + } +} + +/** + * This is the Triangle autonomous OpMode. + * It runs the robot in a triangle, with the starting point being the bottom-middle point. + * + * @author Baron Henderson - 20077 The Indubitables + * @author Samarth Mahapatra - 1002 CircuitRunners Robotics Surge + * @version 1.0, 12/30/2024 + */ +class Triangle extends OpMode { + + private final Pose startPose = new Pose(0, 0, Math.toRadians(0)); + private final Pose interPose = new Pose(24, -24, Math.toRadians(90)); + private final Pose endPose = new Pose(24, 24, Math.toRadians(45)); + + private PathChain triangle; + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the Panels. + */ + @Override + public void loop() { + follower.update(); + drawCurrentAndHistory(); + + if (follower.atParametricEnd()) { + follower.followPath(triangle, true); + } + } + + @Override + public void init() {} + + @Override + public void init_loop() { + telemetryM.debug("This will run in a roughly triangular shape, starting on the bottom-middle point."); + telemetryM.debug("So, make sure you have enough space to the left, front, and right to run the OpMode."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + /** Creates the PathChain for the "triangle".*/ + @Override + public void start() { + follower.setStartingPose(startPose); + + triangle = follower.pathBuilder() + .addPath(new BezierLine(startPose, interPose)) + .setLinearHeadingInterpolation(startPose.getHeading(), interPose.getHeading()) + .addPath(new BezierLine(interPose, endPose)) + .setLinearHeadingInterpolation(interPose.getHeading(), endPose.getHeading()) + .addPath(new BezierLine(endPose, startPose)) + .setLinearHeadingInterpolation(endPose.getHeading(), startPose.getHeading()) + .build(); + + follower.followPath(triangle); + } +} + +/** + * This is the Circle autonomous OpMode. It runs the robot in a PathChain that's actually not quite + * a circle, but some Bezier curves that have control points set essentially in a square. However, + * it turns enough to tune your centripetal force correction and some of your heading. Some lag in + * heading is to be expected. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/12/2024 + */ +class Circle extends OpMode { + public static double RADIUS = 10; + private PathChain circle; + + public void start() { + circle = follower.pathBuilder() + .addPath(new BezierCurve(new Pose(0, 0), new Pose(RADIUS, 0), new Pose(RADIUS, RADIUS))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS)) + .addPath(new BezierCurve(new Pose(RADIUS, RADIUS), new Pose(RADIUS, 2 * RADIUS), new Pose(0, 2 * RADIUS))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS)) + .addPath(new BezierCurve(new Pose(0, 2 * RADIUS), new Pose(-RADIUS, 2 * RADIUS), new Pose(-RADIUS, RADIUS))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS)) + .addPath(new BezierCurve(new Pose(-RADIUS, RADIUS), new Pose(-RADIUS, 0), new Pose(0, 0))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS)) + .build(); + follower.followPath(circle); + } + + @Override + public void init_loop() { + telemetryM.debug("This will run in a roughly circular shape of radius " + RADIUS + ", starting on the right-most edge. "); + telemetryM.debug("So, make sure you have enough space to the left, front, and back to run the OpMode."); + telemetryM.debug("It will also continuously face the center of the circle to test your heading and centripetal correction."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void init() {} + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the FTC Dashboard. + */ + @Override + public void loop() { + follower.update(); + drawCurrentAndHistory(); + + if (follower.atParametricEnd()) { + follower.followPath(circle); + } + } +} + +/** + * This is the Drawing class. It handles the drawing of stuff on Panels Dashboard, like the robot. + * + * @author Lazar - 19234 + * @version 1.1, 5/19/2025 + */ +class Drawing { + public static final double ROBOT_RADIUS = 9; // woah + private static final FieldManager panelsField = PanelsField.INSTANCE.getField(); + + private static final Style robotLook = new Style( + "", "#3F51B5", 0.0 + ); + private static final Style historyLook = new Style( + "", "#4CAF50", 0.0 + ); + + /** + * This prepares Panels Field for using Pedro Offsets + */ + public static void init() { + panelsField.setOffsets(PanelsField.INSTANCE.getPresets().getPEDRO_PATHING()); + } + + /** + * This draws everything that will be used in the Follower's telemetryDebug() method. This takes + * a Follower as an input, so an instance of the DashbaordDrawingHandler class is not needed. + * + * @param follower Pedro Follower instance. + */ + public static void drawDebug(Follower follower) { + if (follower.getCurrentPath() != null) { + drawPath(follower.getCurrentPath(), robotLook); + Pose closestPoint = follower.getPointFromPath(follower.getCurrentPath().getClosestPointTValue()); + drawRobot(new Pose(closestPoint.getX(), closestPoint.getY(), follower.getCurrentPath().getHeadingGoal(follower.getCurrentPath().getClosestPointTValue())), robotLook); + } + drawPoseHistory(follower.getPoseHistory(), historyLook); + drawRobot(follower.getPose(), historyLook); + + sendPacket(); + } + + /** + * This draws a robot at a specified Pose with a specified + * look. The heading is represented as a line. + * + * @param pose the Pose to draw the robot at + * @param style the parameters used to draw the robot with + */ + public static void drawRobot(Pose pose, Style style) { + if (pose == null || Double.isNaN(pose.getX()) || Double.isNaN(pose.getY()) || Double.isNaN(pose.getHeading())) { + return; + } + + panelsField.setStyle(style); + panelsField.moveCursor(pose.getX(), pose.getY()); + panelsField.circle(ROBOT_RADIUS); + + Vector v = pose.getHeadingAsUnitVector(); + v.setMagnitude(v.getMagnitude() * ROBOT_RADIUS); + double x1 = pose.getX() + v.getXComponent() / 2, y1 = pose.getY() + v.getYComponent() / 2; + double x2 = pose.getX() + v.getXComponent(), y2 = pose.getY() + v.getYComponent(); + + panelsField.setStyle(style); + panelsField.moveCursor(x1, y1); + panelsField.line(x2, y2); + } + + /** + * This draws a robot at a specified Pose. The heading is represented as a line. + * + * @param pose the Pose to draw the robot at + */ + public static void drawRobot(Pose pose) { + drawRobot(pose, robotLook); + } + + /** + * This draws a Path with a specified look. + * + * @param path the Path to draw + * @param style the parameters used to draw the Path with + */ + public static void drawPath(Path path, Style style) { + double[][] points = path.getPanelsDrawingPoints(); + + for (int i = 0; i < points[0].length; i++) { + for (int j = 0; j < points.length; j++) { + if (Double.isNaN(points[j][i])) { + points[j][i] = 0; + } + } + } + + panelsField.setStyle(style); + panelsField.moveCursor(points[0][0], points[0][1]); + panelsField.line(points[1][0], points[1][1]); + } + + /** + * This draws all the Paths in a PathChain with a + * specified look. + * + * @param pathChain the PathChain to draw + * @param style the parameters used to draw the PathChain with + */ + public static void drawPath(PathChain pathChain, Style style) { + for (int i = 0; i < pathChain.size(); i++) { + drawPath(pathChain.getPath(i), style); + } + } + + /** + * This draws the pose history of the robot. + * + * @param poseTracker the PoseHistory to get the pose history from + * @param style the parameters used to draw the pose history with + */ + public static void drawPoseHistory(PoseHistory poseTracker, Style style) { + panelsField.setStyle(style); + + int size = poseTracker.getXPositionsArray().length; + for (int i = 0; i < size - 1; i++) { + + panelsField.moveCursor(poseTracker.getXPositionsArray()[i], poseTracker.getYPositionsArray()[i]); + panelsField.line(poseTracker.getXPositionsArray()[i + 1], poseTracker.getYPositionsArray()[i + 1]); + } + } + + /** + * This draws the pose history of the robot. + * + * @param poseTracker the PoseHistory to get the pose history from + */ + public static void drawPoseHistory(PoseHistory poseTracker) { + drawPoseHistory(poseTracker, historyLook); + } + + /** + * This tries to send the current packet to FTControl Panels. + */ + public static void sendPacket() { + panelsField.update(); + } +} \ No newline at end of file diff --git a/build.common.gradle b/build.common.gradle index a1d2fa4ad51c..160f84fffa2b 100644 --- a/build.common.gradle +++ b/build.common.gradle @@ -21,7 +21,7 @@ apply plugin: 'com.android.application' android { - compileSdkVersion 30 + compileSdk 34 signingConfigs { release { diff --git a/build.dependencies.gradle b/build.dependencies.gradle index a8bb721f38d9..653b5f4c53c5 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -1,6 +1,9 @@ repositories { mavenCentral() google() // Needed for androidx + + maven { url= "https://maven.pedropathing.com/" } + maven { url = "https://mymaven.bylazar.com/releases" } } dependencies { @@ -12,6 +15,11 @@ dependencies { implementation 'org.firstinspires.ftc:Hardware:10.3.0' implementation 'org.firstinspires.ftc:FtcCommon:10.3.0' implementation 'org.firstinspires.ftc:Vision:10.3.0' + + implementation 'com.pedropathing:ftc:2.0.0' + implementation 'com.pedropathing:telemetry:0.0.6' + + implementation 'com.bylazar:fullpanels:1.0.2' implementation 'androidx.appcompat:appcompat:1.2.0' } From ddd5f7abbb3b7119f943bb20d985e6241ec4b5c3 Mon Sep 17 00:00:00 2001 From: Baron <126834072+BaronClaps@users.noreply.github.com> Date: Fri, 29 Aug 2025 17:01:29 -0500 Subject: [PATCH 002/152] 2.0.0 - Template Constants --- .../ftc/teamcode/pedroPathing/Constants.java | 34 ++----------------- 1 file changed, 2 insertions(+), 32 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 1b43026ad2ac..6914a4b17daa 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -15,43 +15,13 @@ import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; public class Constants { - - public static FollowerConstants followerConstants = new FollowerConstants() - .centripetalScaling(0.005) - .forwardZeroPowerAcceleration(-41.278) - .lateralZeroPowerAcceleration(-59.7819) - .translationalPIDFCoefficients(new PIDFCoefficients(0.1, 0, 0.01, 0)) - .headingPIDFCoefficients(new PIDFCoefficients(2, 0, 0.1, 0)) - .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0, 0.6, 0)) - .mass(5); - - public static MecanumConstants driveConstants = new MecanumConstants() - .xVelocity(57.8741) - .yVelocity(52.295) - .maxPower(1) - .leftFrontMotorName("lf") - .leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE) - .leftRearMotorDirection(DcMotorSimple.Direction.REVERSE) - .rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD) - .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD) - .motorCachingThreshold(0.01) - .useBrakeModeInTeleOp(false); - - public static PinpointConstants pinpointConstants = new PinpointConstants() - .forwardPodY(-5) - .strafePodX(0.5) - .distanceUnit(DistanceUnit.INCH) - .hardwareMapName("pinpoint") - .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) - .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED); + public static FollowerConstants followerConstants = new FollowerConstants(); public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1); public static Follower createFollower(HardwareMap hardwareMap) { return new FollowerBuilder(followerConstants, hardwareMap) - .mecanumDrivetrain(driveConstants) - .pinpointLocalizer(pinpointConstants) .pathConstraints(pathConstraints) .build(); } -} \ No newline at end of file +} From 50d82039a2a18f938d0bab86fed2493d633bf631 Mon Sep 17 00:00:00 2001 From: Baron <126834072+BaronClaps@users.noreply.github.com> Date: Fri, 29 Aug 2025 17:13:20 -0500 Subject: [PATCH 003/152] 2.0.0 - Template Constants --- .../ftc/teamcode/pedroPathing/Constants.java | 8 -------- 1 file changed, 8 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 6914a4b17daa..fa30420ac7cd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -1,19 +1,11 @@ package org.firstinspires.ftc.teamcode.pedroPathing; -import com.pedropathing.control.FilteredPIDFCoefficients; -import com.pedropathing.control.PIDFCoefficients; import com.pedropathing.follower.Follower; import com.pedropathing.follower.FollowerConstants; import com.pedropathing.ftc.FollowerBuilder; -import com.pedropathing.ftc.drivetrains.MecanumConstants; -import com.pedropathing.ftc.localization.constants.PinpointConstants; import com.pedropathing.paths.PathConstraints; -import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver; -import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; -import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; - public class Constants { public static FollowerConstants followerConstants = new FollowerConstants(); From 16059fb72c7c70bd8812f1d358896be952464597 Mon Sep 17 00:00:00 2001 From: Baron <126834072+BaronClaps@users.noreply.github.com> Date: Fri, 29 Aug 2025 17:33:11 -0500 Subject: [PATCH 004/152] Add Circle to the selector --- .../firstinspires/ftc/teamcode/pedroPathing/Tuning.java | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java index edf090ed237d..be71f39b0ffd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java @@ -68,8 +68,9 @@ public Tuning() { p.add("Centripetal Tuner", CentripetalTuner::new); }); s.folder("Tests", p -> { - p.add("Line Test", LineTest::new); + p.add("Line", Line::new); p.add("Triangle", Triangle::new); + p.add("Circle", Circle::new); }); }); } @@ -935,7 +936,7 @@ public void loop() { * @author Harrison Womack - 10158 Scott's Bots * @version 1.0, 3/12/2024 */ -class LineTest extends OpMode { +class Line extends OpMode { public static double DISTANCE = 40; private boolean forward = true; @@ -1320,4 +1321,4 @@ public static void drawPoseHistory(PoseHistory poseTracker) { public static void sendPacket() { panelsField.update(); } -} \ No newline at end of file +} From aaf40d0685f31793b9e8f36194f1ff060607e08b Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Sep 2025 15:37:21 -0400 Subject: [PATCH 005/152] Added Apriltag code --- .../LOAD-Code/April_Tag_Follow_Test.java | 245 ++++++++++++++++++ .../ftc/teamcode/LOAD-Code/TeleopTest_V1.java | 63 +++++ 2 files changed, 308 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java new file mode 100644 index 000000000000..a1a23efb3379 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java @@ -0,0 +1,245 @@ +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.pedropathing.follower.Follower; +import com.pedropathing.localization.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; +import org.firstinspires.ftc.robotcore.external.navigation.Position; +import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; +import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; +import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +import java.util.List; + + +@TeleOp(name="April_Tag_Follow_Test",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") +public class April_Tag_Follow_Test extends OpMode { + private Follower follower; + private final Pose startPose = new Pose(0,0,0); + + private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera + private Position cameraPosition = new Position(DistanceUnit.INCH, + 0, 0, 0, 0); + private YawPitchRollAngles cameraOrientation = new YawPitchRollAngles(AngleUnit.DEGREES, + 0, -90, 0, 0); + private AprilTagProcessor aprilTag; + private VisionPortal visionPortal; + + /** This method is call once when init is played, it initializes the follower **/ + @Override + public void init() { + follower = new Follower(hardwareMap, FConstants.class, LConstants.class); + follower.setStartingPose(startPose); + + initAprilTag(); + + // Wait for the DS start button to be touched. + telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); + telemetry.addData(">", "Touch START to start OpMode"); + telemetry.update(); + } + + /** This method is called continuously after Init while waiting to be started. **/ + @Override + public void init_loop() { + } + + /** This method is called once at the start of the OpMode. **/ + @Override + public void start() { + follower.startTeleopDrive(); + } + + /** This is the main loop of the opmode and runs continuously after play **/ + @Override + public void loop() { + + + + /* Telemetry Outputs of our Follower */ + telemetry.addData("X", follower.getPose().getX()); + telemetry.addData("Y", follower.getPose().getY()); + telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); + + telemetryAprilTag(); + + // Save CPU resources; can resume streaming when needed. + if (gamepad1.dpad_down) { + visionPortal.stopStreaming(); + } else if (gamepad1.dpad_up) { + visionPortal.resumeStreaming(); + } + + /* Update Telemetry to the Driver Hub */ + telemetry.update(); + + + + } + + /** We do not use this because everything automatically should disable **/ + @Override + public void stop() { + visionPortal.close(); + } + + /** + * Initialize the AprilTag processor. + */ + public void initAprilTag() { + + // Create the AprilTag processor. + aprilTag = new AprilTagProcessor.Builder() + + // The following default settings are available to un-comment and edit as needed. + //.setDrawAxes(false) + //.setDrawCubeProjection(false) + //.setDrawTagOutline(true) + //.setTagFamily(AprilTagProcessor.TagFamily.TAG_36h11) + //.setTagLibrary(AprilTagGameDatabase.getCenterStageTagLibrary()) + //.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES) + .setCameraPose(cameraPosition, cameraOrientation) + + // == CAMERA CALIBRATION == + // If you do not manually specify calibration parameters, the SDK will attempt + // to load a predefined calibration for your camera. + //.setLensIntrinsics(578.272, 578.272, 402.145, 221.506) + // ... these parameters are fx, fy, cx, cy. + + .build(); + + // Adjust Image Decimation to trade-off detection-range for detection-rate. + // eg: Some typical detection data using a Logitech C920 WebCam + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second (default) + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second (default) + // Note: Decimation can be changed on-the-fly to adapt during a match. + //aprilTag.setDecimation(3); + + // Create the vision portal by using a builder. + VisionPortal.Builder builder = new VisionPortal.Builder(); + + // Set the camera (webcam vs. built-in RC phone camera). + if (USE_WEBCAM) { + builder.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")); + } else { + builder.setCamera(BuiltinCameraDirection.BACK); + } + + // Choose a camera resolution. Not all cameras support all resolutions. + //builder.setCameraResolution(new Size(640, 480)); + + // Enable the RC preview (LiveView). Set "false" to omit camera monitoring. + //builder.enableLiveView(true); + + // Set the stream format; MJPEG uses less bandwidth than default YUY2. + //builder.setStreamFormat(VisionPortal.StreamFormat.YUY2); + + // Choose whether or not LiveView stops if no processors are enabled. + // If set "true", monitor shows solid orange screen if no processors enabled. + // If set "false", monitor shows camera view without annotations. + //builder.setAutoStopLiveView(false); + + // Set and enable the processor. + builder.addProcessor(aprilTag); + + // Build the Vision Portal, using the above settings. + visionPortal = builder.build(); + + // Disable or re-enable the aprilTag processor at any time. + //visionPortal.setProcessorEnabled(aprilTag, true); + + } // end method initAprilTag() + + /** + * Add telemetry about AprilTag detections. + */ + public void telemetryAprilTag() { + + List currentDetections = aprilTag.getDetections(); + telemetry.addData("# AprilTags Detected", currentDetections.size()); + + // Step through the list of detections and display info for each one. + for (AprilTagDetection detection : currentDetections) { + if (detection.metadata != null) { + telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name)); + telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", + detection.robotPose.getPosition().x, + detection.robotPose.getPosition().y, + detection.robotPose.getPosition().z)); + telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", + detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES))); + + followTag( + detection.robotPose.getPosition().x, + detection.robotPose.getPosition().y, + detection.robotPose.getPosition().z, + detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES) + ); + + } else { + telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id)); + telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y)); + } + } // end for() loop + + // Add "key" information to telemetry + telemetry.addLine("\nkey:\nXYZ = X (Right), Y (Forward), Z (Up) dist."); + telemetry.addLine("PRY = Pitch, Roll & Yaw (XYZ Rotation)"); + + } // end method telemetryAprilTag() + + public void followTag(double posX, double posY, double posZ, double angX, double angY, double angZ){ + + double distancMarginError = 1; // Measured in Inches + double angleMarginError = 1; // Measured in Degrees + + double FB_Movement = 0; + double SLR_Movement = 0; + double TLR_Movement = 0; + boolean robotCentric = true; + + double followDistance = 18; // Measured in Inches + + if (posZ > followDistance + distancMarginError) { + FB_Movement = 0.1; + }else if (posZ < followDistance - distancMarginError) { + FB_Movement = -0.1; + }else{ + FB_Movement = 0; + } + + if (-posX > 0 + angleMarginError) { + TLR_Movement = 0.1; + }else if (-posX < 0 - angleMarginError) { + TLR_Movement = -0.1; + }else{ + TLR_Movement = 0; + } + + + + /* Update Pedro to move the robot based on: + - Forward/Backward Movement: -gamepad1.left_stick_y + - Left/Right Movement: -gamepad1.left_stick_x + - Turn Left/Right Movement: -gamepad1.right_stick_x + - Robot-Centric Mode: true + */ + + follower.setTeleOpMovementVectors(FB_Movement, -SLR_Movement, TLR_Movement, robotCentric); + follower.update(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java new file mode 100644 index 000000000000..90f7e7663ad3 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java @@ -0,0 +1,63 @@ +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.pedropathing.follower.Follower; +import com.pedropathing.localization.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; +import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; + + +@TeleOp(name="TeleopTest_V1",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") +public class TeleopTest_V1 extends OpMode { + private Follower follower; + private final Pose startPose = new Pose(0,0,0); + + /** This method is call once when init is played, it initializes the follower **/ + @Override + public void init() { + follower = new Follower(hardwareMap, FConstants.class, LConstants.class); + follower.setStartingPose(startPose); + } + + /** This method is called continuously after Init while waiting to be started. **/ + @Override + public void init_loop() { + } + + /** This method is called once at the start of the OpMode. **/ + @Override + public void start() { + follower.startTeleopDrive(); + } + + /** This is the main loop of the opmode and runs continuously after play **/ + @Override + public void loop() { + + /* Update Pedro to move the robot based on: + - Forward/Backward Movement: -gamepad1.left_stick_y + - Left/Right Movement: -gamepad1.left_stick_x + - Turn Left/Right Movement: -gamepad1.right_stick_x + - Robot-Centric Mode: true + */ + + follower.setTeleOpMovementVectors(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); + follower.update(); + + /* Telemetry Outputs of our Follower */ + telemetry.addData("X", follower.getPose().getX()); + telemetry.addData("Y", follower.getPose().getY()); + telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); + + /* Update Telemetry to the Driver Hub */ + telemetry.update(); + + } + + /** We do not use this because everything automatically should disable **/ + @Override + public void stop() { + } +} From 1d5ad7122c821c10b0415eda17bb8e97a6c9d163 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Sep 2025 15:58:33 -0400 Subject: [PATCH 006/152] Began writing constants file --- .../ftc/teamcode/pedroPathing/Constants.java | 31 ++++++++++++++++++- 1 file changed, 30 insertions(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index fa30420ac7cd..bac2e5063508 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -3,17 +3,46 @@ import com.pedropathing.follower.Follower; import com.pedropathing.follower.FollowerConstants; import com.pedropathing.ftc.FollowerBuilder; +import com.pedropathing.ftc.drivetrains.MecanumConstants; +import com.pedropathing.ftc.localization.constants.PinpointConstants; import com.pedropathing.paths.PathConstraints; +import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver; +import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; + public class Constants { - public static FollowerConstants followerConstants = new FollowerConstants(); + public static FollowerConstants followerConstants = new FollowerConstants() + .mass(5); // TODO: Change this to the actual weight of the robot public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1); + public static MecanumConstants driveConstants = new MecanumConstants() + .maxPower(1) + .rightFrontMotorName("FR") + .rightRearMotorName("BR") + .leftRearMotorName("BL") + .leftFrontMotorName("FL") + .leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE) + .leftRearMotorDirection(DcMotorSimple.Direction.REVERSE) + .rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD) + .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD); + + public static PinpointConstants localizerConstants = new PinpointConstants() + .forwardPodY(-1.5) + .strafePodX(6.5) + .distanceUnit(DistanceUnit.INCH) + .hardwareMapName("pinpoint") + .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) + .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED) + .strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD); + public static Follower createFollower(HardwareMap hardwareMap) { return new FollowerBuilder(followerConstants, hardwareMap) .pathConstraints(pathConstraints) + .mecanumDrivetrain(driveConstants) + .pinpointLocalizer(localizerConstants) .build(); } } From 9c92c35ad69b1a977f8984f8cefc55e3ba008622 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Sep 2025 16:07:21 -0400 Subject: [PATCH 007/152] Removed old code --- .../LOAD-Code/April_Tag_Follow_Test.java | 245 ------------------ .../ftc/teamcode/LOAD-Code/TeleopTest_V1.java | 63 ----- 2 files changed, 308 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java deleted file mode 100644 index a1a23efb3379..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.java +++ /dev/null @@ -1,245 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode; - -import com.pedropathing.follower.Follower; -import com.pedropathing.localization.Pose; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; - -import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; -import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; -import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; -import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; -import org.firstinspires.ftc.robotcore.external.navigation.Position; -import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; -import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; -import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; -import org.firstinspires.ftc.vision.VisionPortal; -import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; -import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; - -import java.util.List; - - -@TeleOp(name="April_Tag_Follow_Test",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") -public class April_Tag_Follow_Test extends OpMode { - private Follower follower; - private final Pose startPose = new Pose(0,0,0); - - private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera - private Position cameraPosition = new Position(DistanceUnit.INCH, - 0, 0, 0, 0); - private YawPitchRollAngles cameraOrientation = new YawPitchRollAngles(AngleUnit.DEGREES, - 0, -90, 0, 0); - private AprilTagProcessor aprilTag; - private VisionPortal visionPortal; - - /** This method is call once when init is played, it initializes the follower **/ - @Override - public void init() { - follower = new Follower(hardwareMap, FConstants.class, LConstants.class); - follower.setStartingPose(startPose); - - initAprilTag(); - - // Wait for the DS start button to be touched. - telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch START to start OpMode"); - telemetry.update(); - } - - /** This method is called continuously after Init while waiting to be started. **/ - @Override - public void init_loop() { - } - - /** This method is called once at the start of the OpMode. **/ - @Override - public void start() { - follower.startTeleopDrive(); - } - - /** This is the main loop of the opmode and runs continuously after play **/ - @Override - public void loop() { - - - - /* Telemetry Outputs of our Follower */ - telemetry.addData("X", follower.getPose().getX()); - telemetry.addData("Y", follower.getPose().getY()); - telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); - - telemetryAprilTag(); - - // Save CPU resources; can resume streaming when needed. - if (gamepad1.dpad_down) { - visionPortal.stopStreaming(); - } else if (gamepad1.dpad_up) { - visionPortal.resumeStreaming(); - } - - /* Update Telemetry to the Driver Hub */ - telemetry.update(); - - - - } - - /** We do not use this because everything automatically should disable **/ - @Override - public void stop() { - visionPortal.close(); - } - - /** - * Initialize the AprilTag processor. - */ - public void initAprilTag() { - - // Create the AprilTag processor. - aprilTag = new AprilTagProcessor.Builder() - - // The following default settings are available to un-comment and edit as needed. - //.setDrawAxes(false) - //.setDrawCubeProjection(false) - //.setDrawTagOutline(true) - //.setTagFamily(AprilTagProcessor.TagFamily.TAG_36h11) - //.setTagLibrary(AprilTagGameDatabase.getCenterStageTagLibrary()) - //.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES) - .setCameraPose(cameraPosition, cameraOrientation) - - // == CAMERA CALIBRATION == - // If you do not manually specify calibration parameters, the SDK will attempt - // to load a predefined calibration for your camera. - //.setLensIntrinsics(578.272, 578.272, 402.145, 221.506) - // ... these parameters are fx, fy, cx, cy. - - .build(); - - // Adjust Image Decimation to trade-off detection-range for detection-rate. - // eg: Some typical detection data using a Logitech C920 WebCam - // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second - // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second - // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second (default) - // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second (default) - // Note: Decimation can be changed on-the-fly to adapt during a match. - //aprilTag.setDecimation(3); - - // Create the vision portal by using a builder. - VisionPortal.Builder builder = new VisionPortal.Builder(); - - // Set the camera (webcam vs. built-in RC phone camera). - if (USE_WEBCAM) { - builder.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")); - } else { - builder.setCamera(BuiltinCameraDirection.BACK); - } - - // Choose a camera resolution. Not all cameras support all resolutions. - //builder.setCameraResolution(new Size(640, 480)); - - // Enable the RC preview (LiveView). Set "false" to omit camera monitoring. - //builder.enableLiveView(true); - - // Set the stream format; MJPEG uses less bandwidth than default YUY2. - //builder.setStreamFormat(VisionPortal.StreamFormat.YUY2); - - // Choose whether or not LiveView stops if no processors are enabled. - // If set "true", monitor shows solid orange screen if no processors enabled. - // If set "false", monitor shows camera view without annotations. - //builder.setAutoStopLiveView(false); - - // Set and enable the processor. - builder.addProcessor(aprilTag); - - // Build the Vision Portal, using the above settings. - visionPortal = builder.build(); - - // Disable or re-enable the aprilTag processor at any time. - //visionPortal.setProcessorEnabled(aprilTag, true); - - } // end method initAprilTag() - - /** - * Add telemetry about AprilTag detections. - */ - public void telemetryAprilTag() { - - List currentDetections = aprilTag.getDetections(); - telemetry.addData("# AprilTags Detected", currentDetections.size()); - - // Step through the list of detections and display info for each one. - for (AprilTagDetection detection : currentDetections) { - if (detection.metadata != null) { - telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name)); - telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", - detection.robotPose.getPosition().x, - detection.robotPose.getPosition().y, - detection.robotPose.getPosition().z)); - telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", - detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES))); - - followTag( - detection.robotPose.getPosition().x, - detection.robotPose.getPosition().y, - detection.robotPose.getPosition().z, - detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES) - ); - - } else { - telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id)); - telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y)); - } - } // end for() loop - - // Add "key" information to telemetry - telemetry.addLine("\nkey:\nXYZ = X (Right), Y (Forward), Z (Up) dist."); - telemetry.addLine("PRY = Pitch, Roll & Yaw (XYZ Rotation)"); - - } // end method telemetryAprilTag() - - public void followTag(double posX, double posY, double posZ, double angX, double angY, double angZ){ - - double distancMarginError = 1; // Measured in Inches - double angleMarginError = 1; // Measured in Degrees - - double FB_Movement = 0; - double SLR_Movement = 0; - double TLR_Movement = 0; - boolean robotCentric = true; - - double followDistance = 18; // Measured in Inches - - if (posZ > followDistance + distancMarginError) { - FB_Movement = 0.1; - }else if (posZ < followDistance - distancMarginError) { - FB_Movement = -0.1; - }else{ - FB_Movement = 0; - } - - if (-posX > 0 + angleMarginError) { - TLR_Movement = 0.1; - }else if (-posX < 0 - angleMarginError) { - TLR_Movement = -0.1; - }else{ - TLR_Movement = 0; - } - - - - /* Update Pedro to move the robot based on: - - Forward/Backward Movement: -gamepad1.left_stick_y - - Left/Right Movement: -gamepad1.left_stick_x - - Turn Left/Right Movement: -gamepad1.right_stick_x - - Robot-Centric Mode: true - */ - - follower.setTeleOpMovementVectors(FB_Movement, -SLR_Movement, TLR_Movement, robotCentric); - follower.update(); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java deleted file mode 100644 index 90f7e7663ad3..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.java +++ /dev/null @@ -1,63 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode; - -import com.pedropathing.follower.Follower; -import com.pedropathing.localization.Pose; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; - -import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; -import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; - - -@TeleOp(name="TeleopTest_V1",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") -public class TeleopTest_V1 extends OpMode { - private Follower follower; - private final Pose startPose = new Pose(0,0,0); - - /** This method is call once when init is played, it initializes the follower **/ - @Override - public void init() { - follower = new Follower(hardwareMap, FConstants.class, LConstants.class); - follower.setStartingPose(startPose); - } - - /** This method is called continuously after Init while waiting to be started. **/ - @Override - public void init_loop() { - } - - /** This method is called once at the start of the OpMode. **/ - @Override - public void start() { - follower.startTeleopDrive(); - } - - /** This is the main loop of the opmode and runs continuously after play **/ - @Override - public void loop() { - - /* Update Pedro to move the robot based on: - - Forward/Backward Movement: -gamepad1.left_stick_y - - Left/Right Movement: -gamepad1.left_stick_x - - Turn Left/Right Movement: -gamepad1.right_stick_x - - Robot-Centric Mode: true - */ - - follower.setTeleOpMovementVectors(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); - follower.update(); - - /* Telemetry Outputs of our Follower */ - telemetry.addData("X", follower.getPose().getX()); - telemetry.addData("Y", follower.getPose().getY()); - telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); - - /* Update Telemetry to the Driver Hub */ - telemetry.update(); - - } - - /** We do not use this because everything automatically should disable **/ - @Override - public void stop() { - } -} From 5f2d8a465bf910c382009f5f96640cd78ffe2ef0 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Sep 2025 16:08:46 -0400 Subject: [PATCH 008/152] Added old code back as .txt files --- .../LOAD-Code/April_Tag_Follow_Test.txt | 254 ++++++++++++++++++ .../ftc/teamcode/LOAD-Code/TeleopTest_V1.txt | 63 +++++ 2 files changed, 317 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.txt create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.txt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.txt new file mode 100644 index 000000000000..2ce84250e593 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.txt @@ -0,0 +1,254 @@ + + +import com.pedropathing.follower.Follower; + +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.pedropathing.follower.Follower; +import com.pedropathing.localization.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; +import org.firstinspires.ftc.robotcore.external.navigation.Position; +import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; +import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; +import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +import java.util.List; + + +@TeleOp(name="April_Tag_Follow_Test",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") +public class April_Tag_Follow_Test extends OpMode { + private Follower follower; + private final Pose startPose = new Pose(0,0,0); + + private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera + private Position cameraPosition = new Position(DistanceUnit.INCH, + 0, 0, 0, 0); + private YawPitchRollAngles cameraOrientation = new YawPitchRollAngles(AngleUnit.DEGREES, + 0, -90, 0, 0); + private AprilTagProcessor aprilTag; + private VisionPortal visionPortal; + + /** This method is call once when init is played, it initializes the follower **/ + @Override + public void init() { + follower = new Follower(hardwareMap, FConstants.class, LConstants.class); + follower.setStartingPose(startPose); + + initAprilTag(); + + // Wait for the DS start button to be touched. + telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); + telemetry.addData(">", "Touch START to start OpMode"); + telemetry.update(); + } + + /** This method is called continuously after Init while waiting to be started. **/ + @Override + public void init_loop() { + } + + /** This method is called once at the start of the OpMode. **/ + @Override + public void start() { + follower.startTeleopDrive(); + } + + /** This is the main loop of the opmode and runs continuously after play **/ + @Override + public void loop() { + + + + /* Telemetry Outputs of our Follower */ + telemetry.addData("X", follower.getPose().getX()); + telemetry.addData("Y", follower.getPose().getY()); + telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); + + telemetryAprilTag(); + + // Save CPU resources; can resume streaming when needed. + if (gamepad1.dpad_down) { + visionPortal.stopStreaming(); + } else if (gamepad1.dpad_up) { + visionPortal.resumeStreaming(); + } + + /* Update Telemetry to the Driver Hub */ + telemetry.update(); + + + + } + + /** We do not use this because everything automatically should disable **/ + @Override + public void stop() { + visionPortal.close(); + } + + /** + * Initialize the AprilTag processor. + */ + public void initAprilTag() { + + // Create the AprilTag processor. + aprilTag = new AprilTagProcessor.Builder() + + // The following default settings are available to un-comment and edit as needed. + //.setDrawAxes(false) + //.setDrawCubeProjection(false) + //.setDrawTagOutline(true) + //.setTagFamily(AprilTagProcessor.TagFamily.TAG_36h11) + //.setTagLibrary(AprilTagGameDatabase.getCenterStageTagLibrary()) + //.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES) + .setCameraPose(cameraPosition, cameraOrientation) + + // == CAMERA CALIBRATION == + // If you do not manually specify calibration parameters, the SDK will attempt + // to load a predefined calibration for your camera. + //.setLensIntrinsics(578.272, 578.272, 402.145, 221.506) + // ... these parameters are fx, fy, cx, cy. + + .build(); + + // Adjust Image Decimation to trade-off detection-range for detection-rate. + // eg: Some typical detection data using a Logitech C920 WebCam + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second (default) + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second (default) + // Note: Decimation can be changed on-the-fly to adapt during a match. + //aprilTag.setDecimation(3); + + // Create the vision portal by using a builder. + VisionPortal.Builder builder = new VisionPortal.Builder(); + + // Set the camera (webcam vs. built-in RC phone camera). + if (USE_WEBCAM) { + builder.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")); + } else { + builder.setCamera(BuiltinCameraDirection.BACK); + } + + // Choose a camera resolution. Not all cameras support all resolutions. + //builder.setCameraResolution(new Size(640, 480)); + + // Enable the RC preview (LiveView). Set "false" to omit camera monitoring. + //builder.enableLiveView(true); + + // Set the stream format; MJPEG uses less bandwidth than default YUY2. + //builder.setStreamFormat(VisionPortal.StreamFormat.YUY2); + + // Choose whether or not LiveView stops if no processors are enabled. + // If set "true", monitor shows solid orange screen if no processors enabled. + // If set "false", monitor shows camera view without annotations. + //builder.setAutoStopLiveView(false); + + // Set and enable the processor. + builder.addProcessor(aprilTag); + + // Build the Vision Portal, using the above settings. + visionPortal = builder.build(); + + // Disable or re-enable the aprilTag processor at any time. + //visionPortal.setProcessorEnabled(aprilTag, true); + + } // end method initAprilTag() + + /** + * Add telemetry about AprilTag detections. + */ + public void telemetryAprilTag() { + + List currentDetections = aprilTag.getDetections(); + telemetry.addData("# AprilTags Detected", currentDetections.size()); + + // Step through the list of detections and display info for each one. + for (AprilTagDetection detection : currentDetections) { + if (detection.metadata != null) { + telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name)); + telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", + detection.robotPose.getPosition().x, + detection.robotPose.getPosition().y, + detection.robotPose.getPosition().z)); + telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", + detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES))); + + followTag( + detection.robotPose.getPosition().x, + detection.robotPose.getPosition().y, + detection.robotPose.getPosition().z, + detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES) + ); + + } else { + telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id)); + telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y)); + } + } // end for() loop + + // Add "key" information to telemetry + telemetry.addLine("\nkey:\nXYZ = X (Right), Y (Forward), Z (Up) dist."); + telemetry.addLine("PRY = Pitch, Roll & Yaw (XYZ Rotation)"); + + } // end method telemetryAprilTag() + + public void followTag(double posX, double posY, double posZ, double angX, double angY, double angZ){ + + double distancMarginError = 1; // Measured in Inches + double angleMarginError = 1; // Measured in Degrees + + double FB_Movement = 0; + double SLR_Movement = 0; + double TLR_Movement = 0; + boolean robotCentric = true; + + double followDistance = 18; // Measured in Inches + + if (posZ > followDistance + distancMarginError) { + FB_Movement = 0.1; + }else if (posZ < followDistance - distancMarginError) { + FB_Movement = -0.1; + }else{ + FB_Movement = 0; + } + + if (-posX > 0 + angleMarginError) { + TLR_Movement = 0.1; + }else if (-posX < 0 - angleMarginError) { + TLR_Movement = -0.1; + }else{ + TLR_Movement = 0; + } + + + + /* Update Pedro to move the robot based on: + - Forward/Backward Movement: -gamepad1.left_stick_y + - Left/Right Movement: -gamepad1.left_stick_x + - Turn Left/Right Movement: -gamepad1.right_stick_x + - Robot-Centric Mode: true + */ + + follower.setTeleOpMovementVectors(FB_Movement, -SLR_Movement, TLR_Movement, robotCentric); + follower.update(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt new file mode 100644 index 000000000000..90f7e7663ad3 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt @@ -0,0 +1,63 @@ +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.pedropathing.follower.Follower; +import com.pedropathing.localization.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; +import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; + + +@TeleOp(name="TeleopTest_V1",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") +public class TeleopTest_V1 extends OpMode { + private Follower follower; + private final Pose startPose = new Pose(0,0,0); + + /** This method is call once when init is played, it initializes the follower **/ + @Override + public void init() { + follower = new Follower(hardwareMap, FConstants.class, LConstants.class); + follower.setStartingPose(startPose); + } + + /** This method is called continuously after Init while waiting to be started. **/ + @Override + public void init_loop() { + } + + /** This method is called once at the start of the OpMode. **/ + @Override + public void start() { + follower.startTeleopDrive(); + } + + /** This is the main loop of the opmode and runs continuously after play **/ + @Override + public void loop() { + + /* Update Pedro to move the robot based on: + - Forward/Backward Movement: -gamepad1.left_stick_y + - Left/Right Movement: -gamepad1.left_stick_x + - Turn Left/Right Movement: -gamepad1.right_stick_x + - Robot-Centric Mode: true + */ + + follower.setTeleOpMovementVectors(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); + follower.update(); + + /* Telemetry Outputs of our Follower */ + telemetry.addData("X", follower.getPose().getX()); + telemetry.addData("Y", follower.getPose().getY()); + telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); + + /* Update Telemetry to the Driver Hub */ + telemetry.update(); + + } + + /** We do not use this because everything automatically should disable **/ + @Override + public void stop() { + } +} From 8d8e33b940a22c4e5b51f57e74a198cf1f6ab9a8 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 2 Sep 2025 17:46:08 -0400 Subject: [PATCH 009/152] Added new Teleop that is current with PedroPathing v2.0 --- .../ftc/teamcode/LOAD-Code/TeleopTest_V2.java | 48 +++++++++++++++++++ 1 file changed, 48 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java new file mode 100644 index 000000000000..4c9d15579e6e --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java @@ -0,0 +1,48 @@ +class TeleopTest_V2 extends OpMode { + + double leftTriggerMult = 0.33; + double rightTriggerMult = 1; + double defaultMult = 0.66; + double currentMult = defaultMult; + + @Override + public void init() {} + + /** This initializes the PoseUpdater, the mecanum drive motors, and the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("This will print your robot's position to telemetry while " + + "allowing robot control through a basic mecanum drive on gamepad 1."); + telemetryM.update(telemetry); + follower.update(); + drawCurrent(); + } + + @Override + public void start() { + follower.startTeleopDrive(); + follower.update(); + } + + /** + * This updates the robot's pose estimate, the simple mecanum drive, and updates the + * Panels telemetry with the robot's position as well as draws the robot's position. + */ + @Override + public void loop() { + + currentMult = 1; + + + follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, true); + follower.update(); + + telemetryM.debug("x:" + follower.getPose().getX()); + telemetryM.debug("y:" + follower.getPose().getY()); + telemetryM.debug("heading:" + follower.getPose().getHeading()); + telemetryM.debug("total heading:" + follower.getTotalHeading()); + telemetryM.update(telemetry); + + drawCurrentAndHistory(); + } +} \ No newline at end of file From 50e5d4ff62c08218d0759d7dd61ab71ef53d4d0f Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Sep 2025 17:49:26 -0400 Subject: [PATCH 010/152] Tuning work --- .../ftc/teamcode/pedroPathing/Constants.java | 14 +++++++++++--- .../ftc/teamcode/pedroPathing/Tuning.java | 4 ++-- 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index bac2e5063508..0e6a0566ee88 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -14,7 +14,13 @@ public class Constants { public static FollowerConstants followerConstants = new FollowerConstants() - .mass(5); // TODO: Change this to the actual weight of the robot + .mass(5) // TODO: Change this to the actual weight of the robot + .forwardZeroPowerAcceleration(-45.7735) + .lateralZeroPowerAcceleration(-53.7000) + // Set following parameters to true to enable dual PID + .useSecondaryTranslationalPIDF(false) + .useSecondaryHeadingPIDF(false) + .useSecondaryDrivePIDF(false); public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1); @@ -27,7 +33,9 @@ public class Constants { .leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE) .leftRearMotorDirection(DcMotorSimple.Direction.REVERSE) .rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD) - .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD); + .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD) + .xVelocity(59.3402) + .yVelocity(46.4157); public static PinpointConstants localizerConstants = new PinpointConstants() .forwardPodY(-1.5) @@ -35,7 +43,7 @@ public class Constants { .distanceUnit(DistanceUnit.INCH) .hardwareMapName("pinpoint") .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) - .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED) + .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD) .strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD); public static Follower createFollower(HardwareMap hardwareMap) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java index be71f39b0ffd..68a4b06dd3d6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java @@ -322,7 +322,7 @@ public void loop() { */ class ForwardVelocityTuner extends OpMode { private final ArrayList velocities = new ArrayList<>(); - public static double DISTANCE = 48; + public static double DISTANCE = 96; public static double RECORD_NUMBER = 10; private boolean end; @@ -428,7 +428,7 @@ public void loop() { class LateralVelocityTuner extends OpMode { private final ArrayList velocities = new ArrayList<>(); - public static double DISTANCE = 48; + public static double DISTANCE = 96; public static double RECORD_NUMBER = 10; private boolean end; From 1d15fa7493b69ea22f87a980ea77699bdb4af171 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Sep 2025 18:42:32 -0400 Subject: [PATCH 011/152] Fixed TeleopTest --- .../ftc/teamcode/LOAD-Code/TeleopTest_V1.txt | 63 ------------------ .../ftc/teamcode/LOAD-Code/TeleopTest_V2.java | 48 -------------- .../April_Tag_Follow_Test.txt | 0 .../ftc/teamcode/LOADCode/TeleopTest_V1.java | 66 +++++++++++++++++++ 4 files changed, 66 insertions(+), 111 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/{LOAD-Code => LOADCode}/April_Tag_Follow_Test.txt (100%) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt deleted file mode 100644 index 90f7e7663ad3..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V1.txt +++ /dev/null @@ -1,63 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode; - -import com.pedropathing.follower.Follower; -import com.pedropathing.localization.Pose; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; - -import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; -import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; - - -@TeleOp(name="TeleopTest_V1",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") -public class TeleopTest_V1 extends OpMode { - private Follower follower; - private final Pose startPose = new Pose(0,0,0); - - /** This method is call once when init is played, it initializes the follower **/ - @Override - public void init() { - follower = new Follower(hardwareMap, FConstants.class, LConstants.class); - follower.setStartingPose(startPose); - } - - /** This method is called continuously after Init while waiting to be started. **/ - @Override - public void init_loop() { - } - - /** This method is called once at the start of the OpMode. **/ - @Override - public void start() { - follower.startTeleopDrive(); - } - - /** This is the main loop of the opmode and runs continuously after play **/ - @Override - public void loop() { - - /* Update Pedro to move the robot based on: - - Forward/Backward Movement: -gamepad1.left_stick_y - - Left/Right Movement: -gamepad1.left_stick_x - - Turn Left/Right Movement: -gamepad1.right_stick_x - - Robot-Centric Mode: true - */ - - follower.setTeleOpMovementVectors(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); - follower.update(); - - /* Telemetry Outputs of our Follower */ - telemetry.addData("X", follower.getPose().getX()); - telemetry.addData("Y", follower.getPose().getY()); - telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); - - /* Update Telemetry to the Driver Hub */ - telemetry.update(); - - } - - /** We do not use this because everything automatically should disable **/ - @Override - public void stop() { - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java deleted file mode 100644 index 4c9d15579e6e..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/TeleopTest_V2.java +++ /dev/null @@ -1,48 +0,0 @@ -class TeleopTest_V2 extends OpMode { - - double leftTriggerMult = 0.33; - double rightTriggerMult = 1; - double defaultMult = 0.66; - double currentMult = defaultMult; - - @Override - public void init() {} - - /** This initializes the PoseUpdater, the mecanum drive motors, and the Panels telemetry. */ - @Override - public void init_loop() { - telemetryM.debug("This will print your robot's position to telemetry while " - + "allowing robot control through a basic mecanum drive on gamepad 1."); - telemetryM.update(telemetry); - follower.update(); - drawCurrent(); - } - - @Override - public void start() { - follower.startTeleopDrive(); - follower.update(); - } - - /** - * This updates the robot's pose estimate, the simple mecanum drive, and updates the - * Panels telemetry with the robot's position as well as draws the robot's position. - */ - @Override - public void loop() { - - currentMult = 1; - - - follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, true); - follower.update(); - - telemetryM.debug("x:" + follower.getPose().getX()); - telemetryM.debug("y:" + follower.getPose().getY()); - telemetryM.debug("heading:" + follower.getPose().getHeading()); - telemetryM.debug("total heading:" + follower.getTotalHeading()); - telemetryM.update(telemetry); - - drawCurrentAndHistory(); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.txt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/April_Tag_Follow_Test.txt similarity index 100% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOAD-Code/April_Tag_Follow_Test.txt rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/April_Tag_Follow_Test.txt diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java new file mode 100644 index 000000000000..0fede74fba61 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java @@ -0,0 +1,66 @@ +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; + +@TeleOp(name = "Example Robot-Centric TeleOp", group = "Examples") +public class TeleopTest_V1 extends OpMode { + private Follower follower; + /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ + private final Pose startPose = new Pose(60,96, Math.toRadians(-90)); + private final Pose scorePose = new Pose(16,128, Math.toRadians(-45)); + private boolean prevYPressed; + + /** This method is called once when init is pressed and initializes the follower **/ + @Override + public void init() { + // Initializing the follower and setting its starting position. + follower = Constants.createFollower(hardwareMap); + follower.setStartingPose(startPose); + } + + /** This method is called once at the start of the OpMode. **/ + @Override + public void start() { + // Calling this method is necessary at the start of your TeleOp OpMode. + follower.startTeleopDrive(); + } + + /** This is the main loop of the OpMode and runs continuously after pressing play **/ + @Override + public void loop() { + /* + * A rising edge detector to check if the y button was pressed. + * If the y button was pressed, relocalize the robot. + */ + if (gamepad1.y && !prevYPressed) { + // Resetting the position of the robot + follower.setStartingPose(new Pose(9, 111, Math.toRadians(0))); + } + + // Update robot movement based on gamepad inputs + /* Update Pedro to move the robot based on: + * Forward/Backward Movement: -gamepad1.left_stick_y + * Left/Right Movement: -gamepad1.left_stick_x + * Turn Left/Right Movement: -gamepad1.right_stick_x + * Robot-Centric Mode: true + */ + // Loop robot movement and odometry values + follower.update(); + + // Telemetry Outputs of the Follower + telemetry.addData("X", follower.getPose().getX()); + telemetry.addData("Y", follower.getPose().getY()); + telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); + + // Update Telemetry to the Driver Hub + telemetry.update(); + + // Updating the status of the gamepad buttons + prevYPressed = gamepad1.y; + } +} \ No newline at end of file From c8e9084841bb71be9cca213d54dfe44a1a122ce3 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Sat, 6 Sep 2025 21:39:29 -0400 Subject: [PATCH 012/152] Fixed TeleopTest_V1.java (I hope) --- .../org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java | 1 + 1 file changed, 1 insertion(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java index 0fede74fba61..71f07a1ab24f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java @@ -28,6 +28,7 @@ public void init() { public void start() { // Calling this method is necessary at the start of your TeleOp OpMode. follower.startTeleopDrive(); + follower.update(); } /** This is the main loop of the OpMode and runs continuously after pressing play **/ From 088e43c8f12a110cc9fa251fa33d62d1cc765173 Mon Sep 17 00:00:00 2001 From: Daniel <141444315+Professor348@users.noreply.github.com> Date: Tue, 9 Sep 2025 08:56:08 -0400 Subject: [PATCH 013/152] Updated to Pedro 2.0.1 --- build.dependencies.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.dependencies.gradle b/build.dependencies.gradle index 868153f675d9..9eb983998037 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -16,7 +16,7 @@ dependencies { implementation 'org.firstinspires.ftc:Vision:11.0.0' implementation 'androidx.appcompat:appcompat:1.2.0' - implementation 'com.pedropathing:ftc:2.0.0' + implementation 'com.pedropathing:ftc:2.0.1' implementation 'com.pedropathing:telemetry:0.0.6' implementation 'com.bylazar:fullpanels:1.0.0' } From 821fe67e6035e940f3b55598c2047e50cd9c0213 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Sat, 13 Sep 2025 09:52:45 -0400 Subject: [PATCH 014/152] Tuned Pedropathing --- .../ftc/teamcode/LOADCode/TeleopTest_V1.java | 29 +++++++++---------- .../ftc/teamcode/pedroPathing/Constants.java | 13 +++++++-- .../ftc/teamcode/pedroPathing/Tuning.java | 4 +-- 3 files changed, 26 insertions(+), 20 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java index 0fede74fba61..57096c9f9622 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java @@ -1,19 +1,23 @@ package org.firstinspires.ftc.teamcode.LOADCode; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.follower; + +import com.bylazar.configurables.annotations.IgnoreConfigurable; +import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @TeleOp(name = "Example Robot-Centric TeleOp", group = "Examples") public class TeleopTest_V1 extends OpMode { - private Follower follower; + public static Follower follower; + @IgnoreConfigurable + static TelemetryManager telemetryM; /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ - private final Pose startPose = new Pose(60,96, Math.toRadians(-90)); - private final Pose scorePose = new Pose(16,128, Math.toRadians(-45)); - private boolean prevYPressed; + private final Pose startPose = new Pose(60,96, Math.toRadians(0)); /** This method is called once when init is pressed and initializes the follower **/ @Override @@ -21,6 +25,7 @@ public void init() { // Initializing the follower and setting its starting position. follower = Constants.createFollower(hardwareMap); follower.setStartingPose(startPose); + follower.update(); } /** This method is called once at the start of the OpMode. **/ @@ -28,20 +33,12 @@ public void init() { public void start() { // Calling this method is necessary at the start of your TeleOp OpMode. follower.startTeleopDrive(); + follower.update(); } /** This is the main loop of the OpMode and runs continuously after pressing play **/ @Override public void loop() { - /* - * A rising edge detector to check if the y button was pressed. - * If the y button was pressed, relocalize the robot. - */ - if (gamepad1.y && !prevYPressed) { - // Resetting the position of the robot - follower.setStartingPose(new Pose(9, 111, Math.toRadians(0))); - } - // Update robot movement based on gamepad inputs /* Update Pedro to move the robot based on: * Forward/Backward Movement: -gamepad1.left_stick_y @@ -49,18 +46,18 @@ public void loop() { * Turn Left/Right Movement: -gamepad1.right_stick_x * Robot-Centric Mode: true */ + follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); // Loop robot movement and odometry values follower.update(); // Telemetry Outputs of the Follower telemetry.addData("X", follower.getPose().getX()); telemetry.addData("Y", follower.getPose().getY()); - telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); + telemetry.addData("Heading in Degrees", Math.toDegrees(1)); // Update Telemetry to the Driver Hub telemetry.update(); // Updating the status of the gamepad buttons - prevYPressed = gamepad1.y; } } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 0e6a0566ee88..4156b984b2f3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -1,5 +1,7 @@ package org.firstinspires.ftc.teamcode.pedroPathing; +import com.pedropathing.control.FilteredPIDFCoefficients; +import com.pedropathing.control.PIDFCoefficients; import com.pedropathing.follower.Follower; import com.pedropathing.follower.FollowerConstants; import com.pedropathing.ftc.FollowerBuilder; @@ -20,9 +22,16 @@ public class Constants { // Set following parameters to true to enable dual PID .useSecondaryTranslationalPIDF(false) .useSecondaryHeadingPIDF(false) - .useSecondaryDrivePIDF(false); + .useSecondaryDrivePIDF(false) + .translationalPIDFCoefficients(new PIDFCoefficients(.1, 0, 0.01, 0.05)) + .headingPIDFCoefficients(new PIDFCoefficients(3, 0.3, 0.2, 0.05)) + .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.3, 0.1, 0.01, 0.6, 0.6)); - public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1); + public static PathConstraints pathConstraints = new PathConstraints( + 0.99, + 100, + 3, + 1); public static MecanumConstants driveConstants = new MecanumConstants() .maxPower(1) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java index 68a4b06dd3d6..0a5b40ab7dad 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java @@ -1188,10 +1188,10 @@ class Drawing { private static final FieldManager panelsField = PanelsField.INSTANCE.getField(); private static final Style robotLook = new Style( - "", "#3F51B5", 0.0 + "", "#3F51B5", 0.5 ); private static final Style historyLook = new Style( - "", "#4CAF50", 0.0 + "", "#4CAF50", 0.5 ); /** From 587ceea78f2eefc1d35ec6be6c28b98f12adb72e Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Sat, 13 Sep 2025 10:12:07 -0400 Subject: [PATCH 015/152] Added program to chase an aprilTag and tried to modify it to use pedropathing controls --- .../LOADCode/AutoDriveToAprilTagOmni.java | 322 ++++++++++++++++++ .../ftc/teamcode/LOADCode/Chase_AprilTag.java | 225 ++++++++++++ 2 files changed, 547 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java new file mode 100644 index 000000000000..523776cd3a31 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java @@ -0,0 +1,322 @@ +/* Copyright (c) 2023 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.qualcomm.robotcore.eventloop.opmode.Disabled; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.util.Range; + +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +import java.util.List; +import java.util.concurrent.TimeUnit; + +/* + * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. + * The code assumes a Holonomic (Mecanum or X Drive) Robot. + * + * For an introduction to AprilTags, see the ftc-docs link below: + * https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html + * + * When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera. + * This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below. + * https://ftc-docs.firstinspires.org/apriltag-detection-values + * + * The drive goal is to rotate to keep the Tag centered in the camera, while strafing to be directly in front of the tag, and + * driving towards the tag to achieve the desired distance. + * To reduce any motion blur (which will interrupt the detection process) the Camera exposure is reduced to a very low value (5mS) + * You can determine the best Exposure and Gain values by using the ConceptAprilTagOptimizeExposure OpMode in this Samples folder. + * + * The code assumes a Robot Configuration with motors named: front_left_drive and front_right_drive, back_left_drive and back_right_drive. + * The motor directions must be set so a positive power goes forward on all wheels. + * This sample assumes that the current game AprilTag Library (usually for the current season) is being loaded by default, + * so you should choose to approach a valid tag ID. + * + * Under manual control, the left stick will move forward/back & left/right. The right stick will rotate the robot. + * Manually drive the robot until it displays Target data on the Driver Station. + * + * Press and hold the *Left Bumper* to enable the automatic "Drive to target" mode. + * Release the Left Bumper to return to manual driving mode. + * + * Under "Drive To Target" mode, the robot has three goals: + * 1) Turn the robot to always keep the Tag centered on the camera frame. (Use the Target Bearing to turn the robot.) + * 2) Strafe the robot towards the centerline of the Tag, so it approaches directly in front of the tag. (Use the Target Yaw to strafe the robot) + * 3) Drive towards the Tag to get to the desired distance. (Use Tag Range to drive the robot forward/backward) + * + * Use DESIRED_DISTANCE to set how close you want the robot to get to the target. + * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. + * + * Use Android Studio to Copy this Class, and Paste it into the TeamCode/src/main/java/org/firstinspires/ftc/teamcode folder. + * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list. + * + */ + +@TeleOp(name="Omni Drive To AprilTag", group = "Concept") +@Disabled +public class AutoDriveToAprilTagOmni extends LinearOpMode +{ + // Adjust these numbers to suit your robot. + final double DESIRED_DISTANCE = 12.0; // this is how close the camera should get to the target (inches) + + // Set the GAIN constants to control the relationship between the measured position error, and how much power is + // applied to the drive motors to correct the error. + // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. + final double SPEED_GAIN = 0.02 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) + final double STRAFE_GAIN = 0.015 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) + final double TURN_GAIN = 0.01 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + + final double MAX_AUTO_SPEED = 0.5; // Clip the approach speed to this max value (adjust for your robot) + final double MAX_AUTO_STRAFE= 0.5; // Clip the strafing speed to this max value (adjust for your robot) + final double MAX_AUTO_TURN = 0.3; // Clip the turn speed to this max value (adjust for your robot) + + private DcMotor frontLeftDrive = null; // Used to control the left front drive wheel + private DcMotor frontRightDrive = null; // Used to control the right front drive wheel + private DcMotor backLeftDrive = null; // Used to control the left back drive wheel + private DcMotor backRightDrive = null; // Used to control the right back drive wheel + + private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera + private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. + private VisionPortal visionPortal; // Used to manage the video source. + private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. + private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag + + @Override public void runOpMode() + { + boolean targetFound = false; // Set to true when an AprilTag target is detected + double drive = 0; // Desired forward power/speed (-1 to +1) + double strafe = 0; // Desired strafe power/speed (-1 to +1) + double turn = 0; // Desired turning power/speed (-1 to +1) + + // Initialize the Apriltag Detection process + initAprilTag(); + + // Initialize the hardware variables. Note that the strings used here as parameters + // to 'get' must match the names assigned during the robot configuration. + // step (using the FTC Robot Controller app on the phone). + frontLeftDrive = hardwareMap.get(DcMotor.class, "FL"); + frontRightDrive = hardwareMap.get(DcMotor.class, "FR"); + backLeftDrive = hardwareMap.get(DcMotor.class, "BL"); + backRightDrive = hardwareMap.get(DcMotor.class, "BR"); + + // To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions. + // When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive. + // Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips + frontLeftDrive.setDirection(DcMotor.Direction.REVERSE); + backLeftDrive.setDirection(DcMotor.Direction.REVERSE); + frontRightDrive.setDirection(DcMotor.Direction.FORWARD); + backRightDrive.setDirection(DcMotor.Direction.FORWARD); + + if (USE_WEBCAM) + setManualExposure(6, 250); // Use low exposure time to reduce motion blur + + // Wait for driver to press start + telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); + telemetry.addData(">", "Touch START to start OpMode"); + telemetry.update(); + waitForStart(); + + while (opModeIsActive()) + { + targetFound = false; + desiredTag = null; + + // Step through the list of detected tags and look for a matching tag + List currentDetections = aprilTag.getDetections(); + for (AprilTagDetection detection : currentDetections) { + // Look to see if we have size info on this tag. + if (detection.metadata != null) { + // Check to see if we want to track towards this tag. + if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) { + // Yes, we want to use this tag. + targetFound = true; + desiredTag = detection; + break; // don't look any further. + } else { + // This tag is in the library, but we do not want to track it right now. + telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id); + } + } else { + // This tag is NOT in the library, so we don't have enough information to track to it. + telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id); + } + } + + // Tell the driver what we see, and what to do. + if (targetFound) { + telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n"); + telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); + telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); + telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); + telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); + } else { + telemetry.addData("\n>","Drive using joysticks to find valid target\n"); + } + + // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . + if (gamepad1.left_bumper && targetFound) { + + // Determine heading, range and Yaw (tag image rotation) error so we can use them to control the robot automatically. + double rangeError = (desiredTag.ftcPose.range - DESIRED_DISTANCE); + double headingError = desiredTag.ftcPose.bearing; + double yawError = desiredTag.ftcPose.yaw; + + // Use the speed and turn "gains" to calculate how we want the robot to move. + drive = Range.clip(rangeError * SPEED_GAIN, -MAX_AUTO_SPEED, MAX_AUTO_SPEED); + turn = Range.clip(headingError * TURN_GAIN, -MAX_AUTO_TURN, MAX_AUTO_TURN) ; + strafe = Range.clip(-yawError * STRAFE_GAIN, -MAX_AUTO_STRAFE, MAX_AUTO_STRAFE); + + telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + } else { + + // drive using manual POV Joystick mode. Slow things down to make the robot more controlable. + drive = -gamepad1.left_stick_y / 2.0; // Reduce drive rate to 50%. + strafe = -gamepad1.left_stick_x / 2.0; // Reduce strafe rate to 50%. + turn = -gamepad1.right_stick_x / 3.0; // Reduce turn rate to 33%. + telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + } + telemetry.update(); + + // Apply desired axes motions to the drivetrain. + moveRobot(drive, strafe, turn); + sleep(10); + } + } + + /** + * Move robot according to desired axes motions + *

+ * Positive X is forward + *

+ * Positive Y is strafe left + *

+ * Positive Yaw is counter-clockwise + */ + public void moveRobot(double x, double y, double yaw) { + // Calculate wheel powers. + double frontLeftPower = x - y - yaw; + double frontRightPower = x + y + yaw; + double backLeftPower = x + y - yaw; + double backRightPower = x - y + yaw; + + // Normalize wheel powers to be less than 1.0 + double max = Math.max(Math.abs(frontLeftPower), Math.abs(frontRightPower)); + max = Math.max(max, Math.abs(backLeftPower)); + max = Math.max(max, Math.abs(backRightPower)); + + if (max > 1.0) { + frontLeftPower /= max; + frontRightPower /= max; + backLeftPower /= max; + backRightPower /= max; + } + + // Send powers to the wheels. + frontLeftDrive.setPower(frontLeftPower); + frontRightDrive.setPower(frontRightPower); + backLeftDrive.setPower(backLeftPower); + backRightDrive.setPower(backRightPower); + } + + /** + * Initialize the AprilTag processor. + */ + private void initAprilTag() { + // Create the AprilTag processor by using a builder. + aprilTag = new AprilTagProcessor.Builder().build(); + + // Adjust Image Decimation to trade-off detection-range for detection-rate. + // e.g. Some typical detection data using a Logitech C920 WebCam + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second + // Note: Decimation can be changed on-the-fly to adapt during a match. + aprilTag.setDecimation(2); + + // Create the vision portal by using a builder. + if (USE_WEBCAM) { + visionPortal = new VisionPortal.Builder() + .setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")) + .addProcessor(aprilTag) + .build(); + } else { + visionPortal = new VisionPortal.Builder() + .setCamera(BuiltinCameraDirection.BACK) + .addProcessor(aprilTag) + .build(); + } + } + + /* + Manually set the camera gain and exposure. + This can only be called AFTER calling initAprilTag(), and only works for Webcams; + */ + private void setManualExposure(int exposureMS, int gain) { + // Wait for the camera to be open, then use the controls + + if (visionPortal == null) { + return; + } + + // Make sure camera is streaming before we try to set the exposure controls + if (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING) { + telemetry.addData("Camera", "Waiting"); + telemetry.update(); + while (!isStopRequested() && (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING)) { + sleep(20); + } + telemetry.addData("Camera", "Ready"); + telemetry.update(); + } + + // Set camera controls unless we are stopping. + if (!isStopRequested()) + { + ExposureControl exposureControl = visionPortal.getCameraControl(ExposureControl.class); + if (exposureControl.getMode() != ExposureControl.Mode.Manual) { + exposureControl.setMode(ExposureControl.Mode.Manual); + sleep(50); + } + exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS); + sleep(20); + GainControl gainControl = visionPortal.getCameraControl(GainControl.class); + gainControl.setGain(gain); + sleep(20); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java new file mode 100644 index 000000000000..1dd9eb3b580e --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java @@ -0,0 +1,225 @@ +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.bylazar.configurables.annotations.IgnoreConfigurable; +import com.bylazar.telemetry.TelemetryManager; +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.util.Range; + +import org.firstinspires.ftc.robotcontroller.external.samples.BasicOpMode_Iterative; +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl; +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +import java.util.List; +import java.util.concurrent.TimeUnit; + +@TeleOp(name = "Chase AprilTag", group = "Examples") +public class Chase_AprilTag extends OpMode { + public static Follower follower; + @IgnoreConfigurable + static TelemetryManager telemetryM; + /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ + private final Pose startPose = new Pose(60,96, Math.toRadians(0)); + + // Adjust these numbers to suit your robot. + final double DESIRED_DISTANCE = 24.0; // this is how close the camera should get to the target (inches) + + // Set the GAIN constants to control the relationship between the measured position error, and how much power is + // applied to the drive motors to correct the error. + // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. + final double SPEED_GAIN = 0.02 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) + final double STRAFE_GAIN = 0.015 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) + final double TURN_GAIN = 0.01 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + + final double MAX_AUTO_SPEED = 0.5; // Clip the approach speed to this max value (adjust for your robot) + final double MAX_AUTO_STRAFE= 0.5; // Clip the strafing speed to this max value (adjust for your robot) + final double MAX_AUTO_TURN = 0.3; // Clip the turn speed to this max value (adjust for your robot) + + private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera + private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. + private VisionPortal visionPortal; // Used to manage the video source. + private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. + private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag + + boolean targetFound = false; // Set to true when an AprilTag target is detected + double drive = 0; // Desired forward power/speed (-1 to +1) + double strafe = 0; // Desired strafe power/speed (-1 to +1) + double turn = 0; // Desired turning power/speed (-1 to +1) + + /** This method is called once when init is pressed and initializes the follower **/ + @Override + public void init() { + + // Initialize the Apriltag Detection process + initAprilTag(); + + // Initializing the follower and setting its starting position. + follower = Constants.createFollower(hardwareMap); + follower.setStartingPose(startPose); + follower.update(); + } + + /** This method is called once at the start of the OpMode. **/ + @Override + public void start() { + // Calling this method is necessary at the start of your TeleOp OpMode. + follower.startTeleopDrive(); + follower.update(); + } + + /** This is the main loop of the OpMode and runs continuously after pressing play **/ + @Override + public void loop() { + + + targetFound = false; + desiredTag = null; + + // Step through the list of detected tags and look for a matching tag + List currentDetections = aprilTag.getDetections(); + for (AprilTagDetection detection : currentDetections) { + // Look to see if we have size info on this tag. + if (detection.metadata != null) { + // Check to see if we want to track towards this tag. + if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) { + // Yes, we want to use this tag. + targetFound = true; + desiredTag = detection; + break; // don't look any further. + } else { + // This tag is in the library, but we do not want to track it right now. + telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id); + } + } else { + // This tag is NOT in the library, so we don't have enough information to track to it. + telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id); + } + } + + // Tell the driver what we see, and what to do. + if (targetFound) { + telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n"); + telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); + telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); + telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); + telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); + } else { + telemetry.addData("\n>","Drive using joysticks to find valid target\n"); + } + + // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . + if (gamepad1.left_bumper && targetFound) { + + // Determine heading, range and Yaw (tag image rotation) error so we can use them to control the robot automatically. + double rangeError = (desiredTag.ftcPose.range - DESIRED_DISTANCE); + double headingError = desiredTag.ftcPose.bearing; + double yawError = desiredTag.ftcPose.yaw; + + // Use the speed and turn "gains" to calculate how we want the robot to move. + drive = Range.clip(rangeError * SPEED_GAIN, -MAX_AUTO_SPEED, MAX_AUTO_SPEED); + turn = Range.clip(headingError * TURN_GAIN, -MAX_AUTO_TURN, MAX_AUTO_TURN) ; + strafe = Range.clip(-yawError * STRAFE_GAIN, -MAX_AUTO_STRAFE, MAX_AUTO_STRAFE); + + telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + } else { + + // drive using manual POV Joystick mode. Slow things down to make the robot more controlable. + drive = -gamepad1.left_stick_y / 2.0; // Reduce drive rate to 50%. + strafe = -gamepad1.left_stick_x / 2.0; // Reduce strafe rate to 50%. + turn = -gamepad1.right_stick_x / 3.0; // Reduce turn rate to 33%. + telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + } + telemetry.update(); + + + // Update robot movement based on gamepad inputs + /* Update Pedro to move the robot based on: + * Forward/Backward Movement: -gamepad1.left_stick_y + * Left/Right Movement: -gamepad1.left_stick_x + * Turn Left/Right Movement: -gamepad1.right_stick_x + * Robot-Centric Mode: true + */ + follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); + // Loop robot movement and odometry values + follower.update(); + + // Telemetry Outputs of the Follower + telemetry.addData("X", follower.getPose().getX()); + telemetry.addData("Y", follower.getPose().getY()); + telemetry.addData("Heading in Degrees", Math.toDegrees(1)); + + // Update Telemetry to the Driver Hub + telemetry.update(); + + // Updating the status of the gamepad buttons + } + + /** + * Initialize the AprilTag processor. + */ + private void initAprilTag() { + // Create the AprilTag processor by using a builder. + aprilTag = new AprilTagProcessor.Builder().build(); + + // Adjust Image Decimation to trade-off detection-range for detection-rate. + // e.g. Some typical detection data using a Logitech C920 WebCam + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second + // Note: Decimation can be changed on-the-fly to adapt during a match. + aprilTag.setDecimation(2); + + // Create the vision portal by using a builder. + if (USE_WEBCAM) { + visionPortal = new VisionPortal.Builder() + .setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")) + .addProcessor(aprilTag) + .build(); + } else { + visionPortal = new VisionPortal.Builder() + .setCamera(BuiltinCameraDirection.BACK) + .addProcessor(aprilTag) + .build(); + } + } + + /* + Manually set the camera gain and exposure. + This can only be called AFTER calling initAprilTag(), and only works for Webcams; + */ + private void setManualExposure(int exposureMS, int gain) { + // Wait for the camera to be open, then use the controls + + if (visionPortal == null) { + return; + } + + // Make sure camera is streaming before we try to set the exposure controls + if (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING) { + telemetry.addData("Camera", "Waiting"); + telemetry.update(); + while ((visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING)) {} + telemetry.addData("Camera", "Ready"); + telemetry.update(); + + } + + // Set camera controls unless we are stopping. + ExposureControl exposureControl = visionPortal.getCameraControl(ExposureControl.class); + if (exposureControl.getMode() != ExposureControl.Mode.Manual) { + exposureControl.setMode(ExposureControl.Mode.Manual); + } + exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS); + GainControl gainControl = visionPortal.getCameraControl(GainControl.class); + gainControl.setGain(gain); + } +} \ No newline at end of file From d9bd24c259abaf38ed2b59132b5de5f4be8cf923 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 16 Sep 2025 10:11:01 -0400 Subject: [PATCH 016/152] More AprilTag testing --- .../LOADCode/AutoDriveToAprilTagOmni.java | 29 +- .../ftc/teamcode/LOADCode/Chase_AprilTag.java | 8 +- .../LOADCode/PedroDriveToAprilTag.java | 315 ++++++++++++++++++ .../ftc/teamcode/LOADCode/TeleopTest_V1.java | 2 +- 4 files changed, 341 insertions(+), 13 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java index 523776cd3a31..34a34972d48b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java @@ -86,23 +86,22 @@ * */ -@TeleOp(name="Omni Drive To AprilTag", group = "Concept") -@Disabled +@TeleOp(name="Follow AprilTag", group = "Demo") public class AutoDriveToAprilTagOmni extends LinearOpMode { // Adjust these numbers to suit your robot. - final double DESIRED_DISTANCE = 12.0; // this is how close the camera should get to the target (inches) + final double DESIRED_DISTANCE = 80.0; // this is how close the camera should get to the target (inches) // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double SPEED_GAIN = 0.02 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) - final double STRAFE_GAIN = 0.015 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) - final double TURN_GAIN = 0.01 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + final double SPEED_GAIN = 0.04 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) + final double STRAFE_GAIN = 0.04 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) + final double TURN_GAIN = 0.04 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) - final double MAX_AUTO_SPEED = 0.5; // Clip the approach speed to this max value (adjust for your robot) - final double MAX_AUTO_STRAFE= 0.5; // Clip the strafing speed to this max value (adjust for your robot) - final double MAX_AUTO_TURN = 0.3; // Clip the turn speed to this max value (adjust for your robot) + final double MAX_AUTO_SPEED = 1; // Clip the approach speed to this max value (adjust for your robot) + final double MAX_AUTO_STRAFE= 1; // Clip the strafing speed to this max value (adjust for your robot) + final double MAX_AUTO_TURN = 1; // Clip the turn speed to this max value (adjust for your robot) private DcMotor frontLeftDrive = null; // Used to control the left front drive wheel private DcMotor frontRightDrive = null; // Used to control the right front drive wheel @@ -115,6 +114,9 @@ public class AutoDriveToAprilTagOmni extends LinearOpMode private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag + private boolean toggle = false; + private boolean oldToggleVal = false; + @Override public void runOpMode() { boolean targetFound = false; // Set to true when an AprilTag target is detected @@ -187,8 +189,15 @@ public class AutoDriveToAprilTagOmni extends LinearOpMode telemetry.addData("\n>","Drive using joysticks to find valid target\n"); } + if (gamepad1.b && !oldToggleVal){ + toggle = !toggle; + oldToggleVal = true; + }else if (!gamepad1.b && oldToggleVal){ + oldToggleVal = false; + } + // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . - if (gamepad1.left_bumper && targetFound) { + if (toggle && targetFound) { // Determine heading, range and Yaw (tag image rotation) error so we can use them to control the robot automatically. double rangeError = (desiredTag.ftcPose.range - DESIRED_DISTANCE); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java index 1dd9eb3b580e..0fc114a5b640 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java @@ -4,6 +4,7 @@ import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.Range; @@ -16,12 +17,14 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import org.firstinspires.ftc.vision.VisionPortal; import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagLibrary; import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; import java.util.List; import java.util.concurrent.TimeUnit; @TeleOp(name = "Chase AprilTag", group = "Examples") +@Disabled public class Chase_AprilTag extends OpMode { public static Follower follower; @IgnoreConfigurable @@ -30,7 +33,7 @@ public class Chase_AprilTag extends OpMode { private final Pose startPose = new Pose(60,96, Math.toRadians(0)); // Adjust these numbers to suit your robot. - final double DESIRED_DISTANCE = 24.0; // this is how close the camera should get to the target (inches) + final double DESIRED_DISTANCE = 30.0; // this is how close the camera should get to the target (inches) // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. @@ -167,7 +170,8 @@ public void loop() { */ private void initAprilTag() { // Create the AprilTag processor by using a builder. - aprilTag = new AprilTagProcessor.Builder().build(); + aprilTag = new AprilTagProcessor.Builder() + .build(); // Adjust Image Decimation to trade-off detection-range for detection-rate. // e.g. Some typical detection data using a Logitech C920 WebCam diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java new file mode 100644 index 000000000000..8b9985e4b844 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java @@ -0,0 +1,315 @@ +/* Copyright (c) 2023 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode; + +import com.bylazar.configurables.annotations.IgnoreConfigurable; +import com.bylazar.telemetry.TelemetryManager; +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.util.Range; + +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl; +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +import java.util.List; +import java.util.concurrent.TimeUnit; + +/* + * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. + * The code assumes a Holonomic (Mecanum or X Drive) Robot. + * + * For an introduction to AprilTags, see the ftc-docs link below: + * https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html + * + * When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera. + * This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below. + * https://ftc-docs.firstinspires.org/apriltag-detection-values + * + * The drive goal is to rotate to keep the Tag centered in the camera, while strafing to be directly in front of the tag, and + * driving towards the tag to achieve the desired distance. + * To reduce any motion blur (which will interrupt the detection process) the Camera exposure is reduced to a very low value (5mS) + * You can determine the best Exposure and Gain values by using the ConceptAprilTagOptimizeExposure OpMode in this Samples folder. + * + * The code assumes a Robot Configuration with motors named: front_left_drive and front_right_drive, back_left_drive and back_right_drive. + * The motor directions must be set so a positive power goes forward on all wheels. + * This sample assumes that the current game AprilTag Library (usually for the current season) is being loaded by default, + * so you should choose to approach a valid tag ID. + * + * Under manual control, the left stick will move forward/back & left/right. The right stick will rotate the robot. + * Manually drive the robot until it displays Target data on the Driver Station. + * + * Press and hold the *Left Bumper* to enable the automatic "Drive to target" mode. + * Release the Left Bumper to return to manual driving mode. + * + * Under "Drive To Target" mode, the robot has three goals: + * 1) Turn the robot to always keep the Tag centered on the camera frame. (Use the Target Bearing to turn the robot.) + * 2) Strafe the robot towards the centerline of the Tag, so it approaches directly in front of the tag. (Use the Target Yaw to strafe the robot) + * 3) Drive towards the Tag to get to the desired distance. (Use Tag Range to drive the robot forward/backward) + * + * Use DESIRED_DISTANCE to set how close you want the robot to get to the target. + * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. + * + * Use Android Studio to Copy this Class, and Paste it into the TeamCode/src/main/java/org/firstinspires/ftc/teamcode folder. + * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list. + * + */ + +@TeleOp(name="Pedro Follow AprilTag", group = "Demo") +public class PedroDriveToAprilTag extends LinearOpMode +{ + // Adjust these numbers to suit your robot. + final double DESIRED_DISTANCE = 80.0; // this is how close the camera should get to the target (inches) + + // Set the GAIN constants to control the relationship between the measured position error, and how much power is + // applied to the drive motors to correct the error. + // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. + final double SPEED_GAIN = 0.04 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) + final double STRAFE_GAIN = 0.03 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) + final double TURN_GAIN = 0.02 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + + final double MAX_AUTO_SPEED = 1; // Clip the approach speed to this max value (adjust for your robot) + final double MAX_AUTO_STRAFE= 1; // Clip the strafing speed to this max value (adjust for your robot) + final double MAX_AUTO_TURN = 1; // Clip the turn speed to this max value (adjust for your robot) + + private DcMotor frontLeftDrive = null; // Used to control the left front drive wheel + private DcMotor frontRightDrive = null; // Used to control the right front drive wheel + private DcMotor backLeftDrive = null; // Used to control the left back drive wheel + private DcMotor backRightDrive = null; // Used to control the right back drive wheel + + private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera + private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. + private VisionPortal visionPortal; // Used to manage the video source. + private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. + private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag + + private boolean toggle = false; + private boolean oldToggleVal = false; + + public static Follower follower; + @IgnoreConfigurable + static TelemetryManager telemetryM; + /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ + private final Pose startPose = new Pose(60,96, Math.toRadians(0)); + + @Override public void runOpMode() + { + boolean targetFound = false; // Set to true when an AprilTag target is detected + double drive; // Desired forward power/speed (-1 to +1) + double strafe; // Desired strafe power/speed (-1 to +1) + double turn; // Desired turning power/speed (-1 to +1) + + // Initialize the Apriltag Detection process + initAprilTag(); + + // Initialize the hardware variables. Note that the strings used here as parameters + // to 'get' must match the names assigned during the robot configuration. + // step (using the FTC Robot Controller app on the phone). + frontLeftDrive = hardwareMap.get(DcMotor.class, "FL"); + frontRightDrive = hardwareMap.get(DcMotor.class, "FR"); + backLeftDrive = hardwareMap.get(DcMotor.class, "BL"); + backRightDrive = hardwareMap.get(DcMotor.class, "BR"); + + // To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions. + // When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive. + // Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips + frontLeftDrive.setDirection(DcMotor.Direction.REVERSE); + backLeftDrive.setDirection(DcMotor.Direction.REVERSE); + frontRightDrive.setDirection(DcMotor.Direction.FORWARD); + backRightDrive.setDirection(DcMotor.Direction.FORWARD); + + if (USE_WEBCAM) + setManualExposure(6, 250); // Use low exposure time to reduce motion blur + + follower = Constants.createFollower(hardwareMap); + follower.setStartingPose(startPose); + follower.update(); + + // Wait for driver to press start + telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); + telemetry.addData(">", "Touch START to start OpMode"); + telemetry.update(); + waitForStart(); + + follower.startTeleopDrive(); + follower.update(); + + while (opModeIsActive()) + { + targetFound = false; + desiredTag = null; + + // Step through the list of detected tags and look for a matching tag + List currentDetections = aprilTag.getDetections(); + for (AprilTagDetection detection : currentDetections) { + // Look to see if we have size info on this tag. + if (detection.metadata != null) { + // Check to see if we want to track towards this tag. + if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) { + // Yes, we want to use this tag. + targetFound = true; + desiredTag = detection; + break; // don't look any further. + } else { + // This tag is in the library, but we do not want to track it right now. + telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id); + } + } else { + // This tag is NOT in the library, so we don't have enough information to track to it. + telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id); + } + } + + // Tell the driver what we see, and what to do. + if (targetFound) { + telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n"); + telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); + telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); + telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); + telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); + } else { + telemetry.addData("\n>","Drive using joysticks to find valid target\n"); + } + + if (gamepad1.b && !oldToggleVal){ + toggle = !toggle; + oldToggleVal = true; + }else if (!gamepad1.b && oldToggleVal){ + oldToggleVal = false; + } + + // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . + if (toggle && targetFound) { + + // Determine heading, range and Yaw (tag image rotation) error so we can use them to control the robot automatically. + double rangeError = (desiredTag.ftcPose.range - DESIRED_DISTANCE); + double headingError = desiredTag.ftcPose.bearing; + double yawError = desiredTag.ftcPose.yaw; + + // Use the speed and turn "gains" to calculate how we want the robot to move. + drive = Range.clip(rangeError * SPEED_GAIN, -MAX_AUTO_SPEED, MAX_AUTO_SPEED); + turn = Range.clip(headingError * TURN_GAIN, -MAX_AUTO_TURN, MAX_AUTO_TURN) ; + strafe = Range.clip(-yawError * STRAFE_GAIN, -MAX_AUTO_STRAFE, MAX_AUTO_STRAFE); + + telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + } else { + + // drive using manual POV Joystick mode. Slow things down to make the robot more controlable. + drive = -gamepad1.left_stick_y / 2.0; // Reduce drive rate to 50%. + strafe = -gamepad1.left_stick_x / 2.0; // Reduce strafe rate to 50%. + turn = -gamepad1.right_stick_x / 3.0; // Reduce turn rate to 33%. + telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + } + telemetry.update(); + + // Apply desired axes motions to the drivetrain. + follower.setTeleOpDrive(drive, strafe, turn, true); + follower.update(); + //moveRobot(drive, strafe, turn); + sleep(10); + } + } + + /** + * Initialize the AprilTag processor. + */ + private void initAprilTag() { + // Create the AprilTag processor by using a builder. + aprilTag = new AprilTagProcessor.Builder().build(); + + // Adjust Image Decimation to trade-off detection-range for detection-rate. + // e.g. Some typical detection data using a Logitech C920 WebCam + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second + // Note: Decimation can be changed on-the-fly to adapt during a match. + aprilTag.setDecimation(2); + + // Create the vision portal by using a builder. + if (USE_WEBCAM) { + visionPortal = new VisionPortal.Builder() + .setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")) + .addProcessor(aprilTag) + .build(); + } else { + visionPortal = new VisionPortal.Builder() + .setCamera(BuiltinCameraDirection.BACK) + .addProcessor(aprilTag) + .build(); + } + } + + /* + Manually set the camera gain and exposure. + This can only be called AFTER calling initAprilTag(), and only works for Webcams; + */ + private void setManualExposure(int exposureMS, int gain) { + // Wait for the camera to be open, then use the controls + + if (visionPortal == null) { + return; + } + + // Make sure camera is streaming before we try to set the exposure controls + if (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING) { + telemetry.addData("Camera", "Waiting"); + telemetry.update(); + while (!isStopRequested() && (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING)) { + sleep(20); + } + telemetry.addData("Camera", "Ready"); + telemetry.update(); + } + + // Set camera controls unless we are stopping. + if (!isStopRequested()) + { + ExposureControl exposureControl = visionPortal.getCameraControl(ExposureControl.class); + if (exposureControl.getMode() != ExposureControl.Mode.Manual) { + exposureControl.setMode(ExposureControl.Mode.Manual); + sleep(50); + } + exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS); + sleep(20); + GainControl gainControl = visionPortal.getCameraControl(GainControl.class); + gainControl.setGain(gain); + sleep(20); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java index 57096c9f9622..bf96091ee387 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java @@ -11,7 +11,7 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants; -@TeleOp(name = "Example Robot-Centric TeleOp", group = "Examples") +@TeleOp(name = "Example Robot-Centric TeleOp", group = "Main") public class TeleopTest_V1 extends OpMode { public static Follower follower; @IgnoreConfigurable From 66dc05758c25e3fe3abb4d39b1554c58df1eb9b4 Mon Sep 17 00:00:00 2001 From: Daniel <141444315+Professor348@users.noreply.github.com> Date: Wed, 17 Sep 2025 08:48:48 -0400 Subject: [PATCH 017/152] Update README.md Updated the README to describe what the repo is for better. --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index 522fb8048e75..1aa865b6cf37 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,6 @@ +# LOAD Robotics DECODE Robot Code +This repository contains LOAD Robotics' robot code for the 2025-2026 FTC season DECODE. + ## NOTICE This repository contains the public FTC SDK for the DECODE (2025-2026) competition season. From 4fa6e405ad82bf4716ee778738dc0659a42986d5 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Tue, 23 Sep 2025 20:31:03 -0400 Subject: [PATCH 018/152] Finalized transfer of aprilTag tracking from example code to Pedropathing, & made a field-centric heading-based tag tracker --- .../LOADCode/April_Tag_Follow_Test.txt | 254 ------------------ .../ftc/teamcode/LOADCode/Chase_AprilTag.java | 229 ---------------- ...Omni.java => FieldCentricTagTracking.java} | 119 +++----- .../LOADCode/PedroDriveToAprilTag.java | 38 +-- 4 files changed, 42 insertions(+), 598 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/April_Tag_Follow_Test.txt delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{AutoDriveToAprilTagOmni.java => FieldCentricTagTracking.java} (71%) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/April_Tag_Follow_Test.txt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/April_Tag_Follow_Test.txt deleted file mode 100644 index 2ce84250e593..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/April_Tag_Follow_Test.txt +++ /dev/null @@ -1,254 +0,0 @@ - - -import com.pedropathing.follower.Follower; - -import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; -import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; -import org.firstinspires.ftc.vision.VisionPortal; -import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; - -package org.firstinspires.ftc.teamcode.LOADCode; - -import com.pedropathing.follower.Follower; -import com.pedropathing.localization.Pose; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; - -import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; -import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; -import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; -import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; -import org.firstinspires.ftc.robotcore.external.navigation.Position; -import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; -import org.firstinspires.ftc.teamcode.pedroPathing.constants.FConstants; -import org.firstinspires.ftc.teamcode.pedroPathing.constants.LConstants; -import org.firstinspires.ftc.vision.VisionPortal; -import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; -import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; - -import java.util.List; - - -@TeleOp(name="April_Tag_Follow_Test",group = "org/firstinspires/ftc/teamcode/pedroPathing/LOADCode") -public class April_Tag_Follow_Test extends OpMode { - private Follower follower; - private final Pose startPose = new Pose(0,0,0); - - private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera - private Position cameraPosition = new Position(DistanceUnit.INCH, - 0, 0, 0, 0); - private YawPitchRollAngles cameraOrientation = new YawPitchRollAngles(AngleUnit.DEGREES, - 0, -90, 0, 0); - private AprilTagProcessor aprilTag; - private VisionPortal visionPortal; - - /** This method is call once when init is played, it initializes the follower **/ - @Override - public void init() { - follower = new Follower(hardwareMap, FConstants.class, LConstants.class); - follower.setStartingPose(startPose); - - initAprilTag(); - - // Wait for the DS start button to be touched. - telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch START to start OpMode"); - telemetry.update(); - } - - /** This method is called continuously after Init while waiting to be started. **/ - @Override - public void init_loop() { - } - - /** This method is called once at the start of the OpMode. **/ - @Override - public void start() { - follower.startTeleopDrive(); - } - - /** This is the main loop of the opmode and runs continuously after play **/ - @Override - public void loop() { - - - - /* Telemetry Outputs of our Follower */ - telemetry.addData("X", follower.getPose().getX()); - telemetry.addData("Y", follower.getPose().getY()); - telemetry.addData("Heading in Degrees", Math.toDegrees(follower.getPose().getHeading())); - - telemetryAprilTag(); - - // Save CPU resources; can resume streaming when needed. - if (gamepad1.dpad_down) { - visionPortal.stopStreaming(); - } else if (gamepad1.dpad_up) { - visionPortal.resumeStreaming(); - } - - /* Update Telemetry to the Driver Hub */ - telemetry.update(); - - - - } - - /** We do not use this because everything automatically should disable **/ - @Override - public void stop() { - visionPortal.close(); - } - - /** - * Initialize the AprilTag processor. - */ - public void initAprilTag() { - - // Create the AprilTag processor. - aprilTag = new AprilTagProcessor.Builder() - - // The following default settings are available to un-comment and edit as needed. - //.setDrawAxes(false) - //.setDrawCubeProjection(false) - //.setDrawTagOutline(true) - //.setTagFamily(AprilTagProcessor.TagFamily.TAG_36h11) - //.setTagLibrary(AprilTagGameDatabase.getCenterStageTagLibrary()) - //.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES) - .setCameraPose(cameraPosition, cameraOrientation) - - // == CAMERA CALIBRATION == - // If you do not manually specify calibration parameters, the SDK will attempt - // to load a predefined calibration for your camera. - //.setLensIntrinsics(578.272, 578.272, 402.145, 221.506) - // ... these parameters are fx, fy, cx, cy. - - .build(); - - // Adjust Image Decimation to trade-off detection-range for detection-rate. - // eg: Some typical detection data using a Logitech C920 WebCam - // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second - // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second - // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second (default) - // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second (default) - // Note: Decimation can be changed on-the-fly to adapt during a match. - //aprilTag.setDecimation(3); - - // Create the vision portal by using a builder. - VisionPortal.Builder builder = new VisionPortal.Builder(); - - // Set the camera (webcam vs. built-in RC phone camera). - if (USE_WEBCAM) { - builder.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")); - } else { - builder.setCamera(BuiltinCameraDirection.BACK); - } - - // Choose a camera resolution. Not all cameras support all resolutions. - //builder.setCameraResolution(new Size(640, 480)); - - // Enable the RC preview (LiveView). Set "false" to omit camera monitoring. - //builder.enableLiveView(true); - - // Set the stream format; MJPEG uses less bandwidth than default YUY2. - //builder.setStreamFormat(VisionPortal.StreamFormat.YUY2); - - // Choose whether or not LiveView stops if no processors are enabled. - // If set "true", monitor shows solid orange screen if no processors enabled. - // If set "false", monitor shows camera view without annotations. - //builder.setAutoStopLiveView(false); - - // Set and enable the processor. - builder.addProcessor(aprilTag); - - // Build the Vision Portal, using the above settings. - visionPortal = builder.build(); - - // Disable or re-enable the aprilTag processor at any time. - //visionPortal.setProcessorEnabled(aprilTag, true); - - } // end method initAprilTag() - - /** - * Add telemetry about AprilTag detections. - */ - public void telemetryAprilTag() { - - List currentDetections = aprilTag.getDetections(); - telemetry.addData("# AprilTags Detected", currentDetections.size()); - - // Step through the list of detections and display info for each one. - for (AprilTagDetection detection : currentDetections) { - if (detection.metadata != null) { - telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name)); - telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", - detection.robotPose.getPosition().x, - detection.robotPose.getPosition().y, - detection.robotPose.getPosition().z)); - telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", - detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES))); - - followTag( - detection.robotPose.getPosition().x, - detection.robotPose.getPosition().y, - detection.robotPose.getPosition().z, - detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), - detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES) - ); - - } else { - telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id)); - telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y)); - } - } // end for() loop - - // Add "key" information to telemetry - telemetry.addLine("\nkey:\nXYZ = X (Right), Y (Forward), Z (Up) dist."); - telemetry.addLine("PRY = Pitch, Roll & Yaw (XYZ Rotation)"); - - } // end method telemetryAprilTag() - - public void followTag(double posX, double posY, double posZ, double angX, double angY, double angZ){ - - double distancMarginError = 1; // Measured in Inches - double angleMarginError = 1; // Measured in Degrees - - double FB_Movement = 0; - double SLR_Movement = 0; - double TLR_Movement = 0; - boolean robotCentric = true; - - double followDistance = 18; // Measured in Inches - - if (posZ > followDistance + distancMarginError) { - FB_Movement = 0.1; - }else if (posZ < followDistance - distancMarginError) { - FB_Movement = -0.1; - }else{ - FB_Movement = 0; - } - - if (-posX > 0 + angleMarginError) { - TLR_Movement = 0.1; - }else if (-posX < 0 - angleMarginError) { - TLR_Movement = -0.1; - }else{ - TLR_Movement = 0; - } - - - - /* Update Pedro to move the robot based on: - - Forward/Backward Movement: -gamepad1.left_stick_y - - Left/Right Movement: -gamepad1.left_stick_x - - Turn Left/Right Movement: -gamepad1.right_stick_x - - Robot-Centric Mode: true - */ - - follower.setTeleOpMovementVectors(FB_Movement, -SLR_Movement, TLR_Movement, robotCentric); - follower.update(); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java deleted file mode 100644 index 0fc114a5b640..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Chase_AprilTag.java +++ /dev/null @@ -1,229 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode; - -import com.bylazar.configurables.annotations.IgnoreConfigurable; -import com.bylazar.telemetry.TelemetryManager; -import com.pedropathing.follower.Follower; -import com.pedropathing.geometry.Pose; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.util.Range; - -import org.firstinspires.ftc.robotcontroller.external.samples.BasicOpMode_Iterative; -import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; -import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; -import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl; -import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl; -import org.firstinspires.ftc.teamcode.pedroPathing.Constants; -import org.firstinspires.ftc.vision.VisionPortal; -import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; -import org.firstinspires.ftc.vision.apriltag.AprilTagLibrary; -import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; - -import java.util.List; -import java.util.concurrent.TimeUnit; - -@TeleOp(name = "Chase AprilTag", group = "Examples") -@Disabled -public class Chase_AprilTag extends OpMode { - public static Follower follower; - @IgnoreConfigurable - static TelemetryManager telemetryM; - /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ - private final Pose startPose = new Pose(60,96, Math.toRadians(0)); - - // Adjust these numbers to suit your robot. - final double DESIRED_DISTANCE = 30.0; // this is how close the camera should get to the target (inches) - - // Set the GAIN constants to control the relationship between the measured position error, and how much power is - // applied to the drive motors to correct the error. - // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double SPEED_GAIN = 0.02 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) - final double STRAFE_GAIN = 0.015 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) - final double TURN_GAIN = 0.01 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) - - final double MAX_AUTO_SPEED = 0.5; // Clip the approach speed to this max value (adjust for your robot) - final double MAX_AUTO_STRAFE= 0.5; // Clip the strafing speed to this max value (adjust for your robot) - final double MAX_AUTO_TURN = 0.3; // Clip the turn speed to this max value (adjust for your robot) - - private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera - private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. - private VisionPortal visionPortal; // Used to manage the video source. - private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. - private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag - - boolean targetFound = false; // Set to true when an AprilTag target is detected - double drive = 0; // Desired forward power/speed (-1 to +1) - double strafe = 0; // Desired strafe power/speed (-1 to +1) - double turn = 0; // Desired turning power/speed (-1 to +1) - - /** This method is called once when init is pressed and initializes the follower **/ - @Override - public void init() { - - // Initialize the Apriltag Detection process - initAprilTag(); - - // Initializing the follower and setting its starting position. - follower = Constants.createFollower(hardwareMap); - follower.setStartingPose(startPose); - follower.update(); - } - - /** This method is called once at the start of the OpMode. **/ - @Override - public void start() { - // Calling this method is necessary at the start of your TeleOp OpMode. - follower.startTeleopDrive(); - follower.update(); - } - - /** This is the main loop of the OpMode and runs continuously after pressing play **/ - @Override - public void loop() { - - - targetFound = false; - desiredTag = null; - - // Step through the list of detected tags and look for a matching tag - List currentDetections = aprilTag.getDetections(); - for (AprilTagDetection detection : currentDetections) { - // Look to see if we have size info on this tag. - if (detection.metadata != null) { - // Check to see if we want to track towards this tag. - if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) { - // Yes, we want to use this tag. - targetFound = true; - desiredTag = detection; - break; // don't look any further. - } else { - // This tag is in the library, but we do not want to track it right now. - telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id); - } - } else { - // This tag is NOT in the library, so we don't have enough information to track to it. - telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id); - } - } - - // Tell the driver what we see, and what to do. - if (targetFound) { - telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n"); - telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); - telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); - telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); - telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); - } else { - telemetry.addData("\n>","Drive using joysticks to find valid target\n"); - } - - // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . - if (gamepad1.left_bumper && targetFound) { - - // Determine heading, range and Yaw (tag image rotation) error so we can use them to control the robot automatically. - double rangeError = (desiredTag.ftcPose.range - DESIRED_DISTANCE); - double headingError = desiredTag.ftcPose.bearing; - double yawError = desiredTag.ftcPose.yaw; - - // Use the speed and turn "gains" to calculate how we want the robot to move. - drive = Range.clip(rangeError * SPEED_GAIN, -MAX_AUTO_SPEED, MAX_AUTO_SPEED); - turn = Range.clip(headingError * TURN_GAIN, -MAX_AUTO_TURN, MAX_AUTO_TURN) ; - strafe = Range.clip(-yawError * STRAFE_GAIN, -MAX_AUTO_STRAFE, MAX_AUTO_STRAFE); - - telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); - } else { - - // drive using manual POV Joystick mode. Slow things down to make the robot more controlable. - drive = -gamepad1.left_stick_y / 2.0; // Reduce drive rate to 50%. - strafe = -gamepad1.left_stick_x / 2.0; // Reduce strafe rate to 50%. - turn = -gamepad1.right_stick_x / 3.0; // Reduce turn rate to 33%. - telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); - } - telemetry.update(); - - - // Update robot movement based on gamepad inputs - /* Update Pedro to move the robot based on: - * Forward/Backward Movement: -gamepad1.left_stick_y - * Left/Right Movement: -gamepad1.left_stick_x - * Turn Left/Right Movement: -gamepad1.right_stick_x - * Robot-Centric Mode: true - */ - follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); - // Loop robot movement and odometry values - follower.update(); - - // Telemetry Outputs of the Follower - telemetry.addData("X", follower.getPose().getX()); - telemetry.addData("Y", follower.getPose().getY()); - telemetry.addData("Heading in Degrees", Math.toDegrees(1)); - - // Update Telemetry to the Driver Hub - telemetry.update(); - - // Updating the status of the gamepad buttons - } - - /** - * Initialize the AprilTag processor. - */ - private void initAprilTag() { - // Create the AprilTag processor by using a builder. - aprilTag = new AprilTagProcessor.Builder() - .build(); - - // Adjust Image Decimation to trade-off detection-range for detection-rate. - // e.g. Some typical detection data using a Logitech C920 WebCam - // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second - // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second - // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second - // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second - // Note: Decimation can be changed on-the-fly to adapt during a match. - aprilTag.setDecimation(2); - - // Create the vision portal by using a builder. - if (USE_WEBCAM) { - visionPortal = new VisionPortal.Builder() - .setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")) - .addProcessor(aprilTag) - .build(); - } else { - visionPortal = new VisionPortal.Builder() - .setCamera(BuiltinCameraDirection.BACK) - .addProcessor(aprilTag) - .build(); - } - } - - /* - Manually set the camera gain and exposure. - This can only be called AFTER calling initAprilTag(), and only works for Webcams; - */ - private void setManualExposure(int exposureMS, int gain) { - // Wait for the camera to be open, then use the controls - - if (visionPortal == null) { - return; - } - - // Make sure camera is streaming before we try to set the exposure controls - if (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING) { - telemetry.addData("Camera", "Waiting"); - telemetry.update(); - while ((visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING)) {} - telemetry.addData("Camera", "Ready"); - telemetry.update(); - - } - - // Set camera controls unless we are stopping. - ExposureControl exposureControl = visionPortal.getCameraControl(ExposureControl.class); - if (exposureControl.getMode() != ExposureControl.Mode.Manual) { - exposureControl.setMode(ExposureControl.Mode.Manual); - } - exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS); - GainControl gainControl = visionPortal.getCameraControl(GainControl.class); - gainControl.setGain(gain); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/FieldCentricTagTracking.java similarity index 71% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/FieldCentricTagTracking.java index 34a34972d48b..88937245bb2d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/AutoDriveToAprilTagOmni.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/FieldCentricTagTracking.java @@ -29,7 +29,10 @@ package org.firstinspires.ftc.teamcode.LOADCode; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; +import com.bylazar.configurables.annotations.IgnoreConfigurable; +import com.bylazar.telemetry.TelemetryManager; +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.DcMotor; @@ -39,6 +42,7 @@ import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl; import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl; +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import org.firstinspires.ftc.vision.VisionPortal; import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; @@ -81,33 +85,18 @@ * Use DESIRED_DISTANCE to set how close you want the robot to get to the target. * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. * - * Use Android Studio to Copy this Class, and Paste it into the TeamCode/src/main/java/org/firstinspires/ftc/teamcode folder. - * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list. - * */ -@TeleOp(name="Follow AprilTag", group = "Demo") -public class AutoDriveToAprilTagOmni extends LinearOpMode +@TeleOp(name="Field-Centric Tag Tracking", group = "Demo") +public class FieldCentricTagTracking extends LinearOpMode { // Adjust these numbers to suit your robot. - final double DESIRED_DISTANCE = 80.0; // this is how close the camera should get to the target (inches) - // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double SPEED_GAIN = 0.04 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) - final double STRAFE_GAIN = 0.04 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) final double TURN_GAIN = 0.04 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) - - final double MAX_AUTO_SPEED = 1; // Clip the approach speed to this max value (adjust for your robot) - final double MAX_AUTO_STRAFE= 1; // Clip the strafing speed to this max value (adjust for your robot) final double MAX_AUTO_TURN = 1; // Clip the turn speed to this max value (adjust for your robot) - private DcMotor frontLeftDrive = null; // Used to control the left front drive wheel - private DcMotor frontRightDrive = null; // Used to control the right front drive wheel - private DcMotor backLeftDrive = null; // Used to control the left back drive wheel - private DcMotor backRightDrive = null; // Used to control the right back drive wheel - private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. private VisionPortal visionPortal; // Used to manage the video source. @@ -117,41 +106,38 @@ public class AutoDriveToAprilTagOmni extends LinearOpMode private boolean toggle = false; private boolean oldToggleVal = false; + public static Follower follower; + @IgnoreConfigurable + static TelemetryManager telemetryM; + /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ + private final Pose startPose = new Pose(60,96, Math.toRadians(0)); + @Override public void runOpMode() { - boolean targetFound = false; // Set to true when an AprilTag target is detected - double drive = 0; // Desired forward power/speed (-1 to +1) - double strafe = 0; // Desired strafe power/speed (-1 to +1) - double turn = 0; // Desired turning power/speed (-1 to +1) + boolean targetFound; // Set to true when an AprilTag target is detected + double drive; // Desired forward power/speed (-1 to +1) + double strafe; // Desired strafe power/speed (-1 to +1) + double turn; // Desired turning power/speed (-1 to +1) // Initialize the Apriltag Detection process initAprilTag(); - // Initialize the hardware variables. Note that the strings used here as parameters - // to 'get' must match the names assigned during the robot configuration. - // step (using the FTC Robot Controller app on the phone). - frontLeftDrive = hardwareMap.get(DcMotor.class, "FL"); - frontRightDrive = hardwareMap.get(DcMotor.class, "FR"); - backLeftDrive = hardwareMap.get(DcMotor.class, "BL"); - backRightDrive = hardwareMap.get(DcMotor.class, "BR"); - - // To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions. - // When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive. - // Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips - frontLeftDrive.setDirection(DcMotor.Direction.REVERSE); - backLeftDrive.setDirection(DcMotor.Direction.REVERSE); - frontRightDrive.setDirection(DcMotor.Direction.FORWARD); - backRightDrive.setDirection(DcMotor.Direction.FORWARD); - if (USE_WEBCAM) setManualExposure(6, 250); // Use low exposure time to reduce motion blur + follower = Constants.createFollower(hardwareMap); + follower.setStartingPose(startPose); + follower.update(); + // Wait for driver to press start telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); waitForStart(); + follower.startTeleopDrive(); + follower.update(); + while (opModeIsActive()) { targetFound = false; @@ -196,71 +182,34 @@ public class AutoDriveToAprilTagOmni extends LinearOpMode oldToggleVal = false; } + drive = -gamepad1.left_stick_y; + strafe = -gamepad1.left_stick_x; + // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . if (toggle && targetFound) { - // Determine heading, range and Yaw (tag image rotation) error so we can use them to control the robot automatically. - double rangeError = (desiredTag.ftcPose.range - DESIRED_DISTANCE); + // Determine heading (tag image rotation) error so we can use them to control the robot automatically. double headingError = desiredTag.ftcPose.bearing; - double yawError = desiredTag.ftcPose.yaw; - // Use the speed and turn "gains" to calculate how we want the robot to move. - drive = Range.clip(rangeError * SPEED_GAIN, -MAX_AUTO_SPEED, MAX_AUTO_SPEED); + // Use the turn "gain" to calculate how we want the robot to move. turn = Range.clip(headingError * TURN_GAIN, -MAX_AUTO_TURN, MAX_AUTO_TURN) ; - strafe = Range.clip(-yawError * STRAFE_GAIN, -MAX_AUTO_STRAFE, MAX_AUTO_STRAFE); telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); } else { - // drive using manual POV Joystick mode. Slow things down to make the robot more controlable. - drive = -gamepad1.left_stick_y / 2.0; // Reduce drive rate to 50%. - strafe = -gamepad1.left_stick_x / 2.0; // Reduce strafe rate to 50%. - turn = -gamepad1.right_stick_x / 3.0; // Reduce turn rate to 33%. + // drive using manual POV Joystick mode. Slow things down to make the robot more controllable. + turn = -gamepad1.right_stick_x; telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); } telemetry.update(); // Apply desired axes motions to the drivetrain. - moveRobot(drive, strafe, turn); + follower.setTeleOpDrive(drive, strafe, turn, false); + follower.update(); sleep(10); } } - /** - * Move robot according to desired axes motions - *

- * Positive X is forward - *

- * Positive Y is strafe left - *

- * Positive Yaw is counter-clockwise - */ - public void moveRobot(double x, double y, double yaw) { - // Calculate wheel powers. - double frontLeftPower = x - y - yaw; - double frontRightPower = x + y + yaw; - double backLeftPower = x + y - yaw; - double backRightPower = x - y + yaw; - - // Normalize wheel powers to be less than 1.0 - double max = Math.max(Math.abs(frontLeftPower), Math.abs(frontRightPower)); - max = Math.max(max, Math.abs(backLeftPower)); - max = Math.max(max, Math.abs(backRightPower)); - - if (max > 1.0) { - frontLeftPower /= max; - frontRightPower /= max; - backLeftPower /= max; - backRightPower /= max; - } - - // Send powers to the wheels. - frontLeftDrive.setPower(frontLeftPower); - frontRightDrive.setPower(frontRightPower); - backLeftDrive.setPower(backLeftPower); - backRightDrive.setPower(backRightPower); - } - /** * Initialize the AprilTag processor. */ @@ -275,7 +224,7 @@ private void initAprilTag() { // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second // Note: Decimation can be changed on-the-fly to adapt during a match. - aprilTag.setDecimation(2); + aprilTag.setDecimation(3); // Create the vision portal by using a builder. if (USE_WEBCAM) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java index 8b9985e4b844..a035b1288d58 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java @@ -90,28 +90,23 @@ * */ -@TeleOp(name="Pedro Follow AprilTag", group = "Demo") +@TeleOp(name="Follow AprilTag", group = "Demo") public class PedroDriveToAprilTag extends LinearOpMode { // Adjust these numbers to suit your robot. - final double DESIRED_DISTANCE = 80.0; // this is how close the camera should get to the target (inches) + final double DESIRED_DISTANCE = 60.0; // this is how close the camera should get to the target (inches) // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. final double SPEED_GAIN = 0.04 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) - final double STRAFE_GAIN = 0.03 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) - final double TURN_GAIN = 0.02 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + final double STRAFE_GAIN = 0.04 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) + final double TURN_GAIN = 0.04 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) final double MAX_AUTO_SPEED = 1; // Clip the approach speed to this max value (adjust for your robot) final double MAX_AUTO_STRAFE= 1; // Clip the strafing speed to this max value (adjust for your robot) final double MAX_AUTO_TURN = 1; // Clip the turn speed to this max value (adjust for your robot) - private DcMotor frontLeftDrive = null; // Used to control the left front drive wheel - private DcMotor frontRightDrive = null; // Used to control the right front drive wheel - private DcMotor backLeftDrive = null; // Used to control the left back drive wheel - private DcMotor backRightDrive = null; // Used to control the right back drive wheel - private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. private VisionPortal visionPortal; // Used to manage the video source. @@ -129,30 +124,14 @@ public class PedroDriveToAprilTag extends LinearOpMode @Override public void runOpMode() { - boolean targetFound = false; // Set to true when an AprilTag target is detected - double drive; // Desired forward power/speed (-1 to +1) - double strafe; // Desired strafe power/speed (-1 to +1) - double turn; // Desired turning power/speed (-1 to +1) + boolean targetFound; // Set to true when an AprilTag target is detected + double drive; // Desired forward power/speed (-1 to +1) + double strafe; // Desired strafe power/speed (-1 to +1) + double turn; // Desired turning power/speed (-1 to +1) // Initialize the Apriltag Detection process initAprilTag(); - // Initialize the hardware variables. Note that the strings used here as parameters - // to 'get' must match the names assigned during the robot configuration. - // step (using the FTC Robot Controller app on the phone). - frontLeftDrive = hardwareMap.get(DcMotor.class, "FL"); - frontRightDrive = hardwareMap.get(DcMotor.class, "FR"); - backLeftDrive = hardwareMap.get(DcMotor.class, "BL"); - backRightDrive = hardwareMap.get(DcMotor.class, "BR"); - - // To drive forward, most robots need the motor on one side to be reversed, because the axles point in opposite directions. - // When run, this OpMode should start both motors driving forward. So adjust these two lines based on your first test drive. - // Note: The settings here assume direct drive on left and right wheels. Gear Reduction or 90 Deg drives may require direction flips - frontLeftDrive.setDirection(DcMotor.Direction.REVERSE); - backLeftDrive.setDirection(DcMotor.Direction.REVERSE); - frontRightDrive.setDirection(DcMotor.Direction.FORWARD); - backRightDrive.setDirection(DcMotor.Direction.FORWARD); - if (USE_WEBCAM) setManualExposure(6, 250); // Use low exposure time to reduce motion blur @@ -240,7 +219,6 @@ public class PedroDriveToAprilTag extends LinearOpMode // Apply desired axes motions to the drivetrain. follower.setTeleOpDrive(drive, strafe, turn, true); follower.update(); - //moveRobot(drive, strafe, turn); sleep(10); } } From 155330cbab70b6721989e94d4b3e932e2ce1ba20 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Mon, 13 Oct 2025 17:40:28 -0400 Subject: [PATCH 019/152] Began Auto Development --- .../teamcode/LOADCode/Autos/TestAutoR1.java | 243 ++++++++++++++++++ .../FieldCentricTagTracking.java | 5 +- .../{ => TeleOps}/PedroDriveToAprilTag.java | 5 +- .../LOADCode/{ => TeleOps}/TeleopTest_V1.java | 6 +- .../ftc/teamcode/pedroPathing/Constants.java | 4 +- 5 files changed, 251 insertions(+), 12 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => TeleOps}/FieldCentricTagTracking.java (98%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => TeleOps}/PedroDriveToAprilTag.java (99%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => TeleOps}/TeleopTest_V1.java (92%) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java new file mode 100644 index 000000000000..d1e4acf27298 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java @@ -0,0 +1,243 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Autos; // make sure this aligns with class location + +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; +import com.pedropathing.util.Timer; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; + +@Autonomous(name = "TestAutoR1", group = "TestAuto") +public class TestAutoR1 extends OpMode { + + private Follower follower; + private Timer pathTimer, actionTimer, opmodeTimer; + + private int pathState; + private boolean shooting; + + private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. + private final Pose scorePose = new Pose(86, 22, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. + private final Pose pickupR3PoseA = new Pose(110.4, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. + private final Pose pickupR3PoseB = new Pose(121.9, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. + private final Pose pickupR2PoseA = new Pose(110.4, 59.5, Math.toRadians(0)); // Middle (Second Set) of Artifacts from the Spike Mark. + private final Pose pickupR2PoseB = new Pose(121.9, 59.5, Math.toRadians(0)); // Middle (Second Set) of Artifacts from the Spike Mark. + private final Pose pickupR1PoseA = new Pose(110.4, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. + private final Pose pickupR1PoseB = new Pose(121.9, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. + + private PathChain grabPickup1, scorePickup, grabPickup2, grabPickup3; + + public void buildPaths() { + + grabPickup1 = follower.pathBuilder() + .addPath(new BezierCurve( + startPose, + new Pose(91.100, 35.700), + pickupR1PoseA + )) + .setLinearHeadingInterpolation(startPose.getHeading(), pickupR1PoseA.getHeading()) + .addPath(new BezierLine( + pickupR1PoseA, + pickupR1PoseB + )) + .setLinearHeadingInterpolation(pickupR1PoseA.getHeading(), pickupR1PoseA.getHeading()) + .setVelocityConstraint(0.5) + .build(); + + grabPickup2 = follower.pathBuilder() + .addPath(new BezierCurve( + scorePose, + new Pose(91.100, 60.5), + pickupR2PoseA + )) + .setLinearHeadingInterpolation(scorePose.getHeading(), pickupR2PoseA.getHeading()) + .addPath(new BezierLine( + pickupR2PoseA, + pickupR2PoseB + )) + .setLinearHeadingInterpolation(pickupR2PoseA.getHeading(), pickupR2PoseA.getHeading()) + .setVelocityConstraint(0.5) + .build(); + + grabPickup3 = follower.pathBuilder() + .addPath(new BezierCurve( + scorePose, + new Pose(91.100, 84.6), + pickupR3PoseA + )) + .setLinearHeadingInterpolation(scorePose.getHeading(), pickupR3PoseA.getHeading()) + .addPath(new BezierLine( + pickupR3PoseA, + pickupR3PoseB + )) + .setLinearHeadingInterpolation(pickupR3PoseA.getHeading(), pickupR3PoseA.getHeading()) + .setVelocityConstraint(0.5) + .build(); + + scorePickup = follower.pathBuilder() + .addPath(new BezierLine( + follower.getPose(), + scorePose + )) + .setLinearHeadingInterpolation(follower.getHeading(), scorePose.getHeading()) + .setVelocityConstraint(0.5) + .build(); + } + + public void delay(int time){ + Timer wait = new Timer(); + wait.resetTimer(); + while (wait.getElapsedTime() < time){} + } + + public void autonomousPathUpdate() { + switch (pathState) { + case 0: + + //Shoot balls + + setPathState(1); + break; + case 1: + + /* You could check for + - Follower State: "if(!follower.isBusy()) {}" + - Time: "if(pathTimer.getElapsedTimeSeconds() > 1) {}" + - Robot Position: "if(follower.getPose().getX() > 36) {}" + */ + + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ + follower.followPath(grabPickup1,true); + setPathState(2); + } + break; + case 2: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup1Pose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(scorePickup,true); + setPathState(3); + } + break; + case 3: + + //Shoot balls + + setPathState(4); + break; + case 4: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ + follower.followPath(grabPickup2,true); + setPathState(5); + } + break; + case 5: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup2Pose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(scorePickup,true); + setPathState(6); + } + break; + case 6: + + //Shoot balls + + setPathState(7); + break; + case 7: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ + follower.followPath(grabPickup3,true); + setPathState(8); + } + break; + case 8: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(scorePickup, true); + setPathState(9); + } + break; + case 9: + + //Shoot balls + + setPathState(10); + break; + case 10: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Set the state to a Case we won't use or define, so it just stops running an new paths */ + setPathState(-1); + } + break; + } + } + + /** These change the states of the paths and actions. It will also reset the timers of the individual switches **/ + public void setPathState(int pState) { + pathState = pState; + pathTimer.resetTimer(); + } + + /** This method is called once at the init of the OpMode. **/ + @Override + public void init() { + pathTimer = new Timer(); + opmodeTimer = new Timer(); + opmodeTimer.resetTimer(); + + shooting = false; + + + follower = Constants.createFollower(hardwareMap); + buildPaths(); + follower.setStartingPose(startPose); + + } + + /** This method is called continuously after Init while waiting for "play". **/ + @Override + public void init_loop() {} + + /** This method is called once at the start of the OpMode. + * It runs all the setup actions, including building paths and starting the path system **/ + @Override + public void start() { + opmodeTimer.resetTimer(); + setPathState(0); + } + + /** This is the main loop of the OpMode, it will run repeatedly after clicking "Play". **/ + @Override + public void loop() { + + // These loop the movements of the robot, these must be called continuously in order to work + follower.update(); + autonomousPathUpdate(); + + // Feedback to Driver Hub for debugging + telemetry.addData("path state", pathState); + telemetry.addData("shooting", shooting); + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("heading", follower.getPose().getHeading()); + telemetry.update(); + } + + /** We do not use this because everything should automatically disable **/ + @Override + public void stop() { + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/FieldCentricTagTracking.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index 88937245bb2d..11b08efbf26d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode; +package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; @@ -35,7 +35,6 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.util.Range; import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; @@ -87,7 +86,7 @@ * */ -@TeleOp(name="Field-Centric Tag Tracking", group = "Demo") +@TeleOp(name="Field-Centric Tag Tracking", group = "TestTeleOp") public class FieldCentricTagTracking extends LinearOpMode { // Adjust these numbers to suit your robot. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/PedroDriveToAprilTag.java similarity index 99% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/PedroDriveToAprilTag.java index a035b1288d58..5e9218db9662 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/PedroDriveToAprilTag.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/PedroDriveToAprilTag.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode; +package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; @@ -35,7 +35,6 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.util.Range; import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; @@ -90,7 +89,7 @@ * */ -@TeleOp(name="Follow AprilTag", group = "Demo") +@TeleOp(name="Follow AprilTag", group = "TestTeleOp") public class PedroDriveToAprilTag extends LinearOpMode { // Adjust these numbers to suit your robot. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TeleopTest_V1.java similarity index 92% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TeleopTest_V1.java index bf96091ee387..42d2ecd02a76 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleopTest_V1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TeleopTest_V1.java @@ -1,6 +1,4 @@ -package org.firstinspires.ftc.teamcode.LOADCode; - -import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.follower; +package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; @@ -11,7 +9,7 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants; -@TeleOp(name = "Example Robot-Centric TeleOp", group = "Main") +@TeleOp(name = "Example Robot-Centric TeleOp", group = "TestTeleOp") public class TeleopTest_V1 extends OpMode { public static Follower follower; @IgnoreConfigurable diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 4156b984b2f3..07b7693b75ca 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -30,8 +30,8 @@ public class Constants { public static PathConstraints pathConstraints = new PathConstraints( 0.99, 100, - 3, - 1); + 1, + 0.5); public static MecanumConstants driveConstants = new MecanumConstants() .maxPower(1) From 6dabceb6e8508052e15b8140711aba8865364c0f Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Mon, 13 Oct 2025 18:58:30 -0400 Subject: [PATCH 020/152] Continue Auto Development --- .../teamcode/LOADCode/Autos/TestAutoR1.java | 82 ++++++++----------- .../ftc/teamcode/pedroPathing/Constants.java | 11 ++- 2 files changed, 43 insertions(+), 50 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java index d1e4acf27298..70235a8840da 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java @@ -22,6 +22,7 @@ public class TestAutoR1 extends OpMode { private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. private final Pose scorePose = new Pose(86, 22, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. + private final Pose leavePose = new Pose(97, 30, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. private final Pose pickupR3PoseA = new Pose(110.4, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. private final Pose pickupR3PoseB = new Pose(121.9, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. private final Pose pickupR2PoseA = new Pose(110.4, 59.5, Math.toRadians(0)); // Middle (Second Set) of Artifacts from the Spike Mark. @@ -29,7 +30,7 @@ public class TestAutoR1 extends OpMode { private final Pose pickupR1PoseA = new Pose(110.4, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. private final Pose pickupR1PoseB = new Pose(121.9, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. - private PathChain grabPickup1, scorePickup, grabPickup2, grabPickup3; + private PathChain grabPickup1, scorePickup, grabPickup2, grabPickup3, leave; public void buildPaths() { @@ -45,7 +46,6 @@ public void buildPaths() { pickupR1PoseB )) .setLinearHeadingInterpolation(pickupR1PoseA.getHeading(), pickupR1PoseA.getHeading()) - .setVelocityConstraint(0.5) .build(); grabPickup2 = follower.pathBuilder() @@ -60,7 +60,6 @@ public void buildPaths() { pickupR2PoseB )) .setLinearHeadingInterpolation(pickupR2PoseA.getHeading(), pickupR2PoseA.getHeading()) - .setVelocityConstraint(0.5) .build(); grabPickup3 = follower.pathBuilder() @@ -75,7 +74,6 @@ public void buildPaths() { pickupR3PoseB )) .setLinearHeadingInterpolation(pickupR3PoseA.getHeading(), pickupR3PoseA.getHeading()) - .setVelocityConstraint(0.5) .build(); scorePickup = follower.pathBuilder() @@ -84,7 +82,13 @@ public void buildPaths() { scorePose )) .setLinearHeadingInterpolation(follower.getHeading(), scorePose.getHeading()) - .setVelocityConstraint(0.5) + .build(); + leave = follower.pathBuilder() + .addPath(new BezierLine( + follower.getPose(), + leavePose + )) + .setLinearHeadingInterpolation(follower.getHeading(), leavePose.getHeading()) .build(); } @@ -98,12 +102,6 @@ public void autonomousPathUpdate() { switch (pathState) { case 0: - //Shoot balls - - setPathState(1); - break; - case 1: - /* You could check for - Follower State: "if(!follower.isBusy()) {}" - Time: "if(pathTimer.getElapsedTimeSeconds() > 1) {}" @@ -111,73 +109,63 @@ public void autonomousPathUpdate() { */ /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { + if(pathTimer.getElapsedTimeSeconds() > 5) { /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ follower.followPath(grabPickup1,true); - setPathState(2); + setPathState(1); } break; - case 2: + case 1: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup1Pose's position */ - if(!follower.isBusy()) { + if(pathTimer.getElapsedTimeSeconds() > 5) { /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ follower.followPath(scorePickup,true); - setPathState(3); + setPathState(2); } break; - case 3: - - //Shoot balls - - setPathState(4); - break; - case 4: + case 2: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { + if(pathTimer.getElapsedTimeSeconds() > 5) { /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ follower.followPath(grabPickup2,true); - setPathState(5); + setPathState(3); } break; - case 5: + case 3: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup2Pose's position */ - if(!follower.isBusy()) { + if(pathTimer.getElapsedTimeSeconds() > 5) { /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ follower.followPath(scorePickup,true); - setPathState(6); + setPathState(4); } break; - case 6: - - //Shoot balls - - setPathState(7); - break; - case 7: + case 4: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { + if(pathTimer.getElapsedTimeSeconds() > 5) { /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ follower.followPath(grabPickup3,true); - setPathState(8); + setPathState(5); } break; - case 8: + case 5: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ - if(!follower.isBusy()) { + if(pathTimer.getElapsedTimeSeconds() > 5) { /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ follower.followPath(scorePickup, true); - setPathState(9); + setPathState(6); } break; - case 9: - - //Shoot balls - - setPathState(10); + case 6: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ + if(pathTimer.getElapsedTimeSeconds() > 5) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(leave, true); + setPathState(7); + } break; - case 10: + case 7: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { + if(pathTimer.getElapsedTimeSeconds() > 5) { /* Set the state to a Case we won't use or define, so it just stops running an new paths */ setPathState(-1); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 07b7693b75ca..f1445e0561bf 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -29,9 +29,14 @@ public class Constants { public static PathConstraints pathConstraints = new PathConstraints( 0.99, - 100, - 1, - 0.5); + 0.1, + 0.1, + 0.009, + 50, + 1.25, + 10, + 1 + ); public static MecanumConstants driveConstants = new MecanumConstants() .maxPower(1) From 35a0d0fa039c4227a2d3ad7dc2f6f1866594d015 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 14 Oct 2025 16:15:05 -0400 Subject: [PATCH 021/152] Worked on autotracking camera turret --- .../teamcode/LOADCode/Autos/TestAutoR1.java | 26 ++--- .../TeleOps/FieldCentricTagTracking.java | 44 ++++++--- .../LOADCode/Tests/ConceptScanServo.java | 99 +++++++++++++++++++ 3 files changed, 143 insertions(+), 26 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java index 70235a8840da..e0bd2fa7b7d0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java @@ -109,7 +109,7 @@ public void autonomousPathUpdate() { */ /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ follower.followPath(grabPickup1,true); setPathState(1); @@ -117,7 +117,7 @@ public void autonomousPathUpdate() { break; case 1: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup1Pose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ follower.followPath(scorePickup,true); setPathState(2); @@ -125,7 +125,7 @@ public void autonomousPathUpdate() { break; case 2: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ follower.followPath(grabPickup2,true); setPathState(3); @@ -133,7 +133,7 @@ public void autonomousPathUpdate() { break; case 3: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup2Pose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ follower.followPath(scorePickup,true); setPathState(4); @@ -141,7 +141,7 @@ public void autonomousPathUpdate() { break; case 4: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ follower.followPath(grabPickup3,true); setPathState(5); @@ -149,7 +149,7 @@ public void autonomousPathUpdate() { break; case 5: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ follower.followPath(scorePickup, true); setPathState(6); @@ -157,7 +157,7 @@ public void autonomousPathUpdate() { break; case 6: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ follower.followPath(leave, true); setPathState(7); @@ -165,7 +165,7 @@ public void autonomousPathUpdate() { break; case 7: /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(pathTimer.getElapsedTimeSeconds() > 5) { + if(!follower.isBusy()) { /* Set the state to a Case we won't use or define, so it just stops running an new paths */ setPathState(-1); } @@ -186,9 +186,6 @@ public void init() { opmodeTimer = new Timer(); opmodeTimer.resetTimer(); - shooting = false; - - follower = Constants.createFollower(hardwareMap); buildPaths(); follower.setStartingPose(startPose); @@ -217,11 +214,16 @@ public void loop() { // Feedback to Driver Hub for debugging telemetry.addData("path state", pathState); - telemetry.addData("shooting", shooting); telemetry.addData("x", follower.getPose().getX()); telemetry.addData("y", follower.getPose().getY()); telemetry.addData("heading", follower.getPose().getHeading()); telemetry.update(); + + if (gamepad1.left_stick_y < -10){ + + }else if (gamepad1.left_stick_y > 10){ + + } } /** We do not use this because everything should automatically disable **/ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index 11b08efbf26d..6a50880b5ace 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -29,12 +29,15 @@ package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; +import android.view.textclassifier.TextClassifierEvent; + import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.CRServo; import com.qualcomm.robotcore.util.Range; import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; @@ -93,11 +96,11 @@ public class FieldCentricTagTracking extends LinearOpMode // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double TURN_GAIN = 0.04 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + final double TURN_GAIN = 0.02; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) final double MAX_AUTO_TURN = 1; // Clip the turn speed to this max value (adjust for your robot) private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera - private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. + private static final int DESIRED_TAG_ID = 24; // Choose the tag you want to approach or set to -1 for ANY tag. private VisionPortal visionPortal; // Used to manage the video source. private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag @@ -117,6 +120,10 @@ public class FieldCentricTagTracking extends LinearOpMode double drive; // Desired forward power/speed (-1 to +1) double strafe; // Desired strafe power/speed (-1 to +1) double turn; // Desired turning power/speed (-1 to +1) + double target_turn = 0; + double angleToTag; + + CRServo turret; // Initialize the Apriltag Detection process initAprilTag(); @@ -137,6 +144,8 @@ public class FieldCentricTagTracking extends LinearOpMode follower.startTeleopDrive(); follower.update(); + turret = hardwareMap.get(CRServo.class, "turret"); + while (opModeIsActive()) { targetFound = false; @@ -165,39 +174,44 @@ public class FieldCentricTagTracking extends LinearOpMode // Tell the driver what we see, and what to do. if (targetFound) { - telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n"); telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); } else { - telemetry.addData("\n>","Drive using joysticks to find valid target\n"); - } - - if (gamepad1.b && !oldToggleVal){ - toggle = !toggle; - oldToggleVal = true; - }else if (!gamepad1.b && oldToggleVal){ - oldToggleVal = false; + telemetry.addData("\n>","Drive using joysticks to find valid target or\n"); + telemetry.addData("\n>", "use D-pad to turn camera to find target"); } drive = -gamepad1.left_stick_y; strafe = -gamepad1.left_stick_x; + turn = -gamepad1.right_stick_x; + + // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . - if (toggle && targetFound) { + if (targetFound) { // Determine heading (tag image rotation) error so we can use them to control the robot automatically. double headingError = desiredTag.ftcPose.bearing; + angleToTag = Math.atan2(desiredTag.ftcPose.y,desiredTag.ftcPose.x) * (180/Math.PI); //Minus robot heading + // follower.getPose().getHeading(); // This gets the robot heading + // Use the turn "gain" to calculate how we want the robot to move. - turn = Range.clip(headingError * TURN_GAIN, -MAX_AUTO_TURN, MAX_AUTO_TURN) ; + target_turn = -Range.clip(headingError * TURN_GAIN, -1, 1) ; telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); } else { // drive using manual POV Joystick mode. Slow things down to make the robot more controllable. - turn = -gamepad1.right_stick_x; + if (gamepad1.dpad_left){ + target_turn = -0.2; + }else if (gamepad1.dpad_right){ + target_turn = 0.2; + }else{ + target_turn = 0; + } telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); } telemetry.update(); @@ -205,6 +219,8 @@ public class FieldCentricTagTracking extends LinearOpMode // Apply desired axes motions to the drivetrain. follower.setTeleOpDrive(drive, strafe, turn, false); follower.update(); + turret.setPower(target_turn); + telemetry.addData("Turret Speed:", target_turn); sleep(10); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java new file mode 100644 index 000000000000..5a3ed2795af9 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java @@ -0,0 +1,99 @@ +/* Copyright (c) 2017 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode.Tests; + +import com.qualcomm.robotcore.eventloop.opmode.Disabled; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.CRServo; +import com.qualcomm.robotcore.hardware.Servo; + +/* + * This OpMode scans a single servo back and forward until Stop is pressed. + * The code is structured as a LinearOpMode + * INCREMENT sets how much to increase/decrease the servo position each cycle + * CYCLE_MS sets the update period. + * + * This code assumes a Servo configured with the name "left_hand" as is found on a Robot. + * + * NOTE: When any servo position is set, ALL attached servos are activated, so ensure that any other + * connected servos are able to move freely before running this test. + * + * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. + * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list + */ +@TeleOp(name = "Servo Test", group = "TestHardware") + +public class ConceptScanServo extends LinearOpMode { + + static final double INCREMENT = 0.01; // amount to slew servo each CYCLE_MS cycle + static final int CYCLE_MS = 10; // period of each cycle + static final double MAX_POS = 1.0; // Maximum rotational position + static final double MIN_POS = 0.0; // Minimum rotational position + + // Define class members + CRServo servo; + double position = (MAX_POS - MIN_POS) / 2; // Start at halfway position + boolean rampUp = true; + + + @Override + public void runOpMode() { + + // Connect to servo (Assume Robot Left Hand) + // Change the text in quotes to match any servo name on your robot. + servo = hardwareMap.get(CRServo.class, "turret"); + + // Wait for the start button + telemetry.addData(">", "Press Start to scan Servo." ); + telemetry.update(); + waitForStart(); + + + // Scan servo till stop pressed. + while(opModeIsActive()){ + + + + // Display the current value + telemetry.addData("Servo Position", "%5.2f", gamepad1.right_stick_x); + telemetry.addData(">", "Press Stop to end test." ); + telemetry.update(); + + // Set the servo to the new position and pause; + servo.setPower(gamepad1.right_stick_x); + sleep(CYCLE_MS); + } + + // Signal done; + telemetry.addData(">", "Done"); + telemetry.update(); + } +} From 0ef4582f15ea3e149a225ce67016a9b14c9f16d6 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 14 Oct 2025 18:06:35 -0400 Subject: [PATCH 022/152] Worked on autotracking camera turret --- .../TeleOps/FieldCentricTagTracking.java | 46 +++++++++++++++++-- .../LOADCode/Tests/ConceptScanServo.java | 9 +++- build.dependencies.gradle | 2 + 3 files changed, 50 insertions(+), 7 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index 6a50880b5ace..7e2a3369be71 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -29,14 +29,17 @@ package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; +import android.service.controls.Control; import android.view.textclassifier.TextClassifierEvent; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; +import com.pedropathing.util.Timer; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.AnalogInput; import com.qualcomm.robotcore.hardware.CRServo; import com.qualcomm.robotcore.util.Range; @@ -52,6 +55,9 @@ import java.util.List; import java.util.concurrent.TimeUnit; +import dev.nextftc.control.ControlSystem; +import dev.nextftc.control.KineticState; + /* * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. * The code assumes a Holonomic (Mecanum or X Drive) Robot. @@ -96,7 +102,7 @@ public class FieldCentricTagTracking extends LinearOpMode // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double TURN_GAIN = 0.02; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + final double TURN_GAIN = 0.0075; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) final double MAX_AUTO_TURN = 1; // Clip the turn speed to this max value (adjust for your robot) private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera @@ -108,6 +114,8 @@ public class FieldCentricTagTracking extends LinearOpMode private boolean toggle = false; private boolean oldToggleVal = false; + public Timer turretVelTimer; + public static Follower follower; @IgnoreConfigurable static TelemetryManager telemetryM; @@ -121,9 +129,17 @@ public class FieldCentricTagTracking extends LinearOpMode double strafe; // Desired strafe power/speed (-1 to +1) double turn; // Desired turning power/speed (-1 to +1) double target_turn = 0; - double angleToTag; + double angleToTag = 0; CRServo turret; + ControlSystem turretPID = ControlSystem.builder() + .posPid(0, 0, 0) + .build(); + AnalogInput turretEncoder; + double turretPos = 0; + double oldTurretTime = 0; + double oldTurretPos = 0; + double turretVel = 0; // Initialize the Apriltag Detection process initAprilTag(); @@ -135,6 +151,8 @@ public class FieldCentricTagTracking extends LinearOpMode follower.setStartingPose(startPose); follower.update(); + turretVelTimer = new Timer(); + // Wait for driver to press start telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); telemetry.addData(">", "Touch START to start OpMode"); @@ -145,12 +163,15 @@ public class FieldCentricTagTracking extends LinearOpMode follower.update(); turret = hardwareMap.get(CRServo.class, "turret"); + turretEncoder = hardwareMap.get(AnalogInput.class,"AxonTurret"); while (opModeIsActive()) { targetFound = false; desiredTag = null; + turretVelTimer.resetTimer(); + // Step through the list of detected tags and look for a matching tag List currentDetections = aprilTag.getDetections(); for (AprilTagDetection detection : currentDetections) { @@ -217,10 +238,25 @@ public class FieldCentricTagTracking extends LinearOpMode telemetry.update(); // Apply desired axes motions to the drivetrain. - follower.setTeleOpDrive(drive, strafe, turn, false); + follower.setTeleOpDrive(drive, strafe, turn, true); follower.update(); - turret.setPower(target_turn); - telemetry.addData("Turret Speed:", target_turn); + + double currentTime = turretVelTimer.getElapsedTime(); + + turretPID.setGoal(new KineticState(turretPos+angleToTag)); + + turretPos = (turretEncoder.getVoltage() / 3.3) * 360; + turretVel = (turretPos-oldTurretPos)/(currentTime-oldTurretTime); + telemetry.addData("Servo Power:", turretPID.calculate(new KineticState(turretPos, turretVel))); + turret.setPower(0); + + oldTurretTime = currentTime; + oldTurretPos = turretPos; + + telemetry.addData("Turret Pos:", turretPos); + telemetry.addData("Target Pos:", turretPos+angleToTag); + telemetry.addData("Turret Vel:", turretVel); + telemetry.addData("Angle To Tag:", angleToTag); sleep(10); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java index 5a3ed2795af9..4f84f046fb25 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java @@ -32,6 +32,7 @@ import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.AnalogInput; import com.qualcomm.robotcore.hardware.CRServo; import com.qualcomm.robotcore.hardware.Servo; @@ -60,7 +61,8 @@ public class ConceptScanServo extends LinearOpMode { // Define class members CRServo servo; - double position = (MAX_POS - MIN_POS) / 2; // Start at halfway position + AnalogInput turretEncoder; + double axonPos = 0; // Start at halfway position boolean rampUp = true; @@ -70,6 +72,8 @@ public void runOpMode() { // Connect to servo (Assume Robot Left Hand) // Change the text in quotes to match any servo name on your robot. servo = hardwareMap.get(CRServo.class, "turret"); + turretEncoder = hardwareMap.get(AnalogInput.class,"AxonTurret"); + // Wait for the start button telemetry.addData(">", "Press Start to scan Servo." ); @@ -80,9 +84,10 @@ public void runOpMode() { // Scan servo till stop pressed. while(opModeIsActive()){ - + axonPos = (turretEncoder.getVoltage() / 3.3) * 360; // Display the current value + telemetry.addData("Encoder Position", axonPos); telemetry.addData("Servo Position", "%5.2f", gamepad1.right_stick_x); telemetry.addData(">", "Press Stop to end test." ); telemetry.update(); diff --git a/build.dependencies.gradle b/build.dependencies.gradle index bf1157dffe90..ba0325aa45f1 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -18,5 +18,7 @@ dependencies { implementation 'com.pedropathing:ftc:2.0.2' implementation 'com.pedropathing:telemetry:1.0.0' implementation 'com.bylazar:fullpanels:1.0.6' + + implementation 'dev.nextftc:control:1.0.0' } From eb16005759231371b710227587d430e60094ac31 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Tue, 14 Oct 2025 18:09:19 -0400 Subject: [PATCH 023/152] Worked on autotracking camera turret --- .../ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index 7e2a3369be71..bfddff3f1f51 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -133,7 +133,7 @@ public class FieldCentricTagTracking extends LinearOpMode CRServo turret; ControlSystem turretPID = ControlSystem.builder() - .posPid(0, 0, 0) + .posPid(1, 0, 0) .build(); AnalogInput turretEncoder; double turretPos = 0; From 0110d803b9d7e7c6cd5f036bfca22bf4d88554a3 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Wed, 15 Oct 2025 17:21:41 -0400 Subject: [PATCH 024/152] Adjusted turret code to avoid NANs --- .../TeleOps/FieldCentricTagTracking.java | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index bfddff3f1f51..6a16599c7242 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -139,6 +139,7 @@ public class FieldCentricTagTracking extends LinearOpMode double turretPos = 0; double oldTurretTime = 0; double oldTurretPos = 0; + double oldTurretVel = 0; double turretVel = 0; // Initialize the Apriltag Detection process @@ -246,12 +247,21 @@ public class FieldCentricTagTracking extends LinearOpMode turretPID.setGoal(new KineticState(turretPos+angleToTag)); turretPos = (turretEncoder.getVoltage() / 3.3) * 360; - turretVel = (turretPos-oldTurretPos)/(currentTime-oldTurretTime); - telemetry.addData("Servo Power:", turretPID.calculate(new KineticState(turretPos, turretVel))); - turret.setPower(0); + double timeDiff = currentTime - oldTurretTime; + if (timeDiff == 0){ + turretVel = oldTurretVel; + }else{ + turretVel = (turretPos - oldTurretPos) / timeDiff; + } + double turretPower = turretPID.calculate(new KineticState(turretPos, turretVel)); + telemetry.addData("Servo Power:", turretPower); + if (gamepad1.b){ + turret.setPower(turretPower); + } oldTurretTime = currentTime; oldTurretPos = turretPos; + oldTurretVel = turretVel; telemetry.addData("Turret Pos:", turretPos); telemetry.addData("Target Pos:", turretPos+angleToTag); From 4e22aa1e246ed1b4b2cb1c2f68f007a8164e624d Mon Sep 17 00:00:00 2001 From: Professor348 Date: Fri, 17 Oct 2025 09:21:05 -0400 Subject: [PATCH 025/152] Updated to Pedropathing 2.0.3 --- .../LOADCode/Tests/{ConceptScanServo.java => ServoTest.java} | 4 +--- build.dependencies.gradle | 2 +- 2 files changed, 2 insertions(+), 4 deletions(-) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/{ConceptScanServo.java => ServoTest.java} (96%) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ServoTest.java similarity index 96% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ServoTest.java index 4f84f046fb25..07439e713cf5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ConceptScanServo.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ServoTest.java @@ -29,12 +29,10 @@ package org.firstinspires.ftc.teamcode.LOADCode.Tests; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.AnalogInput; import com.qualcomm.robotcore.hardware.CRServo; -import com.qualcomm.robotcore.hardware.Servo; /* * This OpMode scans a single servo back and forward until Stop is pressed. @@ -52,7 +50,7 @@ */ @TeleOp(name = "Servo Test", group = "TestHardware") -public class ConceptScanServo extends LinearOpMode { +public class ServoTest extends LinearOpMode { static final double INCREMENT = 0.01; // amount to slew servo each CYCLE_MS cycle static final int CYCLE_MS = 10; // period of each cycle diff --git a/build.dependencies.gradle b/build.dependencies.gradle index ba0325aa45f1..11a2cc27df10 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -15,7 +15,7 @@ dependencies { implementation 'org.firstinspires.ftc:Vision:11.0.0' implementation 'androidx.appcompat:appcompat:1.2.0' - implementation 'com.pedropathing:ftc:2.0.2' + implementation 'com.pedropathing:ftc:2.0.3' implementation 'com.pedropathing:telemetry:1.0.0' implementation 'com.bylazar:fullpanels:1.0.6' From 794d2da735915c3b182105b4cfea1cd6228c5dcd Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Mon, 20 Oct 2025 19:01:38 -0400 Subject: [PATCH 026/152] Worked on tuning turret tracking --- .../TeleOps/FieldCentricTagTracking.java | 71 +++++-------------- 1 file changed, 17 insertions(+), 54 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index 6a16599c7242..9eb692a49ceb 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -41,6 +41,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.AnalogInput; import com.qualcomm.robotcore.hardware.CRServo; +import com.qualcomm.robotcore.hardware.Servo; import com.qualcomm.robotcore.util.Range; import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; @@ -128,19 +129,13 @@ public class FieldCentricTagTracking extends LinearOpMode double drive; // Desired forward power/speed (-1 to +1) double strafe; // Desired strafe power/speed (-1 to +1) double turn; // Desired turning power/speed (-1 to +1) - double target_turn = 0; - double angleToTag = 0; + double headingError = 0; CRServo turret; - ControlSystem turretPID = ControlSystem.builder() - .posPid(1, 0, 0) - .build(); AnalogInput turretEncoder; - double turretPos = 0; - double oldTurretTime = 0; - double oldTurretPos = 0; - double oldTurretVel = 0; - double turretVel = 0; + + double turretPos; + double turretPower = 0; // Initialize the Apriltag Detection process initAprilTag(); @@ -152,8 +147,6 @@ public class FieldCentricTagTracking extends LinearOpMode follower.setStartingPose(startPose); follower.update(); - turretVelTimer = new Timer(); - // Wait for driver to press start telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); telemetry.addData(">", "Touch START to start OpMode"); @@ -171,7 +164,8 @@ public class FieldCentricTagTracking extends LinearOpMode targetFound = false; desiredTag = null; - turretVelTimer.resetTimer(); + turretPos = (turretEncoder.getVoltage() / 3.3) * 360; + // Step through the list of detected tags and look for a matching tag List currentDetections = aprilTag.getDetections(); @@ -209,65 +203,34 @@ public class FieldCentricTagTracking extends LinearOpMode strafe = -gamepad1.left_stick_x; turn = -gamepad1.right_stick_x; - - // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . if (targetFound) { // Determine heading (tag image rotation) error so we can use them to control the robot automatically. - double headingError = desiredTag.ftcPose.bearing; - - angleToTag = Math.atan2(desiredTag.ftcPose.y,desiredTag.ftcPose.x) * (180/Math.PI); //Minus robot heading - // follower.getPose().getHeading(); // This gets the robot heading - - // Use the turn "gain" to calculate how we want the robot to move. - target_turn = -Range.clip(headingError * TURN_GAIN, -1, 1) ; + headingError = -desiredTag.ftcPose.bearing; + turretPower = Math.pow(Math.min(Math.abs(headingError/25),1), 5) * headingError/Math.abs(headingError) * 0.75; telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); } else { - - // drive using manual POV Joystick mode. Slow things down to make the robot more controllable. - if (gamepad1.dpad_left){ - target_turn = -0.2; - }else if (gamepad1.dpad_right){ - target_turn = 0.2; - }else{ - target_turn = 0; - } telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); } telemetry.update(); // Apply desired axes motions to the drivetrain. - follower.setTeleOpDrive(drive, strafe, turn, true); + follower.setTeleOpDrive(drive, strafe, turn/2, true); follower.update(); - double currentTime = turretVelTimer.getElapsedTime(); - - turretPID.setGoal(new KineticState(turretPos+angleToTag)); - - turretPos = (turretEncoder.getVoltage() / 3.3) * 360; - double timeDiff = currentTime - oldTurretTime; - if (timeDiff == 0){ - turretVel = oldTurretVel; - }else{ - turretVel = (turretPos - oldTurretPos) / timeDiff; - } - double turretPower = turretPID.calculate(new KineticState(turretPos, turretVel)); - telemetry.addData("Servo Power:", turretPower); - if (gamepad1.b){ + if (gamepad1.b && targetFound){ turret.setPower(turretPower); + }else{ + turret.setPower(0); } - oldTurretTime = currentTime; - oldTurretPos = turretPos; - oldTurretVel = turretVel; + telemetry.addData("Turret Power:", turretPower); + telemetry.addData("Heading Error:", headingError); + telemetry.addData("Absolute Angle:", turretPos); - telemetry.addData("Turret Pos:", turretPos); - telemetry.addData("Target Pos:", turretPos+angleToTag); - telemetry.addData("Turret Vel:", turretVel); - telemetry.addData("Angle To Tag:", angleToTag); - sleep(10); + sleep(1); } } From 0be4a5d52925d1ea2c4fa570dfc1c4a8ed909e5d Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 21 Oct 2025 17:47:51 -0400 Subject: [PATCH 027/152] Fixed a discontinuity in the turret power formula at x=0 and also added a test telemetry message --- .../LOADCode/TeleOps/FieldCentricTagTracking.java | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index 9eb692a49ceb..583c75116dce 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -209,7 +209,11 @@ public class FieldCentricTagTracking extends LinearOpMode // Determine heading (tag image rotation) error so we can use them to control the robot automatically. headingError = -desiredTag.ftcPose.bearing; - turretPower = Math.pow(Math.min(Math.abs(headingError/25),1), 5) * headingError/Math.abs(headingError) * 0.75; + if (Math.signum(headingError) != 0) { + turretPower = Math.pow(Math.min(Math.abs(headingError/25),1), 5) * Math.signum(headingError) * 0.75; + } else { + turretPower = 0; + } telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); } else { telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); @@ -230,6 +234,8 @@ public class FieldCentricTagTracking extends LinearOpMode telemetry.addData("Heading Error:", headingError); telemetry.addData("Absolute Angle:", turretPos); + telemetry.addData("Ari Test Telemetry:",69420); + sleep(1); } } From 16dc4b39c19ecf19a719eca7154b153f2fc0147e Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 21 Oct 2025 18:20:58 -0400 Subject: [PATCH 028/152] Tweaking the turret power formula further =D 10/21 6:20 --- .../ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java index 583c75116dce..7ea043774a11 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java @@ -210,7 +210,7 @@ public class FieldCentricTagTracking extends LinearOpMode headingError = -desiredTag.ftcPose.bearing; if (Math.signum(headingError) != 0) { - turretPower = Math.pow(Math.min(Math.abs(headingError/25),1), 5) * Math.signum(headingError) * 0.75; + turretPower = Math.pow(Math.min(Math.abs(headingError/20),1), 2) * Math.signum(headingError) * 0.8; } else { turretPower = 0; } From 19a18ebd6947c6628f8dd852e6ddbef4aa231454 Mon Sep 17 00:00:00 2001 From: Dan <141444315+Professor348@users.noreply.github.com> Date: Thu, 23 Oct 2025 20:01:37 -0400 Subject: [PATCH 029/152] Cleaned up and commented some code in FieldCentricTagTracking.java --- ...cking.java => TurretAprilTagTracking.java} | 102 ++++++------------ 1 file changed, 35 insertions(+), 67 deletions(-) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/{FieldCentricTagTracking.java => TurretAprilTagTracking.java} (78%) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java similarity index 78% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java index 7ea043774a11..90c5857303e5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/FieldCentricTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java @@ -29,20 +29,14 @@ package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; -import android.service.controls.Control; -import android.view.textclassifier.TextClassifierEvent; - import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; -import com.pedropathing.util.Timer; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.AnalogInput; import com.qualcomm.robotcore.hardware.CRServo; -import com.qualcomm.robotcore.hardware.Servo; -import com.qualcomm.robotcore.util.Range; import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; @@ -56,9 +50,6 @@ import java.util.List; import java.util.concurrent.TimeUnit; -import dev.nextftc.control.ControlSystem; -import dev.nextftc.control.KineticState; - /* * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. * The code assumes a Holonomic (Mecanum or X Drive) Robot. @@ -96,77 +87,64 @@ * */ -@TeleOp(name="Field-Centric Tag Tracking", group = "TestTeleOp") -public class FieldCentricTagTracking extends LinearOpMode +@TeleOp(name="Turret April-Tag Tracking", group = "TestTeleOp") +public class TurretAprilTagTracking extends LinearOpMode { - // Adjust these numbers to suit your robot. - // Set the GAIN constants to control the relationship between the measured position error, and how much power is - // applied to the drive motors to correct the error. - // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double TURN_GAIN = 0.0075; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) - final double MAX_AUTO_TURN = 1; // Clip the turn speed to this max value (adjust for your robot) - private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera - private static final int DESIRED_TAG_ID = 24; // Choose the tag you want to approach or set to -1 for ANY tag. + private static final int DESIRED_TAG_ID = 24; // Choose the tag you want to approach or set to -1 for ANY tag. private VisionPortal visionPortal; // Used to manage the video source. private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. - private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag - - private boolean toggle = false; - private boolean oldToggleVal = false; - - public Timer turretVelTimer; - - public static Follower follower; + public static Follower follower; // Used for managing the PedroPathing path follower @IgnoreConfigurable - static TelemetryManager telemetryM; - /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ + static TelemetryManager telemetryM; // Used for putting telemetry data on Panels + + // Start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(60,96, Math.toRadians(0)); @Override public void runOpMode() { - boolean targetFound; // Set to true when an AprilTag target is detected - double drive; // Desired forward power/speed (-1 to +1) - double strafe; // Desired strafe power/speed (-1 to +1) - double turn; // Desired turning power/speed (-1 to +1) - double headingError = 0; + boolean targetFound; // Set to true when an AprilTag target is detected + double headingError = 0; // The error in degrees in the turret's angle + // Used to store the hardware objects for the robot CRServo turret; AnalogInput turretEncoder; - double turretPos; - double turretPower = 0; + double turretPos; // Used to store the current angle of the turret + double turretPower = 0; // Used to store the calculated power to output to the turret servo - // Initialize the Apriltag Detection process - initAprilTag(); + initAprilTag(); // Initialize the Apriltag Detection process if (USE_WEBCAM) setManualExposure(6, 250); // Use low exposure time to reduce motion blur - follower = Constants.createFollower(hardwareMap); - follower.setStartingPose(startPose); - follower.update(); + follower = Constants.createFollower(hardwareMap); // Initializes the PedroPathing path follower + follower.setStartingPose(startPose); // Sets the initial position of the robot on the field + follower.update(); // Applies the initialization - // Wait for driver to press start telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); - waitForStart(); - follower.startTeleopDrive(); - follower.update(); + waitForStart(); // Wait for driver to press start + + follower.startTeleopDrive(); // Activate the manual drive function for the drivetrain + follower.update(); // Apply the activation + // Fetch the actual hardware objects and store them in their respective variables turret = hardwareMap.get(CRServo.class, "turret"); turretEncoder = hardwareMap.get(AnalogInput.class,"AxonTurret"); while (opModeIsActive()) { + // Used to indicate whether or not a valid AprilTag has been detected targetFound = false; - desiredTag = null; + // Used to hold the data for a detected AprilTag + AprilTagDetection desiredTag = null; + // Read the Axon servo encoder position and convert it from a voltage to an angle in degrees turretPos = (turretEncoder.getVoltage() / 3.3) * 360; - // Step through the list of detected tags and look for a matching tag List currentDetections = aprilTag.getDetections(); for (AprilTagDetection detection : currentDetections) { @@ -195,18 +173,13 @@ public class FieldCentricTagTracking extends LinearOpMode telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); } else { - telemetry.addData("\n>","Drive using joysticks to find valid target or\n"); - telemetry.addData("\n>", "use D-pad to turn camera to find target"); + telemetry.addData("\n>","Drive using joysticks to find a valid target\n"); } - drive = -gamepad1.left_stick_y; - strafe = -gamepad1.left_stick_x; - turn = -gamepad1.right_stick_x; - - // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . - if (targetFound) { - - // Determine heading (tag image rotation) error so we can use them to control the robot automatically. + // If B on Gamepad1 is being pressed, AND we have found the desired target, automatically aim the turret at the AprilTag. + // Otherwise, stop moving + if (gamepad1.b && targetFound) { + // Determine heading error so we can use them to control the robot automatically. headingError = -desiredTag.ftcPose.bearing; if (Math.signum(headingError) != 0) { @@ -214,22 +187,17 @@ public class FieldCentricTagTracking extends LinearOpMode } else { turretPower = 0; } - telemetry.addData("Auto","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + + turret.setPower(turretPower); + } else { - telemetry.addData("Manual","Drive %5.2f, Strafe %5.2f, Turn %5.2f ", drive, strafe, turn); + turretPower = 0; } - telemetry.update(); // Apply desired axes motions to the drivetrain. - follower.setTeleOpDrive(drive, strafe, turn/2, true); + follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x/2, true); follower.update(); - if (gamepad1.b && targetFound){ - turret.setPower(turretPower); - }else{ - turret.setPower(0); - } - telemetry.addData("Turret Power:", turretPower); telemetry.addData("Heading Error:", headingError); telemetry.addData("Absolute Angle:", turretPos); From 27670956bd0337f325db90c82de48b4d5298a9fd Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Thu, 23 Oct 2025 23:28:41 -0400 Subject: [PATCH 030/152] Cleaned up and commented some more code in FieldCentricTagTracking.java --- .../teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java index 90c5857303e5..cdce2411b45e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java @@ -111,7 +111,7 @@ public class TurretAprilTagTracking extends LinearOpMode AnalogInput turretEncoder; double turretPos; // Used to store the current angle of the turret - double turretPower = 0; // Used to store the calculated power to output to the turret servo + double turretPower; // Used to store the calculated power to output to the turret servo initAprilTag(); // Initialize the Apriltag Detection process @@ -187,13 +187,12 @@ public class TurretAprilTagTracking extends LinearOpMode } else { turretPower = 0; } - - turret.setPower(turretPower); - } else { turretPower = 0; } + turret.setPower(turretPower); + // Apply desired axes motions to the drivetrain. follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x/2, true); follower.update(); From 277f52fd953ce625b272d6fbfab92e7b564ab6cb Mon Sep 17 00:00:00 2001 From: Professor348 Date: Sat, 25 Oct 2025 19:15:05 -0400 Subject: [PATCH 031/152] Update TurretAprilTagTracking.java Testing the Discord webhook --- .../ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java index cdce2411b45e..8bb0990dc051 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java @@ -98,7 +98,7 @@ public class TurretAprilTagTracking extends LinearOpMode @IgnoreConfigurable static TelemetryManager telemetryM; // Used for putting telemetry data on Panels - // Start Pose of our robot. This can be changed or saved from the autonomous period. + // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(60,96, Math.toRadians(0)); @Override public void runOpMode() From 0f09e0a02cafb59d48cbea12ab387cd4ca6851df Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 27 Oct 2025 18:59:17 -0400 Subject: [PATCH 032/152] Turret Tuning --- .../TeleOps/TurretAprilTagTracking.java | 23 +++++++++---------- 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java index 8bb0990dc051..780d8b6ef778 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java @@ -96,7 +96,7 @@ public class TurretAprilTagTracking extends LinearOpMode private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. public static Follower follower; // Used for managing the PedroPathing path follower @IgnoreConfigurable - static TelemetryManager telemetryM; // Used for putting telemetry data on Panels + public TelemetryManager telemetryM; // Used for putting telemetry data on Panels // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(60,96, Math.toRadians(0)); @@ -133,7 +133,7 @@ public class TurretAprilTagTracking extends LinearOpMode // Fetch the actual hardware objects and store them in their respective variables turret = hardwareMap.get(CRServo.class, "turret"); - turretEncoder = hardwareMap.get(AnalogInput.class,"AxonTurret"); + turretEncoder = hardwareMap.get(AnalogInput.class,"turretEncoder"); while (opModeIsActive()) { @@ -155,6 +155,8 @@ public class TurretAprilTagTracking extends LinearOpMode // Yes, we want to use this tag. targetFound = true; desiredTag = detection; + // Determine heading error so we can use them to control the robot automatically. + headingError = -desiredTag.ftcPose.bearing; break; // don't look any further. } else { // This tag is in the library, but we do not want to track it right now. @@ -178,20 +180,18 @@ public class TurretAprilTagTracking extends LinearOpMode // If B on Gamepad1 is being pressed, AND we have found the desired target, automatically aim the turret at the AprilTag. // Otherwise, stop moving - if (gamepad1.b && targetFound) { - // Determine heading error so we can use them to control the robot automatically. - headingError = -desiredTag.ftcPose.bearing; - - if (Math.signum(headingError) != 0) { - turretPower = Math.pow(Math.min(Math.abs(headingError/20),1), 2) * Math.signum(headingError) * 0.8; + if (gamepad1.b) { + if (Math.abs(headingError) >= 0.5) { + turretPower = Math.pow(Math.min(Math.abs(headingError/7.5),1), 2) * Math.signum(headingError) * 0.2; } else { turretPower = 0; } } else { turretPower = 0; } - - turret.setPower(turretPower); + if(gamepad1.b){ + turret.setPower(turretPower); + } // Apply desired axes motions to the drivetrain. follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x/2, true); @@ -201,8 +201,7 @@ public class TurretAprilTagTracking extends LinearOpMode telemetry.addData("Heading Error:", headingError); telemetry.addData("Absolute Angle:", turretPos); - telemetry.addData("Ari Test Telemetry:",69420); - + telemetry.update(); sleep(1); } } From c5101858941a5088301a5ca3c376d9a09ad5b2d9 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 28 Oct 2025 18:08:30 -0400 Subject: [PATCH 033/152] Semi-finished auto-aiming turret --- .../LOADCode/TeleOps/TurretLocalization.java | 290 ++++++++++++++++++ .../ftc/teamcode/pedroPathing/Constants.java | 4 +- 2 files changed, 292 insertions(+), 2 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java new file mode 100644 index 000000000000..8aaa6da054c3 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java @@ -0,0 +1,290 @@ +/* Copyright (c) 2023 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; + +import com.bylazar.configurables.annotations.IgnoreConfigurable; +import com.bylazar.telemetry.TelemetryManager; +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.AnalogInput; +import com.qualcomm.robotcore.hardware.CRServo; + +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl; +import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl; +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +import java.util.List; +import java.util.concurrent.TimeUnit; + +/* + * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. + * The code assumes a Holonomic (Mecanum or X Drive) Robot. + * + * For an introduction to AprilTags, see the ftc-docs link below: + * https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html + * + * When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera. + * This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below. + * https://ftc-docs.firstinspires.org/apriltag-detection-values + * + * The drive goal is to rotate to keep the Tag centered in the camera, while strafing to be directly in front of the tag, and + * driving towards the tag to achieve the desired distance. + * To reduce any motion blur (which will interrupt the detection process) the Camera exposure is reduced to a very low value (5mS) + * You can determine the best Exposure and Gain values by using the ConceptAprilTagOptimizeExposure OpMode in this Samples folder. + * + * The code assumes a Robot Configuration with motors named: front_left_drive and front_right_drive, back_left_drive and back_right_drive. + * The motor directions must be set so a positive power goes forward on all wheels. + * This sample assumes that the current game AprilTag Library (usually for the current season) is being loaded by default, + * so you should choose to approach a valid tag ID. + * + * Under manual control, the left stick will move forward/back & left/right. The right stick will rotate the robot. + * Manually drive the robot until it displays Target data on the Driver Station. + * + * Press and hold the *Left Bumper* to enable the automatic "Drive to target" mode. + * Release the Left Bumper to return to manual driving mode. + * + * Under "Drive To Target" mode, the robot has three goals: + * 1) Turn the robot to always keep the Tag centered on the camera frame. (Use the Target Bearing to turn the robot.) + * 2) Strafe the robot towards the centerline of the Tag, so it approaches directly in front of the tag. (Use the Target Yaw to strafe the robot) + * 3) Drive towards the Tag to get to the desired distance. (Use Tag Range to drive the robot forward/backward) + * + * Use DESIRED_DISTANCE to set how close you want the robot to get to the target. + * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. + * + */ + +@TeleOp(name="Turret Localization", group = "TestTeleOp") +public class TurretLocalization extends LinearOpMode +{ + private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera + private static final int DESIRED_TAG_ID = 24; // Choose the tag you want to approach or set to -1 for ANY tag. + private VisionPortal visionPortal; // Used to manage the video source. + private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. + public static Follower follower; // Used for managing the PedroPathing path follower + @IgnoreConfigurable + public TelemetryManager telemetryM; // Used for putting telemetry data on Panels + + // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. + private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); + + @Override public void runOpMode() + { + boolean targetFound; // Set to true when an AprilTag target is detected + double headingError = 0; // The error in degrees in the turret's angle + + // Used to store the hardware objects for the robot + CRServo turret; + AnalogInput turretEncoder; + + double turretPos; // Used to store the current angle of the turret + double turretPower; // Used to store the calculated power to output to the turret servo + boolean runTurret = true; + + int[] goalCoords = new int[2]; + if (DESIRED_TAG_ID == 24){ + goalCoords[0] = 144; + goalCoords[1] = 144; + }else if (DESIRED_TAG_ID == 20){ + goalCoords[0] = 0; + goalCoords[1] = 144; + } + + initAprilTag(); // Initialize the Apriltag Detection process + + if (USE_WEBCAM) + setManualExposure(6, 250); // Use low exposure time to reduce motion blur + + follower = Constants.createFollower(hardwareMap); // Initializes the PedroPathing path follower + follower.setStartingPose(startPose); // Sets the initial position of the robot on the field + follower.update(); // Applies the initialization + + telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); + telemetry.addData(">", "Touch START to start OpMode"); + telemetry.update(); + + waitForStart(); // Wait for driver to press start + + follower.startTeleopDrive(); // Activate the manual drive function for the drivetrain + follower.update(); // Apply the activation + + // Fetch the actual hardware objects and store them in their respective variables + turret = hardwareMap.get(CRServo.class, "turret"); + turretEncoder = hardwareMap.get(AnalogInput.class,"turretEncoder"); + + while (opModeIsActive()) + { + // Used to indicate whether or not a valid AprilTag has been detected + targetFound = false; + // Used to hold the data for a detected AprilTag + AprilTagDetection desiredTag = null; + + // Read the Axon servo encoder position and convert it from a voltage to an angle in degrees + turretPos = Math.abs(((turretEncoder.getVoltage() / 3.3) * 360) - 360); + + // Step through the list of detected tags and look for a matching tag + List currentDetections = aprilTag.getDetections(); + for (AprilTagDetection detection : currentDetections) { + // Look to see if we have size info on this tag. + if (detection.metadata != null) { + // Check to see if we want to track towards this tag. + if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) { + // Yes, we want to use this tag. + targetFound = true; + desiredTag = detection; + // Determine heading error so we can use them to control the robot automatically. + headingError = -desiredTag.ftcPose.bearing; + break; // don't look any further. + } else { + // This tag is in the library, but we do not want to track it right now. + telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id); + } + } else { + // This tag is NOT in the library, so we don't have enough information to track to it. + telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id); + } + } + + // Tell the driver what we see, and what to do. + if (targetFound) { + telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); + telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); + telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); + telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); + } else { + telemetry.addData("\n>","Drive using joysticks to find a valid target\n"); + } + + double targetAngle; + double[] robotPose = {follower.getPose().getX(), follower.getPose().getY()}; + targetAngle = Math.toDegrees(Math.atan2(goalCoords[1]-robotPose[1], goalCoords[0]-robotPose[0])) - Math.toDegrees(follower.getPose().getHeading()); + targetAngle = (180 + targetAngle) % 360; + + double angleDiff = (targetAngle - turretPos); + turretPower = -Math.pow(Math.min(Math.abs(angleDiff/60),1), 1.33) * Math.signum(angleDiff); + + if (gamepad1.bWasPressed()){ + runTurret = !runTurret; + } + + if(runTurret){ + turret.setPower(turretPower); + }else{ + turret.setPower(0); + } + + // Apply desired axes motions to the drivetrain. + follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x/2, true); + follower.update(); + + telemetry.addData("Target Angle:", targetAngle); + telemetry.addData("Turret Angle:", turretPos); + telemetry.addData("Turret Error:", angleDiff); + telemetry.addData("Turret Power:", turretPower); + telemetry.addData("Robot Heading:", Math.toDegrees(follower.getPose().getHeading())); + + telemetry.update(); + } + } + + /** + * Initialize the AprilTag processor. + */ + private void initAprilTag() { + // Create the AprilTag processor by using a builder. + aprilTag = new AprilTagProcessor.Builder().build(); + + // Adjust Image Decimation to trade-off detection-range for detection-rate. + // e.g. Some typical detection data using a Logitech C920 WebCam + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second + // Note: Decimation can be changed on-the-fly to adapt during a match. + aprilTag.setDecimation(3); + + // Create the vision portal by using a builder. + if (USE_WEBCAM) { + visionPortal = new VisionPortal.Builder() + .setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")) + .addProcessor(aprilTag) + .build(); + } else { + visionPortal = new VisionPortal.Builder() + .setCamera(BuiltinCameraDirection.BACK) + .addProcessor(aprilTag) + .build(); + } + } + + /* + Manually set the camera gain and exposure. + This can only be called AFTER calling initAprilTag(), and only works for Webcams; + */ + private void setManualExposure(int exposureMS, int gain) { + // Wait for the camera to be open, then use the controls + + if (visionPortal == null) { + return; + } + + // Make sure camera is streaming before we try to set the exposure controls + if (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING) { + telemetry.addData("Camera", "Waiting"); + telemetry.update(); + while (!isStopRequested() && (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING)) { + sleep(20); + } + telemetry.addData("Camera", "Ready"); + telemetry.update(); + } + + // Set camera controls unless we are stopping. + if (!isStopRequested()) + { + ExposureControl exposureControl = visionPortal.getCameraControl(ExposureControl.class); + if (exposureControl.getMode() != ExposureControl.Mode.Manual) { + exposureControl.setMode(ExposureControl.Mode.Manual); + sleep(50); + } + exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS); + sleep(20); + GainControl gainControl = visionPortal.getCameraControl(GainControl.class); + gainControl.setGain(gain); + sleep(20); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index f1445e0561bf..a7335ed6b1d0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -52,8 +52,8 @@ public class Constants { .yVelocity(46.4157); public static PinpointConstants localizerConstants = new PinpointConstants() - .forwardPodY(-1.5) - .strafePodX(6.5) + .forwardPodY(-2) + .strafePodX(4.5) .distanceUnit(DistanceUnit.INCH) .hardwareMapName("pinpoint") .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) From 00345b8e19e95017921636bb3ac7ff75b2fde65c Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Thu, 30 Oct 2025 13:44:50 -0400 Subject: [PATCH 034/152] Working on wraparound issues with the turret. We will try Daniel's reverse power method on Monday, and if it does not work, we will try my dead zone method. --- .../LOADCode/TeleOps/TurretLocalization.java | 21 ++++++++++++++++--- 1 file changed, 18 insertions(+), 3 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java index 8aaa6da054c3..51b18cc5fb8b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java @@ -113,6 +113,9 @@ public class TurretLocalization extends LinearOpMode double turretPos; // Used to store the current angle of the turret double turretPower; // Used to store the calculated power to output to the turret servo boolean runTurret = true; + double targetAngle; + double lastTurretPos; + int wraparoundTrigger = 0; int[] goalCoords = new int[2]; if (DESIRED_TAG_ID == 24){ @@ -144,6 +147,7 @@ public class TurretLocalization extends LinearOpMode // Fetch the actual hardware objects and store them in their respective variables turret = hardwareMap.get(CRServo.class, "turret"); turretEncoder = hardwareMap.get(AnalogInput.class,"turretEncoder"); + lastTurretPos = Math.abs(((turretEncoder.getVoltage() / 3.3) * 360) - 360); while (opModeIsActive()) { @@ -188,35 +192,46 @@ public class TurretLocalization extends LinearOpMode telemetry.addData("\n>","Drive using joysticks to find a valid target\n"); } - double targetAngle; + double[] robotPose = {follower.getPose().getX(), follower.getPose().getY()}; + targetAngle = Math.toDegrees(Math.atan2(goalCoords[1]-robotPose[1], goalCoords[0]-robotPose[0])) - Math.toDegrees(follower.getPose().getHeading()); targetAngle = (180 + targetAngle) % 360; double angleDiff = (targetAngle - turretPos); - turretPower = -Math.pow(Math.min(Math.abs(angleDiff/60),1), 1.33) * Math.signum(angleDiff); + turretPower = -Math.pow(Math.min(Math.abs(angleDiff/60),1), (4f/3f)) * Math.signum(angleDiff); + + if (Math.abs(turretPos-lastTurretPos) <= 10){ + wraparoundTrigger += (int)Math.signum(turretPos - 180); + } if (gamepad1.bWasPressed()){ runTurret = !runTurret; } - if(runTurret){ turret.setPower(turretPower); }else{ turret.setPower(0); } + // TODO We will work on Daniel's deadzone method next meeting, If that does not work, we will work on Ari's! + + // Apply desired axes motions to the drivetrain. follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x/2, true); follower.update(); + lastTurretPos = turretPos; + telemetry.addData("Target Angle:", targetAngle); telemetry.addData("Turret Angle:", turretPos); telemetry.addData("Turret Error:", angleDiff); telemetry.addData("Turret Power:", turretPower); telemetry.addData("Robot Heading:", Math.toDegrees(follower.getPose().getHeading())); + telemetry.addData("Wraparound Trigger This Time: ", wraparoundTrigger); telemetry.update(); + } } From e8098f0b537e28a87960388b811d079e2f29d80e Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Thu, 30 Oct 2025 13:46:19 -0400 Subject: [PATCH 035/152] Working on wraparound issues with the turret. We will try Daniel's reverse power method on Monday, and if it does not work, we will try my dead zone method. I added the barebones system for wraparound detection, and a telemetry output to measure it as well. --- .../ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java index 51b18cc5fb8b..79e01c5cef35 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java @@ -217,7 +217,7 @@ public class TurretLocalization extends LinearOpMode // TODO We will work on Daniel's deadzone method next meeting, If that does not work, we will work on Ari's! - // Apply desired axes motions to the drivetrain. + // Apply desired axes motions to the drivetrain follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x/2, true); follower.update(); From af1c3b7be052f6a9700be845a181b390b382cce3 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Sat, 1 Nov 2025 11:56:55 -0400 Subject: [PATCH 036/152] Added (But didn't enable) a PID controller for aiming the turret. --- .../LOADCode/TeleOps/TurretLocalization.java | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java index 79e01c5cef35..2bb8fa2e0194 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java @@ -50,6 +50,9 @@ import java.util.List; import java.util.concurrent.TimeUnit; +import dev.nextftc.control.ControlSystem; +import dev.nextftc.control.KineticState; + /* * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. * The code assumes a Holonomic (Mecanum or X Drive) Robot. @@ -126,6 +129,10 @@ public class TurretLocalization extends LinearOpMode goalCoords[1] = 144; } + ControlSystem turretPID = ControlSystem.builder() + .posPid(0,0,0) + .build(); + initAprilTag(); // Initialize the Apriltag Detection process if (USE_WEBCAM) @@ -205,6 +212,11 @@ public class TurretLocalization extends LinearOpMode wraparoundTrigger += (int)Math.signum(turretPos - 180); } + if (false){ + turretPID.setGoal(new KineticState(targetAngle)); + turretPower = turretPID.calculate(new KineticState(turretPos)); + } + if (gamepad1.bWasPressed()){ runTurret = !runTurret; } From 1a5e1b4732ddfd666dadb021739cbe7218c54bd7 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 3 Nov 2025 18:11:08 -0500 Subject: [PATCH 037/152] Installed PID on turret, worked on some tuning --- .../LOADCode/TeleOps/TurretLocalization.java | 84 +++++++++++++------ 1 file changed, 59 insertions(+), 25 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java index 2bb8fa2e0194..ab0879122222 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java @@ -29,6 +29,7 @@ package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; +import com.bylazar.configurables.annotations.Configurable; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; @@ -52,6 +53,8 @@ import dev.nextftc.control.ControlSystem; import dev.nextftc.control.KineticState; +import dev.nextftc.control.feedback.PIDCoefficients; +import kotlin.jvm.JvmField; /* * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. @@ -89,18 +92,22 @@ * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. * */ - +@Configurable @TeleOp(name="Turret Localization", group = "TestTeleOp") public class TurretLocalization extends LinearOpMode { private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera - private static final int DESIRED_TAG_ID = 24; // Choose the tag you want to approach or set to -1 for ANY tag. + int DESIRED_TAG_ID = 24; // Choose the tag you want to approach or set to -1 for ANY tag. private VisionPortal visionPortal; // Used to manage the video source. private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. public static Follower follower; // Used for managing the PedroPathing path follower - @IgnoreConfigurable public TelemetryManager telemetryM; // Used for putting telemetry data on Panels + //Turret PID coefficients + public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.75, 0.005, 200); + + public static int turretDeadZoneSize = 15; + // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); @@ -116,21 +123,14 @@ public class TurretLocalization extends LinearOpMode double turretPos; // Used to store the current angle of the turret double turretPower; // Used to store the calculated power to output to the turret servo boolean runTurret = true; + boolean useTurretPID = true; double targetAngle; double lastTurretPos; int wraparoundTrigger = 0; - int[] goalCoords = new int[2]; - if (DESIRED_TAG_ID == 24){ - goalCoords[0] = 144; - goalCoords[1] = 144; - }else if (DESIRED_TAG_ID == 20){ - goalCoords[0] = 0; - goalCoords[1] = 144; - } ControlSystem turretPID = ControlSystem.builder() - .posPid(0,0,0) + .posPid(new PIDCoefficients(turretCoefficients.kP/100000000, turretCoefficients.kI/100000000, turretCoefficients.kD/100000000)) .build(); initAprilTag(); // Initialize the Apriltag Detection process @@ -158,6 +158,23 @@ public class TurretLocalization extends LinearOpMode while (opModeIsActive()) { + + if (gamepad1.yWasPressed()){ + if (DESIRED_TAG_ID == 24){ + DESIRED_TAG_ID = 20; + } else { + DESIRED_TAG_ID = 24; + } + } + + if (DESIRED_TAG_ID == 24){ + goalCoords[0] = 144; + goalCoords[1] = 144; + }else if (DESIRED_TAG_ID == 20){ + goalCoords[0] = 0; + goalCoords[1] = 144; + } + // Used to indicate whether or not a valid AprilTag has been detected targetFound = false; // Used to hold the data for a detected AprilTag @@ -190,6 +207,11 @@ public class TurretLocalization extends LinearOpMode } // Tell the driver what we see, and what to do. + if (DESIRED_TAG_ID == 24){ + telemetry.addData("Goal Selected: ","Red"); + } else { + telemetry.addData("Goal Selected: ","Blue"); + } if (targetFound) { telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); @@ -199,22 +221,31 @@ public class TurretLocalization extends LinearOpMode telemetry.addData("\n>","Drive using joysticks to find a valid target\n"); } + // This block finds the robot position from it's odometry data and calculates the angle between the selected goal and the robot, adjusting the camera to match that angle double[] robotPose = {follower.getPose().getX(), follower.getPose().getY()}; - targetAngle = Math.toDegrees(Math.atan2(goalCoords[1]-robotPose[1], goalCoords[0]-robotPose[0])) - Math.toDegrees(follower.getPose().getHeading()); targetAngle = (180 + targetAngle) % 360; - + targetAngle = Math.min(Math.max(targetAngle, turretDeadZoneSize), 360-turretDeadZoneSize); double angleDiff = (targetAngle - turretPos); turretPower = -Math.pow(Math.min(Math.abs(angleDiff/60),1), (4f/3f)) * Math.signum(angleDiff); - if (Math.abs(turretPos-lastTurretPos) <= 10){ - wraparoundTrigger += (int)Math.signum(turretPos - 180); + if (gamepad1.aWasPressed()){ + useTurretPID = !useTurretPID; } - - if (false){ + if (useTurretPID){ turretPID.setGoal(new KineticState(targetAngle)); - turretPower = turretPID.calculate(new KineticState(turretPos)); + turretPower = -turretPID.calculate(new KineticState(turretPos)); + telemetry.addData("Turret Control System:", "PID"); + }else{ + telemetry.addData("Turret Control System:", "Non-PID"); + } + + if (Math.abs(turretPos-lastTurretPos) >= 30){ + wraparoundTrigger += (int)Math.signum(turretPos - 180); + } + if (wraparoundTrigger != 0) { + //turretPower = Math.max(Math.min(-wraparoundTrigger, 0.1), -0.1); } if (gamepad1.bWasPressed()){ @@ -235,15 +266,18 @@ public class TurretLocalization extends LinearOpMode lastTurretPos = turretPos; - telemetry.addData("Target Angle:", targetAngle); - telemetry.addData("Turret Angle:", turretPos); - telemetry.addData("Turret Error:", angleDiff); - telemetry.addData("Turret Power:", turretPower); - telemetry.addData("Robot Heading:", Math.toDegrees(follower.getPose().getHeading())); + telemetry.addData("Target Angle", targetAngle); + telemetry.addData("Turret Angle", turretPos); + telemetry.addData("Turret Error", angleDiff); + telemetry.addData("Turret Power", turretPower); + telemetry.addData("Robot Heading", Math.toDegrees(follower.getPose().getHeading())); telemetry.addData("Wraparound Trigger This Time: ", wraparoundTrigger); + telemetry.addData("-", "---------------------------------------------"); + telemetry.addData("kP", turretCoefficients.kP); + telemetry.addData("kI", turretCoefficients.kI); + telemetry.addData("kD", turretCoefficients.kD); telemetry.update(); - } } From 843a6f50c4d965b57fd710e67d84c350d8f0b081 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 4 Nov 2025 16:48:17 -0500 Subject: [PATCH 038/152] Added new "LoadHardwareClass" hardware manager, as well as a new teleop that uses it All the new features are organized into a new "Main_" folder to seperate our new clean code from the testing stuff. --- .../LOADCode/Main_/LoadHardwareClass.java | 154 ++++++++++++++++++ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 88 ++++++++++ 2 files changed, 242 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java new file mode 100644 index 000000000000..8f7ec768ac3a --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -0,0 +1,154 @@ +/* Copyright (c) 2022 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode.Main_; + +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.Servo; +import com.qualcomm.robotcore.util.Range; + +/* + * This file works in conjunction with the External Hardware Class sample called: ConceptExternalHardwareClass.java + * Please read the explanations in that Sample about how to use this class definition. + * + * This file defines a Java Class that performs all the setup and configuration for a sample robot's hardware (motors and sensors). + * It assumes three motors (left_drive, right_drive and arm) and two servos (left_hand and right_hand) + * + * This one file/class can be used by ALL of your OpModes without having to cut & paste the code each time. + * + * Where possible, the actual hardware objects are "abstracted" (or hidden) so the OpMode code just makes calls into the class, + * rather than accessing the internal hardware directly. This is why the objects are declared "private". + * + * Use Android Studio to Copy this Class, and Paste it into your team's code folder with *exactly the same name*. + * + * Or... In OnBot Java, add a new file named RobotHardware.java, select this sample, and select Not an OpMode. + * Also add a new OpMode, select the sample ConceptExternalHardwareClass.java, and select TeleOp. + * + */ + +public class LoadHardwareClass { + + /* Declare OpMode members. */ + private LinearOpMode myOpMode = null; // gain access to methods in the calling OpMode. + + // Motors and servos go here + // Drivetrain + private DcMotor frontLeft = null; + private DcMotor frontRight = null; + private DcMotor backLeft = null; + private DcMotor backRight = null; + //Other + + // Public drive constants, empty for now + + public final double maxSpeed = 1.0; // make this slower for outreaches + + // Constructor that allows the OpMode to pass a reference to itself. + public LoadHardwareClass(LinearOpMode opmode) { + myOpMode = opmode; + } + + /** + * Initialize all the robot's hardware. + * This method must be called ONCE when the OpMode is initialized. + *

+ * All of the hardware devices are accessed via the hardware map, and initialized. + */ + public void init() { + // Define and initialize motors (note: need to use reference to actual OpMode). + frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "frontLeft"); + frontRight = myOpMode.hardwareMap.get(DcMotor.class, "frontRight"); + backLeft = myOpMode.hardwareMap.get(DcMotor.class, "backLeft"); + backRight = myOpMode.hardwareMap.get(DcMotor.class, "backRight"); + + // Set motor directions + frontLeft.setDirection(DcMotor.Direction.REVERSE); + frontRight.setDirection(DcMotor.Direction.FORWARD); + backLeft.setDirection(DcMotor.Direction.REVERSE); + backRight.setDirection(DcMotor.Direction.FORWARD); + + // If the drivetrain motors have encoders, handle all that here + + + + // Define and initialize servos here + + //Set servo directions + + myOpMode.telemetry.addData(">", "Hardware Initialized"); + myOpMode.telemetry.update(); + } + + + public void mecanumDrive(double forward, double strafe, double rotate) { + // This calculates the power needed for each wheel based on the amount of forward, + // strafe right, and rotate + double frontLeftPower = forward + strafe + rotate; + double frontRightPower = forward - strafe - rotate; + double backRightPower = forward + strafe - rotate; + double backLeftPower = forward - strafe + rotate; + + double maxPower = 1.0; + + // This is needed to make sure we don't pass > 1.0 to any wheel + // It allows us to keep all of the motors in proportion to what they should + // be and not get clipped + maxPower = Math.max(maxPower, Math.abs(frontLeftPower)); + maxPower = Math.max(maxPower, Math.abs(frontRightPower)); + maxPower = Math.max(maxPower, Math.abs(backRightPower)); + maxPower = Math.max(maxPower, Math.abs(backLeftPower)); + + // We multiply by maxSpeed so that it can be set lower for outreaches + // When a young child is driving the robot, we may not want to allow full + // speed. + setDrivePower( + maxSpeed * (frontLeftPower / maxPower), + maxSpeed * (frontRightPower / maxPower), + maxSpeed * (backLeftPower / maxPower), + maxSpeed * (backRightPower / maxPower) + ); + } + + /** + * Pass the requested wheel motor powers to the appropriate hardware drive motors. + * + * @param flPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward + * @param frPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward + * @param blPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward + * @param brPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward + */ + public void setDrivePower(double flPower, double frPower, double blPower, double brPower) { + // Output the values to the motor drives. + frontLeft.setPower(flPower); + frontRight.setPower(frPower); + backLeft.setPower(blPower); + backRight.setPower(brPower); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java new file mode 100644 index 000000000000..1842fffaab3c --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -0,0 +1,88 @@ +/* Copyright (c) 2017 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; + +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.util.ElapsedTime; +import com.qualcomm.robotcore.util.Range; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.LoadHardwareClass; + + +/* + * This file contains an minimal example of a Linear "OpMode". An OpMode is a 'program' that runs in either + * the autonomous or the teleop period of an FTC match. The names of OpModes appear on the menu + * of the FTC Driver Station. When a selection is made from the menu, the corresponding OpMode + * class is instantiated on the Robot Controller and executed. + * + * This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot + * It includes all the skeletal structure that all linear OpModes contain. + * + * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. + * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list + */ + +@TeleOp(name="Teleop_Main_", group="TestTeleOp") +//@Disabled +public class Teleop_Main_ extends LinearOpMode { + + // Declare OpMode members. + private ElapsedTime runtime = new ElapsedTime(); + + + @Override + public void runOpMode() { + telemetry.addData("Status", "Initialized"); + telemetry.update(); + + LoadHardwareClass Robot = new LoadHardwareClass(this); + + // Wait for the game to start (driver presses START) + waitForStart(); + runtime.reset(); + + // run until the end of the match (driver presses STOP) + while (opModeIsActive()) { + + Robot.init(); + + Robot.mecanumDrive( + gamepad1.right_stick_y, + gamepad1.right_stick_x, + gamepad1.left_stick_x + ); + + telemetry.addData("Status", "Run Time: " + runtime.toString()); + telemetry.update(); + } + } +} From 7cf8be7b56aa938c6172083005c61799b8d7f7c0 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 4 Nov 2025 16:52:15 -0500 Subject: [PATCH 039/152] Fixed the incorrect hardware map references in the last version --- .../LOADCode/Main_/LoadHardwareClass.java | 25 +++++-------------- 1 file changed, 6 insertions(+), 19 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 8f7ec768ac3a..996ab7912b77 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -35,22 +35,9 @@ import com.qualcomm.robotcore.util.Range; /* - * This file works in conjunction with the External Hardware Class sample called: ConceptExternalHardwareClass.java - * Please read the explanations in that Sample about how to use this class definition. - * - * This file defines a Java Class that performs all the setup and configuration for a sample robot's hardware (motors and sensors). - * It assumes three motors (left_drive, right_drive and arm) and two servos (left_hand and right_hand) - * - * This one file/class can be used by ALL of your OpModes without having to cut & paste the code each time. - * - * Where possible, the actual hardware objects are "abstracted" (or hidden) so the OpMode code just makes calls into the class, - * rather than accessing the internal hardware directly. This is why the objects are declared "private". - * - * Use Android Studio to Copy this Class, and Paste it into your team's code folder with *exactly the same name*. - * - * Or... In OnBot Java, add a new file named RobotHardware.java, select this sample, and select Not an OpMode. - * Also add a new OpMode, select the sample ConceptExternalHardwareClass.java, and select TeleOp. + * This file is designed to work with our OpModes to handle all our hardware functionality to declutter our main scripts * + * The logic goes in the OpModes and the hardware control is handled here. */ public class LoadHardwareClass { @@ -83,10 +70,10 @@ public LoadHardwareClass(LinearOpMode opmode) { */ public void init() { // Define and initialize motors (note: need to use reference to actual OpMode). - frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "frontLeft"); - frontRight = myOpMode.hardwareMap.get(DcMotor.class, "frontRight"); - backLeft = myOpMode.hardwareMap.get(DcMotor.class, "backLeft"); - backRight = myOpMode.hardwareMap.get(DcMotor.class, "backRight"); + frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "fl"); + frontRight = myOpMode.hardwareMap.get(DcMotor.class, "fr"); + backLeft = myOpMode.hardwareMap.get(DcMotor.class, "bl"); + backRight = myOpMode.hardwareMap.get(DcMotor.class, "br"); // Set motor directions frontLeft.setDirection(DcMotor.Direction.REVERSE); From 519e170bf7e0e2ad9b80cb285a1a83dfaf333144 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 4 Nov 2025 16:55:00 -0500 Subject: [PATCH 040/152] Turret tweaks and fixed hardwaremap assignments --- .../LOADCode/Main_/LoadHardwareClass.java | 8 ++++---- .../LOADCode/TeleOps/TurretLocalization.java | 16 +++++++++++----- 2 files changed, 15 insertions(+), 9 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 996ab7912b77..71d5eca5d30f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -70,10 +70,10 @@ public LoadHardwareClass(LinearOpMode opmode) { */ public void init() { // Define and initialize motors (note: need to use reference to actual OpMode). - frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "fl"); - frontRight = myOpMode.hardwareMap.get(DcMotor.class, "fr"); - backLeft = myOpMode.hardwareMap.get(DcMotor.class, "bl"); - backRight = myOpMode.hardwareMap.get(DcMotor.class, "br"); + frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "FL"); + frontRight = myOpMode.hardwareMap.get(DcMotor.class, "FR"); + backLeft = myOpMode.hardwareMap.get(DcMotor.class, "BL"); + backRight = myOpMode.hardwareMap.get(DcMotor.class, "BR"); // Set motor directions frontLeft.setDirection(DcMotor.Direction.REVERSE); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java index ab0879122222..3a0a8d473813 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java @@ -106,7 +106,7 @@ public class TurretLocalization extends LinearOpMode //Turret PID coefficients public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.75, 0.005, 200); - public static int turretDeadZoneSize = 15; + public static int turretDeadZoneSize = 5; // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); @@ -123,7 +123,7 @@ public class TurretLocalization extends LinearOpMode double turretPos; // Used to store the current angle of the turret double turretPower; // Used to store the calculated power to output to the turret servo boolean runTurret = true; - boolean useTurretPID = true; + boolean useTurretPID = false; double targetAngle; double lastTurretPos; int wraparoundTrigger = 0; @@ -241,11 +241,17 @@ public class TurretLocalization extends LinearOpMode telemetry.addData("Turret Control System:", "Non-PID"); } - if (Math.abs(turretPos-lastTurretPos) >= 30){ + if (gamepad1.dpad_left){ + turretPower = 0.4; + }else if (gamepad1.dpad_right){ + turretPower = -0.4; + } + + if ((Math.abs(turretPos-lastTurretPos) >= 120) && (turretPos<350 || turretPos>10)){ wraparoundTrigger += (int)Math.signum(turretPos - 180); } if (wraparoundTrigger != 0) { - //turretPower = Math.max(Math.min(-wraparoundTrigger, 0.1), -0.1); + turretPower = Math.max(Math.min(-wraparoundTrigger, 0.2), -0.2); } if (gamepad1.bWasPressed()){ @@ -261,7 +267,7 @@ public class TurretLocalization extends LinearOpMode // Apply desired axes motions to the drivetrain - follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x/2, true); + follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, true); follower.update(); lastTurretPos = turretPos; From d3269fc25e5ca4ac5482abc23555e2ef00fec185 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 4 Nov 2025 17:00:58 -0500 Subject: [PATCH 041/152] Updated the gamepad bindings for mecanumDrive --- .../ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java | 8 ++++---- .../ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java | 8 +++++--- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 71d5eca5d30f..81ae3b7038db 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -97,10 +97,10 @@ public void init() { public void mecanumDrive(double forward, double strafe, double rotate) { // This calculates the power needed for each wheel based on the amount of forward, // strafe right, and rotate - double frontLeftPower = forward + strafe + rotate; - double frontRightPower = forward - strafe - rotate; - double backRightPower = forward + strafe - rotate; - double backLeftPower = forward - strafe + rotate; + double frontLeftPower = -forward + strafe + rotate; + double frontRightPower = -forward - strafe - rotate; + double backRightPower = -forward + strafe - rotate; + double backLeftPower = -forward - strafe + rotate; double maxPower = 1.0; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 1842fffaab3c..62e638dbfa8b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -76,12 +76,14 @@ public void runOpMode() { Robot.init(); Robot.mecanumDrive( - gamepad1.right_stick_y, - gamepad1.right_stick_x, - gamepad1.left_stick_x + gamepad1.left_stick_y, + gamepad1.left_stick_x, + gamepad1.right_stick_x ); + telemetry.addData("Status", "Run Time: " + runtime.toString()); + telemetry.addData("Version: ", "11/4/25"); telemetry.update(); } } From a3bf4f38a3cbe9d658d69817bed2a8f480524119 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 4 Nov 2025 17:04:16 -0500 Subject: [PATCH 042/152] Re-Scoped the Robot.init(); call to remove it from the main loop. --- .../ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 62e638dbfa8b..c9c3108d69bd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -70,11 +70,10 @@ public void runOpMode() { waitForStart(); runtime.reset(); + Robot.init(); // run until the end of the match (driver presses STOP) while (opModeIsActive()) { - Robot.init(); - Robot.mecanumDrive( gamepad1.left_stick_y, gamepad1.left_stick_x, From 0e5a34258b6a5747172b3fe1e927bcd9c9c9b08c Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 4 Nov 2025 17:21:07 -0500 Subject: [PATCH 043/152] Added more TODOs and comments --- .../LOADCode/Main_/LoadHardwareClass.java | 6 ++---- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 16 ++-------------- 2 files changed, 4 insertions(+), 18 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 81ae3b7038db..f0afa511126f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -35,7 +35,7 @@ import com.qualcomm.robotcore.util.Range; /* - * This file is designed to work with our OpModes to handle all our hardware functionality to declutter our main scripts + * This file is designed to work with our OpModes to handle all our hardware functionality to de-clutter our main scripts * * The logic goes in the OpModes and the hardware control is handled here. */ @@ -83,8 +83,6 @@ public void init() { // If the drivetrain motors have encoders, handle all that here - - // Define and initialize servos here //Set servo directions @@ -93,7 +91,7 @@ public void init() { myOpMode.telemetry.update(); } - + //TODO Add "PedroDriveTM" to replace the current Mecanum drive. public void mecanumDrive(double forward, double strafe, double rotate) { // This calculates the power needed for each wheel based on the amount of forward, // strafe right, and rotate diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index c9c3108d69bd..b18414e17724 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -37,19 +37,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.LoadHardwareClass; - -/* - * This file contains an minimal example of a Linear "OpMode". An OpMode is a 'program' that runs in either - * the autonomous or the teleop period of an FTC match. The names of OpModes appear on the menu - * of the FTC Driver Station. When a selection is made from the menu, the corresponding OpMode - * class is instantiated on the Robot Controller and executed. - * - * This particular OpMode just executes a basic Tank Drive Teleop for a two wheeled robot - * It includes all the skeletal structure that all linear OpModes contain. - * - * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. - * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list - */ +//TODO, implement all our external libraries and functionality. @TeleOp(name="Teleop_Main_", group="TestTeleOp") //@Disabled @@ -80,10 +68,10 @@ public void runOpMode() { gamepad1.right_stick_x ); - telemetry.addData("Status", "Run Time: " + runtime.toString()); telemetry.addData("Version: ", "11/4/25"); telemetry.update(); + //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging } } } From ba2ffa94dff5e3a922dd1622fa92ac04e8f0e305 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 4 Nov 2025 17:53:22 -0500 Subject: [PATCH 044/152] Began adding functionality for a turret, as well as more comments and TODOs --- .../LOADCode/Main_/LoadHardwareClass.java | 44 +++++++++++-------- 1 file changed, 26 insertions(+), 18 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index f0afa511126f..5542dced4704 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -31,6 +31,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.Servo; import com.qualcomm.robotcore.util.Range; @@ -40,6 +41,14 @@ * The logic goes in the OpModes and the hardware control is handled here. */ +//TODO Abstract all the individual systems rather than the entire hardware +/* +Example: Abstract class for drivetrain, turret, intake, etc +They could be all individually referenced in the main OpMode +Drivetrain.doThing(args); +Turret.doOtherThing(args); +etc etc +*/ public class LoadHardwareClass { /* Declare OpMode members. */ @@ -52,9 +61,9 @@ public class LoadHardwareClass { private DcMotor backLeft = null; private DcMotor backRight = null; //Other + private DcMotorEx turretMotor = null; - // Public drive constants, empty for now - + // Public drive constants public final double maxSpeed = 1.0; // make this slower for outreaches // Constructor that allows the OpMode to pass a reference to itself. @@ -62,12 +71,6 @@ public LoadHardwareClass(LinearOpMode opmode) { myOpMode = opmode; } - /** - * Initialize all the robot's hardware. - * This method must be called ONCE when the OpMode is initialized. - *

- * All of the hardware devices are accessed via the hardware map, and initialized. - */ public void init() { // Define and initialize motors (note: need to use reference to actual OpMode). frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "FL"); @@ -75,13 +78,15 @@ public void init() { backLeft = myOpMode.hardwareMap.get(DcMotor.class, "BL"); backRight = myOpMode.hardwareMap.get(DcMotor.class, "BR"); + turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "turretMotor"); + // Set motor directions frontLeft.setDirection(DcMotor.Direction.REVERSE); frontRight.setDirection(DcMotor.Direction.FORWARD); backLeft.setDirection(DcMotor.Direction.REVERSE); backRight.setDirection(DcMotor.Direction.FORWARD); - // If the drivetrain motors have encoders, handle all that here + // If the motors have encoders, handle all that here // Define and initialize servos here @@ -120,15 +125,6 @@ public void mecanumDrive(double forward, double strafe, double rotate) { maxSpeed * (backRightPower / maxPower) ); } - - /** - * Pass the requested wheel motor powers to the appropriate hardware drive motors. - * - * @param flPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward - * @param frPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward - * @param blPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward - * @param brPower Fwd/Rev driving power (-1.0 to 1.0) +ve is forward - */ public void setDrivePower(double flPower, double frPower, double blPower, double brPower) { // Output the values to the motor drives. frontLeft.setPower(flPower); @@ -136,4 +132,16 @@ public void setDrivePower(double flPower, double frPower, double blPower, double backLeft.setPower(blPower); backRight.setPower(brPower); } + + public void setTurretPower(double power){ + turretMotor.setPower(power); + } + + public double getTurretPosition(){ + return turretMotor.getCurrentPosition(); + } + + public double getTurretVelocity(){ + return turretMotor.getVelocity(); + } } From a888ecb22f37831a36d0d386c9c3eae71eebd83a Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 4 Nov 2025 19:11:09 -0500 Subject: [PATCH 045/152] Implemented Turret PID --- .../LOADCode/Main_/LoadHardwareClass.java | 35 ++++++++++++++++--- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 18 ++++++++++ 2 files changed, 48 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 5542dced4704..ee2cd9c167c9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -32,8 +32,10 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; -import com.qualcomm.robotcore.hardware.Servo; -import com.qualcomm.robotcore.util.Range; + +import dev.nextftc.control.ControlSystem; +import dev.nextftc.control.KineticState; +import dev.nextftc.control.feedback.PIDCoefficients; /* * This file is designed to work with our OpModes to handle all our hardware functionality to de-clutter our main scripts @@ -60,12 +62,19 @@ public class LoadHardwareClass { private DcMotor frontRight = null; private DcMotor backLeft = null; private DcMotor backRight = null; - //Other + // Other private DcMotorEx turretMotor = null; // Public drive constants public final double maxSpeed = 1.0; // make this slower for outreaches + // Turret Constants + // PID coefficients + PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); + // Encoder ticks/rotation + // 1620rpm - 103.8 + double ticksPerRotation = 103.8; + // Constructor that allows the OpMode to pass a reference to itself. public LoadHardwareClass(LinearOpMode opmode) { myOpMode = opmode; @@ -90,7 +99,7 @@ public void init() { // Define and initialize servos here - //Set servo directions + // Set servo directions myOpMode.telemetry.addData(">", "Hardware Initialized"); myOpMode.telemetry.update(); @@ -137,11 +146,27 @@ public void setTurretPower(double power){ turretMotor.setPower(power); } - public double getTurretPosition(){ + public double getTurretEncoderTicks(){ return turretMotor.getCurrentPosition(); } + public double getTurretAngle(){ + return (turretMotor.getCurrentPosition()/ticksPerRotation*360); + } + public double getTurretVelocity(){ return turretMotor.getVelocity(); } + + public double getTurretPower(){ + return turretMotor.getPower(); + } + + public void setTurretAngle(double angle){ + ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); + KineticState currentKineticState = new KineticState(getTurretAngle(), getTurretVelocity()); + turretPID.setGoal(new KineticState(angle)); + setTurretPower(turretPID.calculate(currentKineticState)); + } + } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index b18414e17724..3ee6dc880ea8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -58,6 +58,8 @@ public void runOpMode() { waitForStart(); runtime.reset(); + double target = 0; + Robot.init(); // run until the end of the match (driver presses STOP) while (opModeIsActive()) { @@ -68,6 +70,22 @@ public void runOpMode() { gamepad1.right_stick_x ); + if (gamepad1.b){ + target = 90; + }else if (gamepad1.y){ + target = 0; + }else if (gamepad1.a){ + target = 180; + }else if (gamepad1.x){ + target = 270; + } + + Robot.setTurretAngle(target); + + telemetry.addData("Target:", target); + telemetry.addData("Angle", Robot.getTurretAngle()); + telemetry.addData("Set Power", Robot.getTurretPower()); + telemetry.addData("Status", "Run Time: " + runtime.toString()); telemetry.addData("Version: ", "11/4/25"); telemetry.update(); From 2552e470f1b172f6713cf04e96ee06e748da2097 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 4 Nov 2025 20:42:03 -0500 Subject: [PATCH 046/152] Abstracted hardware functions into Drivetrain and Turret objects, and added Pedropathing mecanum drive --- .../LOADCode/Main_/LoadHardwareClass.java | 159 ++++++++++-------- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 20 ++- 2 files changed, 102 insertions(+), 77 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index ee2cd9c167c9..09ae45a7d8be 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -29,10 +29,14 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_; +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; + import dev.nextftc.control.ControlSystem; import dev.nextftc.control.KineticState; import dev.nextftc.control.feedback.PIDCoefficients; @@ -45,7 +49,7 @@ //TODO Abstract all the individual systems rather than the entire hardware /* -Example: Abstract class for drivetrain, turret, intake, etc +Example: Abstract class for drivetrain, Turret, intake, etc They could be all individually referenced in the main OpMode Drivetrain.doThing(args); Turret.doOtherThing(args); @@ -65,19 +69,17 @@ public class LoadHardwareClass { // Other private DcMotorEx turretMotor = null; + // Misc Constants + public Follower follower = null; + public Pose initialPose = null; + // Public drive constants public final double maxSpeed = 1.0; // make this slower for outreaches - // Turret Constants - // PID coefficients - PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); - // Encoder ticks/rotation - // 1620rpm - 103.8 - double ticksPerRotation = 103.8; - // Constructor that allows the OpMode to pass a reference to itself. - public LoadHardwareClass(LinearOpMode opmode) { + public LoadHardwareClass(LinearOpMode opmode, Pose pose) { myOpMode = opmode; + initialPose = pose; } public void init() { @@ -101,72 +103,91 @@ public void init() { // Set servo directions + // PedroPathing initialization + follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower + follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field + follower.update(); // Applies the initialization + myOpMode.telemetry.addData(">", "Hardware Initialized"); myOpMode.telemetry.update(); } - //TODO Add "PedroDriveTM" to replace the current Mecanum drive. - public void mecanumDrive(double forward, double strafe, double rotate) { - // This calculates the power needed for each wheel based on the amount of forward, - // strafe right, and rotate - double frontLeftPower = -forward + strafe + rotate; - double frontRightPower = -forward - strafe - rotate; - double backRightPower = -forward + strafe - rotate; - double backLeftPower = -forward - strafe + rotate; - - double maxPower = 1.0; - - // This is needed to make sure we don't pass > 1.0 to any wheel - // It allows us to keep all of the motors in proportion to what they should - // be and not get clipped - maxPower = Math.max(maxPower, Math.abs(frontLeftPower)); - maxPower = Math.max(maxPower, Math.abs(frontRightPower)); - maxPower = Math.max(maxPower, Math.abs(backRightPower)); - maxPower = Math.max(maxPower, Math.abs(backLeftPower)); - - // We multiply by maxSpeed so that it can be set lower for outreaches - // When a young child is driving the robot, we may not want to allow full - // speed. - setDrivePower( - maxSpeed * (frontLeftPower / maxPower), - maxSpeed * (frontRightPower / maxPower), - maxSpeed * (backLeftPower / maxPower), - maxSpeed * (backRightPower / maxPower) - ); - } - public void setDrivePower(double flPower, double frPower, double blPower, double brPower) { - // Output the values to the motor drives. - frontLeft.setPower(flPower); - frontRight.setPower(frPower); - backLeft.setPower(blPower); - backRight.setPower(brPower); - } - - public void setTurretPower(double power){ - turretMotor.setPower(power); - } - - public double getTurretEncoderTicks(){ - return turretMotor.getCurrentPosition(); - } - - public double getTurretAngle(){ - return (turretMotor.getCurrentPosition()/ticksPerRotation*360); - } - - public double getTurretVelocity(){ - return turretMotor.getVelocity(); - } - - public double getTurretPower(){ - return turretMotor.getPower(); + public class Drivetrain { + public void mecanumDrive(double forward, double strafe, double rotate) { + // This calculates the power needed for each wheel based on the amount of forward, + // strafe right, and rotate + double frontLeftPower = -forward + strafe + rotate; + double frontRightPower = -forward - strafe - rotate; + double backRightPower = -forward + strafe - rotate; + double backLeftPower = -forward - strafe + rotate; + + double maxPower = 1.0; + + // This is needed to make sure we don't pass > 1.0 to any wheel + // It allows us to keep all of the motors in proportion to what they should + // be and not get clipped + maxPower = Math.max(maxPower, Math.abs(frontLeftPower)); + maxPower = Math.max(maxPower, Math.abs(frontRightPower)); + maxPower = Math.max(maxPower, Math.abs(backRightPower)); + maxPower = Math.max(maxPower, Math.abs(backLeftPower)); + + // We multiply by maxSpeed so that it can be set lower for outreaches + // When a young child is driving the robot, we may not want to allow full + // speed. + setDrivePower( + maxSpeed * (frontLeftPower / maxPower), + maxSpeed * (frontRightPower / maxPower), + maxSpeed * (backLeftPower / maxPower), + maxSpeed * (backRightPower / maxPower) + ); + } + public void pedroMecanumDrive(double forward, double strafe, double rotate, boolean robotCentricEnabled){ + follower.setTeleOpDrive(forward, strafe, rotate, robotCentricEnabled); + follower.update(); + } + public void setDrivePower(double flPower, double frPower, double blPower, double brPower) { + // Output the values to the motor drives. + frontLeft.setPower(flPower); + frontRight.setPower(frPower); + backLeft.setPower(blPower); + backRight.setPower(brPower); + } } - public void setTurretAngle(double angle){ - ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getTurretAngle(), getTurretVelocity()); - turretPID.setGoal(new KineticState(angle)); - setTurretPower(turretPID.calculate(currentKineticState)); + public class Turret { + // Turret Constants + // PID coefficients + PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); + // Encoder ticks/rotation + // 1620rpm - 103.8 + double ticksPerRotation = 103.8; + + public double getTurretEncoderTicks(){ + return turretMotor.getCurrentPosition(); + } + + public void setTurretPower(double power){ + turretMotor.setPower(power); + } + + public double getTurretAngle(){ + return (turretMotor.getCurrentPosition()/ticksPerRotation*360); + } + + public double getTurretVelocity(){ + return turretMotor.getVelocity(); + } + + public double getTurretPower(){ + return turretMotor.getPower(); + } + + public void setTurretAngle(double angle){ + ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); + KineticState currentKineticState = new KineticState(getTurretAngle(), getTurretVelocity()); + turretPID.setGoal(new KineticState(angle)); + setTurretPower(turretPID.calculate(currentKineticState)); + } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 3ee6dc880ea8..78650ccfed99 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -29,11 +29,10 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; +import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.util.ElapsedTime; -import com.qualcomm.robotcore.util.Range; import org.firstinspires.ftc.teamcode.LOADCode.Main_.LoadHardwareClass; @@ -46,13 +45,17 @@ public class Teleop_Main_ extends LinearOpMode { // Declare OpMode members. private ElapsedTime runtime = new ElapsedTime(); + // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. + private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); @Override public void runOpMode() { telemetry.addData("Status", "Initialized"); telemetry.update(); - LoadHardwareClass Robot = new LoadHardwareClass(this); + LoadHardwareClass Robot = new LoadHardwareClass(this, startPose); + LoadHardwareClass.Drivetrain Drivetrain = Robot.new Drivetrain(); + LoadHardwareClass.Turret Turret = Robot.new Turret(); // Wait for the game to start (driver presses START) waitForStart(); @@ -64,10 +67,11 @@ public void runOpMode() { // run until the end of the match (driver presses STOP) while (opModeIsActive()) { - Robot.mecanumDrive( + Drivetrain.pedroMecanumDrive( gamepad1.left_stick_y, gamepad1.left_stick_x, - gamepad1.right_stick_x + gamepad1.right_stick_x, + true ); if (gamepad1.b){ @@ -80,11 +84,11 @@ public void runOpMode() { target = 270; } - Robot.setTurretAngle(target); + Turret.setTurretAngle(target); telemetry.addData("Target:", target); - telemetry.addData("Angle", Robot.getTurretAngle()); - telemetry.addData("Set Power", Robot.getTurretPower()); + telemetry.addData("Angle", Turret.getTurretAngle()); + telemetry.addData("Set Power", Turret.getTurretPower()); telemetry.addData("Status", "Run Time: " + runtime.toString()); telemetry.addData("Version: ", "11/4/25"); From 0a746a0dbd15c8eeb2709f334691c29a5c2754c5 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Wed, 5 Nov 2025 08:28:48 -0500 Subject: [PATCH 047/152] Commented a bunch of stuff in LoadHardwareClass & Teleop_Main_, and moved all previous experimentation into it's own package. --- .../LOADCode/Main_/LoadHardwareClass.java | 106 +++++++++++++++--- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 23 ++-- .../{ => Testing_}/Autos/TestAutoR1.java | 2 +- .../TeleOps/PedroDriveToAprilTag.java | 2 +- .../{ => Testing_}/TeleOps/TeleopTest_V1.java | 2 +- .../TeleOps/TurretAprilTagTracking.java | 2 +- .../TeleOps/TurretLocalization.java | 2 +- .../{ => Testing_}/Tests/ServoTest.java | 2 +- 8 files changed, 113 insertions(+), 28 deletions(-) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => Testing_}/Autos/TestAutoR1.java (98%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => Testing_}/TeleOps/PedroDriveToAprilTag.java (99%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => Testing_}/TeleOps/TeleopTest_V1.java (97%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => Testing_}/TeleOps/TurretAprilTagTracking.java (99%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => Testing_}/TeleOps/TurretLocalization.java (99%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/{ => Testing_}/Tests/ServoTest.java (98%) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 09ae45a7d8be..9edbc6a8abf6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -71,17 +71,23 @@ public class LoadHardwareClass { // Misc Constants public Follower follower = null; - public Pose initialPose = null; + public Pose initialPose = new Pose(0,0, 0); // Public drive constants - public final double maxSpeed = 1.0; // make this slower for outreaches + public double speedMultiplier = 1.0; // make this slower for outreaches - // Constructor that allows the OpMode to pass a reference to itself. - public LoadHardwareClass(LinearOpMode opmode, Pose pose) { + /** + * Constructor that allows the OpMode to pass a reference to itself. + * @param opmode The input for this parameter should almost always be "this". + */ + public LoadHardwareClass(LinearOpMode opmode) { myOpMode = opmode; - initialPose = pose; } + /** + * Initializes all hardware for the robot. + * Must be called once at the start of each op-mode. + */ public void init() { // Define and initialize motors (note: need to use reference to actual OpMode). frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "FL"); @@ -113,7 +119,19 @@ public void init() { } public class Drivetrain { - public void mecanumDrive(double forward, double strafe, double rotate) { + /** + * Implements a custom mecanum drive controller. + * Must be called every loop to function properly. + * @param Forward The joystick value for driving forward/backward + * @param Strafe The joystick value for strafing + * @param Rotate The joystick value to turn left/right + */ + public void mecanumDrive(double Forward, double Strafe, double Rotate) { + // Puts the inputted joystick values into their own variable to allow for modification. + double forward = Forward * speedMultiplier; + double strafe = Strafe * speedMultiplier; + double rotate = Rotate * speedMultiplier; + // This calculates the power needed for each wheel based on the amount of forward, // strafe right, and rotate double frontLeftPower = -forward + strafe + rotate; @@ -135,16 +153,33 @@ public void mecanumDrive(double forward, double strafe, double rotate) { // When a young child is driving the robot, we may not want to allow full // speed. setDrivePower( - maxSpeed * (frontLeftPower / maxPower), - maxSpeed * (frontRightPower / maxPower), - maxSpeed * (backLeftPower / maxPower), - maxSpeed * (backRightPower / maxPower) + (frontLeftPower / maxPower), + (frontRightPower / maxPower), + (backLeftPower / maxPower), + (backRightPower / maxPower) ); } - public void pedroMecanumDrive(double forward, double strafe, double rotate, boolean robotCentricEnabled){ - follower.setTeleOpDrive(forward, strafe, rotate, robotCentricEnabled); + + /** + * Uses PedroPathing's follower class to implement a mecanum drive controller. + * Must be called every loop to function properly. + * @param forward The joystick value for driving forward/backward + * @param strafe The joystick value for strafing + * @param rotate The joystick value to turn left/right + * @param robotCentric If true, enables robot centric. If false, enables field centric. + */ + public void pedroMecanumDrive(double forward, double strafe, double rotate, boolean robotCentric){ + follower.setTeleOpDrive( + forward * speedMultiplier, + strafe * speedMultiplier, + rotate * speedMultiplier, + robotCentric); follower.update(); } + + /** + * Sets the output power of all four drivetrain motors. + */ public void setDrivePower(double flPower, double frPower, double blPower, double brPower) { // Output the values to the motor drives. frontLeft.setPower(flPower); @@ -159,32 +194,73 @@ public class Turret { // PID coefficients PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); // Encoder ticks/rotation - // 1620rpm - 103.8 + // 1620rpm - 103.8 ticks at the motor shaft double ticksPerRotation = 103.8; + /** + * @return The current position of the motor in encoder ticks. Can be any value. + */ public double getTurretEncoderTicks(){ return turretMotor.getCurrentPosition(); } + /** + * @return The resolution of the turret's encoder in ticks/rotation. + */ + public double getTurretEncoderResolution(){ + return ticksPerRotation; + } + + /** + * @param power A value between -1 and 1 to set the turret motor's power to. + */ public void setTurretPower(double power){ turretMotor.setPower(power); } + /** + * @return The angle of the turret in degrees. Can be any value. + */ + public double getTurretAngleAbsolute(){ + return (getTurretEncoderTicks()/ticksPerRotation*360); + } + + /** + * @return The angle of the turret in degrees. Can be any value between 0 and 360. + */ public double getTurretAngle(){ - return (turretMotor.getCurrentPosition()/ticksPerRotation*360); + return getTurretAngleAbsolute()%360; } + /** + * @return The velocity of the turret in encoder ticks/second. + */ public double getTurretVelocity(){ return turretMotor.getVelocity(); } + /** + * @return The velocity of the turret in degrees/second. + */ + public double getTurretVelocityDegrees(){ + return (getTurretVelocity()/ticksPerRotation*360); + } + + /** + * @return The power that the motor has been set to. + */ public double getTurretPower(){ return turretMotor.getPower(); } + /** + * Uses a PID controller to move the turret to the desired position. + * Must be called every loop to function properly. + * @param angle The angle to move the turret to. + */ public void setTurretAngle(double angle){ ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getTurretAngle(), getTurretVelocity()); + KineticState currentKineticState = new KineticState(getTurretAngleAbsolute(), getTurretVelocity()); turretPID.setGoal(new KineticState(angle)); setTurretPower(turretPID.calculate(currentKineticState)); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 78650ccfed99..c1b4cd34aadd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -39,7 +39,6 @@ //TODO, implement all our external libraries and functionality. @TeleOp(name="Teleop_Main_", group="TestTeleOp") -//@Disabled public class Teleop_Main_ extends LinearOpMode { // Declare OpMode members. @@ -53,20 +52,30 @@ public void runOpMode() { telemetry.addData("Status", "Initialized"); telemetry.update(); - LoadHardwareClass Robot = new LoadHardwareClass(this, startPose); + // Create a new instance of our Robot class + LoadHardwareClass Robot = new LoadHardwareClass(this); + + // Instantiate the various hardware classes of the robot LoadHardwareClass.Drivetrain Drivetrain = Robot.new Drivetrain(); LoadHardwareClass.Turret Turret = Robot.new Turret(); + // Pass the starting pose of the robot to the Robot class + Robot.initialPose = startPose; + // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); + // This variable contains the target position for the turret. double target = 0; + // Initialize all hardware of the robot Robot.init(); + // run until the end of the match (driver presses STOP) while (opModeIsActive()) { + // Pass the joystick positions to our mecanum drive controller Drivetrain.pedroMecanumDrive( gamepad1.left_stick_y, gamepad1.left_stick_x, @@ -74,20 +83,20 @@ public void runOpMode() { true ); - if (gamepad1.b){ + if (gamepad1.bWasPressed()){ target = 90; - }else if (gamepad1.y){ + }else if (gamepad1.yWasPressed()){ target = 0; - }else if (gamepad1.a){ + }else if (gamepad1.aWasPressed()){ target = 180; - }else if (gamepad1.x){ + }else if (gamepad1.xWasPressed()){ target = 270; } Turret.setTurretAngle(target); telemetry.addData("Target:", target); - telemetry.addData("Angle", Turret.getTurretAngle()); + telemetry.addData("Angle", Turret.getTurretAngleAbsolute()); telemetry.addData("Set Power", Turret.getTurretPower()); telemetry.addData("Status", "Run Time: " + runtime.toString()); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Autos/TestAutoR1.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Autos/TestAutoR1.java index e0bd2fa7b7d0..22eac797483c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Autos/TestAutoR1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Autos/TestAutoR1.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Autos; // make sure this aligns with class location +package org.firstinspires.ftc.teamcode.LOADCode.Testing_.Autos; // make sure this aligns with class location import com.pedropathing.follower.Follower; import com.pedropathing.geometry.BezierCurve; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/PedroDriveToAprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java similarity index 99% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/PedroDriveToAprilTag.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java index 5e9218db9662..85e5dfa4834c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/PedroDriveToAprilTag.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; +package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java similarity index 97% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TeleopTest_V1.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java index 42d2ecd02a76..2bf6850f09be 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TeleopTest_V1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; +package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java similarity index 99% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java index 780d8b6ef778..1f5245473418 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretAprilTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; +package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java similarity index 99% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java index 3a0a8d473813..35012485bdec 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.TeleOps; +package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; import com.bylazar.configurables.annotations.Configurable; import com.bylazar.configurables.annotations.IgnoreConfigurable; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ServoTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Tests/ServoTest.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ServoTest.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Tests/ServoTest.java index 07439e713cf5..7ecb5011e141 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Tests/ServoTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Tests/ServoTest.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.Tests; +package org.firstinspires.ftc.teamcode.LOADCode.Testing_.Tests; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; From a546fd3210fde3ff937c0901d552371dd5c82d56 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Wed, 5 Nov 2025 11:24:02 -0500 Subject: [PATCH 048/152] Added Intake hardware class and added it to Teleop_Main_ --- .../LOADCode/Main_/LoadHardwareClass.java | 69 +++++++++++++++---- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 17 ++++- 2 files changed, 71 insertions(+), 15 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 9edbc6a8abf6..0453bfa2082f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -68,6 +68,7 @@ public class LoadHardwareClass { private DcMotor backRight = null; // Other private DcMotorEx turretMotor = null; + private DcMotorEx intakeMotor = null; // Misc Constants public Follower follower = null; @@ -95,7 +96,8 @@ public void init() { backLeft = myOpMode.hardwareMap.get(DcMotor.class, "BL"); backRight = myOpMode.hardwareMap.get(DcMotor.class, "BR"); - turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "turretMotor"); + turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "turret"); + intakeMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "intake"); // Set motor directions frontLeft.setDirection(DcMotor.Direction.REVERSE); @@ -118,6 +120,42 @@ public void init() { myOpMode.telemetry.update(); } + public class Intake { + // Intake Constants + // Encoder ticks/rotation + // 1620rpm - 103.8 ticks at the motor shaft + double ticksPerRotation = 103.8; + + + /** + * @param power A value between -1 and 1 that the intake motor's power will be set to. + */ + public void setPower(double power){ + intakeMotor.setPower(power); + } + + /** + * @return The power that the intake motor has been set to. + */ + public double getPower(){ + return intakeMotor.getPower(); + } + + /** + * @return The velocity of the turret in encoder ticks/second. + */ + public double getTurretVelocity(){ + return intakeMotor.getVelocity(); + } + + /** + * @return The velocity of the intake in RPM. + */ + public double getTurretVelocityRPM(){ + return ((getTurretVelocity()*60)/ticksPerRotation); + } + } + public class Drivetrain { /** * Implements a custom mecanum drive controller. @@ -198,38 +236,38 @@ public class Turret { double ticksPerRotation = 103.8; /** - * @return The current position of the motor in encoder ticks. Can be any value. + * @return The current position of the turret motor in encoder ticks. Can be any value. */ - public double getTurretEncoderTicks(){ + public double getEncoderTicks(){ return turretMotor.getCurrentPosition(); } /** * @return The resolution of the turret's encoder in ticks/rotation. */ - public double getTurretEncoderResolution(){ + public double getEncoderResolution(){ return ticksPerRotation; } /** - * @param power A value between -1 and 1 to set the turret motor's power to. + * @param power A value between -1 and 1 that the turret motor's power will be set to. */ - public void setTurretPower(double power){ + public void setPower(double power){ turretMotor.setPower(power); } /** * @return The angle of the turret in degrees. Can be any value. */ - public double getTurretAngleAbsolute(){ - return (getTurretEncoderTicks()/ticksPerRotation*360); + public double getAngleAbsolute(){ + return (getEncoderTicks()/ticksPerRotation*360); } /** * @return The angle of the turret in degrees. Can be any value between 0 and 360. */ public double getTurretAngle(){ - return getTurretAngleAbsolute()%360; + return getAngleAbsolute()%360; } /** @@ -247,7 +285,14 @@ public double getTurretVelocityDegrees(){ } /** - * @return The power that the motor has been set to. + * @return The velocity of the turret in RPM. + */ + public double getTurretVelocityRPM(){ + return ((getTurretVelocity()*60)/ticksPerRotation); + } + + /** + * @return The power that the turret motor has been set to. */ public double getTurretPower(){ return turretMotor.getPower(); @@ -260,9 +305,9 @@ public double getTurretPower(){ */ public void setTurretAngle(double angle){ ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getTurretAngleAbsolute(), getTurretVelocity()); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getTurretVelocity()); turretPID.setGoal(new KineticState(angle)); - setTurretPower(turretPID.calculate(currentKineticState)); + setPower(turretPID.calculate(currentKineticState)); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index c1b4cd34aadd..f237ce3c11fe 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -58,6 +58,7 @@ public void runOpMode() { // Instantiate the various hardware classes of the robot LoadHardwareClass.Drivetrain Drivetrain = Robot.new Drivetrain(); LoadHardwareClass.Turret Turret = Robot.new Turret(); + LoadHardwareClass.Intake Intake = Robot.new Intake(); // Pass the starting pose of the robot to the Robot class Robot.initialPose = startPose; @@ -95,10 +96,20 @@ public void runOpMode() { Turret.setTurretAngle(target); - telemetry.addData("Target:", target); - telemetry.addData("Angle", Turret.getTurretAngleAbsolute()); - telemetry.addData("Set Power", Turret.getTurretPower()); + Intake.setPower(gamepad1.left_trigger); + // Turret-related Telemetry + telemetry.addData("Turret Target Angle:", target); + telemetry.addData("Turret Actual Angle", Turret.getAngleAbsolute()); + telemetry.addData("Turret Set Power", Turret.getTurretPower()); + + // Intake-related Telemetry + telemetry.addLine(); + telemetry.addData("Intake Set Power", Intake.getPower()); + telemetry.addData("Intake RPM", Intake.getTurretVelocityRPM()); + + // System-related Telemetry + telemetry.addLine(); telemetry.addData("Status", "Run Time: " + runtime.toString()); telemetry.addData("Version: ", "11/4/25"); telemetry.update(); From 5fd2663f12badde0ffa3de263f2c8c52503577b1 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Wed, 5 Nov 2025 13:31:43 -0500 Subject: [PATCH 049/152] Changed hardware subclasses to be members of parent Robot class --- .../LOADCode/Main_/LoadHardwareClass.java | 81 ++++++++++--------- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 19 ++--- 2 files changed, 51 insertions(+), 49 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 0453bfa2082f..38e27d801dc9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -56,7 +56,6 @@ etc etc */ public class LoadHardwareClass { - /* Declare OpMode members. */ private LinearOpMode myOpMode = null; // gain access to methods in the calling OpMode. @@ -77,12 +76,20 @@ public class LoadHardwareClass { // Public drive constants public double speedMultiplier = 1.0; // make this slower for outreaches + // Declare subclasses + public final Drivetrain drivetrain; + public final Turret turret; + public final Intake intake; + /** * Constructor that allows the OpMode to pass a reference to itself. * @param opmode The input for this parameter should almost always be "this". */ public LoadHardwareClass(LinearOpMode opmode) { myOpMode = opmode; + this.turret = new Turret(); + this.intake = new Intake(); + this.drivetrain = new Drivetrain(); } /** @@ -120,42 +127,6 @@ public void init() { myOpMode.telemetry.update(); } - public class Intake { - // Intake Constants - // Encoder ticks/rotation - // 1620rpm - 103.8 ticks at the motor shaft - double ticksPerRotation = 103.8; - - - /** - * @param power A value between -1 and 1 that the intake motor's power will be set to. - */ - public void setPower(double power){ - intakeMotor.setPower(power); - } - - /** - * @return The power that the intake motor has been set to. - */ - public double getPower(){ - return intakeMotor.getPower(); - } - - /** - * @return The velocity of the turret in encoder ticks/second. - */ - public double getTurretVelocity(){ - return intakeMotor.getVelocity(); - } - - /** - * @return The velocity of the intake in RPM. - */ - public double getTurretVelocityRPM(){ - return ((getTurretVelocity()*60)/ticksPerRotation); - } - } - public class Drivetrain { /** * Implements a custom mecanum drive controller. @@ -311,4 +282,40 @@ public void setTurretAngle(double angle){ } } + public class Intake { + // Intake Constants + // Encoder ticks/rotation + // 1620rpm - 103.8 ticks at the motor shaft + double ticksPerRotation = 103.8; + + + /** + * @param power A value between -1 and 1 that the intake motor's power will be set to. + */ + public void setPower(double power){ + intakeMotor.setPower(power); + } + + /** + * @return The power that the intake motor has been set to. + */ + public double getPower(){ + return intakeMotor.getPower(); + } + + /** + * @return The velocity of the turret in encoder ticks/second. + */ + public double getTurretVelocity(){ + return intakeMotor.getVelocity(); + } + + /** + * @return The velocity of the intake in RPM. + */ + public double getTurretVelocityRPM(){ + return ((getTurretVelocity()*60)/ticksPerRotation); + } + } + } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index f237ce3c11fe..de7ffe22b7ef 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -55,11 +55,6 @@ public void runOpMode() { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); - // Instantiate the various hardware classes of the robot - LoadHardwareClass.Drivetrain Drivetrain = Robot.new Drivetrain(); - LoadHardwareClass.Turret Turret = Robot.new Turret(); - LoadHardwareClass.Intake Intake = Robot.new Intake(); - // Pass the starting pose of the robot to the Robot class Robot.initialPose = startPose; @@ -77,7 +72,7 @@ public void runOpMode() { while (opModeIsActive()) { // Pass the joystick positions to our mecanum drive controller - Drivetrain.pedroMecanumDrive( + Robot.drivetrain.pedroMecanumDrive( gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x, @@ -94,19 +89,19 @@ public void runOpMode() { target = 270; } - Turret.setTurretAngle(target); + Robot.turret.setTurretAngle(target); - Intake.setPower(gamepad1.left_trigger); + Robot.intake.setPower(gamepad1.left_trigger); // Turret-related Telemetry telemetry.addData("Turret Target Angle:", target); - telemetry.addData("Turret Actual Angle", Turret.getAngleAbsolute()); - telemetry.addData("Turret Set Power", Turret.getTurretPower()); + telemetry.addData("Turret Actual Angle", Robot.turret.getAngleAbsolute()); + telemetry.addData("Turret Set Power", Robot.turret.getTurretPower()); // Intake-related Telemetry telemetry.addLine(); - telemetry.addData("Intake Set Power", Intake.getPower()); - telemetry.addData("Intake RPM", Intake.getTurretVelocityRPM()); + telemetry.addData("Intake Set Power", Robot.intake.getPower()); + telemetry.addData("Intake RPM", Robot.intake.getTurretVelocityRPM()); // System-related Telemetry telemetry.addLine(); From 34939345c950986a76a1750f7e516c1f33c8d319 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Wed, 5 Nov 2025 16:13:02 -0500 Subject: [PATCH 050/152] Began setting up to add the other turret actuation classes (hood, flywheel) --- .../LOADCode/Main_/LoadHardwareClass.java | 203 +++++++++--------- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 6 +- 2 files changed, 106 insertions(+), 103 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 38e27d801dc9..ae3e488a2541 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -34,6 +34,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.Servo; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @@ -65,12 +66,15 @@ public class LoadHardwareClass { private DcMotor frontRight = null; private DcMotor backLeft = null; private DcMotor backRight = null; + // Turret + private DcMotorEx turretRotationMotor = null; + private DcMotorEx turretFlywheel = null; + private Servo turretHoodServo = null; // Other - private DcMotorEx turretMotor = null; private DcMotorEx intakeMotor = null; // Misc Constants - public Follower follower = null; + private Follower follower = null; public Pose initialPose = new Pose(0,0, 0); // Public drive constants @@ -97,34 +101,36 @@ public LoadHardwareClass(LinearOpMode opmode) { * Must be called once at the start of each op-mode. */ public void init() { - // Define and initialize motors (note: need to use reference to actual OpMode). - frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "FL"); - frontRight = myOpMode.hardwareMap.get(DcMotor.class, "FR"); - backLeft = myOpMode.hardwareMap.get(DcMotor.class, "BL"); - backRight = myOpMode.hardwareMap.get(DcMotor.class, "BR"); - - turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "turret"); - intakeMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "intake"); - - // Set motor directions - frontLeft.setDirection(DcMotor.Direction.REVERSE); - frontRight.setDirection(DcMotor.Direction.FORWARD); - backLeft.setDirection(DcMotor.Direction.REVERSE); - backRight.setDirection(DcMotor.Direction.FORWARD); + // Define and initialize motors & servos (note: need to use reference to actual OpMode). + // Drivetrain + frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "FL"); + frontRight = myOpMode.hardwareMap.get(DcMotor.class, "FR"); + backLeft = myOpMode.hardwareMap.get(DcMotor.class, "BL"); + backRight = myOpMode.hardwareMap.get(DcMotor.class, "BR"); + // Turret + turretRotationMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "turretRotation"); + turretFlywheel = myOpMode.hardwareMap.get(DcMotorEx.class, "turretFlywheel"); + turretHoodServo = myOpMode.hardwareMap.get(Servo.class, "turretHood"); + // Intake + intakeMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "intake"); + + // Set motor/servo directions + // Drivetrain + frontLeft.setDirection(DcMotor.Direction.REVERSE); + frontRight.setDirection(DcMotor.Direction.FORWARD); + backLeft.setDirection(DcMotor.Direction.REVERSE); + backRight.setDirection(DcMotor.Direction.FORWARD); // If the motors have encoders, handle all that here - // Define and initialize servos here - - // Set servo directions - // PedroPathing initialization - follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower - follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field - follower.update(); // Applies the initialization + follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower + follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field + follower.update(); // Applies the initialization - myOpMode.telemetry.addData(">", "Hardware Initialized"); - myOpMode.telemetry.update(); + // Misc telemetry + myOpMode.telemetry.addData(">", "Hardware Initialized"); + myOpMode.telemetry.update(); } public class Drivetrain { @@ -199,86 +205,83 @@ public void setDrivePower(double flPower, double frPower, double blPower, double } public class Turret { - // Turret Constants + public final TurretHeading heading = new TurretHeading(); + + /** + * This class contains the controls and functions for the heading of the turret + */ + public class TurretHeading { + // Turret Constants // PID coefficients PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); // Encoder ticks/rotation // 1620rpm - 103.8 ticks at the motor shaft double ticksPerRotation = 103.8; - - /** - * @return The current position of the turret motor in encoder ticks. Can be any value. - */ - public double getEncoderTicks(){ - return turretMotor.getCurrentPosition(); - } - - /** - * @return The resolution of the turret's encoder in ticks/rotation. - */ - public double getEncoderResolution(){ - return ticksPerRotation; - } - - /** - * @param power A value between -1 and 1 that the turret motor's power will be set to. - */ - public void setPower(double power){ - turretMotor.setPower(power); - } - - /** - * @return The angle of the turret in degrees. Can be any value. - */ - public double getAngleAbsolute(){ - return (getEncoderTicks()/ticksPerRotation*360); - } - - /** - * @return The angle of the turret in degrees. Can be any value between 0 and 360. - */ - public double getTurretAngle(){ - return getAngleAbsolute()%360; - } - - /** - * @return The velocity of the turret in encoder ticks/second. - */ - public double getTurretVelocity(){ - return turretMotor.getVelocity(); - } - - /** - * @return The velocity of the turret in degrees/second. - */ - public double getTurretVelocityDegrees(){ - return (getTurretVelocity()/ticksPerRotation*360); - } - - /** - * @return The velocity of the turret in RPM. - */ - public double getTurretVelocityRPM(){ - return ((getTurretVelocity()*60)/ticksPerRotation); - } - - /** - * @return The power that the turret motor has been set to. - */ - public double getTurretPower(){ - return turretMotor.getPower(); - } - - /** - * Uses a PID controller to move the turret to the desired position. - * Must be called every loop to function properly. - * @param angle The angle to move the turret to. - */ - public void setTurretAngle(double angle){ - ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getAngleAbsolute(), getTurretVelocity()); - turretPID.setGoal(new KineticState(angle)); - setPower(turretPID.calculate(currentKineticState)); + /** + * @return The current position of the turret motor in encoder ticks. Can be any value. + */ + public double getEncoderTicks(){ + return turretRotationMotor.getCurrentPosition(); + } + /** + * @return The resolution of the turret's encoder in ticks/rotation. + */ + public double getEncoderResolution(){ + return ticksPerRotation; + } + /** + * @param power A value between -1 and 1 that the turret motor's power will be set to. + */ + public void setPower(double power){ + turretRotationMotor.setPower(power); + } + /** + * @return The angle of the turret in degrees. Can be any value. + */ + public double getAngleAbsolute(){ + return (getEncoderTicks()/ticksPerRotation*360); + } + /** + * @return The angle of the turret in degrees. Can be any value between 0 and 360. + */ + public double getAngle(){ + return getAngleAbsolute()%360; + } + /** + * @return The velocity of the turret in encoder ticks/second. + */ + public double getVelocity(){ + return turretRotationMotor.getVelocity(); + } + /** + * @return The velocity of the turret in degrees/second. + */ + public double getVelocityDegrees(){ + return (getVelocity()/ticksPerRotation*360); + } + /** + * @return The velocity of the turret in RPM. + */ + public double getVelocityRPM(){ + return ((getVelocity()*60)/ticksPerRotation); + } + /** + * @return The power that the turret motor has been set to. + */ + public double getPower(){ + return turretRotationMotor.getPower(); + } + /** + * Uses a PID controller to move the turret to the desired position. + * Must be called every loop to function properly. + * @param angle The angle to move the turret to. + */ + public void setTargetAngle(double angle){ + ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getVelocity()); + turretPID.setGoal(new KineticState(angle)); + setPower(turretPID.calculate(currentKineticState)); + } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index de7ffe22b7ef..847deee80d5b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -89,14 +89,14 @@ public void runOpMode() { target = 270; } - Robot.turret.setTurretAngle(target); + Robot.turret.heading.setTargetAngle(target); Robot.intake.setPower(gamepad1.left_trigger); // Turret-related Telemetry telemetry.addData("Turret Target Angle:", target); - telemetry.addData("Turret Actual Angle", Robot.turret.getAngleAbsolute()); - telemetry.addData("Turret Set Power", Robot.turret.getTurretPower()); + telemetry.addData("Turret Actual Angle", Robot.turret.heading.getAngleAbsolute()); + telemetry.addData("Turret Set Power", Robot.turret.heading.getPower()); // Intake-related Telemetry telemetry.addLine(); From 6946198b326d7a1b8638b34e5f7514d0275b2182 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Wed, 5 Nov 2025 22:24:33 -0500 Subject: [PATCH 051/152] Moved all motor functionality to an external DcMotorExClass for easier development --- .../Hardware_Classes/DcMotorExClass.java | 109 ++++++++++++++ .../LOADCode/Main_/LoadHardwareClass.java | 134 ++---------------- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 4 +- 3 files changed, 120 insertions(+), 127 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java new file mode 100644 index 000000000000..dac4ee981174 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java @@ -0,0 +1,109 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes; + +import com.qualcomm.robotcore.hardware.DcMotorEx; + +import dev.nextftc.control.ControlSystem; +import dev.nextftc.control.KineticState; +import dev.nextftc.control.feedback.PIDCoefficients; + +public class DcMotorExClass { + // Turret Constants + // PID coefficients + PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); + // Encoder ticks/rotation + // 1620rpm - 103.8 ticks at the motor shaft + double ticksPerRotation = 103.8; + + private DcMotorEx motorObject = null; + + public DcMotorExClass(DcMotorEx motor){ + motorObject = motor; + } + + /** + * @return The current position of the turret motor in encoder ticks. Can be any value. + */ + public double getEncoderTicks(){ + return motorObject.getCurrentPosition(); + } + + /** + * @return The resolution of the turret's encoder in ticks/rotation. + */ + public double getEncoderResolution(){ + return ticksPerRotation; + } + + /** + * @param power A value between -1 and 1 that the turret motor's power will be set to. + */ + public void setPower(double power){ + motorObject.setPower(power); + } + + /** + * @return The angle of the turret in degrees. Can be any value. + */ + public double getAngleAbsolute(){ + return (getEncoderTicks()/ticksPerRotation*360); + } + + /** + * @return The angle of the turret in degrees. Can be any value between 0 and 360. + */ + public double getAngle(){ + return getAngleAbsolute()%360; + } + + /** + * @return The velocity of the turret in encoder ticks/second. + */ + public double getVelocity(){ + return motorObject.getVelocity(); + } + + /** + * @return The velocity of the turret in degrees/second. + */ + public double getDegreesPerSecond(){ + return (getVelocity()/ticksPerRotation*360); + } + + /** + * @return The velocity of the turret in RPM. + */ + public double getRPM(){ + return ((getVelocity()*60)/ticksPerRotation); + } + + /** + * @return The power that the turret motor has been set to. + */ + public double getPower(){ + return motorObject.getPower(); + } + + /** + * Uses a PID controller to move the motor to the desired position. + * Must be called every loop to function properly. + * @param angle The angle to move the motor to. + */ + public void setAngle(double angle){ + ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getVelocity()); + turretPID.setGoal(new KineticState(angle)); + setPower(turretPID.calculate(currentKineticState)); + } + + /** + * Uses a PID controller to accelerate the motor to the desired RPM + * Must be called every loop to function properly. + * @param rpm The RPM to accelerate the motor to + */ + public void setTurretAngle(double rpm){ + ControlSystem PID = ControlSystem.builder().velPid(turretCoefficients).build(); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getVelocity()); + PID.setGoal(new KineticState(0, rpm)); + setPower(PID.calculate(currentKineticState)); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 38e27d801dc9..4a1f4ecfa8fc 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -35,6 +35,7 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.DcMotorExClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import dev.nextftc.control.ControlSystem; @@ -67,6 +68,7 @@ public class LoadHardwareClass { private DcMotor backRight = null; // Other private DcMotorEx turretMotor = null; + private DcMotorEx flywheelMotor = null; private DcMotorEx intakeMotor = null; // Misc Constants @@ -78,8 +80,9 @@ public class LoadHardwareClass { // Declare subclasses public final Drivetrain drivetrain; - public final Turret turret; - public final Intake intake; + public final DcMotorExClass turret; + public final DcMotorExClass flywheel; + public final DcMotorExClass intake; /** * Constructor that allows the OpMode to pass a reference to itself. @@ -87,8 +90,9 @@ public class LoadHardwareClass { */ public LoadHardwareClass(LinearOpMode opmode) { myOpMode = opmode; - this.turret = new Turret(); - this.intake = new Intake(); + this.turret = new DcMotorExClass(turretMotor); + this.flywheel = new DcMotorExClass(flywheelMotor); + this.intake = new DcMotorExClass(intakeMotor); this.drivetrain = new Drivetrain(); } @@ -104,6 +108,7 @@ public void init() { backRight = myOpMode.hardwareMap.get(DcMotor.class, "BR"); turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "turret"); + turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "flywheel"); intakeMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "intake"); // Set motor directions @@ -197,125 +202,4 @@ public void setDrivePower(double flPower, double frPower, double blPower, double backRight.setPower(brPower); } } - - public class Turret { - // Turret Constants - // PID coefficients - PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); - // Encoder ticks/rotation - // 1620rpm - 103.8 ticks at the motor shaft - double ticksPerRotation = 103.8; - - /** - * @return The current position of the turret motor in encoder ticks. Can be any value. - */ - public double getEncoderTicks(){ - return turretMotor.getCurrentPosition(); - } - - /** - * @return The resolution of the turret's encoder in ticks/rotation. - */ - public double getEncoderResolution(){ - return ticksPerRotation; - } - - /** - * @param power A value between -1 and 1 that the turret motor's power will be set to. - */ - public void setPower(double power){ - turretMotor.setPower(power); - } - - /** - * @return The angle of the turret in degrees. Can be any value. - */ - public double getAngleAbsolute(){ - return (getEncoderTicks()/ticksPerRotation*360); - } - - /** - * @return The angle of the turret in degrees. Can be any value between 0 and 360. - */ - public double getTurretAngle(){ - return getAngleAbsolute()%360; - } - - /** - * @return The velocity of the turret in encoder ticks/second. - */ - public double getTurretVelocity(){ - return turretMotor.getVelocity(); - } - - /** - * @return The velocity of the turret in degrees/second. - */ - public double getTurretVelocityDegrees(){ - return (getTurretVelocity()/ticksPerRotation*360); - } - - /** - * @return The velocity of the turret in RPM. - */ - public double getTurretVelocityRPM(){ - return ((getTurretVelocity()*60)/ticksPerRotation); - } - - /** - * @return The power that the turret motor has been set to. - */ - public double getTurretPower(){ - return turretMotor.getPower(); - } - - /** - * Uses a PID controller to move the turret to the desired position. - * Must be called every loop to function properly. - * @param angle The angle to move the turret to. - */ - public void setTurretAngle(double angle){ - ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getAngleAbsolute(), getTurretVelocity()); - turretPID.setGoal(new KineticState(angle)); - setPower(turretPID.calculate(currentKineticState)); - } - } - - public class Intake { - // Intake Constants - // Encoder ticks/rotation - // 1620rpm - 103.8 ticks at the motor shaft - double ticksPerRotation = 103.8; - - - /** - * @param power A value between -1 and 1 that the intake motor's power will be set to. - */ - public void setPower(double power){ - intakeMotor.setPower(power); - } - - /** - * @return The power that the intake motor has been set to. - */ - public double getPower(){ - return intakeMotor.getPower(); - } - - /** - * @return The velocity of the turret in encoder ticks/second. - */ - public double getTurretVelocity(){ - return intakeMotor.getVelocity(); - } - - /** - * @return The velocity of the intake in RPM. - */ - public double getTurretVelocityRPM(){ - return ((getTurretVelocity()*60)/ticksPerRotation); - } - } - } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index de7ffe22b7ef..ed12998113f1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -96,12 +96,12 @@ public void runOpMode() { // Turret-related Telemetry telemetry.addData("Turret Target Angle:", target); telemetry.addData("Turret Actual Angle", Robot.turret.getAngleAbsolute()); - telemetry.addData("Turret Set Power", Robot.turret.getTurretPower()); + telemetry.addData("Turret Set Power", Robot.turret.getPower()); // Intake-related Telemetry telemetry.addLine(); telemetry.addData("Intake Set Power", Robot.intake.getPower()); - telemetry.addData("Intake RPM", Robot.intake.getTurretVelocityRPM()); + telemetry.addData("Intake RPM", Robot.intake.getRPM()); // System-related Telemetry telemetry.addLine(); From 1c690177a022f6860b6c9308179d0220713e55e4 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Wed, 5 Nov 2025 22:30:21 -0500 Subject: [PATCH 052/152] Bugfixed some merge issues --- .../LOADCode/Main_/LoadHardwareClass.java | 125 +----------------- 1 file changed, 3 insertions(+), 122 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 39c8c75b6e8f..69bfe2065ed1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -68,11 +68,10 @@ public class LoadHardwareClass { private DcMotor backLeft = null; private DcMotor backRight = null; // Turret - private DcMotorEx turretRotationMotor = null; - private DcMotorEx turretFlywheel = null; - private Servo turretHoodServo = null; - // Other private DcMotorEx turretMotor = null; + private DcMotorEx flywheelMotor = null; + private Servo hoodServo = null; + // Other private DcMotorEx intakeMotor = null; // Misc Constants @@ -204,122 +203,4 @@ public void setDrivePower(double flPower, double frPower, double blPower, double backRight.setPower(brPower); } } - - public class Turret { - public final TurretHeading heading = new TurretHeading(); - - /** - * This class contains the controls and functions for the heading of the turret - */ - public class TurretHeading { - // Turret Constants - // PID coefficients - PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); - // Encoder ticks/rotation - // 1620rpm - 103.8 ticks at the motor shaft - double ticksPerRotation = 103.8; - /** - * @return The current position of the turret motor in encoder ticks. Can be any value. - */ - public double getEncoderTicks(){ - return turretRotationMotor.getCurrentPosition(); - } - /** - * @return The resolution of the turret's encoder in ticks/rotation. - */ - public double getEncoderResolution(){ - return ticksPerRotation; - } - /** - * @param power A value between -1 and 1 that the turret motor's power will be set to. - */ - public void setPower(double power){ - turretRotationMotor.setPower(power); - } - /** - * @return The angle of the turret in degrees. Can be any value. - */ - public double getAngleAbsolute(){ - return (getEncoderTicks()/ticksPerRotation*360); - } - /** - * @return The angle of the turret in degrees. Can be any value between 0 and 360. - */ - public double getAngle(){ - return getAngleAbsolute()%360; - } - /** - * @return The velocity of the turret in encoder ticks/second. - */ - public double getVelocity(){ - return turretRotationMotor.getVelocity(); - } - /** - * @return The velocity of the turret in degrees/second. - */ - public double getVelocityDegrees(){ - return (getVelocity()/ticksPerRotation*360); - } - /** - * @return The velocity of the turret in RPM. - */ - public double getVelocityRPM(){ - return ((getVelocity()*60)/ticksPerRotation); - } - /** - * @return The power that the turret motor has been set to. - */ - public double getPower(){ - return turretRotationMotor.getPower(); - } - /** - * Uses a PID controller to move the turret to the desired position. - * Must be called every loop to function properly. - * @param angle The angle to move the turret to. - */ - public void setTargetAngle(double angle){ - ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getAngleAbsolute(), getVelocity()); - turretPID.setGoal(new KineticState(angle)); - setPower(turretPID.calculate(currentKineticState)); - } - } - } - - public class Intake { - // Intake Constants - // Encoder ticks/rotation - // 1620rpm - 103.8 ticks at the motor shaft - double ticksPerRotation = 103.8; - - - /** - * @param power A value between -1 and 1 that the intake motor's power will be set to. - */ - public void setPower(double power){ - intakeMotor.setPower(power); - } - - /** - * @return The power that the intake motor has been set to. - */ - public double getPower(){ - return intakeMotor.getPower(); - } - - /** - * @return The velocity of the turret in encoder ticks/second. - */ - public double getTurretVelocity(){ - return intakeMotor.getVelocity(); - } - - /** - * @return The velocity of the intake in RPM. - */ - public double getTurretVelocityRPM(){ - return ((getTurretVelocity()*60)/ticksPerRotation); - } - } - } From 9e6d0ea4acbb91ff12fc4830b5dfc29f25a87455 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Thu, 6 Nov 2025 08:37:10 -0500 Subject: [PATCH 053/152] Finished creating a generic DcMotorExClass and MecanumDrivetrainClass for abstraction purposes. --- .../Hardware_Classes/DcMotorExClass.java | 58 ++++--- .../MecanumDrivetrainClass.java | 55 ++++++ .../LOADCode/Main_/LoadHardwareClass.java | 156 ++---------------- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 7 +- 4 files changed, 107 insertions(+), 169 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java index dac4ee981174..c308138f4cdc 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java @@ -1,5 +1,8 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes; +import androidx.annotation.NonNull; + +import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotorEx; import dev.nextftc.control.ControlSystem; @@ -7,17 +10,35 @@ import dev.nextftc.control.feedback.PIDCoefficients; public class DcMotorExClass { - // Turret Constants // PID coefficients PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); // Encoder ticks/rotation - // 1620rpm - 103.8 ticks at the motor shaft + // 1620rpm Gobilda - 103.8 ticks at the motor shaft double ticksPerRotation = 103.8; - + // Motor object private DcMotorEx motorObject = null; - public DcMotorExClass(DcMotorEx motor){ - motorObject = motor; + /** + * Initializes the motor hardware + * @param opmode Allows this class to access the robot hardware objects. + * @param motorName The name of the motor in the robot's configuration. + * @param encoderResolution The resolution of the motor's encoder in ticks/rotation. + */ + public void init (@NonNull OpMode opmode, String motorName, double encoderResolution){ + // Initialize the motor object + motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); + ticksPerRotation = encoderResolution; + } + /** + * Initializes the motor hardware. + * The resolution of the motor encoder will default to + * 103.8 ticks/rotation, the value for a 1620RPM Gobilda motor. + * @param opmode Allows this class to access the robot hardware objects. + * @param motorName The name of the motor in the robot's configuration. + */ + public void init (@NonNull OpMode opmode, String motorName){ + // Initialize the motor object + motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); } /** @@ -26,84 +47,75 @@ public DcMotorExClass(DcMotorEx motor){ public double getEncoderTicks(){ return motorObject.getCurrentPosition(); } - /** * @return The resolution of the turret's encoder in ticks/rotation. */ public double getEncoderResolution(){ return ticksPerRotation; } - /** * @param power A value between -1 and 1 that the turret motor's power will be set to. */ public void setPower(double power){ motorObject.setPower(power); } - /** * @return The angle of the turret in degrees. Can be any value. */ public double getAngleAbsolute(){ return (getEncoderTicks()/ticksPerRotation*360); } - /** * @return The angle of the turret in degrees. Can be any value between 0 and 360. */ public double getAngle(){ return getAngleAbsolute()%360; } - /** * @return The velocity of the turret in encoder ticks/second. */ public double getVelocity(){ return motorObject.getVelocity(); } - /** * @return The velocity of the turret in degrees/second. */ public double getDegreesPerSecond(){ - return (getVelocity()/ticksPerRotation*360); + return (getVelocity()/ticksPerRotation)*360; } - /** * @return The velocity of the turret in RPM. */ public double getRPM(){ - return ((getVelocity()*60)/ticksPerRotation); + return (getVelocity()/ticksPerRotation)*60; } - /** * @return The power that the turret motor has been set to. */ public double getPower(){ return motorObject.getPower(); } - /** * Uses a PID controller to move the motor to the desired position. * Must be called every loop to function properly. - * @param angle The angle to move the motor to. + * @param angle The angle in degrees to move the motor to. Can be any number. */ public void setAngle(double angle){ ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getAngleAbsolute(), getVelocity()); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); turretPID.setGoal(new KineticState(angle)); setPower(turretPID.calculate(currentKineticState)); } - /** * Uses a PID controller to accelerate the motor to the desired RPM * Must be called every loop to function properly. - * @param rpm The RPM to accelerate the motor to + * @param rpm The RPM to accelerate the motor to. Can be any number */ - public void setTurretAngle(double rpm){ + public void setRPM(double rpm){ + double degreesPerSecond = rpm*6; ControlSystem PID = ControlSystem.builder().velPid(turretCoefficients).build(); - KineticState currentKineticState = new KineticState(getAngleAbsolute(), getVelocity()); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); PID.setGoal(new KineticState(0, rpm)); setPower(PID.calculate(currentKineticState)); } -} +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java new file mode 100644 index 000000000000..d5ac68e19fea --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java @@ -0,0 +1,55 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes; + +import androidx.annotation.NonNull; + +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; + +public class MecanumDrivetrainClass { + // Controls the speed of the robot + public double speedMultiplier = 1.0; // make this slower for outreaches + + // Misc Constants + private Follower follower = null; + private Pose initialPose = new Pose(0,0, 0); + + /** + * @param pose The position and heading that the robot starts at on the field. + */ + public void setInitialPose (Pose pose){ + initialPose = pose; + } + + /** + * Initializes the PedroPathing follower. + * Needs to be run once after all hardware is initialized. + * Does not need to be run if not using PedroPathing. + * @param myOpMode Allows the follower access to the robot hardware. + */ + public void init (@NonNull OpMode myOpMode){ + // PedroPathing initialization + follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower + follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field + follower.update(); // Applies the initialization + } + + /** + * Uses PedroPathing's follower class to implement a mecanum drive controller. + * Must be called every loop to function properly. + * @param forward The joystick value for driving forward/backward + * @param strafe The joystick value for strafing + * @param rotate The joystick value to turn left/right + * @param robotCentric If true, enables robot centric. If false, enables field centric. + */ + public void pedroMecanumDrive(double forward, double strafe, double rotate, boolean robotCentric){ + follower.setTeleOpDrive( + forward * speedMultiplier, + strafe * speedMultiplier, + rotate * speedMultiplier, + robotCentric); + follower.update(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 69bfe2065ed1..ad37dd4db95a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -28,20 +28,9 @@ */ package org.firstinspires.ftc.teamcode.LOADCode.Main_; - -import com.pedropathing.follower.Follower; -import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.hardware.DcMotor; -import com.qualcomm.robotcore.hardware.DcMotorEx; -import com.qualcomm.robotcore.hardware.Servo; - import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.DcMotorExClass; -import org.firstinspires.ftc.teamcode.pedroPathing.Constants; - -import dev.nextftc.control.ControlSystem; -import dev.nextftc.control.KineticState; -import dev.nextftc.control.feedback.PIDCoefficients; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.MecanumDrivetrainClass; /* * This file is designed to work with our OpModes to handle all our hardware functionality to de-clutter our main scripts @@ -49,40 +38,12 @@ * The logic goes in the OpModes and the hardware control is handled here. */ -//TODO Abstract all the individual systems rather than the entire hardware -/* -Example: Abstract class for drivetrain, Turret, intake, etc -They could be all individually referenced in the main OpMode -Drivetrain.doThing(args); -Turret.doOtherThing(args); -etc etc -*/ public class LoadHardwareClass { /* Declare OpMode members. */ private LinearOpMode myOpMode = null; // gain access to methods in the calling OpMode. - // Motors and servos go here - // Drivetrain - private DcMotor frontLeft = null; - private DcMotor frontRight = null; - private DcMotor backLeft = null; - private DcMotor backRight = null; - // Turret - private DcMotorEx turretMotor = null; - private DcMotorEx flywheelMotor = null; - private Servo hoodServo = null; - // Other - private DcMotorEx intakeMotor = null; - - // Misc Constants - private Follower follower = null; - public Pose initialPose = new Pose(0,0, 0); - - // Public drive constants - public double speedMultiplier = 1.0; // make this slower for outreaches - // Declare subclasses - public final Drivetrain drivetrain; + public final MecanumDrivetrainClass drivetrain; public final DcMotorExClass turret; public final DcMotorExClass flywheel; public final DcMotorExClass intake; @@ -93,114 +54,23 @@ public class LoadHardwareClass { */ public LoadHardwareClass(LinearOpMode opmode) { myOpMode = opmode; - this.turret = new DcMotorExClass(turretMotor); - this.flywheel = new DcMotorExClass(flywheelMotor); - this.intake = new DcMotorExClass(intakeMotor); - this.drivetrain = new Drivetrain(); + this.drivetrain = new MecanumDrivetrainClass(); + this.turret = new DcMotorExClass(); + this.flywheel = new DcMotorExClass(); + this.intake = new DcMotorExClass(); } - /** * Initializes all hardware for the robot. * Must be called once at the start of each op-mode. */ public void init() { - // Define and initialize motors (note: need to use reference to actual OpMode). - frontLeft = myOpMode.hardwareMap.get(DcMotor.class, "FL"); - frontRight = myOpMode.hardwareMap.get(DcMotor.class, "FR"); - backLeft = myOpMode.hardwareMap.get(DcMotor.class, "BL"); - backRight = myOpMode.hardwareMap.get(DcMotor.class, "BR"); - - turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "turret"); - turretMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "flywheel"); - intakeMotor = myOpMode.hardwareMap.get(DcMotorEx.class, "intake"); - - // Set motor/servo directions - // Drivetrain - frontLeft.setDirection(DcMotor.Direction.REVERSE); - frontRight.setDirection(DcMotor.Direction.FORWARD); - backLeft.setDirection(DcMotor.Direction.REVERSE); - backRight.setDirection(DcMotor.Direction.FORWARD); - - // If the motors have encoders, handle all that here - - // PedroPathing initialization - follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower - follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field - follower.update(); // Applies the initialization - + // Initialize all subclasses + drivetrain.init(myOpMode); + turret.init(myOpMode, "turret"); + flywheel.init(myOpMode, "flywheel"); + intake.init(myOpMode, "intake"); // Misc telemetry - myOpMode.telemetry.addData(">", "Hardware Initialized"); - myOpMode.telemetry.update(); - } - - public class Drivetrain { - /** - * Implements a custom mecanum drive controller. - * Must be called every loop to function properly. - * @param Forward The joystick value for driving forward/backward - * @param Strafe The joystick value for strafing - * @param Rotate The joystick value to turn left/right - */ - public void mecanumDrive(double Forward, double Strafe, double Rotate) { - // Puts the inputted joystick values into their own variable to allow for modification. - double forward = Forward * speedMultiplier; - double strafe = Strafe * speedMultiplier; - double rotate = Rotate * speedMultiplier; - - // This calculates the power needed for each wheel based on the amount of forward, - // strafe right, and rotate - double frontLeftPower = -forward + strafe + rotate; - double frontRightPower = -forward - strafe - rotate; - double backRightPower = -forward + strafe - rotate; - double backLeftPower = -forward - strafe + rotate; - - double maxPower = 1.0; - - // This is needed to make sure we don't pass > 1.0 to any wheel - // It allows us to keep all of the motors in proportion to what they should - // be and not get clipped - maxPower = Math.max(maxPower, Math.abs(frontLeftPower)); - maxPower = Math.max(maxPower, Math.abs(frontRightPower)); - maxPower = Math.max(maxPower, Math.abs(backRightPower)); - maxPower = Math.max(maxPower, Math.abs(backLeftPower)); - - // We multiply by maxSpeed so that it can be set lower for outreaches - // When a young child is driving the robot, we may not want to allow full - // speed. - setDrivePower( - (frontLeftPower / maxPower), - (frontRightPower / maxPower), - (backLeftPower / maxPower), - (backRightPower / maxPower) - ); - } - - /** - * Uses PedroPathing's follower class to implement a mecanum drive controller. - * Must be called every loop to function properly. - * @param forward The joystick value for driving forward/backward - * @param strafe The joystick value for strafing - * @param rotate The joystick value to turn left/right - * @param robotCentric If true, enables robot centric. If false, enables field centric. - */ - public void pedroMecanumDrive(double forward, double strafe, double rotate, boolean robotCentric){ - follower.setTeleOpDrive( - forward * speedMultiplier, - strafe * speedMultiplier, - rotate * speedMultiplier, - robotCentric); - follower.update(); - } - - /** - * Sets the output power of all four drivetrain motors. - */ - public void setDrivePower(double flPower, double frPower, double blPower, double brPower) { - // Output the values to the motor drives. - frontLeft.setPower(flPower); - frontRight.setPower(frPower); - backLeft.setPower(blPower); - backRight.setPower(brPower); - } + myOpMode.telemetry.addData(">", "Hardware Initialized"); + myOpMode.telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index ed12998113f1..5029cfa87e12 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -55,8 +55,8 @@ public void runOpMode() { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); - // Pass the starting pose of the robot to the Robot class - Robot.initialPose = startPose; + // Pass the starting pose of the robot to the drivetrain subclass + Robot.drivetrain.setInitialPose(startPose); // Wait for the game to start (driver presses START) waitForStart(); @@ -89,9 +89,10 @@ public void runOpMode() { target = 270; } - Robot.turret.setTurretAngle(target); + Robot.turret.setAngle(target); Robot.intake.setPower(gamepad1.left_trigger); + Robot.flywheel.setPower(gamepad1.right_trigger); // Turret-related Telemetry telemetry.addData("Turret Target Angle:", target); From 7513d7cd0305503a912aadcb02e3257d69c1b0e8 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Thu, 6 Nov 2025 08:46:26 -0500 Subject: [PATCH 054/152] Added a way to set the PID coefficients for a motor object --- .../LOADCode/Main_/Hardware_Classes/DcMotorExClass.java | 6 +++--- .../Main_/Hardware_Classes/MecanumDrivetrainClass.java | 4 +++- .../ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java | 5 +++++ 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java index c308138f4cdc..188b5056f497 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java @@ -11,7 +11,7 @@ public class DcMotorExClass { // PID coefficients - PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); + PIDCoefficients coefficients = new PIDCoefficients(0.005, 0, 0); // Encoder ticks/rotation // 1620rpm Gobilda - 103.8 ticks at the motor shaft double ticksPerRotation = 103.8; @@ -101,7 +101,7 @@ public double getPower(){ * @param angle The angle in degrees to move the motor to. Can be any number. */ public void setAngle(double angle){ - ControlSystem turretPID = ControlSystem.builder().posPid(turretCoefficients).build(); + ControlSystem turretPID = ControlSystem.builder().posPid(coefficients).build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); turretPID.setGoal(new KineticState(angle)); setPower(turretPID.calculate(currentKineticState)); @@ -113,7 +113,7 @@ public void setAngle(double angle){ */ public void setRPM(double rpm){ double degreesPerSecond = rpm*6; - ControlSystem PID = ControlSystem.builder().velPid(turretCoefficients).build(); + ControlSystem PID = ControlSystem.builder().velPid(coefficients).build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); PID.setGoal(new KineticState(0, rpm)); setPower(PID.calculate(currentKineticState)); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java index d5ac68e19fea..8a08068b850a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java @@ -17,6 +17,9 @@ public class MecanumDrivetrainClass { private Pose initialPose = new Pose(0,0, 0); /** + * Sets the initial position & heading of the robot. + * Must be run BEFORE the robot is intialized. + * Otherwise, it will default to (0,0,0). * @param pose The position and heading that the robot starts at on the field. */ public void setInitialPose (Pose pose){ @@ -26,7 +29,6 @@ public void setInitialPose (Pose pose){ /** * Initializes the PedroPathing follower. * Needs to be run once after all hardware is initialized. - * Does not need to be run if not using PedroPathing. * @param myOpMode Allows the follower access to the robot hardware. */ public void init (@NonNull OpMode myOpMode){ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index ad37dd4db95a..c4ed680f5f20 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -32,6 +32,8 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.DcMotorExClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.MecanumDrivetrainClass; +import dev.nextftc.control.feedback.PIDCoefficients; + /* * This file is designed to work with our OpModes to handle all our hardware functionality to de-clutter our main scripts * @@ -48,6 +50,9 @@ public class LoadHardwareClass { public final DcMotorExClass flywheel; public final DcMotorExClass intake; + // Subsystem configuration + PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); + /** * Constructor that allows the OpMode to pass a reference to itself. * @param opmode The input for this parameter should almost always be "this". From 25684686f468e398e19ec49fa28cfd9980bfe894 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Thu, 6 Nov 2025 08:56:52 -0500 Subject: [PATCH 055/152] Implemented the setting of the PID coefficients for the turret and flywheel in LoadHardwareClass --- .../Main_/Hardware_Classes/DcMotorExClass.java | 15 +++++++++++---- .../LOADCode/Main_/LoadHardwareClass.java | 8 +++++++- .../Testing_/TeleOps/TurretLocalization.java | 4 +--- 3 files changed, 19 insertions(+), 8 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java index 188b5056f497..d77e5b3faf8b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java @@ -10,8 +10,8 @@ import dev.nextftc.control.feedback.PIDCoefficients; public class DcMotorExClass { - // PID coefficients - PIDCoefficients coefficients = new PIDCoefficients(0.005, 0, 0); + // PID pidCoefficients + PIDCoefficients pidCoefficients = new PIDCoefficients(0.005, 0, 0); // Encoder ticks/rotation // 1620rpm Gobilda - 103.8 ticks at the motor shaft double ticksPerRotation = 103.8; @@ -41,6 +41,13 @@ public void init (@NonNull OpMode opmode, String motorName){ motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); } + /** + * Sets the value of the PID coefficients of the motor. + * @param coefficients The values to set the coefficients to. + */ + public void setPidCoefficients(PIDCoefficients coefficients) { + pidCoefficients = coefficients; + } /** * @return The current position of the turret motor in encoder ticks. Can be any value. */ @@ -101,7 +108,7 @@ public double getPower(){ * @param angle The angle in degrees to move the motor to. Can be any number. */ public void setAngle(double angle){ - ControlSystem turretPID = ControlSystem.builder().posPid(coefficients).build(); + ControlSystem turretPID = ControlSystem.builder().posPid(pidCoefficients).build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); turretPID.setGoal(new KineticState(angle)); setPower(turretPID.calculate(currentKineticState)); @@ -113,7 +120,7 @@ public void setAngle(double angle){ */ public void setRPM(double rpm){ double degreesPerSecond = rpm*6; - ControlSystem PID = ControlSystem.builder().velPid(coefficients).build(); + ControlSystem PID = ControlSystem.builder().velPid(pidCoefficients).build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); PID.setGoal(new KineticState(0, rpm)); setPower(PID.calculate(currentKineticState)); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index c4ed680f5f20..164982c25219 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -52,6 +52,7 @@ public class LoadHardwareClass { // Subsystem configuration PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); + PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); /** * Constructor that allows the OpMode to pass a reference to itself. @@ -71,9 +72,14 @@ public LoadHardwareClass(LinearOpMode opmode) { public void init() { // Initialize all subclasses drivetrain.init(myOpMode); - turret.init(myOpMode, "turret"); + turret.init(myOpMode, "turret", 103.8); flywheel.init(myOpMode, "flywheel"); intake.init(myOpMode, "intake"); + + // Pass PID pidCoefficients to motor classes + turret.setPidCoefficients(turretCoefficients); + flywheel.setPidCoefficients(flywheelCoefficients); + // Misc telemetry myOpMode.telemetry.addData(">", "Hardware Initialized"); myOpMode.telemetry.update(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java index 35012485bdec..542bb87d0d0f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java @@ -30,7 +30,6 @@ package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; import com.bylazar.configurables.annotations.Configurable; -import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; @@ -54,7 +53,6 @@ import dev.nextftc.control.ControlSystem; import dev.nextftc.control.KineticState; import dev.nextftc.control.feedback.PIDCoefficients; -import kotlin.jvm.JvmField; /* * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. @@ -103,7 +101,7 @@ public class TurretLocalization extends LinearOpMode public static Follower follower; // Used for managing the PedroPathing path follower public TelemetryManager telemetryM; // Used for putting telemetry data on Panels - //Turret PID coefficients + //Turret PID pidCoefficients public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.75, 0.005, 200); public static int turretDeadZoneSize = 5; From 18fb1c80eb85ddea4e4891949332a8ded4323e01 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Thu, 6 Nov 2025 09:44:26 -0500 Subject: [PATCH 056/152] Reworked how the initial robot pose is passed to MecanumDrivetrainClass to be more intuitive --- .../Hardware_Classes/MecanumDrivetrainClass.java | 14 ++------------ .../teamcode/LOADCode/Main_/LoadHardwareClass.java | 5 +++-- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 5 +---- 3 files changed, 6 insertions(+), 18 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java index 8a08068b850a..d571ebae3124 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java @@ -14,24 +14,14 @@ public class MecanumDrivetrainClass { // Misc Constants private Follower follower = null; - private Pose initialPose = new Pose(0,0, 0); - - /** - * Sets the initial position & heading of the robot. - * Must be run BEFORE the robot is intialized. - * Otherwise, it will default to (0,0,0). - * @param pose The position and heading that the robot starts at on the field. - */ - public void setInitialPose (Pose pose){ - initialPose = pose; - } /** * Initializes the PedroPathing follower. * Needs to be run once after all hardware is initialized. * @param myOpMode Allows the follower access to the robot hardware. + * @param initialPose The starting pose of the robot. */ - public void init (@NonNull OpMode myOpMode){ + public void init (@NonNull OpMode myOpMode, Pose initialPose){ // PedroPathing initialization follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 164982c25219..828861f39762 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -28,6 +28,7 @@ */ package org.firstinspires.ftc.teamcode.LOADCode.Main_; +import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.DcMotorExClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.MecanumDrivetrainClass; @@ -69,9 +70,9 @@ public LoadHardwareClass(LinearOpMode opmode) { * Initializes all hardware for the robot. * Must be called once at the start of each op-mode. */ - public void init() { + public void init(Pose initialPose) { // Initialize all subclasses - drivetrain.init(myOpMode); + drivetrain.init(myOpMode, initialPose); turret.init(myOpMode, "turret", 103.8); flywheel.init(myOpMode, "flywheel"); intake.init(myOpMode, "intake"); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 5029cfa87e12..f24a739dd506 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -55,9 +55,6 @@ public void runOpMode() { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); - // Pass the starting pose of the robot to the drivetrain subclass - Robot.drivetrain.setInitialPose(startPose); - // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); @@ -66,7 +63,7 @@ public void runOpMode() { double target = 0; // Initialize all hardware of the robot - Robot.init(); + Robot.init(startPose); // run until the end of the match (driver presses STOP) while (opModeIsActive()) { From 9ef1d23a5b8679943a80cab26d4aced2b088aa7f Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Thu, 6 Nov 2025 10:38:54 -0500 Subject: [PATCH 057/152] Worked on the velocity PID for the flywheel --- .../Calculation_Classes/Turret_Heading.java | 34 +++++++++++++++++++ .../Hardware_Classes/DcMotorExClass.java | 16 +++++++-- .../LOADCode/Main_/LoadHardwareClass.java | 3 ++ build.dependencies.gradle | 2 ++ 4 files changed, 53 insertions(+), 2 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java new file mode 100644 index 000000000000..53d28124967f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java @@ -0,0 +1,34 @@ +/* Copyright (c) 2022 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Calculation_Classes; + +public class Turret_Heading { + +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java index d77e5b3faf8b..19689018e1ce 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java @@ -8,10 +8,12 @@ import dev.nextftc.control.ControlSystem; import dev.nextftc.control.KineticState; import dev.nextftc.control.feedback.PIDCoefficients; +import dev.nextftc.control.feedforward.BasicFeedforwardParameters; public class DcMotorExClass { // PID pidCoefficients - PIDCoefficients pidCoefficients = new PIDCoefficients(0.005, 0, 0); + PIDCoefficients pidCoefficients = new PIDCoefficients(0, 0, 0); + BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); // Encoder ticks/rotation // 1620rpm Gobilda - 103.8 ticks at the motor shaft double ticksPerRotation = 103.8; @@ -48,6 +50,13 @@ public void init (@NonNull OpMode opmode, String motorName){ public void setPidCoefficients(PIDCoefficients coefficients) { pidCoefficients = coefficients; } + /** + * Sets the value of the FeedForward coefficients of the motor. + * @param coefficients The values to set the coefficients to. + */ + public void setFFCoefficients(BasicFeedforwardParameters coefficients) { + ffCoefficients = coefficients; + } /** * @return The current position of the turret motor in encoder ticks. Can be any value. */ @@ -120,7 +129,10 @@ public void setAngle(double angle){ */ public void setRPM(double rpm){ double degreesPerSecond = rpm*6; - ControlSystem PID = ControlSystem.builder().velPid(pidCoefficients).build(); + ControlSystem PID = ControlSystem.builder() + .velPid(pidCoefficients) + .basicFF(ffCoefficients) + .build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); PID.setGoal(new KineticState(0, rpm)); setPower(PID.calculate(currentKineticState)); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 828861f39762..4a9b55d1699a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -34,6 +34,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.MecanumDrivetrainClass; import dev.nextftc.control.feedback.PIDCoefficients; +import dev.nextftc.control.feedforward.BasicFeedforwardParameters; /* * This file is designed to work with our OpModes to handle all our hardware functionality to de-clutter our main scripts @@ -54,6 +55,7 @@ public class LoadHardwareClass { // Subsystem configuration PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); + BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); /** * Constructor that allows the OpMode to pass a reference to itself. @@ -80,6 +82,7 @@ public void init(Pose initialPose) { // Pass PID pidCoefficients to motor classes turret.setPidCoefficients(turretCoefficients); flywheel.setPidCoefficients(flywheelCoefficients); + flywheel.setFFCoefficients(ffCoefficients); // Misc telemetry myOpMode.telemetry.addData(">", "Hardware Initialized"); diff --git a/build.dependencies.gradle b/build.dependencies.gradle index 6c3f16adbefb..9325e95d3af9 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -18,5 +18,7 @@ dependencies { implementation 'com.pedropathing:ftc:2.0.3' implementation 'com.pedropathing:telemetry:1.0.0' implementation 'com.bylazar:fullpanels:1.0.9' + + implementation 'dev.nextftc:control:1.0.0' } From fefe9a4c7a9dd853e0579e743907a952a7d89232 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Thu, 6 Nov 2025 14:07:24 -0500 Subject: [PATCH 058/152] Created Turret_Heading class to store our heading calculations for the turret, and added it to testing system for turret. --- .../Calculation_Classes/Turret_Heading.java | 26 +++++++++++++++++++ .../Hardware_Classes/DcMotorExClass.java | 2 +- .../MecanumDrivetrainClass.java | 2 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 6 +++++ 4 files changed, 34 insertions(+), 2 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java index 53d28124967f..a0a7b68995af 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java @@ -29,6 +29,32 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Calculation_Classes; +import com.pedropathing.geometry.Pose; + public class Turret_Heading { + /** + * @param robotPose The pose of the robot, gotten from PedroPathing's localization + * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. + * @return The angle to set the turret to in degrees. + */ + public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ + Pose goalPose = new Pose(0,144,0); + if (targetRedGoal) {goalPose = new Pose(144, 144, 0);} + + + return Math.toDegrees(Math.atan2( + goalPose.getY()-robotPose.getY(), + goalPose.getX()-robotPose.getX() + ) + ) - Math.toDegrees(robotPose.getHeading()) + 180; + } + /** + * @param robotPose The pose of the robot, gotten from PedroPathing's localization + * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. + * @return The angle to set the turret to in degrees. + */ + public double calcAprilTag (Pose robotPose, boolean targetRedGoal){ + return 0; + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java index 19689018e1ce..8936b60ef094 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java @@ -134,7 +134,7 @@ public void setRPM(double rpm){ .basicFF(ffCoefficients) .build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); - PID.setGoal(new KineticState(0, rpm)); + PID.setGoal(new KineticState(0, degreesPerSecond)); setPower(PID.calculate(currentKineticState)); } } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java index d571ebae3124..d32c61ca47c2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java @@ -13,7 +13,7 @@ public class MecanumDrivetrainClass { public double speedMultiplier = 1.0; // make this slower for outreaches // Misc Constants - private Follower follower = null; + public Follower follower = null; /** * Initializes the PedroPathing follower. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index f24a739dd506..5f56e5dd8e34 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -34,6 +34,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.ElapsedTime; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Calculation_Classes.Turret_Heading; import org.firstinspires.ftc.teamcode.LOADCode.Main_.LoadHardwareClass; //TODO, implement all our external libraries and functionality. @@ -54,6 +55,7 @@ public void runOpMode() { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); + Turret_Heading targeting = new Turret_Heading(); // Wait for the game to start (driver presses START) waitForStart(); @@ -84,6 +86,10 @@ public void runOpMode() { target = 180; }else if (gamepad1.xWasPressed()){ target = 270; + }else if (gamepad1.guide){ + target = targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), true); + }else if (gamepad1.back){ + target = targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), false); } Robot.turret.setAngle(target); From 301f3d56566f242ab07b06268ede9a8ed5a6487a Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 10 Nov 2025 18:17:56 -0500 Subject: [PATCH 059/152] Bugfixes with Pedropathing mecanum drive & turret aimbot calculation work --- .../Calculation_Classes/Turret_Heading.java | 4 +--- .../Hardware_Classes/DcMotorExClass.java | 8 +++++++ .../MecanumDrivetrainClass.java | 9 ++++--- .../LOADCode/Main_/LoadHardwareClass.java | 16 +++++++++---- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 24 ++++++++++++------- .../TeleOps/PedroDriveToAprilTag.java | 3 ++- .../Testing_/TeleOps/TeleopTest_V1.java | 2 ++ .../TeleOps/TurretAprilTagTracking.java | 3 ++- .../Testing_/TeleOps/TurretLocalization.java | 2 ++ 9 files changed, 50 insertions(+), 21 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java index a0a7b68995af..10056d53d64b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java @@ -41,11 +41,9 @@ public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ Pose goalPose = new Pose(0,144,0); if (targetRedGoal) {goalPose = new Pose(144, 144, 0);} - return Math.toDegrees(Math.atan2( goalPose.getY()-robotPose.getY(), - goalPose.getX()-robotPose.getX() - ) + goalPose.getX()-robotPose.getX()) ) - Math.toDegrees(robotPose.getHeading()) + 180; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java index 8936b60ef094..47bfdb94e31b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java @@ -3,6 +3,7 @@ import androidx.annotation.NonNull; import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; import dev.nextftc.control.ControlSystem; @@ -57,6 +58,13 @@ public void setPidCoefficients(PIDCoefficients coefficients) { public void setFFCoefficients(BasicFeedforwardParameters coefficients) { ffCoefficients = coefficients; } + /** + * Resets the internal encoder of the motor to zero. + */ + public void resetEncoder(){ + motorObject.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); + motorObject.setMode(DcMotor.RunMode.RUN_USING_ENCODER); + } /** * @return The current position of the turret motor in encoder ticks. Can be any value. */ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java index d32c61ca47c2..41026b5cbc50 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java @@ -26,6 +26,9 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose){ follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field follower.update(); // Applies the initialization + + follower.startTeleopDrive(); + follower.update(); } /** @@ -38,9 +41,9 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose){ */ public void pedroMecanumDrive(double forward, double strafe, double rotate, boolean robotCentric){ follower.setTeleOpDrive( - forward * speedMultiplier, - strafe * speedMultiplier, - rotate * speedMultiplier, + -forward * speedMultiplier, + -strafe * speedMultiplier, + -rotate * speedMultiplier, robotCentric); follower.update(); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index 4a9b55d1699a..ea1aa2890c6a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -28,6 +28,7 @@ */ package org.firstinspires.ftc.teamcode.LOADCode.Main_; +import com.bylazar.configurables.annotations.Configurable; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.DcMotorExClass; @@ -41,7 +42,7 @@ * * The logic goes in the OpModes and the hardware control is handled here. */ - +@Configurable public class LoadHardwareClass { /* Declare OpMode members. */ private LinearOpMode myOpMode = null; // gain access to methods in the calling OpMode. @@ -53,9 +54,9 @@ public class LoadHardwareClass { public final DcMotorExClass intake; // Subsystem configuration - PIDCoefficients turretCoefficients = new PIDCoefficients(0.005, 0, 0); - PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); - BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); + public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); + public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); + public static BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); /** * Constructor that allows the OpMode to pass a reference to itself. @@ -88,4 +89,11 @@ public void init(Pose initialPose) { myOpMode.telemetry.addData(">", "Hardware Initialized"); myOpMode.telemetry.update(); } + + public void updatePIDs(){ + // Pass PID pidCoefficients to motor classes + turret.setPidCoefficients(turretCoefficients); + flywheel.setPidCoefficients(flywheelCoefficients); + flywheel.setFFCoefficients(ffCoefficients); + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 5f56e5dd8e34..403f124a4800 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -74,22 +74,24 @@ public void runOpMode() { Robot.drivetrain.pedroMecanumDrive( gamepad1.left_stick_y, gamepad1.left_stick_x, - gamepad1.right_stick_x, + gamepad1.right_stick_x/2, true ); - if (gamepad1.bWasPressed()){ + if (gamepad2.bWasPressed()){ target = 90; - }else if (gamepad1.yWasPressed()){ + }else if (gamepad2.yWasPressed()){ target = 0; - }else if (gamepad1.aWasPressed()){ + }else if (gamepad2.aWasPressed()){ target = 180; - }else if (gamepad1.xWasPressed()){ + }else if (gamepad2.xWasPressed()){ target = 270; - }else if (gamepad1.guide){ - target = targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), true); - }else if (gamepad1.back){ - target = targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), false); + }else if (gamepad2.guide){ + target = Math.abs(targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), true)-540); + }else if (gamepad2.back){ + target = Math.abs(targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), false)-540); + }else if (Math.abs(gamepad2.left_stick_x)>0.2 || Math.abs(gamepad2.left_stick_y)>0.2) { + target = Math.toDegrees(Math.atan2(gamepad2.left_stick_y, gamepad2.left_stick_x)); } Robot.turret.setAngle(target); @@ -97,10 +99,14 @@ public void runOpMode() { Robot.intake.setPower(gamepad1.left_trigger); Robot.flywheel.setPower(gamepad1.right_trigger); + Robot.updatePIDs(); + // Turret-related Telemetry + telemetry.addData("Turret PIDs", LoadHardwareClass.turretCoefficients); telemetry.addData("Turret Target Angle:", target); telemetry.addData("Turret Actual Angle", Robot.turret.getAngleAbsolute()); telemetry.addData("Turret Set Power", Robot.turret.getPower()); + telemetry.addData("Turret RPM", Robot.turret.getRPM()); // Intake-related Telemetry telemetry.addLine(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java index 85e5dfa4834c..33e9ad0a2e2d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java @@ -33,6 +33,7 @@ import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.Range; @@ -88,7 +89,7 @@ * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list. * */ - +@Disabled @TeleOp(name="Follow AprilTag", group = "TestTeleOp") public class PedroDriveToAprilTag extends LinearOpMode { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java index 2bf6850f09be..bf3e7448b693 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java @@ -4,11 +4,13 @@ import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +@Disabled @TeleOp(name = "Example Robot-Centric TeleOp", group = "TestTeleOp") public class TeleopTest_V1 extends OpMode { public static Follower follower; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java index 1f5245473418..360f4fe39b98 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java @@ -33,6 +33,7 @@ import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.AnalogInput; @@ -86,7 +87,7 @@ * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. * */ - +@Disabled @TeleOp(name="Turret April-Tag Tracking", group = "TestTeleOp") public class TurretAprilTagTracking extends LinearOpMode { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java index 542bb87d0d0f..379931b378d7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java @@ -33,6 +33,7 @@ import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.AnalogInput; @@ -90,6 +91,7 @@ * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. * */ +@Disabled @Configurable @TeleOp(name="Turret Localization", group = "TestTeleOp") public class TurretLocalization extends LinearOpMode From 9424c3935085e1397ce089cee4694107432408d9 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 11 Nov 2025 18:29:28 -0500 Subject: [PATCH 060/152] Made outreach TeleOp & began auto work --- .../LOADCode/Main_/Auto_/TestAuto.java | 233 ++++++++++++++++++ .../LOADCode/Main_/LoadHardwareClass.java | 2 + .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 2 +- .../Main_/Teleop_/Teleop_Outreach_.java | 85 +++++++ 4 files changed, 321 insertions(+), 1 deletion(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java new file mode 100644 index 000000000000..a92d6a81c116 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java @@ -0,0 +1,233 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Auto_; // make sure this aligns with class location + +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; +import com.pedropathing.util.Timer; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; + +@Autonomous(name = "TestAutoR1", group = "TestAuto") +public class TestAuto extends OpMode { + + private Follower follower; + private Timer pathTimer, actionTimer, opmodeTimer; + + private int pathState; + private boolean shooting; + + private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. + private final Pose scorePose = new Pose(86, 22, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. + private final Pose leavePose = new Pose(97, 30, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. + private final Pose pickupR3PoseA = new Pose(110.4, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. + private final Pose pickupR3PoseB = new Pose(121.9, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. + private final Pose pickupR2PoseA = new Pose(110.4, 59.5, Math.toRadians(0)); // Middle (Second Set) of Artifacts from the Spike Mark. + private final Pose pickupR2PoseB = new Pose(121.9, 59.5, Math.toRadians(0)); // Middle (Second Set) of Artifacts from the Spike Mark. + private final Pose pickupR1PoseA = new Pose(110.4, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. + private final Pose pickupR1PoseB = new Pose(121.9, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. + + private PathChain grabPickup1, scorePickup, grabPickup2, grabPickup3, leave; + + public void buildPaths() { + + grabPickup1 = follower.pathBuilder() + .addPath(new BezierCurve( + startPose, + new Pose(91.100, 35.700), + pickupR1PoseA + )) + .setLinearHeadingInterpolation(startPose.getHeading(), pickupR1PoseA.getHeading()) + .addPath(new BezierLine( + pickupR1PoseA, + pickupR1PoseB + )) + .setLinearHeadingInterpolation(pickupR1PoseA.getHeading(), pickupR1PoseA.getHeading()) + .build(); + + grabPickup2 = follower.pathBuilder() + .addPath(new BezierCurve( + scorePose, + new Pose(91.100, 60.5), + pickupR2PoseA + )) + .setLinearHeadingInterpolation(scorePose.getHeading(), pickupR2PoseA.getHeading()) + .addPath(new BezierLine( + pickupR2PoseA, + pickupR2PoseB + )) + .setLinearHeadingInterpolation(pickupR2PoseA.getHeading(), pickupR2PoseA.getHeading()) + .build(); + + grabPickup3 = follower.pathBuilder() + .addPath(new BezierCurve( + scorePose, + new Pose(91.100, 84.6), + pickupR3PoseA + )) + .setLinearHeadingInterpolation(scorePose.getHeading(), pickupR3PoseA.getHeading()) + .addPath(new BezierLine( + pickupR3PoseA, + pickupR3PoseB + )) + .setLinearHeadingInterpolation(pickupR3PoseA.getHeading(), pickupR3PoseA.getHeading()) + .build(); + + scorePickup = follower.pathBuilder() + .addPath(new BezierLine( + follower.getPose(), + scorePose + )) + .setLinearHeadingInterpolation(follower.getHeading(), scorePose.getHeading()) + .build(); + leave = follower.pathBuilder() + .addPath(new BezierLine( + follower.getPose(), + leavePose + )) + .setLinearHeadingInterpolation(follower.getHeading(), leavePose.getHeading()) + .build(); + } + + public void delay(int time){ + Timer wait = new Timer(); + wait.resetTimer(); + while (wait.getElapsedTime() < time){} + } + + public void autonomousPathUpdate() { + switch (pathState) { + case 0: + + /* You could check for + - Follower State: "if(!follower.isBusy()) {}" + - Time: "if(pathTimer.getElapsedTimeSeconds() > 1) {}" + - Robot Position: "if(follower.getPose().getX() > 36) {}" + */ + + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ + follower.followPath(grabPickup1,true); + setPathState(1); + } + break; + case 1: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup1Pose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(scorePickup,true); + setPathState(2); + } + break; + case 2: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ + follower.followPath(grabPickup2,true); + setPathState(3); + } + break; + case 3: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup2Pose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(scorePickup,true); + setPathState(4); + } + break; + case 4: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ + follower.followPath(grabPickup3,true); + setPathState(5); + } + break; + case 5: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(scorePickup, true); + setPathState(6); + } + break; + case 6: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ + if(!follower.isBusy()) { + /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ + follower.followPath(leave, true); + setPathState(7); + } + break; + case 7: + /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ + if(!follower.isBusy()) { + /* Set the state to a Case we won't use or define, so it just stops running an new paths */ + setPathState(-1); + } + break; + } + } + + /** These change the states of the paths and actions. It will also reset the timers of the individual switches **/ + public void setPathState(int pState) { + pathState = pState; + pathTimer.resetTimer(); + } + + /** This method is called once at the init of the OpMode. **/ + @Override + public void init() { + pathTimer = new Timer(); + opmodeTimer = new Timer(); + opmodeTimer.resetTimer(); + + follower = Constants.createFollower(hardwareMap); + buildPaths(); + follower.setStartingPose(startPose); + + } + + /** This method is called continuously after Init while waiting for "play". **/ + @Override + public void init_loop() {} + + /** This method is called once at the start of the OpMode. + * It runs all the setup actions, including building paths and starting the path system **/ + @Override + public void start() { + opmodeTimer.resetTimer(); + setPathState(0); + } + + /** This is the main loop of the OpMode, it will run repeatedly after clicking "Play". **/ + @Override + public void loop() { + + // These loop the movements of the robot, these must be called continuously in order to work + follower.update(); + autonomousPathUpdate(); + + // Feedback to Driver Hub for debugging + telemetry.addData("path state", pathState); + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("heading", follower.getPose().getHeading()); + telemetry.update(); + + if (gamepad1.left_stick_y < -10){ + + }else if (gamepad1.left_stick_y > 10){ + + } + } + + /** We do not use this because everything should automatically disable **/ + @Override + public void stop() { + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java index ea1aa2890c6a..271ab9a0ec4e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java @@ -96,4 +96,6 @@ public void updatePIDs(){ flywheel.setPidCoefficients(flywheelCoefficients); flywheel.setFFCoefficients(ffCoefficients); } + + } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 403f124a4800..4bbd0ea8792f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -39,7 +39,7 @@ //TODO, implement all our external libraries and functionality. -@TeleOp(name="Teleop_Main_", group="TestTeleOp") +@TeleOp(name="Teleop_Main_", group="TeleOp") public class Teleop_Main_ extends LinearOpMode { // Declare OpMode members. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java new file mode 100644 index 000000000000..6cda9ec4f013 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -0,0 +1,85 @@ +/* Copyright (c) 2017 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; + +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.util.ElapsedTime; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Calculation_Classes.Turret_Heading; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.LoadHardwareClass; + +//TODO, implement all our external libraries and functionality. + +@TeleOp(name="Teleop_Outreach_", group="TeleOp") +public class Teleop_Outreach_ extends LinearOpMode { + + // Declare OpMode members. + private ElapsedTime runtime = new ElapsedTime(); + + // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. + private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); + + @Override + public void runOpMode() { + telemetry.addData("Status", "Initialized"); + telemetry.update(); + + // Create a new instance of our Robot class + LoadHardwareClass Robot = new LoadHardwareClass(this); + + // Wait for the game to start (driver presses START) + waitForStart(); + runtime.reset(); + + // Initialize all hardware of the robot + Robot.init(startPose); + + // run until the end of the match (driver presses STOP) + while (opModeIsActive()) { + + // Pass the joystick positions to our mecanum drive controller + Robot.drivetrain.pedroMecanumDrive( + gamepad1.left_stick_y/2, + gamepad1.left_stick_x/2, + gamepad1.right_stick_x/2, + true + ); + + // System-related Telemetry + telemetry.addLine(); + telemetry.addData("Status", "Run Time: " + runtime.toString()); + telemetry.addData("Version: ", "11/4/25"); + telemetry.update(); + //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging + } + } +} From f06c7c90f8e33e1191095a86fde978e8f6753abc Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 11 Nov 2025 19:05:27 -0500 Subject: [PATCH 061/152] Installed Marrow and got Prompter working --- TeamCode/build.gradle | 1 + .../LOADCode/Main_/Auto_/TestAuto.java | 33 ++++++++++++++----- 2 files changed, 26 insertions(+), 8 deletions(-) diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index 878287a7c712..d077f69030f6 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -25,4 +25,5 @@ android { dependencies { implementation project(':FtcRobotController') + implementation 'io.github.skeleton-army.marrow:core:0.1.2' } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java index a92d6a81c116..eb95bfceaec8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java @@ -8,6 +8,8 @@ import com.pedropathing.util.Timer; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.skeletonarmy.marrow.prompts.OptionPrompt; +import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @@ -20,6 +22,15 @@ public class TestAuto extends OpMode { private int pathState; private boolean shooting; + Prompter prompter = null; + + enum Alliance { + RED, + BLUE + } + + Alliance alliance = null; + private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. private final Pose scorePose = new Pose(86, 22, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. private final Pose leavePose = new Pose(97, 30, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. @@ -190,11 +201,21 @@ public void init() { buildPaths(); follower.setStartingPose(startPose); + prompter = new Prompter(this); + prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", Alliance.RED, Alliance.BLUE)); + prompter.onComplete(() -> { + alliance = prompter.get("alliance"); + telemetry.addData("Selection", "Complete"); + } + ); + } /** This method is called continuously after Init while waiting for "play". **/ @Override - public void init_loop() {} + public void init_loop() { + prompter.run(); + } /** This method is called once at the start of the OpMode. * It runs all the setup actions, including building paths and starting the path system **/ @@ -210,7 +231,9 @@ public void loop() { // These loop the movements of the robot, these must be called continuously in order to work follower.update(); - autonomousPathUpdate(); + //autonomousPathUpdate(); + + telemetry.addData("Alliance", alliance); // Feedback to Driver Hub for debugging telemetry.addData("path state", pathState); @@ -218,12 +241,6 @@ public void loop() { telemetry.addData("y", follower.getPose().getY()); telemetry.addData("heading", follower.getPose().getHeading()); telemetry.update(); - - if (gamepad1.left_stick_y < -10){ - - }else if (gamepad1.left_stick_y > 10){ - - } } /** We do not use this because everything should automatically disable **/ From d731254c128de517ff62f0e3c231416ee66aa1a0 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Wed, 12 Nov 2025 09:07:04 -0500 Subject: [PATCH 062/152] Updated file system to reflect flowchart plan & removed some old test files. --- .../Actuators_}/DcMotorExClass.java | 2 +- .../Calculation_}/Turret_Heading.java | 2 +- .../Drivetrain_}/MecanumDrivetrainClass.java | 2 +- .../{ => Hardware_}/LoadHardwareClass.java | 9 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 4 +- .../Main_/Teleop_/Teleop_Outreach_.java | 3 +- .../LOADCode/Testing_/Autos/TestAutoR1.java | 233 ------------ .../{TeleOps => }/PedroDriveToAprilTag.java | 6 +- .../Testing_/TeleOps/TeleopTest_V1.java | 63 ---- .../Testing_/TeleOps/TurretLocalization.java | 357 ------------------ .../LOADCode/Testing_/Tests/ServoTest.java | 102 ----- .../{TeleOps => }/TurretAprilTagTracking.java | 2 +- 12 files changed, 14 insertions(+), 771 deletions(-) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/{Hardware_Classes => Hardware_/Actuators_}/DcMotorExClass.java (98%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/{Calculation_Classes => Hardware_/Calculation_}/Turret_Heading.java (97%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/{Hardware_Classes => Hardware_/Drivetrain_}/MecanumDrivetrainClass.java (96%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/{ => Hardware_}/LoadHardwareClass.java (92%) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Autos/TestAutoR1.java rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/{TeleOps => }/PedroDriveToAprilTag.java (98%) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Tests/ServoTest.java rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/{TeleOps => }/TurretAprilTagTracking.java (99%) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/DcMotorExClass.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/DcMotorExClass.java index 47bfdb94e31b..e44843ceb5c2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/DcMotorExClass.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes; +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; import androidx.annotation.NonNull; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Calculation_/Turret_Heading.java similarity index 97% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Calculation_/Turret_Heading.java index 10056d53d64b..4bb74bd4ad1c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Calculation_Classes/Turret_Heading.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Calculation_/Turret_Heading.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Calculation_Classes; +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_; import com.pedropathing.geometry.Pose; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java similarity index 96% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index 41026b5cbc50..eb11d98f8bdd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_Classes/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes; +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_; import androidx.annotation.NonNull; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java similarity index 92% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index 271ab9a0ec4e..b05e3c66b750 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -27,12 +27,13 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.Main_; +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; import com.bylazar.configurables.annotations.Configurable; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.DcMotorExClass; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_Classes.MecanumDrivetrainClass; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.DcMotorExClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; @@ -45,7 +46,7 @@ @Configurable public class LoadHardwareClass { /* Declare OpMode members. */ - private LinearOpMode myOpMode = null; // gain access to methods in the calling OpMode. + private final LinearOpMode myOpMode; // gain access to methods in the calling OpMode. // Declare subclasses public final MecanumDrivetrainClass drivetrain; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 4bbd0ea8792f..efd5b28aba2b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -34,8 +34,8 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.ElapsedTime; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Calculation_Classes.Turret_Heading; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.LoadHardwareClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_.Turret_Heading; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; //TODO, implement all our external libraries and functionality. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index 6cda9ec4f013..9eac8bfc9745 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -34,8 +34,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.ElapsedTime; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Calculation_Classes.Turret_Heading; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.LoadHardwareClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; //TODO, implement all our external libraries and functionality. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Autos/TestAutoR1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Autos/TestAutoR1.java deleted file mode 100644 index 22eac797483c..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Autos/TestAutoR1.java +++ /dev/null @@ -1,233 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Testing_.Autos; // make sure this aligns with class location - -import com.pedropathing.follower.Follower; -import com.pedropathing.geometry.BezierCurve; -import com.pedropathing.geometry.BezierLine; -import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.PathChain; -import com.pedropathing.util.Timer; -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; - -import org.firstinspires.ftc.teamcode.pedroPathing.Constants; - -@Autonomous(name = "TestAutoR1", group = "TestAuto") -public class TestAutoR1 extends OpMode { - - private Follower follower; - private Timer pathTimer, actionTimer, opmodeTimer; - - private int pathState; - private boolean shooting; - - private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. - private final Pose scorePose = new Pose(86, 22, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. - private final Pose leavePose = new Pose(97, 30, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. - private final Pose pickupR3PoseA = new Pose(110.4, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. - private final Pose pickupR3PoseB = new Pose(121.9, 83.6, Math.toRadians(0)); // Highest (First Set) of Artifacts from the Spike Mark. - private final Pose pickupR2PoseA = new Pose(110.4, 59.5, Math.toRadians(0)); // Middle (Second Set) of Artifacts from the Spike Mark. - private final Pose pickupR2PoseB = new Pose(121.9, 59.5, Math.toRadians(0)); // Middle (Second Set) of Artifacts from the Spike Mark. - private final Pose pickupR1PoseA = new Pose(110.4, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. - private final Pose pickupR1PoseB = new Pose(121.9, 35.5, Math.toRadians(0)); // Lowest (Third Set) of Artifacts from the Spike Mark. - - private PathChain grabPickup1, scorePickup, grabPickup2, grabPickup3, leave; - - public void buildPaths() { - - grabPickup1 = follower.pathBuilder() - .addPath(new BezierCurve( - startPose, - new Pose(91.100, 35.700), - pickupR1PoseA - )) - .setLinearHeadingInterpolation(startPose.getHeading(), pickupR1PoseA.getHeading()) - .addPath(new BezierLine( - pickupR1PoseA, - pickupR1PoseB - )) - .setLinearHeadingInterpolation(pickupR1PoseA.getHeading(), pickupR1PoseA.getHeading()) - .build(); - - grabPickup2 = follower.pathBuilder() - .addPath(new BezierCurve( - scorePose, - new Pose(91.100, 60.5), - pickupR2PoseA - )) - .setLinearHeadingInterpolation(scorePose.getHeading(), pickupR2PoseA.getHeading()) - .addPath(new BezierLine( - pickupR2PoseA, - pickupR2PoseB - )) - .setLinearHeadingInterpolation(pickupR2PoseA.getHeading(), pickupR2PoseA.getHeading()) - .build(); - - grabPickup3 = follower.pathBuilder() - .addPath(new BezierCurve( - scorePose, - new Pose(91.100, 84.6), - pickupR3PoseA - )) - .setLinearHeadingInterpolation(scorePose.getHeading(), pickupR3PoseA.getHeading()) - .addPath(new BezierLine( - pickupR3PoseA, - pickupR3PoseB - )) - .setLinearHeadingInterpolation(pickupR3PoseA.getHeading(), pickupR3PoseA.getHeading()) - .build(); - - scorePickup = follower.pathBuilder() - .addPath(new BezierLine( - follower.getPose(), - scorePose - )) - .setLinearHeadingInterpolation(follower.getHeading(), scorePose.getHeading()) - .build(); - leave = follower.pathBuilder() - .addPath(new BezierLine( - follower.getPose(), - leavePose - )) - .setLinearHeadingInterpolation(follower.getHeading(), leavePose.getHeading()) - .build(); - } - - public void delay(int time){ - Timer wait = new Timer(); - wait.resetTimer(); - while (wait.getElapsedTime() < time){} - } - - public void autonomousPathUpdate() { - switch (pathState) { - case 0: - - /* You could check for - - Follower State: "if(!follower.isBusy()) {}" - - Time: "if(pathTimer.getElapsedTimeSeconds() > 1) {}" - - Robot Position: "if(follower.getPose().getX() > 36) {}" - */ - - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { - /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ - follower.followPath(grabPickup1,true); - setPathState(1); - } - break; - case 1: - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup1Pose's position */ - if(!follower.isBusy()) { - /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ - follower.followPath(scorePickup,true); - setPathState(2); - } - break; - case 2: - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { - /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ - follower.followPath(grabPickup2,true); - setPathState(3); - } - break; - case 3: - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup2Pose's position */ - if(!follower.isBusy()) { - /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ - follower.followPath(scorePickup,true); - setPathState(4); - } - break; - case 4: - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { - /* Since this is a pathChain, we can have Pedro hold the end point while we are grabbing the sample */ - follower.followPath(grabPickup3,true); - setPathState(5); - } - break; - case 5: - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ - if(!follower.isBusy()) { - /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ - follower.followPath(scorePickup, true); - setPathState(6); - } - break; - case 6: - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the pickup3Pose's position */ - if(!follower.isBusy()) { - /* Since this is a pathChain, we can have Pedro hold the end point while we are scoring the sample */ - follower.followPath(leave, true); - setPathState(7); - } - break; - case 7: - /* This case checks the robot's position and will wait until the robot position is close (1 inch away) from the scorePose's position */ - if(!follower.isBusy()) { - /* Set the state to a Case we won't use or define, so it just stops running an new paths */ - setPathState(-1); - } - break; - } - } - - /** These change the states of the paths and actions. It will also reset the timers of the individual switches **/ - public void setPathState(int pState) { - pathState = pState; - pathTimer.resetTimer(); - } - - /** This method is called once at the init of the OpMode. **/ - @Override - public void init() { - pathTimer = new Timer(); - opmodeTimer = new Timer(); - opmodeTimer.resetTimer(); - - follower = Constants.createFollower(hardwareMap); - buildPaths(); - follower.setStartingPose(startPose); - - } - - /** This method is called continuously after Init while waiting for "play". **/ - @Override - public void init_loop() {} - - /** This method is called once at the start of the OpMode. - * It runs all the setup actions, including building paths and starting the path system **/ - @Override - public void start() { - opmodeTimer.resetTimer(); - setPathState(0); - } - - /** This is the main loop of the OpMode, it will run repeatedly after clicking "Play". **/ - @Override - public void loop() { - - // These loop the movements of the robot, these must be called continuously in order to work - follower.update(); - autonomousPathUpdate(); - - // Feedback to Driver Hub for debugging - telemetry.addData("path state", pathState); - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("heading", follower.getPose().getHeading()); - telemetry.update(); - - if (gamepad1.left_stick_y < -10){ - - }else if (gamepad1.left_stick_y > 10){ - - } - } - - /** We do not use this because everything should automatically disable **/ - @Override - public void stop() { - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/PedroDriveToAprilTag.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/PedroDriveToAprilTag.java index 33e9ad0a2e2d..8f3c7cb0f91c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/PedroDriveToAprilTag.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/PedroDriveToAprilTag.java @@ -27,13 +27,12 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; +package org.firstinspires.ftc.teamcode.LOADCode.Testing_; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.Range; @@ -89,7 +88,6 @@ * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list. * */ -@Disabled @TeleOp(name="Follow AprilTag", group = "TestTeleOp") public class PedroDriveToAprilTag extends LinearOpMode { @@ -120,7 +118,7 @@ public class PedroDriveToAprilTag extends LinearOpMode @IgnoreConfigurable static TelemetryManager telemetryM; /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ - private final Pose startPose = new Pose(60,96, Math.toRadians(0)); + private final Pose startPose = new Pose(0,0, Math.toRadians(0)); @Override public void runOpMode() { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java deleted file mode 100644 index bf3e7448b693..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TeleopTest_V1.java +++ /dev/null @@ -1,63 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; - -import com.bylazar.configurables.annotations.IgnoreConfigurable; -import com.bylazar.telemetry.TelemetryManager; -import com.pedropathing.follower.Follower; -import com.pedropathing.geometry.Pose; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; - -import org.firstinspires.ftc.teamcode.pedroPathing.Constants; - -@Disabled -@TeleOp(name = "Example Robot-Centric TeleOp", group = "TestTeleOp") -public class TeleopTest_V1 extends OpMode { - public static Follower follower; - @IgnoreConfigurable - static TelemetryManager telemetryM; - /** Start Pose of our robot. This can be changed or saved from the autonomous period. */ - private final Pose startPose = new Pose(60,96, Math.toRadians(0)); - - /** This method is called once when init is pressed and initializes the follower **/ - @Override - public void init() { - // Initializing the follower and setting its starting position. - follower = Constants.createFollower(hardwareMap); - follower.setStartingPose(startPose); - follower.update(); - } - - /** This method is called once at the start of the OpMode. **/ - @Override - public void start() { - // Calling this method is necessary at the start of your TeleOp OpMode. - follower.startTeleopDrive(); - follower.update(); - } - - /** This is the main loop of the OpMode and runs continuously after pressing play **/ - @Override - public void loop() { - // Update robot movement based on gamepad inputs - /* Update Pedro to move the robot based on: - * Forward/Backward Movement: -gamepad1.left_stick_y - * Left/Right Movement: -gamepad1.left_stick_x - * Turn Left/Right Movement: -gamepad1.right_stick_x - * Robot-Centric Mode: true - */ - follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, false); - // Loop robot movement and odometry values - follower.update(); - - // Telemetry Outputs of the Follower - telemetry.addData("X", follower.getPose().getX()); - telemetry.addData("Y", follower.getPose().getY()); - telemetry.addData("Heading in Degrees", Math.toDegrees(1)); - - // Update Telemetry to the Driver Hub - telemetry.update(); - - // Updating the status of the gamepad buttons - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java deleted file mode 100644 index 379931b378d7..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretLocalization.java +++ /dev/null @@ -1,357 +0,0 @@ -/* Copyright (c) 2023 FIRST. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted (subject to the limitations in the disclaimer below) provided that - * the following conditions are met: - * - * Redistributions of source code must retain the above copyright notice, this list - * of conditions and the following disclaimer. - * - * Redistributions in binary form must reproduce the above copyright notice, this - * list of conditions and the following disclaimer in the documentation and/or - * other materials provided with the distribution. - * - * Neither the name of FIRST nor the names of its contributors may be used to endorse or - * promote products derived from this software without specific prior written permission. - * - * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS - * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, - * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; - -import com.bylazar.configurables.annotations.Configurable; -import com.bylazar.telemetry.TelemetryManager; -import com.pedropathing.follower.Follower; -import com.pedropathing.geometry.Pose; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.AnalogInput; -import com.qualcomm.robotcore.hardware.CRServo; - -import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; -import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; -import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl; -import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl; -import org.firstinspires.ftc.teamcode.pedroPathing.Constants; -import org.firstinspires.ftc.vision.VisionPortal; -import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; -import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; - -import java.util.List; -import java.util.concurrent.TimeUnit; - -import dev.nextftc.control.ControlSystem; -import dev.nextftc.control.KineticState; -import dev.nextftc.control.feedback.PIDCoefficients; - -/* - * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. - * The code assumes a Holonomic (Mecanum or X Drive) Robot. - * - * For an introduction to AprilTags, see the ftc-docs link below: - * https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html - * - * When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera. - * This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below. - * https://ftc-docs.firstinspires.org/apriltag-detection-values - * - * The drive goal is to rotate to keep the Tag centered in the camera, while strafing to be directly in front of the tag, and - * driving towards the tag to achieve the desired distance. - * To reduce any motion blur (which will interrupt the detection process) the Camera exposure is reduced to a very low value (5mS) - * You can determine the best Exposure and Gain values by using the ConceptAprilTagOptimizeExposure OpMode in this Samples folder. - * - * The code assumes a Robot Configuration with motors named: front_left_drive and front_right_drive, back_left_drive and back_right_drive. - * The motor directions must be set so a positive power goes forward on all wheels. - * This sample assumes that the current game AprilTag Library (usually for the current season) is being loaded by default, - * so you should choose to approach a valid tag ID. - * - * Under manual control, the left stick will move forward/back & left/right. The right stick will rotate the robot. - * Manually drive the robot until it displays Target data on the Driver Station. - * - * Press and hold the *Left Bumper* to enable the automatic "Drive to target" mode. - * Release the Left Bumper to return to manual driving mode. - * - * Under "Drive To Target" mode, the robot has three goals: - * 1) Turn the robot to always keep the Tag centered on the camera frame. (Use the Target Bearing to turn the robot.) - * 2) Strafe the robot towards the centerline of the Tag, so it approaches directly in front of the tag. (Use the Target Yaw to strafe the robot) - * 3) Drive towards the Tag to get to the desired distance. (Use Tag Range to drive the robot forward/backward) - * - * Use DESIRED_DISTANCE to set how close you want the robot to get to the target. - * Speed and Turn sensitivity can be adjusted using the SPEED_GAIN, STRAFE_GAIN and TURN_GAIN constants. - * - */ -@Disabled -@Configurable -@TeleOp(name="Turret Localization", group = "TestTeleOp") -public class TurretLocalization extends LinearOpMode -{ - private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera - int DESIRED_TAG_ID = 24; // Choose the tag you want to approach or set to -1 for ANY tag. - private VisionPortal visionPortal; // Used to manage the video source. - private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. - public static Follower follower; // Used for managing the PedroPathing path follower - public TelemetryManager telemetryM; // Used for putting telemetry data on Panels - - //Turret PID pidCoefficients - public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.75, 0.005, 200); - - public static int turretDeadZoneSize = 5; - - // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. - private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); - - @Override public void runOpMode() - { - boolean targetFound; // Set to true when an AprilTag target is detected - double headingError = 0; // The error in degrees in the turret's angle - - // Used to store the hardware objects for the robot - CRServo turret; - AnalogInput turretEncoder; - - double turretPos; // Used to store the current angle of the turret - double turretPower; // Used to store the calculated power to output to the turret servo - boolean runTurret = true; - boolean useTurretPID = false; - double targetAngle; - double lastTurretPos; - int wraparoundTrigger = 0; - int[] goalCoords = new int[2]; - - ControlSystem turretPID = ControlSystem.builder() - .posPid(new PIDCoefficients(turretCoefficients.kP/100000000, turretCoefficients.kI/100000000, turretCoefficients.kD/100000000)) - .build(); - - initAprilTag(); // Initialize the Apriltag Detection process - - if (USE_WEBCAM) - setManualExposure(6, 250); // Use low exposure time to reduce motion blur - - follower = Constants.createFollower(hardwareMap); // Initializes the PedroPathing path follower - follower.setStartingPose(startPose); // Sets the initial position of the robot on the field - follower.update(); // Applies the initialization - - telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch START to start OpMode"); - telemetry.update(); - - waitForStart(); // Wait for driver to press start - - follower.startTeleopDrive(); // Activate the manual drive function for the drivetrain - follower.update(); // Apply the activation - - // Fetch the actual hardware objects and store them in their respective variables - turret = hardwareMap.get(CRServo.class, "turret"); - turretEncoder = hardwareMap.get(AnalogInput.class,"turretEncoder"); - lastTurretPos = Math.abs(((turretEncoder.getVoltage() / 3.3) * 360) - 360); - - while (opModeIsActive()) - { - - if (gamepad1.yWasPressed()){ - if (DESIRED_TAG_ID == 24){ - DESIRED_TAG_ID = 20; - } else { - DESIRED_TAG_ID = 24; - } - } - - if (DESIRED_TAG_ID == 24){ - goalCoords[0] = 144; - goalCoords[1] = 144; - }else if (DESIRED_TAG_ID == 20){ - goalCoords[0] = 0; - goalCoords[1] = 144; - } - - // Used to indicate whether or not a valid AprilTag has been detected - targetFound = false; - // Used to hold the data for a detected AprilTag - AprilTagDetection desiredTag = null; - - // Read the Axon servo encoder position and convert it from a voltage to an angle in degrees - turretPos = Math.abs(((turretEncoder.getVoltage() / 3.3) * 360) - 360); - - // Step through the list of detected tags and look for a matching tag - List currentDetections = aprilTag.getDetections(); - for (AprilTagDetection detection : currentDetections) { - // Look to see if we have size info on this tag. - if (detection.metadata != null) { - // Check to see if we want to track towards this tag. - if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) { - // Yes, we want to use this tag. - targetFound = true; - desiredTag = detection; - // Determine heading error so we can use them to control the robot automatically. - headingError = -desiredTag.ftcPose.bearing; - break; // don't look any further. - } else { - // This tag is in the library, but we do not want to track it right now. - telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id); - } - } else { - // This tag is NOT in the library, so we don't have enough information to track to it. - telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id); - } - } - - // Tell the driver what we see, and what to do. - if (DESIRED_TAG_ID == 24){ - telemetry.addData("Goal Selected: ","Red"); - } else { - telemetry.addData("Goal Selected: ","Blue"); - } - if (targetFound) { - telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); - telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); - telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); - telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); - } else { - telemetry.addData("\n>","Drive using joysticks to find a valid target\n"); - } - - // This block finds the robot position from it's odometry data and calculates the angle between the selected goal and the robot, adjusting the camera to match that angle - - double[] robotPose = {follower.getPose().getX(), follower.getPose().getY()}; - targetAngle = Math.toDegrees(Math.atan2(goalCoords[1]-robotPose[1], goalCoords[0]-robotPose[0])) - Math.toDegrees(follower.getPose().getHeading()); - targetAngle = (180 + targetAngle) % 360; - targetAngle = Math.min(Math.max(targetAngle, turretDeadZoneSize), 360-turretDeadZoneSize); - double angleDiff = (targetAngle - turretPos); - turretPower = -Math.pow(Math.min(Math.abs(angleDiff/60),1), (4f/3f)) * Math.signum(angleDiff); - - if (gamepad1.aWasPressed()){ - useTurretPID = !useTurretPID; - } - if (useTurretPID){ - turretPID.setGoal(new KineticState(targetAngle)); - turretPower = -turretPID.calculate(new KineticState(turretPos)); - telemetry.addData("Turret Control System:", "PID"); - }else{ - telemetry.addData("Turret Control System:", "Non-PID"); - } - - if (gamepad1.dpad_left){ - turretPower = 0.4; - }else if (gamepad1.dpad_right){ - turretPower = -0.4; - } - - if ((Math.abs(turretPos-lastTurretPos) >= 120) && (turretPos<350 || turretPos>10)){ - wraparoundTrigger += (int)Math.signum(turretPos - 180); - } - if (wraparoundTrigger != 0) { - turretPower = Math.max(Math.min(-wraparoundTrigger, 0.2), -0.2); - } - - if (gamepad1.bWasPressed()){ - runTurret = !runTurret; - } - if(runTurret){ - turret.setPower(turretPower); - }else{ - turret.setPower(0); - } - - // TODO We will work on Daniel's deadzone method next meeting, If that does not work, we will work on Ari's! - - - // Apply desired axes motions to the drivetrain - follower.setTeleOpDrive(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x, true); - follower.update(); - - lastTurretPos = turretPos; - - telemetry.addData("Target Angle", targetAngle); - telemetry.addData("Turret Angle", turretPos); - telemetry.addData("Turret Error", angleDiff); - telemetry.addData("Turret Power", turretPower); - telemetry.addData("Robot Heading", Math.toDegrees(follower.getPose().getHeading())); - telemetry.addData("Wraparound Trigger This Time: ", wraparoundTrigger); - telemetry.addData("-", "---------------------------------------------"); - telemetry.addData("kP", turretCoefficients.kP); - telemetry.addData("kI", turretCoefficients.kI); - telemetry.addData("kD", turretCoefficients.kD); - - telemetry.update(); - } - } - - /** - * Initialize the AprilTag processor. - */ - private void initAprilTag() { - // Create the AprilTag processor by using a builder. - aprilTag = new AprilTagProcessor.Builder().build(); - - // Adjust Image Decimation to trade-off detection-range for detection-rate. - // e.g. Some typical detection data using a Logitech C920 WebCam - // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second - // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second - // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second - // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second - // Note: Decimation can be changed on-the-fly to adapt during a match. - aprilTag.setDecimation(3); - - // Create the vision portal by using a builder. - if (USE_WEBCAM) { - visionPortal = new VisionPortal.Builder() - .setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")) - .addProcessor(aprilTag) - .build(); - } else { - visionPortal = new VisionPortal.Builder() - .setCamera(BuiltinCameraDirection.BACK) - .addProcessor(aprilTag) - .build(); - } - } - - /* - Manually set the camera gain and exposure. - This can only be called AFTER calling initAprilTag(), and only works for Webcams; - */ - private void setManualExposure(int exposureMS, int gain) { - // Wait for the camera to be open, then use the controls - - if (visionPortal == null) { - return; - } - - // Make sure camera is streaming before we try to set the exposure controls - if (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING) { - telemetry.addData("Camera", "Waiting"); - telemetry.update(); - while (!isStopRequested() && (visionPortal.getCameraState() != VisionPortal.CameraState.STREAMING)) { - sleep(20); - } - telemetry.addData("Camera", "Ready"); - telemetry.update(); - } - - // Set camera controls unless we are stopping. - if (!isStopRequested()) - { - ExposureControl exposureControl = visionPortal.getCameraControl(ExposureControl.class); - if (exposureControl.getMode() != ExposureControl.Mode.Manual) { - exposureControl.setMode(ExposureControl.Mode.Manual); - sleep(50); - } - exposureControl.setExposure((long)exposureMS, TimeUnit.MILLISECONDS); - sleep(20); - GainControl gainControl = visionPortal.getCameraControl(GainControl.class); - gainControl.setGain(gain); - sleep(20); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Tests/ServoTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Tests/ServoTest.java deleted file mode 100644 index 7ecb5011e141..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/Tests/ServoTest.java +++ /dev/null @@ -1,102 +0,0 @@ -/* Copyright (c) 2017 FIRST. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted (subject to the limitations in the disclaimer below) provided that - * the following conditions are met: - * - * Redistributions of source code must retain the above copyright notice, this list - * of conditions and the following disclaimer. - * - * Redistributions in binary form must reproduce the above copyright notice, this - * list of conditions and the following disclaimer in the documentation and/or - * other materials provided with the distribution. - * - * Neither the name of FIRST nor the names of its contributors may be used to endorse or - * promote products derived from this software without specific prior written permission. - * - * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS - * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, - * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -package org.firstinspires.ftc.teamcode.LOADCode.Testing_.Tests; - -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.AnalogInput; -import com.qualcomm.robotcore.hardware.CRServo; - -/* - * This OpMode scans a single servo back and forward until Stop is pressed. - * The code is structured as a LinearOpMode - * INCREMENT sets how much to increase/decrease the servo position each cycle - * CYCLE_MS sets the update period. - * - * This code assumes a Servo configured with the name "left_hand" as is found on a Robot. - * - * NOTE: When any servo position is set, ALL attached servos are activated, so ensure that any other - * connected servos are able to move freely before running this test. - * - * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. - * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list - */ -@TeleOp(name = "Servo Test", group = "TestHardware") - -public class ServoTest extends LinearOpMode { - - static final double INCREMENT = 0.01; // amount to slew servo each CYCLE_MS cycle - static final int CYCLE_MS = 10; // period of each cycle - static final double MAX_POS = 1.0; // Maximum rotational position - static final double MIN_POS = 0.0; // Minimum rotational position - - // Define class members - CRServo servo; - AnalogInput turretEncoder; - double axonPos = 0; // Start at halfway position - boolean rampUp = true; - - - @Override - public void runOpMode() { - - // Connect to servo (Assume Robot Left Hand) - // Change the text in quotes to match any servo name on your robot. - servo = hardwareMap.get(CRServo.class, "turret"); - turretEncoder = hardwareMap.get(AnalogInput.class,"AxonTurret"); - - - // Wait for the start button - telemetry.addData(">", "Press Start to scan Servo." ); - telemetry.update(); - waitForStart(); - - - // Scan servo till stop pressed. - while(opModeIsActive()){ - - axonPos = (turretEncoder.getVoltage() / 3.3) * 360; - - // Display the current value - telemetry.addData("Encoder Position", axonPos); - telemetry.addData("Servo Position", "%5.2f", gamepad1.right_stick_x); - telemetry.addData(">", "Press Stop to end test." ); - telemetry.update(); - - // Set the servo to the new position and pause; - servo.setPower(gamepad1.right_stick_x); - sleep(CYCLE_MS); - } - - // Signal done; - telemetry.addData(">", "Done"); - telemetry.update(); - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TurretAprilTagTracking.java similarity index 99% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TurretAprilTagTracking.java index 360f4fe39b98..0b39aaea7655 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TeleOps/TurretAprilTagTracking.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Testing_/TurretAprilTagTracking.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode.LOADCode.Testing_.TeleOps; +package org.firstinspires.ftc.teamcode.LOADCode.Testing_; import com.bylazar.configurables.annotations.IgnoreConfigurable; import com.bylazar.telemetry.TelemetryManager; From 15477124140bab6ca3a5f1ad54ae03f91c53b6e3 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Wed, 12 Nov 2025 10:17:07 -0500 Subject: [PATCH 063/152] began work on auto pathing class --- .../Drivetrain_/MecanumDrivetrainClass.java | 7 ++++ .../Hardware_/Drivetrain_/Pedro_Paths.java | 32 +++++++++++++++++++ 2 files changed, 39 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index eb11d98f8bdd..0e15affd4ccc 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -31,6 +31,13 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose){ follower.update(); } + /** + * @return Pedropathing's follower object + */ + public Follower getFollower() { + return follower; + } + /** * Uses PedroPathing's follower class to implement a mecanum drive controller. * Must be called every loop to function properly. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java new file mode 100644 index 000000000000..de15b2f716a1 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -0,0 +1,32 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_; + +import com.pedropathing.follower.Follower; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; + +public class Pedro_Paths { + // The variable to store PedroPathing's follower object for path building + private Follower follower; + + /** + * Must be called after MecanumDrivetrainClass is initialized. + * @param follow PedroPathing's follower object, gotten from MecanumDrivetrainClass + */ + public void init(Follower follow){ + follower = follow; + } + + // Define primary poses to be used in paths + public final Pose startPose1 = new Pose(87, 8.8, Math.toRadians(90)); + public final Pose scorePose1 = new Pose(86, 22, Math.toRadians(80)); + + // Define paths to be used by PedroPathing + public final PathChain gotoScorePose1 = follower.pathBuilder() + .addPath(new BezierCurve( + follower.getPose(), + scorePose1 + )) + .setLinearHeadingInterpolation(follower.getPose().getHeading(), scorePose1.getHeading()) + .build(); +} From c553d78e4b96e3123d49cffea88aab67e343c337 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Sat, 15 Nov 2025 08:54:15 -0500 Subject: [PATCH 064/152] Added Servo control classes --- .../Actuators_/Generic_/CRServoClass.java | 36 ++++++++++++++++++ .../{ => Generic_}/DcMotorExClass.java | 23 +++++++++++- .../Actuators_/Generic_/ServoClass.java | 37 +++++++++++++++++++ .../Main_/Hardware_/Actuators_/Intake.java | 26 +++++++++++++ .../Main_/Hardware_/LoadHardwareClass.java | 19 +++++++--- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 36 +++++++++++------- 6 files changed, 157 insertions(+), 20 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/{ => Generic_}/DcMotorExClass.java (88%) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java new file mode 100644 index 000000000000..8580b1521929 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java @@ -0,0 +1,36 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_; + +import androidx.annotation.NonNull; + +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.CRServo; +import com.qualcomm.robotcore.hardware.DcMotorSimple; + +public class CRServoClass{ + private CRServo servo; + + public void init(@NonNull OpMode opmode, String servoName){ + servo = opmode.hardwareMap.get(CRServo.class, servoName); + } + + /** + * @param power The power to set the servo to. Must be a value between -1 and 1. + */ + public void setPower(double power){ + servo.setPower(power); + } + + /** + * @param direction The direction to set the servo to. + */ + public void setDirection(DcMotorSimple.Direction direction){ + servo.setDirection(direction); + } + + /** + * @return The power the servo has been set to. + */ + public double getPower(){ + return servo.getPower(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java similarity index 88% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/DcMotorExClass.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java index e44843ceb5c2..0448e93f37b3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java @@ -1,10 +1,11 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_; import androidx.annotation.NonNull; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; import dev.nextftc.control.ControlSystem; import dev.nextftc.control.KineticState; @@ -65,6 +66,26 @@ public void resetEncoder(){ motorObject.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); motorObject.setMode(DcMotor.RunMode.RUN_USING_ENCODER); } + /** + * Sets the runMode of the motor. + * @param runMode The mode to set the motor to. + */ + public void setRunMode(DcMotor.RunMode runMode){ + motorObject.setMode(runMode); + } + /** + * Sets the zeroPowerBehaviour of the motor. + * @param behaviour The behaviour to apply to the motor. + */ + public void setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior behaviour){ + motorObject.setZeroPowerBehavior(behaviour); + } + /** + * @param direction The direction to set the motor to. + */ + public void setDirection(DcMotorSimple.Direction direction){ + motorObject.setDirection(direction); + } /** * @return The current position of the turret motor in encoder ticks. Can be any value. */ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java new file mode 100644 index 000000000000..ac65228e8b7f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java @@ -0,0 +1,37 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_; + +import androidx.annotation.NonNull; + +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.Servo; + +public class ServoClass { + private Servo servo; + + public void init(@NonNull OpMode opmode, String servoName){ + servo = opmode.hardwareMap.get(Servo.class, servoName); + } + + /** + * @param angle The angle to set the servo to. Must be a value between 0 and 1, + * representing the endpoints of it's movement. + */ + public void setAngle(double angle){ + servo.setPosition(angle); + } + + /** + * @param direction The direction to set the servo to. + */ + public void setDirection(Servo.Direction direction){ + servo.setDirection(direction); + } + + /** + * @return A value between 0 and 1 that the servo has been set to. + */ + public double getAngle(){ + return servo.getPosition(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java new file mode 100644 index 000000000000..f20e23ba0312 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -0,0 +1,26 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; + +import androidx.annotation.NonNull; + +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.CRServoClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; + +public class Intake { + private final OpMode opMode; + + private final DcMotorExClass intake; + private final CRServoClass belt; + + public Intake(OpMode opmode){ + opMode = opmode; + this.intake = new DcMotorExClass(); + this.belt = new CRServoClass(); + } + + public void init(){ + intake.init(opMode, "intake"); + + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index b05e3c66b750..608a13ce0256 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -28,11 +28,14 @@ */ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; + import com.bylazar.configurables.annotations.Configurable; import com.pedropathing.geometry.Pose; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.DcMotorExClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.CRServoClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; import dev.nextftc.control.feedback.PIDCoefficients; @@ -46,13 +49,14 @@ @Configurable public class LoadHardwareClass { /* Declare OpMode members. */ - private final LinearOpMode myOpMode; // gain access to methods in the calling OpMode. + private final OpMode myOpMode; // gain access to methods in the calling OpMode. // Declare subclasses public final MecanumDrivetrainClass drivetrain; public final DcMotorExClass turret; public final DcMotorExClass flywheel; public final DcMotorExClass intake; + public final CRServoClass belt; // Subsystem configuration public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); @@ -63,12 +67,13 @@ public class LoadHardwareClass { * Constructor that allows the OpMode to pass a reference to itself. * @param opmode The input for this parameter should almost always be "this". */ - public LoadHardwareClass(LinearOpMode opmode) { + public LoadHardwareClass(OpMode opmode) { myOpMode = opmode; this.drivetrain = new MecanumDrivetrainClass(); this.turret = new DcMotorExClass(); this.flywheel = new DcMotorExClass(); this.intake = new DcMotorExClass(); + this.belt = new CRServoClass(); } /** * Initializes all hardware for the robot. @@ -80,6 +85,10 @@ public void init(Pose initialPose) { turret.init(myOpMode, "turret", 103.8); flywheel.init(myOpMode, "flywheel"); intake.init(myOpMode, "intake"); + belt.init(myOpMode, "belt"); + + // Misc configuration + intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); // Pass PID pidCoefficients to motor classes turret.setPidCoefficients(turretCoefficients); @@ -97,6 +106,4 @@ public void updatePIDs(){ flywheel.setPidCoefficients(flywheelCoefficients); flywheel.setFFCoefficients(ffCoefficients); } - - } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index efd5b28aba2b..d50d6823af6e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -70,6 +70,12 @@ public void runOpMode() { // run until the end of the match (driver presses STOP) while (opModeIsActive()) { + if (gamepad1.left_trigger > 0.5){ + Robot.drivetrain.speedMultiplier = 0.2; + }else{ + Robot.drivetrain.speedMultiplier = 1; + } + // Pass the joystick positions to our mecanum drive controller Robot.drivetrain.pedroMecanumDrive( gamepad1.left_stick_y, @@ -78,15 +84,7 @@ public void runOpMode() { true ); - if (gamepad2.bWasPressed()){ - target = 90; - }else if (gamepad2.yWasPressed()){ - target = 0; - }else if (gamepad2.aWasPressed()){ - target = 180; - }else if (gamepad2.xWasPressed()){ - target = 270; - }else if (gamepad2.guide){ + if (gamepad2.guide){ target = Math.abs(targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), true)-540); }else if (gamepad2.back){ target = Math.abs(targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), false)-540); @@ -96,8 +94,13 @@ public void runOpMode() { Robot.turret.setAngle(target); - Robot.intake.setPower(gamepad1.left_trigger); - Robot.flywheel.setPower(gamepad1.right_trigger); + if (gamepad2.a){ + Robot.intake.setPower(-1); + }else if (gamepad2.x){ + Robot.intake.setPower(1); + } + + Robot.belt.setPower(gamepad2.left_trigger); Robot.updatePIDs(); @@ -106,11 +109,18 @@ public void runOpMode() { telemetry.addData("Turret Target Angle:", target); telemetry.addData("Turret Actual Angle", Robot.turret.getAngleAbsolute()); telemetry.addData("Turret Set Power", Robot.turret.getPower()); - telemetry.addData("Turret RPM", Robot.turret.getRPM()); // Intake-related Telemetry telemetry.addLine(); - telemetry.addData("Intake Set Power", Robot.intake.getPower()); + telemetry.addData("Intake Status", () -> { + if(Robot.intake.getPower() == 1){ + return "Outtaking"; + }else if (Robot.intake.getPower() == -1){ + return "Intaking"; + }else{ + return "Off"; + } + }); telemetry.addData("Intake RPM", Robot.intake.getRPM()); // System-related Telemetry From f87c29ce71e8e69be3470bf60e0a53d4231f65ba Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Sat, 15 Nov 2025 09:53:41 -0500 Subject: [PATCH 065/152] Put the intake motor and servo into it's own class for ease of use. --- .../Main_/Hardware_/Actuators_/Intake.java | 55 +++++++++++++++---- .../Main_/Hardware_/LoadHardwareClass.java | 15 ++--- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 22 +++----- 3 files changed, 57 insertions(+), 35 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index f20e23ba0312..99ef43a791f9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -1,26 +1,61 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; -import androidx.annotation.NonNull; - import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorSimple; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.CRServoClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; public class Intake { - private final OpMode opMode; + private static OpMode opMode; - private final DcMotorExClass intake; - private final CRServoClass belt; + private final DcMotorExClass intake = new DcMotorExClass(); + private final CRServoClass belt = new CRServoClass(); - public Intake(OpMode opmode){ - opMode = opmode; - this.intake = new DcMotorExClass(); - this.belt = new CRServoClass(); + public enum Mode { + INTAKE, + SHOOTING, + REVERSE, + OFF } - public void init(){ + public void init(OpMode opmode){ + opMode = opmode; intake.init(opMode, "intake"); + belt.init(opMode, "belt"); + + intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); + intake.setDirection(DcMotorSimple.Direction.REVERSE); + } + + public void setMode(Mode direction){ + if (direction == Mode.INTAKE){ + intake.setPower(1); + belt.setPower(1); + }else if (direction == Mode.SHOOTING){ + intake.setPower(0); + belt.setPower(1); + }else if (direction == Mode.REVERSE){ + intake.setPower(-1); + belt.setPower(-1); + }else{ + intake.setPower(0); + belt.setPower(0); + } + } + public Mode getMode(){ + double intakePower = intake.getPower(); + double beltPower = belt.getPower(); + if (intakePower == 1 && beltPower == 1){ + return Mode.INTAKE; + }else if (intakePower == 0 && beltPower == 1){ + return Mode.SHOOTING; + }else if (intakePower == -1 && beltPower == -1){ + return Mode.REVERSE; + }else{ + return Mode.OFF; + } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index 608a13ce0256..cb838a5d0b85 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -32,10 +32,9 @@ import com.bylazar.configurables.annotations.Configurable; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.hardware.DcMotor; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.CRServoClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; import dev.nextftc.control.feedback.PIDCoefficients; @@ -55,8 +54,7 @@ public class LoadHardwareClass { public final MecanumDrivetrainClass drivetrain; public final DcMotorExClass turret; public final DcMotorExClass flywheel; - public final DcMotorExClass intake; - public final CRServoClass belt; + public final Intake intake; // Subsystem configuration public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); @@ -72,8 +70,7 @@ public LoadHardwareClass(OpMode opmode) { this.drivetrain = new MecanumDrivetrainClass(); this.turret = new DcMotorExClass(); this.flywheel = new DcMotorExClass(); - this.intake = new DcMotorExClass(); - this.belt = new CRServoClass(); + this.intake = new Intake(); } /** * Initializes all hardware for the robot. @@ -84,11 +81,7 @@ public void init(Pose initialPose) { drivetrain.init(myOpMode, initialPose); turret.init(myOpMode, "turret", 103.8); flywheel.init(myOpMode, "flywheel"); - intake.init(myOpMode, "intake"); - belt.init(myOpMode, "belt"); - - // Misc configuration - intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); + intake.init(myOpMode); // Pass PID pidCoefficients to motor classes turret.setPidCoefficients(turretCoefficients); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index d50d6823af6e..c38afdf1b2ad 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -34,6 +34,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.ElapsedTime; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_.Turret_Heading; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @@ -95,13 +96,15 @@ public void runOpMode() { Robot.turret.setAngle(target); if (gamepad2.a){ - Robot.intake.setPower(-1); + Robot.intake.setMode(Intake.Mode.INTAKE); + }else if (gamepad2.b){ + Robot.intake.setMode(Intake.Mode.SHOOTING); }else if (gamepad2.x){ - Robot.intake.setPower(1); + Robot.intake.setMode(Intake.Mode.REVERSE); + }else{ + Robot.intake.setMode(Intake.Mode.OFF); } - Robot.belt.setPower(gamepad2.left_trigger); - Robot.updatePIDs(); // Turret-related Telemetry @@ -112,16 +115,7 @@ public void runOpMode() { // Intake-related Telemetry telemetry.addLine(); - telemetry.addData("Intake Status", () -> { - if(Robot.intake.getPower() == 1){ - return "Outtaking"; - }else if (Robot.intake.getPower() == -1){ - return "Intaking"; - }else{ - return "Off"; - } - }); - telemetry.addData("Intake RPM", Robot.intake.getRPM()); + telemetry.addData("Intake Status", Robot.intake.getMode()); // System-related Telemetry telemetry.addLine(); From 5bf1dd93cf2ea0e33426cd0830341c2d0568ec23 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Sat, 15 Nov 2025 13:05:32 -0500 Subject: [PATCH 066/152] Created a turret class that contains the heading motor, flywheel, and hood servo --- .../LOADCode/Main_/Auto_/TestAuto.java | 18 +++---- .../Actuators_/Generic_/DcMotorExClass.java | 16 +++---- .../Main_/Hardware_/Actuators_/Intake.java | 7 +-- .../Main_/Hardware_/Actuators_/Turret.java | 48 +++++++++++++++++++ .../Main_/Hardware_/LoadHardwareClass.java | 36 ++++---------- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 43 +++++++++++------ 6 files changed, 102 insertions(+), 66 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java index eb95bfceaec8..7f4b23dde48e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java @@ -11,9 +11,10 @@ import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; -@Autonomous(name = "TestAutoR1", group = "TestAuto") +@Autonomous(name = "TestAutoR1", group = "TestAuto", preselectTeleOp="Teleop_Main_") public class TestAuto extends OpMode { private Follower follower; @@ -24,12 +25,8 @@ public class TestAuto extends OpMode { Prompter prompter = null; - enum Alliance { - RED, - BLUE - } - - Alliance alliance = null; + // Create a new instance of our Robot class + LoadHardwareClass Robot = new LoadHardwareClass(this); private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. private final Pose scorePose = new Pose(86, 22, Math.toRadians(80)); // Scoring Pose of our robot. It is facing the goal at a 135 degree angle. @@ -202,13 +199,12 @@ public void init() { follower.setStartingPose(startPose); prompter = new Prompter(this); - prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", Alliance.RED, Alliance.BLUE)); + prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", LoadHardwareClass.Alliance.RED, LoadHardwareClass.Alliance.BLUE)); prompter.onComplete(() -> { - alliance = prompter.get("alliance"); + LoadHardwareClass.selectedAlliance = prompter.get("alliance"); telemetry.addData("Selection", "Complete"); } ); - } /** This method is called continuously after Init while waiting for "play". **/ @@ -233,7 +229,7 @@ public void loop() { follower.update(); //autonomousPathUpdate(); - telemetry.addData("Alliance", alliance); + telemetry.addData("Alliance", LoadHardwareClass.selectedAlliance); // Feedback to Driver Hub for debugging telemetry.addData("path state", pathState); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java index 0448e93f37b3..b8ee4836ce7c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java @@ -18,7 +18,9 @@ public class DcMotorExClass { BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); // Encoder ticks/rotation // 1620rpm Gobilda - 103.8 ticks at the motor shaft - double ticksPerRotation = 103.8; + public double ticksPerRotation = 103.8; + // Target position/velocity of the motor + public double target = 0; // Motor object private DcMotorEx motorObject = null; @@ -92,12 +94,6 @@ public void setDirection(DcMotorSimple.Direction direction){ public double getEncoderTicks(){ return motorObject.getCurrentPosition(); } - /** - * @return The resolution of the turret's encoder in ticks/rotation. - */ - public double getEncoderResolution(){ - return ticksPerRotation; - } /** * @param power A value between -1 and 1 that the turret motor's power will be set to. */ @@ -146,9 +142,10 @@ public double getPower(){ * @param angle The angle in degrees to move the motor to. Can be any number. */ public void setAngle(double angle){ + target = angle; ControlSystem turretPID = ControlSystem.builder().posPid(pidCoefficients).build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); - turretPID.setGoal(new KineticState(angle)); + turretPID.setGoal(new KineticState(target)); setPower(turretPID.calculate(currentKineticState)); } /** @@ -157,7 +154,8 @@ public void setAngle(double angle){ * @param rpm The RPM to accelerate the motor to. Can be any number */ public void setRPM(double rpm){ - double degreesPerSecond = rpm*6; + target = rpm; + double degreesPerSecond = target*6; ControlSystem PID = ControlSystem.builder() .velPid(pidCoefficients) .basicFF(ffCoefficients) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 99ef43a791f9..fc1aca065390 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -8,8 +8,6 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; public class Intake { - private static OpMode opMode; - private final DcMotorExClass intake = new DcMotorExClass(); private final CRServoClass belt = new CRServoClass(); @@ -21,9 +19,8 @@ public enum Mode { } public void init(OpMode opmode){ - opMode = opmode; - intake.init(opMode, "intake"); - belt.init(opMode, "belt"); + intake.init(opmode, "intake"); + belt.init(opmode, "belt"); intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); intake.setDirection(DcMotorSimple.Direction.REVERSE); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java new file mode 100644 index 000000000000..000cc97c205f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -0,0 +1,48 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; + +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.ServoClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_.Turret_Heading; + +import dev.nextftc.control.feedback.PIDCoefficients; +import dev.nextftc.control.feedforward.BasicFeedforwardParameters; + +public class Turret { + public final DcMotorExClass rotation = new DcMotorExClass(); + public final DcMotorExClass flywheel = new DcMotorExClass(); + public final ServoClass hood = new ServoClass(); + + Turret_Heading targeting = new Turret_Heading(); + + public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); + public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); + public static BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); + + public void init(OpMode opmode){ + rotation.init(opmode, "turret", 103.8); + flywheel.init(opmode, "flywheel"); + hood.init(opmode, "hood"); + + rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); + + // Pass PID pidCoefficients to motor classes + rotation.setPidCoefficients(turretCoefficients); + flywheel.setPidCoefficients(flywheelCoefficients); + flywheel.setFFCoefficients(ffCoefficients); + } + + public void updatePIDs(){ + // Pass PID pidCoefficients to motor classes + rotation.setPidCoefficients(turretCoefficients); + flywheel.setPidCoefficients(flywheelCoefficients); + flywheel.setFFCoefficients(ffCoefficients); + } + + public void updateAimbot(Pose robotPose, boolean goal){ + rotation.setAngle(targeting.calcLocalizer(robotPose, goal)); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index cb838a5d0b85..6765b1c7788c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -33,13 +33,10 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; -import dev.nextftc.control.feedback.PIDCoefficients; -import dev.nextftc.control.feedforward.BasicFeedforwardParameters; - /* * This file is designed to work with our OpModes to handle all our hardware functionality to de-clutter our main scripts * @@ -52,14 +49,15 @@ public class LoadHardwareClass { // Declare subclasses public final MecanumDrivetrainClass drivetrain; - public final DcMotorExClass turret; - public final DcMotorExClass flywheel; + public final Turret turret; public final Intake intake; - // Subsystem configuration - public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); - public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); - public static BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); + // Declare various enums & other variables that are useful across files + public static Alliance selectedAlliance = null; + public enum Alliance { + RED, + BLUE + } /** * Constructor that allows the OpMode to pass a reference to itself. @@ -68,8 +66,7 @@ public class LoadHardwareClass { public LoadHardwareClass(OpMode opmode) { myOpMode = opmode; this.drivetrain = new MecanumDrivetrainClass(); - this.turret = new DcMotorExClass(); - this.flywheel = new DcMotorExClass(); + this.turret = new Turret(); this.intake = new Intake(); } /** @@ -79,24 +76,11 @@ public LoadHardwareClass(OpMode opmode) { public void init(Pose initialPose) { // Initialize all subclasses drivetrain.init(myOpMode, initialPose); - turret.init(myOpMode, "turret", 103.8); - flywheel.init(myOpMode, "flywheel"); + turret.init(myOpMode); intake.init(myOpMode); - // Pass PID pidCoefficients to motor classes - turret.setPidCoefficients(turretCoefficients); - flywheel.setPidCoefficients(flywheelCoefficients); - flywheel.setFFCoefficients(ffCoefficients); - // Misc telemetry myOpMode.telemetry.addData(">", "Hardware Initialized"); myOpMode.telemetry.update(); } - - public void updatePIDs(){ - // Pass PID pidCoefficients to motor classes - turret.setPidCoefficients(turretCoefficients); - flywheel.setPidCoefficients(flywheelCoefficients); - flywheel.setFFCoefficients(ffCoefficients); - } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index c38afdf1b2ad..229181a49dab 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -33,9 +33,10 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.ElapsedTime; +import com.skeletonarmy.marrow.prompts.OptionPrompt; +import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_.Turret_Heading; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; //TODO, implement all our external libraries and functionality. @@ -46,6 +47,8 @@ public class Teleop_Main_ extends LinearOpMode { // Declare OpMode members. private ElapsedTime runtime = new ElapsedTime(); + Prompter prompter = null; + // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); @@ -56,15 +59,28 @@ public void runOpMode() { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); - Turret_Heading targeting = new Turret_Heading(); + + // Create a new prompter for selecting alliance + prompter = new Prompter(this); + prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", LoadHardwareClass.Alliance.RED, LoadHardwareClass.Alliance.BLUE)); + prompter.onComplete(() -> { + LoadHardwareClass.selectedAlliance = prompter.get("alliance"); + telemetry.addData("Selection", "Complete"); + } + ); + + // Runs repeatedly while in init + while (opModeInInit()){ + // If an auto was not run, run the prompter to select the correct alliance + if (LoadHardwareClass.selectedAlliance == null){ + prompter.run(); + } + } // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); - // This variable contains the target position for the turret. - double target = 0; - // Initialize all hardware of the robot Robot.init(startPose); @@ -86,15 +102,14 @@ public void runOpMode() { ); if (gamepad2.guide){ - target = Math.abs(targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), true)-540); + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); }else if (gamepad2.back){ - target = Math.abs(targeting.calcLocalizer(Robot.drivetrain.follower.getPose(), false)-540); + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); }else if (Math.abs(gamepad2.left_stick_x)>0.2 || Math.abs(gamepad2.left_stick_y)>0.2) { - target = Math.toDegrees(Math.atan2(gamepad2.left_stick_y, gamepad2.left_stick_x)); + Robot.turret.rotation.setAngle( + Math.toDegrees(Math.atan2(gamepad2.left_stick_y, gamepad2.left_stick_x))); } - Robot.turret.setAngle(target); - if (gamepad2.a){ Robot.intake.setMode(Intake.Mode.INTAKE); }else if (gamepad2.b){ @@ -105,13 +120,11 @@ public void runOpMode() { Robot.intake.setMode(Intake.Mode.OFF); } - Robot.updatePIDs(); + Robot.turret.updatePIDs(); // Turret-related Telemetry - telemetry.addData("Turret PIDs", LoadHardwareClass.turretCoefficients); - telemetry.addData("Turret Target Angle:", target); - telemetry.addData("Turret Actual Angle", Robot.turret.getAngleAbsolute()); - telemetry.addData("Turret Set Power", Robot.turret.getPower()); + telemetry.addData("Turret Target Angle:", Robot.turret.rotation.target); + telemetry.addData("Turret Actual Angle", Robot.turret.rotation.getAngleAbsolute()); // Intake-related Telemetry telemetry.addLine(); From e406f6caf39834beaab37d41dd7ad0be4e769685 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 17 Nov 2025 09:56:52 -0500 Subject: [PATCH 067/152] Added function in Turret.java to control the flywheel. --- .../teamcode/LOADCode/Main_/Auto_/TestAuto.java | 14 ++++++++++---- .../Main_/Hardware_/Actuators_/Intake.java | 12 ++++++------ .../Main_/Hardware_/Actuators_/Turret.java | 6 +++++- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 4 ++-- 4 files changed, 23 insertions(+), 13 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java index 7f4b23dde48e..0beef87c1783 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java @@ -100,10 +100,16 @@ public void buildPaths() { .build(); } - public void delay(int time){ - Timer wait = new Timer(); - wait.resetTimer(); - while (wait.getElapsedTime() < time){} + /** + * Copied over from LinearOpMode. + * @param milliseconds The number of milliseconds to sleep. + */ + public final void sleep(long milliseconds) { + try { + Thread.sleep(milliseconds); + } catch (InterruptedException e) { + Thread.currentThread().interrupt(); + } } public void autonomousPathUpdate() { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index fc1aca065390..606b4857d3e8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -12,9 +12,9 @@ public class Intake { private final CRServoClass belt = new CRServoClass(); public enum Mode { - INTAKE, + INTAKING, SHOOTING, - REVERSE, + REVERSING, OFF } @@ -27,13 +27,13 @@ public void init(OpMode opmode){ } public void setMode(Mode direction){ - if (direction == Mode.INTAKE){ + if (direction == Mode.INTAKING){ intake.setPower(1); belt.setPower(1); }else if (direction == Mode.SHOOTING){ intake.setPower(0); belt.setPower(1); - }else if (direction == Mode.REVERSE){ + }else if (direction == Mode.REVERSING){ intake.setPower(-1); belt.setPower(-1); }else{ @@ -46,11 +46,11 @@ public Mode getMode(){ double intakePower = intake.getPower(); double beltPower = belt.getPower(); if (intakePower == 1 && beltPower == 1){ - return Mode.INTAKE; + return Mode.INTAKING; }else if (intakePower == 0 && beltPower == 1){ return Mode.SHOOTING; }else if (intakePower == -1 && beltPower == -1){ - return Mode.REVERSE; + return Mode.REVERSING; }else{ return Mode.OFF; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 000cc97c205f..2bcd289d9f35 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -16,7 +16,7 @@ public class Turret { public final DcMotorExClass flywheel = new DcMotorExClass(); public final ServoClass hood = new ServoClass(); - Turret_Heading targeting = new Turret_Heading(); + private final Turret_Heading targeting = new Turret_Heading(); public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); @@ -45,4 +45,8 @@ public void updatePIDs(){ public void updateAimbot(Pose robotPose, boolean goal){ rotation.setAngle(targeting.calcLocalizer(robotPose, goal)); } + + public void setFlywheelRPM(double rpm){ + flywheel.setRPM(rpm); + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 229181a49dab..6b9f8af92f75 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -111,11 +111,11 @@ public void runOpMode() { } if (gamepad2.a){ - Robot.intake.setMode(Intake.Mode.INTAKE); + Robot.intake.setMode(Intake.Mode.INTAKING); }else if (gamepad2.b){ Robot.intake.setMode(Intake.Mode.SHOOTING); }else if (gamepad2.x){ - Robot.intake.setMode(Intake.Mode.REVERSE); + Robot.intake.setMode(Intake.Mode.REVERSING); }else{ Robot.intake.setMode(Intake.Mode.OFF); } From 680d9b73e6a2555170affdefb4b4efbee0b27dfa Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 17 Nov 2025 19:22:55 -0500 Subject: [PATCH 068/152] TeleOp controls tweaks --- .../Main_/Hardware_/Actuators_/Intake.java | 2 ++ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 17 +++++++++-------- 2 files changed, 11 insertions(+), 8 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 606b4857d3e8..10ea7fc3a2e9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -24,6 +24,8 @@ public void init(OpMode opmode){ intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); intake.setDirection(DcMotorSimple.Direction.REVERSE); + + belt.setDirection(DcMotorSimple.Direction.REVERSE); } public void setMode(Mode direction){ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 6b9f8af92f75..11c6dcc3a72e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -86,18 +86,19 @@ public void runOpMode() { // run until the end of the match (driver presses STOP) while (opModeIsActive()) { - - if (gamepad1.left_trigger > 0.5){ - Robot.drivetrain.speedMultiplier = 0.2; - }else{ - Robot.drivetrain.speedMultiplier = 1; + Robot.drivetrain.speedMultiplier = 0.75; + if (gamepad1.left_trigger >= 0.5) { + Robot.drivetrain.speedMultiplier -= 0.25; + } + if (gamepad1.right_trigger >= 0.5){ + Robot.drivetrain.speedMultiplier += 0.25; } // Pass the joystick positions to our mecanum drive controller Robot.drivetrain.pedroMecanumDrive( - gamepad1.left_stick_y, - gamepad1.left_stick_x, - gamepad1.right_stick_x/2, + Math.pow(gamepad1.left_stick_y,2), + Math.pow(gamepad1.left_stick_x,2), + Math.pow(gamepad1.right_stick_x/2,2), true ); From 836532b61df0ed157cb0e8c4c7a6d882aa4b8b56 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 18 Nov 2025 19:10:27 -0500 Subject: [PATCH 069/152] Began work on auto path modules --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 85 +++++++++++ .../Drivetrain_/MecanumDrivetrainClass.java | 11 ++ .../Hardware_/Drivetrain_/Pedro_Paths.java | 143 ++++++++++++++++-- .../Main_/Hardware_/LoadHardwareClass.java | 12 ++ 4 files changed, 236 insertions(+), 15 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java new file mode 100644 index 000000000000..d2649e2975c7 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -0,0 +1,85 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Auto_; + +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.skeletonarmy.marrow.prompts.OptionPrompt; +import com.skeletonarmy.marrow.prompts.Prompter; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; + +public class Auto_Main_ extends OpMode { + + // Define other PedroPathing constants + private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. + + private enum Auto { + LOAD_ROBOTICS_A, + LOAD_ROBOTICS_B, + MOE_A, + } + + private int autoState = 0; + + private Auto selectedAuto = null; + + // Create the prompter object for selecting Alliance and Auto + Prompter prompter = null; + + // Create a new instance of our Robot class + LoadHardwareClass Robot = new LoadHardwareClass(this); + + @Override + public void init() { + // Initialize all hardware of the robot + Robot.init(startPose); + + prompter = new Prompter(this); + prompter.prompt("alliance", + new OptionPrompt<>("Select Alliance", + LoadHardwareClass.Alliance.RED, + LoadHardwareClass.Alliance.BLUE + )); + prompter.prompt("auto", + new OptionPrompt<>("Select Auto", + Auto.LOAD_ROBOTICS_A, + Auto.MOE_A, + Auto.LOAD_ROBOTICS_B + )); + prompter.onComplete(() -> { + LoadHardwareClass.selectedAlliance = prompter.get("alliance"); + selectedAuto = prompter.get("auto"); + telemetry.addData("Selection", "Complete"); + } + ); + } + + @Override + public void loop() { + switch (selectedAuto) { + case LOAD_ROBOTICS_A: + return; + case LOAD_ROBOTICS_B: + return; + default: + TEMPLATE_A(); + } + } + + private void waitForPathCompletion(){ + if (Robot.drivetrain.pathComplete()){autoState++;} + } + + private void TEMPLATE_A() { + switch (autoState){ + case 0: + Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); + waitForPathCompletion(); + case 1: + Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); + waitForPathCompletion(); + case 2: + Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); + waitForPathCompletion(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index 0e15affd4ccc..db11561f235d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -4,6 +4,7 @@ import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @@ -14,6 +15,7 @@ public class MecanumDrivetrainClass { // Misc Constants public Follower follower = null; + public Pedro_Paths paths = null; /** * Initializes the PedroPathing follower. @@ -24,6 +26,7 @@ public class MecanumDrivetrainClass { public void init (@NonNull OpMode myOpMode, Pose initialPose){ // PedroPathing initialization follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower + paths = new Pedro_Paths(follower); follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field follower.update(); // Applies the initialization @@ -54,4 +57,12 @@ public void pedroMecanumDrive(double forward, double strafe, double rotate, bool robotCentric); follower.update(); } + + public void runPath(PathChain path, boolean holdEndpoint){ + follower.followPath(path, holdEndpoint); + } + + public boolean pathComplete(){ + return !follower.isBusy(); + } } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index de15b2f716a1..e2c328a687be 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -2,31 +2,144 @@ import com.pedropathing.follower.Follower; import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; import com.pedropathing.geometry.Pose; import com.pedropathing.paths.PathChain; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; + public class Pedro_Paths { // The variable to store PedroPathing's follower object for path building - private Follower follower; + public Follower follower; + + /** + * Define primary poses to be used in paths + */ + // Start Poses + public Pose startPose1 = new Pose(112, 136.6, Math.toRadians(270)); + public Pose startPose2 = new Pose(88, 7.4, Math.toRadians(90)); + + // Define all path variables + public PathChain startPose1_to_preload1, startPose1_to_preload2, startPose1_to_preload3; + public PathChain startPose2_to_preload1, startPose2_to_preload2, startPose2_to_preload3; + + public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ + int mult = 1; + if (alliance == LoadHardwareClass.Alliance.BLUE){ + mult = -1; + } + return new Pose( + 144 - pose.getX(), + 144 - pose.getY(), + Math.atan2(Math.sin(pose.getHeading()), mult * Math.cos(pose.getHeading())) + ); + } + + /** + * Builds all the paths, mirroring them to the other side of the field if necessary + */ + public void buildPaths(LoadHardwareClass.Alliance alliance){ + // All paths are for the RED side of the field. they will be mirrored if necessary. + + // Start Pose 1 to Preloads + startPose1_to_preload3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose1, alliance), + autoMirror(new Pose(89.000, 136.600), alliance), + autoMirror(new Pose(89.000, 30.000), alliance), + autoMirror(new Pose(95.000, 35.500), alliance), + autoMirror(new Pose(110.000, 35.500), alliance) + )) + .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .addPath(new BezierLine( + autoMirror(new Pose(110.000, 35.500), alliance), + autoMirror(new Pose(132.000, 35.500), alliance) + )) + .setTangentHeadingInterpolation() + .build(); + startPose1_to_preload2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose1, alliance), + autoMirror(new Pose(89.000, 136.600), alliance), + autoMirror(new Pose(89.000, 54.000), alliance), + autoMirror(new Pose(95.000, 59.500), alliance), + autoMirror(new Pose(110.000, 59.500), alliance) + )) + .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .addPath(new BezierLine( + autoMirror(new Pose(110.000, 59.500), alliance), + autoMirror(new Pose(132.000, 59.500), alliance) + )) + .setTangentHeadingInterpolation() + .build(); + startPose1_to_preload1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose1, alliance), + autoMirror(new Pose(89.000, 136.600), alliance), + autoMirror(new Pose(89.000, 78.000), alliance), + autoMirror(new Pose(95.000, 83.500), alliance), + autoMirror(new Pose(110.000, 83.500), alliance) + )) + .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .addPath(new BezierLine( + autoMirror(new Pose(110.000, 83.500), alliance), + autoMirror(new Pose(132.000, 83.500), alliance) + )) + .setTangentHeadingInterpolation() + .build(); + + // Start Pose 2 to Preloads + startPose2_to_preload3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose2, alliance), + autoMirror(new Pose(89.000, 136.600), alliance), + autoMirror(new Pose(89.000, 41.000), alliance), + autoMirror(new Pose(95.000, 35.500), alliance), + autoMirror(new Pose(110.000, 35.500), alliance) + )) + .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) + .addPath(new BezierLine( + autoMirror(new Pose(110.000, 35.500), alliance), + autoMirror(new Pose(132.000, 35.500), alliance) + )) + .setTangentHeadingInterpolation() + .build(); + startPose2_to_preload2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose2, alliance), + autoMirror(new Pose(89.000, 136.600), alliance), + autoMirror(new Pose(89.000, 65.000), alliance), + autoMirror(new Pose(95.000, 59.500), alliance), + autoMirror(new Pose(110.000, 59.500), alliance) + )) + .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .addPath(new BezierLine( + autoMirror(new Pose(110.000, 59.500), alliance), + autoMirror(new Pose(132.000, 59.500), alliance) + )) + .setTangentHeadingInterpolation() + .build(); + startPose2_to_preload1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose2, alliance), + autoMirror(new Pose(89.000, 89.000), alliance), + autoMirror(new Pose(95.000, 83.500), alliance), + autoMirror(new Pose(110.000, 83.500), alliance) + )) + .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) + .addPath(new BezierLine( + autoMirror(new Pose(110.000, 83.500), alliance), + autoMirror(new Pose(132.000, 83.500), alliance) + )) + .setTangentHeadingInterpolation() + .build(); + } /** * Must be called after MecanumDrivetrainClass is initialized. * @param follow PedroPathing's follower object, gotten from MecanumDrivetrainClass */ - public void init(Follower follow){ + public Pedro_Paths(Follower follow){ follower = follow; } - - // Define primary poses to be used in paths - public final Pose startPose1 = new Pose(87, 8.8, Math.toRadians(90)); - public final Pose scorePose1 = new Pose(86, 22, Math.toRadians(80)); - - // Define paths to be used by PedroPathing - public final PathChain gotoScorePose1 = follower.pathBuilder() - .addPath(new BezierCurve( - follower.getPose(), - scorePose1 - )) - .setLinearHeadingInterpolation(follower.getPose().getHeading(), scorePose1.getHeading()) - .build(); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index 6765b1c7788c..be7c72f5b115 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -59,6 +59,18 @@ public enum Alliance { BLUE } + /** + * Copied from LinearOpMode. + * @param milliseconds The number of milliseconds to sleep. + */ + public final void sleep(long milliseconds) { + try { + Thread.sleep(milliseconds); + } catch (InterruptedException e) { + Thread.currentThread().interrupt(); + } + } + /** * Constructor that allows the OpMode to pass a reference to itself. * @param opmode The input for this parameter should almost always be "this". From e49fc51cbaf35f9825c3ea291df13f803c77a0a1 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Thu, 20 Nov 2025 13:18:50 -0500 Subject: [PATCH 070/152] Began adding new set of auto path modules: preloadX_to_shootingX --- .../Hardware_/Drivetrain_/Pedro_Paths.java | 65 ++++++++++++------- 1 file changed, 40 insertions(+), 25 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index e2c328a687be..cba4e3ba7dd8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -18,10 +18,15 @@ public class Pedro_Paths { // Start Poses public Pose startPose1 = new Pose(112, 136.6, Math.toRadians(270)); public Pose startPose2 = new Pose(88, 7.4, Math.toRadians(90)); + // Shooting Poses + public Pose shootingPose3 = new Pose(85, 15, Math.toRadians(60)); // Define all path variables public PathChain startPose1_to_preload1, startPose1_to_preload2, startPose1_to_preload3; public PathChain startPose2_to_preload1, startPose2_to_preload2, startPose2_to_preload3; + public PathChain preload1_to_shooting1, preload1_to_shooting2, preload1_to_shooting3; + public PathChain preload2_to_shooting1, preload2_to_shooting2, preload2_to_shooting3; + public PathChain preload3_to_shooting1, preload3_to_shooting2, preload3_to_shooting3; public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ int mult = 1; @@ -42,18 +47,18 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ // All paths are for the RED side of the field. they will be mirrored if necessary. // Start Pose 1 to Preloads - startPose1_to_preload3 = follower.pathBuilder() + startPose1_to_preload1 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(startPose1, alliance), autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 30.000), alliance), - autoMirror(new Pose(95.000, 35.500), alliance), - autoMirror(new Pose(110.000, 35.500), alliance) + autoMirror(new Pose(89.000, 78.000), alliance), + autoMirror(new Pose(95.000, 83.500), alliance), + autoMirror(new Pose(110.000, 83.500), alliance) )) .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(new Pose(132.000, 35.500), alliance) + autoMirror(new Pose(110.000, 83.500), alliance), + autoMirror(new Pose(132.000, 83.500), alliance) )) .setTangentHeadingInterpolation() .build(); @@ -72,35 +77,34 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ )) .setTangentHeadingInterpolation() .build(); - startPose1_to_preload1 = follower.pathBuilder() + startPose1_to_preload3 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(startPose1, alliance), autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 78.000), alliance), - autoMirror(new Pose(95.000, 83.500), alliance), - autoMirror(new Pose(110.000, 83.500), alliance) + autoMirror(new Pose(89.000, 30.000), alliance), + autoMirror(new Pose(95.000, 35.500), alliance), + autoMirror(new Pose(110.000, 35.500), alliance) )) .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(new Pose(132.000, 83.500), alliance) + autoMirror(new Pose(110.000, 35.500), alliance), + autoMirror(new Pose(132.000, 35.500), alliance) )) .setTangentHeadingInterpolation() .build(); // Start Pose 2 to Preloads - startPose2_to_preload3 = follower.pathBuilder() + startPose2_to_preload1 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(startPose2, alliance), - autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 41.000), alliance), - autoMirror(new Pose(95.000, 35.500), alliance), - autoMirror(new Pose(110.000, 35.500), alliance) + autoMirror(new Pose(89.000, 89.000), alliance), + autoMirror(new Pose(95.000, 83.500), alliance), + autoMirror(new Pose(110.000, 83.500), alliance) )) .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(new Pose(132.000, 35.500), alliance) + autoMirror(new Pose(110.000, 83.500), alliance), + autoMirror(new Pose(132.000, 83.500), alliance) )) .setTangentHeadingInterpolation() .build(); @@ -119,20 +123,31 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ )) .setTangentHeadingInterpolation() .build(); - startPose2_to_preload1 = follower.pathBuilder() + startPose2_to_preload3 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(startPose2, alliance), - autoMirror(new Pose(89.000, 89.000), alliance), - autoMirror(new Pose(95.000, 83.500), alliance), - autoMirror(new Pose(110.000, 83.500), alliance) + autoMirror(new Pose(89.000, 136.600), alliance), + autoMirror(new Pose(89.000, 41.000), alliance), + autoMirror(new Pose(95.000, 35.500), alliance), + autoMirror(new Pose(110.000, 35.500), alliance) )) .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(new Pose(132.000, 83.500), alliance) + autoMirror(new Pose(110.000, 35.500), alliance), + autoMirror(new Pose(132.000, 35.500), alliance) )) .setTangentHeadingInterpolation() .build(); + + // Preload 1 to Shooting Pose 3 + preload1_to_shooting3 = follower.pathBuilder() + .addPath(new BezierCurve( + new Pose(132.000, 59.500), + new Pose(90.000, 59.500), + shootingPose3 + )) + .setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(60)) + .build(); } /** From f8cf741073a265c2b0925eb4bf34269471ef37d3 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Fri, 21 Nov 2025 17:31:58 -0500 Subject: [PATCH 071/152] Added gate servo controls --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 6 ++++ .../Main_/Hardware_/Actuators_/Turret.java | 19 ++++++++++++ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 30 ++++++++++++++----- 3 files changed, 48 insertions(+), 7 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index d2649e2975c7..49e7effd75b2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -65,10 +65,16 @@ public void loop() { } } + /** + * Waits for the current stage of the auto to be done and then runs the next stage. + */ private void waitForPathCompletion(){ if (Robot.drivetrain.pathComplete()){autoState++;} } + /** + * Template auto + */ private void TEMPLATE_A() { switch (autoState){ case 0: diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 2bcd289d9f35..cb397b075a24 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -8,6 +8,8 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.ServoClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_.Turret_Heading; +import java.util.Optional; + import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; @@ -15,6 +17,7 @@ public class Turret { public final DcMotorExClass rotation = new DcMotorExClass(); public final DcMotorExClass flywheel = new DcMotorExClass(); public final ServoClass hood = new ServoClass(); + public final ServoClass gate = new ServoClass(); private final Turret_Heading targeting = new Turret_Heading(); @@ -22,13 +25,21 @@ public class Turret { public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); public static BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); + public enum gatestate { + OPEN, + CLOSED, + } + public void init(OpMode opmode){ rotation.init(opmode, "turret", 103.8); flywheel.init(opmode, "flywheel"); hood.init(opmode, "hood"); + gate.init(opmode, "gate"); rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); + gate.setAngle(0.5); + // Pass PID pidCoefficients to motor classes rotation.setPidCoefficients(turretCoefficients); flywheel.setPidCoefficients(flywheelCoefficients); @@ -46,6 +57,14 @@ public void updateAimbot(Pose robotPose, boolean goal){ rotation.setAngle(targeting.calcLocalizer(robotPose, goal)); } + public void setGate(gatestate state){ + if (state == gatestate.OPEN){ + gate.setAngle(0.5); + }else if (state == gatestate.CLOSED){ + gate.setAngle(0.25); + } + } + public void setFlywheelRPM(double rpm){ flywheel.setRPM(rpm); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 11c6dcc3a72e..69c72f279f10 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -29,6 +29,8 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; +import com.bylazar.configurables.annotations.Configurable; +import com.pedropathing.Drivetrain; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; @@ -37,16 +39,19 @@ import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; //TODO, implement all our external libraries and functionality. - +@Configurable @TeleOp(name="Teleop_Main_", group="TeleOp") public class Teleop_Main_ extends LinearOpMode { // Declare OpMode members. private ElapsedTime runtime = new ElapsedTime(); + public static double driveExponent = 2; + Prompter prompter = null; // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. @@ -86,19 +91,23 @@ public void runOpMode() { // run until the end of the match (driver presses STOP) while (opModeIsActive()) { - Robot.drivetrain.speedMultiplier = 0.75; + Robot.drivetrain.speedMultiplier = 0.66; if (gamepad1.left_trigger >= 0.5) { - Robot.drivetrain.speedMultiplier -= 0.25; + Robot.drivetrain.speedMultiplier -= 0.33; } if (gamepad1.right_trigger >= 0.5){ - Robot.drivetrain.speedMultiplier += 0.25; + Robot.drivetrain.speedMultiplier += 0.33; } // Pass the joystick positions to our mecanum drive controller + double turnMult = 2; + if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ + turnMult = 1; + } Robot.drivetrain.pedroMecanumDrive( - Math.pow(gamepad1.left_stick_y,2), - Math.pow(gamepad1.left_stick_x,2), - Math.pow(gamepad1.right_stick_x/2,2), + gamepad1.left_stick_y, + gamepad1.left_stick_x, + gamepad1.right_stick_x/turnMult, true ); @@ -121,8 +130,15 @@ public void runOpMode() { Robot.intake.setMode(Intake.Mode.OFF); } + if (gamepad2.b){ + Robot.turret.setGate(Turret.gatestate.OPEN); + }else{ + Robot.turret.setGate(Turret.gatestate.CLOSED); + } + Robot.turret.updatePIDs(); + telemetry.addData("SpeedMult", Robot.drivetrain.speedMultiplier); // Turret-related Telemetry telemetry.addData("Turret Target Angle:", Robot.turret.rotation.target); telemetry.addData("Turret Actual Angle", Robot.turret.rotation.getAngleAbsolute()); From e4563720edf2f870e7255f0331d2a3727083ac91 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 24 Nov 2025 16:51:35 -0500 Subject: [PATCH 072/152] Added some more auto paths --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 11 +- .../Main_/Hardware_/Actuators_/Turret.java | 8 +- .../Hardware_/Drivetrain_/Pedro_Paths.java | 120 +++++++++++++++--- 3 files changed, 115 insertions(+), 24 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 49e7effd75b2..2dd014ecef9a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -1,5 +1,7 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Auto_; +import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; + import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.skeletonarmy.marrow.prompts.OptionPrompt; @@ -46,7 +48,7 @@ public void init() { Auto.LOAD_ROBOTICS_B )); prompter.onComplete(() -> { - LoadHardwareClass.selectedAlliance = prompter.get("alliance"); + selectedAlliance = prompter.get("alliance"); selectedAuto = prompter.get("auto"); telemetry.addData("Selection", "Complete"); } @@ -63,6 +65,13 @@ public void loop() { default: TEMPLATE_A(); } + switch (selectedAlliance) { + case RED: + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); + return; + case BLUE: + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); + } } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index cb397b075a24..8626e2fa2d47 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -53,8 +53,12 @@ public void updatePIDs(){ flywheel.setFFCoefficients(ffCoefficients); } - public void updateAimbot(Pose robotPose, boolean goal){ - rotation.setAngle(targeting.calcLocalizer(robotPose, goal)); + /** + * @param robotPose The pose of the robot, gotten from PedroPathing's localization + * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. + */ + public void updateAimbot(Pose robotPose, boolean targetRedGoal){ + rotation.setAngle(targeting.calcLocalizer(robotPose, targetRedGoal)); } public void setGate(gatestate state){ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index cba4e3ba7dd8..bd05480b4274 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -18,7 +18,13 @@ public class Pedro_Paths { // Start Poses public Pose startPose1 = new Pose(112, 136.6, Math.toRadians(270)); public Pose startPose2 = new Pose(88, 7.4, Math.toRadians(90)); + // Preload Poses + public Pose preloadPose1 = new Pose(130.000, 83.500, Math.toRadians(90)); + public Pose preloadPose2 = new Pose(132.000, 59.500, Math.toRadians(90)); + public Pose preloadPose3 = new Pose(132.000, 35.500, Math.toRadians(90)); // Shooting Poses + public Pose shootingPose1 = new Pose(115, 120, Math.toRadians(-35)); + public Pose shootingPose2 = new Pose(85, 85, Math.toRadians(-15)); public Pose shootingPose3 = new Pose(85, 15, Math.toRadians(60)); // Define all path variables @@ -40,13 +46,7 @@ public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ ); } - /** - * Builds all the paths, mirroring them to the other side of the field if necessary - */ - public void buildPaths(LoadHardwareClass.Alliance alliance){ - // All paths are for the RED side of the field. they will be mirrored if necessary. - - // Start Pose 1 to Preloads + public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { startPose1_to_preload1 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(startPose1, alliance), @@ -58,7 +58,7 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(new Pose(132.000, 83.500), alliance) + autoMirror(preloadPose1, alliance) )) .setTangentHeadingInterpolation() .build(); @@ -73,7 +73,7 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 59.500), alliance), - autoMirror(new Pose(132.000, 59.500), alliance) + autoMirror(preloadPose2, alliance) )) .setTangentHeadingInterpolation() .build(); @@ -88,12 +88,12 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(new Pose(132.000, 35.500), alliance) + autoMirror(preloadPose3, alliance) )) .setTangentHeadingInterpolation() .build(); - - // Start Pose 2 to Preloads + } + public void buildStart2ToPreloads(LoadHardwareClass.Alliance alliance){ startPose2_to_preload1 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(startPose2, alliance), @@ -104,7 +104,7 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(new Pose(132.000, 83.500), alliance) + autoMirror(preloadPose1, alliance) )) .setTangentHeadingInterpolation() .build(); @@ -119,7 +119,7 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 59.500), alliance), - autoMirror(new Pose(132.000, 59.500), alliance) + autoMirror(preloadPose2, alliance) )) .setTangentHeadingInterpolation() .build(); @@ -134,20 +134,98 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(new Pose(132.000, 35.500), alliance) + autoMirror(preloadPose3, alliance) )) .setTangentHeadingInterpolation() .build(); - - // Preload 1 to Shooting Pose 3 + } + public void buildPreload1ToShootings(LoadHardwareClass.Alliance alliance){ + preload1_to_shooting1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose1, alliance), + autoMirror(shootingPose1, alliance) + )) + .setLinearHeadingInterpolation(preloadPose1.getHeading(), shootingPose1.getHeading()) + .build(); + preload1_to_shooting2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose1, alliance), + autoMirror(shootingPose2, alliance) + )) + .setLinearHeadingInterpolation(preloadPose1.getHeading(), shootingPose2.getHeading()) + .build(); + preload1_to_shooting3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose1, alliance), + autoMirror(new Pose(80.000, 83.500), alliance), + autoMirror(shootingPose3, alliance) + )) + .setLinearHeadingInterpolation(preloadPose1.getHeading(), shootingPose3.getHeading()) + .build(); + } + public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ + preload1_to_shooting1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose2, alliance), + autoMirror(new Pose(65,59.5), alliance), + autoMirror(shootingPose1, alliance) + )) + .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose1.getHeading()) + .build(); + preload1_to_shooting2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose2, alliance), + autoMirror(new Pose(65,59.5), alliance), + autoMirror(shootingPose2, alliance) + )) + .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose2.getHeading()) + .build(); preload1_to_shooting3 = follower.pathBuilder() .addPath(new BezierCurve( - new Pose(132.000, 59.500), - new Pose(90.000, 59.500), - shootingPose3 + autoMirror(preloadPose2, alliance), + autoMirror(new Pose(90.000, 59.500), alliance), + autoMirror(shootingPose3, alliance) + )) + .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose3.getHeading()) + .build(); + } + public void buildPreload3ToShootings(LoadHardwareClass.Alliance alliance){ + preload1_to_shooting1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose2, alliance), + autoMirror(new Pose(65,59.5), alliance), + autoMirror(shootingPose1, alliance) + )) + .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose1.getHeading()) + .build(); + preload1_to_shooting2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose2, alliance), + autoMirror(new Pose(65,59.5), alliance), + autoMirror(shootingPose2, alliance) )) - .setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(60)) + .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose2.getHeading()) .build(); + preload1_to_shooting3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(preloadPose2, alliance), + autoMirror(new Pose(90.000, 59.500), alliance), + autoMirror(shootingPose3, alliance) + )) + .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose3.getHeading()) + .build(); + } + + /** + * Builds all the paths, mirroring them to the other side of the field if necessary + */ + public void buildPaths(LoadHardwareClass.Alliance alliance){ + // All paths are for the RED side of the field. they will be mirrored if necessary. + + buildStart1ToPreloads(alliance); + buildStart2ToPreloads(alliance); + buildPreload1ToShootings(alliance); + buildPreload2ToShootings(alliance); } /** From 5af15608c88c0f0f04096f5e6ba933ab21857cd0 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 24 Nov 2025 16:52:37 -0500 Subject: [PATCH 073/152] Added some TODOs --- .../ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 69c72f279f10..089a4e98c05c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -43,6 +43,10 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; //TODO, implement all our external libraries and functionality. + +//TODO, add 2 generic autos for preloads and shooting and stuff + +//TODO, Implement controls graph @Configurable @TeleOp(name="Teleop_Main_", group="TeleOp") public class Teleop_Main_ extends LinearOpMode { From 5c56fe5395092f35a5087b8de76c69056bec43b5 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 24 Nov 2025 17:22:34 -0500 Subject: [PATCH 074/152] Moved all our TODOs into a separate notes file. I also consolidated all our actuator classes into a single "Devices" file. --- .../Main_/Hardware_/Actuators_/Devices.java | 231 ++++++++++++++++++ .../Actuators_/Generic_/CRServoClass.java | 36 --- .../Actuators_/Generic_/DcMotorExClass.java | 167 ------------- .../Actuators_/Generic_/ServoClass.java | 37 --- .../Main_/Hardware_/Actuators_/Intake.java | 6 +- .../Main_/Hardware_/Actuators_/Turret.java | 12 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 4 - .../ftc/teamcode/LOADCode/Notes and TODOs | 7 + 8 files changed, 244 insertions(+), 256 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java new file mode 100644 index 000000000000..0b096ee689c1 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -0,0 +1,231 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; + +import androidx.annotation.NonNull; + +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.CRServo; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.Servo; + +import dev.nextftc.control.ControlSystem; +import dev.nextftc.control.KineticState; +import dev.nextftc.control.feedback.PIDCoefficients; +import dev.nextftc.control.feedforward.BasicFeedforwardParameters; + +public class Devices { + + public static class CRServoClass { + private CRServo servo; + + public void init(@NonNull OpMode opmode, String servoName) { + servo = opmode.hardwareMap.get(CRServo.class, servoName); + } + + /** + * @param power The power to set the servo to. Must be a value between -1 and 1. + */ + public void setPower(double power) { + servo.setPower(power); + } + + /** + * @param direction The direction to set the servo to. + */ + public void setDirection(DcMotorSimple.Direction direction) { + servo.setDirection(direction); + } + + /** + * @return The power the servo has been set to. + */ + public double getPower() { + return servo.getPower(); + } + } + + public static class DcMotorExClass { + // PID pidCoefficients + PIDCoefficients pidCoefficients = new PIDCoefficients(0, 0, 0); + BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); + // Encoder ticks/rotation + // 1620rpm Gobilda - 103.8 ticks at the motor shaft + public double ticksPerRotation = 103.8; + // Target position/velocity of the motor + public double target = 0; + // Motor object + private DcMotorEx motorObject = null; + + /** + * Initializes the motor hardware + * @param opmode Allows this class to access the robot hardware objects. + * @param motorName The name of the motor in the robot's configuration. + * @param encoderResolution The resolution of the motor's encoder in ticks/rotation. + */ + public void init (@NonNull OpMode opmode, String motorName, double encoderResolution){ + // Initialize the motor object + motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); + ticksPerRotation = encoderResolution; + } + /** + * Initializes the motor hardware. + * The resolution of the motor encoder will default to + * 103.8 ticks/rotation, the value for a 1620RPM Gobilda motor. + * @param opmode Allows this class to access the robot hardware objects. + * @param motorName The name of the motor in the robot's configuration. + */ + public void init (@NonNull OpMode opmode, String motorName){ + // Initialize the motor object + motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); + } + + /** + * Sets the value of the PID coefficients of the motor. + * @param coefficients The values to set the coefficients to. + */ + public void setPidCoefficients(PIDCoefficients coefficients) { + pidCoefficients = coefficients; + } + /** + * Sets the value of the FeedForward coefficients of the motor. + * @param coefficients The values to set the coefficients to. + */ + public void setFFCoefficients(BasicFeedforwardParameters coefficients) { + ffCoefficients = coefficients; + } + /** + * Resets the internal encoder of the motor to zero. + */ + public void resetEncoder(){ + motorObject.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); + motorObject.setMode(DcMotor.RunMode.RUN_USING_ENCODER); + } + /** + * Sets the runMode of the motor. + * @param runMode The mode to set the motor to. + */ + public void setRunMode(DcMotor.RunMode runMode){ + motorObject.setMode(runMode); + } + /** + * Sets the zeroPowerBehaviour of the motor. + * @param behaviour The behaviour to apply to the motor. + */ + public void setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior behaviour){ + motorObject.setZeroPowerBehavior(behaviour); + } + /** + * @param direction The direction to set the motor to. + */ + public void setDirection(DcMotorSimple.Direction direction){ + motorObject.setDirection(direction); + } + /** + * @return The current position of the turret motor in encoder ticks. Can be any value. + */ + public double getEncoderTicks(){ + return motorObject.getCurrentPosition(); + } + /** + * @param power A value between -1 and 1 that the turret motor's power will be set to. + */ + public void setPower(double power){ + motorObject.setPower(power); + } + /** + * @return The angle of the turret in degrees. Can be any value. + */ + public double getAngleAbsolute(){ + return (getEncoderTicks()/ticksPerRotation*360); + } + /** + * @return The angle of the turret in degrees. Can be any value between 0 and 360. + */ + public double getAngle(){ + return getAngleAbsolute()%360; + } + /** + * @return The velocity of the turret in encoder ticks/second. + */ + public double getVelocity(){ + return motorObject.getVelocity(); + } + /** + * @return The velocity of the turret in degrees/second. + */ + public double getDegreesPerSecond(){ + return (getVelocity()/ticksPerRotation)*360; + } + /** + * @return The velocity of the turret in RPM. + */ + public double getRPM(){ + return (getVelocity()/ticksPerRotation)*60; + } + /** + * @return The power that the turret motor has been set to. + */ + public double getPower(){ + return motorObject.getPower(); + } + /** + * Uses a PID controller to move the motor to the desired position. + * Must be called every loop to function properly. + * @param angle The angle in degrees to move the motor to. Can be any number. + */ + public void setAngle(double angle){ + target = angle; + ControlSystem turretPID = ControlSystem.builder().posPid(pidCoefficients).build(); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); + turretPID.setGoal(new KineticState(target)); + setPower(turretPID.calculate(currentKineticState)); + } + /** + * Uses a PID controller to accelerate the motor to the desired RPM + * Must be called every loop to function properly. + * @param rpm The RPM to accelerate the motor to. Can be any number + */ + public void setRPM(double rpm){ + target = rpm; + double degreesPerSecond = target*6; + ControlSystem PID = ControlSystem.builder() + .velPid(pidCoefficients) + .basicFF(ffCoefficients) + .build(); + KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); + PID.setGoal(new KineticState(0, degreesPerSecond)); + setPower(PID.calculate(currentKineticState)); + } + } + + public static class ServoClass { + private Servo servo; + + public void init(@NonNull OpMode opmode, String servoName){ + servo = opmode.hardwareMap.get(Servo.class, servoName); + } + + /** + * @param angle The angle to set the servo to. Must be a value between 0 and 1, + * representing the endpoints of it's movement. + */ + public void setAngle(double angle){ + servo.setPosition(angle); + } + + /** + * @param direction The direction to set the servo to. + */ + public void setDirection(Servo.Direction direction){ + servo.setDirection(direction); + } + + /** + * @return A value between 0 and 1 that the servo has been set to. + */ + public double getAngle(){ + return servo.getPosition(); + } + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java deleted file mode 100644 index 8580b1521929..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/CRServoClass.java +++ /dev/null @@ -1,36 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_; - -import androidx.annotation.NonNull; - -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.hardware.CRServo; -import com.qualcomm.robotcore.hardware.DcMotorSimple; - -public class CRServoClass{ - private CRServo servo; - - public void init(@NonNull OpMode opmode, String servoName){ - servo = opmode.hardwareMap.get(CRServo.class, servoName); - } - - /** - * @param power The power to set the servo to. Must be a value between -1 and 1. - */ - public void setPower(double power){ - servo.setPower(power); - } - - /** - * @param direction The direction to set the servo to. - */ - public void setDirection(DcMotorSimple.Direction direction){ - servo.setDirection(direction); - } - - /** - * @return The power the servo has been set to. - */ - public double getPower(){ - return servo.getPower(); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java deleted file mode 100644 index b8ee4836ce7c..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/DcMotorExClass.java +++ /dev/null @@ -1,167 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_; - -import androidx.annotation.NonNull; - -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.hardware.DcMotor; -import com.qualcomm.robotcore.hardware.DcMotorEx; -import com.qualcomm.robotcore.hardware.DcMotorSimple; - -import dev.nextftc.control.ControlSystem; -import dev.nextftc.control.KineticState; -import dev.nextftc.control.feedback.PIDCoefficients; -import dev.nextftc.control.feedforward.BasicFeedforwardParameters; - -public class DcMotorExClass { - // PID pidCoefficients - PIDCoefficients pidCoefficients = new PIDCoefficients(0, 0, 0); - BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); - // Encoder ticks/rotation - // 1620rpm Gobilda - 103.8 ticks at the motor shaft - public double ticksPerRotation = 103.8; - // Target position/velocity of the motor - public double target = 0; - // Motor object - private DcMotorEx motorObject = null; - - /** - * Initializes the motor hardware - * @param opmode Allows this class to access the robot hardware objects. - * @param motorName The name of the motor in the robot's configuration. - * @param encoderResolution The resolution of the motor's encoder in ticks/rotation. - */ - public void init (@NonNull OpMode opmode, String motorName, double encoderResolution){ - // Initialize the motor object - motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); - ticksPerRotation = encoderResolution; - } - /** - * Initializes the motor hardware. - * The resolution of the motor encoder will default to - * 103.8 ticks/rotation, the value for a 1620RPM Gobilda motor. - * @param opmode Allows this class to access the robot hardware objects. - * @param motorName The name of the motor in the robot's configuration. - */ - public void init (@NonNull OpMode opmode, String motorName){ - // Initialize the motor object - motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); - } - - /** - * Sets the value of the PID coefficients of the motor. - * @param coefficients The values to set the coefficients to. - */ - public void setPidCoefficients(PIDCoefficients coefficients) { - pidCoefficients = coefficients; - } - /** - * Sets the value of the FeedForward coefficients of the motor. - * @param coefficients The values to set the coefficients to. - */ - public void setFFCoefficients(BasicFeedforwardParameters coefficients) { - ffCoefficients = coefficients; - } - /** - * Resets the internal encoder of the motor to zero. - */ - public void resetEncoder(){ - motorObject.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); - motorObject.setMode(DcMotor.RunMode.RUN_USING_ENCODER); - } - /** - * Sets the runMode of the motor. - * @param runMode The mode to set the motor to. - */ - public void setRunMode(DcMotor.RunMode runMode){ - motorObject.setMode(runMode); - } - /** - * Sets the zeroPowerBehaviour of the motor. - * @param behaviour The behaviour to apply to the motor. - */ - public void setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior behaviour){ - motorObject.setZeroPowerBehavior(behaviour); - } - /** - * @param direction The direction to set the motor to. - */ - public void setDirection(DcMotorSimple.Direction direction){ - motorObject.setDirection(direction); - } - /** - * @return The current position of the turret motor in encoder ticks. Can be any value. - */ - public double getEncoderTicks(){ - return motorObject.getCurrentPosition(); - } - /** - * @param power A value between -1 and 1 that the turret motor's power will be set to. - */ - public void setPower(double power){ - motorObject.setPower(power); - } - /** - * @return The angle of the turret in degrees. Can be any value. - */ - public double getAngleAbsolute(){ - return (getEncoderTicks()/ticksPerRotation*360); - } - /** - * @return The angle of the turret in degrees. Can be any value between 0 and 360. - */ - public double getAngle(){ - return getAngleAbsolute()%360; - } - /** - * @return The velocity of the turret in encoder ticks/second. - */ - public double getVelocity(){ - return motorObject.getVelocity(); - } - /** - * @return The velocity of the turret in degrees/second. - */ - public double getDegreesPerSecond(){ - return (getVelocity()/ticksPerRotation)*360; - } - /** - * @return The velocity of the turret in RPM. - */ - public double getRPM(){ - return (getVelocity()/ticksPerRotation)*60; - } - /** - * @return The power that the turret motor has been set to. - */ - public double getPower(){ - return motorObject.getPower(); - } - /** - * Uses a PID controller to move the motor to the desired position. - * Must be called every loop to function properly. - * @param angle The angle in degrees to move the motor to. Can be any number. - */ - public void setAngle(double angle){ - target = angle; - ControlSystem turretPID = ControlSystem.builder().posPid(pidCoefficients).build(); - KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); - turretPID.setGoal(new KineticState(target)); - setPower(turretPID.calculate(currentKineticState)); - } - /** - * Uses a PID controller to accelerate the motor to the desired RPM - * Must be called every loop to function properly. - * @param rpm The RPM to accelerate the motor to. Can be any number - */ - public void setRPM(double rpm){ - target = rpm; - double degreesPerSecond = target*6; - ControlSystem PID = ControlSystem.builder() - .velPid(pidCoefficients) - .basicFF(ffCoefficients) - .build(); - KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); - PID.setGoal(new KineticState(0, degreesPerSecond)); - setPower(PID.calculate(currentKineticState)); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java deleted file mode 100644 index ac65228e8b7f..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Generic_/ServoClass.java +++ /dev/null @@ -1,37 +0,0 @@ -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_; - -import androidx.annotation.NonNull; - -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.qualcomm.robotcore.hardware.Servo; - -public class ServoClass { - private Servo servo; - - public void init(@NonNull OpMode opmode, String servoName){ - servo = opmode.hardwareMap.get(Servo.class, servoName); - } - - /** - * @param angle The angle to set the servo to. Must be a value between 0 and 1, - * representing the endpoints of it's movement. - */ - public void setAngle(double angle){ - servo.setPosition(angle); - } - - /** - * @param direction The direction to set the servo to. - */ - public void setDirection(Servo.Direction direction){ - servo.setDirection(direction); - } - - /** - * @return A value between 0 and 1 that the servo has been set to. - */ - public double getAngle(){ - return servo.getPosition(); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 10ea7fc3a2e9..b87a167d7f62 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -4,12 +4,10 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.CRServoClass; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; public class Intake { - private final DcMotorExClass intake = new DcMotorExClass(); - private final CRServoClass belt = new CRServoClass(); + private final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); + private final Devices.CRServoClass belt = new Devices.CRServoClass(); public enum Mode { INTAKING, diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 8626e2fa2d47..dd8984df83e2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -4,20 +4,16 @@ import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotor; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.DcMotorExClass; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Generic_.ServoClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_.Turret_Heading; -import java.util.Optional; - import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; public class Turret { - public final DcMotorExClass rotation = new DcMotorExClass(); - public final DcMotorExClass flywheel = new DcMotorExClass(); - public final ServoClass hood = new ServoClass(); - public final ServoClass gate = new ServoClass(); + public final Devices.DcMotorExClass rotation = new Devices.DcMotorExClass(); + public final Devices.DcMotorExClass flywheel = new Devices.DcMotorExClass(); + public final Devices.ServoClass hood = new Devices.ServoClass(); + public final Devices.ServoClass gate = new Devices.ServoClass(); private final Turret_Heading targeting = new Turret_Heading(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 089a4e98c05c..877aa4ccd4b0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -42,11 +42,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; -//TODO, implement all our external libraries and functionality. -//TODO, add 2 generic autos for preloads and shooting and stuff - -//TODO, Implement controls graph @Configurable @TeleOp(name="Teleop_Main_", group="TeleOp") public class Teleop_Main_ extends LinearOpMode { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs new file mode 100644 index 000000000000..077c8e066c19 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -0,0 +1,7 @@ +//TODO, implement all our external libraries and functionality. + +//TODO, add 2 generic autos for preloads and shooting and stuff + +//TODO, Implement controls graph + +//DONE, Consolidate the generic actuator functionalities folder into one file \ No newline at end of file From 79165b47d5f97688eebe1a880cc3bdaffe796f2a Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 24 Nov 2025 17:38:49 -0500 Subject: [PATCH 075/152] Deleted the turret heading calculation class and added it's functionality to the turret hardware class. --- .../Main_/Hardware_/Actuators_/Turret.java | 19 ++++-- .../Calculation_/Turret_Heading.java | 58 ------------------- 2 files changed, 15 insertions(+), 62 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Calculation_/Turret_Heading.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index dd8984df83e2..605ff5d26dd3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -4,19 +4,20 @@ import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotor; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_.Turret_Heading; + import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; + public class Turret { + + public final Devices.DcMotorExClass rotation = new Devices.DcMotorExClass(); public final Devices.DcMotorExClass flywheel = new Devices.DcMotorExClass(); public final Devices.ServoClass hood = new Devices.ServoClass(); public final Devices.ServoClass gate = new Devices.ServoClass(); - private final Turret_Heading targeting = new Turret_Heading(); - public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); public static BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); @@ -54,7 +55,7 @@ public void updatePIDs(){ * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. */ public void updateAimbot(Pose robotPose, boolean targetRedGoal){ - rotation.setAngle(targeting.calcLocalizer(robotPose, targetRedGoal)); + rotation.setAngle(calcLocalizer(robotPose, targetRedGoal)); } public void setGate(gatestate state){ @@ -65,6 +66,16 @@ public void setGate(gatestate state){ } } + public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ + Pose goalPose = new Pose(0,144,0); + if (targetRedGoal) {goalPose = new Pose(144, 144, 0);} + + return Math.toDegrees(Math.atan2( + goalPose.getY()-robotPose.getY(), + goalPose.getX()-robotPose.getX()) + ) - Math.toDegrees(robotPose.getHeading()) + 180; + } + public void setFlywheelRPM(double rpm){ flywheel.setRPM(rpm); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Calculation_/Turret_Heading.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Calculation_/Turret_Heading.java deleted file mode 100644 index 4bb74bd4ad1c..000000000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Calculation_/Turret_Heading.java +++ /dev/null @@ -1,58 +0,0 @@ -/* Copyright (c) 2022 FIRST. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted (subject to the limitations in the disclaimer below) provided that - * the following conditions are met: - * - * Redistributions of source code must retain the above copyright notice, this list - * of conditions and the following disclaimer. - * - * Redistributions in binary form must reproduce the above copyright notice, this - * list of conditions and the following disclaimer in the documentation and/or - * other materials provided with the distribution. - * - * Neither the name of FIRST nor the names of its contributors may be used to endorse or - * promote products derived from this software without specific prior written permission. - * - * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS - * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, - * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Calculation_; - -import com.pedropathing.geometry.Pose; - -public class Turret_Heading { - /** - * @param robotPose The pose of the robot, gotten from PedroPathing's localization - * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. - * @return The angle to set the turret to in degrees. - */ - public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ - Pose goalPose = new Pose(0,144,0); - if (targetRedGoal) {goalPose = new Pose(144, 144, 0);} - - return Math.toDegrees(Math.atan2( - goalPose.getY()-robotPose.getY(), - goalPose.getX()-robotPose.getX()) - ) - Math.toDegrees(robotPose.getHeading()) + 180; - } - - /** - * @param robotPose The pose of the robot, gotten from PedroPathing's localization - * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. - * @return The angle to set the turret to in degrees. - */ - public double calcAprilTag (Pose robotPose, boolean targetRedGoal){ - return 0; - } -} From 6eccf558335c20572301e3b861059469763a750d Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 24 Nov 2025 18:05:24 -0500 Subject: [PATCH 076/152] Created 12 more auto paths --- .../Hardware_/Drivetrain_/Pedro_Paths.java | 50 +++++++++++++++---- 1 file changed, 40 insertions(+), 10 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index bd05480b4274..0d717357e676 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -33,6 +33,9 @@ public class Pedro_Paths { public PathChain preload1_to_shooting1, preload1_to_shooting2, preload1_to_shooting3; public PathChain preload2_to_shooting1, preload2_to_shooting2, preload2_to_shooting3; public PathChain preload3_to_shooting1, preload3_to_shooting2, preload3_to_shooting3; + public PathChain shooting1_to_preload1, shooting1_to_preload2, shooting1_to_preload3; + public PathChain shooting2_to_preload1, shooting2_to_preload2, shooting2_to_preload3; + public PathChain shooting3_to_preload1, shooting3_to_preload2, shooting3_to_preload3; public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ int mult = 1; @@ -164,7 +167,7 @@ public void buildPreload1ToShootings(LoadHardwareClass.Alliance alliance){ .build(); } public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ - preload1_to_shooting1 = follower.pathBuilder() + preload2_to_shooting1 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(preloadPose2, alliance), autoMirror(new Pose(65,59.5), alliance), @@ -172,7 +175,7 @@ public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ )) .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose1.getHeading()) .build(); - preload1_to_shooting2 = follower.pathBuilder() + preload2_to_shooting2 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(preloadPose2, alliance), autoMirror(new Pose(65,59.5), alliance), @@ -180,7 +183,7 @@ public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ )) .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose2.getHeading()) .build(); - preload1_to_shooting3 = follower.pathBuilder() + preload2_to_shooting3 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(preloadPose2, alliance), autoMirror(new Pose(90.000, 59.500), alliance), @@ -190,42 +193,69 @@ public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ .build(); } public void buildPreload3ToShootings(LoadHardwareClass.Alliance alliance){ - preload1_to_shooting1 = follower.pathBuilder() + preload3_to_shooting1 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(preloadPose2, alliance), - autoMirror(new Pose(65,59.5), alliance), + autoMirror(new Pose(75,30), alliance), + autoMirror(new Pose(80,100), alliance), autoMirror(shootingPose1, alliance) )) .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose1.getHeading()) .build(); - preload1_to_shooting2 = follower.pathBuilder() + preload3_to_shooting2 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(preloadPose2, alliance), - autoMirror(new Pose(65,59.5), alliance), + autoMirror(new Pose(85,32), alliance), autoMirror(shootingPose2, alliance) )) .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose2.getHeading()) .build(); - preload1_to_shooting3 = follower.pathBuilder() + preload3_to_shooting3 = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(preloadPose2, alliance), - autoMirror(new Pose(90.000, 59.500), alliance), autoMirror(shootingPose3, alliance) )) .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose3.getHeading()) .build(); } + public void buildShooting1ToPreloads(LoadHardwareClass.Alliance alliance){ + shooting1_to_preload1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose1, alliance), + autoMirror(new Pose(60, 80), alliance), + autoMirror(preloadPose1, alliance) + )) + .setLinearHeadingInterpolation(shootingPose1.getHeading(), preloadPose1.getHeading()) + .build(); + shooting1_to_preload2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose1, alliance), + autoMirror(new Pose(60, 55), alliance), + autoMirror(preloadPose2, alliance) + )) + .setLinearHeadingInterpolation(shootingPose1.getHeading(), preloadPose2.getHeading()) + .build(); + shooting1_to_preload3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose1, alliance), + autoMirror(new Pose(60, 27), alliance), + autoMirror(preloadPose3, alliance) + )) + .setLinearHeadingInterpolation(shootingPose1.getHeading(), preloadPose3.getHeading()) + .build(); + } /** * Builds all the paths, mirroring them to the other side of the field if necessary */ public void buildPaths(LoadHardwareClass.Alliance alliance){ // All paths are for the RED side of the field. they will be mirrored if necessary. - buildStart1ToPreloads(alliance); buildStart2ToPreloads(alliance); buildPreload1ToShootings(alliance); buildPreload2ToShootings(alliance); + buildPreload3ToShootings(alliance); + buildShooting1ToPreloads(alliance); } /** From e554c3089c19cc6c8e062496abb10d01b2bbdbbd Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 25 Nov 2025 16:04:32 -0500 Subject: [PATCH 077/152] Finished most of the auto paths. --- .../Hardware_/Drivetrain_/Pedro_Paths.java | 121 +++++++++++++++++- 1 file changed, 120 insertions(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index 0d717357e676..58a2801e9854 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -26,16 +26,27 @@ public class Pedro_Paths { public Pose shootingPose1 = new Pose(115, 120, Math.toRadians(-35)); public Pose shootingPose2 = new Pose(85, 85, Math.toRadians(-15)); public Pose shootingPose3 = new Pose(85, 15, Math.toRadians(60)); + // Leave Poses + public Pose leavePose1 = new Pose(90,120); + public Pose leavePose2 = new Pose(95,55); + public Pose leavePose3 = new Pose(115,20); // Define all path variables + // Start Poses to Preloads public PathChain startPose1_to_preload1, startPose1_to_preload2, startPose1_to_preload3; public PathChain startPose2_to_preload1, startPose2_to_preload2, startPose2_to_preload3; + // Preloads to Shooting Positions public PathChain preload1_to_shooting1, preload1_to_shooting2, preload1_to_shooting3; public PathChain preload2_to_shooting1, preload2_to_shooting2, preload2_to_shooting3; public PathChain preload3_to_shooting1, preload3_to_shooting2, preload3_to_shooting3; + // Shooting Positions to Preloads public PathChain shooting1_to_preload1, shooting1_to_preload2, shooting1_to_preload3; public PathChain shooting2_to_preload1, shooting2_to_preload2, shooting2_to_preload3; public PathChain shooting3_to_preload1, shooting3_to_preload2, shooting3_to_preload3; + // Shooting Positions to Leave Positions + public PathChain shooting1_to_leave1, shooting1_to_leave2; + public PathChain shooting2_to_leave1, shooting2_to_leave2; + public PathChain shooting3_to_leave2, shooting3_to_leave3; public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ int mult = 1; @@ -244,18 +255,126 @@ public void buildShooting1ToPreloads(LoadHardwareClass.Alliance alliance){ .setLinearHeadingInterpolation(shootingPose1.getHeading(), preloadPose3.getHeading()) .build(); } + public void buildShooting2ToPreloads(LoadHardwareClass.Alliance alliance){ + shooting2_to_preload1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose2, alliance), + autoMirror(preloadPose1, alliance) + )) + .setLinearHeadingInterpolation(shootingPose2.getHeading(), preloadPose1.getHeading()) + .build(); + shooting2_to_preload2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose2, alliance), + autoMirror(new Pose(75, 56), alliance), + autoMirror(preloadPose2, alliance) + )) + .setLinearHeadingInterpolation(shootingPose2.getHeading(), preloadPose2.getHeading()) + .build(); + shooting2_to_preload3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose2, alliance), + autoMirror(new Pose(68, 30), alliance), + autoMirror(preloadPose3, alliance) + )) + .setLinearHeadingInterpolation(shootingPose2.getHeading(), preloadPose3.getHeading()) + .build(); + } + public void buildShooting3ToPreloads(LoadHardwareClass.Alliance alliance){ + shooting3_to_preload1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose3, alliance), + autoMirror(new Pose(73, 88), alliance), + autoMirror(preloadPose1, alliance) + )) + .setLinearHeadingInterpolation(shootingPose3.getHeading(), preloadPose1.getHeading()) + .build(); + shooting3_to_preload2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose3, alliance), + autoMirror(new Pose(78, 62), alliance), + autoMirror(preloadPose2, alliance) + )) + .setLinearHeadingInterpolation(shootingPose3.getHeading(), preloadPose2.getHeading()) + .build(); + shooting3_to_preload3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose3, alliance), + autoMirror(new Pose(82.5, 35), alliance), + autoMirror(preloadPose3, alliance) + )) + .setLinearHeadingInterpolation(shootingPose3.getHeading(), preloadPose3.getHeading()) + .build(); + } + public void buildShooting1ToLeaves(LoadHardwareClass.Alliance alliance){ + shooting1_to_leave1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose1, alliance), + autoMirror(leavePose1, alliance) + )) + .setConstantHeadingInterpolation(shootingPose1.getHeading()) + .build(); + shooting1_to_leave2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose1, alliance), + autoMirror(leavePose2, alliance) + )) + .setConstantHeadingInterpolation(shootingPose1.getHeading()) + .build(); + } + public void buildShooting2ToLeaves(LoadHardwareClass.Alliance alliance){ + shooting2_to_leave1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose2, alliance), + autoMirror(leavePose1, alliance) + )) + .setConstantHeadingInterpolation(shootingPose2.getHeading()) + .build(); + shooting2_to_leave2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose2, alliance), + autoMirror(leavePose2, alliance) + )) + .setConstantHeadingInterpolation(shootingPose2.getHeading()) + .build(); + } + public void buildShooting3ToLeaves(LoadHardwareClass.Alliance alliance){ + shooting3_to_leave2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose3, alliance), + autoMirror(leavePose2, alliance) + )) + .setConstantHeadingInterpolation(shootingPose3.getHeading()) + .build(); + shooting3_to_leave3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(shootingPose3, alliance), + autoMirror(leavePose3, alliance) + )) + .setConstantHeadingInterpolation(shootingPose3.getHeading()) + .build(); + } /** * Builds all the paths, mirroring them to the other side of the field if necessary */ public void buildPaths(LoadHardwareClass.Alliance alliance){ - // All paths are for the RED side of the field. they will be mirrored if necessary. + /// All paths are for the RED side of the field. they will be mirrored if necessary. + // Paths going from each start position to each of the preloads. buildStart1ToPreloads(alliance); buildStart2ToPreloads(alliance); + // Paths going from each preload to each shooting position buildPreload1ToShootings(alliance); buildPreload2ToShootings(alliance); buildPreload3ToShootings(alliance); + // Paths going from each shooting position to each preload buildShooting1ToPreloads(alliance); + buildShooting2ToPreloads(alliance); + buildShooting3ToPreloads(alliance); + // paths going from each shooting position to the leave positions. + buildShooting1ToLeaves(alliance); + buildShooting2ToLeaves(alliance); + buildShooting3ToLeaves(alliance); } /** From 88912efbab5a8189cf88b9679742881bdc23e176 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 25 Nov 2025 16:07:09 -0500 Subject: [PATCH 078/152] Added call to build auto paths in Auto_Main_.java --- .../ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java | 1 + 1 file changed, 1 insertion(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 2dd014ecef9a..add449a68bbe 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -53,6 +53,7 @@ public void init() { telemetry.addData("Selection", "Complete"); } ); + Robot.drivetrain.paths.buildPaths(selectedAlliance); } @Override From 9cac958618d560960f2ff9bdce5471c05431b8cf Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 25 Nov 2025 16:25:11 -0500 Subject: [PATCH 079/152] Added/Moved old TODOs to our todo list Rescoped our robot initialization in Teleop_Main_.java Added new control profile functions Added HTML docstring control guides for labeling and future hyperlinks. --- .../Main_/Hardware_/Actuators_/Turret.java | 2 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 157 +++++++++++++----- .../ftc/teamcode/LOADCode/Notes and TODOs | 6 +- 3 files changed, 116 insertions(+), 49 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 605ff5d26dd3..564d26e1d08f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -28,7 +28,7 @@ public enum gatestate { } public void init(OpMode opmode){ - rotation.init(opmode, "turret", 103.8); + rotation.init(opmode, "turret", 145.1); //Previously 103.8 flywheel.init(opmode, "flywheel"); hood.init(opmode, "hood"); gate.init(opmode, "gate"); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 877aa4ccd4b0..3ebc03b2b896 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -57,13 +57,14 @@ public class Teleop_Main_ extends LinearOpMode { // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); + // Create a new instance of our Robot class + LoadHardwareClass Robot = new LoadHardwareClass(this); + @Override public void runOpMode() { telemetry.addData("Status", "Initialized"); telemetry.update(); - // Create a new instance of our Robot class - LoadHardwareClass Robot = new LoadHardwareClass(this); // Create a new prompter for selecting alliance prompter = new Prompter(this); @@ -91,50 +92,9 @@ public void runOpMode() { // run until the end of the match (driver presses STOP) while (opModeIsActive()) { - Robot.drivetrain.speedMultiplier = 0.66; - if (gamepad1.left_trigger >= 0.5) { - Robot.drivetrain.speedMultiplier -= 0.33; - } - if (gamepad1.right_trigger >= 0.5){ - Robot.drivetrain.speedMultiplier += 0.33; - } - - // Pass the joystick positions to our mecanum drive controller - double turnMult = 2; - if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ - turnMult = 1; - } - Robot.drivetrain.pedroMecanumDrive( - gamepad1.left_stick_y, - gamepad1.left_stick_x, - gamepad1.right_stick_x/turnMult, - true - ); - - if (gamepad2.guide){ - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); - }else if (gamepad2.back){ - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); - }else if (Math.abs(gamepad2.left_stick_x)>0.2 || Math.abs(gamepad2.left_stick_y)>0.2) { - Robot.turret.rotation.setAngle( - Math.toDegrees(Math.atan2(gamepad2.left_stick_y, gamepad2.left_stick_x))); - } - if (gamepad2.a){ - Robot.intake.setMode(Intake.Mode.INTAKING); - }else if (gamepad2.b){ - Robot.intake.setMode(Intake.Mode.SHOOTING); - }else if (gamepad2.x){ - Robot.intake.setMode(Intake.Mode.REVERSING); - }else{ - Robot.intake.setMode(Intake.Mode.OFF); - } - - if (gamepad2.b){ - Robot.turret.setGate(Turret.gatestate.OPEN); - }else{ - Robot.turret.setGate(Turret.gatestate.CLOSED); - } + Gamepad1(); + Gamepad2(); Robot.turret.updatePIDs(); @@ -152,7 +112,112 @@ public void runOpMode() { telemetry.addData("Status", "Run Time: " + runtime.toString()); telemetry.addData("Version: ", "11/4/25"); telemetry.update(); - //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging + } } + /** + *

Gamepad 1 Controls (Ari's Pick V1)

+ *
    + *
  • Analog Inputs
      + *
    • Left Stick:
        + *
      • X: Rotate Left/Right
      • + *
      • Y: N/A
      • + *
    • + *
    • Right Stick:
        + *
      • X: Strafe Left/Right
      • + *
      • Y: Drive Forwards/Backwards
      • + *
    • + *
    • Left Trigger: Slow Mod
    • + *
    • Right Trigger: Quick Mod
    • + *
  • + * + *
  • Button Inputs
    • + *
    • Letter Buttons:
        + *
      • A: N/A
      • + *
      • B: N/A
      • + *
      • X: N/A
      • + *
      • Y: N/A
      • + *
    • + *
    • Letter Buttons:
        + *
      • DpadUp: N/A
      • + *
      • DpadDown: N/A
      • + *
      • DpadLeft: N/A
      • + *
      • DpadRight: N/A
      • + *
    • + *
    • Bumpers:
        + *
      • Left Bumper: N/A
      • + *
      • Right Bumper: N/A
      • + *
    • + *
    • Stick Buttons:
        + *
      • Left Stick Button: N/A
      • + *
      • Right Stick Button: N/A
      • + *
    • + *
    + *
+ */ + public void Gamepad1(){ + + Robot.drivetrain.speedMultiplier = 0.66; + if (gamepad1.left_trigger >= 0.5) { + Robot.drivetrain.speedMultiplier -= 0.33; + } + if (gamepad1.right_trigger >= 0.5){ + Robot.drivetrain.speedMultiplier += 0.33; + } + + double turnMult = 2; + if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ + turnMult = 1; + } + Robot.drivetrain.pedroMecanumDrive( + gamepad1.left_stick_y, + gamepad1.left_stick_x, + gamepad1.right_stick_x/turnMult, + true + ); + } + + /** + *

Gamepad 2 Controls (Dylan's Pick V1)

+ *
    + *
  • Analog Inputs
      + *
    • Left Stick:
        + *
      • X: N/A
      • + *
      • Y: Intake Direction/Power
      • + *
    • + *
    • Right Stick:
        + *
      • X: Turret Angle Override
      • + *
      • Y: N/A
      • + *
    • + *
    • Left Trigger: N/A
    • + *
    • Right Trigger: N/A
    • + *
  • + * + *
  • Button Inputs
    • + *
    • Letter Buttons:
        + *
      • A: N/A
      • + *
      • B: Shoot
      • + *
      • X: N/A
      • + *
      • Y: Flywheel Toggle
      • + *
    • + *
    • Letter Buttons:
        + *
      • DpadUp: Hood Up Override
      • + *
      • DpadDown: Hood Down Override
      • + *
      • DpadLeft: N/A
      • + *
      • DpadRight: N/A
      • + *
    • + *
    • Bumpers:
        + *
      • Left Bumper: Transfer Belt Out
      • + *
      • Right Bumper: Transfer Belt In
      • + *
    • + *
    • Stick Buttons:
        + *
      • Left Stick Button: N/A
      • + *
      • Right Stick Button: N/A
      • + *
    • + *
    + *
+ */ + public void Gamepad2(){ + + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 077c8e066c19..1c59baec4f0f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -2,6 +2,8 @@ //TODO, add 2 generic autos for preloads and shooting and stuff -//TODO, Implement controls graph +//TODO, Implement controls graph to TeleOp -//DONE, Consolidate the generic actuator functionalities folder into one file \ No newline at end of file +//DONE, Consolidate the generic actuator functionalities folder into one file + +//TODO, Add a more advanced telemetry handler for better organization, readability, and debugging \ No newline at end of file From 314b562d41b489704114a0da9e7062b36200a4d1 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 25 Nov 2025 16:47:13 -0500 Subject: [PATCH 080/152] Working on adding Gamepad2 controls to Teleop_Main_.java Added documentation to Intake.java Added more stuff to Notes and TODOs --- .../Main_/Hardware_/Actuators_/Intake.java | 19 +++++++++++++++++++ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 17 +++++++++++++++++ .../ftc/teamcode/LOADCode/Notes and TODOs | 4 +++- 3 files changed, 39 insertions(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index b87a167d7f62..5b34eff30812 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -26,6 +26,16 @@ public void init(OpMode opmode){ belt.setDirection(DcMotorSimple.Direction.REVERSE); } + /** + * @param direction + * Takes the following inputs + *
    + *
  • Mode.INTAKING
  • + *
  • Mode.SHOOTING
  • + *
  • Mode.REVERSING
  • + *
  • Mode.OFF
  • + *
+ */ public void setMode(Mode direction){ if (direction == Mode.INTAKING){ intake.setPower(1); @@ -42,6 +52,15 @@ public void setMode(Mode direction){ } } + /** + * Outputs one of the following modes + *
    + *
  • Mode.INTAKING
  • + *
  • Mode.SHOOTING
  • + *
  • Mode.REVERSING
  • + *
  • Mode.OFF
  • + *
+ */ public Mode getMode(){ double intakePower = intake.getPower(); double beltPower = belt.getPower(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 3ebc03b2b896..5513ceeba9ee 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -218,6 +218,23 @@ public void Gamepad1(){ * */ public void Gamepad2(){ + double DylanStickDeadzones = 0.2; + + //Intake Controls (Left Stick Y) + if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones){ + if (gamepad2.left_stick_y > 0){ // OUT (Digital) + Robot.intake.setMode(Intake.Mode.REVERSING); + } else { // IN (Digital) + Robot.intake.setMode(Intake.Mode.INTAKING); + } + } else { // OFF + Robot.intake.setMode(Intake.Mode.OFF); + } + + //Turret Angle Controls (Right Stick X) + //To be added after manual control is finished + + //Flywheel Toggle Control (Y Button) } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 1c59baec4f0f..cce8d19f1be1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -6,4 +6,6 @@ //DONE, Consolidate the generic actuator functionalities folder into one file -//TODO, Add a more advanced telemetry handler for better organization, readability, and debugging \ No newline at end of file +//TODO, Add a more advanced telemetry handler for better organization, readability, and debugging + +//TODO, Add proper functionaltiy for manual turret control to Turret.java \ No newline at end of file From a8d198a29aa245129122041a3d16a9f04495de04 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 25 Nov 2025 16:53:09 -0500 Subject: [PATCH 081/152] began work on command system for auto --- TeamCode/build.gradle | 1 + .../LOADCode/Main_/Auto_/Auto_Main_.java | 6 ++-- .../LOADCode/Main_/Hardware_/Commands.java | 33 +++++++++++++++++++ 3 files changed, 37 insertions(+), 3 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index d077f69030f6..8be5f4e0776c 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -26,4 +26,5 @@ android { dependencies { implementation project(':FtcRobotController') implementation 'io.github.skeleton-army.marrow:core:0.1.2' + implementation 'dev.nextftc:ftc:1.0.1' } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index add449a68bbe..fa862bdf9085 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -64,7 +64,7 @@ public void loop() { case LOAD_ROBOTICS_B: return; default: - TEMPLATE_A(); + LEAVE_START_POS(); } switch (selectedAlliance) { case RED: @@ -83,9 +83,9 @@ private void waitForPathCompletion(){ } /** - * Template auto + * This auto starts at the far zone and goes to the human player leave zone */ - private void TEMPLATE_A() { + private void LEAVE_START_POS() { switch (autoState){ case 0: Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java new file mode 100644 index 000000000000..86b8c9fb0c41 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -0,0 +1,33 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; + +import dev.nextftc.core.commands.Command; + +public class Commands { + public class myCommand extends Command { + + public myCommand() { + requires(/* subsystems */); + setInterruptible(true); // this is the default, so you don't need to specify + } + + @Override + public boolean isDone() { + return false; // whether or not the command is done + } + + @Override + public void start() { + // executed when the command begins + } + + @Override + public void update() { + // executed on every update of the command + } + + @Override + public void stop(boolean interrupted) { + // executed when the command ends + } + } +} From 3730386aad3af0cbd303ac1dfbb7574b5d4ae19f Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 25 Nov 2025 17:47:39 -0500 Subject: [PATCH 082/152] Added more flywheel related functionality in Turret.java as well as a flywheel toggle in Teleop_Main_.java --- .../Main_/Hardware_/Actuators_/Turret.java | 55 +++++++++++++++++++ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 8 +++ 2 files changed, 63 insertions(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 564d26e1d08f..fb79195b5c9e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -27,6 +27,11 @@ public enum gatestate { CLOSED, } + public enum flywheelstate { + RUNNING, + OFF + } + public void init(OpMode opmode){ rotation.init(opmode, "turret", 145.1); //Previously 103.8 flywheel.init(opmode, "flywheel"); @@ -58,6 +63,7 @@ public void updateAimbot(Pose robotPose, boolean targetRedGoal){ rotation.setAngle(calcLocalizer(robotPose, targetRedGoal)); } + public void setGate(gatestate state){ if (state == gatestate.OPEN){ gate.setAngle(0.5); @@ -66,6 +72,21 @@ public void setGate(gatestate state){ } } + /** + * Outputs one of the following modes + *
    + *
  • gatestate.OPEN
  • + *
  • gatestate.CLOSED
  • + *
+ */ + public gatestate getGate(){ + if (gate.getAngle() == 0.5){ + return gatestate.OPEN; + } else { + return gatestate.CLOSED; + } + } + public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ Pose goalPose = new Pose(0,144,0); if (targetRedGoal) {goalPose = new Pose(144, 144, 0);} @@ -76,7 +97,41 @@ public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ ) - Math.toDegrees(robotPose.getHeading()) + 180; } + /** + * @param rpm + * RPM Range [0,6000] + */ public void setFlywheelRPM(double rpm){ flywheel.setRPM(rpm); } + + /** + * @return double flywheel.getRPM(); - RPM Range [0,6000] + */ + public double getFlywheelRPM(){ + return flywheel.getRPM(); + } + + public void setFlywheel(flywheelstate state){ + if (state == flywheelstate.RUNNING){ + setFlywheelRPM(6000); + } else if (state == flywheelstate.OFF){ + setFlywheelRPM(0); + } + } + + /** + * Outputs one of the following modes + *
    + *
  • flywheelstate.OFF
  • + *
  • flywheelstate.RUNNING
  • + *
+ */ + public flywheelstate getFlywheel(){ + if (getFlywheelRPM() == 0.0){ + return flywheelstate.OFF; + } else { + return flywheelstate.RUNNING; + } + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 5513ceeba9ee..deeb2dbba3e8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -235,6 +235,14 @@ public void Gamepad2(){ //To be added after manual control is finished //Flywheel Toggle Control (Y Button) + if (gamepad2.yWasPressed()){ + if (Robot.turret.getFlywheel() == Turret.flywheelstate.OFF){ + Robot.turret.setFlywheel(Turret.flywheelstate.RUNNING); + } else { + Robot.turret.setFlywheel(Turret.flywheelstate.OFF); + } + } + } } From 34674fb4a0695c5f29ea58d3cc962f02869f0f16 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 25 Nov 2025 17:50:54 -0500 Subject: [PATCH 083/152] Added runPath command for auto --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 5 +++ .../LOADCode/Main_/Hardware_/Commands.java | 41 +++++++++---------- 2 files changed, 24 insertions(+), 22 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index fa862bdf9085..62ab113a9ca0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -7,8 +7,11 @@ import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; +import dev.nextftc.core.commands.Command; + public class Auto_Main_ extends OpMode { // Define other PedroPathing constants @@ -29,6 +32,7 @@ private enum Auto { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); + Commands Command = new Commands(Robot); @Override public void init() { @@ -97,5 +101,6 @@ private void LEAVE_START_POS() { Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); waitForPathCompletion(); } + Commands.runPath(Robot, Robot.drivetrain.paths.startPose1_to_preload1, true); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 86b8c9fb0c41..7f48f2f22e2f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -1,33 +1,30 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; +import com.pedropathing.paths.PathChain; +import com.qualcomm.robotcore.robot.Robot; + +import dev.nextftc.control.KineticState; import dev.nextftc.core.commands.Command; +import dev.nextftc.core.commands.utility.LambdaCommand; public class Commands { - public class myCommand extends Command { - - public myCommand() { - requires(/* subsystems */); - setInterruptible(true); // this is the default, so you don't need to specify - } - @Override - public boolean isDone() { - return false; // whether or not the command is done - } + private LoadHardwareClass Robot = null; + public static Command runPath = null; + public static Object driveSystem = null; - @Override - public void start() { - // executed when the command begins - } + public static PathChain[] scheduledPaths; - @Override - public void update() { - // executed on every update of the command - } + public Commands(LoadHardwareClass robot){ + Robot = robot; + } - @Override - public void stop(boolean interrupted) { - // executed when the command ends - } + public static Command runPath(LoadHardwareClass Robot, PathChain path, boolean holdEnd) { + return new LambdaCommand("runPedroPath(" + path + ", " + holdEnd) + .setInterruptible(false) + .setStart(() -> Robot.drivetrain.runPath(path, holdEnd)) + .setUpdate(() -> Robot.drivetrain.runPath(path, holdEnd)) + .setIsDone(Robot.drivetrain::pathComplete) + .requires(driveSystem); } } From 305907b883f238876b84b711b98f37bc1a86c30a Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 25 Nov 2025 18:17:38 -0500 Subject: [PATCH 084/152] Finished implementing all available functionality to controls graph --- .../ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java | 2 ++ .../org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs | 6 ++++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index deeb2dbba3e8..02bd7b1b3296 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -243,6 +243,8 @@ public void Gamepad2(){ } } + //Shoot (B Button Press) + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index cce8d19f1be1..ba739f145e2e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -2,10 +2,12 @@ //TODO, add 2 generic autos for preloads and shooting and stuff -//TODO, Implement controls graph to TeleOp +//DONE, Implement controls graph to TeleOp //DONE, Consolidate the generic actuator functionalities folder into one file //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging -//TODO, Add proper functionaltiy for manual turret control to Turret.java \ No newline at end of file +//TODO, Add proper functionality for manual turret control to Turret.java + +//TODO, Shoot mode state machine Off->On->LastShot->Delay->Off etc. cycled with B button on Gamepad2 \ No newline at end of file From 1feb2d950080e753862d984c7b2ff0b443d7906f Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 25 Nov 2025 18:18:55 -0500 Subject: [PATCH 085/152] Finished implementing all available functionality to controls graph --- .../ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java | 1 + 1 file changed, 1 insertion(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 02bd7b1b3296..e60090a44bb9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -244,6 +244,7 @@ public void Gamepad2(){ } //Shoot (B Button Press) + //Statemachine cycle goes here } From 3907a0c1d3ea43d0065ea06f590eedcbb9aa33c4 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Tue, 25 Nov 2025 18:20:49 -0500 Subject: [PATCH 086/152] Added one last TODO --- .../org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index ba739f145e2e..0f917490ff06 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -10,4 +10,6 @@ //TODO, Add proper functionality for manual turret control to Turret.java -//TODO, Shoot mode state machine Off->On->LastShot->Delay->Off etc. cycled with B button on Gamepad2 \ No newline at end of file +//TODO, Shoot mode state machine Off->On->LastShot->Delay->Off etc. cycled with B button on Gamepad2 + +//TODO, add the new code structure graph, control graph, and gamepad HTML to the development branch Readme \ No newline at end of file From 3c1dc67a2fda428a093e6b280c83bcc68fe14c85 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 25 Nov 2025 20:35:36 -0500 Subject: [PATCH 087/152] continued developing the command system for auto --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 69 +++++++++++-------- .../Main_/Hardware_/Actuators_/Devices.java | 2 +- .../Main_/Hardware_/Actuators_/Turret.java | 6 +- .../LOADCode/Main_/Hardware_/Commands.java | 35 ++++++---- .../Drivetrain_/MecanumDrivetrainClass.java | 8 +-- .../Hardware_/Drivetrain_/Pedro_Paths.java | 40 ++++++++++- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 3 +- .../ftc/teamcode/pedroPathing/Constants.java | 2 +- 8 files changed, 109 insertions(+), 56 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 62ab113a9ca0..70e49391938e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -3,6 +3,7 @@ import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -10,17 +11,15 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; -import dev.nextftc.core.commands.Command; - +@Autonomous(name = "Auto_Main_", group = "Main", preselectTeleOp="Teleop_Main_") public class Auto_Main_ extends OpMode { // Define other PedroPathing constants private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. private enum Auto { - LOAD_ROBOTICS_A, - LOAD_ROBOTICS_B, - MOE_A, + test, + LEAVE_FAR_HP } private int autoState = 0; @@ -32,7 +31,6 @@ private enum Auto { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); - Commands Command = new Commands(Robot); @Override public void init() { @@ -47,9 +45,8 @@ public void init() { )); prompter.prompt("auto", new OptionPrompt<>("Select Auto", - Auto.LOAD_ROBOTICS_A, - Auto.MOE_A, - Auto.LOAD_ROBOTICS_B + Auto.test, + Auto.LEAVE_FAR_HP )); prompter.onComplete(() -> { selectedAlliance = prompter.get("alliance"); @@ -60,15 +57,26 @@ public void init() { Robot.drivetrain.paths.buildPaths(selectedAlliance); } + @Override + public void init_loop() { + prompter.run(); + } + + @Override + public void start() { + // Initialize all hardware of the robot + Robot.init(startPose); + } + @Override public void loop() { switch (selectedAuto) { - case LOAD_ROBOTICS_A: + case test: + test(); return; - case LOAD_ROBOTICS_B: + case LEAVE_FAR_HP: + Leave_Far_HP(); return; - default: - LEAVE_START_POS(); } switch (selectedAlliance) { case RED: @@ -76,7 +84,12 @@ public void loop() { return; case BLUE: Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); + return; } + + telemetry.addData("selectedAuto", selectedAuto); + telemetry.addData("follower", Robot.drivetrain.follower.getCurrentPath()); + telemetry.update(); } /** @@ -86,21 +99,21 @@ private void waitForPathCompletion(){ if (Robot.drivetrain.pathComplete()){autoState++;} } - /** - * This auto starts at the far zone and goes to the human player leave zone + /** + * This auto starts at the far zone, + * shoots it's preloads after 5 seconds, + * and goes to the human player leave zone. */ - private void LEAVE_START_POS() { - switch (autoState){ - case 0: - Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); - waitForPathCompletion(); - case 1: - Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); - waitForPathCompletion(); - case 2: - Robot.drivetrain.runPath(Robot.drivetrain.paths.startPose1_to_preload1, true); - waitForPathCompletion(); - } - Commands.runPath(Robot, Robot.drivetrain.paths.startPose1_to_preload1, true); + private void Leave_Far_HP() { + //Commands.setFlywheelState(Robot, Turret.flywheelstate.ON).schedule(); +// new ParallelGroup( +// new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), +// new Delay(5) +// ); + Commands.runPath(Robot, Robot.drivetrain.paths.start2_to_leave3, true).schedule(); + } + + private void test() { + Robot.drivetrain.runPath(Robot.drivetrain.paths.start2_to_leave3, true); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java index 0b096ee689c1..3541e4b84685 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -182,7 +182,7 @@ public void setAngle(double angle){ setPower(turretPID.calculate(currentKineticState)); } /** - * Uses a PID controller to accelerate the motor to the desired RPM + * Uses a PID controller to accelerate the motor to the desired RPM. * Must be called every loop to function properly. * @param rpm The RPM to accelerate the motor to. Can be any number */ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index fb79195b5c9e..649667774cfa 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -28,7 +28,7 @@ public enum gatestate { } public enum flywheelstate { - RUNNING, + ON, OFF } @@ -113,7 +113,7 @@ public double getFlywheelRPM(){ } public void setFlywheel(flywheelstate state){ - if (state == flywheelstate.RUNNING){ + if (state == flywheelstate.ON){ setFlywheelRPM(6000); } else if (state == flywheelstate.OFF){ setFlywheelRPM(0); @@ -131,7 +131,7 @@ public flywheelstate getFlywheel(){ if (getFlywheelRPM() == 0.0){ return flywheelstate.OFF; } else { - return flywheelstate.RUNNING; + return flywheelstate.ON; } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 7f48f2f22e2f..1821920b80f7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -1,30 +1,39 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; import com.pedropathing.paths.PathChain; -import com.qualcomm.robotcore.robot.Robot; -import dev.nextftc.control.KineticState; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; + import dev.nextftc.core.commands.Command; import dev.nextftc.core.commands.utility.LambdaCommand; public class Commands { - private LoadHardwareClass Robot = null; - public static Command runPath = null; public static Object driveSystem = null; - - public static PathChain[] scheduledPaths; - - public Commands(LoadHardwareClass robot){ - Robot = robot; - } + public static Object turretSystem = null; + public static Object intakeSystem = null; public static Command runPath(LoadHardwareClass Robot, PathChain path, boolean holdEnd) { - return new LambdaCommand("runPedroPath(" + path + ", " + holdEnd) + return new LambdaCommand("runPedroPath(" + path + ", " + holdEnd + ")") .setInterruptible(false) .setStart(() -> Robot.drivetrain.runPath(path, holdEnd)) .setUpdate(() -> Robot.drivetrain.runPath(path, holdEnd)) - .setIsDone(Robot.drivetrain::pathComplete) - .requires(driveSystem); + .setIsDone(Robot.drivetrain::pathComplete); + } + + public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheelstate state) { + return new LambdaCommand("shoot()") + .setInterruptible(false) + .setUpdate(() -> Robot.turret.setFlywheel(state)) + .setIsDone(() -> Robot.turret.getFlywheelRPM() > 5900) + .requires(turretSystem); + } + + public static Command setBeltState(LoadHardwareClass Robot, Intake.Mode state) { + return new LambdaCommand("shoot()") + .setInterruptible(false) + .setUpdate(() -> Robot.intake.setMode(state)) + .requires(intakeSystem); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index db11561f235d..c37851e8274a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -34,13 +34,6 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose){ follower.update(); } - /** - * @return Pedropathing's follower object - */ - public Follower getFollower() { - return follower; - } - /** * Uses PedroPathing's follower class to implement a mecanum drive controller. * Must be called every loop to function properly. @@ -60,6 +53,7 @@ public void pedroMecanumDrive(double forward, double strafe, double rotate, bool public void runPath(PathChain path, boolean holdEndpoint){ follower.followPath(path, holdEndpoint); + follower.update(); } public boolean pathComplete(){ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index 58a2801e9854..bfe1475adbb9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -47,6 +47,9 @@ public class Pedro_Paths { public PathChain shooting1_to_leave1, shooting1_to_leave2; public PathChain shooting2_to_leave1, shooting2_to_leave2; public PathChain shooting3_to_leave2, shooting3_to_leave3; + // Start Positions to Leave Positions + public PathChain start1_to_leave1, start1_to_leave2; + public PathChain start2_to_leave2, start2_to_leave3; public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ int mult = 1; @@ -354,6 +357,38 @@ public void buildShooting3ToLeaves(LoadHardwareClass.Alliance alliance){ .setConstantHeadingInterpolation(shootingPose3.getHeading()) .build(); } + public void buildStart1ToLeaves(LoadHardwareClass.Alliance alliance){ + start1_to_leave1 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose1, alliance), + autoMirror(leavePose1, alliance) + )) + .setConstantHeadingInterpolation(startPose1.getHeading()) + .build(); + start1_to_leave2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose1, alliance), + autoMirror(leavePose3, alliance) + )) + .setConstantHeadingInterpolation(startPose1.getHeading()) + .build(); + } + public void buildStart2ToLeaves(LoadHardwareClass.Alliance alliance){ + start2_to_leave2 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose2, alliance), + autoMirror(leavePose1, alliance) + )) + .setConstantHeadingInterpolation(startPose2.getHeading()) + .build(); + start2_to_leave3 = follower.pathBuilder() + .addPath(new BezierCurve( + autoMirror(startPose2, alliance), + autoMirror(leavePose3, alliance) + )) + .setConstantHeadingInterpolation(startPose2.getHeading()) + .build(); + } /** * Builds all the paths, mirroring them to the other side of the field if necessary @@ -371,10 +406,13 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ buildShooting1ToPreloads(alliance); buildShooting2ToPreloads(alliance); buildShooting3ToPreloads(alliance); - // paths going from each shooting position to the leave positions. + // Paths going from each shooting position to the leave positions. buildShooting1ToLeaves(alliance); buildShooting2ToLeaves(alliance); buildShooting3ToLeaves(alliance); + // Paths going from the start positions to the leave positions + buildStart1ToLeaves(alliance); + buildStart2ToLeaves(alliance); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index e60090a44bb9..90d62ae7c231 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -30,7 +30,6 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; import com.bylazar.configurables.annotations.Configurable; -import com.pedropathing.Drivetrain; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; @@ -237,7 +236,7 @@ public void Gamepad2(){ //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()){ if (Robot.turret.getFlywheel() == Turret.flywheelstate.OFF){ - Robot.turret.setFlywheel(Turret.flywheelstate.RUNNING); + Robot.turret.setFlywheel(Turret.flywheelstate.ON); } else { Robot.turret.setFlywheel(Turret.flywheelstate.OFF); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index a7335ed6b1d0..6b78bdee8f54 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -57,7 +57,7 @@ public class Constants { .distanceUnit(DistanceUnit.INCH) .hardwareMapName("pinpoint") .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) - .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD) + .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED) .strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD); public static Follower createFollower(HardwareMap hardwareMap) { From e50cf923097a82aada40116e7798b5c559455d45 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Wed, 26 Nov 2025 09:16:55 -0500 Subject: [PATCH 088/152] Hopefully fixed the runPath command with NextFTC's PedroPathing extension --- TeamCode/build.gradle | 1 + .../LOADCode/Main_/Auto_/Auto_Main_.java | 58 +++++++++++-------- .../Main_/Hardware_/Actuators_/Intake.java | 18 ++++++ .../LOADCode/Main_/Hardware_/Commands.java | 12 ++-- .../Drivetrain_/MecanumDrivetrainClass.java | 18 ++++++ .../Main_/Hardware_/LoadHardwareClass.java | 17 ++++++ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 38 +++++++++++- .../ftc/teamcode/LOADCode/Notes and TODOs | 3 +- 8 files changed, 130 insertions(+), 35 deletions(-) diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index 8be5f4e0776c..096457396ebb 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -27,4 +27,5 @@ dependencies { implementation project(':FtcRobotController') implementation 'io.github.skeleton-army.marrow:core:0.1.2' implementation 'dev.nextftc:ftc:1.0.1' + implementation 'dev.nextftc.extensions:pedro:1.0.0' } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 70e49391938e..ad6aa0ef7c61 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -4,26 +4,27 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; +import org.firstinspires.ftc.teamcode.pedroPathing.Constants; + +import dev.nextftc.extensions.pedro.PedroComponent; +import dev.nextftc.ftc.NextFTCOpMode; @Autonomous(name = "Auto_Main_", group = "Main", preselectTeleOp="Teleop_Main_") -public class Auto_Main_ extends OpMode { +public class Auto_Main_ extends NextFTCOpMode { // Define other PedroPathing constants private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. private enum Auto { - test, + LEAVE_NEAR_LAUNCH, LEAVE_FAR_HP } - private int autoState = 0; - private Auto selectedAuto = null; // Create the prompter object for selecting Alliance and Auto @@ -33,10 +34,14 @@ private enum Auto { LoadHardwareClass Robot = new LoadHardwareClass(this); @Override - public void init() { + public void onInit() { // Initialize all hardware of the robot Robot.init(startPose); + addComponents( + new PedroComponent(Constants::createFollower) + ); + prompter = new Prompter(this); prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", @@ -45,7 +50,7 @@ public void init() { )); prompter.prompt("auto", new OptionPrompt<>("Select Auto", - Auto.test, + Auto.LEAVE_NEAR_LAUNCH, Auto.LEAVE_FAR_HP )); prompter.onComplete(() -> { @@ -58,21 +63,21 @@ public void init() { } @Override - public void init_loop() { + public void onWaitForStart() { prompter.run(); } @Override - public void start() { + public void onStartButtonPressed() { // Initialize all hardware of the robot - Robot.init(startPose); + Robot.init(startPose, PedroComponent.follower()); } @Override - public void loop() { + public void onUpdate() { switch (selectedAuto) { - case test: - test(); + case LEAVE_NEAR_LAUNCH: + Leave_Near_Launch(); return; case LEAVE_FAR_HP: Leave_Far_HP(); @@ -88,21 +93,14 @@ public void loop() { } telemetry.addData("selectedAuto", selectedAuto); - telemetry.addData("follower", Robot.drivetrain.follower.getCurrentPath()); + telemetry.addData("currentPose", Robot.drivetrain.follower.getPose()); telemetry.update(); } - /** - * Waits for the current stage of the auto to be done and then runs the next stage. - */ - private void waitForPathCompletion(){ - if (Robot.drivetrain.pathComplete()){autoState++;} - } - /** * This auto starts at the far zone, * shoots it's preloads after 5 seconds, - * and goes to the human player leave zone. + * and goes to the leave zone next to the human player zone. */ private void Leave_Far_HP() { //Commands.setFlywheelState(Robot, Turret.flywheelstate.ON).schedule(); @@ -110,10 +108,20 @@ private void Leave_Far_HP() { // new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), // new Delay(5) // ); - Commands.runPath(Robot, Robot.drivetrain.paths.start2_to_leave3, true).schedule(); + Commands.runPath(Robot.drivetrain.paths.start2_to_leave3, true).schedule(); } - private void test() { - Robot.drivetrain.runPath(Robot.drivetrain.paths.start2_to_leave3, true); + /** + * This auto starts at the near zone, + * shoots it's preloads after 5 seconds, + * and goes to the leave pose that is in the launch zone. + */ + private void Leave_Near_Launch() { + //Commands.setFlywheelState(Robot, Turret.flywheelstate.ON).schedule(); +// new ParallelGroup( +// new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), +// new Delay(5) +// ); + Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true).schedule(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 5b34eff30812..276819857146 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -8,6 +8,7 @@ public class Intake { private final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); private final Devices.CRServoClass belt = new Devices.CRServoClass(); + private final Devices.ServoClass transfer = new Devices.ServoClass(); public enum Mode { INTAKING, @@ -16,9 +17,15 @@ public enum Mode { OFF } + public enum transferState { + UP, + DOWN + } + public void init(OpMode opmode){ intake.init(opmode, "intake"); belt.init(opmode, "belt"); + transfer.init(opmode, "transfer"); intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); intake.setDirection(DcMotorSimple.Direction.REVERSE); @@ -74,4 +81,15 @@ public Mode getMode(){ return Mode.OFF; } } + + public void setTransfer(transferState state) { + switch (state){ + case UP: + transfer.setAngle(0); + return; + case DOWN: + transfer.setAngle(90); + return; + } + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 1821920b80f7..e52b47c2b60a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -7,6 +7,7 @@ import dev.nextftc.core.commands.Command; import dev.nextftc.core.commands.utility.LambdaCommand; +import dev.nextftc.extensions.pedro.FollowPath; public class Commands { @@ -14,12 +15,11 @@ public class Commands { public static Object turretSystem = null; public static Object intakeSystem = null; - public static Command runPath(LoadHardwareClass Robot, PathChain path, boolean holdEnd) { - return new LambdaCommand("runPedroPath(" + path + ", " + holdEnd + ")") - .setInterruptible(false) - .setStart(() -> Robot.drivetrain.runPath(path, holdEnd)) - .setUpdate(() -> Robot.drivetrain.runPath(path, holdEnd)) - .setIsDone(Robot.drivetrain::pathComplete); + public static Command runPath(PathChain path, boolean holdEnd) { + return new FollowPath(path, holdEnd); + } + public static Command runPath(PathChain path, boolean holdEnd, double maxPower) { + return new FollowPath(path, holdEnd, maxPower); } public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheelstate state) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index c37851e8274a..db8db13a4511 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -34,6 +34,24 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose){ follower.update(); } + /** + * Initializes the PedroPathing follower. + * Needs to be run once after all hardware is initialized. + * @param myOpMode Allows the follower access to the robot hardware. + * @param initialPose The starting pose of the robot. + * @param follow The follower object. + */ + public void init (@NonNull OpMode myOpMode, Pose initialPose, Follower follow){ + // PedroPathing initialization + follower = follow; + paths = new Pedro_Paths(follower); + follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field + follower.update(); // Applies the initialization + + follower.startTeleopDrive(); + follower.update(); + } + /** * Uses PedroPathing's follower class to implement a mecanum drive controller. * Must be called every loop to function properly. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index be7c72f5b115..b0943a033cc5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -30,6 +30,7 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; import com.bylazar.configurables.annotations.Configurable; +import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; @@ -81,6 +82,7 @@ public LoadHardwareClass(OpMode opmode) { this.turret = new Turret(); this.intake = new Intake(); } + /** * Initializes all hardware for the robot. * Must be called once at the start of each op-mode. @@ -95,4 +97,19 @@ public void init(Pose initialPose) { myOpMode.telemetry.addData(">", "Hardware Initialized"); myOpMode.telemetry.update(); } + + /** + * Initializes all hardware for the robot. + * Must be called once at the start of each op-mode. + */ + public void init(Pose initialPose, Follower follower) { + // Initialize all subclasses + drivetrain.init(myOpMode, initialPose, follower); + turret.init(myOpMode); + intake.init(myOpMode); + + // Misc telemetry + myOpMode.telemetry.addData(">", "Hardware Initialized"); + myOpMode.telemetry.update(); + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 90d62ae7c231..7a104e78c08c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -34,6 +34,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.util.ElapsedTime; +import com.skeletonarmy.marrow.TimerEx; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -49,7 +50,10 @@ public class Teleop_Main_ extends LinearOpMode { // Declare OpMode members. private ElapsedTime runtime = new ElapsedTime(); - public static double driveExponent = 2; + // Variables for storing data for the second gamepad controls + public static double DylanStickDeadzones = 0.2; + public int shootingState = 0; + public TimerEx shootingDelay = new TimerEx(1); Prompter prompter = null; @@ -217,7 +221,6 @@ public void Gamepad1(){ * */ public void Gamepad2(){ - double DylanStickDeadzones = 0.2; //Intake Controls (Left Stick Y) if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones){ @@ -243,7 +246,36 @@ public void Gamepad2(){ } //Shoot (B Button Press) - //Statemachine cycle goes here + // Increment the shooting state + if (gamepad2.bWasPressed() && shootingState < 2 && Robot.turret.getFlywheelRPM() > 5900){shootingState++;} + switch (shootingState){ + case 0: + telemetry.addData("Shooting State", "OFF"); + return; + case 1: + Robot.intake.setMode(Intake.Mode.INTAKING); + Robot.turret.setGate(Turret.gatestate.OPEN); + telemetry.addData("Shooting State", "STARTED"); + return; + case 2: + Robot.intake.setMode(Intake.Mode.SHOOTING); + Robot.intake.setTransfer(Intake.transferState.UP); + shootingDelay.restart(); + shootingState++; + telemetry.addData("Shooting State", "TRANSFERRED"); + return; + case 3: + if (shootingDelay.isDone()){shootingState++;} + telemetry.addData("Shooting State", "DELAY"); + return; + case 4: + Robot.turret.setFlywheelRPM(0); + Robot.turret.setGate(Turret.gatestate.CLOSED); + Robot.intake.setMode(Intake.Mode.OFF); + Robot.intake.setTransfer(Intake.transferState.DOWN); + telemetry.addData("Shooting State", "RESET"); + shootingState = 0; + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 0f917490ff06..5b36f82e2c42 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -10,6 +10,7 @@ //TODO, Add proper functionality for manual turret control to Turret.java -//TODO, Shoot mode state machine Off->On->LastShot->Delay->Off etc. cycled with B button on Gamepad2 +//DONE, Shoot mode state machine Off->On->LastShot->Delay->ResetActuators->Off etc. cycled with B button on Gamepad2 +//NOTE: Let's not actually use this at the first scrimmage //TODO, add the new code structure graph, control graph, and gamepad HTML to the development branch Readme \ No newline at end of file From c0ab47e52a20cf00461d0236bf879e6a1781ce83 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Wed, 26 Nov 2025 13:55:01 -0500 Subject: [PATCH 089/152] Semi-finalized two simple auto programs --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 56 +++++++++++++++---- .../LOADCode/Main_/Hardware_/Commands.java | 30 +++++++--- 2 files changed, 65 insertions(+), 21 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index ad6aa0ef7c61..e43a98d0b0f0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -7,10 +7,16 @@ import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +import dev.nextftc.core.commands.delays.Delay; +import dev.nextftc.core.commands.delays.WaitUntil; +import dev.nextftc.core.commands.groups.ParallelGroup; +import dev.nextftc.core.commands.groups.SequentialGroup; import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; @@ -103,12 +109,25 @@ public void onUpdate() { * and goes to the leave zone next to the human player zone. */ private void Leave_Far_HP() { - //Commands.setFlywheelState(Robot, Turret.flywheelstate.ON).schedule(); -// new ParallelGroup( -// new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), -// new Delay(5) -// ); - Commands.runPath(Robot.drivetrain.paths.start2_to_leave3, true).schedule(); + new SequentialGroup( + Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), + new ParallelGroup( + new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), + new Delay(5) + ), + Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + new Delay(2), + Commands.setIntakeMode(Robot, Intake.Mode.INTAKING), + new Delay(1), + Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + new Delay(2), + Commands.setTransferState(Robot, Intake.transferState.UP), + new Delay(1), + Commands.setTransferState(Robot, Intake.transferState.DOWN), + Commands.setIntakeMode(Robot, Intake.Mode.OFF), + Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), + Commands.runPath(Robot.drivetrain.paths.start2_to_leave3, true, 0.6) + ); } /** @@ -117,11 +136,24 @@ private void Leave_Far_HP() { * and goes to the leave pose that is in the launch zone. */ private void Leave_Near_Launch() { - //Commands.setFlywheelState(Robot, Turret.flywheelstate.ON).schedule(); -// new ParallelGroup( -// new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), -// new Delay(5) -// ); - Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true).schedule(); + new SequentialGroup( + Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), + new ParallelGroup( + new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), + new Delay(5) + ), + Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + new Delay(2), + Commands.setIntakeMode(Robot, Intake.Mode.INTAKING), + new Delay(1), + Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + new Delay(2), + Commands.setTransferState(Robot, Intake.transferState.UP), + new Delay(1), + Commands.setTransferState(Robot, Intake.transferState.DOWN), + Commands.setIntakeMode(Robot, Intake.Mode.OFF), + Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), + Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true, 0.6) + ); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index e52b47c2b60a..160769e57e34 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -6,6 +6,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import dev.nextftc.core.commands.Command; +import dev.nextftc.core.commands.utility.InstantCommand; import dev.nextftc.core.commands.utility.LambdaCommand; import dev.nextftc.extensions.pedro.FollowPath; @@ -19,21 +20,32 @@ public static Command runPath(PathChain path, boolean holdEnd) { return new FollowPath(path, holdEnd); } public static Command runPath(PathChain path, boolean holdEnd, double maxPower) { - return new FollowPath(path, holdEnd, maxPower); + return new FollowPath(path, holdEnd, maxPower).requires(driveSystem); } public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheelstate state) { - return new LambdaCommand("shoot()") + return new LambdaCommand("setFlywheelState()") .setInterruptible(false) - .setUpdate(() -> Robot.turret.setFlywheel(state)) - .setIsDone(() -> Robot.turret.getFlywheelRPM() > 5900) + .setStart(() -> Robot.turret.setFlywheel(state)) + .setIsDone(() -> { + if (state == Turret.flywheelstate.ON){ + return Robot.turret.getFlywheelRPM() > 5900; + }else{ + return Robot.turret.getFlywheelRPM() < 100; + } + }) .requires(turretSystem); } - public static Command setBeltState(LoadHardwareClass Robot, Intake.Mode state) { - return new LambdaCommand("shoot()") - .setInterruptible(false) - .setUpdate(() -> Robot.intake.setMode(state)) - .requires(intakeSystem); + public static Command setIntakeMode(LoadHardwareClass Robot, Intake.Mode state) { + return new InstantCommand(new LambdaCommand("setIntakeMode()") + .setStart(() -> Robot.intake.setMode(state)) + .requires(intakeSystem)); + } + + public static Command setTransferState(LoadHardwareClass Robot, Intake.transferState state) { + return new InstantCommand(new LambdaCommand("setIntakeMode()") + .setStart(() -> Robot.intake.setTransfer(state)) + .requires(intakeSystem)); } } From 64d7d02251a3ea198a0bf7bde21d9e4902f4d71e Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 1 Dec 2025 16:33:51 -0500 Subject: [PATCH 090/152] Initial iteration of our MoveRP auto for December 6th scrimmage --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 19 +++++++++++++++---- .../Hardware_/Drivetrain_/Pedro_Paths.java | 17 +++++++++++++++++ .../ftc/teamcode/LOADCode/Notes and TODOs | 4 ++++ 3 files changed, 36 insertions(+), 4 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index e43a98d0b0f0..56db24876da7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -28,7 +28,8 @@ public class Auto_Main_ extends NextFTCOpMode { private enum Auto { LEAVE_NEAR_LAUNCH, - LEAVE_FAR_HP + LEAVE_FAR_HP, + MOVEMENT_RP_DEC6 } private Auto selectedAuto = null; @@ -57,7 +58,8 @@ public void onInit() { prompter.prompt("auto", new OptionPrompt<>("Select Auto", Auto.LEAVE_NEAR_LAUNCH, - Auto.LEAVE_FAR_HP + Auto.LEAVE_FAR_HP, + Auto.MOVEMENT_RP_DEC6 )); prompter.onComplete(() -> { selectedAlliance = prompter.get("alliance"); @@ -88,6 +90,9 @@ public void onUpdate() { case LEAVE_FAR_HP: Leave_Far_HP(); return; + case MOVEMENT_RP_DEC6: + BasicMoveRP(); + return; } switch (selectedAlliance) { case RED: @@ -127,7 +132,7 @@ private void Leave_Far_HP() { Commands.setIntakeMode(Robot, Intake.Mode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), Commands.runPath(Robot.drivetrain.paths.start2_to_leave3, true, 0.6) - ); + ).schedule(); } /** @@ -154,6 +159,12 @@ private void Leave_Near_Launch() { Commands.setIntakeMode(Robot, Intake.Mode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true, 0.6) - ); + ).schedule(); + } + + private void BasicMoveRP(){ + new SequentialGroup( + Commands.runPath(Robot.drivetrain.paths.basicMoveRPPath,true,0.6) + ).schedule(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index bfe1475adbb9..0d68f6551551 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -4,6 +4,7 @@ import com.pedropathing.geometry.BezierCurve; import com.pedropathing.geometry.BezierLine; import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.Path; import com.pedropathing.paths.PathChain; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @@ -15,6 +16,9 @@ public class Pedro_Paths { /** * Define primary poses to be used in paths */ + // Dummy Stand-In Poses + public Pose dummyStartPose = new Pose(0,0,0); + public Pose dummyMoveRPPose = new Pose(0,28,0); // Start Poses public Pose startPose1 = new Pose(112, 136.6, Math.toRadians(270)); public Pose startPose2 = new Pose(88, 7.4, Math.toRadians(90)); @@ -32,6 +36,8 @@ public class Pedro_Paths { public Pose leavePose3 = new Pose(115,20); // Define all path variables + // Dummy Paths + public PathChain basicMoveRPPath; // Start Poses to Preloads public PathChain startPose1_to_preload1, startPose1_to_preload2, startPose1_to_preload3; public PathChain startPose2_to_preload1, startPose2_to_preload2, startPose2_to_preload3; @@ -63,6 +69,16 @@ public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ ); } + /** + *

DON'T EVER USE THIS PATH!!!

+ * This path is ONLY for the December 6th scrimmage, for movement RP bonus only! + */ + public void buildMoveRPPath(){ + basicMoveRPPath = follower.pathBuilder() + .addPath(new BezierLine(dummyStartPose,dummyMoveRPPose)) + .setLinearHeadingInterpolation(dummyStartPose.getHeading(), dummyMoveRPPose.getHeading()) + .build(); + } public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { startPose1_to_preload1 = follower.pathBuilder() .addPath(new BezierCurve( @@ -395,6 +411,7 @@ public void buildStart2ToLeaves(LoadHardwareClass.Alliance alliance){ */ public void buildPaths(LoadHardwareClass.Alliance alliance){ /// All paths are for the RED side of the field. they will be mirrored if necessary. + buildMoveRPPath(); // Paths going from each start position to each of the preloads. buildStart1ToPreloads(alliance); buildStart2ToPreloads(alliance); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 5b36f82e2c42..b9325ab5810e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -6,6 +6,8 @@ //DONE, Consolidate the generic actuator functionalities folder into one file +//TODO, Organize telemetry before adding proper telem system + //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging //TODO, Add proper functionality for manual turret control to Turret.java @@ -13,4 +15,6 @@ //DONE, Shoot mode state machine Off->On->LastShot->Delay->ResetActuators->Off etc. cycled with B button on Gamepad2 //NOTE: Let's not actually use this at the first scrimmage +//TODO, + //TODO, add the new code structure graph, control graph, and gamepad HTML to the development branch Readme \ No newline at end of file From 1da51d2d8fc1b54a2ca4a7b2cd9ea6700a09224e Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 1 Dec 2025 16:41:54 -0500 Subject: [PATCH 091/152] Worked on tuning Flywheel PID --- TeamCode/build.gradle | 1 + .../Main_/Hardware_/Actuators_/Turret.java | 13 ++++++++----- .../Main_/Teleop_/Teleop_Outreach_.java | 19 +++++++++++++++++++ 3 files changed, 28 insertions(+), 5 deletions(-) diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index 096457396ebb..dd6160908114 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -28,4 +28,5 @@ dependencies { implementation 'io.github.skeleton-army.marrow:core:0.1.2' implementation 'dev.nextftc:ftc:1.0.1' implementation 'dev.nextftc.extensions:pedro:1.0.0' + implementation "com.bylazar:graph:1.0.4" } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 649667774cfa..5b40c314998c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -1,5 +1,6 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; +import com.bylazar.configurables.annotations.Configurable; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotor; @@ -9,7 +10,7 @@ import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; - +@Configurable public class Turret { @@ -19,8 +20,8 @@ public class Turret { public final Devices.ServoClass gate = new Devices.ServoClass(); public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); - public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0, 0, 0); - public static BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); + public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0, 0.1); + public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.005,0,0); public enum gatestate { OPEN, @@ -40,19 +41,21 @@ public void init(OpMode opmode){ rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); + flywheel.ticksPerRotation = 28; + gate.setAngle(0.5); // Pass PID pidCoefficients to motor classes rotation.setPidCoefficients(turretCoefficients); flywheel.setPidCoefficients(flywheelCoefficients); - flywheel.setFFCoefficients(ffCoefficients); + flywheel.setFFCoefficients(flywheelFFCoefficients); } public void updatePIDs(){ // Pass PID pidCoefficients to motor classes rotation.setPidCoefficients(turretCoefficients); flywheel.setPidCoefficients(flywheelCoefficients); - flywheel.setFFCoefficients(ffCoefficients); + flywheel.setFFCoefficients(flywheelFFCoefficients); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index 9eac8bfc9745..2001be2512c9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -29,6 +29,10 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; +import android.provider.Settings; + +import com.bylazar.telemetry.PanelsTelemetry; +import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; @@ -43,6 +47,7 @@ public class Teleop_Outreach_ extends LinearOpMode { // Declare OpMode members. private ElapsedTime runtime = new ElapsedTime(); + private TelemetryManager.TelemetryWrapper panelsTelemetry = PanelsTelemetry.INSTANCE.getFtcTelemetry(); // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); @@ -72,6 +77,20 @@ public void runOpMode() { gamepad1.right_stick_x/2, true ); + if (gamepad1.b){ + Robot.turret.setFlywheelRPM(6000); + }else if (gamepad1.y){ + Robot.turret.setFlywheelRPM(500); + }else{ + Robot.turret.setFlywheelRPM(0); + } + + Robot.turret.updatePIDs(); + + telemetry.addData("FlywheelState", Robot.turret.getFlywheel()); + telemetry.addData("FlywheelRPM", Robot.turret.getFlywheelRPM()); + panelsTelemetry.addData("FlywheelRPM", Robot.turret.getFlywheelRPM()); + // System-related Telemetry telemetry.addLine(); From 902ab79e5c15fedb6da5c2f1c6827d2e1ac5a2fb Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 1 Dec 2025 18:12:05 -0500 Subject: [PATCH 092/152] Began adding Dylan's December 6th controls, all the info needed to finish them is in my documentation. --- .../Main_/Hardware_/Actuators_/Intake.java | 7 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 103 ++++++++++++++++++ .../ftc/teamcode/LOADCode/Notes and TODOs | 6 +- 3 files changed, 111 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 276819857146..c01901f55356 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -6,9 +6,10 @@ public class Intake { - private final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); - private final Devices.CRServoClass belt = new Devices.CRServoClass(); - private final Devices.ServoClass transfer = new Devices.ServoClass(); + // RESET THESE TO PRIVATE AFTER DECEMBER 6TH! + public final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); + public final Devices.CRServoClass belt = new Devices.CRServoClass(); + public final Devices.ServoClass transfer = new Devices.ServoClass(); public enum Mode { INTAKING, diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 7a104e78c08c..63212dbed41d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -278,5 +278,108 @@ public void Gamepad2(){ } + } + + /** + *

Gamepad 2 Controls (December 6th Scrimmage)

+ *
    + *
  • Analog Inputs
      + *
    • Left Stick:
        + *
      • X: Tranfer Belt IN ONLY
      • + *
      • Y: Intake Direction/Power
      • + *
    • + *
    • Right Stick:
        + *
      • X: N/A
      • + *
      • Y: N/A
      • + *
    • + *
    • Left Trigger: N/A
    • + *
    • Right Trigger: N/A
    • + *
  • + * + *
  • Button Inputs
    • + *
    • Letter Buttons:
        + *
      • A: N/A
      • + *
      • B: Kicker/Flap/Feeder
      • + *
      • X: N/A
      • + *
      • Y: Flywheel Toggle
      • + *
    • + *
    • Letter Buttons:
        + *
      • DpadUp: N/A
      • + *
      • DpadDown: N/A
      • + *
      • DpadLeft: N/A
      • + *
      • DpadRight: N/A
      • + *
    • + *
    • Bumpers:
        + *
      • Left Bumper: N/A
      • + *
      • Right Bumper: N/A
      • + *
    • + *
    • Stick Buttons:
        + *
      • Left Stick Button: N/A
      • + *
      • Right Stick Button: N/A
      • + *
    • + *
    + *
+ */ + public void Gamepad2Dec6(){ + + //Intake Controls (Left Stick Y) + if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones){ + Robot.intake.intake.setPower(gamepad2.left_stick_y); + } else { // OFF + Robot.intake.setMode(Intake.Mode.OFF); + } + + //Transfer Belt (ABS Left Stick X) + if (Math.abs(gamepad2.left_stick_x) >= DylanStickDeadzones) { + Robot.intake.belt.setPower(Math.abs(gamepad2.left_stick_x)); + } else { // OFF + Robot.intake.belt.setPower(0); + } + + //Turret Angle Controls (Right Stick X) + //To be added after manual control is finished + + //Flywheel Toggle Control (Y Button) + if (gamepad2.yWasPressed()){ + if (Robot.turret.getFlywheel() == Turret.flywheelstate.OFF){ + Robot.turret.setFlywheel(Turret.flywheelstate.ON); + } else { + Robot.turret.setFlywheel(Turret.flywheelstate.OFF); + } + } + + //Kicker Flapper (B Button Press) + // Increment the shooting state + if (gamepad2.bWasPressed() && shootingState < 2 && Robot.turret.getFlywheelRPM() > 5900){shootingState++;} + switch (shootingState){ + case 0: + telemetry.addData("Shooting State", "OFF"); + return; + case 1: + Robot.intake.setMode(Intake.Mode.INTAKING); + Robot.turret.setGate(Turret.gatestate.OPEN); + telemetry.addData("Shooting State", "STARTED"); + return; + case 2: + Robot.intake.setMode(Intake.Mode.SHOOTING); + Robot.intake.setTransfer(Intake.transferState.UP); + shootingDelay.restart(); + shootingState++; + telemetry.addData("Shooting State", "TRANSFERRED"); + return; + case 3: + if (shootingDelay.isDone()){shootingState++;} + telemetry.addData("Shooting State", "DELAY"); + return; + case 4: + Robot.turret.setFlywheelRPM(0); + Robot.turret.setGate(Turret.gatestate.CLOSED); + Robot.intake.setMode(Intake.Mode.OFF); + Robot.intake.setTransfer(Intake.transferState.DOWN); + telemetry.addData("Shooting State", "RESET"); + shootingState = 0; + } + + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index b9325ab5810e..78ce800a3c1d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -15,6 +15,8 @@ //DONE, Shoot mode state machine Off->On->LastShot->Delay->ResetActuators->Off etc. cycled with B button on Gamepad2 //NOTE: Let's not actually use this at the first scrimmage -//TODO, +//TODO, Reset the belt, intake, & transfer kicker back to private after December 6th -//TODO, add the new code structure graph, control graph, and gamepad HTML to the development branch Readme \ No newline at end of file +//TODO, add the new code structure graph, control graph, and gamepad HTML to the development branch Readme + +//TODO, Finish translating Dylan's December 6th controls into the program. \ No newline at end of file From 1340ba216a11ef26bc81156c5fb28db5a474c2a1 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 1 Dec 2025 20:58:51 -0500 Subject: [PATCH 093/152] Finalized Dec. 6th Flywheel PID and added Panels telemetry system. --- .../Main_/Hardware_/Actuators_/Turret.java | 4 ++-- .../LOADCode/Main_/Teleop_/Teleop_Outreach_.java | 14 ++++++-------- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 5b40c314998c..5be7d391857f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -20,8 +20,8 @@ public class Turret { public final Devices.ServoClass gate = new Devices.ServoClass(); public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); - public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0, 0.1); - public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.005,0,0); + public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0.0001, 0.0001); + public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.00002899,0,0); public enum gatestate { OPEN, diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index 2001be2512c9..9ce440677324 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -29,8 +29,6 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; -import android.provider.Settings; - import com.bylazar.telemetry.PanelsTelemetry; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.geometry.Pose; @@ -47,7 +45,7 @@ public class Teleop_Outreach_ extends LinearOpMode { // Declare OpMode members. private ElapsedTime runtime = new ElapsedTime(); - private TelemetryManager.TelemetryWrapper panelsTelemetry = PanelsTelemetry.INSTANCE.getFtcTelemetry(); + private TelemetryManager panelsTelemetry = PanelsTelemetry.INSTANCE.getTelemetry(); // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); @@ -77,18 +75,17 @@ public void runOpMode() { gamepad1.right_stick_x/2, true ); - if (gamepad1.b){ - Robot.turret.setFlywheelRPM(6000); - }else if (gamepad1.y){ - Robot.turret.setFlywheelRPM(500); + if (gamepad1.x){ + Robot.turret.setFlywheelRPM(5485.714285714286); + panelsTelemetry.addData("SetRPM", 5485.714285714286); }else{ Robot.turret.setFlywheelRPM(0); + panelsTelemetry.addData("SetRPM", 0); } Robot.turret.updatePIDs(); telemetry.addData("FlywheelState", Robot.turret.getFlywheel()); - telemetry.addData("FlywheelRPM", Robot.turret.getFlywheelRPM()); panelsTelemetry.addData("FlywheelRPM", Robot.turret.getFlywheelRPM()); @@ -97,6 +94,7 @@ public void runOpMode() { telemetry.addData("Status", "Run Time: " + runtime.toString()); telemetry.addData("Version: ", "11/4/25"); telemetry.update(); + panelsTelemetry.update(telemetry); //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging } } From 341fef5d0d5de158ede5eac596cc6b8efee8ee3a Mon Sep 17 00:00:00 2001 From: Professor348 Date: Tue, 2 Dec 2025 10:23:02 -0500 Subject: [PATCH 094/152] Possibly fixed NextFTC runPath command (will test at next meeting) --- .../ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index ad6aa0ef7c61..0ae7380e2854 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -33,14 +33,17 @@ private enum Auto { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); + public Auto_Main_(){ + addComponents( + new PedroComponent(Constants::createFollower) + ); + } + @Override public void onInit() { // Initialize all hardware of the robot Robot.init(startPose); - - addComponents( - new PedroComponent(Constants::createFollower) - ); + Robot.drivetrain.follower = PedroComponent.follower(); prompter = new Prompter(this); prompter.prompt("alliance", From eb325f8009e657360e5f3c993266ab902f29454a Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Dec 2025 12:50:23 -0500 Subject: [PATCH 095/152] Bugfixed a few issues in Dec. 6th controls function. --- .../Main_/Hardware_/Actuators_/Turret.java | 27 +++++++++---------- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 11 ++++---- 2 files changed, 18 insertions(+), 20 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 5be7d391857f..9579dfb1bcfc 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -32,6 +32,7 @@ public enum flywheelstate { ON, OFF } + public flywheelstate flywheelState = flywheelstate.OFF; public void init(OpMode opmode){ rotation.init(opmode, "turret", 145.1); //Previously 103.8 @@ -115,26 +116,22 @@ public double getFlywheelRPM(){ return flywheel.getRPM(); } + /** + * Sets the target state of the Flywheel + * @param state The state to set the flywheel to (ON/OFF) + */ public void setFlywheel(flywheelstate state){ - if (state == flywheelstate.ON){ - setFlywheelRPM(6000); - } else if (state == flywheelstate.OFF){ - setFlywheelRPM(0); - } + flywheelState = state; } /** - * Outputs one of the following modes - *
    - *
  • flywheelstate.OFF
  • - *
  • flywheelstate.RUNNING
  • - *
+ * Updates the flywheel PID. Must be called every loop. */ - public flywheelstate getFlywheel(){ - if (getFlywheelRPM() == 0.0){ - return flywheelstate.OFF; - } else { - return flywheelstate.ON; + public void updateFlywheel(){ + if (flywheelState == flywheelstate.ON){ + setFlywheelRPM(5485.714285714286); + } else if (flywheelState == flywheelstate.OFF){ + setFlywheelRPM(0); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 63212dbed41d..60054ced100c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -238,7 +238,7 @@ public void Gamepad2(){ //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()){ - if (Robot.turret.getFlywheel() == Turret.flywheelstate.OFF){ + if (Robot.turret.flywheelState == Turret.flywheelstate.OFF){ Robot.turret.setFlywheel(Turret.flywheelstate.ON); } else { Robot.turret.setFlywheel(Turret.flywheelstate.OFF); @@ -326,7 +326,7 @@ public void Gamepad2Dec6(){ if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones){ Robot.intake.intake.setPower(gamepad2.left_stick_y); } else { // OFF - Robot.intake.setMode(Intake.Mode.OFF); + Robot.intake.intake.setPower(0); } //Transfer Belt (ABS Left Stick X) @@ -341,12 +341,13 @@ public void Gamepad2Dec6(){ //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()){ - if (Robot.turret.getFlywheel() == Turret.flywheelstate.OFF){ - Robot.turret.setFlywheel(Turret.flywheelstate.ON); - } else { + if (Robot.turret.flywheelState == Turret.flywheelstate.ON){ Robot.turret.setFlywheel(Turret.flywheelstate.OFF); + }else if (Robot.turret.flywheelState == Turret.flywheelstate.OFF){ + Robot.turret.setFlywheel(Turret.flywheelstate.ON); } } + Robot.turret.updateFlywheel(); //Kicker Flapper (B Button Press) // Increment the shooting state From 18bba20a9555a2745118ac55835753942718d454 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Dec 2025 18:32:59 -0500 Subject: [PATCH 096/152] Completed Dec6th Auto, & finalized controls for Dec 6th Scrimmage --- .../LOADCode/Main_/Auto_/Auto_Dec6th.java | 73 +++++++++++++++++++ .../LOADCode/Main_/Auto_/Auto_Main_.java | 67 ++++++++--------- .../LOADCode/Main_/Auto_/TestAuto.java | 2 + .../Main_/Hardware_/Actuators_/Devices.java | 3 + .../Main_/Hardware_/Actuators_/Intake.java | 3 +- .../LOADCode/Main_/Hardware_/Commands.java | 2 +- .../Drivetrain_/MecanumDrivetrainClass.java | 4 +- .../Hardware_/Drivetrain_/Pedro_Paths.java | 3 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 73 ++++++++----------- .../Main_/Teleop_/Teleop_Outreach_.java | 2 +- .../ftc/teamcode/LOADCode/Notes and TODOs | 5 +- 11 files changed, 150 insertions(+), 87 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java new file mode 100644 index 000000000000..c1fae0517a70 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java @@ -0,0 +1,73 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Auto_; // make sure this aligns with class location + +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; + +@Autonomous(name = "Auto_Dec6th", group = "TestAuto", preselectTeleOp="Teleop_Main_") +public class Auto_Dec6th extends OpMode { + + DcMotorEx FL; + DcMotorEx FR; + DcMotorEx BL; + DcMotorEx BR; + + /** + * Copied over from LinearOpMode. + * @param milliseconds The number of milliseconds to sleep. + */ + public final void sleep(long milliseconds) { + try { + Thread.sleep(milliseconds); + } catch (InterruptedException e) { + Thread.currentThread().interrupt(); + } + } + + /** This method is called once at the init of the OpMode. **/ + @Override + public void init() { + FL = hardwareMap.get(DcMotorEx.class, "FL"); + FR = hardwareMap.get(DcMotorEx.class, "FR"); + BL = hardwareMap.get(DcMotorEx.class, "BL"); + BR = hardwareMap.get(DcMotorEx.class, "BR"); + + FL.setDirection(DcMotorSimple.Direction.REVERSE); + BL.setDirection(DcMotorSimple.Direction.REVERSE); + } + + /** This method is called continuously after Init while waiting for "play". **/ + @Override + public void init_loop() { + + } + + /** This method is called once at the start of the OpMode. + * It runs all the setup actions, including building paths and starting the path system **/ + @Override + public void start() { + sleep(25000); + FL.setPower(0.3); + FR.setPower(0.3); + BL.setPower(0.3); + BR.setPower(0.3); + sleep(1700); + FL.setPower(0); + FR.setPower(0); + BL.setPower(0); + BR.setPower(0); + } + + /** This is the main loop of the OpMode, it will run repeatedly after clicking "Play". **/ + @Override + public void loop() { + + } + + /** We do not use this because everything should automatically disable **/ + @Override + public void stop() { + + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 410704ee4870..45ccb6d84d3f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -4,6 +4,7 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -13,6 +14,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +import dev.nextftc.core.commands.Command; import dev.nextftc.core.commands.delays.Delay; import dev.nextftc.core.commands.delays.WaitUntil; import dev.nextftc.core.commands.groups.ParallelGroup; @@ -20,6 +22,7 @@ import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; +@Disabled @Autonomous(name = "Auto_Main_", group = "Main", preselectTeleOp="Teleop_Main_") public class Auto_Main_ extends NextFTCOpMode { @@ -33,6 +36,7 @@ private enum Auto { } private Auto selectedAuto = null; + private boolean turretOn = false; // Create the prompter object for selecting Alliance and Auto Prompter prompter = null; @@ -40,15 +44,12 @@ private enum Auto { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); - public Auto_Main_(){ - addComponents( - new PedroComponent(Constants::createFollower) - ); - } - @Override public void onInit() { // Initialize all hardware of the robot + addComponents( + new PedroComponent(Constants::createFollower) + ); Robot.init(startPose); Robot.drivetrain.follower = PedroComponent.follower(); @@ -80,30 +81,28 @@ public void onWaitForStart() { @Override public void onStartButtonPressed() { - // Initialize all hardware of the robot - Robot.init(startPose, PedroComponent.follower()); - } - - @Override - public void onUpdate() { + // Schedule the proper auto switch (selectedAuto) { case LEAVE_NEAR_LAUNCH: - Leave_Near_Launch(); + Leave_Near_Launch().invoke(); return; case LEAVE_FAR_HP: - Leave_Far_HP(); - return; - case MOVEMENT_RP_DEC6: - BasicMoveRP(); + Leave_Far_HP().invoke(); return; } - switch (selectedAlliance) { - case RED: - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); - return; - case BLUE: - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); - return; + } + + @Override + public void onUpdate() { + if (turretOn){ + switch (selectedAlliance) { + case RED: + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); + return; + case BLUE: + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); + return; + } } telemetry.addData("selectedAuto", selectedAuto); @@ -116,8 +115,9 @@ public void onUpdate() { * shoots it's preloads after 5 seconds, * and goes to the leave zone next to the human player zone. */ - private void Leave_Far_HP() { - new SequentialGroup( + private Command Leave_Far_HP() { + turretOn = true; + return new SequentialGroup( Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new ParallelGroup( new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), @@ -135,7 +135,7 @@ private void Leave_Far_HP() { Commands.setIntakeMode(Robot, Intake.Mode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), Commands.runPath(Robot.drivetrain.paths.start2_to_leave3, true, 0.6) - ).schedule(); + ); } /** @@ -143,8 +143,9 @@ private void Leave_Far_HP() { * shoots it's preloads after 5 seconds, * and goes to the leave pose that is in the launch zone. */ - private void Leave_Near_Launch() { - new SequentialGroup( + private Command Leave_Near_Launch() { + turretOn = true; + return new SequentialGroup( Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new ParallelGroup( new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), @@ -162,12 +163,6 @@ private void Leave_Near_Launch() { Commands.setIntakeMode(Robot, Intake.Mode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true, 0.6) - ).schedule(); - } - - private void BasicMoveRP(){ - new SequentialGroup( - Commands.runPath(Robot.drivetrain.paths.basicMoveRPPath,true,0.6) - ).schedule(); + ); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java index 0beef87c1783..3c1739e9678e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/TestAuto.java @@ -7,6 +7,7 @@ import com.pedropathing.paths.PathChain; import com.pedropathing.util.Timer; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -14,6 +15,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +@Disabled @Autonomous(name = "TestAutoR1", group = "TestAuto", preselectTeleOp="Teleop_Main_") public class TestAuto extends OpMode { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java index 3541e4b84685..f664d27fd09d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -121,6 +121,9 @@ public void setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior behaviour){ public void setDirection(DcMotorSimple.Direction direction){ motorObject.setDirection(direction); } + public void setEncoderTicks(int ticks){ + motorObject.setTargetPosition(ticks); + } /** * @return The current position of the turret motor in encoder ticks. Can be any value. */ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index c01901f55356..30d827000a53 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -89,8 +89,7 @@ public void setTransfer(transferState state) { transfer.setAngle(0); return; case DOWN: - transfer.setAngle(90); - return; + transfer.setAngle(.05); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 160769e57e34..49131376c7c5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -17,7 +17,7 @@ public class Commands { public static Object intakeSystem = null; public static Command runPath(PathChain path, boolean holdEnd) { - return new FollowPath(path, holdEnd); + return new FollowPath(path, holdEnd).requires(driveSystem); } public static Command runPath(PathChain path, boolean holdEnd, double maxPower) { return new FollowPath(path, holdEnd, maxPower).requires(driveSystem); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index db8db13a4511..f5545637f4d9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -28,7 +28,7 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose){ follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower paths = new Pedro_Paths(follower); follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field - follower.update(); // Applies the initialization + follower.update(); // Applies the initialization follower.startTeleopDrive(); follower.update(); @@ -46,7 +46,7 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose, Follower follow){ follower = follow; paths = new Pedro_Paths(follower); follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field - follower.update(); // Applies the initialization + follower.update(); // Applies the initialization follower.startTeleopDrive(); follower.update(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index 0d68f6551551..d45fa0c3d763 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -4,7 +4,6 @@ import com.pedropathing.geometry.BezierCurve; import com.pedropathing.geometry.BezierLine; import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.Path; import com.pedropathing.paths.PathChain; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @@ -75,7 +74,7 @@ public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ */ public void buildMoveRPPath(){ basicMoveRPPath = follower.pathBuilder() - .addPath(new BezierLine(dummyStartPose,dummyMoveRPPose)) + .addPath(new BezierCurve(dummyStartPose,dummyMoveRPPose)) .setLinearHeadingInterpolation(dummyStartPose.getHeading(), dummyMoveRPPose.getHeading()) .build(); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 60054ced100c..9fde0019cdff 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -30,6 +30,8 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; import com.bylazar.configurables.annotations.Configurable; +import com.bylazar.telemetry.PanelsTelemetry; +import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; @@ -49,6 +51,7 @@ public class Teleop_Main_ extends LinearOpMode { // Declare OpMode members. private ElapsedTime runtime = new ElapsedTime(); + private TelemetryManager panelsTelemetry = PanelsTelemetry.INSTANCE.getTelemetry(); // Variables for storing data for the second gamepad controls public static double DylanStickDeadzones = 0.2; @@ -97,18 +100,29 @@ public void runOpMode() { while (opModeIsActive()) { Gamepad1(); - Gamepad2(); + Gamepad2Dec6(); Robot.turret.updatePIDs(); telemetry.addData("SpeedMult", Robot.drivetrain.speedMultiplier); + telemetry.addLine(); // Turret-related Telemetry telemetry.addData("Turret Target Angle:", Robot.turret.rotation.target); telemetry.addData("Turret Actual Angle", Robot.turret.rotation.getAngleAbsolute()); + telemetry.addLine(); + panelsTelemetry.addData("Flywheel Target Speed", Robot.turret.flywheel.target); + panelsTelemetry.addData("Flywheel Actual Speed", Robot.turret.getFlywheelRPM()); + telemetry.addData("Flywheel Target Speed", Robot.turret.flywheel.target); + telemetry.addData("Flywheel Actual Speed", Robot.turret.getFlywheelRPM()); + + telemetry.addLine(); + telemetry.addData("Belt Power", Robot.intake.belt.getPower()); + + // Intake-related Telemetry telemetry.addLine(); - telemetry.addData("Intake Status", Robot.intake.getMode()); + telemetry.addData("Intake Status", Robot.intake.intake.getPower()); // System-related Telemetry telemetry.addLine(); @@ -329,15 +343,26 @@ public void Gamepad2Dec6(){ Robot.intake.intake.setPower(0); } - //Transfer Belt (ABS Left Stick X) - if (Math.abs(gamepad2.left_stick_x) >= DylanStickDeadzones) { - Robot.intake.belt.setPower(Math.abs(gamepad2.left_stick_x)); + //Transfer Belt (ABS Right Stick Y) + if (Math.abs(gamepad2.right_stick_y) >= DylanStickDeadzones) { + Robot.intake.belt.setPower(Math.abs(gamepad2.right_stick_y)); } else { // OFF Robot.intake.belt.setPower(0); } - //Turret Angle Controls (Right Stick X) - //To be added after manual control is finished + // Gate control + if (Robot.turret.getFlywheelRPM() > 3000){ + Robot.turret.setGate(Turret.gatestate.OPEN); + }else{ + Robot.turret.setGate(Turret.gatestate.CLOSED); + } + + // Transfer control + if (gamepad2.b){ + Robot.intake.setTransfer(Intake.transferState.UP); + }else{ + Robot.intake.setTransfer(Intake.transferState.DOWN); + } //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()){ @@ -348,39 +373,5 @@ public void Gamepad2Dec6(){ } } Robot.turret.updateFlywheel(); - - //Kicker Flapper (B Button Press) - // Increment the shooting state - if (gamepad2.bWasPressed() && shootingState < 2 && Robot.turret.getFlywheelRPM() > 5900){shootingState++;} - switch (shootingState){ - case 0: - telemetry.addData("Shooting State", "OFF"); - return; - case 1: - Robot.intake.setMode(Intake.Mode.INTAKING); - Robot.turret.setGate(Turret.gatestate.OPEN); - telemetry.addData("Shooting State", "STARTED"); - return; - case 2: - Robot.intake.setMode(Intake.Mode.SHOOTING); - Robot.intake.setTransfer(Intake.transferState.UP); - shootingDelay.restart(); - shootingState++; - telemetry.addData("Shooting State", "TRANSFERRED"); - return; - case 3: - if (shootingDelay.isDone()){shootingState++;} - telemetry.addData("Shooting State", "DELAY"); - return; - case 4: - Robot.turret.setFlywheelRPM(0); - Robot.turret.setGate(Turret.gatestate.CLOSED); - Robot.intake.setMode(Intake.Mode.OFF); - Robot.intake.setTransfer(Intake.transferState.DOWN); - telemetry.addData("Shooting State", "RESET"); - shootingState = 0; - } - - } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index 9ce440677324..ebf6e3cb7833 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -85,7 +85,7 @@ public void runOpMode() { Robot.turret.updatePIDs(); - telemetry.addData("FlywheelState", Robot.turret.getFlywheel()); + telemetry.addData("FlywheelState", Robot.turret.flywheelState); panelsTelemetry.addData("FlywheelRPM", Robot.turret.getFlywheelRPM()); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 78ce800a3c1d..8dae2b096875 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -13,10 +13,11 @@ //TODO, Add proper functionality for manual turret control to Turret.java //DONE, Shoot mode state machine Off->On->LastShot->Delay->ResetActuators->Off etc. cycled with B button on Gamepad2 -//NOTE: Let's not actually use this at the first scrimmage //TODO, Reset the belt, intake, & transfer kicker back to private after December 6th //TODO, add the new code structure graph, control graph, and gamepad HTML to the development branch Readme -//TODO, Finish translating Dylan's December 6th controls into the program. \ No newline at end of file +//DONE, Finish translating Dylan's December 6th controls into the program. + +//TODO, Figure out how to use NextFTC's Pedropathing extension for auto. \ No newline at end of file From 081ae9bfc067060fb7fc2e380729822e0bb202f9 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 2 Dec 2025 20:24:56 -0500 Subject: [PATCH 097/152] Got NextFTC's command pathing working, did not use on dec6th auto. --- .../LOADCode/Main_/Auto_/Auto_Dec6th.java | 25 +++++++- .../LOADCode/Main_/Auto_/Auto_Main_.java | 47 ++++++++++----- .../Auto_/NextFTC_Pedro_Example_Auto.java | 54 +++++++++++++++++ .../LOADCode/Main_/Hardware_/Commands.java | 4 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 60 +++++++++++++++++++ .../Main_/Teleop_/Teleop_Outreach_.java | 16 ----- .../ftc/teamcode/pedroPathing/Constants.java | 4 +- 7 files changed, 174 insertions(+), 36 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/NextFTC_Pedro_Example_Auto.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java index c1fae0517a70..a50fec1b7185 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java @@ -1,9 +1,15 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Auto_; // make sure this aligns with class location +import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; + import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.skeletonarmy.marrow.prompts.OptionPrompt; +import com.skeletonarmy.marrow.prompts.Prompter; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @Autonomous(name = "Auto_Dec6th", group = "TestAuto", preselectTeleOp="Teleop_Main_") public class Auto_Dec6th extends OpMode { @@ -13,6 +19,9 @@ public class Auto_Dec6th extends OpMode { DcMotorEx BL; DcMotorEx BR; + // Create the prompter object for selecting Alliance and Auto + Prompter prompter = null; + /** * Copied over from LinearOpMode. * @param milliseconds The number of milliseconds to sleep. @@ -35,12 +44,26 @@ public void init() { FL.setDirection(DcMotorSimple.Direction.REVERSE); BL.setDirection(DcMotorSimple.Direction.REVERSE); + + prompter = new Prompter(this); + prompter.prompt("alliance", + new OptionPrompt<>("Select Alliance", + LoadHardwareClass.Alliance.RED, + LoadHardwareClass.Alliance.BLUE + )); + prompter.onComplete(() -> { + selectedAlliance = prompter.get("alliance"); + telemetry.addData("Selection", "Complete"); + telemetry.addData("Alliance", selectedAlliance); + telemetry.update(); + } + ); } /** This method is called continuously after Init while waiting for "play". **/ @Override public void init_loop() { - + prompter.run(); } /** This method is called once at the start of the OpMode. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 45ccb6d84d3f..dac8c7759eb7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -11,6 +11,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @@ -19,6 +20,7 @@ import dev.nextftc.core.commands.delays.WaitUntil; import dev.nextftc.core.commands.groups.ParallelGroup; import dev.nextftc.core.commands.groups.SequentialGroup; +import dev.nextftc.extensions.pedro.FollowPath; import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; @@ -27,7 +29,7 @@ public class Auto_Main_ extends NextFTCOpMode { // Define other PedroPathing constants - private final Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. + private Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. private enum Auto { LEAVE_NEAR_LAUNCH, @@ -44,12 +46,15 @@ private enum Auto { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); - @Override - public void onInit() { - // Initialize all hardware of the robot + public Auto_Main_() { addComponents( new PedroComponent(Constants::createFollower) ); + } + + @Override + public void onInit() { + // Initialize all hardware of the robot Robot.init(startPose); Robot.drivetrain.follower = PedroComponent.follower(); @@ -69,6 +74,9 @@ public void onInit() { selectedAlliance = prompter.get("alliance"); selectedAuto = prompter.get("auto"); telemetry.addData("Selection", "Complete"); + telemetry.addData("Alliance", selectedAlliance); + telemetry.addData("Auto", selectedAuto); + telemetry.update(); } ); Robot.drivetrain.paths.buildPaths(selectedAlliance); @@ -84,25 +92,28 @@ public void onStartButtonPressed() { // Schedule the proper auto switch (selectedAuto) { case LEAVE_NEAR_LAUNCH: - Leave_Near_Launch().invoke(); + Leave_Near_Launch().schedule(); + startPose = new Pose(0,0,0); return; case LEAVE_FAR_HP: - Leave_Far_HP().invoke(); + Leave_Far_HP().schedule(); + startPose = new Pose(0,0,0); return; + case MOVEMENT_RP_DEC6: + Movement_RP_Dec6th().schedule(); + startPose = new Pose(0,0,0); } } @Override public void onUpdate() { - if (turretOn){ - switch (selectedAlliance) { - case RED: - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); - return; - case BLUE: - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); - return; - } + switch (selectedAlliance) { + case RED: + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); + return; + case BLUE: + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); + return; } telemetry.addData("selectedAuto", selectedAuto); @@ -165,4 +176,10 @@ private Command Leave_Near_Launch() { Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true, 0.6) ); } + + private Command Movement_RP_Dec6th(){ + return new SequentialGroup( + new FollowPath(Robot.drivetrain.paths.basicMoveRPPath, true, 0.5) + ); + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/NextFTC_Pedro_Example_Auto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/NextFTC_Pedro_Example_Auto.java new file mode 100644 index 000000000000..bcbe78d74df4 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/NextFTC_Pedro_Example_Auto.java @@ -0,0 +1,54 @@ +//package org.firstinspires.ftc.teamcode.LOADCode.Main_.Auto_; +// +//import com.acmerobotics.roadrunner.path.BezierLine; +//import com.pedropathing.geometry.Pose; +//import com.pedropathing.paths.PathChain; +//import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +// +//import org.firstinspires.ftc.teamcode.pedroPathing.Constants; +// +//import dev.nextftc.core.commands.groups.SequentialGroup; +//import dev.nextftc.core.components.SubsystemComponent; +//import dev.nextftc.extensions.pedro.FollowPath; +//import dev.nextftc.extensions.pedro.PedroComponent; +//import dev.nextftc.ftc.NextFTCOpMode; +// +//@Autonomous(name = "blueBottom") +//public class NextFTC_Pedro_Example_Auto extends NextFTCOpMode { +// private final Pose startPose = new Pose(85.5, 8.3, Math.toRadians(90.0)); +// private final Pose depositPose = new Pose(84.3, 61.9, Math.toRadians(0.0)); +// private final Pose curvePoint = new Pose(138.2, 48.1); +// +// private PathChain skib; +// +// public NextFTC_Pedro_Example_Auto() { +// addComponents( +// new PedroComponent(Constants::createFollower) +// ); +// } +// +// private void buildPaths() { +// skib = follower.pathBuilder() +// .addPath(new BezierLine(startPose, depositPose)) +// .setLinearHeadingInterpolation(startPose.heading, depositPose.heading) +// .build(); +// } +// +// public Command getSecondRoutine() { +// return new SequentialGroup( +// new FollowPath(skib) +// ); +// } +// +// @Override +// public void onInit() { +// follower.setMaxPower(0.7); +// follower.setStartingPose(startPose); +// buildPaths(); +// } +// +// @Override +// public void onStartButtonPressed() { +// getSecondRoutine().run(); +// } +//} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 49131376c7c5..d363fa3a21ff 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -17,10 +17,10 @@ public class Commands { public static Object intakeSystem = null; public static Command runPath(PathChain path, boolean holdEnd) { - return new FollowPath(path, holdEnd).requires(driveSystem); + return new FollowPath(path, holdEnd); } public static Command runPath(PathChain path, boolean holdEnd, double maxPower) { - return new FollowPath(path, holdEnd, maxPower).requires(driveSystem); + return new FollowPath(path, holdEnd, maxPower); } public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheelstate state) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 9fde0019cdff..3c2a398a3c67 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -57,6 +57,7 @@ public class Teleop_Main_ extends LinearOpMode { public static double DylanStickDeadzones = 0.2; public int shootingState = 0; public TimerEx shootingDelay = new TimerEx(1); + public static double autoaimmultiplier = 100; Prompter prompter = null; @@ -194,6 +195,65 @@ public void Gamepad1(){ ); } + public void Gamepad1Dec6(){ + + Robot.drivetrain.speedMultiplier = 0.66; + if (gamepad1.left_trigger >= 0.5) { + Robot.drivetrain.speedMultiplier -= 0.33; + } + if (gamepad1.right_trigger >= 0.5){ + Robot.drivetrain.speedMultiplier += 0.33; + } + + double turnPower = gamepad1.right_stick_x; + double turnMult = 2; + if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ + turnMult = 1; + } + turnPower = turnPower/turnMult; + + double targetHeading = 0; + telemetry.addData("Alliance", LoadHardwareClass.selectedAlliance); + if (gamepad1.right_stick_button){ + switch (LoadHardwareClass.selectedAlliance){ + case RED: + turnPower = Robot.drivetrain.follower.getHeading() - + Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), false); + targetHeading = Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), false); + telemetry.addData("Pose", Robot.drivetrain.follower.getPose()); + telemetry.addData("Target Heading", targetHeading); + return; + case BLUE: + turnPower = Robot.drivetrain.follower.getHeading() - + Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true); + targetHeading = Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true); + telemetry.addData("Pose", Robot.drivetrain.follower.getPose()); + telemetry.addData("Target Heading", targetHeading); + return; + } + turnPower = turnPower/autoaimmultiplier; + } + telemetry.addData("TurnPower", turnPower); + + if (gamepad1.guide){ + switch (LoadHardwareClass.selectedAlliance){ + case RED: + Robot.drivetrain.follower.setPose(new Pose(144-8.25,7.25, Math.toRadians(90))); + return; + case BLUE: + Robot.drivetrain.follower.setPose(new Pose(8.25,7.25, Math.toRadians(90))); + return; + } + } + + Robot.drivetrain.pedroMecanumDrive( + gamepad1.left_stick_y, + gamepad1.left_stick_x, + turnPower, + true + ); + } + /** *

Gamepad 2 Controls (Dylan's Pick V1)

*
    diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index ebf6e3cb7833..d78be5e09fa8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -38,8 +38,6 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; -//TODO, implement all our external libraries and functionality. - @TeleOp(name="Teleop_Outreach_", group="TeleOp") public class Teleop_Outreach_ extends LinearOpMode { @@ -75,19 +73,6 @@ public void runOpMode() { gamepad1.right_stick_x/2, true ); - if (gamepad1.x){ - Robot.turret.setFlywheelRPM(5485.714285714286); - panelsTelemetry.addData("SetRPM", 5485.714285714286); - }else{ - Robot.turret.setFlywheelRPM(0); - panelsTelemetry.addData("SetRPM", 0); - } - - Robot.turret.updatePIDs(); - - telemetry.addData("FlywheelState", Robot.turret.flywheelState); - panelsTelemetry.addData("FlywheelRPM", Robot.turret.getFlywheelRPM()); - // System-related Telemetry telemetry.addLine(); @@ -95,7 +80,6 @@ public void runOpMode() { telemetry.addData("Version: ", "11/4/25"); telemetry.update(); panelsTelemetry.update(telemetry); - //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 6b78bdee8f54..0fea5f15b57b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -52,8 +52,8 @@ public class Constants { .yVelocity(46.4157); public static PinpointConstants localizerConstants = new PinpointConstants() - .forwardPodY(-2) - .strafePodX(4.5) + .forwardPodY((double) 3 /8) + .strafePodX(6) .distanceUnit(DistanceUnit.INCH) .hardwareMapName("pinpoint") .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) From 4bb83340ba064e53af45d573bfb969edb0e818dd Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 8 Dec 2025 19:24:44 -0500 Subject: [PATCH 098/152] Got the turret tracking semi-working and tuned turret rotation PID --- .../Main_/Hardware_/Actuators_/Turret.java | 8 +- .../Drivetrain_/MecanumDrivetrainClass.java | 18 ---- .../Main_/Hardware_/LoadHardwareClass.java | 15 ---- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 82 ++++--------------- .../Main_/Teleop_/Teleop_Outreach_.java | 15 +++- .../ftc/teamcode/LOADCode/Notes and TODOs | 2 +- .../ftc/teamcode/pedroPathing/Constants.java | 4 +- 7 files changed, 36 insertions(+), 108 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 9579dfb1bcfc..6c593a36d1cc 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -4,7 +4,7 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotor; - +import com.qualcomm.robotcore.hardware.DcMotorSimple; import dev.nextftc.control.feedback.PIDCoefficients; @@ -19,7 +19,7 @@ public class Turret { public final Devices.ServoClass hood = new Devices.ServoClass(); public final Devices.ServoClass gate = new Devices.ServoClass(); - public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.002, 0, 0); + public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.15, 0.1, 0); public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0.0001, 0.0001); public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.00002899,0,0); @@ -41,6 +41,8 @@ public void init(OpMode opmode){ gate.init(opmode, "gate"); rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); + rotation.ticksPerRotation = 751.8 * ((double) 131 /24); + rotation.setDirection(DcMotorSimple.Direction.REVERSE); flywheel.ticksPerRotation = 28; @@ -98,7 +100,7 @@ public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ return Math.toDegrees(Math.atan2( goalPose.getY()-robotPose.getY(), goalPose.getX()-robotPose.getX()) - ) - Math.toDegrees(robotPose.getHeading()) + 180; + ) + Math.toDegrees(robotPose.getHeading()); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index f5545637f4d9..ceda43b9eb0f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -34,24 +34,6 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose){ follower.update(); } - /** - * Initializes the PedroPathing follower. - * Needs to be run once after all hardware is initialized. - * @param myOpMode Allows the follower access to the robot hardware. - * @param initialPose The starting pose of the robot. - * @param follow The follower object. - */ - public void init (@NonNull OpMode myOpMode, Pose initialPose, Follower follow){ - // PedroPathing initialization - follower = follow; - paths = new Pedro_Paths(follower); - follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field - follower.update(); // Applies the initialization - - follower.startTeleopDrive(); - follower.update(); - } - /** * Uses PedroPathing's follower class to implement a mecanum drive controller. * Must be called every loop to function properly. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index b0943a033cc5..420957f905bf 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -97,19 +97,4 @@ public void init(Pose initialPose) { myOpMode.telemetry.addData(">", "Hardware Initialized"); myOpMode.telemetry.update(); } - - /** - * Initializes all hardware for the robot. - * Must be called once at the start of each op-mode. - */ - public void init(Pose initialPose, Follower follower) { - // Initialize all subclasses - drivetrain.init(myOpMode, initialPose, follower); - turret.init(myOpMode); - intake.init(myOpMode); - - // Misc telemetry - myOpMode.telemetry.addData(">", "Hardware Initialized"); - myOpMode.telemetry.update(); - } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 3c2a398a3c67..a869774d9c94 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -35,6 +35,7 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.robot.Robot; import com.qualcomm.robotcore.util.ElapsedTime; import com.skeletonarmy.marrow.TimerEx; import com.skeletonarmy.marrow.prompts.OptionPrompt; @@ -62,7 +63,7 @@ public class Teleop_Main_ extends LinearOpMode { Prompter prompter = null; // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. - private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); + private final Pose startPose = new Pose(88.5,7.8, Math.toRadians(90)); // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); @@ -79,6 +80,8 @@ public void runOpMode() { prompter.onComplete(() -> { LoadHardwareClass.selectedAlliance = prompter.get("alliance"); telemetry.addData("Selection", "Complete"); + telemetry.addData("Alliance", LoadHardwareClass.selectedAlliance); + telemetry.update(); } ); @@ -173,14 +176,16 @@ public void runOpMode() { *
* */ - public void Gamepad1(){ - - Robot.drivetrain.speedMultiplier = 0.66; - if (gamepad1.left_trigger >= 0.5) { - Robot.drivetrain.speedMultiplier -= 0.33; - } - if (gamepad1.right_trigger >= 0.5){ - Robot.drivetrain.speedMultiplier += 0.33; + public void Gamepad1() { + + if (gamepad1.left_trigger >= 0.5 && gamepad1.right_trigger >=0.5){ + Robot.drivetrain.speedMultiplier = 0.66; + }else if (gamepad1.left_trigger >= 0.5) { + Robot.drivetrain.speedMultiplier = 0.33; + }else if (gamepad1.right_trigger >= 0.5){ + Robot.drivetrain.speedMultiplier = 1; + }else{ + Robot.drivetrain.speedMultiplier = 0.66; } double turnMult = 2; @@ -195,65 +200,6 @@ public void Gamepad1(){ ); } - public void Gamepad1Dec6(){ - - Robot.drivetrain.speedMultiplier = 0.66; - if (gamepad1.left_trigger >= 0.5) { - Robot.drivetrain.speedMultiplier -= 0.33; - } - if (gamepad1.right_trigger >= 0.5){ - Robot.drivetrain.speedMultiplier += 0.33; - } - - double turnPower = gamepad1.right_stick_x; - double turnMult = 2; - if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ - turnMult = 1; - } - turnPower = turnPower/turnMult; - - double targetHeading = 0; - telemetry.addData("Alliance", LoadHardwareClass.selectedAlliance); - if (gamepad1.right_stick_button){ - switch (LoadHardwareClass.selectedAlliance){ - case RED: - turnPower = Robot.drivetrain.follower.getHeading() - - Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), false); - targetHeading = Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), false); - telemetry.addData("Pose", Robot.drivetrain.follower.getPose()); - telemetry.addData("Target Heading", targetHeading); - return; - case BLUE: - turnPower = Robot.drivetrain.follower.getHeading() - - Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true); - targetHeading = Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true); - telemetry.addData("Pose", Robot.drivetrain.follower.getPose()); - telemetry.addData("Target Heading", targetHeading); - return; - } - turnPower = turnPower/autoaimmultiplier; - } - telemetry.addData("TurnPower", turnPower); - - if (gamepad1.guide){ - switch (LoadHardwareClass.selectedAlliance){ - case RED: - Robot.drivetrain.follower.setPose(new Pose(144-8.25,7.25, Math.toRadians(90))); - return; - case BLUE: - Robot.drivetrain.follower.setPose(new Pose(8.25,7.25, Math.toRadians(90))); - return; - } - } - - Robot.drivetrain.pedroMecanumDrive( - gamepad1.left_stick_y, - gamepad1.left_stick_x, - turnPower, - true - ); - } - /** *

Gamepad 2 Controls (Dylan's Pick V1)

*
    diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index d78be5e09fa8..3828d0c8e296 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -46,7 +46,7 @@ public class Teleop_Outreach_ extends LinearOpMode { private TelemetryManager panelsTelemetry = PanelsTelemetry.INSTANCE.getTelemetry(); // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. - private final Pose startPose = new Pose(135.6,9.8, Math.toRadians(90)); + private final Pose startPose = new Pose(88.5,7.8, Math.toRadians(90)); @Override public void runOpMode() { @@ -74,6 +74,19 @@ public void runOpMode() { true ); + if (!gamepad1.b){ + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); + telemetry.addData("Target Angle", Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), false)); + }else{ + Robot.turret.rotation.setAngle(0); + telemetry.addData("Target Angle", 0); + } + + telemetry.addData("Turret Angle", Robot.turret.rotation.getAngleAbsolute()); + telemetry.addData("Robot Pose X", Math.round(Robot.drivetrain.follower.getPose().getX())); + telemetry.addData("Robot Pose Y", Math.round(Robot.drivetrain.follower.getPose().getY())); + telemetry.addData("Robot Pose H", Math.round(Robot.drivetrain.follower.getPose().getHeading())); + // System-related Telemetry telemetry.addLine(); telemetry.addData("Status", "Run Time: " + runtime.toString()); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 8dae2b096875..3186bc743189 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -20,4 +20,4 @@ //DONE, Finish translating Dylan's December 6th controls into the program. -//TODO, Figure out how to use NextFTC's Pedropathing extension for auto. \ No newline at end of file +//DONE, Figure out how to use NextFTC's Pedropathing extension for auto. \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 0fea5f15b57b..10b4639b554f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -52,12 +52,12 @@ public class Constants { .yVelocity(46.4157); public static PinpointConstants localizerConstants = new PinpointConstants() - .forwardPodY((double) 3 /8) + .forwardPodY((double) 3/8) .strafePodX(6) .distanceUnit(DistanceUnit.INCH) .hardwareMapName("pinpoint") .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) - .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED) + .forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD) .strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD); public static Follower createFollower(HardwareMap hardwareMap) { From 5fb68b567376bf077c3f20c8f58ddc2848368800 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 9 Dec 2025 19:28:28 -0500 Subject: [PATCH 099/152] Finalized turret tracking calculations and worked on hood and teleop controls --- .../Main_/Hardware_/Actuators_/Devices.java | 54 ++++-- .../Main_/Hardware_/Actuators_/Turret.java | 32 +++- .../Main_/Hardware_/LoadHardwareClass.java | 3 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 176 ++++++------------ .../Main_/Teleop_/Teleop_Outreach_.java | 35 +++- 5 files changed, 147 insertions(+), 153 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java index f664d27fd09d..e6b5abdf45b3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -46,11 +46,20 @@ public double getPower() { } public static class DcMotorExClass { - // PID pidCoefficients + + // Old PID Coefficients + PIDCoefficients old_pidCoefficients = new PIDCoefficients(0, 0, 0); + BasicFeedforwardParameters old_ffCoefficients = new BasicFeedforwardParameters(0,0,0); + + // PID Coefficients PIDCoefficients pidCoefficients = new PIDCoefficients(0, 0, 0); BasicFeedforwardParameters ffCoefficients = new BasicFeedforwardParameters(0,0,0); - // Encoder ticks/rotation - // 1620rpm Gobilda - 103.8 ticks at the motor shaft + /** + *

    Encoder ticks/rotation:


    + * 1620rpm Gobilda - 103.8
    + * 1150rpm Gobilda - 145.1
    + * 223rpm Gobilda - 751.8
    + */ public double ticksPerRotation = 103.8; // Target position/velocity of the motor public double target = 0; @@ -80,6 +89,19 @@ public void init (@NonNull OpMode opmode, String motorName){ motorObject = opmode.hardwareMap.get(DcMotorEx.class, motorName); } + ControlSystem velPID = null; + ControlSystem posPID = null; + + public void buildPIDs(){ + if (old_pidCoefficients != pidCoefficients || old_ffCoefficients != ffCoefficients){ + velPID = ControlSystem.builder() + .velPid(pidCoefficients) + .basicFF(ffCoefficients) + .build(); + posPID = ControlSystem.builder().posPid(pidCoefficients).build(); + } + } + /** * Sets the value of the PID coefficients of the motor. * @param coefficients The values to set the coefficients to. @@ -123,6 +145,7 @@ public void setDirection(DcMotorSimple.Direction direction){ } public void setEncoderTicks(int ticks){ motorObject.setTargetPosition(ticks); + setRunMode(DcMotor.RunMode.RUN_TO_POSITION); } /** * @return The current position of the turret motor in encoder ticks. Can be any value. @@ -178,12 +201,22 @@ public double getPower(){ * @param angle The angle in degrees to move the motor to. Can be any number. */ public void setAngle(double angle){ + setAngle(angle, 0); + } + /** + * Uses a PID controller to move the motor to the desired position. + * Must be called every loop to function properly. + * @param angle The angle in degrees to move the motor to. Can be any number. + * @param velocity The velocity the motor should be spinning at when it reaches the target point + */ + public void setAngle(double angle, double velocity){ target = angle; - ControlSystem turretPID = ControlSystem.builder().posPid(pidCoefficients).build(); + buildPIDs(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); - turretPID.setGoal(new KineticState(target)); - setPower(turretPID.calculate(currentKineticState)); + posPID.setGoal(new KineticState(target, velocity)); + setPower(posPID.calculate(currentKineticState)); } + /** * Uses a PID controller to accelerate the motor to the desired RPM. * Must be called every loop to function properly. @@ -191,14 +224,11 @@ public void setAngle(double angle){ */ public void setRPM(double rpm){ target = rpm; + buildPIDs(); double degreesPerSecond = target*6; - ControlSystem PID = ControlSystem.builder() - .velPid(pidCoefficients) - .basicFF(ffCoefficients) - .build(); KineticState currentKineticState = new KineticState(getAngleAbsolute(), getDegreesPerSecond()); - PID.setGoal(new KineticState(0, degreesPerSecond)); - setPower(PID.calculate(currentKineticState)); + velPID.setGoal(new KineticState(0, degreesPerSecond)); + setPower(velPID.calculate(currentKineticState)); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 6c593a36d1cc..5c6e3429a050 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -5,6 +5,7 @@ import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.Servo; import dev.nextftc.control.feedback.PIDCoefficients; @@ -13,13 +14,15 @@ @Configurable public class Turret { - + // Hardware definitions public final Devices.DcMotorExClass rotation = new Devices.DcMotorExClass(); public final Devices.DcMotorExClass flywheel = new Devices.DcMotorExClass(); public final Devices.ServoClass hood = new Devices.ServoClass(); public final Devices.ServoClass gate = new Devices.ServoClass(); - public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.15, 0.1, 0); + // The PID coefficient variables + public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.06, 0, 0); // 223RPM + //public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.3, 0, 0.007); // 1150RPM public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0.0001, 0.0001); public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.00002899,0,0); @@ -41,12 +44,13 @@ public void init(OpMode opmode){ gate.init(opmode, "gate"); rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); - rotation.ticksPerRotation = 751.8 * ((double) 131 /24); + rotation.ticksPerRotation = 145.1 * ((double) 131 /24); rotation.setDirection(DcMotorSimple.Direction.REVERSE); flywheel.ticksPerRotation = 28; gate.setAngle(0.5); + hood.setDirection(Servo.Direction.REVERSE); // Pass PID pidCoefficients to motor classes rotation.setPidCoefficients(turretCoefficients); @@ -78,6 +82,22 @@ public void setGate(gatestate state){ } } + /** + * Sets the angle of the hood. + * @param angle An angle in degrees that is constrained to between 0 and 45 + */ + public void setHood(double angle){ + hood.setAngle(Math.min(Math.max(angle, 0), 320)/(360*5)); + } + + /** + * Gets the angle of the hood + * @return A value between 0 and 45 degrees + */ + public double getHood(){ + return hood.getAngle() * 360 * 5; + } + /** * Outputs one of the following modes *
      @@ -94,13 +114,13 @@ public gatestate getGate(){ } public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ - Pose goalPose = new Pose(0,144,0); - if (targetRedGoal) {goalPose = new Pose(144, 144, 0);} + Pose goalPose = new Pose(4,140,0); + if (targetRedGoal) {goalPose = new Pose(140, 140, 0);} return Math.toDegrees(Math.atan2( goalPose.getY()-robotPose.getY(), goalPose.getX()-robotPose.getX()) - ) + Math.toDegrees(robotPose.getHeading()); + ) - Math.toDegrees(robotPose.getHeading()); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index 420957f905bf..0f77fc77f277 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -30,7 +30,6 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; import com.bylazar.configurables.annotations.Configurable; -import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; @@ -54,7 +53,7 @@ public class LoadHardwareClass { public final Intake intake; // Declare various enums & other variables that are useful across files - public static Alliance selectedAlliance = null; + public static Alliance selectedAlliance = Alliance.RED; public enum Alliance { RED, BLUE diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index a869774d9c94..670b9909964b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -29,13 +29,14 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; +import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; + import com.bylazar.configurables.annotations.Configurable; import com.bylazar.telemetry.PanelsTelemetry; import com.bylazar.telemetry.TelemetryManager; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.robot.Robot; import com.qualcomm.robotcore.util.ElapsedTime; import com.skeletonarmy.marrow.TimerEx; import com.skeletonarmy.marrow.prompts.OptionPrompt; @@ -58,12 +59,11 @@ public class Teleop_Main_ extends LinearOpMode { public static double DylanStickDeadzones = 0.2; public int shootingState = 0; public TimerEx shootingDelay = new TimerEx(1); - public static double autoaimmultiplier = 100; Prompter prompter = null; // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. - private final Pose startPose = new Pose(88.5,7.8, Math.toRadians(90)); + private final Pose startPose = new Pose(88.5, 7.8, Math.toRadians(90)); // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); @@ -78,17 +78,17 @@ public void runOpMode() { prompter = new Prompter(this); prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", LoadHardwareClass.Alliance.RED, LoadHardwareClass.Alliance.BLUE)); prompter.onComplete(() -> { - LoadHardwareClass.selectedAlliance = prompter.get("alliance"); + selectedAlliance = prompter.get("alliance"); telemetry.addData("Selection", "Complete"); - telemetry.addData("Alliance", LoadHardwareClass.selectedAlliance); + telemetry.addData("Alliance", selectedAlliance); telemetry.update(); } ); // Runs repeatedly while in init - while (opModeInInit()){ + while (opModeInInit()) { // If an auto was not run, run the prompter to select the correct alliance - if (LoadHardwareClass.selectedAlliance == null){ + if (selectedAlliance == null) { prompter.run(); } } @@ -104,7 +104,7 @@ public void runOpMode() { while (opModeIsActive()) { Gamepad1(); - Gamepad2Dec6(); + Gamepad2(); Robot.turret.updatePIDs(); @@ -136,6 +136,7 @@ public void runOpMode() { } } + /** *

      Gamepad 1 Controls (Ari's Pick V1)

      *
        @@ -178,24 +179,24 @@ public void runOpMode() { */ public void Gamepad1() { - if (gamepad1.left_trigger >= 0.5 && gamepad1.right_trigger >=0.5){ + if (gamepad1.left_trigger >= 0.5 && gamepad1.right_trigger >= 0.5) { Robot.drivetrain.speedMultiplier = 0.66; - }else if (gamepad1.left_trigger >= 0.5) { + } else if (gamepad1.left_trigger >= 0.5) { Robot.drivetrain.speedMultiplier = 0.33; - }else if (gamepad1.right_trigger >= 0.5){ + } else if (gamepad1.right_trigger >= 0.5) { Robot.drivetrain.speedMultiplier = 1; - }else{ + } else { Robot.drivetrain.speedMultiplier = 0.66; } double turnMult = 2; - if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ - turnMult = 1; - } +// if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ +// turnMult = 1; +// } Robot.drivetrain.pedroMecanumDrive( gamepad1.left_stick_y, gamepad1.left_stick_x, - gamepad1.right_stick_x/turnMult, + gamepad1.right_stick_x / turnMult, true ); } @@ -224,8 +225,8 @@ public void Gamepad1() { *
      • Y: Flywheel Toggle
      • *
      *
    • Letter Buttons:
        - *
      • DpadUp: Hood Up Override
      • - *
      • DpadDown: Hood Down Override
      • + *
      • DpadUp: N/A
      • + *
      • DpadDown: N/A
      • *
      • DpadLeft: N/A
      • *
      • DpadRight: N/A
      • *
    • @@ -240,35 +241,43 @@ public void Gamepad1() { *
    *
*/ - public void Gamepad2(){ + public void Gamepad2() { - //Intake Controls (Left Stick Y) - if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones){ - if (gamepad2.left_stick_y > 0){ // OUT (Digital) - Robot.intake.setMode(Intake.Mode.REVERSING); - } else { // IN (Digital) - Robot.intake.setMode(Intake.Mode.INTAKING); - } - } else { // OFF - Robot.intake.setMode(Intake.Mode.OFF); + // Turret Aimbot + if (selectedAlliance == LoadHardwareClass.Alliance.RED) { + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); + } else if (selectedAlliance == LoadHardwareClass.Alliance.BLUE) { + Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); } - //Turret Angle Controls (Right Stick X) - //To be added after manual control is finished - - //Flywheel Toggle Control (Y Button) - if (gamepad2.yWasPressed()){ - if (Robot.turret.flywheelState == Turret.flywheelstate.OFF){ - Robot.turret.setFlywheel(Turret.flywheelstate.ON); - } else { - Robot.turret.setFlywheel(Turret.flywheelstate.OFF); + //Intake Controls (Left Stick Y) + if (shootingState == 0) { + if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones && shootingState > 0) { + if (gamepad2.left_stick_y > 0) { // OUT (Digital) + Robot.intake.setMode(Intake.Mode.REVERSING); + } else { // IN (Digital) + Robot.intake.setMode(Intake.Mode.INTAKING); + } + } else { // OFF + Robot.intake.setMode(Intake.Mode.OFF); + } + //Flywheel Toggle Control (Y Button) + if (gamepad2.yWasPressed()) { + if (Robot.turret.flywheelState == Turret.flywheelstate.OFF) { + Robot.turret.setFlywheel(Turret.flywheelstate.ON); + } else { + Robot.turret.setFlywheel(Turret.flywheelstate.OFF); + } } } + Robot.turret.updateFlywheel(); //Shoot (B Button Press) // Increment the shooting state - if (gamepad2.bWasPressed() && shootingState < 2 && Robot.turret.getFlywheelRPM() > 5900){shootingState++;} - switch (shootingState){ + if (gamepad2.bWasPressed() && shootingState < 2 && Robot.turret.getFlywheelRPM() > 5000) { + shootingState++; + } + switch (shootingState) { case 0: telemetry.addData("Shooting State", "OFF"); return; @@ -285,11 +294,13 @@ public void Gamepad2(){ telemetry.addData("Shooting State", "TRANSFERRED"); return; case 3: - if (shootingDelay.isDone()){shootingState++;} + if (shootingDelay.isDone()) { + shootingState++; + } telemetry.addData("Shooting State", "DELAY"); return; case 4: - Robot.turret.setFlywheelRPM(0); + Robot.turret.setFlywheel(Turret.flywheelstate.OFF); Robot.turret.setGate(Turret.gatestate.CLOSED); Robot.intake.setMode(Intake.Mode.OFF); Robot.intake.setTransfer(Intake.transferState.DOWN); @@ -299,85 +310,4 @@ public void Gamepad2(){ } - - /** - *

Gamepad 2 Controls (December 6th Scrimmage)

- *
    - *
  • Analog Inputs
      - *
    • Left Stick:
        - *
      • X: Tranfer Belt IN ONLY
      • - *
      • Y: Intake Direction/Power
      • - *
    • - *
    • Right Stick:
        - *
      • X: N/A
      • - *
      • Y: N/A
      • - *
    • - *
    • Left Trigger: N/A
    • - *
    • Right Trigger: N/A
    • - *
  • - * - *
  • Button Inputs
    • - *
    • Letter Buttons:
        - *
      • A: N/A
      • - *
      • B: Kicker/Flap/Feeder
      • - *
      • X: N/A
      • - *
      • Y: Flywheel Toggle
      • - *
    • - *
    • Letter Buttons:
        - *
      • DpadUp: N/A
      • - *
      • DpadDown: N/A
      • - *
      • DpadLeft: N/A
      • - *
      • DpadRight: N/A
      • - *
    • - *
    • Bumpers:
        - *
      • Left Bumper: N/A
      • - *
      • Right Bumper: N/A
      • - *
    • - *
    • Stick Buttons:
        - *
      • Left Stick Button: N/A
      • - *
      • Right Stick Button: N/A
      • - *
    • - *
    - *
- */ - public void Gamepad2Dec6(){ - - //Intake Controls (Left Stick Y) - if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones){ - Robot.intake.intake.setPower(gamepad2.left_stick_y); - } else { // OFF - Robot.intake.intake.setPower(0); - } - - //Transfer Belt (ABS Right Stick Y) - if (Math.abs(gamepad2.right_stick_y) >= DylanStickDeadzones) { - Robot.intake.belt.setPower(Math.abs(gamepad2.right_stick_y)); - } else { // OFF - Robot.intake.belt.setPower(0); - } - - // Gate control - if (Robot.turret.getFlywheelRPM() > 3000){ - Robot.turret.setGate(Turret.gatestate.OPEN); - }else{ - Robot.turret.setGate(Turret.gatestate.CLOSED); - } - - // Transfer control - if (gamepad2.b){ - Robot.intake.setTransfer(Intake.transferState.UP); - }else{ - Robot.intake.setTransfer(Intake.transferState.DOWN); - } - - //Flywheel Toggle Control (Y Button) - if (gamepad2.yWasPressed()){ - if (Robot.turret.flywheelState == Turret.flywheelstate.ON){ - Robot.turret.setFlywheel(Turret.flywheelstate.OFF); - }else if (Robot.turret.flywheelState == Turret.flywheelstate.OFF){ - Robot.turret.setFlywheel(Turret.flywheelstate.ON); - } - } - Robot.turret.updateFlywheel(); - } -} +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index 3828d0c8e296..d75c5851e3f1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -55,14 +55,19 @@ public void runOpMode() { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); + // Initialize all hardware of the robot + Robot.init(startPose); + + if (gamepad1.guide){ + Robot.turret.rotation.resetEncoder(); + } + + double hoodAngle = 0; // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); - // Initialize all hardware of the robot - Robot.init(startPose); - // run until the end of the match (driver presses STOP) while (opModeIsActive()) { @@ -74,18 +79,28 @@ public void runOpMode() { true ); - if (!gamepad1.b){ - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); - telemetry.addData("Target Angle", Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), false)); + if (gamepad1.x){ + Robot.turret.rotation.setAngle(180); }else{ - Robot.turret.rotation.setAngle(0); - telemetry.addData("Target Angle", 0); + Robot.turret.rotation.setAngle(Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true)); } - + telemetry.addData("Target Angle", Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true)); telemetry.addData("Turret Angle", Robot.turret.rotation.getAngleAbsolute()); + telemetry.addData("Turret Motor Power", Robot.turret.rotation.getPower()); + telemetry.addLine(); + + double increment = 2; + if (gamepad1.dpad_up && hoodAngle < 320){ + hoodAngle += increment; + }else if (gamepad1.dpad_down && hoodAngle > 0){ + hoodAngle -= increment; + } + Robot.turret.setHood(hoodAngle); + telemetry.addData("Hood Angle", Robot.turret.getHood()); + telemetry.addData("Robot Pose X", Math.round(Robot.drivetrain.follower.getPose().getX())); telemetry.addData("Robot Pose Y", Math.round(Robot.drivetrain.follower.getPose().getY())); - telemetry.addData("Robot Pose H", Math.round(Robot.drivetrain.follower.getPose().getHeading())); + telemetry.addData("Robot Pose H", Math.round(Math.toDegrees(Robot.drivetrain.follower.getPose().getHeading()))); // System-related Telemetry telemetry.addLine(); From 8922e98fc98aa77cd66287168f11b83111cc550a Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+professor348@users.noreply.github.com> Date: Wed, 10 Dec 2025 09:40:56 -0500 Subject: [PATCH 100/152] Fixed a bug in Devices.DcMotorExClass that caused the PIDs to be regenerated every loop, rendering the kI parameter useless. --- .../LOADCode/Main_/Hardware_/Actuators_/Devices.java | 4 +++- .../LOADCode/Main_/Hardware_/Actuators_/Turret.java | 8 ++------ 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java index e6b5abdf45b3..22daf0c179e9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -94,12 +94,14 @@ public void init (@NonNull OpMode opmode, String motorName){ public void buildPIDs(){ if (old_pidCoefficients != pidCoefficients || old_ffCoefficients != ffCoefficients){ + posPID = ControlSystem.builder().posPid(pidCoefficients).build(); velPID = ControlSystem.builder() .velPid(pidCoefficients) .basicFF(ffCoefficients) .build(); - posPID = ControlSystem.builder().posPid(pidCoefficients).build(); } + old_pidCoefficients = pidCoefficients; + old_ffCoefficients = ffCoefficients; } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 5c6e3429a050..9eb08f51253d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -7,7 +7,6 @@ import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.Servo; - import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; @@ -38,17 +37,14 @@ public enum flywheelstate { public flywheelstate flywheelState = flywheelstate.OFF; public void init(OpMode opmode){ - rotation.init(opmode, "turret", 145.1); //Previously 103.8 - flywheel.init(opmode, "flywheel"); + rotation.init(opmode, "turret", 145.1 * ((double) 131 /24)); //Previously 103.8 + flywheel.init(opmode, "flywheel", 28); hood.init(opmode, "hood"); gate.init(opmode, "gate"); rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); - rotation.ticksPerRotation = 145.1 * ((double) 131 /24); rotation.setDirection(DcMotorSimple.Direction.REVERSE); - flywheel.ticksPerRotation = 28; - gate.setAngle(0.5); hood.setDirection(Servo.Direction.REVERSE); From 99fa9677f01e3bbb236ed898a87687aa9d6d8b06 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Fri, 12 Dec 2025 13:56:54 -0500 Subject: [PATCH 101/152] Added Utils_.java for storing any software utilities, & added an InterpLUT to it. --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 17 +- .../Main_/Hardware_/Actuators_/Intake.java | 36 ++--- .../LOADCode/Main_/Hardware_/Commands.java | 2 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 38 +++-- .../ftc/teamcode/LOADCode/Main_/Utils_.java | 150 ++++++++++++++++++ 5 files changed, 198 insertions(+), 45 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index dac8c7759eb7..3567279d71bb 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -11,7 +11,6 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @@ -134,16 +133,16 @@ private Command Leave_Far_HP() { new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), new Delay(5) ), - Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), new Delay(2), - Commands.setIntakeMode(Robot, Intake.Mode.INTAKING), + Commands.setIntakeMode(Robot, Intake.intakeMode.INTAKING), new Delay(1), - Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), new Delay(2), Commands.setTransferState(Robot, Intake.transferState.UP), new Delay(1), Commands.setTransferState(Robot, Intake.transferState.DOWN), - Commands.setIntakeMode(Robot, Intake.Mode.OFF), + Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), Commands.runPath(Robot.drivetrain.paths.start2_to_leave3, true, 0.6) ); @@ -162,16 +161,16 @@ private Command Leave_Near_Launch() { new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), new Delay(5) ), - Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), new Delay(2), - Commands.setIntakeMode(Robot, Intake.Mode.INTAKING), + Commands.setIntakeMode(Robot, Intake.intakeMode.INTAKING), new Delay(1), - Commands.setIntakeMode(Robot, Intake.Mode.SHOOTING), + Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), new Delay(2), Commands.setTransferState(Robot, Intake.transferState.UP), new Delay(1), Commands.setTransferState(Robot, Intake.transferState.DOWN), - Commands.setIntakeMode(Robot, Intake.Mode.OFF), + Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true, 0.6) ); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 30d827000a53..13eff1a3a1f7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -11,7 +11,7 @@ public class Intake { public final Devices.CRServoClass belt = new Devices.CRServoClass(); public final Devices.ServoClass transfer = new Devices.ServoClass(); - public enum Mode { + public enum intakeMode { INTAKING, SHOOTING, REVERSING, @@ -38,20 +38,20 @@ public void init(OpMode opmode){ * @param direction * Takes the following inputs *
    - *
  • Mode.INTAKING
  • - *
  • Mode.SHOOTING
  • - *
  • Mode.REVERSING
  • - *
  • Mode.OFF
  • + *
  • intakeMode.INTAKING
  • + *
  • intakeMode.SHOOTING
  • + *
  • intakeMode.REVERSING
  • + *
  • intakeMode.OFF
  • *
*/ - public void setMode(Mode direction){ - if (direction == Mode.INTAKING){ + public void setMode(intakeMode direction){ + if (direction == intakeMode.INTAKING){ intake.setPower(1); belt.setPower(1); - }else if (direction == Mode.SHOOTING){ + }else if (direction == intakeMode.SHOOTING){ intake.setPower(0); belt.setPower(1); - }else if (direction == Mode.REVERSING){ + }else if (direction == intakeMode.REVERSING){ intake.setPower(-1); belt.setPower(-1); }else{ @@ -63,23 +63,23 @@ public void setMode(Mode direction){ /** * Outputs one of the following modes *
    - *
  • Mode.INTAKING
  • - *
  • Mode.SHOOTING
  • - *
  • Mode.REVERSING
  • - *
  • Mode.OFF
  • + *
  • intakeMode.INTAKING
  • + *
  • intakeMode.SHOOTING
  • + *
  • intakeMode.REVERSING
  • + *
  • intakeMode.OFF
  • *
*/ - public Mode getMode(){ + public intakeMode getMode(){ double intakePower = intake.getPower(); double beltPower = belt.getPower(); if (intakePower == 1 && beltPower == 1){ - return Mode.INTAKING; + return intakeMode.INTAKING; }else if (intakePower == 0 && beltPower == 1){ - return Mode.SHOOTING; + return intakeMode.SHOOTING; }else if (intakePower == -1 && beltPower == -1){ - return Mode.REVERSING; + return intakeMode.REVERSING; }else{ - return Mode.OFF; + return intakeMode.OFF; } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index d363fa3a21ff..9ecdc2411d6e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -37,7 +37,7 @@ public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheels .requires(turretSystem); } - public static Command setIntakeMode(LoadHardwareClass Robot, Intake.Mode state) { + public static Command setIntakeMode(LoadHardwareClass Robot, Intake.intakeMode state) { return new InstantCommand(new LambdaCommand("setIntakeMode()") .setStart(() -> Robot.intake.setMode(state)) .requires(intakeSystem)); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 670b9909964b..2db9822bde1f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -43,8 +43,12 @@ import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake.intakeMode; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake.transferState; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.flywheelstate; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.gatestate; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.Alliance; @Configurable @@ -244,9 +248,9 @@ public void Gamepad1() { public void Gamepad2() { // Turret Aimbot - if (selectedAlliance == LoadHardwareClass.Alliance.RED) { + if (selectedAlliance == Alliance.RED) { Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); - } else if (selectedAlliance == LoadHardwareClass.Alliance.BLUE) { + } else if (selectedAlliance == Alliance.BLUE) { Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); } @@ -254,19 +258,19 @@ public void Gamepad2() { if (shootingState == 0) { if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones && shootingState > 0) { if (gamepad2.left_stick_y > 0) { // OUT (Digital) - Robot.intake.setMode(Intake.Mode.REVERSING); + Robot.intake.setMode(Intake.intakeMode.REVERSING); } else { // IN (Digital) - Robot.intake.setMode(Intake.Mode.INTAKING); + Robot.intake.setMode(intakeMode.INTAKING); } } else { // OFF - Robot.intake.setMode(Intake.Mode.OFF); + Robot.intake.setMode(Intake.intakeMode.OFF); } //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()) { - if (Robot.turret.flywheelState == Turret.flywheelstate.OFF) { - Robot.turret.setFlywheel(Turret.flywheelstate.ON); + if (Robot.turret.flywheelState == flywheelstate.OFF) { + Robot.turret.setFlywheel(flywheelstate.ON); } else { - Robot.turret.setFlywheel(Turret.flywheelstate.OFF); + Robot.turret.setFlywheel(flywheelstate.OFF); } } } @@ -282,13 +286,13 @@ public void Gamepad2() { telemetry.addData("Shooting State", "OFF"); return; case 1: - Robot.intake.setMode(Intake.Mode.INTAKING); - Robot.turret.setGate(Turret.gatestate.OPEN); + Robot.intake.setMode(intakeMode.INTAKING); + Robot.turret.setGate(gatestate.OPEN); telemetry.addData("Shooting State", "STARTED"); return; case 2: - Robot.intake.setMode(Intake.Mode.SHOOTING); - Robot.intake.setTransfer(Intake.transferState.UP); + Robot.intake.setMode(Intake.intakeMode.SHOOTING); + Robot.intake.setTransfer(transferState.UP); shootingDelay.restart(); shootingState++; telemetry.addData("Shooting State", "TRANSFERRED"); @@ -300,10 +304,10 @@ public void Gamepad2() { telemetry.addData("Shooting State", "DELAY"); return; case 4: - Robot.turret.setFlywheel(Turret.flywheelstate.OFF); - Robot.turret.setGate(Turret.gatestate.CLOSED); - Robot.intake.setMode(Intake.Mode.OFF); - Robot.intake.setTransfer(Intake.transferState.DOWN); + Robot.turret.setFlywheel(flywheelstate.OFF); + Robot.turret.setGate(gatestate.CLOSED); + Robot.intake.setMode(intakeMode.OFF); + Robot.intake.setTransfer(transferState.DOWN); telemetry.addData("Shooting State", "RESET"); shootingState = 0; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java new file mode 100644 index 000000000000..08c21def1bd9 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java @@ -0,0 +1,150 @@ +package org.firstinspires.ftc.teamcode.LOADCode.Main_; + +import java.util.ArrayList; +import java.util.Arrays; +import java.util.List; + +public class Utils_ { + /** + * Performs spline interpolation given a set of control points. + */ + public class InterpLUT { + + private List mX = new ArrayList<>(); + private List mY = new ArrayList<>(); + private List mM = new ArrayList<>(); + + private InterpLUT(List x, List y, List m) { + mX = x; + mY = y; + mM = m; + } + + public InterpLUT() { + } + + /** + * Adds a control point to the LUT + */ + public void add(double input, double output) { + mX.add(input); + mY.add(output); + } + + /** + * Creates a monotone cubic spline from a given set of control points. + * + *

+ * The spline is guaranteed to pass through each control point exactly. Moreover, assuming the control points are + * monotonic (Y is non-decreasing or non-increasing) then the interpolated values will also be monotonic. + * + * @throws IllegalArgumentException if the X or Y arrays are null, have different lengths or have fewer than 2 values. + */ + //public static LUTWithInterpolator createLUT(List x, List y) { + public void createLUT() { + List x = this.mX; + List y = this.mY; + + if (x == null || y == null || x.size() != y.size() || x.size() < 2) { + throw new IllegalArgumentException("There must be at least two control " + + "points and the arrays must be of equal length."); + } + + final int n = x.size(); + Double[] d = new Double[n - 1]; // could optimize this out + Double[] m = new Double[n]; + + // Compute slopes of secant lines between successive points. + for (int i = 0; i < n - 1; i++) { + Double h = x.get(i + 1) - x.get(i); + if (h <= 0f) { + throw new IllegalArgumentException("The control points must all " + + "have strictly increasing X values."); + } + d[i] = (y.get(i + 1) - y.get(i)) / h; + } + + // Initialize the tangents as the average of the secants. + m[0] = d[0]; + for (int i = 1; i < n - 1; i++) { + m[i] = (d[i - 1] + d[i]) * 0.5f; + } + m[n - 1] = d[n - 2]; + + // Update the tangents to preserve monotonicity. + for (int i = 0; i < n - 1; i++) { + if (d[i] == 0f) { // successive Y values are equal + m[i] = Double.valueOf(0f); + m[i + 1] = Double.valueOf(0f); + } else { + double a = m[i] / d[i]; + double b = m[i + 1] / d[i]; + double h = Math.hypot(a, b); + if (h > 9f) { + double t = 3f / h; + m[i] = t * a * d[i]; + m[i + 1] = t * b * d[i]; + } + } + } + mX = x; + mY = y; + mM = Arrays.asList(m); + } + + /** + * Interpolates the value of Y = f(X) for given X. Clamps X to the domain of the spline. + * + * @param input The X value. + * @return The interpolated Y = f(X) value. + */ + public double get(double input) { + // Handle the boundary cases. + final int n = mX.size(); + if (Double.isNaN(input)) { + return input; + } + if (input <= mX.get(0)) { + throw new IllegalArgumentException("User requested value outside of bounds of LUT. Bounds are: " + mX.get(0).toString() + " to " + mX.get(n - 1).toString() + ". Value provided was: " + input); + } + if (input >= mX.get(n - 1)) { + throw new IllegalArgumentException("User requested value outside of bounds of LUT. Bounds are: " + mX.get(0).toString() + " to " + mX.get(n - 1).toString() + ". Value provided was: " + input); + } + + // Find the index 'i' of the last point with smaller X. + // We know this will be within the spline due to the boundary tests. + int i = 0; + while (input >= mX.get(i + 1)) { + i += 1; + if (input == mX.get(i)) { + return mY.get(i); + } + } + + // Perform cubic Hermite spline interpolation. + double h = mX.get(i + 1) - mX.get(i); + double t = (input - mX.get(i)) / h; + return (mY.get(i) * (1 + 2 * t) + h * mM.get(i) * t) * (1 - t) * (1 - t) + + (mY.get(i + 1) * (3 - 2 * t) + h * mM.get(i + 1) * (t - 1)) * t * t; + } + + // For debugging. + @Override + public String toString() { + StringBuilder str = new StringBuilder(); + final int n = mX.size(); + str.append("["); + for (int i = 0; i < n; i++) { + if (i != 0) { + str.append(", "); + } + str.append("(").append(mX.get(i)); + str.append(", ").append(mY.get(i)); + str.append(": ").append(mM.get(i)).append(")"); + } + str.append("]"); + return str.toString(); + } + + } +} From eabfa8d823db7bb0360d12b5a35a6828083cd118 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Fri, 12 Dec 2025 18:13:16 -0500 Subject: [PATCH 102/152] Retuned flywheel PID with weights, and added manual hood controls --- .../Main_/Hardware_/Actuators_/Turret.java | 27 ++++++++++---- .../Main_/Hardware_/LoadHardwareClass.java | 2 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 36 ++++++++++++------- 3 files changed, 46 insertions(+), 19 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 9eb08f51253d..9ec43097d921 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -16,14 +16,19 @@ public class Turret { // Hardware definitions public final Devices.DcMotorExClass rotation = new Devices.DcMotorExClass(); public final Devices.DcMotorExClass flywheel = new Devices.DcMotorExClass(); + public final Devices.DcMotorExClass flywheel2 = new Devices.DcMotorExClass(); public final Devices.ServoClass hood = new Devices.ServoClass(); public final Devices.ServoClass gate = new Devices.ServoClass(); - // The PID coefficient variables + // Turret PID coefficients public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.06, 0, 0); // 223RPM //public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.3, 0, 0.007); // 1150RPM - public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0.0001, 0.0001); - public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.00002899,0,0); + + // Flywheel PID coefficients + //public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0.0001, 0.0001); + //public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.00002899,0,0); + public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.00005, 0, 0); + public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.0003,0,0); public enum gatestate { OPEN, @@ -36,9 +41,12 @@ public enum flywheelstate { } public flywheelstate flywheelState = flywheelstate.OFF; + public static double onSpeed = 4500; + public void init(OpMode opmode){ rotation.init(opmode, "turret", 145.1 * ((double) 131 /24)); //Previously 103.8 flywheel.init(opmode, "flywheel", 28); + flywheel2.init(opmode, "flywheel2", 28); hood.init(opmode, "hood"); gate.init(opmode, "gate"); @@ -48,10 +56,14 @@ public void init(OpMode opmode){ gate.setAngle(0.5); hood.setDirection(Servo.Direction.REVERSE); + flywheel2.setDirection(DcMotorSimple.Direction.REVERSE); + // Pass PID pidCoefficients to motor classes rotation.setPidCoefficients(turretCoefficients); flywheel.setPidCoefficients(flywheelCoefficients); flywheel.setFFCoefficients(flywheelFFCoefficients); + flywheel2.setPidCoefficients(flywheelCoefficients); + flywheel2.setFFCoefficients(flywheelFFCoefficients); } public void updatePIDs(){ @@ -59,6 +71,8 @@ public void updatePIDs(){ rotation.setPidCoefficients(turretCoefficients); flywheel.setPidCoefficients(flywheelCoefficients); flywheel.setFFCoefficients(flywheelFFCoefficients); + flywheel2.setPidCoefficients(flywheelCoefficients); + flywheel2.setFFCoefficients(flywheelFFCoefficients); } /** @@ -80,10 +94,10 @@ public void setGate(gatestate state){ /** * Sets the angle of the hood. - * @param angle An angle in degrees that is constrained to between 0 and 45 + * @param angle An angle in degrees that is constrained to between 0 and 320 degrees */ public void setHood(double angle){ - hood.setAngle(Math.min(Math.max(angle, 0), 320)/(360*5)); + hood.setAngle(Math.min(Math.max(angle, 0), 260)/(360*5)); } /** @@ -125,6 +139,7 @@ public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ */ public void setFlywheelRPM(double rpm){ flywheel.setRPM(rpm); + flywheel2.setPower(flywheel.getPower()); } /** @@ -147,7 +162,7 @@ public void setFlywheel(flywheelstate state){ */ public void updateFlywheel(){ if (flywheelState == flywheelstate.ON){ - setFlywheelRPM(5485.714285714286); + setFlywheelRPM(onSpeed); } else if (flywheelState == flywheelstate.OFF){ setFlywheelRPM(0); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index 0f77fc77f277..697b59448911 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -53,7 +53,7 @@ public class LoadHardwareClass { public final Intake intake; // Declare various enums & other variables that are useful across files - public static Alliance selectedAlliance = Alliance.RED; + public static Alliance selectedAlliance = null; public enum Alliance { RED, BLUE diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 2db9822bde1f..44511b6e7d33 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -64,6 +64,8 @@ public class Teleop_Main_ extends LinearOpMode { public int shootingState = 0; public TimerEx shootingDelay = new TimerEx(1); + private double hoodAngle = 0; + Prompter prompter = null; // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. @@ -115,29 +117,30 @@ public void runOpMode() { telemetry.addData("SpeedMult", Robot.drivetrain.speedMultiplier); telemetry.addLine(); // Turret-related Telemetry - telemetry.addData("Turret Target Angle:", Robot.turret.rotation.target); + panelsTelemetry.addData("Turret Target Angle", Robot.turret.rotation.target); + panelsTelemetry.addData("Turret Actual Angle", Robot.turret.rotation.getAngleAbsolute()); + telemetry.addData("Turret Target Angle", Robot.turret.rotation.target); telemetry.addData("Turret Actual Angle", Robot.turret.rotation.getAngleAbsolute()); + telemetry.addData("Turret Hood Angle", Robot.turret.getHood()); telemetry.addLine(); panelsTelemetry.addData("Flywheel Target Speed", Robot.turret.flywheel.target); panelsTelemetry.addData("Flywheel Actual Speed", Robot.turret.getFlywheelRPM()); + panelsTelemetry.addData("Flywheel Power", Robot.turret.flywheel.getPower()); telemetry.addData("Flywheel Target Speed", Robot.turret.flywheel.target); telemetry.addData("Flywheel Actual Speed", Robot.turret.getFlywheelRPM()); - - telemetry.addLine(); - telemetry.addData("Belt Power", Robot.intake.belt.getPower()); - + telemetry.addData("Flywheel State", Robot.turret.getFlywheelRPM()); // Intake-related Telemetry telemetry.addLine(); - telemetry.addData("Intake Status", Robot.intake.intake.getPower()); + telemetry.addData("Intake Mode", Robot.intake.getMode()); // System-related Telemetry telemetry.addLine(); telemetry.addData("Status", "Run Time: " + runtime.toString()); - telemetry.addData("Version: ", "11/4/25"); + telemetry.addData("Version: ", "12/12/25"); telemetry.update(); - + panelsTelemetry.update(); } } @@ -256,14 +259,14 @@ public void Gamepad2() { //Intake Controls (Left Stick Y) if (shootingState == 0) { - if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones && shootingState > 0) { - if (gamepad2.left_stick_y > 0) { // OUT (Digital) - Robot.intake.setMode(Intake.intakeMode.REVERSING); + if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones) { + if (gamepad2.left_stick_y < 0) { // OUT (Digital) + Robot.intake.setMode(intakeMode.REVERSING); } else { // IN (Digital) Robot.intake.setMode(intakeMode.INTAKING); } } else { // OFF - Robot.intake.setMode(Intake.intakeMode.OFF); + Robot.intake.setMode(intakeMode.OFF); } //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()) { @@ -276,6 +279,15 @@ public void Gamepad2() { } Robot.turret.updateFlywheel(); + // Hood Controls + double increment = 4; + if (gamepad2.dpad_up && hoodAngle < 260){ + hoodAngle += increment; + }else if (gamepad2.dpad_down && hoodAngle > 0){ + hoodAngle -= increment; + } + Robot.turret.setHood(hoodAngle); + //Shoot (B Button Press) // Increment the shooting state if (gamepad2.bWasPressed() && shootingState < 2 && Robot.turret.getFlywheelRPM() > 5000) { From 51c508ede92cda5d394cc11f6bb046cae8b8e9bf Mon Sep 17 00:00:00 2001 From: Ari Date: Mon, 15 Dec 2025 17:59:33 -0500 Subject: [PATCH 103/152] Added the barebones structure for advanced telemetry handling. --- .../ftc/teamcode/LOADCode/Main_/Utils_.java | 59 +++++++++++++++++++ 1 file changed, 59 insertions(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java index 08c21def1bd9..a5de6ba89773 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java @@ -5,6 +5,16 @@ import java.util.List; public class Utils_ { + + public enum telemetrySortCategory { + DRIVETRAIN, + INTAKE, + TRANSFER, + TURRET, + TESTINGVALUES, + OTHER, + } + /** * Performs spline interpolation given a set of control points. */ @@ -147,4 +157,53 @@ public String toString() { } } + + /** + * This class is for the runtime per-loop sorting and displaying of every single TelemetryObject. + * There should only be one of these per program. + */ + public class TelemetryManager{ + List telemtryList = new ArrayList<>(); + + public void addLine(TelemetryObject telemetryline){ + telemtryList.add(telemetryline); + } + } + + /** + * This class represents a single line of telemetry, which will be sorted and managed by a TelemetryManager. + * It will contain all the relevant data for lookup and sorting, as well as functionality for live runtime editing of keys and values + */ + public class TelemetryObject{ + + Object name; + Object key; + Object value; + telemetrySortCategory category; + + public TelemetryObject(Object initialName, + Object initialKey, + Object initialValue, + telemetrySortCategory telemCategory, + TelemetryManager telemetryManagerParent){ + name = initialName; + key = initialKey; + value = initialValue; + category = telemCategory; + } + + public Object getName(){ + return name; + } + public Object getKey(){ + return key; + } + public Object getValue(){ + return value; + } + public telemetrySortCategory getTelemCategory(){ + return category; + } + + } } From a3c9f025544936a2fd0d54da3396997d544c67f7 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 15 Dec 2025 18:17:13 -0500 Subject: [PATCH 104/152] Worked on cleaning up some hardware functions, tested REV Color Sensor, and did some flywheel testing. --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 4 +-- .../Main_/Hardware_/Actuators_/Devices.java | 29 +++++++++++++++ .../Main_/Hardware_/Actuators_/Intake.java | 13 +++++-- .../Main_/Hardware_/Actuators_/Turret.java | 36 +++++++++---------- .../LOADCode/Main_/Hardware_/Commands.java | 2 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 16 ++++----- .../Main_/Teleop_/Teleop_Outreach_.java | 16 +++++++-- .../ftc/teamcode/LOADCode/Notes and TODOs | 2 +- 8 files changed, 82 insertions(+), 36 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 3567279d71bb..5cfbc244226d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -108,10 +108,10 @@ public void onStartButtonPressed() { public void onUpdate() { switch (selectedAlliance) { case RED: - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); + Robot.turret.updateAimbot(Robot, true); return; case BLUE: - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); + Robot.turret.updateAimbot(Robot, false); return; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java index 22daf0c179e9..6db114ed4315 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -7,8 +7,13 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.DistanceSensor; +import com.qualcomm.robotcore.hardware.NormalizedColorSensor; +import com.qualcomm.robotcore.hardware.NormalizedRGBA; import com.qualcomm.robotcore.hardware.Servo; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; + import dev.nextftc.control.ControlSystem; import dev.nextftc.control.KineticState; import dev.nextftc.control.feedback.PIDCoefficients; @@ -263,4 +268,28 @@ public double getAngle(){ return servo.getPosition(); } } + + public static class REVColorSensorV3Class { + private NormalizedColorSensor sensor; + + public void init(@NonNull OpMode opmode, String sensorName){ + sensor = opmode.hardwareMap.get(NormalizedColorSensor.class, sensorName); + } + + public NormalizedRGBA getNormalizedColors(){ + return sensor.getNormalizedColors(); + } + + public double getGain(){ + return sensor.getGain(); + } + + public void setGain(double gain){ + sensor.setGain((float) gain); + } + + public double getDistance(DistanceUnit units){ + return ((DistanceSensor) sensor).getDistance(units); + } + } } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 13eff1a3a1f7..aa619ed9d38d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -7,9 +7,13 @@ public class Intake { // RESET THESE TO PRIVATE AFTER DECEMBER 6TH! - public final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); - public final Devices.CRServoClass belt = new Devices.CRServoClass(); - public final Devices.ServoClass transfer = new Devices.ServoClass(); + private final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); + private final Devices.CRServoClass belt = new Devices.CRServoClass(); + private final Devices.ServoClass transfer = new Devices.ServoClass(); + public final Devices.REVColorSensorV3Class color1 = new Devices.REVColorSensorV3Class(); + public final Devices.REVColorSensorV3Class color2 = new Devices.REVColorSensorV3Class(); + public final Devices.REVColorSensorV3Class color3 = new Devices.REVColorSensorV3Class(); + public final Devices.REVColorSensorV3Class color4 = new Devices.REVColorSensorV3Class(); public enum intakeMode { INTAKING, @@ -27,11 +31,14 @@ public void init(OpMode opmode){ intake.init(opmode, "intake"); belt.init(opmode, "belt"); transfer.init(opmode, "transfer"); + color1.init(opmode, "color1"); intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); intake.setDirection(DcMotorSimple.Direction.REVERSE); belt.setDirection(DcMotorSimple.Direction.REVERSE); + + color1.setGain(2); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 9ec43097d921..a748086bd5d0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -1,5 +1,7 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; +import androidx.annotation.NonNull; + import com.bylazar.configurables.annotations.Configurable; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; @@ -7,6 +9,8 @@ import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.Servo; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; + import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; @@ -16,19 +20,18 @@ public class Turret { // Hardware definitions public final Devices.DcMotorExClass rotation = new Devices.DcMotorExClass(); public final Devices.DcMotorExClass flywheel = new Devices.DcMotorExClass(); - public final Devices.DcMotorExClass flywheel2 = new Devices.DcMotorExClass(); - public final Devices.ServoClass hood = new Devices.ServoClass(); - public final Devices.ServoClass gate = new Devices.ServoClass(); + private final Devices.DcMotorExClass flywheel2 = new Devices.DcMotorExClass(); + private final Devices.ServoClass hood = new Devices.ServoClass(); + private final Devices.ServoClass gate = new Devices.ServoClass(); // Turret PID coefficients public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.06, 0, 0); // 223RPM //public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.3, 0, 0.007); // 1150RPM // Flywheel PID coefficients - //public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0003, 0.0001, 0.0001); - //public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.00002899,0,0); - public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.00005, 0, 0); - public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.0003,0,0); + // 4500RPM + public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0002, 0, 0); + public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.000026,0,0); public enum gatestate { OPEN, @@ -76,15 +79,14 @@ public void updatePIDs(){ } /** - * @param robotPose The pose of the robot, gotten from PedroPathing's localization + * @param robot The pose of the robot, gotten from PedroPathing's localization * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. */ - public void updateAimbot(Pose robotPose, boolean targetRedGoal){ - rotation.setAngle(calcLocalizer(robotPose, targetRedGoal)); + public void updateAimbot(@NonNull LoadHardwareClass robot, boolean targetRedGoal){ + rotation.setAngle(calcLocalizer(robot.drivetrain.follower.getPose(), targetRedGoal)); } - - public void setGate(gatestate state){ + public void setGateState(gatestate state){ if (state == gatestate.OPEN){ gate.setAngle(0.5); }else if (state == gatestate.CLOSED){ @@ -137,23 +139,21 @@ public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ * @param rpm * RPM Range [0,6000] */ - public void setFlywheelRPM(double rpm){ + private void setFlywheelRPM(double rpm){ flywheel.setRPM(rpm); flywheel2.setPower(flywheel.getPower()); } - /** - * @return double flywheel.getRPM(); - RPM Range [0,6000] - */ public double getFlywheelRPM(){ return flywheel.getRPM(); } /** - * Sets the target state of the Flywheel + * Sets the target state of the Flywheel.
+ * updateFlywheel() must be called every loop for this to be effective. * @param state The state to set the flywheel to (ON/OFF) */ - public void setFlywheel(flywheelstate state){ + public void setFlywheelState(flywheelstate state){ flywheelState = state; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 9ecdc2411d6e..4a91ea4f26df 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -26,7 +26,7 @@ public static Command runPath(PathChain path, boolean holdEnd, double maxPower) public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheelstate state) { return new LambdaCommand("setFlywheelState()") .setInterruptible(false) - .setStart(() -> Robot.turret.setFlywheel(state)) + .setStart(() -> Robot.turret.setFlywheelState(state)) .setIsDone(() -> { if (state == Turret.flywheelstate.ON){ return Robot.turret.getFlywheelRPM() > 5900; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 44511b6e7d33..a5f79ab5faa7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -252,9 +252,9 @@ public void Gamepad2() { // Turret Aimbot if (selectedAlliance == Alliance.RED) { - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), true); + Robot.turret.updateAimbot(Robot, true); } else if (selectedAlliance == Alliance.BLUE) { - Robot.turret.updateAimbot(Robot.drivetrain.follower.getPose(), false); + Robot.turret.updateAimbot(Robot, false); } //Intake Controls (Left Stick Y) @@ -271,9 +271,9 @@ public void Gamepad2() { //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()) { if (Robot.turret.flywheelState == flywheelstate.OFF) { - Robot.turret.setFlywheel(flywheelstate.ON); + Robot.turret.setFlywheelState(flywheelstate.ON); } else { - Robot.turret.setFlywheel(flywheelstate.OFF); + Robot.turret.setFlywheelState(flywheelstate.OFF); } } } @@ -299,7 +299,7 @@ public void Gamepad2() { return; case 1: Robot.intake.setMode(intakeMode.INTAKING); - Robot.turret.setGate(gatestate.OPEN); + Robot.turret.setGateState(gatestate.OPEN); telemetry.addData("Shooting State", "STARTED"); return; case 2: @@ -316,14 +316,12 @@ public void Gamepad2() { telemetry.addData("Shooting State", "DELAY"); return; case 4: - Robot.turret.setFlywheel(flywheelstate.OFF); - Robot.turret.setGate(gatestate.CLOSED); + Robot.turret.setFlywheelState(flywheelstate.OFF); + Robot.turret.setGateState(gatestate.CLOSED); Robot.intake.setMode(intakeMode.OFF); Robot.intake.setTransfer(transferState.DOWN); telemetry.addData("Shooting State", "RESET"); shootingState = 0; } - - } } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index d75c5851e3f1..50167883006f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -34,8 +34,10 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.NormalizedRGBA; import com.qualcomm.robotcore.util.ElapsedTime; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @TeleOp(name="Teleop_Outreach_", group="TeleOp") @@ -80,9 +82,9 @@ public void runOpMode() { ); if (gamepad1.x){ - Robot.turret.rotation.setAngle(180); + //Robot.turret.rotation.setAngle(180); }else{ - Robot.turret.rotation.setAngle(Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true)); + //Robot.turret.rotation.setAngle(Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true)); } telemetry.addData("Target Angle", Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true)); telemetry.addData("Turret Angle", Robot.turret.rotation.getAngleAbsolute()); @@ -98,6 +100,16 @@ public void runOpMode() { Robot.turret.setHood(hoodAngle); telemetry.addData("Hood Angle", Robot.turret.getHood()); + telemetry.addLine(); + telemetry.addData("Gain", Robot.intake.color1.getGain()); + telemetry.addData("Distance", Robot.intake.color1.getDistance(DistanceUnit.INCH)); + telemetry.addData("Color", Robot.intake.color1.getNormalizedColors().toColor()); + NormalizedRGBA colors = Robot.intake.color1.getNormalizedColors(); + telemetry.addData("R", colors.red); + telemetry.addData("G", colors.green); + telemetry.addData("B", colors.blue); + + telemetry.addLine(); telemetry.addData("Robot Pose X", Math.round(Robot.drivetrain.follower.getPose().getX())); telemetry.addData("Robot Pose Y", Math.round(Robot.drivetrain.follower.getPose().getY())); telemetry.addData("Robot Pose H", Math.round(Math.toDegrees(Robot.drivetrain.follower.getPose().getHeading()))); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 3186bc743189..1cbabd505c3d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -10,7 +10,7 @@ //TODO, Add a more advanced telemetry handler for better organization, readability, and debugging -//TODO, Add proper functionality for manual turret control to Turret.java +//DONE, Add proper functionality for manual turret control to Turret.java //DONE, Shoot mode state machine Off->On->LastShot->Delay->ResetActuators->Off etc. cycled with B button on Gamepad2 From 5871b1665b8c56dc052117a640a90c94596095ae Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 16 Dec 2025 21:05:34 -0500 Subject: [PATCH 105/152] Tuned PedroPathing and worked on the auto system --- .../LOADCode/Main_/Auto_/Auto_Dec6th.java | 3 +- .../LOADCode/Main_/Auto_/Auto_Main_.java | 60 +-- .../LOADCode/Main_/Hardware_/Commands.java | 1 + .../Drivetrain_/MecanumDrivetrainClass.java | 24 +- .../Hardware_/Drivetrain_/Pedro_Paths.java | 346 +++++++++--------- .../Main_/Hardware_/LoadHardwareClass.java | 18 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 1 + .../ftc/teamcode/LOADCode/Notes and TODOs | 14 +- .../ftc/teamcode/pedroPathing/Constants.java | 21 +- .../ftc/teamcode/pedroPathing/Tuning.java | 19 +- 10 files changed, 268 insertions(+), 239 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java index a50fec1b7185..fc0786fae05d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Dec6th.java @@ -3,6 +3,7 @@ import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorSimple; @@ -10,7 +11,7 @@ import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; - +@Disabled @Autonomous(name = "Auto_Dec6th", group = "TestAuto", preselectTeleOp="Teleop_Main_") public class Auto_Dec6th extends OpMode { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 5cfbc244226d..4ae1a0e636f2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -2,15 +2,17 @@ import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; +import com.pedropathing.geometry.BezierCurve; import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.Path; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @@ -23,7 +25,6 @@ import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; -@Disabled @Autonomous(name = "Auto_Main_", group = "Main", preselectTeleOp="Teleop_Main_") public class Auto_Main_ extends NextFTCOpMode { @@ -33,11 +34,13 @@ public class Auto_Main_ extends NextFTCOpMode { private enum Auto { LEAVE_NEAR_LAUNCH, LEAVE_FAR_HP, - MOVEMENT_RP_DEC6 + TEST_AUTO } private Auto selectedAuto = null; - private boolean turretOn = false; + private boolean turretOn = true; + + Pedro_Paths paths = new Pedro_Paths(); // Create the prompter object for selecting Alliance and Auto Prompter prompter = null; @@ -53,10 +56,6 @@ public Auto_Main_() { @Override public void onInit() { - // Initialize all hardware of the robot - Robot.init(startPose); - Robot.drivetrain.follower = PedroComponent.follower(); - prompter = new Prompter(this); prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", @@ -67,7 +66,7 @@ public void onInit() { new OptionPrompt<>("Select Auto", Auto.LEAVE_NEAR_LAUNCH, Auto.LEAVE_FAR_HP, - Auto.MOVEMENT_RP_DEC6 + Auto.TEST_AUTO )); prompter.onComplete(() -> { selectedAlliance = prompter.get("alliance"); @@ -78,7 +77,6 @@ public void onInit() { telemetry.update(); } ); - Robot.drivetrain.paths.buildPaths(selectedAlliance); } @Override @@ -92,27 +90,29 @@ public void onStartButtonPressed() { switch (selectedAuto) { case LEAVE_NEAR_LAUNCH: Leave_Near_Launch().schedule(); - startPose = new Pose(0,0,0); return; case LEAVE_FAR_HP: Leave_Far_HP().schedule(); - startPose = new Pose(0,0,0); return; - case MOVEMENT_RP_DEC6: - Movement_RP_Dec6th().schedule(); - startPose = new Pose(0,0,0); + case TEST_AUTO: + test_Auto().schedule(); } + // Initialize all hardware of the robot + Robot.init(startPose, PedroComponent.follower()); + paths.buildPaths(selectedAlliance, PedroComponent.follower()); } @Override public void onUpdate() { - switch (selectedAlliance) { - case RED: - Robot.turret.updateAimbot(Robot, true); - return; - case BLUE: - Robot.turret.updateAimbot(Robot, false); - return; + if (turretOn){ + switch (selectedAlliance) { + case RED: + Robot.turret.updateAimbot(Robot, true); + return; + case BLUE: + Robot.turret.updateAimbot(Robot, false); + return; + } } telemetry.addData("selectedAuto", selectedAuto); @@ -127,10 +127,11 @@ public void onUpdate() { */ private Command Leave_Far_HP() { turretOn = true; + startPose = Robot.drivetrain.paths.farStart; return new SequentialGroup( Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new ParallelGroup( - new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), + new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.onSpeed), new Delay(5) ), Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), @@ -144,7 +145,7 @@ private Command Leave_Far_HP() { Commands.setTransferState(Robot, Intake.transferState.DOWN), Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), - Commands.runPath(Robot.drivetrain.paths.start2_to_leave3, true, 0.6) + Commands.runPath(Robot.drivetrain.paths.farStart_to_farLeave, true, 0.6) ); } @@ -155,10 +156,11 @@ private Command Leave_Far_HP() { */ private Command Leave_Near_Launch() { turretOn = true; + startPose = Robot.drivetrain.paths.nearStart; return new SequentialGroup( Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new ParallelGroup( - new WaitUntil(() -> Robot.turret.getFlywheelRPM() > 5900), + new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.onSpeed), new Delay(5) ), Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), @@ -172,13 +174,11 @@ private Command Leave_Near_Launch() { Commands.setTransferState(Robot, Intake.transferState.DOWN), Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), - Commands.runPath(Robot.drivetrain.paths.start1_to_leave1, true, 0.6) + Commands.runPath(Robot.drivetrain.paths.nearShoot_to_nearLeave, true, 0.6) ); } - private Command Movement_RP_Dec6th(){ - return new SequentialGroup( - new FollowPath(Robot.drivetrain.paths.basicMoveRPPath, true, 0.5) - ); + private Command test_Auto(){ + return new FollowPath(new Path(new BezierCurve(paths.farStart, paths.farLeave)), true, 0.6); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 4a91ea4f26df..cfba3a807f2f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -48,4 +48,5 @@ public static Command setTransferState(LoadHardwareClass Robot, Intake.transferS .setStart(() -> Robot.intake.setTransfer(state)) .requires(intakeSystem)); } + } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index ceda43b9eb0f..5eebc1484a7a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -7,6 +7,7 @@ import com.pedropathing.paths.PathChain; import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; public class MecanumDrivetrainClass { @@ -15,7 +16,7 @@ public class MecanumDrivetrainClass { // Misc Constants public Follower follower = null; - public Pedro_Paths paths = null; + public Pedro_Paths paths = new Pedro_Paths(); /** * Initializes the PedroPathing follower. @@ -23,13 +24,30 @@ public class MecanumDrivetrainClass { * @param myOpMode Allows the follower access to the robot hardware. * @param initialPose The starting pose of the robot. */ - public void init (@NonNull OpMode myOpMode, Pose initialPose){ + public void init (@NonNull OpMode myOpMode, Pose initialPose, LoadHardwareClass.Alliance alliance){ // PedroPathing initialization follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower - paths = new Pedro_Paths(follower); follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field follower.update(); // Applies the initialization + //TODO uncommment this: paths.buildPaths(alliance, follower); + } + + /** + * Initializes the PedroPathing follower. + * Needs to be run once after all hardware is initialized. + * @param myOpMode Allows the follower access to the robot hardware. + * @param initialPose The starting pose of the robot. + * @param follow The PedroPathing follower object + */ + public void init (@NonNull OpMode myOpMode, Pose initialPose, LoadHardwareClass.Alliance alliance, Follower follow){ + // PedroPathing initialization + follower = follow; // Initializes the PedroPathing path follower + follower.setPose(initialPose); // Sets the initial position of the robot on the field + follower.update(); // Applies the initialization + //TODO uncommment this: paths.buildPaths(alliance, follower); + } + public void startTeleOpDrive(){ follower.startTeleopDrive(); follower.update(); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index d45fa0c3d763..6955f64d93ef 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -15,46 +15,43 @@ public class Pedro_Paths { /** * Define primary poses to be used in paths */ - // Dummy Stand-In Poses - public Pose dummyStartPose = new Pose(0,0,0); - public Pose dummyMoveRPPose = new Pose(0,28,0); // Start Poses - public Pose startPose1 = new Pose(112, 136.6, Math.toRadians(270)); - public Pose startPose2 = new Pose(88, 7.4, Math.toRadians(90)); + public Pose nearStart = new Pose(112, 136.6, Math.toRadians(270)); + public Pose farStart = new Pose(88, 7.4, Math.toRadians(90)); // Preload Poses - public Pose preloadPose1 = new Pose(130.000, 83.500, Math.toRadians(90)); - public Pose preloadPose2 = new Pose(132.000, 59.500, Math.toRadians(90)); - public Pose preloadPose3 = new Pose(132.000, 35.500, Math.toRadians(90)); + public Pose nearPreload = new Pose(130.000, 83.500, Math.toRadians(90)); + public Pose midPreload = new Pose(132.000, 59.500, Math.toRadians(90)); + public Pose farPreload = new Pose(132.000, 35.500, Math.toRadians(90)); // Shooting Poses - public Pose shootingPose1 = new Pose(115, 120, Math.toRadians(-35)); - public Pose shootingPose2 = new Pose(85, 85, Math.toRadians(-15)); - public Pose shootingPose3 = new Pose(85, 15, Math.toRadians(60)); + public Pose nearShoot = new Pose(115, 120, Math.toRadians(-35)); + public Pose midShoot = new Pose(85, 85, Math.toRadians(-15)); + public Pose farShoot = new Pose(85, 15, Math.toRadians(60)); // Leave Poses - public Pose leavePose1 = new Pose(90,120); - public Pose leavePose2 = new Pose(95,55); - public Pose leavePose3 = new Pose(115,20); + public Pose nearLeave = new Pose(90,120); + public Pose midLeave = new Pose(95,55); + public Pose farLeave = new Pose(115,20); // Define all path variables // Dummy Paths public PathChain basicMoveRPPath; // Start Poses to Preloads - public PathChain startPose1_to_preload1, startPose1_to_preload2, startPose1_to_preload3; - public PathChain startPose2_to_preload1, startPose2_to_preload2, startPose2_to_preload3; + public PathChain nearStart_to_nearPreload, nearStart_to_midPreload, nearStart_to_farPreload; + public PathChain farStart_to_nearPreload, farStart_to_midPreload, farStart_to_farPreload; // Preloads to Shooting Positions - public PathChain preload1_to_shooting1, preload1_to_shooting2, preload1_to_shooting3; - public PathChain preload2_to_shooting1, preload2_to_shooting2, preload2_to_shooting3; - public PathChain preload3_to_shooting1, preload3_to_shooting2, preload3_to_shooting3; + public PathChain nearPreload_to_nearShoot, nearPreload_to_midShoot, nearPreload_to_farShoot; + public PathChain midPreload_to_nearShoot, midPreload_to_midShoot, midPreload_to_farShoot; + public PathChain farPreload_to_nearShoot, farPreload_to_midShoot, farPreload_to_farShoot; // Shooting Positions to Preloads - public PathChain shooting1_to_preload1, shooting1_to_preload2, shooting1_to_preload3; - public PathChain shooting2_to_preload1, shooting2_to_preload2, shooting2_to_preload3; - public PathChain shooting3_to_preload1, shooting3_to_preload2, shooting3_to_preload3; + public PathChain nearShoot_to_nearPreload, nearShoot_to_midPreload, nearShoot_to_farPreload; + public PathChain midShoot_to_nearPreload, midShoot_to_midPreload, midShoot_to_farPreload; + public PathChain farShoot_to_nearPreload, farShoot_to_midPreload, farShoot_to_farPreload; // Shooting Positions to Leave Positions - public PathChain shooting1_to_leave1, shooting1_to_leave2; - public PathChain shooting2_to_leave1, shooting2_to_leave2; - public PathChain shooting3_to_leave2, shooting3_to_leave3; + public PathChain nearShoot_to_nearLeave, nearShoot_to_midLeave; + public PathChain midShoot_to_nearLeave, midShoot_to_midLeave; + public PathChain farShoot_to_midLeave, farShoot_to_farLeave; // Start Positions to Leave Positions - public PathChain start1_to_leave1, start1_to_leave2; - public PathChain start2_to_leave2, start2_to_leave3; + public PathChain nearStart_to_nearLeave, nearStart_to_midLeave; + public PathChain farStart_to_midLeave, farStart_to_farLeave; public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ int mult = 1; @@ -68,349 +65,340 @@ public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ ); } - /** - *

DON'T EVER USE THIS PATH!!!

- * This path is ONLY for the December 6th scrimmage, for movement RP bonus only! - */ - public void buildMoveRPPath(){ - basicMoveRPPath = follower.pathBuilder() - .addPath(new BezierCurve(dummyStartPose,dummyMoveRPPose)) - .setLinearHeadingInterpolation(dummyStartPose.getHeading(), dummyMoveRPPose.getHeading()) - .build(); - } public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { - startPose1_to_preload1 = follower.pathBuilder() + nearStart_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose1, alliance), + autoMirror(nearStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), autoMirror(new Pose(89.000, 78.000), alliance), autoMirror(new Pose(95.000, 83.500), alliance), autoMirror(new Pose(110.000, 83.500), alliance) )) - .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(preloadPose1, alliance) + autoMirror(nearPreload, alliance) )) .setTangentHeadingInterpolation() .build(); - startPose1_to_preload2 = follower.pathBuilder() + nearStart_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose1, alliance), + autoMirror(nearStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), autoMirror(new Pose(89.000, 54.000), alliance), autoMirror(new Pose(95.000, 59.500), alliance), autoMirror(new Pose(110.000, 59.500), alliance) )) - .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 59.500), alliance), - autoMirror(preloadPose2, alliance) + autoMirror(midPreload, alliance) )) .setTangentHeadingInterpolation() .build(); - startPose1_to_preload3 = follower.pathBuilder() + nearStart_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose1, alliance), + autoMirror(nearStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), autoMirror(new Pose(89.000, 30.000), alliance), autoMirror(new Pose(95.000, 35.500), alliance), autoMirror(new Pose(110.000, 35.500), alliance) )) - .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(preloadPose3, alliance) + autoMirror(farPreload, alliance) )) .setTangentHeadingInterpolation() .build(); } public void buildStart2ToPreloads(LoadHardwareClass.Alliance alliance){ - startPose2_to_preload1 = follower.pathBuilder() + farStart_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose2, alliance), + autoMirror(farStart, alliance), autoMirror(new Pose(89.000, 89.000), alliance), autoMirror(new Pose(95.000, 83.500), alliance), autoMirror(new Pose(110.000, 83.500), alliance) )) - .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) + .setLinearHeadingInterpolation(farStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(preloadPose1, alliance) + autoMirror(nearPreload, alliance) )) .setTangentHeadingInterpolation() .build(); - startPose2_to_preload2 = follower.pathBuilder() + farStart_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose2, alliance), + autoMirror(farStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), autoMirror(new Pose(89.000, 65.000), alliance), autoMirror(new Pose(95.000, 59.500), alliance), autoMirror(new Pose(110.000, 59.500), alliance) )) - .setLinearHeadingInterpolation(startPose1.getHeading(), Math.toRadians(0)) + .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 59.500), alliance), - autoMirror(preloadPose2, alliance) + autoMirror(midPreload, alliance) )) .setTangentHeadingInterpolation() .build(); - startPose2_to_preload3 = follower.pathBuilder() + farStart_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose2, alliance), + autoMirror(farStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), autoMirror(new Pose(89.000, 41.000), alliance), autoMirror(new Pose(95.000, 35.500), alliance), autoMirror(new Pose(110.000, 35.500), alliance) )) - .setLinearHeadingInterpolation(startPose2.getHeading(), Math.toRadians(0)) + .setLinearHeadingInterpolation(farStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(preloadPose3, alliance) + autoMirror(farPreload, alliance) )) .setTangentHeadingInterpolation() .build(); } public void buildPreload1ToShootings(LoadHardwareClass.Alliance alliance){ - preload1_to_shooting1 = follower.pathBuilder() + nearPreload_to_nearShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose1, alliance), - autoMirror(shootingPose1, alliance) + autoMirror(nearPreload, alliance), + autoMirror(nearShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose1.getHeading(), shootingPose1.getHeading()) + .setLinearHeadingInterpolation(nearPreload.getHeading(), nearShoot.getHeading()) .build(); - preload1_to_shooting2 = follower.pathBuilder() + nearPreload_to_midShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose1, alliance), - autoMirror(shootingPose2, alliance) + autoMirror(nearPreload, alliance), + autoMirror(midShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose1.getHeading(), shootingPose2.getHeading()) + .setLinearHeadingInterpolation(nearPreload.getHeading(), midShoot.getHeading()) .build(); - preload1_to_shooting3 = follower.pathBuilder() + nearPreload_to_farShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose1, alliance), + autoMirror(nearPreload, alliance), autoMirror(new Pose(80.000, 83.500), alliance), - autoMirror(shootingPose3, alliance) + autoMirror(farShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose1.getHeading(), shootingPose3.getHeading()) + .setLinearHeadingInterpolation(nearPreload.getHeading(), farShoot.getHeading()) .build(); } public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ - preload2_to_shooting1 = follower.pathBuilder() + midPreload_to_nearShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose2, alliance), + autoMirror(midPreload, alliance), autoMirror(new Pose(65,59.5), alliance), - autoMirror(shootingPose1, alliance) + autoMirror(nearShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose1.getHeading()) + .setLinearHeadingInterpolation(midPreload.getHeading(), nearShoot.getHeading()) .build(); - preload2_to_shooting2 = follower.pathBuilder() + midPreload_to_midShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose2, alliance), + autoMirror(midPreload, alliance), autoMirror(new Pose(65,59.5), alliance), - autoMirror(shootingPose2, alliance) + autoMirror(midShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose2.getHeading()) + .setLinearHeadingInterpolation(midPreload.getHeading(), midShoot.getHeading()) .build(); - preload2_to_shooting3 = follower.pathBuilder() + midPreload_to_farShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose2, alliance), + autoMirror(midPreload, alliance), autoMirror(new Pose(90.000, 59.500), alliance), - autoMirror(shootingPose3, alliance) + autoMirror(farShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose3.getHeading()) + .setLinearHeadingInterpolation(midPreload.getHeading(), farShoot.getHeading()) .build(); } public void buildPreload3ToShootings(LoadHardwareClass.Alliance alliance){ - preload3_to_shooting1 = follower.pathBuilder() + farPreload_to_nearShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose2, alliance), + autoMirror(midPreload, alliance), autoMirror(new Pose(75,30), alliance), autoMirror(new Pose(80,100), alliance), - autoMirror(shootingPose1, alliance) + autoMirror(nearShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose1.getHeading()) + .setLinearHeadingInterpolation(midPreload.getHeading(), nearShoot.getHeading()) .build(); - preload3_to_shooting2 = follower.pathBuilder() + farPreload_to_midShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose2, alliance), + autoMirror(midPreload, alliance), autoMirror(new Pose(85,32), alliance), - autoMirror(shootingPose2, alliance) + autoMirror(midShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose2.getHeading()) + .setLinearHeadingInterpolation(midPreload.getHeading(), midShoot.getHeading()) .build(); - preload3_to_shooting3 = follower.pathBuilder() + farPreload_to_farShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(preloadPose2, alliance), - autoMirror(shootingPose3, alliance) + autoMirror(midPreload, alliance), + autoMirror(farShoot, alliance) )) - .setLinearHeadingInterpolation(preloadPose2.getHeading(), shootingPose3.getHeading()) + .setLinearHeadingInterpolation(midPreload.getHeading(), farShoot.getHeading()) .build(); } public void buildShooting1ToPreloads(LoadHardwareClass.Alliance alliance){ - shooting1_to_preload1 = follower.pathBuilder() + nearShoot_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose1, alliance), + autoMirror(nearShoot, alliance), autoMirror(new Pose(60, 80), alliance), - autoMirror(preloadPose1, alliance) + autoMirror(nearPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose1.getHeading(), preloadPose1.getHeading()) + .setLinearHeadingInterpolation(nearShoot.getHeading(), nearPreload.getHeading()) .build(); - shooting1_to_preload2 = follower.pathBuilder() + nearShoot_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose1, alliance), + autoMirror(nearShoot, alliance), autoMirror(new Pose(60, 55), alliance), - autoMirror(preloadPose2, alliance) + autoMirror(midPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose1.getHeading(), preloadPose2.getHeading()) + .setLinearHeadingInterpolation(nearShoot.getHeading(), midPreload.getHeading()) .build(); - shooting1_to_preload3 = follower.pathBuilder() + nearShoot_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose1, alliance), + autoMirror(nearShoot, alliance), autoMirror(new Pose(60, 27), alliance), - autoMirror(preloadPose3, alliance) + autoMirror(farPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose1.getHeading(), preloadPose3.getHeading()) + .setLinearHeadingInterpolation(nearShoot.getHeading(), farPreload.getHeading()) .build(); } public void buildShooting2ToPreloads(LoadHardwareClass.Alliance alliance){ - shooting2_to_preload1 = follower.pathBuilder() + midShoot_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose2, alliance), - autoMirror(preloadPose1, alliance) + autoMirror(midShoot, alliance), + autoMirror(nearPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose2.getHeading(), preloadPose1.getHeading()) + .setLinearHeadingInterpolation(midShoot.getHeading(), nearPreload.getHeading()) .build(); - shooting2_to_preload2 = follower.pathBuilder() + midShoot_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose2, alliance), + autoMirror(midShoot, alliance), autoMirror(new Pose(75, 56), alliance), - autoMirror(preloadPose2, alliance) + autoMirror(midPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose2.getHeading(), preloadPose2.getHeading()) + .setLinearHeadingInterpolation(midShoot.getHeading(), midPreload.getHeading()) .build(); - shooting2_to_preload3 = follower.pathBuilder() + midShoot_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose2, alliance), + autoMirror(midShoot, alliance), autoMirror(new Pose(68, 30), alliance), - autoMirror(preloadPose3, alliance) + autoMirror(farPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose2.getHeading(), preloadPose3.getHeading()) + .setLinearHeadingInterpolation(midShoot.getHeading(), farPreload.getHeading()) .build(); } public void buildShooting3ToPreloads(LoadHardwareClass.Alliance alliance){ - shooting3_to_preload1 = follower.pathBuilder() + farShoot_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose3, alliance), + autoMirror(farShoot, alliance), autoMirror(new Pose(73, 88), alliance), - autoMirror(preloadPose1, alliance) + autoMirror(nearPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose3.getHeading(), preloadPose1.getHeading()) + .setLinearHeadingInterpolation(farShoot.getHeading(), nearPreload.getHeading()) .build(); - shooting3_to_preload2 = follower.pathBuilder() + farShoot_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose3, alliance), + autoMirror(farShoot, alliance), autoMirror(new Pose(78, 62), alliance), - autoMirror(preloadPose2, alliance) + autoMirror(midPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose3.getHeading(), preloadPose2.getHeading()) + .setLinearHeadingInterpolation(farShoot.getHeading(), midPreload.getHeading()) .build(); - shooting3_to_preload3 = follower.pathBuilder() + farShoot_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose3, alliance), + autoMirror(farShoot, alliance), autoMirror(new Pose(82.5, 35), alliance), - autoMirror(preloadPose3, alliance) + autoMirror(farPreload, alliance) )) - .setLinearHeadingInterpolation(shootingPose3.getHeading(), preloadPose3.getHeading()) + .setLinearHeadingInterpolation(farShoot.getHeading(), farPreload.getHeading()) .build(); } public void buildShooting1ToLeaves(LoadHardwareClass.Alliance alliance){ - shooting1_to_leave1 = follower.pathBuilder() + nearShoot_to_nearLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose1, alliance), - autoMirror(leavePose1, alliance) + autoMirror(nearShoot, alliance), + autoMirror(nearLeave, alliance) )) - .setConstantHeadingInterpolation(shootingPose1.getHeading()) + .setConstantHeadingInterpolation(nearShoot.getHeading()) .build(); - shooting1_to_leave2 = follower.pathBuilder() + nearShoot_to_midLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose1, alliance), - autoMirror(leavePose2, alliance) + autoMirror(nearShoot, alliance), + autoMirror(midLeave, alliance) )) - .setConstantHeadingInterpolation(shootingPose1.getHeading()) + .setConstantHeadingInterpolation(nearShoot.getHeading()) .build(); } public void buildShooting2ToLeaves(LoadHardwareClass.Alliance alliance){ - shooting2_to_leave1 = follower.pathBuilder() + midShoot_to_nearLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose2, alliance), - autoMirror(leavePose1, alliance) + autoMirror(midShoot, alliance), + autoMirror(nearLeave, alliance) )) - .setConstantHeadingInterpolation(shootingPose2.getHeading()) + .setConstantHeadingInterpolation(midShoot.getHeading()) .build(); - shooting2_to_leave2 = follower.pathBuilder() + midShoot_to_midLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose2, alliance), - autoMirror(leavePose2, alliance) + autoMirror(midShoot, alliance), + autoMirror(midLeave, alliance) )) - .setConstantHeadingInterpolation(shootingPose2.getHeading()) + .setConstantHeadingInterpolation(midShoot.getHeading()) .build(); } public void buildShooting3ToLeaves(LoadHardwareClass.Alliance alliance){ - shooting3_to_leave2 = follower.pathBuilder() + farShoot_to_midLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose3, alliance), - autoMirror(leavePose2, alliance) + autoMirror(farShoot, alliance), + autoMirror(midLeave, alliance) )) - .setConstantHeadingInterpolation(shootingPose3.getHeading()) + .setConstantHeadingInterpolation(farShoot.getHeading()) .build(); - shooting3_to_leave3 = follower.pathBuilder() + farShoot_to_farLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(shootingPose3, alliance), - autoMirror(leavePose3, alliance) + autoMirror(farShoot, alliance), + autoMirror(farLeave, alliance) )) - .setConstantHeadingInterpolation(shootingPose3.getHeading()) + .setConstantHeadingInterpolation(farShoot.getHeading()) .build(); } public void buildStart1ToLeaves(LoadHardwareClass.Alliance alliance){ - start1_to_leave1 = follower.pathBuilder() + nearStart_to_nearLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose1, alliance), - autoMirror(leavePose1, alliance) + autoMirror(nearStart, alliance), + autoMirror(nearLeave, alliance) )) - .setConstantHeadingInterpolation(startPose1.getHeading()) + .setConstantHeadingInterpolation(nearStart.getHeading()) .build(); - start1_to_leave2 = follower.pathBuilder() + nearStart_to_midLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose1, alliance), - autoMirror(leavePose3, alliance) + autoMirror(nearStart, alliance), + autoMirror(farLeave, alliance) )) - .setConstantHeadingInterpolation(startPose1.getHeading()) + .setConstantHeadingInterpolation(nearStart.getHeading()) .build(); } public void buildStart2ToLeaves(LoadHardwareClass.Alliance alliance){ - start2_to_leave2 = follower.pathBuilder() + farStart_to_midLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose2, alliance), - autoMirror(leavePose1, alliance) + autoMirror(farStart, alliance), + autoMirror(nearLeave, alliance) )) - .setConstantHeadingInterpolation(startPose2.getHeading()) + .setConstantHeadingInterpolation(farStart.getHeading()) .build(); - start2_to_leave3 = follower.pathBuilder() + farStart_to_farLeave = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(startPose2, alliance), - autoMirror(leavePose3, alliance) + autoMirror(farStart, alliance), + autoMirror(farLeave, alliance) )) - .setConstantHeadingInterpolation(startPose2.getHeading()) + .setConstantHeadingInterpolation(farStart.getHeading()) .build(); } /** * Builds all the paths, mirroring them to the other side of the field if necessary */ - public void buildPaths(LoadHardwareClass.Alliance alliance){ + public void buildPaths(LoadHardwareClass.Alliance alliance, Follower follow){ + follower = follow; + /// All paths are for the RED side of the field. they will be mirrored if necessary. - buildMoveRPPath(); // Paths going from each start position to each of the preloads. buildStart1ToPreloads(alliance); buildStart2ToPreloads(alliance); @@ -430,12 +418,4 @@ public void buildPaths(LoadHardwareClass.Alliance alliance){ buildStart1ToLeaves(alliance); buildStart2ToLeaves(alliance); } - - /** - * Must be called after MecanumDrivetrainClass is initialized. - * @param follow PedroPathing's follower object, gotten from MecanumDrivetrainClass - */ - public Pedro_Paths(Follower follow){ - follower = follow; - } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index 697b59448911..91a7ee9afc51 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -30,6 +30,7 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; import com.bylazar.configurables.annotations.Configurable; +import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; @@ -88,7 +89,22 @@ public LoadHardwareClass(OpMode opmode) { */ public void init(Pose initialPose) { // Initialize all subclasses - drivetrain.init(myOpMode, initialPose); + drivetrain.init(myOpMode, initialPose, selectedAlliance); + turret.init(myOpMode); + intake.init(myOpMode); + + // Misc telemetry + myOpMode.telemetry.addData(">", "Hardware Initialized"); + myOpMode.telemetry.update(); + } + + /** + * Initializes all hardware for the robot. + * Must be called once at the start of each op-mode. + */ + public void init(Pose initialPose, Follower follower) { + // Initialize all subclasses + drivetrain.init(myOpMode, initialPose, selectedAlliance, follower); turret.init(myOpMode); intake.init(myOpMode); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index a5f79ab5faa7..fff9cfefe75f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -105,6 +105,7 @@ public void runOpMode() { // Initialize all hardware of the robot Robot.init(startPose); + Robot.drivetrain.startTeleOpDrive(); // run until the end of the match (driver presses STOP) while (opModeIsActive()) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 1cbabd505c3d..39976888d7a7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -1,7 +1,5 @@ //TODO, implement all our external libraries and functionality. -//TODO, add 2 generic autos for preloads and shooting and stuff - //DONE, Implement controls graph to TeleOp //DONE, Consolidate the generic actuator functionalities folder into one file @@ -20,4 +18,14 @@ //DONE, Finish translating Dylan's December 6th controls into the program. -//DONE, Figure out how to use NextFTC's Pedropathing extension for auto. \ No newline at end of file +//DONE, Figure out how to use NextFTC's Pedropathing extension for auto. + + + +//1. TODO, test the auto paths used in the generic autos +//2. TODO, create two generic autos for testing and competition +//3. TODO, test the turret rotation autoaim with shooting +//4. TODO, establish static (non-changing) flywheel speeds for near/far zones +//5. TODO, make hood autoaim using InterpLUT +//6. TODO, test turret hood and rotation autoaim together +//7. TODO, test turret autoaim with the generic autos \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 10b4639b554f..d4338b8b7e58 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -16,16 +16,17 @@ public class Constants { public static FollowerConstants followerConstants = new FollowerConstants() - .mass(5) // TODO: Change this to the actual weight of the robot - .forwardZeroPowerAcceleration(-45.7735) - .lateralZeroPowerAcceleration(-53.7000) + .mass(13.6) // TODO: Change this to the actual weight of the robot + .forwardZeroPowerAcceleration(-42.5878) + .lateralZeroPowerAcceleration(-68.2022) // Set following parameters to true to enable dual PID .useSecondaryTranslationalPIDF(false) .useSecondaryHeadingPIDF(false) .useSecondaryDrivePIDF(false) - .translationalPIDFCoefficients(new PIDFCoefficients(.1, 0, 0.01, 0.05)) - .headingPIDFCoefficients(new PIDFCoefficients(3, 0.3, 0.2, 0.05)) - .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.3, 0.1, 0.01, 0.6, 0.6)); + .centripetalScaling(0.0002) + .translationalPIDFCoefficients(new PIDFCoefficients(0.15, 0, 0.01, 0.05)) + .headingPIDFCoefficients(new PIDFCoefficients(2, 0, 0.1, 0.026)) + .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.02, 0, 0.001, 0.6, 0.02)); public static PathConstraints pathConstraints = new PathConstraints( 0.99, @@ -48,12 +49,12 @@ public class Constants { .leftRearMotorDirection(DcMotorSimple.Direction.REVERSE) .rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD) .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD) - .xVelocity(59.3402) - .yVelocity(46.4157); + .xVelocity(65.1356) + .yVelocity(39.2622); public static PinpointConstants localizerConstants = new PinpointConstants() - .forwardPodY((double) 3/8) - .strafePodX(6) + .forwardPodY(-3.25) + .strafePodX(-6.25) .distanceUnit(DistanceUnit.INCH) .hardwareMapName("pinpoint") .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java index b2688ac39e13..5e656da719d4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java @@ -1,8 +1,8 @@ package org.firstinspires.ftc.teamcode.pedroPathing; import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.changes; -import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.drawOnlyCurrent; import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.draw; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.drawOnlyCurrent; import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.follower; import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.stopRobot; import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.telemetryM; @@ -15,13 +15,16 @@ import com.bylazar.field.Style; import com.bylazar.telemetry.PanelsTelemetry; import com.bylazar.telemetry.TelemetryManager; -import com.pedropathing.ErrorCalculator; import com.pedropathing.follower.Follower; -import com.pedropathing.geometry.*; -import com.pedropathing.math.*; -import com.pedropathing.paths.*; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.math.Vector; +import com.pedropathing.paths.HeadingInterpolator; +import com.pedropathing.paths.Path; +import com.pedropathing.paths.PathChain; import com.pedropathing.telemetry.SelectableOpMode; -import com.pedropathing.util.*; +import com.pedropathing.util.PoseHistory; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; @@ -537,7 +540,7 @@ public void loop() { */ class ForwardZeroPowerAccelerationTuner extends OpMode { private final ArrayList accelerations = new ArrayList<>(); - public static double VELOCITY = 30; + public static double VELOCITY = 60; private double previousVelocity; private long previousTimeNano; @@ -643,7 +646,7 @@ public void loop() { */ class LateralZeroPowerAccelerationTuner extends OpMode { private final ArrayList accelerations = new ArrayList<>(); - public static double VELOCITY = 30; + public static double VELOCITY = 35; private double previousVelocity; private long previousTimeNano; private boolean stopping; From e1d80a28179889c3241e0fc4ec24a0295f23f653 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Fri, 19 Dec 2025 19:21:27 -0500 Subject: [PATCH 106/152] Fixed bug with accessing auto paths and tested pathing, intake, and transfer commands. --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 43 +++++++++++-------- .../Main_/Hardware_/Actuators_/Intake.java | 7 +++ .../LOADCode/Main_/Hardware_/Commands.java | 14 +++--- .../Drivetrain_/MecanumDrivetrainClass.java | 8 +--- .../Hardware_/Drivetrain_/Pedro_Paths.java | 27 ++++++------ .../Main_/Hardware_/LoadHardwareClass.java | 4 +- 6 files changed, 55 insertions(+), 48 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 4ae1a0e636f2..da840d0fb149 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -1,10 +1,9 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Auto_; import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; +import static dev.nextftc.extensions.pedro.PedroComponent.follower; -import com.pedropathing.geometry.BezierCurve; import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.Path; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -21,7 +20,6 @@ import dev.nextftc.core.commands.delays.WaitUntil; import dev.nextftc.core.commands.groups.ParallelGroup; import dev.nextftc.core.commands.groups.SequentialGroup; -import dev.nextftc.extensions.pedro.FollowPath; import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; @@ -40,13 +38,13 @@ private enum Auto { private Auto selectedAuto = null; private boolean turretOn = true; - Pedro_Paths paths = new Pedro_Paths(); - // Create the prompter object for selecting Alliance and Auto Prompter prompter = null; // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); + // Create a Paths object for accessing modular auto paths + Pedro_Paths paths = new Pedro_Paths(); public Auto_Main_() { addComponents( @@ -86,20 +84,24 @@ public void onWaitForStart() { @Override public void onStartButtonPressed() { + // Build paths + paths.buildPaths(selectedAlliance, follower()); // Schedule the proper auto switch (selectedAuto) { case LEAVE_NEAR_LAUNCH: Leave_Near_Launch().schedule(); - return; + break; case LEAVE_FAR_HP: Leave_Far_HP().schedule(); - return; + break; case TEST_AUTO: test_Auto().schedule(); + break; } // Initialize all hardware of the robot - Robot.init(startPose, PedroComponent.follower()); - paths.buildPaths(selectedAlliance, PedroComponent.follower()); + Robot.init(startPose, follower()); + telemetry.addData("Initialized", ""); + telemetry.update(); } @Override @@ -107,14 +109,20 @@ public void onUpdate() { if (turretOn){ switch (selectedAlliance) { case RED: + telemetry.addData("Aimbot Target", "RED"); Robot.turret.updateAimbot(Robot, true); - return; + break; case BLUE: + telemetry.addData("Aimbot Target", "BLUE"); Robot.turret.updateAimbot(Robot, false); - return; + break; } } + Robot.turret.updateFlywheel(); + + telemetry.addData("Path", paths.farStart_to_farLeave.endPose()); + telemetry.addLine(); telemetry.addData("selectedAuto", selectedAuto); telemetry.addData("currentPose", Robot.drivetrain.follower.getPose()); telemetry.update(); @@ -127,11 +135,10 @@ public void onUpdate() { */ private Command Leave_Far_HP() { turretOn = true; - startPose = Robot.drivetrain.paths.farStart; + startPose = paths.farStart; return new SequentialGroup( - Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new ParallelGroup( - new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.onSpeed), + // Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new Delay(5) ), Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), @@ -145,7 +152,7 @@ private Command Leave_Far_HP() { Commands.setTransferState(Robot, Intake.transferState.DOWN), Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), - Commands.runPath(Robot.drivetrain.paths.farStart_to_farLeave, true, 0.6) + Commands.runPath(paths.farStart_to_farLeave, true, 0.6) ); } @@ -156,7 +163,7 @@ private Command Leave_Far_HP() { */ private Command Leave_Near_Launch() { turretOn = true; - startPose = Robot.drivetrain.paths.nearStart; + startPose = paths.nearStart; return new SequentialGroup( Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new ParallelGroup( @@ -174,11 +181,11 @@ private Command Leave_Near_Launch() { Commands.setTransferState(Robot, Intake.transferState.DOWN), Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), - Commands.runPath(Robot.drivetrain.paths.nearShoot_to_nearLeave, true, 0.6) + Commands.runPath(paths.nearShoot_to_nearLeave, true, 0.6) ); } private Command test_Auto(){ - return new FollowPath(new Path(new BezierCurve(paths.farStart, paths.farLeave)), true, 0.6); + return Commands.runPath(paths.farStart_to_nearPreload, true); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index aa619ed9d38d..13d4379fd9ec 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -32,6 +32,10 @@ public void init(OpMode opmode){ belt.init(opmode, "belt"); transfer.init(opmode, "transfer"); color1.init(opmode, "color1"); + color2.init(opmode, "color2"); + color3.init(opmode, "color3"); + color4.init(opmode, "color4"); + intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); intake.setDirection(DcMotorSimple.Direction.REVERSE); @@ -39,6 +43,9 @@ public void init(OpMode opmode){ belt.setDirection(DcMotorSimple.Direction.REVERSE); color1.setGain(2); + color2.setGain(2); + color3.setGain(2); + color4.setGain(2); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index cfba3a807f2f..86a881bdbff7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -12,10 +12,6 @@ public class Commands { - public static Object driveSystem = null; - public static Object turretSystem = null; - public static Object intakeSystem = null; - public static Command runPath(PathChain path, boolean holdEnd) { return new FollowPath(path, holdEnd); } @@ -29,24 +25,26 @@ public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheels .setStart(() -> Robot.turret.setFlywheelState(state)) .setIsDone(() -> { if (state == Turret.flywheelstate.ON){ - return Robot.turret.getFlywheelRPM() > 5900; + return Robot.turret.getFlywheelRPM() > Turret.onSpeed; }else{ return Robot.turret.getFlywheelRPM() < 100; } }) - .requires(turretSystem); + ; } public static Command setIntakeMode(LoadHardwareClass Robot, Intake.intakeMode state) { return new InstantCommand(new LambdaCommand("setIntakeMode()") .setStart(() -> Robot.intake.setMode(state)) - .requires(intakeSystem)); + .setIsDone(() -> true) + ); } public static Command setTransferState(LoadHardwareClass Robot, Intake.transferState state) { return new InstantCommand(new LambdaCommand("setIntakeMode()") .setStart(() -> Robot.intake.setTransfer(state)) - .requires(intakeSystem)); + .setIsDone(() -> true) + ); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index 5eebc1484a7a..f933e60d4a40 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -7,7 +7,6 @@ import com.pedropathing.paths.PathChain; import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; public class MecanumDrivetrainClass { @@ -16,7 +15,6 @@ public class MecanumDrivetrainClass { // Misc Constants public Follower follower = null; - public Pedro_Paths paths = new Pedro_Paths(); /** * Initializes the PedroPathing follower. @@ -24,12 +22,11 @@ public class MecanumDrivetrainClass { * @param myOpMode Allows the follower access to the robot hardware. * @param initialPose The starting pose of the robot. */ - public void init (@NonNull OpMode myOpMode, Pose initialPose, LoadHardwareClass.Alliance alliance){ + public void init (@NonNull OpMode myOpMode, Pose initialPose){ // PedroPathing initialization follower = Constants.createFollower(myOpMode.hardwareMap); // Initializes the PedroPathing path follower follower.setStartingPose(initialPose); // Sets the initial position of the robot on the field follower.update(); // Applies the initialization - //TODO uncommment this: paths.buildPaths(alliance, follower); } /** @@ -39,12 +36,11 @@ public void init (@NonNull OpMode myOpMode, Pose initialPose, LoadHardwareClass. * @param initialPose The starting pose of the robot. * @param follow The PedroPathing follower object */ - public void init (@NonNull OpMode myOpMode, Pose initialPose, LoadHardwareClass.Alliance alliance, Follower follow){ + public void init (@NonNull OpMode myOpMode, Pose initialPose, Follower follow){ // PedroPathing initialization follower = follow; // Initializes the PedroPathing path follower follower.setPose(initialPose); // Sets the initial position of the robot on the field follower.update(); // Applies the initialization - //TODO uncommment this: paths.buildPaths(alliance, follower); } public void startTeleOpDrive(){ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index 6955f64d93ef..713559941a20 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -19,7 +19,7 @@ public class Pedro_Paths { public Pose nearStart = new Pose(112, 136.6, Math.toRadians(270)); public Pose farStart = new Pose(88, 7.4, Math.toRadians(90)); // Preload Poses - public Pose nearPreload = new Pose(130.000, 83.500, Math.toRadians(90)); + public Pose nearPreload = new Pose(128.000, 83.500, Math.toRadians(90)); public Pose midPreload = new Pose(132.000, 59.500, Math.toRadians(90)); public Pose farPreload = new Pose(132.000, 35.500, Math.toRadians(90)); // Shooting Poses @@ -27,13 +27,13 @@ public class Pedro_Paths { public Pose midShoot = new Pose(85, 85, Math.toRadians(-15)); public Pose farShoot = new Pose(85, 15, Math.toRadians(60)); // Leave Poses - public Pose nearLeave = new Pose(90,120); - public Pose midLeave = new Pose(95,55); - public Pose farLeave = new Pose(115,20); + public Pose nearLeave = new Pose(90,120, Math.toRadians(90)); + public Pose midLeave = new Pose(95,55, Math.toRadians(90)); + public Pose farLeave = new Pose(115,20, Math.toRadians(90)); - // Define all path variables - // Dummy Paths - public PathChain basicMoveRPPath; + /** + *

Define all path variables

+ */ // Start Poses to Preloads public PathChain nearStart_to_nearPreload, nearStart_to_midPreload, nearStart_to_farPreload; public PathChain farStart_to_nearPreload, farStart_to_midPreload, farStart_to_farPreload; @@ -54,15 +54,14 @@ public class Pedro_Paths { public PathChain farStart_to_midLeave, farStart_to_farLeave; public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ - int mult = 1; if (alliance == LoadHardwareClass.Alliance.BLUE){ - mult = -1; + return new Pose( + 144 - pose.getX(), + 144 - pose.getY(), + Math.atan2(Math.sin(pose.getHeading()), -Math.cos(pose.getHeading())) + ); } - return new Pose( - 144 - pose.getX(), - 144 - pose.getY(), - Math.atan2(Math.sin(pose.getHeading()), mult * Math.cos(pose.getHeading())) - ); + return pose; } public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index 91a7ee9afc51..b0943a033cc5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -89,7 +89,7 @@ public LoadHardwareClass(OpMode opmode) { */ public void init(Pose initialPose) { // Initialize all subclasses - drivetrain.init(myOpMode, initialPose, selectedAlliance); + drivetrain.init(myOpMode, initialPose); turret.init(myOpMode); intake.init(myOpMode); @@ -104,7 +104,7 @@ public void init(Pose initialPose) { */ public void init(Pose initialPose, Follower follower) { // Initialize all subclasses - drivetrain.init(myOpMode, initialPose, selectedAlliance, follower); + drivetrain.init(myOpMode, initialPose, follower); turret.init(myOpMode); intake.init(myOpMode); From 2488e368ffffd7d89910a4b064d61cff02b3baba Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+professor348@users.noreply.github.com> Date: Sat, 20 Dec 2025 12:04:20 -0500 Subject: [PATCH 107/152] Added DualProximitySensorClass to Devices.java and implemented sensor read functions in Intake.java --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 2 +- .../Main_/Hardware_/Actuators_/Devices.java | 26 +++++++++++++++ .../Main_/Hardware_/Actuators_/Intake.java | 33 ++++++++++++------- .../Main_/Hardware_/Actuators_/Turret.java | 4 +-- .../LOADCode/Main_/Hardware_/Commands.java | 2 +- 5 files changed, 51 insertions(+), 16 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index da840d0fb149..ca2d3709d055 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -167,7 +167,7 @@ private Command Leave_Near_Launch() { return new SequentialGroup( Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), new ParallelGroup( - new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.onSpeed), + new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.flywheelSpeed), new Delay(5) ), Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java index 6db114ed4315..0162b89399f8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -292,4 +292,30 @@ public double getDistance(DistanceUnit units){ return ((DistanceSensor) sensor).getDistance(units); } } + + public static class DualProximitySensorClass { + private final REVColorSensorV3Class sensor1 = new REVColorSensorV3Class(); + private final REVColorSensorV3Class sensor2 = new REVColorSensorV3Class(); + + public double threshold = 2; + public DistanceUnit units = DistanceUnit.CM; + + public void init(@NonNull OpMode opmode, String sensor1Name, String sensor2Name){ + sensor1.init(opmode, sensor1Name); + sensor2.init(opmode, sensor2Name); + } + + public void setGain(double gain){ + sensor1.setGain(gain); + sensor2.setGain(gain); + } + + public boolean objectDetected(){ + return (sensor1.getDistance(units) < threshold || sensor2.getDistance(units) < threshold); + } + + public double[] getDistances(){ + return new double[]{sensor1.getDistance(units), sensor2.getDistance(units)}; + } + } } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 13d4379fd9ec..3ed7dbf88de4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -4,16 +4,16 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; + public class Intake { // RESET THESE TO PRIVATE AFTER DECEMBER 6TH! private final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); private final Devices.CRServoClass belt = new Devices.CRServoClass(); private final Devices.ServoClass transfer = new Devices.ServoClass(); - public final Devices.REVColorSensorV3Class color1 = new Devices.REVColorSensorV3Class(); - public final Devices.REVColorSensorV3Class color2 = new Devices.REVColorSensorV3Class(); - public final Devices.REVColorSensorV3Class color3 = new Devices.REVColorSensorV3Class(); - public final Devices.REVColorSensorV3Class color4 = new Devices.REVColorSensorV3Class(); + public final Devices.DualProximitySensorClass topSensor = new Devices.DualProximitySensorClass(); + public final Devices.DualProximitySensorClass bottomSensor = new Devices.DualProximitySensorClass(); public enum intakeMode { INTAKING, @@ -27,14 +27,14 @@ public enum transferState { DOWN } + public static double proximitySensorThreshold = 20; + public void init(OpMode opmode){ intake.init(opmode, "intake"); belt.init(opmode, "belt"); transfer.init(opmode, "transfer"); - color1.init(opmode, "color1"); - color2.init(opmode, "color2"); - color3.init(opmode, "color3"); - color4.init(opmode, "color4"); + topSensor.init(opmode, "color1", "color2"); + bottomSensor.init(opmode, "color3", "color4"); intake.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); @@ -42,10 +42,12 @@ public void init(OpMode opmode){ belt.setDirection(DcMotorSimple.Direction.REVERSE); - color1.setGain(2); - color2.setGain(2); - color3.setGain(2); - color4.setGain(2); + topSensor.setGain(2); + topSensor.units = DistanceUnit.MM; + topSensor.threshold = proximitySensorThreshold; + bottomSensor.setGain(2); + bottomSensor.units = DistanceUnit.MM; + bottomSensor.threshold = proximitySensorThreshold; } /** @@ -106,4 +108,11 @@ public void setTransfer(transferState state) { transfer.setAngle(.05); } } + + public boolean getTopSensorState(){ + return topSensor.objectDetected(); + } + public boolean getBottomSensorState(){ + return bottomSensor.objectDetected(); + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index a748086bd5d0..4529d7032eda 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -44,7 +44,7 @@ public enum flywheelstate { } public flywheelstate flywheelState = flywheelstate.OFF; - public static double onSpeed = 4500; + public static double flywheelSpeed = 4500; public void init(OpMode opmode){ rotation.init(opmode, "turret", 145.1 * ((double) 131 /24)); //Previously 103.8 @@ -162,7 +162,7 @@ public void setFlywheelState(flywheelstate state){ */ public void updateFlywheel(){ if (flywheelState == flywheelstate.ON){ - setFlywheelRPM(onSpeed); + setFlywheelRPM(flywheelSpeed); } else if (flywheelState == flywheelstate.OFF){ setFlywheelRPM(0); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 86a881bdbff7..3b05f53fd8ae 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -25,7 +25,7 @@ public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheels .setStart(() -> Robot.turret.setFlywheelState(state)) .setIsDone(() -> { if (state == Turret.flywheelstate.ON){ - return Robot.turret.getFlywheelRPM() > Turret.onSpeed; + return Robot.turret.getFlywheelRPM() > Turret.flywheelSpeed; }else{ return Robot.turret.getFlywheelRPM() < 100; } From 33dc49887f2741068ea5a81a02e89a2f276f967f Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Sat, 20 Dec 2025 20:54:09 -0500 Subject: [PATCH 108/152] Installed Marrow's NextFTC Extension --- TeamCode/build.gradle | 1 + .../LOADCode/Main_/Auto_/Auto_Main_.java | 16 +++++++++++++++- .../ftc/teamcode/LOADCode/Main_/Utils_.java | 18 +++++++++--------- 3 files changed, 25 insertions(+), 10 deletions(-) diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index dd6160908114..651c811d8a36 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -26,6 +26,7 @@ android { dependencies { implementation project(':FtcRobotController') implementation 'io.github.skeleton-army.marrow:core:0.1.2' + implementation 'io.github.skeleton-army.marrow:nextftc:0.1.2' // For NextFTC implementation 'dev.nextftc:ftc:1.0.1' implementation 'dev.nextftc.extensions:pedro:1.0.0' implementation "com.bylazar:graph:1.0.4" diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index ca2d3709d055..03b75b9437e4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -5,6 +5,7 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.skeletonarmy.marrow.TimerEx; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -16,6 +17,7 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import dev.nextftc.core.commands.Command; +import dev.nextftc.core.commands.conditionals.IfElseCommand; import dev.nextftc.core.commands.delays.Delay; import dev.nextftc.core.commands.delays.WaitUntil; import dev.nextftc.core.commands.groups.ParallelGroup; @@ -41,6 +43,9 @@ private enum Auto { // Create the prompter object for selecting Alliance and Auto Prompter prompter = null; + // Create a TimerEx object for time tracking + TimerEx time = new TimerEx(30); + // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); // Create a Paths object for accessing modular auto paths @@ -100,6 +105,7 @@ public void onStartButtonPressed() { } // Initialize all hardware of the robot Robot.init(startPose, follower()); + telemetry.addData("Initialized", ""); telemetry.update(); } @@ -186,6 +192,14 @@ private Command Leave_Near_Launch() { } private Command test_Auto(){ - return Commands.runPath(paths.farStart_to_nearPreload, true); + return new IfElseCommand( + () -> time.isLessThan(5), + new SequentialGroup( + + ), + new SequentialGroup( + + ) + ); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java index a5de6ba89773..8131e9dfb13b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Utils_.java @@ -6,15 +6,6 @@ public class Utils_ { - public enum telemetrySortCategory { - DRIVETRAIN, - INTAKE, - TRANSFER, - TURRET, - TESTINGVALUES, - OTHER, - } - /** * Performs spline interpolation given a set of control points. */ @@ -158,6 +149,15 @@ public String toString() { } + public enum telemetrySortCategory { + DRIVETRAIN, + INTAKE, + TRANSFER, + TURRET, + TESTINGVALUES, + OTHER, + } + /** * This class is for the runtime per-loop sorting and displaying of every single TelemetryObject. * There should only be one of these per program. From 817e9558361761cb58f9fb3e4c847d157d74e7e5 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 22 Dec 2025 16:41:18 -0500 Subject: [PATCH 109/152] Add files via upload Updated flowcharts and diagrams for the README in Dev branch --- File_Structure.png | Bin 0 -> 233641 bytes Robot_Controls.png | Bin 0 -> 809370 bytes Robot_Wiring.png | Bin 0 -> 180567 bytes 3 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 File_Structure.png create mode 100644 Robot_Controls.png create mode 100644 Robot_Wiring.png diff --git a/File_Structure.png b/File_Structure.png new file mode 100644 index 0000000000000000000000000000000000000000..166df00c2742afbbab6b2376a0d48143e3fb438d GIT binary patch literal 233641 zcmeFZWn5KV+b@cpfFdFxAR7 znsDFG>vQ%w&wI}KboTz8^+83}nrqH6$GEP4jrs0{gb?Os!pj&K7?{t61*9=BE{s)1$j_OnNs-Pe?|s^HkgcfTRW2#Y>M>KuYRels~wj?x|g* zyy3(nC2(C3_donmMv!s^6VsOcwwjun=Qk$&tDLd#sS@Ab_4yBf4Eg6PXM2jBf~!7x zoqwEb`(Hodr~Q`w*H4d$Y%>3O8^%XWPPu>m&~ZMN=3hS;cuL&-*AInH(vUGec@2D& zIrq=MF-$u$kg+~~d9eO}_iJje5fB)b3|5qvpC`b@$2VY#`p+Z!_HJ`46}n@_#`7u; z&eQ*NzmU7RC^YkwpPv}3;b(>VdCw=`|J!2^Q=xh|8*%>`ISfsVb>&-;t_B4K*;SxXDC58YRZ(9NR?%IrQQ`zknm#UUFUjc2dmy`2X)!Xup#(qglDUv7z=!^K+qL7o}L_&*|yD z-d=erDa+mUnKKu#eweUkqlmIzzkaPB@5;)}y+0nncR0M{mS)SrKff~_-`?DunUmwT zGZ`T&B2q|y0nWJQ$4QT<5mqeFYgMx!o}8Pb?UIv|Gc`3OBO}Ym$PkU7KWMYBTI&=d zMei+Ekjp%mkZ3Eno%5@Y)8}W6&Q3{5`Si(RX$0-)=*ULIWjovb=@X;p=fJo)UV$*I z*G)R*OI3SQZLvfI1Q{fzo&EjP6~&HgQ>KH(hKfXR1{mwlj>n*8+2`Fm$JM6$A;H0y zuUxU8{}B`s(Kj@dMZdbW1!u0Dr&V_bo14+NH>*$GIXf#$48`esb8Wgkp3Pj{(Q!w` z9Bn(%czsKO&w5HsTwL72VY?~hzISfpp{|}D@8R}%LP7%1l(Vz*g>&cLym@0NecUJ4 zPl}w!OI%{&gI~T3UT@x*4ip;B^=9*gv$C-*$z>@Q%`P1sF6mBSyKmRFL@)$AerZ>6 zkXa;QIRc2F`_ zL|HYYibuD_^D*2Axi1;VW**l&iF~FevTpbY`Nvh?{sMjP*RNgHJB8SadKZT)`f@cG z=G-=V6l!H7xo%@MjMaMIxN+lPe}7`5=G7VX<}>l?4r6bYmzOImD`6B$r1kamQacU4 zwYIuWhAF6u>PEP4RgBW96wi|$j*(WP(Iv=?>`EosId$q31A6^?^7D|kSgtKk(*4J* zX>IY3^xI(eUAuMbJ}qZ#TWV^m=LPJljb0TP0=6ur^DV|YIun1LyRx}7I(qao{%}2Q zWo4zVuCASXO)Nk#U&DUbR>9bKPSR~PM7!brhPwT1cLvO4SWBBLD?xYX=H_&*-4EB| zopB8r@#S+=%UpJ>sGq0mChNrUy6$fDX|P4N^6igdCnYA*tCg?AOwA0lw_ieUHB)kO za_W3?TAqyLUhm-VN)->WwdGXP*Vi{SUD#WyuGVjli+ZHbyEk9Jq@kv;X}mVos_wo= z#nfY3GECWI#AEd>WfkVndM!4e4e=341%r7`CGn+8mzdP2Zu2;;_f;R-^7DJT>@3$} zk6N|R$)n_Q`&#aDyfCjm*bJjp*yWo?Zje*bF}l=LOioR0p6g5!GB=_lsCGMWQc@U{ z2xGTjR5dm>*3{G#6NBM6?>RP;7B3+oVdvWKyfHL16cZEkJcLqLN9XL>v+D-+-{SfB zn3%qsm5}nfD4K={Hzoz}mcxLsWET|3P-e-`5!(-u361wCXwcEp&Q)u^3l4H~a|__v zRDAK`#g>p9X2SgZe8p1LpbpdXe(CB?gR7XBVH_|tdn*C%LmeF-u|k@wj}DgZQ&7y< zaHe%pSB%4LTw00`47_&xwyLzW)&906$LX=Lv6-0}BZkb1tgHvm=@}UK99NTF%8Yt4 zS&VxdpP@q!Lv%!xWo2beOtPYNTgoMQHo9Xttk<1f6%-=6$#-79e2Ehs9=G`EJ6>pjyg!_wKJ-)!T1wk7dZDIZ+dfUkVkxg7+ZMb;b=@f*7Su zRMXh4t*ygHf0<}b?2EVI{To6}x5T-5?V2VdzOu4%&aIm_Z%*29ii(P=S<7cBj*X9Z zIVY>kxo(ka82ufflCNY+!C4F|3rY^BflO zuvx?@tH*eB$~t+9dfy^D(ZcpyXDu`UjZ7q6KwaiLz6gYtAfHuC>7s@}dF;(Cb+;Ye{v?7&dcv{#Z81SRt10&)A|hJo)5&%1dF9eIn&UEwKX!L_FZRVW zDMJ+v<$#7|bU~D9a;V3wWU0SE$W-PXbV{VD9~r4N7_I!OlaBt@UtzyAms_1fZ)#xh zqtr5Kz7v*Ketv$j`RK^Oi0iYYyyWBweZIY@fp?WIJFC$Bi(b}xrKhKFZ*S*T9}W}= zZ~oeXMPAU(OWUAYY*j1KLv=7M_9rE*y`>wv_Udy^Zav*bL>UA18deIB zAEUu~IXOK&Jqrs9DE%wr4LuyNx-VY79L#|;n6!Pcw*^&tZ*NaBp7-GEyBqnQ2i2Z% z)rYGs41L)uB|1$w9Kp~I-4@HHv4}YfEywFeuq%Se-DMg?Mw;7s_p%zgBJaHfTbcDW{S+x($dOG zZW@$Ns#|@8S-u)qWh}5PZaT(sOB%^-&=NfoRC@2LI z$-&hZ@u<+q$lv8ysc<8`@|Z@77A<5at7>WUb!oiA@pctLu*hyTfwSNFVWyE)P%k!}>n`0|S=wEl?d{YjWM zb82O`19e-%1qB6LKd`j)WPISX&79Ae&!4-bk0U1|^T_hoS14(0OiWhLQ_bACyXnrK zJ)6!J@_?Rx@gN8ARuf}LQ}?)6h_r{_(sem?^|+|0{(*r3uC%JE5z(1~O*cxVrOXLt z7h&EMlD*hhe-4uwO=du~KGFp|J_Du>t%N1t*OOu8?Ps5j%8rc0cXxM>`fYhBNI?UQ znrmuruO5HT)h#5K5u54f=T}E^@HrSY%_gCQ( zq58$StUiA(AtK_mJ?5>pRYinPU6GWO6o2Z;lP9xZNsqRLq7a00Um|8Z;AlGls(6Wx z`w@KB#+<3?720C#DfB)qEiE0LWT%*df&yJh2DS3gh=^&zO_)QwD-EO(4{=JNqyz^C zLqpi=KbWOsXaAwY)ZSDNA9l{zOu;ZNZQbT`bE);hL|_Ch zEv>H5ukrDChhLZab0Z@oUk(!^=T7cne9ZE$MgYv@Ui_VR+f$0&?CkR*d(Fpfq{W=7kQjFzr}FKV zd6sG!6Fd9%V#QMULumWb7jARf81!Vy$)t)smy{eWHXQ`?`sK?PsAB^a{(U1ORZ3)@ zq%O-(I3ia`TmdS(uGHPytImgGi=$^;&CC{Qb1RvW_b}l?H7{C-BW%iJY;`h1V-cYG z%=Z-Iz8v(JCILCQZe7tEVqaxnTAKCz_h>3~0>=$oOv<^X+Qj(LK93Kw}3VLWh zQVHd|x3_n^A;6v#C_<*0eQB_}ZZWxAmlhg*fpWH+E}ocByP`i$JQXC!}0#=~G6=^UanS8>ngDqS@L_SR=y2NjPoN_afn< zN{WlUyu3ynr(@3yikO(pueI~>LCYNR#lgX0Vq&Tcy{`}!5rKNtGolD&Vt;3?0=uoP zO+rkpazuWAe?Oc~r8jAmeCNt7`tG?6sE!Ei8Yu^oA?+cyuE@j2wl&*>g1%ESWaVp8 zo|H7+7(~uCGztWs<2F{T#Qj0I9~_l-6>3*iL zqsj$ZFwBu=s46xy($E~MtB;`6K6>;Bpo1O3CV+PY1AdS-C{j)d{`&Rn&f4_-d-w3K zp7*W|ijLkZh(E|W;%X_ILAqK1oKaVrWXa%yH#X_wb?4t52^6B?I=Z?|pWeQG%XhTX zK3kiY91QdQCarv7QPIKvG~bdtE%Y=Xz^bsWZ;vGj1>oV~)i*S>M?M@U8r^nfOKD%74Q+oy=0>JED;5Gg_&z~i& zNC_?p0*oYe-(Nu*jqD&Nw466rZt1nf%q%RZ$;tKXk%?h>k3%)r1&|>v{r$lken9?7 zSfyhH`SW%aer)(xSA2R<3R{gw^9AjP+YNl>Q^J@qgJM850i+LY4rS+|vr%5oS!CKf zEw5v!q}1<6@aXVh^hm8Zy=$iXO0teq#TOQ)yLX>{nIyL7jD=S|Ig?`Qr1mmMLK|=8 zNGE}MP@Dnu;5=m3+1}2;!=v{8otS8-daeT7Ku5=N8s9<2o+gI~(|4^r?u~94N$!=` z$p9XnGD527E*UhLTp7jAqXX)>e;yoEDzt_3AQc_ZehK8M;oj~z+S*#o%h9d!8XE4~%VXGl`=5^XL9CdLcXyj?4g(nH|Mo2?Z9OwK`7$6S z0fipU*Y$O}Bx?`COQwn0&g$gn&!6+N-@nIlWN_OX9363*%RVsqy-+e5{*qQcE3jzY z3B7BQi4D`>N1pbuH?-asmD_}bvkMD!b&c;E)!jkpf+aTV8uek9Di?&RmM6b0pM(XH z+kuq#^{YTZ{{zGP@~a`^J1~0B(ag<)UtC>WbkdSpqXJ#c&CKKxzQ+S%QvmmBBb174 zdDMKaa;1s=XqD@*vk9`IpG8Wz3H6nqNB*4@0Mv*p;36R}KqIs>$p?iurvkgayYH2_ zM{_%_0$+DuPa-u`Yx^{}_P5R%^97MYF$!(=7D^;z*z*7xY@L%s{;Qt*Z}+KHF}qjL z7mvWd9(1v;V@Ii;Ebhc+>UahjNkteL%nMg7H%ZO zNa!y`eNZ^Z#&fj421?p&VWlyQ%|MlFMKOhcBrjh%e5j^W@I)qj{A0n++}s?qWCRe_ zvD?akF?}Yv3)JbfN%1c8{;@0sPm$(KLdN^)+eImj>odR>qJt6_rR;3 z`v20ztA)ZE9UTqM)E&>$XU^Di68{@rWHCzu!3uQJ#H1wMpwF5Xd?Lj2Hk=oZ6sZ&6 z5^77q@_^BZpjXSx%9_tJD0I=k^M?(YewgIvgjWA`p5WfS*MDNpw}kOh=RL`|xSV^l zl%TClPENuxX6NT^_?orygk^!m{FJnMd)MfJU{f^%A73>n34`X)IE$YCV~WXM+O-~KNTnoTOcAp2?lJGYfD#yKMgY+U>rzv0H6$x z#YaY+tCS(n=LnBKA_A2a6wRjA))et`ei&(8j?g~<8E)_HZn~KuIEGPVridPSZ;e4% zY^<8Px&Vhzr zcr2vi6aHQ81pq2TS2H$7A#alabqJcpPf~RRK{=d0nG5Ida&neeR;td?c&wxs7x(t{ z^^J~d%sqv-c#u8*djXt1e;!!Ak=i*%2^MB%kjxC!5QBs9>_5xO^K(ake}?VN8g@{G zHk{gi!|Y?kTXv>{cb&Zc7jcF&)z07eCkyZqlOKr2u-Ve=ETPT|P0f!@I)AWDm|6AD zWu2UyTwPsdWV(JPfg0_ViOi+@Qa}q}IoQ1sa{c#p5bghe?mTvHzr!I>y!mfS4&34- zT9I2&!7bR&k8XgX68!AXi7wzDk`8@#dU{$xUfxMoPT)F=M52|I6%couomJg{%zvBu z=dbA&4la0#Nj-nUAI$&n$MK=!AR`Fw!eNjcev+ zvq)!Kmsy&*-!-dtSQ$zZOxSY}?lDVz8gsbR?EY_8|9~%Bgi&3RvB7#$>*^qmb^rK5 zm5Ygq=?^3D>w*O{@`ZjzCxt`v_s;hA*$WpgP-n@bb~F3thL!sC3Ru|KPzvNl>f_}o zb!X>_X>Q_XO~!P4@^zVX`va_xFnv&cjqAb-i06mVdQ!PO z$UgSX@jrbE6`CIx@QkavXt$cEsIL=U(A?=Hxc(@7!3aFy4jW!>2Yx~0AJreH1{-b+ zFhPBBjodZJ`Tg5qLo}^R3C2Aw9i*VX!xCg>YKAg3&%BDc($rsf$8$o5KdtNksI9@N zDn7t-BzBQ~{MbXb=lgf2*+jUHKtG@6Uc$nv8WFyf0oqdaGqhf#HN8Kfyb|2$L*eSPPSXJzPKz>R-P^o-wc7M-DRP?jUVrpru7jtfk6b#`fKbb1zU3`<`+ zPv++c=KA!2G#YAZ%hr{R4ft=lX!lhbZ-w{8#+_&1M63p8XJ%&3&d$=*ZJ6P(m-8z8 znP`BnZDV!%Bd@A`pwj=8HUTZa$Z2C12BEoGBp}mhI}ynI-CSscGdxvgWjoC*z*hjj zcs{^*+NMZ;_pYi?)mGG}R=tp<1ADV$Xy{Z@PS{Qxu7F?Vi@8-Na{Tf70foe5xCrz&HS=7KsPp=4uF+{X*vGu7mSvU)LSh8&wvUk zC@6Gwb(y5+oRE64?tgL|2SFhr6lNy4(|uyzwU*HI?+R{Rxbr!QJ+@7&4zNE7$N;3I z@gS~|kkI>nxk*4k02(kHY_(a}0y(3!1etSw)K2J;bo{7Rj#!C`FG-n%+C$upFz0K2 z!E1bcvZtY;fo1K>n=2Z$6Z&~}DPyT})X)ULHVFrpD>xVj7Z-47?8iVsKv>|SR61>B z_J$$LW}9!n;US|PzJL8lKp2UQMe$ol&FR5)F*-@aWG6cO=p!VJIKQ7#4t#<0os$a@NTh@NXqg#IAD zf&hcQWvJML-_`yE=)oC~n*u{aaY;#+KFBC4I=~>pd19izSWrp19PUg5dyi)|RR(YE z)7^&;SAcD3xE~;1&CQ5^}KuZIZ5 zN5@lG-bq_x;ywhZU1XGNU{!O7zsytY=4g0N+|u3-OsKb*(J%QlT(Jm9?E(S`7hIsVC9)UY!?l{w4QdeB#vqs#W?xpOmQ7AeYX{LrEAMMv z-5YQ3ctn4Tdc>W06%K^|@^2<;NpN{XIurCmP)qVlOBLr5KcYdT2U-0AsM1s4qE=TL zzkR!kg~bb89sJQkdIaC$3;m7F3LfD34x~y~bAuTLQ!dB!`7#wKGQ2o|w96;MRbU>2 z8Z`098XQQcDEMT}TbOk4x26fiAP^Tilv+k-V9a8EplEKszd-rcIY}FkYgSiRL8_*> ze_!a?Gd*w>wzp%r>?P(9=Hy}dO5!G?+s^JTz2YZL2seN?zr3~v!X_#`o!xbJ9Tu?( zYjkgq|1G|Q8OibSaR>p#J5CW~8=u0^6q^}IH8L?l%Gkd-&+iE zJkEBHA3uh1S5Q!R`7)vRIJ~G$3iBaG`Tt>@MCTVoDh7bSHJU)a&d-!H)~w!-z$iL1 zA>n09I30LK%D3J~X&xOOfB*q{`<06qBUy~Y_k&eID72MAMhagj?J~YSplr~!o05~0 zp`CyzH!(Sh^h)3TgM)(ne6U7WYR+IcM(r5qqUGh~Q%#HDqh}b^$Zo)@00NmLer{`W zYHD|Pw=IU_5fv2`4-YyoFE1hC$y_2bn0aDIMDv-fjm`Rr{0C8-RQH2E_hE2aQQ{Oj z%2SOlN;KL!$$ovGl;H!XE@ESY9+An3cHUb2@PW{D?sNJYgmF;rpI8jPCwF(tX15?^ zs-B%wu4a1`z2wU9;K4j-K*Qy>#(cFp8Gb=QOm1I|&cH0fX=-W$ah^%)#futiFGfbV z4KnvZUEdx@puMJIC(QOB=f$%7EG!$b_9HtG6EI^}tZx)1U@-Q7Yzpt;|6)`Gl4yDt zP_6+y&rVc%`7XGC>dgmv_r*UX+j78rY7`-ngD(W=6)HC$2w7|mEyxitjS*JMZvg8H z&sUHV^jJsko9B~0etaAoh#jWhUiJun&8UiGl{8;}i{s(CcW(l5?lX$)z@$R509z1T zAx!;Z=F_C3TwJSPbL1z@{?C);O>8eTomQ6`cHu>?1jEPA)l^Dx= z*lcTa6Wk@Y&3=78aJP{Z$M6NPzm33E0#=#|)yc0!@d3!RvCM|SpEZ9I)04+L&1P^| zPeJd^$;kl?IH?mK508=z1h8E6rt;EJ^xJ@d>ghOVU^&S+O%Xo;eVV)P4eAw?HE7o$ zilaBFo8p30nU7Mb#Y-rP@pZ^dlwnB6QOH&AfvY;TN)3Y7sx+^{ab5Fxsa2?)jYJI? zZsA9Q2Nx?L1hmBP<{tqAis>H`X$6Ia-7NZG#sKL>3(aoq!mQ4eVp8vwZg2NaqS=D} z!wV80bW*@?DkWyFM+aLJ)?h;;=?sv}0mXqQ9}yp)iv_OEAqdvulrpZa2k}Sy(`prV zO+Udtv7PIMp%Hyw<|n10hOA|XU-b8r3%%b*ENZJs9~Wm;h?XP@`U1%YL!(MOn$?z+ z!Fv(JJyRniClIVAEgY%Q5Bt;mO{yS^1qQ2{tn38MRDw52@DAEHio-f}PJ+oQD><2r zLq2ZjI>j+NGnyA{l63T~OH_Z$-Iz|c&+&T~U1wH;&2-tq_0FU<#gUQM1UcvHc)J}; znM1*~EBF3jh)F!n>3ws~`}PYp$KL*AlT=kz70jC)20FYJ(827`pJBNQCci)apM?#W0Dj%AHLE z$ux;l`kd3}zqPkZ#s+F^axZsD{K;Ci$(w(4cQbE?M;Mryg|h?R7D1&$BH{2TQR#eS zt6oxP`k`x{%MNJ2O%Z4z2vB8a(y)k}Z&YS-fLMwQm?2PvCKY3OoO^pxrD4V0#KnE> z?G2_vqp_{+2J}2Ix_*Gs^0VfYf_|ee#M?j~f`B4Z4U2VWq9AC(wzjsgfHf+x!<#9{ zczAf&*&U$Q4Rgs^g;wpawm|2!alZhu3N!SEyl>sFrKQ}qnd(SM-W?r~{iTZ|tg^V5 zt^YyH2Z8ZkaIg3`qQAY6n=B8dVPaYZKg|>SYbixFX)}ZWY+(#Lc2m5s6Xr}B8jW^M z&s_ax&h!W5_79;Ne=&SRTlg}fQk=ihgWmYAqNEg636@m(VM~2%gI|k7UwN%mSTuAj zKm{(p-IVK{-bF1Tsu&Yzcv<=gsZM)NiVd0HN|a~HTB?D`Y2l|NE{27|0*TzaK~Y=ZzFU@_Q4vnx~?Bi%uGz7+TF zC2tX9ojHBli95E%mLUT25MT`J8qnI`yg@>;DDe=Ed$B2CAVoA{@kbv2+*8J8u^4ts zn2YMowLjLK4y!=9!oXMGZ^QH>*MQ6|fTeK2c%W+&VTC_D_OZ!ds2l-qg`kiBv!uBl z$%FKqoZ`U+$`C_<;OL0dw6v}5wI4=r#Gr!XU-e4JRDuw}NM|QmU2;lFnG9SuJ`Dh) z)ej#&lxu!Ioo)Qt0KlVF1F?O2mnt6Oqx)eXpduflBfu;{pE8HO#LZpV{*Xx{ycwTh zW(x9?3oyVyM7n2eAWSPMEd1Mj8MIh{hrq9Z$2ebQ#lH#&>``xD=h zCy+9#t)tJEaKqNUxoC@)WY9$;JwU9f(ADf+)ec&qn-sH643xszA9*9;1wC&69vi@ zK;!fc{7-ZAMlS$dD{E`;pZce*G;93 zms0tcqP8JR!3nAA?QMtX)+xeKFw~}^&6^v6L95_0eV?%@kNfO)xW991Ntv$>d}wky zI^atd>=+oog&^Ou|DzR_!j&tcl9Je$E`c>K31y?#_VbOVX#rQ(Fm}sd0&Z@+C5LeF z7|&oQk!H-U$n~2y!@|Syh=~`D1Lk&McL6T}BA<<#8|=+ik&NRmGaD|Sn1J-fJn#hz z_7Bm~zCJ!k${NzGWzU-TkpwI)^c~RlLACv?8OQ-Ooz!i645GWbL4JltMzbXJWC&gZ zyOhcO&;`{)g95k%>=5vo>)xg*NcuIp6~~jD5)8O74J)Qcj{u`G1FtGF?pqwKKH6Rx zSMEE94V1bN!crRn-t%_ORf&)hJ>fkoPfyIBnrlFJ=G>$@8;wDgaJ9#6Ma|N&vTj0l z4Y2uWiTP-|+vcO}mNE`k5*={7tN^o2Pfmj1VyM9I)oOt*88qGh7;b0=mGt=UzAy0^-ci znpZwPm$R=Rfd9NN#6$cTAb^ploDDn|676$97-}wp^mPDk?F0*SF>Y>ddCS#_CP*=p zL?~(R3yX`#KGK&kFi78>1ealge9SOb0S>0g4cogkZ@=^N`_|M1C>gXcqOl8>@I9@u zVDN$857-eTGRhEYHOu)Q4|lRX+I?$-4rKNS+#OfgM z-oqQ-drr$CgY6Z}Kbh(*6bi{-KxhSKOA*~Mt8NEcto^!ntYh=t3jmi}V%eFio15k~VDF@W+yWdAtkS4Q;!+UV1?mm>$x!W% zm!g4zfwJ-dG%FByyOFpd=oK4~QRt~QLIjJCWKb0GUzQ9)<7OFhif0q;%*+Jv8Pz(q zzP=6_;35p~+D<@PAb0@6lG+`W?BhZ-9*hZlPrymd=I4Ni8C4_lV|%VLq*8(VJ^-(+ zyIkz5Pp3glVk7{0V?9&T?17}f)l14Wid>uPAwzh_>mUoyzW$+=tBD-@DhA4!DFa7N)< zH(`dxa64M5s>V27l8DqAsdNO@8~iq=kBNy-=R_>k;A>6Uno*tGN0PQse(BX~(V@u9 zz!rcDk%3JHDk{+u4^Ky1ugSWr#9mgOJ^f43z~x2v!f%MH6gq@;K@toRfzg zMCe`6_eUWnUibBDqp`5?+X$;3i4RXxL9uLZZl=Mt$$q9NE8G40(v6AiD9|bch{Wyf z?84P#K<1Qt0|&tvg2sdVy{lQ!--h@Gi8tXq-un1RFBxWy5Fz3XlNu-)j^ehqMZIqV zo~+_E1_k)}$&OxxxWI*`mtTAAgc#*Eb87r}|q5!yQRXMjK%Slp~De7sCRQzSV zJjLDHGe&3S6%wFwvB5gblRk#8BsY6tPmzj>^UQaO4fm)DBD&GRcXykU5+_DK)@cRxeHJ=*_N=fR zL~T3+f@7XgmOigaQI&2i3`o|Pm8YF*V$H%=kdgl+iDB$l;6&rJhg%WNtM{cED8MGMjiRI^eo7q=vGm;4D`SC6e^owtmee^oIG9GH@n(jw+RSX$ zMb1tfT`Z>FQ$gPR)ndL5W61sJ05&=?aPeVtimiePVKfoKg&?I^h31P2^ z!mq~ZD8kJ2gzt$|w6xZ(QVfi+PkL7O8T~WuQEVK52=Yr|(^Gg0mpL+LQ3XV~#@>y# zAG>pcB@z@G-zDy5vZj9(-{{#TYj}b-$jZx;qExl#UElYupXhL$Dl5>J|A*xr&v&+) zJzMXtd33^VKd?Pq0!?W!@b5#S1lfQV67mSzBgD^))UZ5=psIfd4gvVBJ%%I6mX7~1 zx>^HD=2jGCNRvjw2(2XAHclyl7yH|ROA(s6TdqPBy@{GMXVFNqYk}p6Q3EA|(N0HS z9|H1Ssi!fv768P+KBxy^!9cXB91r7QWo-?16{=S{Sc-@=BYVU)X63SJ37uw54~#(C zUS-X1;>WsIykcU?% z76tO_AZT1XdG+ud1y8#zWz4Wh}t1^sHv z{Nfpm-#G~hWZ=@y(O_H^fboQ_4L5LbPGT7tjE|3pMw8LT&JMB^7=9uWX)@?|d=Dw1 z!xbPk^eV*>ILXQ12btQ%d{%&V6AK|wBqE`UgvREt@HnzRm6Du&2K-#r+ zg5b=oX$StdpVx_ELPKG`+_PPVPS70%g%Ml=`7|(m6jfAE68bti4$jWldKP@Z?%`7* z(b3MeLCE)D1OQTiOR*M@<}#zOhD;hyMFy4pk&+fyu8kyM@VFNw}$TgBZsf& zVbctxR5Kn`u*JhYPLg0_VX-ym&4}Q^bg;Nc7qZW+F!E3B7l8{}O*oo=_ zzoZou`kck!56m=zZ$BS$l)3{9h0>sIZig^63=c0G*zN_fnX9j0CmA0DLvCiK2!v5I z*8%@_@be$*mbbQGGaZv9I4l*zIkp@%R4>%j&_FRDKYW7BF|OV|PE`bS3=Qq0 zG!B|aN2_620G$U+*>D2zy`|wIrKp&0i>U4p&`(4hnx9V)SWACu`31D-*iwtJFW{>T z3=S4$A1@Kcdw)AX=U{&rB&h&9gEd;11D}MZuXFrMhqJzQIJa*#+`QgcS2&~ zub-bi!G5!2zpdPdU{?%$5hn;wcpNp1#MZD_rn+OaPu#n7_9^=$V>8)Zn!A@1rERkZ zoQitmHa`^&7+08<6cyQpI8j*IZi< z*W6>33LemqToSujz2q(F@+fM5^&UY;O^73$zJ#y8Kl**j3##p$b2W1yMSz4@h(z7s z<%0c3j17LS!9D>n$G?O>JV<}RdIX$t$V^BR=95SzKz3QmMev=#-4yBP62k!?Zr+h2 z@P9_{^Ai7^Vh*O{l`B5jFJAkki?Ub6D!Mr72J=51%DOD&dQ(sePenmR!8H5ug^cq# z$Jq*vAKKa$4IXcUrDO{Q2+4w8`%pa5$_vJ6e*LtwPB6$jRsg~a0oKil>Z#&|c2(~x7dil*?m6Xo+X7e=$H=JCbJUK<6m@Uti#I1NU@mh~> z)!z2ldy*wx3=*=CChiT^F>Q18w@+~sue~|Gj<-)k_oTEEUi=OkofN)^{4Yt;+p2UC z;dk``iZPrn^yJrmEZ|+x_WgeE%GtCdiQyr~?~R zXtiy=!3o4LfkN+%)w%|AzSmG2`nj`9X(I!!MQ&TTd~Zo=6y4bI8p2s>k-` z940o-bLPw+J5lWmJcsQ(LPu@rRtqA}3njEm@3ips5}!tmrNyMLr{O>G?)rQYpG(}A zx>=0t!@?%3_wa8UWrBLLI}xQ7{NH~*i6hMLkbWyb6QoFoCnTJlHmLHHMq(=BuEG#? zaHxuypk5b=Z$_;#>-qO}S}ToP9%n~(Szl2JYzT%n@VPnMyZn&>kdGu<{AcSGsXy=F z>~#uQUANR%?m8@&h#-?Q;?+z1wEL9rZ^UHK2(Y-k>@C>ra!I`014i_qc|)KVNrmJ2KZM*R|ieqPru+yE(6M6@8!P zF;&djqvR8X`veWmI);a* zW)5jWx(LX^d2v`LB6})RlF&c2epQI&e(W*o>gsB`0}a%GdG(}$LM?dgjzqWG$mqt( ze|jh~ZL=;>6lRUuzbp(cJXdwLLR%VJ-IGz_*!vQ@oV5|{=U@ry#r5?>C`I*Axz8&VV%33FGE%`K4j9F(qR?ySMrzD?c2F7cLG@N>w20XOo~GLJEK^k0l5r)ox+2c;SzNsnd4P@K zbXnnkheT@e!KdMu;}v*68!}RZS1$Ekrg}zpg=vs;n||8r;kW$2Pf9dJZDvK^*9SM! zn!mB*2eZ*I*#yPcedu7!U=~bpd7k4?qNKn~6`#d~H!6qmm=6MQkaYKM)w`mPNx*au zLd39xo`}uN1#C}e4#i=33<0+sKgfPp7%K0CH06}f(%4&Z|8r_jq5nOWJY2o@>~RSJ z;WqtQhc2`9G=d8Yg|r9EX9{If@ZK$6x+ED!%XNFR_Sv|8E9bo6r{9zE#Vz?9-vNx> zOGvM@F!R%VylH>;>#wjeDQOWZoQsD8FG{kL{Fi)w;uH=n7|$BL{~(TuHCXiIv+rMj z?c}6uP=_@ege&@?M^2s3fE~&Tva%2b($R_GRi1!M6tLgw-B}cJK({Sa#+1?A@f{xb}bXJq6m2n$ZrnWC@3d)^Esuy zhVuf;DotM>_MMXnCxDJ>mHGKh z3=ER=5!SFq%CvwS0jL6Px~U(WQ)5u9CDPWo!e3C`(+BfK*QyhoQIT*P8yjX;R<~A~ z2M;Em3f%3aD;WxgoPA^@yXgRP{zP5_iAte?l(qF5?0OZ>7r2XT{2_5&?_3+cZp9CK zM;IKHTAG@6U}s}fFl=vvsq*!+|Id(@iCs6g{9x*=+UJDF-m9H2UF%6?bHZSxlfu; zKrVx8vb21t!~~=XHZ38VIOJ2Bf+-+b17f2p%xBmz)Rgi_?;G;$7BJ9|NdWX*JdWED zf>$5{R__fjl{f6}>_7_nchmiN8#=N%h$bLUUzlpEf;`1Z=-~U#;u}?Z2v#GHYAGFb zh0NDd`CQKYyh+Y;aCYF;LA;6VchIO|L~4Uhnd-Akhp8x`=;jM9Ls_VTL8wZ5{Ny)u z-CQEhK%JGPkqe-H3?o}coZPkvMhz*K-2-rgfOHN8fBPn81yEU3B26qR@dXuZ=x!_W zeGAtnCog~g!Uf3BZAp8!>T$VjTWnFl?mN4pjJJR{Q9Xn>INwE2XY|`v0O@{~Bt;*g zeflwSb{OnL$h!J@MGy6tThe7_jv0mx@yPY19OtEB75PnDiT8Hf7H03BX6$#Vm@mL{ z04&5?_kde(ULKk8tly;{=$9B=`u+QEAa|dV zqzxJ&xt&>{9PpuakaGYEG#{mgWgQxum;Ek>Qi7~>_YA$Lkn!DNseD(3^AhJuEBX<;F%U~T?pWk^^mpXqlV0v_21I1euMx^#d4#uHqX8C7S0 z6Qd>#Hh4o0FsV~fS$S4jxXXq?p&tw@c=|{@kXg6=ZRjf*J+qMOC@&WPkCctA1nA

uLR8_o65m9toKLQ5`Y(ipT{XE{JCxoV z^XWq!?uJsq`z5Qx@p=_=SDhZ3H_}QP3MILpUQmX-@$$ZqE_>I~y>hK;t)6HiZ7=u| z0Rdit<1mrA$?hy|ALqe~cYB%H;c&MVGCT`HGx_zp)W6ML#Nb_kq{nxoB4jr`m}T^< zGqvPD4Fz+RK?fvsU>=nAv)8A>bbMV({5 zg;9$1Zj3X7SspdQ@0f)jxS`$xVEkq!oI`u123u8KA=sR^7EO=$QDdZ&sEs1sI?f1q)0yqT2_0b za+qT7_Ruc!m0g>{IoH1aHhT_NK~xVo&mm7Bv&7Jld^h{swKQF<{~EMeY61uM^J(Y`{Ggg$H3Y1z!z$;oTkYh$qen2xq$rB|iT^vC1# z-o{2g%`MeG3Jss?>23AM^R9h+f3Sxg%l+J~(IaNT&Co$-B7Vf>QFURcstAs7TZ?gT z;N;pZy1Uv|H-<1>*SD&@g#-dgnW%Eo9bmU(Mefi1`Kmp)p(0darjI~S7en;{tM0s_ zBrm<0LE)gAfq5S1%v?8N*o&{oIMPQ5s|)PRW{vh&J%9(z=;C{+!v16Rdh|)*W+y@lx5q1levsm3l?=L> znX@=`jkaW>GKM9kiWYq6o zPZwM$AtfOtO_tv(eOF1$HK3wW@S~b9xaXVR+L-5su){+h`Ej!rqr5<^fx!V`2?3pC z>5TPlPwRdwWtD<6fB6+^7t<`GHsz}zAh{$cg*!^2`dD3E9lX7|tQ{6q!xteX9=sf_ z*jRWz#PUy1>`kj1?)tVGR<)RHG3bG{tVPk@95v^v;5LcU?Fz(igsOTC=@g7F#J3cR z`WLK3whOj4=tlO};t9Nz@@;0m)cK}qI8HL~9d2)aVBy)7yPP6T6EjUtm zA|tkbu1=<|wc~DeRxIi1==w)9zVbWT*_nQ`vvb-m4YfEo1Ub2askR5b*Vdjn6l1f6Ia8^HBqkIm_;3J&lim5Dzj+!W*M88k{Qo-S68k!S6A=U z7yZ>W_M=GqLf@OaV$a4mF0g^`=gT%>IA+^G#KZ( zmqyc!7?BO9fEgRC7Yp{_aRE-&X+D+IYih^U)}#Gc{5+rh?sAIk<8z`Z#>n~KFep!;wiGio3$)FUvB&Mg9s>bPyl(WO&i2)kbWf||XK3=*+rd{-m9LG0; zUPHpIJXiaFu=SQvBt|o@f8u!WkOre<>t}+Q>8A{53JzL9pr4CGnfco*c>&-@i4iX@OV1^C~6R8_8OX& zjgDijS;WrIrj7yMKL^OUUHtlymL4DyTvuzu@b}*jPc=`LJ8tv~49eyHi)L zF8Nk%rS)JUJ`ry*svkA(GD~*ei1qfAvuL^V*88VTe8QdM0vCc&}?NN9F;AeJFpLe>P$pN0P}670Uk#e5?i?ztNA`Ywk2+Zk4gM)KH8 zy7$n+x4-2lzkYUA$-j4U$#G+K#a`%(&l&@5yxn~4mbC-=b81{`1Z~_$`3yrgVi#_P zl6Go>z#Q2m*WFKXT{4LRHYrGIXP68z-=5s_z{E23`~j3$^SRIRH4YBrAuARS7~i2K za>!AWXUVC!4ApL5JuJ?Mk@%#MPlK8)12CT2kMtsxIW9VCvCpVM4Dj}se6RgJy@)F>!?0HJ8n2!6skc8#-=3D0Z6`Q zRa=r;!E7Oh?)+p1vw#CXE`r5tL8_)nzSc*GM^iy5CN^1MK8S(y>=aS(RJm%-dQyfU zOj=SCHj`)&n==0Dv9*0$JS5&{y^IeaPiv!FoaoXmQa=4eRr&@VxljnRwpiRR6X4`@ zhBkoV7eJ@UIP3BvJX@dOrEBpYY&Q9wCj)S^RO2BrAR;NYkKClcCbrMp7f6dvP&x7@ zcN%Y(=Z}+4)c#LN@}dB=pYc8AC^HTHyfhR_c`IxzSWkP~vc=QKa4t@o|RRacYGfZa|1=AmWGF| zx?aleQ@#=DY&5be=;(wC^In^qt#iHIT$XJ~{0WRFbGe0k>%#_|33C{t`U(otPP+mX zlh$k`lW^kgG8F#QEu}SD8!B!JXjh)OeVcS;g}idLKr(-?u&^N|CTZ-n{2LWjzxghO zu4@{L(4-$uu=pJ|6634ce)n<9o{eqv5E^>YLLHMS79Hw(U+Aq1IPWnrSpy<8CFso) zT0y}S(%%CE@1@44wx*X`f2S+^4owp%D?`v!+uU{W9?O?V* zTpF~J7pAPrcN^5{b|z^SYG9M{m7INmhaG)5Y_@nkI02#2Wzlquh)%^U82H?$ z&F8V_#%yKkI+GUQUgbU!MmD#&Ha}@IHsrOK|Lx?2`1XUn;&07k?^LskHI(!>Z4)L1 zqkE`s-}AT*>5!bZD!=!`+bsZh+iqS(R473!;L@n4!*gj`x z|D!qmLH0!|G8ENIzpsEUElK+#wEvsS!^UuuU{M))L&>R{n>ZHM)=Y-LZkfu2CyFf* zA4hUJSPjr7=NlWL>BC{vfp@6}m3=trr!nHx{^I=h#kt^qqQzee{NBZ~E)&qMiKB4U zEB~u?H0GN~!9j?1WYf&5^YTLY^ppXKq@qGFiU0L6G*$Rby6#v5S42Zux!LA#P$`IW z5iCC=^1ps7knD0Mu_Dh6{iD8Qdb>)Idpl{_=O~ROBqSt|;$fko63fQ3ynvFHr|K0{ zKe3DifSNWm2ocA{#**>7M*LIY@uUd5NEW0b)Yc5+InjBQ{Ztd1psvj-dNokQN(Olr zhN$F9%gR3ROG>(v(bML_gMzA~tQ;$H@42L;Vzv@+;$nWxLjo{cL;J@Z`s>L+auH6u z`NiQG0U@CQuL|-w^7X!GWnrtZEJr+G5(Ou-gNCs%q!gT>u7uL zekE%$0mJ?tYUH!;@b&~}phPE=^#~Ax`6}UX!UIMceih(XpprOYdUCKiR+Rk~fcBse zHZA!#4?RV_m?S+z;k4#Re;0CE!3uof`T}%(fi#%oLLd;yx_f{l@#MI3XiX5&yLxT4m+$E83 zmkEgl2RJU!wll;+aRWs_xRF%Q^8k>8AcQda>C$;`UmpMgsqs<-Uzg|aAN?Jk!0|>W9@cNMI zweSl)RnbrGl0J2JuNKRoH1K~BRt&(}g90Sl2SxAK-^&t_N@Ko>QS#O4pSo|#<6J{%qvQWPx5( zQ-KolswkfST=n+)M^iCM+)eFkf5a&9L zeibBRKqd;Rmvc3bmox#MK>o;B>e;hvF6HnlU-b_Ux7)n9xV#_nMYP-K$derN_yg|r zL(4xHc!AWy9bGJBGU$_Ku2BlvO1b@)_eM{#17ycJP;3;v!~hbel6zlLtO)8)kd)a2 zTCg7T3J#pTurh%3`R>R3SQO-MfVu(-31Ef1F92>RC?^TflSPXs2=K$j=-01(b3^AV zZr~f^5OynLqM)s0x4S^qH0gXViUvAZtrf?Yj-H5$HUkUP{|0HM5%dE$4wL~o3`&JU z&TH{9S+g}_w!vzQeJom)VT8}_FdSUwhVM{2B@xP6d2xZqcX)VD)A$JG@t>Q@F zx|kBE6MgGwYcmCOCIDZ7?NeB|Sfjwr{6;vf-@Gb$?)&&&-NwqwJy~nO=1WThDSoc- z@x{$>b0Kf0=?oD|SlBSlJE)%3H~j0vv2|aA?)eYRIxR_>=v^ZnM)9Qw=$TvMuem0n58buU=hd z`*JjqTp$^>A9uuIUV-989xdpg6mINsz%GGH_3GS-Lbgo8++X`v}fDr<^oZ&C8 zs-|h+gx{A{fiFv399?(*;>&Nmilj4or5`+g?&K6IOc^fwHaIY_ezCqL04q@Ia433F z(`Pt&f5*fvZhb%eY-8_JMdWe+$cT!D{g<>SgttjS>+){wvjZk8Te^z(0TQRUCwN!2 zx!-kvxXl>(I`9(~)#oo7p38TYMIIqjj>nBGSQWvssi~7Ux32qt>M^~tro%_2e!09x z3vepk!h<=fq9P&@Sx6CG&^4q#O}+jSq;zDmEKE)Bc4O*5{Tc?^6`1J{vN3V0l?$6S zZtbBAs)B6yJ+|;wrN)b>;wHb1Z63FhS6d8|spRg44o>P+?Adt6J^D<>ktp6aM}>z` zk9molx*Z?QKa=Rmr~cm4B`OpYauXoutFa|8LfIX7O#J*wSe24hRhK|W^y*rdTJ@t} zWXqWLRZ09?bDN7K0Z}FO)Q0RNq$DJjStzae7ptB~4d|`Dg8TD}=ka_lT|>WF1F3M) zth4AH6k5_nF|AZaEeh+OY}}fh$8rvMxWGppg>s3EA^LCv&z2Bb9IZp71<0tV3hgzb z_A4uU#`VdHF`StB^BA%n4q+>!Om%|J%5ws@`RfL6{QaZ)pp9?+Mo$HZdA`Yx1&^D|=SRk;2H}ELded6Pf9hO>JZE<++Idqw_om~E3?@8J z*AFolL+>O|<6h6rl|4I*vvY$Ws>K4z+07&&CFJsA7i>j!-@)vlvZHAX>s<>UyWhV?jIg!ZPUYO<;p z>u#*7Zn;K2&iO{s4C?)H#J7IcZtUwf4()!(#{JHG|6btG1xJA89vu{)`I5WdM`xW? z?bJa(4HufJ-cgcX|KW4cS2*et5v(Fm6~#|eaJ)79E?+j!^L@?0H;aY* z%EgUoyQb!uKEn0!l6_epEk$|xcI}ZL_+DtD@>y%;^ug+Mc%Kf@T}`s+sTfwnZEA0M zFL>;~?wej(S>v}~`sKer**#j+L{)KbdpiSdSVojB%{Hkw)e^PYnBv6Y<9|YolRErH zK31&0Hry}b!&pXdppWwA&EfH}!)io0@l&-i^)0&3Z{YiqkQr609lvA)LREyGXf8@D zpA_7>INE22L4bX5HL)$Ldcl}K{^D&4KE4A^94tghGFgdF{u|M;bBqYJOXN$w< zG&VGpRs`v1@l3<9=g&l+-IwVz#|SsMEWXodIk%B)*t*>1&EQCe!IpCK{8&^}rRPHFrlxbaO##G~{f*(m z!3q)Vz_-Dq6SBu5e$LqKQ5pRet;!Wq1T=KjP^`{&Z}Kne;KsXF1Xj-MLVY zkr?r_u4LyLff)Y2>FHaMkw1vo`W(kFm3-Xkh>Xr8pv$hTNmeJylLLh2?aCWu&a`Kh?vvhz?x*q2 zcU{Bo6koNbdG}>dEtSKKhlBX-iwWiB<=8479(+9OhE=+Md>iW~&{A%FSJ>grU>?@e z&KG>eZ%XK1E@wwN z8(sWtXJ<7O);jjH@vL;}(GTpB>5GjuM!2_f&-SbqhbBewKeHu11bSiI&b6eRY%iB_ zk1-h~YM-VD6d@ANA-~GuEyL!q0OX5ef}w=2R}t zOYx>`cf*^2zb=(BFH~2&5Zry%rMT4&TQjcC~KIV@PhW*!@<`Yc>x=dE|s z?a`gw9cEUNvG8?FkjPF=_0fq>?M_yvjg?f*tDN1aA!O9}J>0XoLUGn;L7^ktk8 z6sXl|Xat8+!ZOk{w~0YIZ66`yqYx!aiLq7hq5+GL2jGc+^` z{Ias$E%KKy>$L$6^S{6{e$*0D-nX{eT=v_T<*Bj%7Qq02V%SRfjf!$`(w6LSx&=Gn z5f~>Nn&__8e=9O*^)OSsJFR1#d|SDHejXnVsXYXPJ=t>3T3b)MVli;Gs!9-f z9)-vKKRUvkoE_=$gL(|a2-leA2v&9|v`&(2Ff8B9)2`Z$Zf zbNK0so0ud`{&}uW%#&CVVG)^XARZn)ub62l+A2c!kgugIyYeThX!C4epZ|@)J^SV# zfUR#+ktk-I%`^rdMc(COY>mh$zP{k-69Z2RlWU;W>m-`Q#Q8^y0E^BA>&;??}TJo(AN^k&6%?~F>Xk2$%y zRVAQqYF@?*ssq0GL`0tzva9zCv~q71baRdm%lcenO;9Iz*Ka;AW5r2I9D(2F%Ln%n z=dH`^tHc29INZQeQsN&7EH|#Wonv~pB))E-h2L#RkGfQ4fz?#0Ue0BSW8b75n> zNY`iFtuy^9l{k%&%u%Q7Hfn5(upz3ZOml2z+X*AhR_<^H8VyTW+RH4*{$cZ5jUJXR2OG&J^j`^b4AFlYQFdV zTmGY&+3-a$9$;j$KKUM~l_im;BzPPkB$deX=<%m};Z+6oDS0K+b^Dnzsb^d7ISk)q zQFyVt9Q!2ZrFxz^bqp0DYB&80(x$88beSG9={Rq9j)_i3MmFe{1!>9S6Fn1TiVtbY zPvnZu-M42L!+&6CELd!=Jku6ACf{dnVSZNXz8hvWdUV{g+;8*h6`+EW$Gv~+6BMH_ zZLK*s9|xqfy%SIG^1lGIAvf_wvK=M7if~Akv$P~D1wt#mLO|g{JL}u_9j^#al&OV| znl??xFO{mC_7W~s+}kg@cfZ?d-w(QPh|IKNEaYx2GOQ^ibQ)U^vJPS!0$5hc_Mg{o;4#eaTh4++eut@D@se=h)NuaO{_RcF@lJ$bB#w;CNbr-2c4qfEUu!G0kn5>a`<~@%fl%6>JUl@)g4wm zQT)V^fS(K30u5!pWY*TdLj*CsYd7V$|1;GlpHbQrfH{QLI|^WDR)*ZnYTo@p-Ff@N z@6V&jJ=a*F+L0}!yX7TbhhzwQuT|&l5`3i-6MyYtA&+bqhSo0(qwV( zM*4^G$#3oT4d@2p#6ah7EZHp~nl1C(cm!X_#-;P|Pz~S*0QEcJgUH}0tpED(aNFX1 z&>%Tq=uFD{*`};uSyW7sdv{?TUl<<29I7LL1y` zd$HjKypy3R+d&0~I9^zy@;vKSvRHxdFkb_PP}Cm)LDgzU3&u5_EunGa9*Bd$+xrA~ zC(grc(LK-JjX925L64HdW1<#kAb(U*Tl(CLA$ov5DNuR@`7Ep6rg48`5! z2dN@cRfFwubAk_r-+MaB;)Ax_;~|+*`C+Ja^RFE zBddM{2W3jRa-)lf8LCZ?awQseb1bGG$3d ziJ=j9U0#Ah_v%GRJT;0`RMTalriX4}X?dwi63=f%=RLeKjd5VS9phJ=7N5eDfXcWO zeIzi~*GHX`Y&yGzj_ns>AJNDr?5u6eK0iC4cQMSKFk>f4?DURGzAE3?bp@(MKF1hE zMXYnBnF~82kDJjYFfjK*$fMJZU3`ci(R?c1xmhuCgd>#FpjRMvJ5L3DeY~dO(0>(VmY2o+()0!k$P*0b|I-8% zPh5Fb(K|7+@?|u@yzG&2=e>$&O!x5nf7` z85F<$;!-0DNK{tQU12shvYrtv&}~kRDk*3pb7(V%HaJyQt2&lsuqm(QWBch_wo#d}k9tIvxp z8pL33$;YSambxIIVclwCc=BhxqNJdn*LmqzhIm+nUAR=S{YAr*ZDUAPV8@$b@@!RC z5qJdl&Go$<>PkNv3#-)1NJJ$p=Q{vLO*^l1Y%U}1;PzlCy$!R+uRxdG*{0fRT zfPOs$r!X}7f+i6`)t!2heS3+C5D<1d{&XRcisI{l^f2@M8b(%yjB|^PT%_VzbXcCq zX=?6&^;nG?bMI@`+Rw^w_?hgY?5c(gr6&e~a$LK+@QGnVz5KvmR9^mRWisSJtO-Bo zTN%1^e8xu_0B3alc5Ad}$#5+LR|Aj)dz=Ps;{e=PQBf97kxJ8bljly?h+^65K>cxh zYie{bJwr~WRI=yp7|-SMxV>%JhT6j;4Ys=`=UXF*{!C4slGakPvbO_ebc^!K;K?f} z7zKuo@sX^8GUsCD)g@*?=ue0O)s*m&O=>4 z(c6mD7&-d;4duRA4F2SCXbBO3N{WLd*HPGA@5bC$Fl#?B0-$b6ilz@qB?xX~D(9^niiWV)aeEXjh>J zxhIS9(yzL!SI4~Nf$>9&yFOa77<_}Yt4dIPeSvS|nUutPXkccvhV}Okp2tKx?3r^W zc3M}6i;8E3ka>LmxHvt)>Ez%Og9?9*{k+knw5w!@n z!r!AB*at|>Mgm+u|3z0phbYPRu{{dWT0zoo;+HSK(ofNYaCS~+1+lJ;ZE^~l_5XM+ zEOxi@5n~i0sEdK0ZL7b`q7XoBlfO%+>&_h&a0m#G4-Y$&9*L(Z0nS#`V_)J^Z!XxZ z1i!sI3y6i1!S?a`y5d@X{kDkvl5r_sW{3*h+oY1-m3GhNds4=0$ee3wRT39ZA8-`A7S=nSIrX|9wetLh%3f<;z>jr}r|_KPs3(Pt=0B zVeS1_#P;rLYbb?~UGGPP&*6Myy%%=CQ+%R$c5^)S>B9#pQv-+dtrYOQK91%&{rYr6 zWvfXQM*n}k)Ncphzx!8LqXQLdU$biAXw^o&dPhw?p`c!ek-$VM#nOcvV{7YZQJyzd z9%DZFMI=@e9trPx&%n&K6@B^z{_o#ML`upMecY(=X+GGo14E6bS$~@|%Ee=Z_f*Y2 zTTD@T;98(}R)3;=f%U0UfN>_8hHO&wy3)&+4h!9jEd;@z(h4@Rl9KiZ3OI;E3!LbG z{LppXYWJXUr}dio4zEU!sKt^^Sy^draiMyEj*gyQ$onK{X{qVcr?I4$i!n7`$0cC; z)JPRh4ebYh!HH$Z^77KPvGVm-6$)N6B4FXC;a>fW(V6#7S(Z%Q@qlJ(q3)z=_z%%% zJJFLAw~P#zXlhRD7HF)ydB|5Uf+Bb_UqK}D5KG}+k*R_Tji@}I%bei;Pji44bsrR! zXfxq4VPVL`Fl<~4J*Z5mFjj_+a0me0?B}D>(~mbQGxnV}ga(tmp=J8ayPCOuw8#%W z(fp+3rb3v`(_8ZSGU&vGR^}|M-24D=ycmDMENIzfHg!+E4+<{x2U-|gn%m&Z|8{yp zQuNCGF58h`i#vn#wl;~@tDh+S+Aku--Wy+e)v&aZcqi;@UnU?J!GO##B0Ab&t$g;v zQv~@WI2Wdop6G+U2dbLEp=maQudma6os}<2x7-5fM49y zCfT78xmU--&Zx4Gbu$nXiwwcR^`aL^&qEI1uPDgw;2#bx530dm{iYSnnAdMB{_Z!I zE*9Qo_HxJ=Z*g(5#qPV@AIy=~DU&G1I6O3R5?)Ra)a;`D_Y#0DUc8W_rTEUl6Q=pF zdmy=5`F7NLVNg`N4hiqcq}5TdoYD*4Z^v)A zjv@1o!4iv%I&z`3%)5U=|KswL(aitsOcyt%+p^2Q7a!sw-E#Hiil}*L@{3~Sm)rgC zwUf!N`iI>nz?|g3W`g?bs|I>Wd?Kn?V$-bDXKKdmK7&JY#;h6Qf8pT(I=gnEY1JH`(1LqOK>cO0Q!wEbvpLnCBH4#QPW zE7tQ>4|0o7Pz`Zk_&$qSF05u_iND37tRflO+^biyyk5>3(DaxupM71AsNRC&8STr* z^mz2I(;r9Ds@=OD{Ve07LVl`lyqdWoFtkRmNPSVOE%~uyC%N78=vY2Yycr@M=u;CA z=jk@omy|^RKX>xhR{9o0ljZsfd}>~mKW&nPdBh6jf}7W6G{mkOoSukv;FAP?m!+Mn z8M;*1zijF>M0ZKF?{b#!Eta3RO0tJ6$86X&h)D!st^FO)GlpsPi^%1(|7M(DtZ~*q zkWLUddwSyk;{*T)u_9}D*Q%3B6&tyS#(lpi_BTggqq`*<8BQqtGGd%GG^cFTJZ}Ia z_fxO?QH0)@AF~J*QquimsQm-=a^xMyg6=4uD6&{G!yrM8OBX9)zv3OE7DCQ>5+Iy* z&Gt&X6wQ7`uCFgjaT#f-7$WcvZ&QPf~G%PCoZ}#RWg7 z3diRuQ)6V8u2JlN9Ik)mGG9}?S#{GgOR{?Os!Y}1hplg+PZ}qlAc0+lm(DxBpeofj@4D2SWEyoMwWO5?SSO z4Z;0#Oshx!@DDc>AO*-pZN~|jqF=}$Fn=#NmTPyATKOso+lM$OHci`>(5D94bA0a7 z*(f7LZIJI|w8=%5jgtvg-h7sn-Y(DiZ;+A5jdEH$(2NnU4>n;TdUgj{GpJ8DeZSWh z#{61bxRDD~o{M9v8~DO}$8FjbH9d62wI?+5hAnASsl#KB5x)c}=95WL|4&6Mxe!Z` zLKN6~$X`x~^WTKatx(#cW8LBf*FUnO$fsjMZDOGg9moHUD!&onYxCiv$m4Q`L{C+V z|I3v_&KcrExA^s;eRrUP@?!j-Yrdqt6N<#kHZqu&jexHdTU&cO@OY49hQH$%#l=>D z@(07d3JlQxpKX+K^53ug;_o-!{YM<+pMQ?>2estFS=jZ>1zqZ&AMY@%A(!!g#>oY` z^y3_>mj^A6ILJ*a^i~4`UAK34g z+Vxj46vXHZUwRT=u9ZKyDj#$A@h#&r;)8;#dN<9C0cY{gFL~VXZOsSem!icYUF0(& z0`???urJq(71syrrK1n6`~fEapF7m`hx2(yY0zGcaR*aDOytUgKiZgos3_@6n&ec+ zD^n4||8wV!tuOY3P?oZ@>(Z+-aBFG5{EG#UpxKlSO|3BMUWHe83UH^DhzLV;D+c}} zd}zr73)qk`Td5;iqU)v$6>i{b#$rJi2`9dgJ54O?(hga#x3SQFc>DL8mlfqP+TRLy zxzi>7KUnxMWQ+SkWB_i%_Y4WZNqTBGzrW3vvckShL;Y~VW5=TY$IG+ZcW!bR?W{Wo zlog%2I?dK^klm`}XG{1AJ`QPew6PLbC4sY)1%ichy=Tnr%Z?h11fU|qmeAJtJM^m_ z3rQ%u^uCYsUOD~C)s_(O2zB!rxx zAwx<3h}W{z_twyz%!eL>jzmtvlwn3gq}fU&czDo@L{&GGl3^~RGb+<~ND#b>HA+18 z-D@r;u{AuYdSTx{ZLGgaCEddMaS!oW>B}*ZS7RSvu_c6zz6mDXQOHWd2h&Thv>sEi zbhSkIC)Mq=0urniyZ%Bm8~%h0hPoIKfBa>lnJj)=snpmRTJF8RHOP}x&f=7m`a4yt z+H}P{x3keD)HXq@d$vqb7s#-eFZG$3<6?eNt`;~95L#zh`QwsX64*SW_YUwWi=z*- z`9RuiM5w(Dssm%$&HBIzJe4~f2DB^J^|WHr!2&&#{h~_zi`E6ZG&p;emz7n?wAZcf z^G*A8sClYhLh%b;9la1K_y^|G6`D@#{{lN@NMTqm{?2h?B_%ONgI;l-iqEgIu=d_A zgEv#yiGAO1P~S@s$@?-K(z&ke79f~yJ@!B^)ypx58=wNOVKQ=hOaWEpu0E{CQd$JC z1&|nMHv@GSaK@-GXC|+}B&6F)iaRlmHem7`ffSjrx@N`JqsKe+#boL#B`kh4MRm#BQ>1MSv1Es#NW zu(rh9x>iAYu}){Qw^vvOa2V~4#@mriRm5t5w;3mlYNh1n=BB0=$>@m)coU*c`217v zGXi41J7Eh83t%F&v6FPH;kMZFL5{Y~qF6k=cH8PQoKeA_1&; z0+M-ix!s}HwGI}D4B9F!a*&b#x?&eY6E|EF8^FN33u8{ma z`Jp8B_r#B6C}z6NjVzrPKLL;Ls~K%Ay@Ux{>X|q#F1p1S_AyRjwO<^GXgQI(qhsS| zc_5j*?_k&&EhqjFcDAojcp~)nA3cM=?D0b}JOIn^Z&`6fJ`?Fh9{QX3WgyWEq@-0x z-ol(9kFs<#5_wei4!#QKZZQB91Oxz8Mg)tPZEkHmD@4rTloSy88w6>zkLU%o^rwb>{Guq^36@nc^yEe?{+zWa?&$lF#PGGc<; zWKP@C#gy`U1u{ii*4#SQW|sPQCb;PsT(1U2f&P+#{)s=99Z~himoKF?%h^vo9_`mu z5S~%&ME!TSi?ZVs89q!bRyG7&bU0ihRIh~BGF{`>h(!VNR;N1H-8g@?EmQ~36>O%;(f_R8MJ5Q{Y3A?9F9DW=1|4igKNb=HEW>1Ke7)* zOZIIBOGfbp@gNq9>$rG^;`pT(4PK3AC5o3bjZ}3k&a6jN7fj#OXZ|v8GX8nD!6`tC zCpt<37(X-KsQXHS|BYIH^O;aOmUsDm zf!eX^cD4qva$kNI5ybG^kv~Y{S=rg7?8_QW)EseMpQ)j}I2SICXcR00je%cjPk{)j zg$c@XmB}xm8t9hSsajS9N?h#*vT*VTXc z;EVOE4%Jq%ZH?hm z=wr>xMqU7$Lvc_T92`PGS%z+co>YnvbS?-6Ge}tVuT;otUSYVPnjHZ@&F@4{uM?Ra z68)h~P%s39O4GEK}cvz48S@5x~`*wHNiM-|~8#*1ekfI2}+v#M%=8^DMF zwks<;@UBz+RRm;Fu@VrKik$0}_kj7YSPZQ$_*@0s2s}riVy{bx*F$&iq_u7&w|@T(1!_mugooA<#2dsEfPDt5h=rPa zf8v1>33`IyysE$y2jbXon`cnbvDvu*`whYte}`*G1Oj(^C!1*{hloGVa|Mwz(mo7>VcL6XMM*K)DTPbQ2gpc6m?~skse{TNK-Bbp_JFbOlIbBgcWy-o_RFprbR2 zg9#I7hspMZS18XbqaN#DyZP;Y(3pZ5{;lkaGrXLk5%ap7Z#c0k4@>ne%S`iUE)gkR zp62|^E#~Trr8-@svb6w-JHRc>9?%!c}(c7{hBsTJd#j@h@3`J3ai?peoxD& z_3U(HD`+CTdU{}EN#Sj?{$igVw|(sn__g2Qk_TeeK%oAO-c}rxiaG!P%V;B(=P%P( zkDB}l%$mP~Oxd&`0Ub5ziVJIB$*4%}b>yvShK*bPZxZ|IQ`GYEbGb@OM;>yGWnZpn zG2S*}voriCclYL-08ybcHDKGU79f_#vFcbWZENhG;|+5!zie!51krCkifc`n;jJJ& zm=VB%7iX!8=J!=uexnLWEJUN~n5PiZ!W9*^mBX)0dO0G??aefcMQFV~^j~GCjz{UP zVTj|Txo?Ur$Z}Nmb?2J#m7v?LMNF#qLqguV&DiC(|1=)v!=_kfq%BR5>I(21jS>+@ zH!_Ki6Ve-CEPwo~c$QRk-O`jPgiU(_FC#r2wjM2f%qCILvo}!7>Z|$_jWtUV)IkTY z6gT}Q2a!C}`N1?UQ#Ses9GI7!{NH8gNyL-?bz2znUE+3Hu~$)2UU$yEDXeVOXBm0; z4iix~nc{d6%z`Ua_%JOeE4wpC|%H25`2oV`tHLg z54j$gXCy~NG&)lLUE5Ro5Gy=G)& zP2mEm7Dt}b)zj!uP**@>c$tb**7Sg4iFwG~*5<90g9Nkkx9QTD@Dgft3U;kd8a^tTAHY1F_`&joN z>3%Z3X&XuA>;0=i=^7RmQi2;yy#gL-oimqAmkoBM@>gwSXT>ua68(54$3!pvwWanX7YrxuM7p%l19;FQ$F?j?b-)Yrjy(7fLfyeusGY4rXdQ<%fQI^Vx@Zr^8#P867Z7A~Gnya35gIFT zDU{s$gxkIn%Miz?MRbdR=H@lE-}nu`Njl$IjZREf_urTOdxHF8Mixn!?Ht)hjr){R zTFbJn)mMUoriM$@8Tn+HDsuXz;v8UuR)+9Si^&Cqk3kURmnplH>J>jzAb3F>M1=~R z1(n=>Dn2NXodRAXE^ZK%@EPdofr~2r^ek?rw|>Myi@QDR8M)9|ICCuv z6J20ldrL5(#mWjCdU}t2Qws}yyIq=vwS-lE2X_lG-@LX_eQd32bP*)@q9cohM>EGq zBY7%MB^lt=8H7B{cTVg#=G^x59IH}PR#!Kx7!?m8nqFP40cne5K9?C5JlR-aGet%| zL6f5CgQP($l%&~F6lIDDxGtcE4*`vuwzfb_ca6~~XX~H6q@;+cDFLC=xvkmHriCCC zv-9((e@n|Cm-PuNb2sbR%i|4?qs>;;F)tSv*={~??&&+Enw^<&J)D={+!U9Tm>4Tv z7Ew=N$k_-`x)*p2M|Cz1J|Y-@CjD2d#xLpp`QoNk13l#U1g0xQPbp+fR@P=J_nYlY zHP!(&x>QI5-V5&-)p1EkIvnMv+#!+x z)J$bD5ORlg=9zpCD(KL=g7_0ta9q>>+P$? z4%une-Nei3+J@~zU2biy0yjussi z-Chhe^W>_k!rD!=gdsblLRdJ}TlQ>!5QX*b8~Y8De?}~V2^sHp%S7F74KcH@@i9I< zdNng+mXOfRzxh4>z_m!tvSQRjDW~@2B=_Oppd8BrnT0j}8JL*Rk&^?PN~GPJaS5=; zpaSL&CNL$$tyi&asKi3rIy%zBBkmS%!J6*Kw&A=qm1$&bocZx%C1>A#GUm7``>Huk z0fE!S#zt$>CZTfI<4!KZ&eX|~fpP|}xUtS>vOc!+5@~V=Gr5I2Jaz-Wvu*0Pf*Kmm zyFYy*OiawUN7WimcHH1|)TapM@qxv~l|yR9;e1+ZLx|gEPSslui@0Lp#hBG(zW1wg{UB!60V^4a)#s(Lc6|d`oE$FrW zrc=a1Yl=+2$F|us+e&tb36@W;X3I}y1&8yLqH6Xh9J)(nh1T!Ks(`erPUYRmXT1sv z?-`o%0yy|@T~Uw|0ND#Wf(GyrEW+(2qpR{1nJh=V~?jzybf3@cj+ z_KnDhh{u!p+1Wf`7y;a#66H%+E@1Gmv%70l9rP7SyMQkrCj0VH2kTwY%tnm~h|c!^ z=HJ`tbHscALK8O%>o^^bb_(kcGlAYI*e6u#UIvpq>0r-UyNxYiyxkJIZPVb@^Xlq@ zjt(ZWgpYkar-|U{;}U%}i`1#~&zCO

%IU@p@P9ah#{_<9;}wpswx$egqo=9!EcA zQr@>Na&d6s)XIHq`!zL1HtDr!>hk=4R72hVgjMu|!s`7ALLKh}ayo)wj@{j`iGDnhCpKF%3#IU>&2ZBSJ&NTMiBn8;9i>N*r8U=ORVu7<=EDguUV!(bi+ z**$P>b83$&Jf{31X@&Iez*8`ocXrY&NMfGGWSc|_-0i`m!SF5@muhZ5n>My<3~2uM zTIE3D6VlUYA4QVTmct>ioQc|>0OBR=B7wD^WD_~_U4#}SplkqH{R<0~ZQ^w$>F2U> zZ=2DvDV*<^#rQ1AIa#e&!Z#5gFPNO8{>V5aEZhbhrM41n?ofr}5p<=n8eDPO=u7<7 zKVG+ej39H_UmLHn+?-if%%TY)aWcvZ%IsT3zxFZM(%S5Br=7Z)1eiRqKFiGYv$$KR0gjg8;W%DUY2Vvf z?o*Cy*r>&a^!Lvn+kyG$_)C=-hpqTzWYTCrNrfsDa{mWULyi2dA3q$T8R|eGdDFF4 zw@^d$%sredp_BDDW>2CP4Q$S5-rmO^yYEb&ynHz~U|c3~Kk8RRM6N(`VK`1e6Dv_@ z80)xzz?<_^VHano>jx)~>A&CvH-9T0#Yfe#3}GrRFW3-KS4V6@-b4Z#wsEpD(gGR^ z!Y%O-kG>~qy#j#*&_{m@d9Mw<%C+$@?A$q1zwQ;U>Le|lx}YL$^{^dh!-no+8uZjI za2@geUNhE`#IKGN!C!}*n5vP|o|Jp@5I9;^8lGM4NKKaIh3 z=nTAv`s>2P?73a%o{4FUKp!Y|Z~cdmP3e zSmw1G0)4rf&1XMFAlG|0Hzx2lC_v7bC)3AjSg{a+f61|92~<&@C_ zMq>v{DXCNkv=$NZ?ZXpyt?~<0K;x`!JQC}u_XT!DWQdWK>YY<{GOi0Akl>x9ny(R? zlCrVB-f8Jp0hXZLTf+Q*8c{*+J9AVCEL@<*e{gn;0D8FnkMeAIom`4z>lQ9V1D;-9 z%TN;Sbv7y)21%r|Q_vn+Am!33Nd3_P%u9&4BJJ!3leo{Pz6MK6gM#=Ef`=Po6nz7#kx3QatA(#Ru|O6FNs54$@u3TPG)dHuBWNYH-F}CgbHZMn*;p z2V{@B2X!qeM8keP1e$D#ZAm0x#fKRzGnmDut=_9A2 z(gNnTEiF-+OmVAVb}N=$SO{i+C$O1;l0skX1TMIQ!FCAsRKQe_QGxS7Zca{H?qf8f zyc>;*Ku~aRM4eay1c1Qf33kW=$D9KNLC!N|XNPWi`TTG$dSdzGxwvu488!2&PW-Ie8pgjhnRh)8)b>Y=10o%C{Pb(xH;fgq*Dg1J7P)2z1~ zN6^&N5@MS9`>|nfLvLVXz?%0tUdoUaI%7L&7`!U2v(5r-ijz~s;GyHiN5`UdQDRL2zuKe>T08*IErH_gk(L@p z2S`C$&;nb&lBHMgEez;61qLGJ142rNEy3mm+H7+JH*f;Mq4)c=EdX6$>5+~fpV&Yu z#s!*@M`acz02bzRph@fm^RL~|&|_@!H5ahgJRh^<6sokJUphGW`1(q2e~v;fW>C-_ z!ZKc6<=x<8gpXtA`+3PYG5>(p=I_8Z3sv#>_}O$-oPvzsvr<;CM4`%~JLOm~==TA<+F*>UI= z*q)1?jgAug-V$}W?VuZEO9#0uE4SXOq2>`QwAiFJ+`RWM7T|2rr&mF-lR#1#_*j|L zs~>Y~jyD6ygD6;E={zu`6Fl8-ICt4zSoQo1VnPIi?AfD0x~u!yD0>?LMiJIT;y#^+81H-CTq+6Prs`Q{Zi?Ods2& z$_L*F^me@qr`TdZ3azk^nfNXylzHMGqVbElx*mY}gqlpP33lTf3Za7bA3qqt#0uWE zO0Lrsoz1)~+y8|62^>CxePyoL6{m7@Gt%5|9+I2N`Oiu@(J>&H_Vx#NlH{N@ zRtDG}ukIeTv_J;R95t%BSNxny;_l4|4q_Qlzuee1b#ZZ-HR5*8*Ts0F51zP&AnJ_X zns8|cO7CsQoP7}RAcybjMd7-lz_H-P->8QmG$j*bU|&Qb_q2$v{(p46Wmr{f*9M9ODkuihp@5Roohk^@(%q#rNVfqfDJ`vZ2na|n z8tE

Fz~$ow0E5_xs-OoU?v-?Q5fxHRpWhGsn2c9TOAr>PNSjV%oRwg{vs=QZg}p z7Wmwh&~s$^lHehb2bdcSSax12z*{jp)v`HWJ$C^6+ z;fJWuW9(yBEFyWIAS#O zJ5&`g#h={PdUWU0FC3Qp;o=X&+&d=*7&r62ZROv*PBZv0WsEq#M`LrE1Q(!Q+7^C? zyMP4i2$!x;`(QfU-KV_tzJ^~AM|U2+^8bAM&W}^2OZn>z$D6m|g!-gF^g$UgQbyTw zaBCe4Xz+^a8K%Yd%Fjn*EyV5Y*xdluhWHR?7Z(WO?rMAxtRDQrcGjPdG)O>WF_O^no}cmy%?sn%KWH=Zcyu4TMLc7Fo+1}K`5^1UM_93tM9uO!CT5vg`R|Ag9u|CjRAr9FV8ju# z$U414AftU#oIH42;0oC!7kk2!`x9FS+u2+52k>lcmtI~By$&^SV-$MxV>jf}L&^^` zznkYTM&6GRc68(-fJR*MKUVBa!q9qpKF9|=5|>fs$7~%o=gC2*MSFcFykw50nbg3JbK71RfdR5 z1@m9N9@@lpC`qe#q9dXX`Y3|@3Ha4$gS*DV9rm`5C;OGFhAUzgdqxxvlf|$F_jNWu zTpP3Du4sU^EoyV~N^2ymCSeILyxj(tQ5fw%ADu4L4mU76=7LnMvd>l^FCFYta9#QG zk{avg^^jHrzCD5G{pz`u(NV#9li(0ZvT6UP;A~3}`@06sZ9iT_nYc{6nG)^2;9!G* zYnR_W$hnN>?PmiZ(Z9a{iv}8^iL&n{M;70noL`gjBZl6>5znTNSGCC!zEw@NzL62E zFzTm$-(9lU>4B<@g^pML{pV(Lg6q}YmoS>PLO#bnR(~e+j99-(e&x8+gSbFrv18a08|x~UA8A6$Y=b{KNHC6?2F^?(W(m-2l{4C*XyDcv*NW895fFmJvc2blxQs(Xt#=n zr}Xq?!XoVL?dpT@nT`6=cT5ND?HuOGc*6MHkIzmQWuTv|fB0~fghcnj1B$6B*Yb+3 z&8>n|DGGTIqZY07(eP05(zOmW8Y^2c5Fj0Lpf7VpyfNPV_35^*E~Q3RZ#TQKRNUbl zUGDzT(V2#tb6zPoElbF+kPm6@TQPSH4Q;u^+@a6~04gvd%pf@}RF$Lhlt*=a>CYdS z?i=Ws=}lpF@;h{%?1c`}MFxkNfRc$s&|S!Mu6{m2Sy=d3L+N+2f(Q-H-G)FnWR$U* znmSabxkW}0C_W6%rcBOks*mk%+;Fd~OlD#sAbCNm#^&K}s!mi9(e#e5#0GSst{eTz z81c8!zJQH4WDg0U!@yR7_FnJozsn2j%K3^mbKKKJjJlsy>@k49I)t_bx$IdSwrX4a z)P6XzRrgFNL8F-Atm}bu+Yw+ujU%OW5sXy&snSt*h;eMoe{NT@n=XioHq^iVskTXv z0=J-|X0=2FAQb@N>HBoIS;*<&;8NR;zSh`(fa{+yPgoEoQ>*whK7O{w%}q4s|CAEvvFW`nN@M zm_rw-%#fA&P|(@v!es>aMrvnU0e>RGzqQ_or=?;w zA2%Qfv+JC!+%^7GcqQsEy?7Y1q2K7f)6V(4F)(=WaSZ3$XyI}PecDlfkS`Z;vaHqQv{?$B-E@Lu6b3TEXCVrKm{dU;RfaCxired*I6P<0vaPkW4@W z0GZ8)62#bW>RZ?(hs=yJ)VIpFhsQ~qTaQKyI=#I=bQSFXi$2Y&NNzd|&osLV2tML* z_9VFA`4l4JpM&FilkH=)I{c#^LuSTNCe5pkmraDGu3nZLINy^dn$OpSF5FpC_s!;Z zB2I>q>6@E-(2x!Y=C)f@*(BHNbuZb@SnebRjR~0khCK@wr0 z6_8bLfxmV{R0cHjg7#*nE=Q-AFjV>`MU`WgP1yVTexJH-8YBdBy3JcCr5;MQU zIj9dL8Q^ZM*c;he>6K|MFIOA>Lr6#@_RLC0=WwQZJLwYrw57K5;;<%y)P21MW(L@~ zT5j|3{#$Pp>=DfdNI>Yyl?o!W5B+-Fc5_$+_&OqJI^slLi?nFo{C-MwS8vX>8c5<@ zjQ3=W3{}_lta_ei2uXOTPY{YlKaxD9-)PkN<-wvIn!IO%_S&@^zVwfs(_WV`_DJsv z>V437l$Dd6!uaI*$`B&*_+b#)+0o8&D3zq+tDPldZO6C%ovodn(HxHrYcB&z{mgw3 zF<`Blaba$$?iCC8A8^E+L_Su}G&PA;zo2Zl-V_WK2tdn%tHTa)6$!j^9S=%%fM-;# zi60&FaD$@0d;6kpgO=9Lv_@<`JU^45=OV&gbq5&O zT4p9N(^M~d6)f>vvg)+djaM}h1~`%0jy2YX8E>!bA4Ex|{wd=*L^eS-z_q)?L0aYn zLPF1)!nXH~Qa01vjv(oibEkFuU(8Cf@p8otCJH!pt2ADZc#2zBFI{@r-3_H*U3}-S zPpP~1J5e@l8RsXDjvWY9;PM?oyd0d!Ytz^FQA$YXv|)0ZdfOcA@Z048bW8+OWUV0>nIC-n`F&-$HI10qF$Z8aC^{r? z=|B1fgtr=Gk-9q`;c0)@M(j@ZXQde%!7SxT>L*`+tQ*&c_K}F~{E}aEmgO6N{1{WE zqJJ808Ohbb{vIcdcb8;!ZGK?1_YEkF^L<-d_Jb(~1P*3?(#SWB4)^plmD%t)7aEqE zZ_eO(91X)@6|hxk1HQ}T&tU?GlAg@tkS5AZ-1*Q$;2?Q_-+FW9&L@NIreM3B9Xc}S zSLZv&{~i|9zfMK72&v2&dpTYmEDoNVrh|=mHE}OAS!nHmY@iC1POH*Kz{v@o z?c~B4W$5pc?I9md);xW>&8+hC?fl`eC>h{{A;$i4)Y32CxIt|SUPv|JbfS%oU42|gf znwR5)C2JE;H`DV|W=-JD^!}HgHJ9C(0z+ggYHLtH0`kM3q(Z5?V<$1WEvj^7o%VORfqtbyagm7~5gt zg~;|d0_|QQjX`Iv!AkqoI z85jsLd6rLi4_6nDyJsoT#$m?_dbmTztGs;ZmTU(;1i{2|ziE0REgdMHqF02!jz2j$ z2|a@TjSiPoOhNaOh*1mdXb&F`rHFPt**L!ba?|2=1HCe8eCe5M*K{RtgI9gpr~509 zjNiB*i0m^*4CepN3HgYj@u_QwRV{dT@zNWQ{R`(~a(pz9fDe_%Jic|gEtZCiRV{)k zwO~KJEU|X5$2a1h#=V&K$kvCl*AqV7P07nMyO5AQFyK+r-uJs4w@Kn%u?T248kRKj zQ)>?wS4c5zv8-eV`Nd@SUsF|5h_OeratMM9h2)u;AD=&$3=V3#?7AXcID7BG3)K^$ zUod2ksFSkzbnD8aA|2d#$n}U0#AD) z2jxHGDs-aG;bCN^zEOf1DIe%KTv3Lxc zBdX9vTb}u1x+qDJBKvHmWmlX^ri&QgUcMN6p_#84oIU!#h*!|-Ym~$+kQf#ZKc-bw zM`F(eQAKXKxp8xDa*NXAhEl(;fhg0+^p#l{l93?e|~?TN#WLG#%G}O;6mXolFx_CI3kJnpMAcy$CG~ji~fB! z!g-HwNnqUqCWLkqGKwDxj_Jy(BeD`L4l6Xjy#(;n2Ww_#COzHq^XQwP_te7NC4aFT zw?yJI>#|R0PZxKbIqYzsZjv!kW!cnGgPZ}oL{ZU#h}|(Jopt2@Kt00TWc6=O9ZcBp z+z(KKh^0rL&))W?fmJ}*)`JNGm?&ly$qiVn=J>vwMD{pUXzYohllj8+AeyZWB14vX zG8|-k4~ulS6YcsM=J%LH&qpx9Dz#gOM{xi zoqwvc&t026Yw{tnCzUQ1;?P^dXe1;5W`e+9nZQL=l%U@Rmxc{Uu5BDeA}vznnsxp< zW1|j&{O1tBCMvZU;v|LsYLfpE-!DODjV*2lQ#J_lc z22A?kIs-c`2VnphEW@M`3mZFu%X$iYP~6C!qoI>t(@^>uV~oSY6I-wkr) zf!6I*e)cCEa@RH;s*Xqq#EgN2+#bsv+LmuN#L_r4BN9j~*1)$v@g63(Gf0RIb03Eo z7Z@2pgz>Z$7trq^*Wi8CHmJmf!4I~{1u_^Jely=;ZffcRd3z|jv!L)^6ws$Odu0Tn>o1q-pa|jvWPBS~ z(SkdD^4nj4MSzO!fi0<$2oJB=q@R`}MoQ##n(XYpezM#mDw-!G#OCZ|&tts?V;k(h zt>D_&#`u;%CK}{{5^NpJC-fG;;OVK_J*FS$8@6W}H%u^qW)2tY$Sq7_k-x#B7*dk| zUSpxJYc%iSKdTEN67STI5k`at20+yTa-EFeN#D_MH7bS!!gO@&Gwi3!`e9{W?gos078gK$DED!-BSMuPGeJGBy zY8U+lv~?yxuPgoxogMyA17pKN7}dYmymS7YJTIXN(8@u2j;9vDWBejiai|geagm2l z*wAnma;y&hw;?PTA4@r2Jp+dYhy!qb-iHW=RhpJcgT=gOD8-HHCcyD z9GGhj6#x~pS|*Tc0ahscb=Uy<_as9=HH#ZKn7g8^vtC{kQ5Z z__A|e^6y~VYbkrr=aW`>F+1aeNPMox`RdV2c)vi4aS>`Lxw<3C@AiX^F4IPWBj zg~Fx{Z!3uXiw_H%Sx~qQc_XQ6*;=JGvop=1VyX3d5GA?~5sMNM61hquAiGjh`VFV2 zq9C~9L*_nMVogC{b+B2>4qA}&S7j(a>Q(9ZC{9}WC3wRHKi$1u(HJ9{3ZW9rihsAv zk*UG4u`$U37-gWcFySXKIV__D_9;etRUHtljq=i^1P8aB3ekr{!h)flVh(Z(h3w$0gA*ceG1nlY+05%!b(R)aMi=kItvbksKF{$pq* zA`UTh@o9Bi)FyM1;Wd38zo1MyT449SQgtHah+&MBNW>8Uo})%_A+S)-Df5jV2s7kwp_W!S-&S^9%Smi*J7KGN% zo3=>PRvrBA`#sk&dfy@EhW8g?a^14aXr7a41qB7)zthvud}^E?THS@WG!sOgqCO)% zsLkS3b4hD(l>`HOH!R{%y0qP;_HyOOuthO}`ml<9s^6u7Nw7cr`XmNrufA|_Xu6Zp zOTX0bFmLghcK}`Jd#9a}H{yQ=QGOC$;Iza8x-rnJf!Wt&osYFS-}$f8!Ts+N9QGDe z;Ew`MWGndk&-^~1j*`5#u;}|Q7eFKvtaK<_EQ-|?GK)sYn#g1r=8q0-967rtL5M-w zqQeAS6RNCdeG|`BZPk+Uy$q}R-mdf}EmbgcsfJ@Fy}0Tog+oS0rjfSvJ9%Jv(fkRF zYdPgWDFLHKMOn_1G3nC{Zy%omXS<1!zjY`Uh&l#Dg0WeNgI`8`p$-gulwdGePPAaP zl^(>uO+}8XM$`3zKOP%*vC*kB>z5rV)Ek7w8TK#wi>DOj%V{f*&qp#N556^#*#Doz zahOow^qCGJOAEb)Dx0xHZoijRTzldt{`}P9JLTU}+^>GhK=C7CU%CY2_Pt!LR?T92 z(jYt>9AR|H5|cmKkZ3>N*%^ct79L(Y`N)@Ac$7!>d(FZAWD7L|=fW=c>CljU?W>r+T@0 zI3iT>fp2iS0I0@=;T1`XbDiZDKEC7WvD5q|UB}4{N86YdGY;SZ5@Mml4WMj%SanIS zblCzl;Dr9^HIUct3R3jjG~{*211~1}k?%?yzx2#CE54=N!yEmOrB`sk62-+LM|tz^ z2k&2erz*?w{Mm@gG{H*<7^<)QSBlasC~)RI%4Ob&Jw=_6Mf9kJLo>IW3PX0w!QG(; zzC+Y|BamG8XW=dEb`X}JTwiN-8%T)QKspEwV#)D+7(@Nvf)(V!#{0lKG~`KS9&IKp z1**G&b)r0&*Uh=^;N=8S^6*ge#vJGJ>g>`7zDz$}GF3joj-C5M-Qe*5S^*uWBc#Ac z`^e7D4i_op?f+J*@INWK49YCD;`+IbTDS=HIzQFv@y1-L_|MS(C|I4?!t0C7tT zw-9;(oWRu9x8GPH;K%uEW~T2LI^QP++JLX?j(n-0`)n9|_7*S-)&8Wm_UAFzW4p^u zIfuT|tHsHPlu2~h{I$zFIaiu`CqUoQIO}TE_T@G{ev=tL6I+uh32K=`$4W;>hvI?a zT(6h&MQvfYp1P9%rEIBQH)4%~Jyvap=b*&;f5T&Fp1O-zURYM8BhXwxt;ei+8!JaF z^ie=kB{c-5%%o5igI)y9LY$bSy=aIneBRoe)+)X%@fi*=`E~61=GlJ_mIwPH?3@sM zD-VP$gX)0+hsjzm8&|KHQaO2fRu&eOKE)Ps2?;>2qCo9Df;T=eU{pw`rUt4AzPEWP z{T2m(u+Z~0ng4c!o{fJ`J1agu9)#b0AUL1&^z?iv5dmx(7EPQIEhD2xZcem*^_x%v zB=EaLEc&8L033C@{uLWaD8bY)XAK+usGd>Tt@X>>!A_}2QjT+o>-_#>4lJX?xqpYs zE;;#^Ng=R;fXD#7$|zifZPg1kmtIhYKvro8UL@3Xf8bT#n~S0i3#QUqETaE zT=sXYBZKmDLBq0y0S8q2=)I219s%7Y~29IE3kZ?|yaX?%fnQno>n-9FY3nyLS&-TF&?7A3=6`?b@~N zQK&26`)HRt1`lPPFKGBfhv_d*uG)a*vou z^9FwcAqx_HHbN;-RROmU1jg^Zn6qMQZU0tZa9kmjry$z80l>S!goh{LZ#g;>(Kzko z;*ur{Pitp_pvPqG6`*q2rWAhwg4+H*pyr~Gd)C;rySocy`agfvi2viJW`%kFB=99b zBlHAHEoEvPI3`qi2IcQqATyN^xHwRx8vQ5skFs`s{jF+P;*Czg^5YxFclc4NaFF910}4C=7j}G^!^#-jjNHOn-MiIPL0}=R7tGZvHTk2wlE%#Y`{#9b*l%rt}fu-zfDX$GA|o0-rv_J%!%2&WSIPn6O@AgPS%^2^kD1# z`|HD;zN3%T&HvlYd zKyqL++}*9qgpZ#UbIsu16=3Gc0sjqtWq9wGcB6cEQ1-cjBfNK|^gmw|4IkGLZVKoY zz}KFDGO`sQJ`^P^HL*k^M}hWXaffKL0gGHX1m~1fXN1kq)?;7a4F2e(5wCcE;-j#} zx6gDqR#z@E1T{|D3=wZO>K3dR*dXHSi&R%RVn)sK)Y|MrhfG-1ZlGt4>2xo)Imgv^ z+*z;%Vx2`&_t1N@5p&JaeAzgV6WDxvxvf`#586WCCeQ9ywk$1P zicpSSvg!;X<0Ewsz{nA`zsnaTDJpPK+WQ-MllQ-T_aC$zP?P%9J+PKWzfE}=RWQAm z{XnEtuMnoufqnJX(UITDF^Ch$$;ciYZ0+8@eudAkUXN`^N~ECQq*%plCZf*p4P#;2 z3S~6k+Wx}Za=`#)MjfPe^j#3)JM@U8%KUidVjn){0HR7ZcMnhWQA@)H0B~5ZC-jSBY3)CT)w<7538X`Bap^0 z4D1gY@k5)1wXaKn146&aVZ=)5=I{yh<=WUuse7;&Fd!jp zZ4Dv_iVcEu=NG+48<-4a&2b!1mU4t&T$HXb;g49EivFbto`b?TiF_2kX-ZjfmQH!; zYnguy&-nbTlj^QUHQ~^PW^?I!MW<~||dW8im z^uZrn=kr$Wi6UErKQd-BY=To>FHzg0r1n?&YHbGo{dy4nJ0r{6|Fx_ygWR%6QEqoD9`01(V#}UH%oNqsR9QS)z#3Feu9_Do`=;)S&vC$$4^rfuFxrg3Q1FAL8PS z7|KMUOCAe{qF$IerrqGKo%^E7|1WhBfrt^X{q8r#bvS=mI^Xa_>q_MD&5yG=h-;7l z!jw3&HH~qt=BeU@4Z4ZoWC#h{|LGPK5~$;|7%-Vstw7~5$IYO}w`|OJC9)mkI!1;v){v#PvGNW`muKrEovzK;yp?3w-oQOP)Z+Qv8cD|%#Xw>={TR>pSNQ^U>C3iI zrww+(H|BAfd9s??X*pTS4i0DI%E!p6KeuO}kTK4d&;`FJXG{tb0k-0^Z|f}tPJE>N zHS7ts&mPQnU*fo~3D2I42&cdh4nw3w5jTUE=;YRc^yv>Tf&2bngRqy8$VZntJj5FJ z=^P8G&%;42!d!qYE5?uJ#%2Gjyv zk-uvH_M>s}@Q_)NxZz7$yT{poia0b)vx<`HtQNb{pBk~K^71w(Ot$zW%RSZk%0>P1 z4nF0zn^1o_MqP%LL~@7z<~CjmC5A)_pPYeIKxSDPqD-y7Tl*>&CXes*N4jU!IL?|P zWW~bh3rUfOt2&yWEZA?THJ{ZR6~L_Gu^0VENFTfe*58#R(S)A3BqVXs(cDb%gnN#TT|WH46G#Asa#Oa%9|e&7 z8?b1WaSYFHUGMQCVCdBr@s9K0u_7I!1vYI zju&8Hla}gG%`$&VFBgJ&mP26=`b^AO{I8vFo+o&=I!8?(zZLqS0aeTU^0eUMUtp3j z+ZvhhwPY#N-71Ntr)SJ*`Ej8LtLf>nJJn}#$^^G#>*J5NJxf;Y{ecCRf{qrKrZyy z-Bi5zqhv%RZHk@C68&I<(ISQ(hj=FXtw>O z>)rsu+%gfzE4#89$A*cCi3hv^e~qrO9QHdep)tuY;8Dt8#WFphW>ZL9V$Lfih9Pcm zbZaXwT}NT@PplR^Y6~x<8VSv-nGLQa(SrceX+h_oRZ6DUZ-k17wyqu2r-y_@BuEU? z(()|Uy+W&|2$%nob5Y0fKCdt%V=l;nAfEyU7Z<{MQ|Xq*%ZCbJ+f*>IGqJIOuWu*S zexqFggmZWhj&%Rlh~3_32cEp5yuAGqPC_FQ0UjQloXvra%@IgiH40S2fo{6B{F|Mf zGuL^45_BE;$qw|YQ?||LOUvp!TNGcvc(~DjLqh6WJkx{pY$?;Uz^^^8q|&5|6ZnUJ z_Zu3NJwaEYFX}b^(@aJX7_=uLeqB<0TRB70_r=g)-UaYuUXV2u6U!1`O&xE9+YABh z`}@$*zQ@1@YkF2q2|-}F_AlBt29hPj#qnG2uI!!d786Bl(gq8E@X2B)jKoPYd+lU& z;w-8QI^&jK*3%ITYTKQw!x-`1jl(fv-R|`}cz+uMjf+q->!3xpipyY2$Y9@C$J^P) z-$7?h=zRRxbg1&gOg(0v?5SNGEgf(3cp%C5JpD^l{@6EfgqpB7`1}7j*wXj&i}CXf zx3e2483CBivk@juFvfvd1RkT-NR>wwsyt3S3uU)60Wo~(*8CPWSv<3wvxyB$@4b_R zV<8_1f_<#|Lq}MH_@8lJbv6niz?aj~I&P!Ul~3~~!om$5qP=5H*J&yFSGLUs?!D& z)6ln_O#1ZijdC*3(16ewzBTdPmC-_px!Ikz!<{Sj_1j+_V&azX_DG~q$((M!#VDGe z0Y)Mf1xT@$)8*fv0+BEN=wz+A`e$34alE6Rq-!}Wf#FqtT174QQ!*{5S#Jg&5I8rB zUKOxo&lr1a;0ltn1h8}hd494Vv6x-K3+803(4lgmv12mg9s8w7kU6c_PA=gBrV z_c+_1u9~0e!VW&9@+aCmiqsz47b2rQ7-!cM6ZL)VXMWzMosYRnEB4}D;@u8kGiLk*Z?w%?NJ0*Y z2+0SE`NY?+%cTopN#&p=13rbawhXdz|9H#y<5f9>P&tB>my-CryQRkQuV0%#2DTD2 zV{TdMBe=&6sj2z$Y2R^MGgyrmZUHrZejq11Ba4pT&Nm*#0tMg1-IdYdwNNeYlinb~ zv97@vxpxmge0Y1|!nV!90YKBM9Hcw>=O}}xF$!Wpk9+Z}J^nVgX+&a@{CIy#@vzGC zdMPh2ywx_3Pi*vY0;AHWIKi9S+dn?vVvNG`sQ2A(Yx{9>aAS5>6OaScY#zV_a4lV= zMURBJa+D;zz#s1DmEr#GdG1#$B;+R{E*%ygi~wg0WZ85eke0#B#Ev7h$ZR+wI3glC z_WSQw!~>DO0iRS$^}JLl|CE^zdpnG$hz9!mxmfn5iZwT9AuINr8N3SDJ9w2x9kgo~ zy3;yhzhS@5w0!00v8;4>pH^-XLaD;SJ~KV!ulQQx2y}mX)gSj+DU$XKb6)7uXKrnS zhR`&@BR+mP!Q;#YWDf+zqa07tmRc4`MiD+rxi_z4*-BO?I@^GX^4_<9TmlwR(Ed|{ z;$c{6MxDMr=~8i;&VEDo`!DpxK7}ln@jZ2W?|Z!3nVZ1DZX@^NW1rs{yst8Hmd0X~ z$Gaw?mvb(mc~X5FR)8)VGBuRIp(X$m7`BlN{PrsF3cUEX<4a-xyZe$9R6Ee480JLbGxC3v{7q>qU?t*5_CM8t@E z(a+AdBIvlD=R+DDnjk2dM$6=;trK+|tYnWIAv-&se=@xCwvlX2J77dkSzC~fN;F08 zhPHoYn(=TT$%%R#zk@}?_TohWj}Obrzx&#vnT6=@FdwRE(};K9Jm55 z1CSiJN+H!w^_8SM`uwr7wLFd!F^+9jRgFYM+%1r=c)&+amzbeAFXMG}_4m{{@KGUQ zHnYt5mXT4O_>TTFJ2okg?M74D&#*9;f!qXkeGvoU4=)xtL-g7}SCgNAN(Rw!L5bj| z;H_3QV8A1%aqJljS)Z^I@|E#9! zAoZ8OKT~!GF40|^37yt&LfN)>?7^?uiev<{x$VS@46MtCS0$t)PNwD$5PNJ9Vd>Tz zw4T<&!#+q_om%KdqaDpNpAaSe{P`2|;jgE@_KIXw$GuJ3F>6(1KE^kZ69ojimS%#k zpi%*b_{ufCx0u>u&z`ZVnX9|Fn7X)p5ND?nJj;JOvq3f~=}j?XgJ@*>>vGnB2{%WF zUKWSlLuxE-VsQw_;ZTYAYXV?iFV1uhO-8`GNj8duPmxWTKpTEes6 zBn1({JiT>LuC)d}l0XYs%rU%Ws+1!sCD#3ljj>`^O{b{By=s3^hV0Le2M!JX)j^L! zX_y~8;H6vk8$~n+=>@0%`0D8(mPRW~-_hC1tEwg*fsKbZ?yxtS(cCQPI1^k|d2FNO z1&a+-*q`SB7)ed_P>4<;)QT!0}^0{KTQkq}Dr-P2{;$6-*Qn!h> z8S<$bh`96J|H)?*K-VB59k|JB+FMrE_U&7(e*NmvF1w~XQ3(gN@1G+>eY*hnoy%Qi)r{sUmIp%Bu|)Lkm2ii; zEY7NGx+rT5IMOH|o@{@jGUHGelJ70(6g=AnW%+SN8mZfQ&2voLzTX3W!in!jG%^&* z+y-(6fT2WtJtreuN=CwENmNjc%aZiK+T!Wk#_3YWD|QaWLuS&FF9v^FQ#j#D$8o>e z%~aE?du3+wC(mVX8k>K6{bX;xJ$9(O{~ifJ6t`VwWf~QjoSN;Ovp~^myq`NA{00r_WZIu`9 zu8V~O0)yp4NGp13dW}LouX;VFlXgxwJWZ=slY)xU*P+t6j7_aumOT!5Lo;|FT=yy~ z+wSWdwk)0XuJ>y;F{n#(-|)-IIv^wBB&A`vsYtB^S17;UPX;CbITLEUu_z-mznP@h0V;gC%D<$Z4sO=m+Jl6ux0~W;1THStp0)Y znYgmk$gj6Pag85YI6r&WH=ne$d;``;h}W{lB`iid38&%gMSgTqGym<-$Lv%x_Pv_7 zpLD4fnxM?bjE$)(3?<`u><%_(4Rm``rJg#DlHjL-h6;r!)_xQ6X*t{b^Fn{t`SjrS zojW11u^QkRx#R4k&5G>yDb;Nm+q7vPz{nBOwURP-U#l1)VAXP&4p7$eh|3{NJ(=b9 zDO0bQm3NW1a>J*4p;dnVe2ZX%gJX5S->2K-cFNwJ%b_nEc^&%k@Ep2e!j+gWH_)xC z<#H5;v}nyXmAiNSG*Y{0B3}{6B9$OmhJi!3<`oU)0vj99znR;+xam`j7M>rsn*9TG zyBaCmwg;E?j5GRwcfG6`UW?7jB>v5FYi%#9`#anw&-)uIYwpG1UgMqmC_t%o)+$xA4zd3)7r@Zy z(Id(Q7iW%&v&w#>BzQ5RJ|*7ZuimDYr(s{T*BT<8BKhbp3X|0YgiIZnwrim9dO?{? zo7K;w(6_y)yEht>qNHxdv4=sXz!R4=N}<8&bF(nS*u1|b>?d2j_l>BvN_BSEf~9<_ zx~3~aIDU=S#cl>0w+QEv$A>lQ9C}#4z-j)L-mRs5Lv~x_fSPPJHI|>@&HK{gvVpPJ zRXr%4>ZufIs5~2&_9Nhzn%=hKKRd?fzKN00Kokj|L(q0qo?{O1}8nfdw8)+*@= zvRcjZO2*xC_4?LW>vrrn4I*0?E2aZ8u37gSA=_Qo#_QO#-ffvx`BLZjXGLfE()-T% zZ1PJNcP{SmxP?V-GP|B4xUnAT|MYs`J4Ssorah!Un3=raETypZx82vQdE21IDFP=2 zrr1@zJe6-RKVJcF%MHhO$+Q4tI@YM(^A{x=caL%H)~vUBw{G^|sPH2ZoJKQ_pvu|$ z1;j7rf;FLb)I9#xr_BRb{Y?UyT9d+?ii$QN+i#E33JYV1?K@K)=tQa*%Z{hXEa}yL zIyMHHgLzjc>Lo-Tyg%w7C@v)hCNlxKRi{f|<|D&RoA!n+Wn{#H-5fLzsnkt;oMj2- z3`*qKL}<3^qe(?e6lEBM zVL4}_Ho`Z3k`M^fvs1=#$7#EmcAmpcAfIv(?=HOYmQ~7`+!&%$qU?;mr^|xaMVgcT zRJ|8#eDose3zj>+ptF;Lu(Jw!!d`DKuMO%J9wq5@@y}#80 zvG*I1hNe?Z%K3Yz)NndEeRlg>)3pA8%wF1et<2+*XxtqjVEiw7Lo}M~e#rwg|Etes z9mb+`9ULz|+a+JCN2;mx&||x zXM%4eNm4Tkg3hLG((2s#xlT`in#^hDh;z(w3zL!0VWL_&2@4Fc%1?F`ldwv^hf*Pa zk!!g>-QFa+v%_jQn7g_0Y zX>?ZOZD+BT6&L?1$y}jn@1r(bF%51`WQ5A=vc5i@%uxkDj(!8718Skd;ATBJE%93n zUlFl%U;9lY4$nvG=bLdT21>_HV8gu@$eW7qznf{Yy4bsP+oDjfz6FvJl0>mB$Brir zmE-vlI$LwuhKB6@{Zcc$s*j2xGZ#SXd)`r5cZ?-{1_eJrkQC%Sv=x2KZ-~7 zUCV75Puo>hR#xg_TtuBUEpc%(LC-WGTzdq8M~Uv8}kfwV1gIN*tfp;MZt- zV5=H0|JEcAcI-{X78^?5KXqxQc#_!C%J`XjlWS$v#i~2;VI==?@L*9k2Zuqe$*)v9a1e==>tVA2l~nFLNtu zUp1#UAwx40KZbbiHER6rAwrw$5|xleaIfgxyNX(?zkbE|aEWgM{#^iJIZ?#3W8 zc6=-Xf+%R9AHCfhEgmyE>a?{7xBZz2s(43wE9>t-M?ak+Y^v}$I}!wHNP7Pga4jAA zkTWyjV8pyRedGQWq5$;#q<8P2yJ+;GS?T(A369p%5f5b0k-k3sK|W5-gwFZki-)a9 zyf5Ox^q)n=vXNlM4{Bu?NmKA0PugW<^Vq(d)u4&6{1Gk9Ax$wQ}Ij*qFs}JPH+a_{(yFE60Qq^XPC54Yd%kl7ku{LdMj! zk`CXTBD{t8ri-!hk>P;r#9N=b+OQaoih~}BGlIJ9T1>`VmAuUeb&HC0`4mWE^wU0` zN;6QUyaTpf2`G zbM^EFhlT6ouGF$V8IMCh@T$K{WZp`Z()?UrlaIydCU`W>Rw*F4pq3~LH)mvIl+mx5TfVv1{WAmqG*6X=k5mxa-dbP3AR8_)VcWX2 z*Ad67ouLpcL`TCdaKGq>mHUeqO~_GR#yD~74?co-wB7oNaUXs3!)$K#D@nZZUTXi{ zRouvac?+vWYo|;xUy7-w9z&e>-yU}d<`!kWr1oDFa`#%y`P=M(M24pZ43qHXPFJo* z`BQ~&7Mo>M_Lx^_<-VW{^!G5x z^V(ws67tkk(g}bZyCKI-P1O0sxVR0oHpU%o**O-3pKsm0J6!d>-^6F>*>hoGamo-( zJd;BoD^2zkxraE{+l>lDdNp4%IqcU4lJb{3?_|GzEf25w5Y5gw-p=U_Vgc8Mp239$ zFji94)^=Fbgl8l8l{ss8MCSB#iXUEMM1*}%?%v+fr@OxrRlZdWTde+Y*3>F%y+HWm zVC8ekEqCg11D6s`c$9?O?`ytJcTG_i#H9j&lVV)+d3|YWs`mxX-@mmMw093& z>!?abk-=*g)CESf01x>3Zk|fW+>lohYX;>}CUE}m;k1Q|8@_(Mn4JxIs+J^dQG6u! zN1r=u4Y55wRPvAP7Nl*BGFWO^{90sxW zvo;8Rh_Ih-7&t`mDg*D$8RRyNCtC@EcK2fT2H-};#PL@oPL1??-NMAh$yO@_VG9PK z4F%0gQ*a#&VxxE+!1MZ+pHLvlky+PUZIIGX;}{tlnpY$Tupib{ebKUHe5^=CMKjm- ziJqUI!AH>xFY^n1YF^I*i|$gDm@n0AbHQ;Ot<(lr%wbSEQpn*y)Tx1cD5=Byuhg`R zjL*jP1wFK~5Steie~FS+cx=uQ&TzuS+=%x=VPJiz{zg0$IFabkft2=%5Vn#_%Ss_K^VY8 zL*rEQE^$n2x;x1SLv!`lCq19KJcH&N289}WKN_&X#Q(C&gi`hH@Nfy*`!)+^zV?Y{Tu`j;3uV&cAhp}h0y zY~5!(ER49y>|%!Qbc4s~Mo{OdO)I=GxcmFVXBztYes*+pta+S$`&L9w$9Hz@M|_hL zf+|>8#J^p&E7ce-a@&Q2zMk;{PFy^f^)c_bDjp%Bl7_26x(TSyt zF(+S1?z+YN0y{a)*uY47 z%eewT-(R2f!^0`!?AGA|{!nQfKN{04ErmpwqQ+@veCL~_$IdhI2PE7!3&m9@_1GT! zlo=1WxxMLTY3*sQW-xwAjf?B&d)EX@(8JZ3H^CM@{gXLP|opk-}X7!qF#L& zJ=qAVV#UXTmlgxP#*;+Q-$_X+0*L>G_!MoP_NUhy{WN1bhn14(1N_%@dg*iNO&$S? zBE1u;Trx5@`2$%FFJI?k^RfLxKX(8P~PbWu)9A;f1DCzWK*Yk|TyLxJ&b@ z+U!(IK4ganrC~X~XpfRDtwQ+&Kpa2opLu%hdB!ZFkfpkxw+3|J( zW)k*?jsJ(Rw}7hp+oFZB6%Y#$1VIJqMnGDTmhJ{=kZulT5Yo~OBHhv*igZagNOyOh zw~qg~_r5p2@txsd0P6Yevt#WQbItjbMr^Y%ZGj=mulDTB#;MX{-Ad3swrFZcekm}S zAj|(|!n2WnMP|LHe)e3H^ay2}Re#3iSL1u;gPPK5#{HS{fN}+Lw87k}phyneWoY(j z`H?Cf1Bry{hC274kPulpIeuKMha7Sm8ayRaI)@8Qc<8Dna`_hT2eotD=Hx5hzPFTQ z<>u61Tf@XHJT|D+x-x9==)-KopB@pdT?|RVe;6nW-l$T3X%UCYC}H&a=F``UxmOz5jPz5V zSyQoz4Xdh%{vCAO!v_bSK}s&POjV~)2?%zvD&Af|*w`sY(kR%-T_5*A1%H`*I3X?1 z(L_oXAHTI|BN9hvRFEP$fPQ+=xVT3htL{+noaGCJsN121xpI{DgxatlzFLOg zS7!V zgXsUt=}lV=@m&4*gVZ<#PvB^>e#gOOHaS=rk2S`0cL6v%w=|#sG=5l55!jRz`SDAs^3Ghoa@?|+ z;3P5MC4}7IBKAW)Ifg0+cpp?w2$i~nZ<7M2zbR!i9{J(j0I}QK0y@}?3ep<%4R4r- z37ru(+tU`OuQJ^Eu-Ne-pH}-^R6bq%8=j{qW_onh>7~p9Y)s-;vf23J5*Fv9z}9%h z5nE^V{IpE)nuFz+Cfz5Rir5Xo!os1|8-;h0veBhyp0>Jms#$F_eAu(U{olj*6pbfM zSUAje9DcvvP5K^&_bb$36hpff2twY|yU4SLQPoH_KXk$NljTc9?#%ODXfiBP%IRce z&x8I>rMR^-X)#t=79jyMMumgvC-NcKA>Tu`X7QN<$CIeL1LwO)fQOqb;ga^{mA1=Y zZ`;y-ZQSe%e7nVT=P)0s>6vv%{==-4`9%K?De@9)Yvyg1iKN_dN{$Ern@Q{Y`Dxnk z+}ikpj?8VC!1OG^^IKdD4IPU~2yuyEK*kCYUzw4cEbP)Pj1o+$pTUnQv}t#j%t?2lwT+1cJ^apy_?0JUBr1XleNPcx#lL}mEFy}%RM86je5?=MWd!u*C zKEwOp+^a`=w~+dGnl&^Ak=@=Tdww!lt{m{J&!{8fU zBh{s=a^fm#Hx%QS5{}Jx!Set8`huePW00~h4eMHHo`Z_@+?L<)HR(5m-T_#a9NdWN zxOG0ydf81~*%Tt*rar^{p~m^%pA0qMz*M_4kV=>g4mrIQ`#vWBPnh#A(a)~L3@uVC zQcPdSOCa%grCQC9(v9&sG;VEeJ|!_h)J@3eISa#x_leE*6ipg+zaX#ki0R3;cT>X9 zarXc*_dZFOjDS5m$&WCrGg+jx4#S@2=i9yw`7X~1ox}g3HY3BRx^)rl(y&SVyncvU z<7*LxXKV*>z}3vf$Vk{lruGmqA5Ml9aWYTuXJj&AB7!m_&bNDh9AO-BA?F4tdGNO78SeY2@laZo( z@Rd3_KSRR1w#rHIh+2zrGG3K~#teGRnphf>ks^SfcmD^lzlXxrV}32^{LD$s#jS4n zTZ?(TxNeVCPc(9L4#&5AZ?F30$$IT`X&Rq9!yKJh-~Yl5g_6HsS`Mho`jK&_(|nij zjhi^`9ydOoY6~#T7Zik&`DW#344NHWUZ_NZQ9Wn=V!WAwbmvQKTU#EmbK7kZis2nK zVR#@TE3={MHo2YBcE4R+$~E`2FG`kYa<<~?=*`z=hu@QUugkl;ZXc1yOiaoRO0j8q zz(*_{HHANRs{9W8rKvID973JoZ={a#elh+kcJ_}*7y~ZKmD3x#zUMMj5I8IX09gOcZ#9+^$5m_k#wWd+dIrMiLN!Quvrq z+z9%{j*KD<%+_LxTE%ig3eyx=r9Y7)#m*l(Z{t1&xrKi1XAdq>Q_P~@6}Ec`ggB)r zw2t`uN(U~Y@`$d56V-Rv^=p;{epkWjXr+<<(l6Y@LtIo1dX~Z8I%k0|=EhChYr+^Z zR98Kln~0T+yztm*%%aQF{m}guo7-WjB2sYQVd>+*a6jc;Z((e&`X!dVt5~w&R5VQ2 zalL<^DO@(Va?^xKuA`oCelxJ^9m&%eL)($Wt94tXTms>4%efO;vc;}v+>=M0_V@0Ec<{aXjSG>Q?MgWB+0wx- zF6(-G{KF*+1V7(I6!Qa^b3y@WA0VQ+J~(D*w;UI0|Cv=#hA$Wtua#(NaI@T2L-PlR za+U&oy=5uogQkLRO(Hj8JEUjl>N4PC%+nc~m^quyywxN=Ml|l?-x@!Va@F90O2dJ) z$$(F*Ph6#a{BzqMTF*Wc<_lMSvH1S#fHyQgn#iyo5`mH>uG?E_#37ooRmzUM&a+;< z1*y_Jt?Nb5%DFyVYcM#W&QTq(da$o*rdevIUdA*wvsV_ITe#3!bF>~ahch>N3_w!e!SH1{7GV++YyCVuk@gl(8XHzQ-6)TzyKej z-51RgC&V|s`3sC2G9%ORtR9`*S|u(L7x*dIG-AS9I81mL)HE~K+3a#U)nuUC^@uk( zbC>(rMRQ}cz!sY4IDI=FWa?+gaV)-x=W&YG#o9ak+{8-zbnU$pF@=g0>Fw)4?%QHA zQf+>)VqPT?|KWAk+#mPAx2q>%eM{-1&E};1ul>aTXaTOE+M)2qGGxcI6rU1c)+jTR zbjIGCaIAYml5~F9w1AFrUkV$#q=qLZ=507Y2@Uj^BifQGE4I?UJc@qF7)Z2cQR#v* zM8+D=KQ?UMN@u#s^u?!}t;VZC|EP+`x8d#+tQ$6wP+bp86piT^_|^A&3jtePnUg*>Kq&Q`LCJTS$4-`U0ZP$Wpdi5w4BVUbRkYI6FNeLWWQ*2hCEQS%;F_kh=9A$;x5Pg7Yr^V zyW~V}Pq=B%#*VCU7O0y=;v*x4jcZPv>_bRK+_aEV*Q~aZrYxSz1j{s+%;uH^Joak6 z^0oQH;EH@R4i}yITF%>g`6<|;6~#GWG_xJ8s`(}YPC_R{Geq0pFy(ioyhMUq>N)#n zddGTB7cT|U#nx`}je8X88L$&dn22R}YlXTCUtN>iNm|MBulUd`Tw>ivyS6W1nF`=1Rzt2bLQHe3#g%02ov+a=?b z3ynLbulP#Fas-9MkwmoAo-Vf;B)ARC>`~16lns?t99N_Wyk<_-U3A**I@>EB*jFg% z&CXC(sSfWeSx%KN)NenY-(=%;SiY9bX9aSdef0!HHMadZY}whJlOn0|ME zq3|Jmo&gTUd3P)o=zDs&%Rt|!j<>$0Tz0ra&(qb~ZpE&SJYSq7O}I=(P6iplVnOa9k-Fb4 zj@y_~gH!!+eb-E1|C>n@L;g- zCg06yF*!aELX!1&MsbrrdlpJ4Y@=H=x<=+C_UScV<~(eXm$!D90t4k(pPHiIAZ?lb zg}~${{Z^hbyt0F(lIiwBJ~h@PJ<8%zCN%KE^fvzhDd3!emsdmnacRW3P$%nmq*$t; z4yR2z3okE_UHvT78>bumz44$Iu;KS{Xe}$p6WnU%d`9G;>;NiP*Y4g6ao~z?ngP)y zsLmyD+GdhkY@8kN7P+2P2L(wJVl^$<1dkHC9`aZ@iHa_Fx$XmjsdIs*C(?>3+Mhu4 z1XZ0;<=$z}Q^>1fp%D`a-$RUd#*K>T|IVFa!z2>$oxXChM2w8(l%#T$xZvzzirCS#_qB{b`{>R8eK?Rasf`8;^*E1 zq@BM+Z^n9ddM30Bi`)=lA7+P6+y&~cggg#S4e5!YG2t3fi7*<7Ud{qgSJkE zez~B^uSs9S-iQ_stGOgbpYq6rB7M}L(w~;*H46#{twKTf4tp+@?{+^LwL1AEFrCOD z|Go*ls9CL}i#$z@kFuw{6auxNgLeZAK};ua#Z zo|i|yU!L#1RHD?_w_Q(4BiYV)&es7I*;RgHD|=X{5nj|&t%cYwahcwBBIJouc%ZE(Y_>BKa z5P;GNFg@Gbjg*y#YtQ#K+_poASy@~eVV{8G)K-n4*6qF(3!F*hy?RL~Q z*%F9@GiPd=gYNOc1gFgRkv-(@J>?4QH_WzYfEj6{`rraj0y2&F%=Pf*M=u#lQpx-*h`t$H7F#*DR-2(=E(}1*71#jNJo&7!V24>0(B4}0Z9{xUO!A=-Z`(|b@SfD@!cFQ#P zzIkr9QHjZT&#$3hZm=VI4WH5G(5l1@Oxfrr8??7avAeCGei*(2?Ia}Bn(39_Y?}tc zOTshoWeW=nHp+M6D?BUWoa}5Vg5xt5BN`ri?YI|@Ypm@!H$remiez;h$_bypmYw4yt-00JrP-6| zhS%WwLT@+`Vi9~%-lvLcYR+07oa=`Z!B5+oOC))Y&gy>UUcvB*ciE@+#ifPTnVrMK zpNXuPRHfO_tOKZId*pfe7nhY<^JQKf$}TA*Lj4yw&n5Xwqc3d}th(OTnW&t)ref$HMK*w^=c&F)IWs zqZ}h}wv$s*X=znd7%H{)vxlJyo+I6+w+#ShjJ^98t-l{R*UbLZ-H=WfXNXCHIzEam1y+n-`YSg?=fVY%+*i6f1TOoQBoe}qlV zE;cKFmC0-l(onH}pXX!d;! zT>T#Al>2#&VOBWGR@?91`jC&j`zJ;5uEiUL6TQ7E5xYo5-TT15lchA-n_sP>4d3t= z#t!Js%mPgt?-1{x=BrmO1_svxn|%HKpYj5o3u_EFl!Kr^Rfmp)bN+f2gt!YxQe=wl z)+*}O;1JLHP7%Lkk)*(W$bD>z#B>M!C}T4-847F>5z2ZKJT6>%2`P$0suaVMeS|(S z_+P=s@vUw_nWFU!_cOE))0FxEFa~YldyXzVlPT1@ySu`Cq`(!|qJ`js60<}^VQx*Q z)-%wt?&^$tNC1kHM`@ZE7&j}8j>Ko3OkGSxj6?vn+0x$G+S%1{>yFp%wPQB(^cBWk zenI~E&epX_HT+byS~Kn&qM3Z{;B5BgnQh6OVKEl?aQF!ep7nm=UB4>G|7BQ;F6ocpDlI^jB+p1>; zd_j3sHk;A@)r~K2^-fuQ_Og#`62eK14(1VfblWDQG60vDThk@JZA#EnD46&fVF2=p zJY;B%0*yW#sa118ERwhT7-{qCKctklAAppSA-0a-`)J7^?^!SOr^7;p9!&B|+Djv+ z_Kst21DV2;pyv!~M(+Auz*ruzk&~nc(=BpR;Q^1`2FSY`tv3(Y!R35ZYx@ zV*_nS)0*E`0HofiL6Wo~x3RiBcHA)Fwc&QysK?eQ*u=`h=IAmJYsAiMr4K;s^)q97 z<(>9&=4)6F%Z?gj2J=)C!lDFNfsqKkeA>DH$mQDp!_$2&HIp$P0tJ2newJq}pDPOr z3&2S`;Bn3?PjTE6&jKg92tBw8x8Z!*+SXrCs+PGc&31BjJM^37XH5M04EM z`dy58m^_~J{DjbAB`6)Ll4SPQd?gSd*W$F|SB|b&Z!dgy0@hi-CFY*q9#gv*H(dUp zNUnDu2gHbWUfwEvJ>LIojG=F4=e%hH$n(6|xWs;l;A8qQa@v>hB|cYm4VQD>djIXp z>SqT=&F`qhl(7&)Lhe6T`d{&p9z&E^;qX~YI7T2>Y{!B%$bB7ew~T${~M>qV~Ay1p7P*!5qbqT?}UMY`!c z0(JsDy@pMK9*GQW*M$H|g{-uU47SLHGo4-Wyfms^2%R;|Uf|TbsWT$$9(mQjDOLt~ z-0tV!JnG+^Xr9N?kt;t|!^!P77OsI4NJlwuRi0(0!oqAYAA8C^%auQDs_D8n*QCmm zo1IJAWh7+Kv>!LBE-@JV^(oL$1JN)ISyo2M(#k7MkZ6E2PujvpTWi$0%D#iK5aQI5 zTRU{t06`BV=!7XmCB?g9f|};PwY*YSRXiD}G>?03`_=Ge5MOE}_gmKChr?sq#m+S| zJGXd`KKFqOShMs|Jj+~zo5V>_!VYWr*UWw_m&^9Y4&qo2YvW&+@OLjfPBZNH$h4nu zOUo~}?EWACc0!mDbZ%z$U`xAhZe0@!cnBB4aT0KN1Wl8WTAYs^mFCp=k3rL%lwB^( zQ%Vo6N3&D@-U0YU^NCm?eX9UKM>sc6%*;%u++EtuUc$h*A1o}>2)zeqowbwr7LTBE zHo^8q)Y@c|Yw8pxT;jCyhtIBbZZJxG$ zZW5qIci)>I+96uBjwy(TJruH@V(13W%CkT!lQg8VnM@+07x?HN+7&c?`^9iUvrhYH zVSMk%88=H{GKqZUvv@NRvhc=7EATDFFFKKO28-y;eiDA3ly_<5?J_Er>Ey-!`E^ih zOFl%_bY27wxtH|t{I2E=az3JBQ1FXI>ekNwYBs-J?t3~kI{J2%Mb!JdFBsD5>mdiwTR*|~&x@ngJgrlFt?d#%(bZ~8*-A!;Qv$R$GPqkYo(h=vUc0OO? zBMbn|q%RR($d!|jkdT(Xqx{@vQ3@Dxhdeb`czMyZ@Lq0D|Je=<2o(N4<=Pk5T0&Vqd)An}Z z&OB`-uUj`j6noqDMi*h`?=pzpL9Ui$wk7%P%iEonRJoswO0^ zKb(I-CqTuvi!Xxhi0MTY$!G(~UNW7brluZ)vgMWp8tniY_15Xa-4sM#2SK~Rs=RMt zpk|FTyYf(x(LK6q=0J;=#Vq#=y2y%UZX!$;~B`PZM zS)AwacQv~;dduL+hB>>-G3oGU?9bt>9@sn0Bm|zrpEU^9+rot%?@UdzO*|i*FuQTi zc2>WTfk)%{=CUmEJO5n5F}>{fO~#@I6{!0EeRaHJ{0M~?Ke;baTi>CZ+q_xywd~kd z942dw$Vqc%9A{|)K#gZZB)bx78CY0MTSGAgCozrm3zgFdX4h5~HC?u%3|zy4f}$cL zP4XiTR)@nre}4W}LF4xXK%O9Ggl<#vYi~dbH$-6!~u4#;mxNIIM{PS_O z+#{hg0JtYt_5zrMsluQ)09Dep5dgl~T;TQqjm}+ZU>TBwzVmDTUysM!+!PSeu^swr zqm$UAgV`T~06%4)(}nF*CLQ$HyjE6PBUk6t{Fc?HJugoDT#G?Pe1Xo=Paac7w^G1f z`Kv~+j(=3MMV{I7t-`gK^^DQqLP5o$z@e}(Ba$s@C{l={-+`izdiJs z2I=MQ(keWcK|XRz)aVv{!0U&SzSvi&H*d;cIlpkcnG`*0CLYJ~IxH*$UH%i#S$5;h zmcQ$Ug}<&rR!t>cQg!`ZTq@_e{z7qavc|a)Ilnuxm?ZZ7(p6INCYkNvH^sCQRT}Ju z)s@vxe{;XXXPG^eXc)iSVP^s4cTbFD^Rh|@S@Ia{&f=nEZUnCP)X~$kZ8u5I zdJ7PS$&?vL_BO@5ZB&f$`I-(M{+ps-sU@QvrabpkBVzrAF4_ryh|K$~`heE1_~W`& zE-fUUdc8XI|LG_LN;X>*EsLM%7v+@RVQ9P zWSeA60@9rJtns{gwMGKkffGTIkDTVCKA6`SQPQn{sjTy+;o#7v2@On7d8|z*jt)s{n7%e-8x~pG3-mo_~W%G_`xEoFE>?u0V8*cpg&nXpCL@ zbp#pS&4ANkX>0Vaw}_3XY2|y>fAc5Fpx>wUNnoKa$jKR;**9hh2;|A`H#D885EA%S zhO)y`I=chA6&;Im;-X?#B|AgJgTM@*QJ$6YB>X#-6sX4yt+>59;`ct5%RnpzA2#^T z>>-@Gzm^^C%=q|@O2)5#E&bvBm`R4q&DBK1Ob%G7`Jc|_5{cyqj1jr_kG-WGv%{jb+=1giHqH|#~)&y|$@HFI{? zs<+b8t3R&fs~fLW{fK<(doO@^gG;(+$!0odC@U!VYozS$xUduxGseB$A#S2&IC@l6 zHut^=^-Id9FR#b}khp~!5LL;`|3CN!HP!cx-ow)q<%L_#Qvp{nwC6khS@${g+c7n3 zpyeeaS2kri0E>BCFW?ppE;BtFlewLoQhJ@1MKmJLtkizAanZp2fc+deu!_suFZ2DsjIn*RMs(eTiq@=`{0af9g~T8-15h3NT^!gIFF zZw!qlc27y0LAG6WwB4Y~E+Wim%#40K>}p2Y^QCtDDP{vfB~!D6h`ZOHbHr`=J_O=* z&l>|t+5k>lAeL&-1-M=r9~{Fli#cUvSq+0h=%7NMpel#?@jYrJc7pMZw%)s^1V4EsZV@Q3g{(cFfTsDe`o6^`%MZz4!h$33%1Y(Q}f+fSK zQz>ao74|N$KnEBQZ&yHS1o(NE=q_vZhzJWC8W}xy#ncwiEzR64vk>u{`!blg<`g-C|V`jX>_E+)RZjA zGFH6<+SwZ$M74EN07UQ3AEnl~!cy+6;nSeI?YKHXB-G&%zq}k@!pf|(&60kdHDS%x zLHS~M*HTDIYb>`!tFJ=8?n?<<=^_eOc|u;lJoC$?mVq?dKh5-MI7V;Wsf}?+;Ho;$n4=-n@!~J@fxK&fRtrhAwYn`aY zU&|(^HZw8($X2)?*c2apht*m?ng0h%l-k3G;hl7a6~4};%X@amt;DhKy1f1F3JG}f z3wVPdgtj&*QDB#@U8OovUem%J6QP~C%g6lOPAN@uQm^{R(3_dA8fk+I+vNzgizzR# zpJKbC6C$q7y(%=G*2z~6#ugd#QQB75%rqaJm|wS*ESbFcKgA=z>qk$yZI}DL3iytU zjEtF~+-v}@riw$c1(X>=*8W}^D%8^8?IAVowY2NPajmTjm$LHk2(g$cMFeZ^-b)q{ zQH$v?Ep;Nj+bO5Km>qQo-J@=8-^kW3r!jSK)P}<;@VgPikdsqhZy7aFV2;%0t5+V0 z=edg9W4z604|vakh_hIjX@>DeVy;m$!)|0>vnsUt|mNeuq{1rBPWab>bj2~ zc2k4r&!6u6P43OQ7qPtb^2^+vC7ffQQHnH96*N4-8g5U+A)j5fY~et@?q zanncJ;h~19cL2$h&sPCy3=;lsKI_5;JqtwKtoQfdncg2`cWLNi$Y*@C8@6qtC}d`r zZHqUSR(Zz!S#j!~^SP=9f*1_QH^^rx1bIwMXjD*NjBEyoeRxbv<=a8Jj~61WP;|EM zyiv+Ucx+cOi=JSNkF##uW)^W;I2ootdcucIL?@HsPL;wyBSwM!t%X*za{C`FKs2sz z%=a&Rq+_>l1UBe?Qx+qO0Vr*`8n9!d^ZUm(y>hIcZClx4;<{g4JZ6?qKZWD{+$=CH zttq#6v{H1QLe8oBQG!U=GLA7O>Kd;Iix4jqYU zwR=ML?-}%!2yw~XsjtuMU~`pr=Wu8A681+fi}R$J_nh0w9ROVDU6$qVy7$V3`VbYa zpC0W1Z#$woe%%L+42UpefDSDxYRRe`bOrAf{Sj2u`tTCPW|HEIT&SwG)Z6UZTgc8} z++|C6PN-m*{(^3%W%eSfmu-`;Ibw(xSCnQtSX`OLbFgjmh{CPOTl;WS(&daiaI{Uo z@Ht_@Mc)qnZ>OguSwkks_&ABc@%8+XG1xNNmNDXVAuau*E6?^TFt2(IuT~UE6r~CV za7js2?;!K-i8n3#?9Y*l6Uy3Rvotk(rB9HW*wE(NYGqdIr;TFq??$QxJym6yxO zejJaB%7I&{J2;E)MCw3IX0X41?%+fS51W91I;M^PjzFk_G-#4dSv1cyCxI+WGF4hH z`}?oQr{zTJmD?vD{r$%i30@X^ov?pRO47TG62sFk{BF#m(k>V>{HR`VCS{%C&ZbN6EQ?+a9i5tdsp}h(G`!%VP6cWEfebJYzawb>}Vs<|C66&xD z;@e(TcL)IVnm1$?NhYs}!dSMcr|rs})VOPMiOhupIRcIGPR0edsEtcU_2Rgwq=SaV zZVU7&33*6puOry_M}&^{La*8`N^f(fD=;N(uZUqwhmeW-508xzPK2(Fs|lV*zo+>6 z>50$ZUp(*Xp|1r!^te<&>JGo^VG!lll7Aq$N6dWc$JmGe^y2$>UH5m7oF(EmqN#4& z%A#;2JX+!j(J2YkhI(XU{Fk&A66A5!Y~T&y(B7p`J+>d2pM2cYr}m^NLuN*a<}IGz zy?a;p3tUxP*3a_bsh)T#MDibpaID0oA)9qqnqNSo@7-wWof`c||BMMnm!8PK6cQZV z_xLkOJCi4!w*a;@zY$I`XrP>(9KezZ$jQS}VN2h8VhpzgP^V_(2@{ zaxw4vOQDTHxf>!awA*(cyej%zfL=?@a_>)D!yo%^_%Z&UdMj{8eau3_Cgpdps;Yup zqq(lcbQIvl19N}=DVpCk1PZ|R;HKtsD1%)`I(_ur*H$vwX&b{9%p z&;$v;)Zzmkc~D+ip|Syp^y9}buL2d9Gf%>QhS!;Kk<1$|z1dmaoGdWkK=lE*UeM5Z ztNw|OoO~hocI9~Pe})Xt4Sw!+?yR8^KOm1*_cJ6W#tBZW7DKx2<39sMlfA<&Uq>pf zs=Bh}u)VWWOm`WLED{JJh`14Q{|=L4UG|FDT|{+FRn@5{fmxZw6rZGIAdIT+Cj-2D z-XJvf8!7u5tGA`Blz~uJ3-D)l|1C`X&XP|Ohrto}^z{r3@>EOBPWIPS1}~!Bd*SMO z4x&!bXvk}*-i$QF?5;rnGp2Wz4gJV>EwAzhH%5xH3Ja}aF9HXU3M4}An4X^=y&cGQ zTuO-mNk5V)_rGTHT}BHY4o-^gO*BDS5Yjr;Fdr-HHZHdFG6c~b{@Wn@n2_K$ZaWB| z63`?n2O@eiDls#Fc7ap_6N=^Y_!yDX_9xW+LXTP#DnvC89%c>l{3I+a47$};2J=c) zfF^A1{fieXJ!mg<3OqyQwfXpdz*Oyn{4sp~z2pJgv%LSWeI*MLUy6zmlN-cuq)be* zHS);eKsdvGx`$DlSwY{- zfS5{IS(!=e*#nX^s{b-M{~W$_Mt>%JOiyX{XeB<>k-zRO6KJexqS(wLAh3$=i!xBg zMPHBe97x>8CEyUE&ij9VVWCXg6%i3x#`L?RkMA!if;zZ=zqhf2w1e15=udZ4#B;&`clXQq=~-C-rA2K5)Qf>=5yV2!K3!)Ax%z(xgavEp z2?|A#e2oh;U}Nb?zh+(}d;j>{>O$mg!?+6`12-cn3<*$gfEfbh9V$69N8XKXQ1_gb zyCQb+)zREVhR44+F1;x-tKhlHb5_VQ8km|L(^70sO_l zft#P4WB)Qh(b3VZt*yH6>dzRY4W0Ig3WuQpc*5Jo;_>cIMbF>=1MhYY!R;wSau~uB zKAlf+DhKNfpBZbso7~tyCX+Rwg|xh@RYN1Y+%fu6#eknih3!%B-`1=?ad4%W?hRUy zGQc!vNSH>yH)o@x-DdwY6R6JwmoIDCF)Kwj+ z(*u@j$fN|ssU8k){bgfiZ*c!f1~hv28><%^_g6XYfKH<+tE#>IL4)sokmcP6XfuL~ zC@1UH>+0+s39nX^zTa5~vrAB`OsLc>Pe3(PW{zWAORts2elB%lILNYx~ z!7jG6v@kse!H%S`a==?$BXX$IU9PkroY_jpF9vcB%NXf`WRMuayjt&v&kW>aoj^^* zlYpVs^Y^s=xd0f*3JMErH$CV8V9PFS_kg0|cnID+l@PefMMOaA5ZEAE%fg;nLCqf|k7Z#+Kp&*>xG?*1 zfk>hA(KhT=@&sqA$r=}(vqX?0*;WRT7~p988iQWP@C&t{(X=r2balD*hjd_8;2ojm zTsuLrvZBJy-DINb2(&ND{El+WU9w6_?8aI_fR37q3W^7&rlvBwK%CO-l*wu`^v(6` z81$ap&KKN>y5d+=OH9hwD^`F+L=lQcmM6b}d3nKY-8upG2sBxP?Bf{Nkfq+Vxg(G^ zjH<`LrMZ6j;*4g$LyvL!r8)+Fla(sVnZ}d#$}X^yS<>?Id!3vcgrM08^NeVYW_hdM z5v|97cbp)MJ=F>1PQPB=@)syDspmSH4O!0COX{ZBA?M_DTIxvw*%R-8fbc0HBFEV% zgZQP|P$5Oo3M7jmMkDjTQKEu67!3K&us)I!60WCPO_PobaW4g(wi@n(WF-(J-N8qK zX5VpH7+~mPBO@2B%7J?0n&(b1VP#9`-$w(fS|D9Oxx zu+SxMRz8Q@FAnmel6w;m$#&i#&(ESmp8=iaIvN9J&@cz^r%VHwGaaPH7Z)AoqYOX= zkjQmOuK8_VHSBXc*gzuI%mWQ#{I0c{>S-_a`#UqS2AHMPNBhhI++|IR37gx?lu?M1v z^MN!3UZ9eQORMtCEP*EqBuHClz#sshbFDFCqO}-cpbN9Jz%g(M?ynv~)ehq2BtgWP8SS`FGGroTP6*}$DjzP>Z7cP%Jt zKTzpB+(|%k{oK+M!`GZ(NtO5Lh-4(8r|;T0Am&Ew0(k)hcY;ZlThk4ztryV5v|$i% z-!szEb}Z~vgSm)3V^)DY6hJ5bND%?4*dVCElsyR;LhWk?GWa;5k&%Z$Qlr*eiPFY} zn6cGq(hYgWNJV4P;DZC+2JGW)W!G9H=;?tiYHx0iWHX-tS-rg7T;PH*8!4isrfxGX zZVdzpRTvKN1`%gvWz}x^n<**ll%!CRipgsC4vz_OI5UC$W&i1<&*~ik2&gegCk{3q)^k-bkhX~@u3$Kg z2Xoawb{---kP`b$c-8<2^mw04=ITHW2CE1x)E<(9&vW?gE`m zH|btfSOG5f&!0c>Ft0}0g6{-I$;a7DLZb6`8#f`fc`ck{D6S{Rzj*Y>dbRpsBBW)N zd&kL51blL+zMqtC`<+rGP}uUE?e;=|5!|hir$H;d{q)%b|K*ekP4BGE3uZ}I#PneK z+gc0D%9KXPlm%{WIA^4%QyB3m&T^qs}LPO-lf3Vb>%J)q9=eK4g$iuw`tY;f>h z<;Sms3MP0UKL*$d&ZAG8&#M)GbK0+;?xyk565zYX09 zpM2Puy(pggTBQXv?2L}*@+E(R;4$y%)UCF@4EA3mBUH?q4|wpy6+x+UUJ`IMJs*Uv z)l^hQ$d%^{pQZNvj0K70n90-BDgo1$(1?h(##aeJDQhQ-LcARI>uOQFQ~J9=K(fS4 zeKn8VK!^w=XJHMpl?yYovV^LeyWkRH8?$(o z5EuglGa!A8!VUo6KJ}}1Zy%rFbXdlW-Ud>t+t-EV5Qt+hp4~*K^q-wB@DgvXtGVs4 zxmnNnvt`=fbiL*j&&`awsnl ziqwZZx&jA4Gkhs5`s4R6ew1OOYy03o!;aZm=*k+m0|Y-@i)Z9&6BHz+MMddmiNI;! z%-;eeK!p;*HM7kh@U(}S&dGVUydgeKXQ$k2es>vIsB@TliQG=N&NYcBf2&R&htoVd zdLDHdUz7Gg^L#sETW=I3R>gv#so>~~M(`Xpy+;>c*)k#C`d!d@70_RySz$Ed)csOW zAoK9pLR`1uFooVlB-%*bP=Gc|s9%lecrgiJSHKCzJC3ByQp~HF3E+g*`RvDgh_iPq zGI|}+ECpD%N-tJOWpRMU^M>;RC)}T~A@mb;9rvg;k9@N0`U5{Eq;nspHo!dzBGBZ( z9skU6czC$l*ZFYDD}qM3r!q=dLgE~pBeI5Og_m$OwO_L>L($|`Q0Z(a84>ogTl6IF zFNrLRlR=cS0mnb7-S~)c%=xtr+ypk_d+xmU?*2^gnstLUS3v>or2@q((iKkSoO}Oq z_*tsbQ&Y+I6!V*AykjAJH@*#49MUvPHX4*vVAyV7S1Yr4eA-T1I`(y6b{E8~Kw&iT ztFE)7q64xsT@j}QTnX@$09>6U6qsos0Sv8Ryg;l1t`0@3S^Ox)DT<@sr63`qD0b`A z(=zkP8su>vQihulTt$>CSgo-EE&$3)8Gk{JDH7f8SbT3e8c@Y;V?)3dlz==n*t4`B zvuuK+2Mx7)`s)+bm4$^nzrTM35%b#hRs+2jOh=fqlw>Uihv}c*K(59|G9K<9t$j7AS>hZJSY3y|b)w~i_bbe<(C z*o}#aLC)}=zZ&lqn4lm|JYKu1y#5AIn(x~2k1on7D4c^0il8s=0|&%@!fw|srPZ8hMB5&?V@hO?si;J8EBt60(qqb+u|*gG^Boj1OZ|9id$xmZl5nCj zbN(I8R_O%db$A)gFpu>Y&ZB_>m0d4{RT1XYCX>4{Zm~Gvgl;V-u`%YfMJDGIv55epca@aJRu(o9?ja(`2 zO!X2K>>);uL8q(lprpR z#^0$PRf?_Q{beR9m~RF&Tr^rtq}?=0$;rJmkAK{+d1M++BYUJ~L;)I*DUon(YuJz5 zLU`W8C(=vLJOy^AxwA8zG7L8v?8t#hM7M4bz_D*m4504k2>M8xv*_ptw&9WO6i3+v z=2g;UJJHM1vdIthj7;S@Def5-4)5z8COs80?e& zMu^3eUj+hmmSBpk{t>5Z{`FH*oV(Y6t_H%QzHe1;Kd<}TQNT&fog%5VuRhRt$c-q1 zTZxv|6ub-Ytd<@Y!?6L~t0QI;hz|gGi6nAu1F^^&nxAYm7Qsc(jJbp}4@O^2r`FTdvQ1~+I! z?1a+M&ev(`V+NrN=L z;18Gk@w$C2b?tSgJW}LAEwbAAlHNQ}w<+REAq9@WgGzre%f=@N+LG$k2wMcALM*7= zm{Jf|3a*rj^gc-U!-o9P`*r?ZA7z^yZ4GK`nIe8|* zmwe-MSdPh!^ojeFB0uEW`cVgP^CiKyF$13SVxpJsEO_4MyvQBiy~oS)%F=DjugYtt z-^Jht18~;E?KsWt!Diiuw_oSwL2Xe?|B$M<;+L{^0ZuZ8sod#k?O6;$<^e{O&bEsZ z1n%u#D1+0}ESi-_m#(CwM6tub<-Z(CkN@0iRv4MJ;VCjoN*mEG7&SU|NqaZ(Yy?7N zF^7v@8j@ww;XiaK)9c?QmlGqBxDKnLEowVqr$&7hEAZ#srlU_BSpDyOk3b)`w-ra+ zGTp_Gep;oY{Vc70fwy>1H{S_WUA_3;)AK4$O0F~+Nuad6sESH-#k?4-@w{ysj& zMnJy+oouatm2IgXx7VKc%-k>IZ8zURr zL6+v(ay+*aI24+gu4;}-hgCi2AHM&F2Fdzyximv_-=5n*tXOjjK6Pd$H9`mFQ{DBJiu^A1yIryDveMFzO%blH zHC+2VWMTtru!j&3d~6K6{;s=lL}UAgW6zJYE0Xb5F^@|pZMgg{L{AItQOw{ivb>+t z&rMC$2bw;`xE^X#6~Ae8Wr2)_@slG^VDHo~Z1H@V(00AeOZ4OkfiRr;o@~$&dL2V; zEuu06_t0LhF~m?z0nbdAnaULl^gA9H8E|rN0G2ajbDkf0gAl>iOzx#(`Crv{zl8_KcCoPLjzQd85=fPug_@FZf`+1Ww4j!XP$$pP)fV6%|Y zYbY>#?Oq%NK_(8Nu@NpR5bk%!(`WBrXy6bIkUC1mm|Xnyxq#x4k&zJ+%XM_Bx`A4I z2tyz!z8p$yI^6GJzC0@R*_u_Tf-TgW%-s*3xo~MWTspzjRsf0{aVoz0LHxMgeDQmO zYBv&M3g(K`8?Wd^yI*ilMvq24^}1#ki6bRG1LShrPzX=AhAY{7V_94ra()LmWTlu=MnT5*2I_QuReIHO8V|CT{E z9?tl=te$qeA;;r$c$u|W&dqBPgk+_$M zoI(olzC;=Uo&_?mu?w(m&4(%;Vb5GC*k+>E^Ep3)+M9p7M)Yq+3~Cf8*e~}Jn-4GO zy6Yo|__;tjuUT`j+^fPrXq?{B)&`Y(AoC$jW>;y0r@XW#*?? z>DF_?=1EK%X{>}TnuUnj3~Czq=E7@Aq;+ElY^!}12xe=Bc(7*7h)U`@N-V!~F{+xS zZto{Na%(k!^N0X0<7XbE8qE*)F7dzjD0m$jnynPOROz}i^Y~cB%)})Bz$1H_Fss3; zz-$pR{9xx^*F!)yTAoG;+n0+h?mR2Dx*{%NVzQL4k_#|X!tR5v66yB1y(QiKnUD0c zDctP8c#!=cr&tc3c0D3xNj-gx_&{J$^QVj&PL`8}Pbd1D_Tx*xJCEx&Lqa042clC% zVvh)71^M}dG6t{w|Dy%iI9jjxzMV_AgezvPupsg zg{Pl}xwtR@4gjPL5ec9EWNrm)Z$MjjTI&$d3B=zE2!q;yMzY|_Dkwl7+bQ%dr{yJE ziWQ}Qy@I5oXk67-HU^!cLr(!@ix`v;%d!7f5w(S9aU&~)aOTsUbtgyNRZ14;Z3n26 zyr=-={G9s~%{FS|H+t)Jo46}F4_5xrcDVH5u5*?MO>>Y!Ui`pm#_j&amNRXe=o)UJ zw%(8g$$`)LxDU~Dn$Qt&lU;{gjS;T>@HvOtvlq=U8AMtde|YjUbgkAofm@6j04_VI zOLgwoV!BkvZ=VCbk2^MgKGNvm!EEuG-P#ERYILt}sbZtQ>h<^Yi71KqQf`9E>`x*o2a?p*Vx)-=U2oXJ==?uIuy& zkRj?LP>vuh^4^R9NeVp}F}{sv!Gaq>$jj!2!V||BH9yK8BaZjz%RlDR$mHktGy(+y z93R@!W(p%17CPUsH8ogmO0(gITVlwls0{mZ3l0Tt=Wp-1!R!bnrD%_3$mN(4dtkti zXVCfJ{FLv{=8-7?+kY%9cnZhH$7h$|yB@9%3QeoBEf17ljDP!<$3)KoCcHTayWIu5<8x5VGl>CxaOALWW5o>AwwLhuo$M+G(+DDpGVdra%QcAN!j!^0Tn_QE;y|5$#;_>OO?rho5B#-ppp9h~4jsg@?6|nND;?1*OKNx$ z?Swz}rdxB4KXkV2Ep(JRwL-4EUsuQ1sHYDfqNUJ-3>4?r0O`BCk$6LR9bJK^%_>Q| zR|VKT{Z{64Y2-UUdnf_W&gk#--~15!!({RlDzLqrWLx0WVi53! z{#ql{8tX!M-pjsPW6*&B7ooBl3$B3M?wlHP33ROC!2plhD0=6DBbU_yvc#VFxVQ@7 z0tzDpTuL}@BFV}{kMV^P@weI1Sz--UPs=-%fb=;S@UjUQ@#s!&P35;Eq;u=P}D0GN@e(+&@vDl=EWdOPz4 z@BQ+LqVbI&w&fDtdQfdZVOH&au$+}e37D71RWSKj=}mU+AaeDBtoCbfulLcY2IAU7 zZA41z$3aCdtt@~&-J8VTvEzL8qDJwpgvKtznZ z1E{lHRb&x?fCwKBhytcG&t72)WQf%mgS#D!mqOgQPm^Rr!XqM5xojqZZGoJRayJ%0 z4K(iWq$WM@EUc_zPe>_TotyWD=lNu?G$iCJyz|s~1J>8xM9?^aLTGc{b<$FowNxJ*IJNNij>%2Drk1V|XWwDA#QDo9^`>d~?VEz#d4Az_{eUs?s>^9qkdHmGPdo7gn0 zEG-pU6Z)*&JedQ8;{BWjjrW!qm{L@WRYQ zNHPUn$#`IN(@s*6UX1IJ=62mcqv%MI@_gbep_|AYa|lNG*~_Xvkr^t+{2~^UN`^ow z6moj*eCgCgE~T-wAucI)GPEFphlOLVGwu?NN@I%vb?heqg$Pq%EmTI%w=T4nDlz$3Bzy=sK5~a)_<$|yF+Nhq~~B~PDI7vJY!UQyLcsO zRv%>L8cl9?&F9CQqwI&`?vE;LA5mr&;=y@od2>2i`T~*PK-N8be`sYCn(7*V{Rs7c zhsmx5ac<>lv!1Pg3Qs(6=@_Uc4es1J% zTx=ZI_wj~X8uAWT$fWYkn;N1fLJdFiVX9 zog>qg1QY@se4kx^l1}#hf(h%f!0jbOEr&N>K!b($dF7yMD!XBg47kv>^MZy77!-wo zMDGYwupa=vR||Je)}(^>x=PxwFElSdz3(!P$&XzbFVbY6%LQ|In4Sw2=o!#STY?8B zHAO|6T{LN^k@?3OCEC^UhTyp`n?E`34s&H^OlbFK5Fpp|6C)rOy_v{p)qqG7O_($j zI!Ky1kbCWZakAnW>6N`yvfLa;$%`U-MmA4RQa}(CR$}$`8d6TtEsK;^Fc)wB*|=i^ zxF{6FWidKfLp~Lt{eZM0z$b3h4G^CWp<`CfqiGWI4MC$|CMW(pE55t67)jT_Y6!r_ z!iwp%^G&mCceGMf=k(r?XEYlnCc}o9L-O9_S(h?wnORgG#}j6!0?Y>|AYpuC7pH0}5LgJ;d|0 z&dCDEd=^~7#UY<=2)S@&K?RrsxNKTl>9P0bZ1W``*tPKCYZN`bi-ThZwupX@0Fsye z3^;e|4v>6lhq9X;5 zzX7`gTqFa#enHG5uqg*{3F@#TrWbDD6!5FE)Ejn?E$l8$OUr^$%h8P^ z(smkUl-z%W&@2vTPl7Rukcw+|DjjDyf=~h!d~}+@!^4AeF*{Ljo&7eOyjC!$n0PGj z$(XjC6cyX3H`{1@rg2UePT3_D<`O-f{wtvB#U&&PZJ#6+?k6CULvL!!s3oQY1TS7E zy9s$81dfplmB^0a$;mo6-H>lHkF%8rExuib+>`-JYh}im=mGS1b&!Ut zY6MuSWZ}g>xPXB9n^1S}M<_EfuLBGjC4K`W0!Qi4t?pZ8bqUL-V8p)d^Jy315!3+*G&j=;Ix3leB%(G{&JYt_W93Q zk_#RGPoxwwMtk7V-h(Z9SuM$qAVQOwK=vgntfHT@gxF$sFkm#CfV+SZ^XM_`I;{;n zk4#j9&x4V_)evo}EU5o2i&C~#3mk;^{a=bGH9IfwV!#t6(UpmL5vdXfX>Z}@03!~3 z=&-lzX6}Jy1Qy}rr+Sv$;4410NV2!yR{K}<1wZ|BK}I7I3M5(GLiJ(xt=UI- zS`~3?{>uC#p+RDKf*0QIyfFq=^za~?aYjg_T2_AuAv8UAVdQ8&gid7eT^xg6k~qu< z502Ipd^|u%_oCSca`f*ZMDTqB*Z)X>?xwSXI?>l^?&oP`8K0G;Zw3PSldQg=;S^qG+Ey~5n?P|l;>z?FMNRT7BVIjvJK|O z#a$`zmGZ53MT)&$%>I6$?#jIze-%^WbhsJL54@k4!diz#c3R)0D5pd6t>T&eugMxn zlXD0usBf_1UHDE|X?QHWb}ab&C;0z+wEt5Z_#ZtV;4ap2-~`NSBn~xYgE0qw5OKCR z`t_?6&Gt9`DfgURUAbWv5Wg$%d?o!d_p+sk+Gw@R5I|j?kU2FuOSdr#E~Rb2V-b=6 ze%fGsm$=q>NlD45D--H4d*rV213;o!r7w7NY8{q9oK#p)U}5DMle$9=MX{eqs)CSoC|d@w)N)AcJM%3GGt5&$5L)b4hTUBE zqH!PK;BbGw4@(`Ua|w#r#os?w!|TA&2u2SbK+=hj06bm1hQxwpTJ8>E4l+QfTXV)L z!$`EukZ?2dCuGG){l^g65u`VHved(`&qgAUSNQe5>3mX8fG5qJ`JbwIG zO>K17b_gA*g{QEn2z=X?J9mB)&x88Wz%56T{qD#A98o+xJWz6Ifm3oz6bOj5i^o=1 z&5Kd+v@80MSOiqEl7gT95jp?SN;8t_;1k??0s<2Wi69UyBC)7~pabApEe+Nx#B+bk z5rOBH)j|w*^Ob=RtFE4aiW@EtP}D22rb1Y$Kfg)w#?>qS&tkw)b^{fumFvOVkl;42 z{}Oupa{XUg#=KkqLmA8qzx&@~0Qv73{PWiVWQ|L>_kwTz{|l%8$wgfQAr`~S`txJB zH2+J;{lEV5{cn}c!O021;Qu3OM%+68FU|6QUKkwdzn{mSe|V1uf?|X~9m?(m22Jv7 zK$|)8rTn*&RTh9-kO#tT9Pk*BX=q#dA5`P~6S&qvtBJ>gA0DlOIH4jte9L2t%{l1N@sn87zmcX{BM1*3PJ}`qf?@U;EXcW;Pw3ZI@;$gm&oqH zS-yXlP8TlcT5?EmI2#<@=$j!*4}<^fEm?Mps|AEftNH+^fUWe&Kyhf%eo-l!*YEE$ z$#v&-HPVNT0p1MUU4T+-eNyl@+E#Ouzn>RkMaKgWH}=1Wd25z4;!8DO=ATniQg%Ml z)txri{nt%P`q>^D*b(8OtE-m&i*2>lzxL@Cp1<&Cm6Lz}X7e1;gy0(-m6%v<+=Yert;!~Ocx?ofXo!dJ-lM;f z>%)KPxhwz8(=vGX=O_O@3v?{}&v*Nu_J!9F3jclst_Ez{meI8%5L(i1m?ZRk1>VP4 zIr1|uIR$~pA=!MC0SoS}=qr~dO+5{Ib_&6{IMq{(%oaTJfZ(!qQ3qMS?lcXt4$8B^ zYI91OWQe{pK^^TkLqOxrrR0=Yt!zyCJgFI{vY1@^;k?AoW%i%|;`g#hA>QgG1sxq7 z-u#)VOAYtx^RD16ele*e+sn0y(@#N%hkA0>fzj5Rtv?qfT0oTkvE)fx9quY*!XvKeE^8l7q9}7)a-5W=e>8(NNyJHy(|PiXy!RsO1^?HI;x-OErnE!xyUF zs{1ixqq-@2r5a}M^eqAmSZK8w`g-c>>P9lzQnL}AC4cU^H)jmkGLV6aFvE!)_rNXV zQ|9r~ZQ5P3{hatoX}mqUV@BiT-ul)$KL0$*4lc9G_=-~EhEn1-$V%qv(YjkmQ_L*6 z)wQ&=c4$)M%|Is#aEpvgC~BvXr{`&9KRXgWY{ZHG4tVCe=)QwEL`2goPx0Id^&;b} zEe>ZGlyES&z5RrqRLOo$+*e7ao!^R`(SG>Mn@jcc6y1F9gUYrHCV{+8cK?xw7VFkW z7tHyhHXgCz*biUeI{r!h0>l*__)2vevr&OsI1pM~yBFf+W!8)9>p?nGURWqY+&Vs? z5@}mKwevGlbm?5PSlxMoM1mRCneEB`w`LNV@F;*pXn+eQ0b1;mxY@;GU+|JsSR`Qpl*P7;ED_p+rxW|+8<7BjHL*P5zfNg=2XK8FIx*B(oXZa(Kh+==jUD8~=4y?d_2mCWcxU5&f=6z_I) zc+^60A z9>$V=&z6F^KOYvSwAAialI3`~1qMi^m4yo~1e~ihp)_^Fc-v)s=ciVFiUf|RaZ_L> z`DM=|XvBM1z)CrUSh`P74Ad4dscg)DaoD;y3_W?3&1+jHd!!WJkR>HPoeC4v4(82@ z)UA}2W7f}NC6XHFW80RpzhdgHI?-455qcTf8G4ugNsu9be4Pj3^gfAQcxd^THcgcn zqYR_3RkV$*&t6Axb$od$T0J`U^YFTtVB+tj20@`_;gPLH4E#gB^Xz^!d?)0_$2h3# zB2?F}!IuyHeEVpH*X16kgjqz9n1nrA6+SwaY1Fuq(q_!^7S*(T(2(_MF>+|z;?J9W z{GNRLjk>z~{WRBXBl{+n?94ehx%sCi8}?m_ml5HXbDy^H?8Du8Z60=2QJy5;kB`HRkHU<9gZqHUCR$^9n>ccOWurFk8ON#|wLfP!E`imN z2Ne(IodIY@aTB<(tuF2GT+_)T)>lMka@IY0DWv~M9OXJwZc(dnTd7Pf1)wl3V9&fHus_0yt!qeddkk2AzsE$KM!-6b%AP6rBECGi)p zaQ-Zz?^jdDJ`?Yf9U7|-D2b3(ho6<_Tutn8<`cuI!!-bfbp>W+N3Stkz9ys1*OMM` zlNs^JpMUD8*Ll&g?S`rs41>@XS&#<`h_7G2hGBxN%#6^23S@^Zwx%5}Ku%Tcdi z-_c!V@I$Z*JW#BT{D_jMWX(ijjF`mKBqWZciTQKR<6bGndTM;TZ;=uLC7u`e(9q`E z8oIlzOl5BO^S7zdZ2lbQmB)eRx<6$j?GZTh^?QR9h_fV-F4C9OUmzNBiPW@F26{{6nooF!Rqe`eWKL)8Clqr~p{=qTUDx-Qc=(hY_8RFWe+VshK2h0)xVD6Hp5Hvkr2}+7{ zGQkfgzWy{}AEp4KRzKGG|B+~&ty}1#vyA4W(~Uj^OBs*m5pX@$)kT11px{XC$yN(g zQG^ShW}uM7M4OeK-U>D z5E)hD=}!9*m-dsO2FQmD1oqhux$=5yy`Ao5EUDsBunMiO>}9-WG=0}u4KRpQVmq^y z2X*CRM^{1cw zZ^8tOJ0ivxJqKW8&LU=d3iLEUqmYwSFk!!WXB?huOO$(DeRUvU+7=`2`S%sn0?^qO zh;r8~s0QSrOf>s6LrxyV4YY5*%I-bU<^Hr;AX)pG6Im-uaFBfMV`8j(xjaq>N0H6?^ZMxy5n~G5G0?c1 z^{ZEx!@dPI;ZIOa0g!C!ih*Ph)79CjNTdp_P4hJ8FPbYn*6%OQa6b|eyM6tt8kt?= zk-DYjI;g}|b!zksfxv;%$TfA`t$si77Pn(->8XDfL4KM8Hc2H4^ z^XevU6Pd8A3Z@blj*d*OH@kg=_*_`kr>QZ{+4)d9_SLwjMa)v#wq&MeaYuyJ=ZrG#OPZ+bk;~Vuj)-h94^Hfvo@EyN>okbjKW6Zk%Kfv4g z3r`cgD1-2yk?{j`uefbJsfMcn(0qylWCJ?30aolbRFyfpWdJ6Aw5q5aAT?TUi3Hd|arr-d{hWp)ut= z*K#Qk8)w|p7XdrQ!O$p!Q7BEAaWpl?u-?{LT{Z6HYf{3n*`z|6rLcQJ{JC<=Qvfx6 zk0Fc!lJP4kmPUbC$g2k8Rcire4pVVCpywG;&`Js-9B4vVT3IO^p02rt#X?6X0^Q$l zL_m^JVFFq$cyr^ROz8r7`-z;ui!&bX_itC4gj{_mvyVN+IEdpQ!HgmcqC=!gXAYy^M;ps znxRGX#L%eMafSLppHy5&go{FThaCt0rVGqh{VA(9mBhYZI=%MpZ2XXb-|x}x<^szRtn{o3SAOj!V9;sFr&ywptY0@+gq`^w z4XQF1>;StP_MpPw-*@<(M?O0k_2b76peunU$PI$#F@W*2s;bmC)}da1T~t(*LaE2JILUuK};ar;bmapy;Z%bV4KAqib*(K*J&Qd8PjT2brtMMd2Aq@`=p%V+ZEq2~5mbpev7t|UZ74;rP*I{^NVY#towR~zTkZgY= zCp9|33V1g_b|$f3?PW1l@$=lU^X&6o zMI&9JYW^D~cmVjdt0^fB0^Dn4Xy}w4iwq4Zg98Kaot1F!YQ99Y(WX*v0W7) zihu!MAk$!4yoD4@*haRlN@tPovNNNrrk3rjG%y1#v4CGdS6QRMr>iF(ou;zT&<~P9 zXfCK^f-$(2#%2=CdU18;N|vtG{Zk7#*r9vhJ|?WB3A=wxpmT}zctY^PK`&n7 z`~;U18UifL&1*n;XTvoGh%F?O?(V#v?np>)0RkyVmOcj+%%|!Rn=(I4Na6KEfHR(c z-iiikIViREQ+U08?LthbK)mJ$*Ap3}wCgwo$!6A_+y#mCWy4Me=BpC*g}jfg>&GhR z*S(rr(nZns`%T&7rs(Tx9ivzXtjCZzu96@Qk3SOO#iSrE{e!5Ov;1g3Kb8t<%h@3xCUMFC+Dv?MTS zSw!Szn<12+8*6KWbxa0^Fh_=y4BAyUv{>9hp1!iQv?jv;L*iU@93m_96|oxHtq<2H z7i4BG1mfsLCBYU9h7l%nK;f1h#Y9IxtJDIk6#-%l4R&PeBv4!H0!L8p$Tqu4^I6+0 z*kU+?+xF{er(n5}(N`gTQoc!L`-ZjJ6}nmP>YS$38{G4}DT2B3m0Od}pC(3Q6P6|A zt4^=gJwb_0WRx3UI~*O2bw6jnEgJ|aG=QAGtceK;Rp86vY!(b&X4|vy!e6tzT4c@u z(Stjp+2#w}Tp;w}@j*v=AM)de;i%l`%*@5vK|jotv(&vy?WDcEm8|5tE1_e^SDW0Qp&*Ox_!O(Olr$aBhJsQ!r?lmu#i>>{3Q@P9+sKl z^(30`q%<9E?n@cn*=$w|!KtihN99D7GbRPhj`3k2g_*#C||#g{f7 zPeNxQ8D6Te&kIq}YpxyuH#8P|cXuv?KQ zL-M_wB*;Jid!u~c!HA!aNq4nAzxK2(5t`B3j=L5$w5N{F4rsuyPpg*PYN`9{w(acx zgEj8yxN@VF!0Oo&`}(!gs~0yBSBv`N$DhFa!1#S`t{DiKv=aU89sU{|F>02HrD#3@ zCzJb-UF>U9AW-~;my9ivAUXaDohoR}(2)Z>e{#(K_6oFoNkfZeUmrqX1qT{vu}tSD zVAoRco^-pta)RBInuDvRNZqKntcKgW`Sjv;H+Ce*~CJhCoTR zd_&|WQ-1w&!-G;Luc!!MXIV)Q-&Em8m8t-b*k(9bMU2!E5Sz4Cb9upw@uH50cfynl z&vK*g#qV?M z<}TSaI}2f=dVFu1vW>OtiOI;IEZ(?UAqJo)Yg}}6dLJr}_wNdr5L8DPR=xXdb6<`n zxpxx#8qynbpcV@IObi4d_?=(BW&zQ|av!MbqxCRg>rc+yrBYI6a&oq3 z7 z@P+`XMNKY^*mG)DHZru_$))c6Vy;S~kC4B;m(Bix-A>(y>W1T-quQQCGpbxM!LznN zeizl|vUBj08L#6o&_P6g)O?D!Pe7bf75|8yh=^$2iZl{IYqk6JnyOrbqc*AjQtDCD z69C%~j9jpjN2Beq%`jLK1)#&2~RDXG6O32Y$=c78J zCEC7xkyMkZwyv%VydSk3&I`wxiP?D!FQ7i#9O4cQIZI5snv&q2Zh zD!CXQjef^m{gIbX2gjE2p4q&4X=%ylqv2uP_2W?6uGh}W(P#hO!SS|@*HPtU@b4;x zz<)egmjO#ycWnTc2m<#Sm8eN1_i|#-dApmjv$ht}Qc4T1S*rgiaX%2qRt5=T{e=}x z)uexYw>9|oS(`2TgkKWz$TqNwV8Fx+|YeDNowepWDX^ zPcb#tALf`?Bwh`4k@0&TP*p1}DPqX~apBkNrPC(Ht}5f{@yifmwo$&sdp*RO7Y$u9 z0{G!gzb!fT1>Wv_WmiX~xu*AMEYJ10a%t(wcYDv@VPl7#Gn=hJr$T&uENLFTJ6`r) z!f~^9)LvY1E!swgZuaKP0V1>k`^k!5OEREYyt`Z4E-)~g{Nck8iIDxO<`ityhH z>~0tlY`*Ank>2nozSlG}8~{vEt+~-NFo;4Euk6&CQwEK{;;kj_^t02A&17w}OB6MA z>`G4!txI1a4vt;_^OTjoaCdroq=I~lj6%oth?F&~kMA1<_=NO+AM+E5FQ8qV>_;>A zDc@e2O}?Fm)^?!I0PHtwd_iYt=eKW9U1I&(sv#MzQUSuxBxvmg2&bXPr#u;z!2(($ zt#g585CUEAbQ8r%3I8zlh-u>R(dW_)#hjNn3^^udyvnl+Jf1S)1WH`LIBkYmmq8y= z?zf0M&c1_$9c5-gcd@T(VVQQf~Y(RVe0 za>!MU_I^dLvk^DA1MS`*k2ct8Uc8?uHeub@hrYF=Z!uynYfW?GMM;^%>e4Ltb>v%e z;!_$;%BouUT`uBCC|Bd@ke*V)DTNJaZFVKp45WbY>OXvu1+N|#(d;`d+F8nL(3yt# zZK>eM334R+@BSC|--G%+O$fn4?decPhS=qC{L58yrC^S^x%BO8H|r<*ZY6}y%&g5e zJk3q}7#@jtyxG;@Zgtgzdd^1?hM={TLwpDhzExH3+xAFkqq7qw=;TeWX_ey@B;Tdr zGmo@)?Mbc}|kEbkrDr;-;1VPq1r&EJm zz8T%fd(V<0t^a&$r|;-k{$t8r1{I%kZ4I?0%*g)U&bVn$JL=bJa|(an?f{Tu6BAPS zY)RITevpyXT+N!LV`R(@Dgku{+(=+F#o`J=@A_#6_i zq&g~whCe_D_W&DPe3CByb&;^sA&}5d`y3n}U#F%S1n7q?=}lMu+^n} z;7Nf7aCBs!!n?viMIKE%7T&*7o`T|=rkJk^HbTmUqgg2c$9n#>t<~vsQJ%|`mX-$9 zX@78=;gGGhHKib4qh7y@GU(LG-VvU(VwglmZpfLQ(wA~*7Q0ljU!5Bni-7qD*mud~ zrO}^!ymN+3r-t-Fvc01NR7tBzYU%0eP&L7Ze8&H97ysi^FHny||6o*AmvKQ!iID3y z;gl3?fajo(S4b6@n4N{$4Ie*(5?KH7<115Aes;G}Q0l?A0o3>slP>k=0QDKCfbW6z z3dnpIWE3z?$0hdL+fhAIwvNW_NvVHDwdaIX&)A}&-G$11yYXf#(o12?4=M1?6qc2B zWo1LgYyg?s*M0|iKV5wHLPzA3HCL62zq^!-%v6m%1yO03S2wH~d?;I4h+{uGKF-a~ z9t-=*gA_<}>vE`{0jL$1uxE6tVR^o{K3eGBfO6A5MlAyv#%$U2Bcp1Yk zP?VPRvFQT2TXoLy?OW}N{{hkfXA_GoPS z@IjFQ8|->OCjqts0CAM1;D5gbv!1~-%sqdGS?x1_}O`SYmhBBTV`c!DWSq+c}Q z;s<*jB!#2v&{7{99DKbR2qeJJ!*;8zAt8@XNB}o#kLudmq#`UZ9oaO61#Egmei!<7 z?^I4MI@DhLq9Oc*BvjD!OotN7cKU6NX{B;*H4*=-M%E7je_mm)ZT0xbh^)N)^71k@ zHMMm15C~eqdfWz&%x%bl9mNqudd?}mMU>4Z~V~3^>CS;lVsp65(j$K!Z)NjK6 z)lpJAQv9I$G>XLj)aD_6Wq!V9E8Kb9x8Tk*kN_nNT;wImPZ{K0RPt4!VNk0$VQX^^ zzcUy5Sh3)o?HnH;b8&M+x5UR}5Sz4chS#H^q5{BUYHS?!Fwl0TKP}gpq3T{hAP^LZ zX=xlaZ0Qj+nni?7ghFNX&!$VxNck$OkJ5NCVIl8!w;;qe1{M73SFc|E z3MD5e=h-eKybG6&cxJRU=1pW|*r$UJ_U^))S&StodNQ>8PW~bR9Ue6nm0DFp*N}Xv zpfz0W``e;H{GcFHEmfXG{DcDko1RU-?WoEId`Ao8Msr!CI2ow&RIm6(uDhb#zMXzV z_Yy3D*1Bu~oF^tG&N(nZt#ii;ZG(1nifo1=Pjm0K2IKw;a>^G_kE%FX7Pt z;z*GnU(HdaTVTokrqm;ekQv4(MZ%f_Zo`^ zEN08lBUeGlvmq`2(%wF#T^B1tiIrU+T{UPCIHdc;r9Nfri?<}0T2v$}=ZA%b zH8>%Mi?a&|$XdOiRfM3;0{CY&L5DXN#zc(xlPA&Q=H|31kGB(2QhMz%Oaxv;YZZ%+ zF1AZj#z1NU+2N1{S#|0H7CVfv{`L)b>sPe)p&q1P?M1o-6!-UQboxT>U9(=f%A$`Q zx)2-dZ(_ol%uPioEVStGF$J^bJ7U|)pb{AcEeJ&=O{irl(ynG2e&lHjpUJKdf`p^1 z801FDy+upC$hA81u6qNG0_4%FL+%XNDAR4Cc8OEuS9c#mQU)GRS>Qo_Wz+7)uI8aR zZp7)+q|VUJoP>NWAQe59xf?f}_|}$6E3_DEQ=E(#J@p^lzfaj5toJ~cJX*&^J_l3s z)Ge#Lx)Y2|ebek~bqK~f24Bc=@9dTWH9Gut_{lh=(VIPw8Vy%*TMy_~tqoiLMco z7pu$I!X`O0)n@@z*{9!x4G-QB{$ltry{GQ$?H_mq1ew*L<;@J>>!3{-Ad**jFGLKo zD8irIldfe@fz{n9E0Lzea^SyIRL+kxep1zQfI)@HFf`~!9UG$88@)iR&i#YD?6x}X z{jWGlaCNVJy_X_SGx1BlK6>U>?PzW9Wh3)#!;f!@0@85;YkTXIml=$mQ{KFJ?=3uJ zkUb(XeB4d9-d0JJj(I2D))%L_?;GFgV_Jvg7%VZa$vc5Hbslc1SFU&kjIQ%In({Ep zRh2Q+6<7v%nRp%ZullE-yMUU;0 zm^!$uSXGMD>8BO4hSv@~1RJS*p2<-U|7eb`CAAAWTfc>lPVMul%k#E93L4r`QNJ#> zyS^ocRV+v`nu#wBH>aEqF9KU$9>B65E;>t;50RjMykDl|S4zX$;$AlbqjiI$l34;(=4SjSHjI zvYt7x*K2++0w^AgV?C%GW1jkI&piP)mYjR&eZ6OJPsE(7=3;;SF*)BVrqnn3{2AQ+ z^>05&5evW|w)x^eS^$v~P1>@%l-g3I0pwFUb|y0ygko6^vUBP5|<+~v9STq#0h+y(Le>aHx>_ zXNikD5)_EMy!7z*ZzrKsqQg&$FPf8fCls&RormrHz_|SnRw%09d_i948Jrp-oGFt6| zWj|4&y}aN%T^^e-6V1-;k)y^M$X2#!c!1p^@y<@YR39fX`QF8N^YO1u*8y(Plb@!a z%|sc8aJP}>6o8%GhFQbFvU729m8J9?)jA1B!}OcekX2&xmw4|@nM8-5f9EWIQcsNB zagM$E{E?G6X|_<5B9Zf_kbloow`5|H+;Qqmep?rs z0c&NIh3!-{J{CUi11e&YpM#+~NGym7c|)9;>(EUls>ktr6PwWnp7cwapdf&=3 z-=xA06%3lAc$0o|_3G7CB%T8SqSp>QgkOUNuM_nL;e882KN9UYBdb2}0zkqyJD6Ck z40_xl0s*@&CwDSWOjUQJQ8=0?BsNoT7G$iR7C_d}S#Lt;!56)Pxh43i&qzftq^pXsEQ*LPr?K0sPnXqPGu>|dd#352-PgaI`~&0X{$|Na#T zad8CC50h%g1I0CEYJb9G^1Bn?G~r6_iYjaCPgZ{nN9MPj z!oxDpU`*U^y05?5^|O*-3|= z6+UrlNXTvVcFAw@*XJhxY>4(H2SL~Ln0n=WC-CcmT1(je2ME7SSh?X7riWbjJ2XMY z_jld?J^@NFHMPKPMAwPVSp09)tRAAfWaN?ZvhQV`@zBs#zzhDyRkD+4 z@Z$=hD5j`jXtjixSQPTf?OqoqBpE5_g8l8v{Jo~A1>Q!Y9e}K-ISEN79xGhtE+Ph3uD{98*Eo-IVxgCw$9(U zc@r0vt7`a44L$_p_ zkZd}#rKKg=uE`zR!NHPJQt4YTouX39 zJ3gtDoQvxinx%!@_ZMGgq06WM%La~;B2%SJzv*m%TZO3r5mivvfa{#mZNhNNUC zq1jBCi45G}HlSRH%I@K|< zlo*4@z;CbcvY(VaFQMb(`wd#5;*yf4-_}Un)Ivh3XKOiIJtY~0KgYK~pHsn@*aL8& zMY5NFdwaV%KRtcuHZeHU0K(&BXl`zw7E|lA z3}DMX=Sod!M)%>jE@WD$YpYIAPocCn=VxY)blH)kzBh3=5F(u&;~r@&$_1dSm1+HS zAE7*1Y}XqS^i&HLc26d>{?0{>cF47hxXmlIlHa~v6$=!39Msx4G*qM92b9b3@Nl{5 zu`GpvfB-9Nbd{%vM}^i_QBt^grgV13J*lTyXG5LPxauY3qi)=f(RP3qlcsdY#+#Z( zdSdkC1(U9ch0a5>p)1t7Hzxb~`*H3tqb`ZPc+bhr-M@$C!Nk|k0f2xLACV0(&qGSV zM;?M(X_&ywLIZAv9QIvJ#jM8(*EI2+$ThX!#Hvc7Q{J1TCZQ*?2rqhIJpKNjlp&?y zBy}3+$rp>{hP(SNlKu^x`^e1Uve;~zBNcK9G@1n!y2{ET1dB%GBxBj^v95B=jIs{Y z`r7*@WRWpc{a&=G`p?R9_pV`Hf=E>1{XoSlU(&zP(2X7|7$ z@hF6*sr@T>Heq-z5GWk|{0Xte%;z9^Hkt>#4oFUaHcOC9S8iA2k7bmOkS;k0! zyLveo+2nfmYp}54j`t7f;Vn1nkgwHw+_bPb2r?&ugRl2OYYe>JPB=U};!3uD>{r8r z`-@Mt04d?d5D^&6E`WyO4M|tlrL=-4d87MsF2maMQmx9@Rb6%umd)mil1kmLJovp} zbN>72YveQEfdNI+6>9&pRTFBqdP<&c-D`&$=Q^f+K)C)tY`t|df6BCQOgu%sjfPdh!M-eFdBJDr1`oe;o6#p7+odJX3vK+me@8mgn$#Tgk5 z?hHbN2rh)}OGg&8fo^cqOxu9HJpDKfB0AOu_9lwmbQl?{zkmN?%LAJQ7dN--0oye* zUOv9-#h=5K1Vu2Sl?1&31nGT;y$4OW4*Tr9Irn7ih6QWXyKpgb9X;k~v4m25WoH6> zd@b9oP?|f8dtF`k8LiCBXeV=wOO>NHFLK+&mNfM47bQ;!*`2BIeeZEbd!?m%N1OzBnf6|lg*BbY3%C@(ogfr zlHNZ!=zoXpU@Z2XQGy0^UjW9!wm>g}F zxjkejSN4^lF=n)Uc3XL1yZ;wmZmiu8jJkq)Y)-B(NcGdD1%EII8mH5X)Ma;d%`b3L z$#u1glMlpkDUkNsG%+&BsO_ESh>|s=YfXi-ER0*6eE5)~^9A zgTs4^#N}4baQ5H|KYyhv?f4k=V{l&*N_j(FC-o9C48Sw^cH5t`c1hP`IMaizl7wG6 z>@;72X=ByV)S27W*)+JmpMa@ScdR+NX^%&!*&Y;jOa$F9vDWjb1)|qh<&u?r&VoMA zSw743dFT@VsB`$hfF*do4~W(~98H!lr*w&Y=j}V-c#z+X6wPa3 zTmvIR-?=Bae}=MTtk@o2#sK+{#q_uJ!7i_h3ztJ>Jcr#t=q>Q6i3d>gr2aKE8{$Bv z&*mu*LBXVe$nM!8*npOgS$vd&DktUJH_f>gf1;yyIrVx}f|KVOGBU-iOY|@_fY6DL z39L3`0DU06d8nvTnuL1>&24YjzD9%f?Md%`_z6l%RDtr z7r6zOm1b>Lo3k)Bjn*9=KM!<pp7S1wtEDDw1#~W@JhvirGqLRa( z+)*y=5>%E7INUBft@!yBxkt;0m>+T9YfZXw3{v3H(NT~SUesTm)prG<-)mj54pCsU z-+pSfi_`E41VO*SkNUCQ#6uz?F;{=*{rs3|GmXX#<|6A?PiJ`IEha>DgYe_)XD z9;y!kK~J7~?TA@h z@(c~d9d^VXU^F)3%A0GUOdI_CP&=~*1^zZDrIAJ*xW3KS^gAB>?9N0-Y1E)5`XKR& zIvtD&fH%#JR4BATX^m2lX>jy;pKH$x$yccx1|Tmc$}MQlS(WzsjX$HO@AWT5XbnOf$9bp5<-X^1N+LkT^A;88UZNSrMe+9=g9rw23Vmofs!0!;#p=n!AsO(Flz|vS0j06*;hfP91cNu}@lci>EeCI6 zzX6uF02GT`>e4MSojHC10nS%vy}@o^8Z-R%$;pp+yG=MxIbEt&Z%t>o-NnGg_aDLk z+-+tz8)GsvXKzA*f+7kM1OyVcUp4)>E=WSu;f7XiJ9zDK{2}wyX(EU?X49>1G-M}6&Cok@HT#m^Hd(qw!4X2GG9i0>ao}$HE zYt8#K1mBA6JC6VQ^@+G1o!;%3|Ncxb(055OMa<33O-=J~o2pc=I3J|c)?UE4Q-SR* zGUus*Dr)mB=t*@KJh%wf7hyPrQfC<8;@Q}UU#MunFg7>G_nV`{H);kGSTmR4N-XyD z0XZl>-cso@R1O=tY}MMi9ye_b;KN((ay)w*oRQnWyTl1@4)~{SpPZ+rA_^6EC#-r0 zWMaUW8s-@A*E_*(vP{Fqc&6_z~{}jJ!eY4{ra!Mj~}lgNfRh2 z(@d@0pPOb^H{v7OuZPO;z0ZnC`}XbY`JAfaJ9KaaRC3q_Q^Eur=^==1IPdbiOmN~> zkd|&)+S{-_n@>Gl?st35bg@S;P+E!%q-k8b_g$Uqw8yTFiH*%++_XGjsW{;az=(Ny zG@n1;fCJ+D_W+wUW?9*ZmP&e`Z?nt&&%x-kmzJYthJh4oH#CHg2FFQ*_|`LbG880M zV%F5u1h#1gKoPjW{(H&px?13c3u-Xvx|RW51cscdLSj;il~K2mu4Bx4Us8f#o2iKX z;aEmnJzLK?*!Tv!DMZhjyNyd;spPgBpnP8eq$e*=IqUTcT8V6_ zuQ=?l+y%?D1uOauOif}6#?@fLU}4Id0Z*tFvNMq67-4Ai+b}TmaGo>6FMzLxQs4*F zabNuW^8V>Ou$_oFMtWh=JQWs82#GE+u}mfu*Xbz$Zb5P9VYQe+8GrfT&tY0^PAF<= zA+)rxD1j^DB4>IkU`s9SF%j%lT0N5YwHnTj zI%)l9`=((QLmC4s1D~`S7heV-mhb~UcgY|+QN5CO2Ws)VUdTVijh&sG%tslXEt?H} zOL0her-w1~kBnUTwNGXrQ19KlapT6Yk&S}FC?~(eD=H+a%lG06eZiU?>LCR_{QI{6 zjt+l{QXC~lzB{>7`o96gn91SDC_d1@?g&Qw%IcUcDtb{U5EVhWwjLAbhCs2+n|`2Q z%C0u^c#(P3r9%e7g@ph#vaDcomC9J|1e~f`vYeheKZmuKD^57R98sr zV5$G_c8HR}yq~1M#!}PAu6S4e1xgFw5dwKzj9vjcJ37Wv-oyPQyV|L0bHZL)ds&=t z?tRv$G&8{nl4t6a;kRlJy>RrB1Kn=B(1f`mNpV=cDuw^PC&+(B#07G%Mz&v1PWj}E znu3IS)XPl783;DQ<@hHj2k}%0BOX9Ucdi7w6wt%i#A_q%50GC4&K8vuA3sLVwR+vZ zwN_@@&i5>F!w0dw;$5Fa($ zl63ZiR}GkGDyXP*+LHYDoA-%We^FuH)4w0Ff&CJ>P@a=K|2bZsaqAz{tJCt$ox6`D zGC!r=gbiR@MInn2IKDiOpFANi_f5p64uW}hW8<4V`G0@i=n{zCo=##Ct-y6RkiZO` zVeH7Q4;%YscW+=@Cz?JmB-S8L&TvkrrCnq&__+)6?@dA}@%LIZTft*58kRU9I?>UU zV8mI;Q&>>24J8JT#f-b%-U$@Qmf$uT5^mQ7KSF)CRKK++;jv96D~Fxl7tdS3Gi$J^ zSXd;jRK>~*tGRNe81;v{^c@3P!{;U^YeTULlR#L>$iEj^XtO5Io#?i|{60(8v6H5} z>%tq;8_-o)iw-Qrm@?#{!C^IoU>4PI)E|GgRX1u#|JzUK?0Yo>aN{(gaUqe<4+w9+ zK0P)%HO=#x0h?M7_J?D}G-;U5QAKu+N&KVPxG`CMWUO)a+h$`94meE(;0J&u5>OB? zFV0}V=i}>326QnbABtK7sG>$T5JjVcNF@b|HAz<48^P-2?b>^Vcn0Ix2e6450MmzrgnHJX>^L!Ez zylDGEplsg8p^Y3LOmW&1ms8AqK|$esacYm`?Er>!JmyqHLD5Z+w?k)Msx`r*SoIIG zx@xEc+b3?g7U`^gXoHmVn5Q?8_RY8uKmlkeyCe+mBWP5RcGBl3y>5#YUK1zHbgpj_ zSlQX%*|h@BF$v(&^~MZ01<&2`E4qb)g9EIoU3<>nm!JsJ(a~uQB&M)~9EvN( zXU{%z8pHVf~T87*y^1Bk!$$NVz=U`^I)tAH%Dh5Wp`-l!$RLBUIAO+43fBq4P z6(GkK5)fFQs*UYIzQ%PX0O`o*8~{r$RSh~V2+09EygKmT?79zZ34o`TfZ+~VabTI) z9tP2UFepELf*5og6laOKUT`7uJ{EtInHm*IK60(60AmA$%gjaCv$DV{cPr zDcg&YsKR{!d?A8H0U)c|YM{{p=9MQ;2(nE`kC4fb0Ov6(EFXA@2O^i()|_TNaA9j~ z{SetW<-8}3=|kEpn+>OQOl&OD3vd8wB?1K|{mLh2Wa0?8sq-cZV#337SWfa%cis`) zqOMERK_CQR{zlgIcXzcaf-MXT17MyFCt+wc0E>{A!E0;FJQfD7#}RW=MLh7n!5*6G zv<)V!HY0-~cG?Ra;fQg&6@CS~G;WL)CkXCY2FVJES`5CZy0I z1o_JNI_xlz;FJDH-$vF9%n(7rwkre`y*j%`O@w-W{l}Xy#wci8uDiT(+Yt)Cj?NUG zV#Y}$o7YU@1@X8ICK%j7ggBU_p|>wrJska8{9q$9g#E=maczA)H$Oj-=@lDWCD55G zojUw0$ET*aSy}Nwnn--rJ9rMPM3`DcRRaf5B4ZDBYJGIFC;0em;De^Om@%r#1x(Oi zzoMkGklyu>dk@`%eyK9j4i4@OxFqjdf{YaG4>x^CkQsI46^)utwM0DOo^%Q9?t^@m z(GF?w2;Kq=@SK;6p}U0eXK5K3bA$-Z2XM#K==^`U$c zlk>iVfdR|S(A4xG4sZbm7|(nMz9q1nK@AO5Kv2;`I}LL@SlI)6-@yX#91P2l6Er{)|tgY#60`c=BuavyJ?Fzn*!tXKI5>dE6nXI)7O+Xgcv~Y;~ z|F{4FzwIEp4pgP|3yH9@+}%+IQnok0)s3$2*`uPNk?jR>`{~nt#RD4C<7c}DAbxbY zSIka{Gz%s#2LW4j%}vWA=u4WGf5L0_rSIa>?K}mtV2czG?GRHrzgG!l2%zp-X!X_K zChiLF{7gd9Tz{eV`JG3e`yj3#@&TB?5oscn@~G06#xcI)OlA zSFmzVbUii9l4XaAf}WmtF)$z?J(A@JQ9iCOo|T_Zakn>yHOCd%LDcENfD#zXaJI0R zC13zlH3483@_4NUytwwb3f`Lu`rZK46(+9zK7MR$Y^0|EbC9U6DBy zzVWwa1HF?hrCgTm{^@NCB}{L`+2IB>_JBF*2$gAl@3w#ex(D?*Si^!$g8osn_N%~F zolSXpc}V2_cTCr_Vl5A4_2_75pbl&z0FweUMo%L1ccIR0hfQC|h=olnNa6$nARP|= zxqs`1x5z-;ULrpF08Kr$p8x;5z&5JLR6F@Sf;{$3}-{2 z*&0{^eWzkr`DGvQ1k}jXSg6rn-^+U$xwuRjqTxAO9Z*v;Ge_(r9334wd+$~cU1Qmu zFn3u~fx-*&hnE4&^zBNUE^2953ST=!7iH9EVy!{4O|r4(jlcuBzN3FTD9X)z@J(qVeH z#bJ7Xk$Cy?CD7tj{`utgT>NKaG6O^HPA$?55ONJ-iP z02yR`+JzMm5g+q>V;v^YO`d3=ct^sI4)Q<-@umm<@0vGgei4q+(gTp_g3E5N>Ecq` zj(8_7zOlBJQcA^_CJo^j$O?&N()v-Q=nr@M^9)yXK(#QHPH`J6$7_}hCfUU~{WZiJ?LT&1S3@(MJtS+5E zt}@_}fJ<>W(pgCir4z+fCE%!Z}E zVWR}5-N4Sb#-)KJd?F&%YTFHPDi%iUPC#O`d+H8oYC~Uwyay0y&L{bB3?PY>%&uSv zuDZfC1$N}1&ownPe5QsK!t8BWJ}$DTt`P;7@9U0p0}P?fYNx990!pIrT2nNrozLRs z{adpI(!JQkMaL&<{m%B@ZS({o5&tEh|vlI_qtwyd7|?c2B2RU`HVNW6tF zRF6;2>|GxDt`N}Ku>hscE&%i~V(B1k2-Tm251}A=_Lk@LVf!IOn}A^~Y_8?w8wCD~ z;MP4axKv0FA4pRR)B%>2s*6KLlBwprr}v?7TN}-HgEB}Rq7-Ahg&c9=Z~;LrLWPHu zbE3ch&64v{z_wv^ANmVxp#A zA6Nld6B3fg;UVt%ff4T){}v21XEUnl_8Muyu&-gF->l`hVgQTDoM zAkM~Bft7)9udVHjIkUOMguTp`U4OLBS2uw?`yRRH(y#7dTNo~;*0sy~ef zFI#;EjAMUKOPw9Z>8VY%ovy*_^wv6A>v`d=!nq5R zj9acG=ogeY@DxZ=+Gq3IA)t`ACBI4-W@A?^AP|ycy%W?YR5$ z`n57v*kJMcF1B^Ke+fb_Tyd?W{=?zAy=3ox4~H}eEt;F(M@R2|zFmEGYGa~*TXa04 zTSTRtJRku72lgMk=?zvnHa`Mv>f4|C`ud=6@oIY2%M0^_`Fp_eLt;_@f4xhSj^8|G z7g6u>`6nrM04VONFSH#154HZX4|JQGlYgL+j?CSl3}1zHvUh(WFZZAGZ$nW<1`a}B zNke*T1NcDD@HA=NmgDga7w&(-vNj^U9Q7Q+Wny!p*!8G`Wz64w#ZP>Cmqh=i-p-q| zws&aKckzS`8>PiQvF6ddj7sp6dO&3eIJ(buxUL3dg!^BbnrbH>Oy6qWcb_yJYs<*x-rW4Zc~DG=lakw*^ag zET-o6trmiwvifNj+koiqqpP-Ki5CG*DqF@%K)U>WfyCSbZ*>w4hTgq%XS?xV6z^Yf zkq2EcQC%iwb2X-NCH+pJ0BqR1$8!sB1NP&%IM}a9wW5PMKbM(^0P8S^sl~$MxT)S& zK_L+2nL!CON}@{|S-Yil=s?&^OZvyL*7cH%uBVxi;@?ln31`6kJYoQ}P|M3vE`99B z;4{u^xB1JYtiS(#@z}a?PUa~8*v8=trPJ=TKo2kSXfc^<*Z%Be^|VJn{J@(jM!>H} zNMsxngP(BKd9490$cJQ^<%4ETqYef;Pou0N&y{r!QRI7EdZXGguHeAQ>W}Y zYkpE#cljbJ+Yycz2i`w^d{rqYTd`RLT+zojCBSuPbl9ICd)5dfWQ*P2DrKaH2WzSl zOMOAJ3z4yCp7#{eNT|Z|^ENu4{T~hPTLMS2XMb@{vrGkbhh~)|vo2uXn}X9Q6pN0a zuf>KPx#Sfqt1vU$6spshob}(P^_3IF(xcUuKB@Ob`;#m#t&0T}s&VO4&uLtU$JTKr zUijS+UEDcN?H{<>$-Gr9e(l%8ytecG*k4C0EU%Ok)T7FpRxIVg)%x%8nd><#14w$AEKx>WtPp&L?=e-Zm0)a$QZWtWJS+< zey=Z%$LbnAK4u-;{MpF=%_fpNBc!*mCC~qVFKc~Q`!z$ z6j5REHI9#bADj`5o}b)S@Uj_VC;+ltYz9+aJ3ENh3qH)2%K?U%2{YliNaFzi>GzUH z<6E8}V?pV9NW*CGdXcAoOkRzv$k3{WnpznD@%fepSfdhN%+JsKiu$-g^iiCuGt79T zWygVtHjwJ!Jq+Saj?*0!BUu#AvPUTHH&a0e^XJd<_Nj@XxjE2wQ-h&b2n}u0CNF3k z`K~5P2<8XYkGIYFK4y|$*rqsSryo29B4|Y1U^a_`>i03DF3~!V4b_Hwpm$ro$&mK1 zep%x7|Mbhjo|9%2IiX;^e-+*Z=hKO1HhQhgse(G&RYy+uAbU6K@n24*yeWwhpfH*==Yb6di-89 zon2|gKMlQ^r;4vu$IxP6xouArta!ZBdV@j|9pB#;D-#6|`6hjOUcar&pad%0#NPbO zOnZ>r>g!p&eD4N3!(S0Kd;E8>6P}>`;R}(UgH_Zj;n@Zbo`bUlaqQ;BI@V9!$qY4X zl1MKk&_~JchTzl4fV60jiGhL7@hRZWps6A!B#-Qb+O^qMy5OG|SUxaY4I1_=5vflu zEDQ!H9wb#ds}D>~L-X=}mkbq@8tb6md%nQXZ(5!PVNjOh8wTRtU&l=JStJ$jWWCf% z)9pz9(YA9pw6l5k16yk#Mgk|3NikcyPve|c38T9klGTgD4{Zu4KqVz3+YylOg9NN` zGaRq^=9iRML)<&jkz5BfR=}|Q)ngF+MVLg5XlcId&bT*90~&1ewpHsAUgDGiylEXg zV2pjw;|CD$gMxy>sT6z!lA&ycHtVvrJN{@YIw#{d`A{aQ48BmkvYp%+vO%BGZ z$#@0s=czv~c2(<|PfbZ>JuTaKSz4N+zt-aD*mv*X_M11K{`|=tz|=KRZ19`XD`r1n z?+k8o(KixWiE$^uZb(CtDfE%_RL<9Bk7mWh#pBtmJbRZi0Ce;6nuaU_NMR`9mfv1g$eu@3DDvbLrSPOXWX=Wu;2&{@5abs{HuKGttgf3qL+p-f; zR8zwVFBXhCkh2=~8DC*yPxV+Iz{#FHHvD`|p#})o=Gv=rDJd<;V#>b2ZlNO+lz8m% zWV8}7rF==FN^5JaYlJQ788qwZs4V1+GVi4xyoWK1JfRwqgr@tqG>yGOj*Z8UWh(Hn z8-{1?SlxNRELfkz!wvN2K=!d^B?4EIf2H9k%PE1-toOo&Jk~C>2L~i**HcaD@!&b( zIvjAoc=azFC`n@a<&9o!d?h9ZS#iBZZP?FiUxA=#uc&P34AP*yAHr?zcaxR8P@X?dw3Awg?w z?67>!=SdSS+CP6%9V#E*ycvA`TA*_-d1&{_d>k92vI++?o34;QswOQwDEDSYATO>C zy(}J!i;R3*)~8Z#CPx_#xPJMV2~@y)Az=3OVNS?ffbX|*9tgSR)1+xE(OCsCU{H@-xet!GJxv2Y{hzLO2e`)wkni@d&2Wk1rQ%;br1Ktb}J5pHQaOE&Uqb&P- zk0u7=&<-10Faqmsv{+AHkh?!i^VV4W@X+giXIH+ofnO#PIK>{F(v+Ve&bPR@NmuJ* zsEoYVAT|k30#81hotf%zb{g?3*rlz$Ae{uV;fVnLy?Ss8NUXO2+&@4jq@W@F{ky}~ z$l`gMSH=I-=isGXSLdp!=??016coMam>7}^v^@FP@Nn#h4})hQ{X~hFN?+YN-N}_+a_ai z_PzSWDzXIO?ep#kK4r^N#=V1nh#5V#w)K)?wK!8N# zKf!xNPvsV%VX%O}G$F+fb~zA9gF-<`%y4U}7GX+}(>L4XrG)ffca9TE0j}E+j6vXg zjEpFwrI&3XX$YWXu<`%@Xy7SU!a}(H%x$CKc*WPweoPyglV@5~dhp{(NG`R5L>URi z+wc9#U-(?#y!jbH<9+LMZH{qK3jg>pSK6q`n8XAR8M$YAx~JN4BxZX2YeGE}p%fZw zY74y<+d4t3%Nn5^rWD?rGuX&Mrg3^k23SXcq8NCG07SKiVVePgASvluwU09>65c=p zw<>Lh9SHL}Aj-EW77y9$9)Pz0;2?M$SoScnVjyeHtFNyIlo5tN8~-$RVxit#L4uOLcL)pBd3THCGfd3k7am~=MRKRz9#K~Bb@$S}+bd9Bz5N`K7& zPEq-bi_<#p$s~T4q@<7dD_VvtS}TS{cT4*h=HdKUSoH7`zR}v^f8$2gCAZp@yP5S+ zgYBuPyD+KP*GO{GFFz@SA3fr8;N09VX*Mbi9iP!mn%p$nlCrZFv$2!3;^an$@}cG) z%>UgEJE-yt;(x>e-7Wkb=Nk=Cwisq*RR{Ri)i7m zSZ2L$(Ee~Aebv)b&(re&)Y?X+-Wx2lkFMXi`RY~UyoO2cYg%Sj25A!pHX5ARrrDA) zBJCZI#*3=zjOwb4s_Jxqa*ic!L)77y?jE0!x^C3i?h%MN?C%e@4CZ}$2MvwJZf$Fe z0t1#}4A|W;s^Nsa(*-sW5X=Nfw8#ODx32aN3@nZs*M;`NeFL(MH185xJXZ@ohMs|i z;njryKL2Y1w6Sw|fzdHAisN6Z1_RF06ZCviSg%SwpMn_NF`ibIj&H1!-GL+Qu~_XF z`8-cAwE1aoNzb;hC_E8qZDDC?1HMnPLMRd`(II31ss3?;HF3Lo5V?nr0cg6!VxP-Fr*NSe?1`t%v$XGqyGc z4-QxTga~hENM56+1@N+=92#fla=36rIp8G>@c}KxkR|@49E_GfUt210f|OcS;FK5t z!be0O9Ug`>2j~PrW>KKwB=~jCYA{*d#7BncuQlS8 zBrh2FV3{W;|D5-a6-W0Sp0)hoalPnU#eA(X1UwpstJ&Ts;RQT73VABo=*~0Xb_Xbm2vB|>@(Yjz?~*7Nkr2Lfd?Oy}|*aHsy zeAh`awJa?Sc-?s^Yw16DwvX z^`4g(WwMeV^n%@v){c%b0YUtbKqb#mqYg4Bn2_&(A^|cG3X1Ee{a4Ec<%nvLH916z z$SLXmdv@lhV<;acD0KYQzpS?LJ@6Jlw1+N8^4xJm38nblNDuu7&volN02}Jb<+0-0 z7AUsygufHr+O?l(6aFBZ8Z{v#@byQN;KPU4ea8$7e{b08Ykqr5sSM_*)L7g9T&rn7 zxmLTI()@=W&tx8my0Nc*iIG>2nXurSBC48K>0=)=$2J+&Zuh!$Q{diRu&!F>DR)bM zi~00QIOh5;=JoGVZ4~9#u3b+G!o_RDxHID`a6QCR_$RLK7m{Ew_4!KnLsP_EmY`v_ zqU{k4PUHb!8M@cSV8bB0s3wZT_Xfo4oZ)ouyMxDHf+ygFIdEJ{6TOx85@q_Y+Y_2~ zJwKGQK%;>KUFj@Re^@^OPQ8LvgocFvLXKE8@x+lN+Yq^qvmq3rjzG+(LHkbNsCf*s z67_tI^ZQGn_KX_QeUBtr7GUnds4& zGq+v29d7`?Kqp>43z57)ld1?*s{w)ywp}%ArUW<35hio+WHN8Sbf;`0$u!bT-wJC)e<`6rO zAB;}KFASMuRq_DsXe*iYDSNC*nIyIBa+irRN`RztJ!alM+O)Ebr}Q_kji7K*?GFjHIKecmhV37F+uKq(!{md! zXLw+LGJg<=gx~#873bBVBhP6v>E?RrXmy&LQa2RHP`^JA4Fs}_=Og+7&~ z#6CcK4|2?Ch#X|?Ha7>g%-9EL`&Ox*F!0;PQP-?@9M&I@pDsVsufV!R{^ifk_8bNZ z#j{{x#4Y?vUiwvW&*-E!4^JXmhR60V0Q4`iY||nxl7d=f#HTB?`eC+fv;3rXHLV3J z(W=7pG731uEr|yV1viD-WDS|Nzj)mQl_6?UD_Md(mr%$0$B7@MO7F|v=D!_SsWcU; zBE2MrG`*6iJmQY|w*DySf2rD(s$H{LH!dK>%o^*;Ht&nd4Oh&a9?=<_vt)DTZuM{d zFlW`q8TdB6-gduLt9XenO7c@kbs}`+Dg6T4QDV4GcSvPEHwx(Ga@~$OizYqz@r=X1 zP}xK?ZstA-7VV=ZuCP+n@rO)ZBU6INaeCeW6F4hg%v=n{v5dJD6&Z_-_O zg4eNzfB3~5?%i%{%A_{|T7@%S^~n2DqS)bv&nPI5?x&P<|K=~u9i|uS^ofv~H~TrV z9;!++aBEP-XC+{w}zl|R}{y3}t{a@(*JI0M-zRX!dp9^E-42`kXFY8UeN0pn|b=5A7jr|w3HRv2`!2$Llyv2Aq*n;@vsAsk6)keW{EWS$37f()}&Ie6z24lP@ zCHmL%qc&;Z(Ip=HAj5_5xlsquc5#`WFQ5gHO$m(NEsv z87tQMsuNp2Bvlac`a&|Q`c}93iAjosmX$Sj zyq2B)XP#eTLI^P#_~pNCitUelY|eMl$p3^8-IRk+fn!?}J8G=pc;nNWcL9tCpPyw1 zqK`4=d|VbBWYE*I*^xeg*sUp+2wGE1SgAM%2pur#Ee8rp+)~ zbv&fHFc$VB@3wgUVO!PlyHTCZ``piHz4jemi>P!1-iY zbtOBNUO9L_6TcWcJkNt5dC14ba9QHhM5x-j|Co=y;O6ixdtV`!N`9Amekm71^co!h zLq=9VKD6`k*C?8IR%s^RClO(K6(+T*5PL5MvGD3`eoNtdZk}odqM#pRv(5e;FIz{qb&{rPSc7$VA%gc(>51aWJ@iJ#}5i=Cf z|K-p>;$u7Vcmj)0+w#S@+HIc~e6QHTtTf2+2vI*9p|BRiT;E$jT1_n;9Q^EP{rYru zjXyLO1yH_mk(@Vs3#HnMu5p25N?jd(NtoN`(+_cZ98Z0uvr^OfLqF$$P)Mo7pdYLh ze0_aakRAYWw{0YWF|v+}>cO|l{l!R>2GiSwCfobcI!2!{?1+L(kvd{iG}Bg7mc!;# z41Vf6q&7ekNnz}dzYgxjM%gHF(WrAO659_%>4U>1AFXnH-VIjylV#n7(EDSoF;9rBF(LUEmv^yt6l} zBOVi(Qj7tUNLB_43M1j8h$AFyz7Z~PSoWD8_NxOHoKX9*^!pB^rG-6YA zhM{cZ7jit>wNqcj{8D^lO0s(N%SLMUZtdpk&&^fOlC zsge0WstEWW0ktJRKc6@i?ci`(2V>f5T3IDSGIhwt#&9=q;p$+xJ~C3_z7oNx(Lx>z z*U3-{8HFU5#dMS1baBKw-(}$^s$q38zeJ1HRk^HCnZKav_jZJlF;LA+Ti>pYP+|Gk zj=CLUNKV$BmW@P2P$b$PZYMoI#0Y-sc6OF?4Wv9|LMb5Q2#<*SU2r*l+tTtZ^gMjk zKXV3=eq^iGk(VPsWk0xEuq_oVEIbEHF?Bjq z1=?ewl01uZb9wSvqN1HKu`zG`h+b(6(0kLf(JV;P)j03By*fJ}!~C#1kL91f6)G{KWiNLbrnQ%Y`M4)@J|Mdd;cl^-kLxyV=mBFO^1ConKGE zvPD60Y;I`@d3jRf6+?-#e2oc8u$lXy<}Wgzu6s7F3N^KWz)uK3gSEu+TE#^6HTS{K zt*n!_wy)*W7jNwaetlZcwVQHvGr;_2@7MtjCCW}{8zW75<&&J?pe}iJq13c@C*BaQb1amN`<<<-cHe{j{zl73BPtWs+EHHfaUl@ZbOq`C4XE zB~B~f-;v|O!?x)HxA&y!Iy=Nfy~XBu6au~K$Z<& zACoavgh8Sb;1fWG1-pT9TnkrMS7={`oPl}NnI``RA)c))nlT9H+<{_r*RP|?Q56e| zZ2;LZh*;@`&n(F}pKSfv7JV0P+Rk5XitTZ%vv2MRkf9G5oYrcNv`hy>1Ix;HkMetXp5!5GV*9u|F1539zdgK{t z2|3hEc=w523oaAQFLPSS85jnxUq3(E9CI5cr<2Lh3n1hHcrQM+|LlFy!Q*i|$l?Kk z<1hWFAUq8jtJ%m6j`NF)Kaa>I5?|SLE+&3=ZBxwcy*z6^zq$A0`Hzs$NBO^hNC-$xZX zb}#S_1%+sywE1LJw|v)T-BQonCobEvhGXJX^6y0>Xf$@uiLbzcV5i#a37F!;GZA&( z^w95(Mv!O51_%X#32I7tng&q#1J*^e@Ss-Gd6c4(+>cUR+R zV^Z=7kmcLX*BuO3vWRQ0`kCUgjSC@ZCPI^diG6Zg5EYv(d+2;5FVeyL?}^g)$+;>C z_~V*Ha0dRZ8nR@S|2=A}tghjasH>}kXahkGLiw)oQQ5Tgbm={SX%Cs?=5_gKO7gRc z@=Tax&wddd2wFgHL*X-C7TM3l;_)$TY&78$6H5zE(j#gv%j>CC!}11KEUor_kF(Fe z`S^&Uh3oR?^Mr&aSI6TjWfYE1PSZ})YQQr)X+^EA;R+3Xq%c`0ZQdud7F0l2cg`mj zR8v&6Dr*R|CJ|x3M0QgjRa&?GV2aL8D%*_-895~`T_Yg~(A)9G3~dLp?r)CT<^KNp z$~3Z!?^VzHQ&J`-$tZk$j<)KZ<)+(1$vPx-r7RwZ9Q-Qu&9MAk@{*f-itP;D+Qtx_ znA>rWhNXo<%+Htbt=#OsKWAFWzU=z1sDkajobMBoft;r^$<6oL9(InoNs(d(?^$-{ zv1G{^oxKk$!tLQvSKM!?#ehR{zBjylYJW&3aOWl@;{EV+yve5I8;RJn=d7LLeL_|Z z6DAxYqA+$gkJVZW=Ly9^#hxTpQIO{&ilO3SCpLO6BL%6zx>3|B&N z5&Dp%te@yG6~QZj_!5}k`}yc9z~~NH@Ym_H8I7z^ig+H4Vz=pQA+|=VsjW}ke)+em z95uEo{2mM&5`nY1TbzcC?e>|QbDR44X8-NUv;lsvfS?c&24WW4k&%=+VvY0qScNHB z4UMZk$#IeBXgr?A>FGq>yg=uTgGjJ)4R}lgBU3W37bGMTgEB(RU1M(F+S#L&czVxl zp5_}f2eM2UXTQMlT>v65*_OHWze2O^oR$`$DzKSvc>@Iu3TrqFE|B(0WMtqjtG!Qi4ESDk|4p6@Y@|;xPytlaVyRf>V0f^543B5Ne-6$Srlyl}cJD}nL3Vh0 z>PeNy`((hN%7gD(5#5?I#eSbkwt9xwL7fPY)9Bec5 z8e3ij*jHzYY0}x;SL>a)SI4LaOICE8PHWlWq0%8HR27w#Oe{=17xTrk&nYZV!4JP3 zcbg^mYDnJuxbOK9azPAnj%CH{F@XXRhO45(vcV2%(l4=4by{1b*1*8j;B^d0`XWkc zW_nf1uT}!x(*NXF?j5!!*pohcl`wCqq*NAd}`|=WU{te z1d2s|9c4uV7(X+}DfP#LmIS5Z%m3XOpfrrVW@a{pcJF7KM-1)mDXCAR~ueVlK`E+elOhPogLbS~6WUNki zATrS{KAef-)yrqk8N20WURFD~bHRq_P6V!wl2ejd?`G{#NXpw?8Hxa5!B}9 zYxH=2@cg=CxO7H)xP~5WG{Hc*S^VpqgL zF-R9zBvA46A;1(7lb9Hol>N6_aaYgGx^AHd`1bXW4I`cSD6BzaCi0Zw(4!E?1l&Vk zcwFZ){9EK@d;L|D%v?*L%l7QqlZvf}tIy2M>GI^AHdP%0GloV+(j+7bhut2adL+O7 zjHjCs(u=f2W+p(B^^JaVgLQb6#X4)40V6u^sy2tjoa18RWlFn2q2i}c^9srzIZ1JR ztsQIAb9~R)94vhV{J2zg|~dnf_5-j#+@c@J#&~h#99U3ob$j;pS$9F7=yS_sL((#{{aSu@ zc3J+7=X-}6SE#%9BBu*pJ6dDiO$Z60p4r2A(gyiec-ZVd>v{qL6z@ zZmP+x1PL)rc%6%w6V0breGSZv%BG3fVzmp8J$NpNPxR{vlql%?uHN1LiC|FaT6Awf zIU7;Fc!Rp(&oW7`CsyL-UN80HX>*ssYiSJA(@n3wzW2U3`n^%FHf9=Yt}d7EWv>il zOkc6uDC;eT`PogKQLxERo1gFO_14v-`}28VM>`zPda)5nNJ&Wnp9^Uy<$$aY+(lK2 z_0T#Ui(^7V`R!;?8mRw1&$2gmC=DMo-+6$jZ)s^sg*qZ>V!!`+tNQ66)z$IRTC~i- zR_)ez?o*@c+)i6B1BU3T+ymYKZRUgW!DgS`4$yN2J$wcw@qXsB6hC4fiN$AB)U4{N zs+c%WVqzkG%zaRpa(r}h6iX9>eCaBU#Id~}a4-v{tWd7B;wfJMlW}KJ#atjT0GKss z2R;);oR;(%;)w$~OvRP@&-&L6T)vQT0A2y9X&GYOe%_A<`^OxTGg&!F{78v$S-4*) zN*o@^t~BHDV0s_NA5FdMjmqt}20I`k4tZXN_O}0rtG|G%YU}>T;iD)j5(X_LC?F-$ zjnduSjdXVjh)9WagMf4>UD8rgQqmyO(k&qHp9k+Ve((1^gK>ugE}VV#UTdxypOD&$ zdEU>Qp^}G1)H$;19rZ?~ps2XGMnPq{pg&5=)5{CiOoQ>Btk;6gR!IkG&0aCLD^C?D zGuqc$SgaWsh(vj%lbmf%O5ea*nDN@07LAnIa%VL+59~?&(Z+MUZwTSQb=^hw;HCQYvl8G2K9-Dqp8z_Q$nFHZ>i>B1b#wVKO$Q+m^HAqP zB{uu-s4)62~xAZ(-x+CakGhCr2F`9K2p)A}01(CZ~Y& zqOtadF2C+6>NBWx09Y^_uV4fklqgqG+?5EgU+;Rnxd}3rTc-Xr85I>H9iz}I(st^# z;=iz;B(9>QY@c;LrLVWh7t428>ZN3Ms|oC4p_uGR|^|szZM%8DpWZ4VV*o@6hNM(Tm1nAC8k+5=IF(#M! zn(?QcI%?R)jaoIE^*P-ofMiQ9^8w+P>E{~C%JeS?L)f`}(xR3(Yq29s0wBRbFS z&v_+!8Ta;u;bC#F9O*vRz-~@wmW#%VG#tMvHmCV^63+jGQ=O26r1EfcWTD?s^mc7s#gM5? zlDVpA>F$ptU|>v6O&RF6ViOUS@5WwKh}0f0;TVZaOI!7wqj)%P6%-btp`%wH{7AB* z6?^onO%fL^pk+RwF^_0>=eU9nsWtsSF*9rLU#)RrS`u!o z^6AS#cH#9sns2mldw@hG@{aH!HkvGM++XC%-_MrmC1Us1^6=>JO-`MTQ&v_{MB$cB zN)^YvULp4gx9H2FNa=U5s$sw?|FN>&uR8koprUbO)~D$%)m+Aqu_;U9X3d_7$Ej;n zE6D@y_Ws#VTd8N5q+IqtpKlHthol{!-DftDq390|eh178;*=Effs6cV@9~EDVvip% z6=$O%3<(Za{}JVV*i%!pw}c;tTB;3r94d)u2^>!8G@k=AFKragoCx{5fGXT7zt~${ zUI6KUC}=k*sM!Lm*WI;KZ1?n#*mV=jXPx`Fv2kY!nsYKT9q*?3N0J-mbaWo#hWHEm zp&z{+OQs|nFyccRlbtI3E-Czztg*2&gsWK(H0<3(G_+bZ z9Kt(yYyosvJ9HVtRRfb05GxqahU=4Jh?C4xfXRvrIieLmuodFq1Xy<-@1dJF?M#D9 zea=VI-n6>kl`$Si>mI+mOxM;PSgVz=P*8+*FaCC{1z#nvzjJROFdJMH!rjjY>{(ga zRMw_QW?pH=ZmSb;GFw%C51gH1@$8H-H+t+h@7T?glef?#eLB|Ib-j)z3T(zE(24mR z7r^ROvwjIEhdKEp+HP*5?#s^GdNc4zxvc+=kxcId1O`U`e&ruL1IYiRXsOW z;&+4O3;RPm0|NyfKnSfJ!2aa7nm%myAXP|8jZR!&os-w{+%5H&UtAWLrj zdNO=3L5j_%na5nGU?kFiulq2i^5whTV^iICXv8&^$G@H^GJ(UwaZT_6sh9nQ|Iy)D zAr!m~Wr8&?#n}!D-=MbDV)5zN%`=@Q(&X!a#1?GR;NNKB)byOJ4nOw$-u1NxhAT*R zKA{k`*_hyl7Lj^a;lxC3IRD=TmAW4qamvusn7TMyO%L3Xl#tPQpCT+%E;6JoFP~ts zA^+LtV>uD0=XwwoX>WWa2?5SCcPSQiv2T&!)njJ8T7S-evGZy6V(y8(c}t7H2+hHd zqDcWkQA*0ka^Wh`swPI+il)KqyTvJWv+jGuAo!>~JunjyAKxT77x}XS&wSQn+5f`x zg!7;f_?==|o4gapmn#FYC(r*eyOsj6jkL zGz26hkSJL)C7kFuh@b4GD!2(xN3=L3dGK@bALNmxg;<4Fl6Y$m{Qk>NdO9C+;nEsx zyvBcW#6SBNZ@T7{Vo+$PtIu?sfD^=x$rGOS#)5`>qkR|EnFZde=N<<|#wh)<53{8b z?vawpnt)?+YE;zx*w5~`r~Ju?8s(2XW*dl3H*X{uPVDEUrk2ih zb8|(X9&VDJc;b^YF_BX`qsL7;5Gh7=X*vJicN#|LoSLXpJ-zX#=wfA7N(@!68dx9( z>OK>p;lJRRWn=-odS`iFo_M<4cPK9zZzHEo;{Y98k%766yqjB_&&6I_lq~Pb*nBt- z%sSp}IP^bEbvq1#KKD$w_)@W!Vobg5Iqy-CQ&LeBa6`!u;zBQ!930k4AgXx&X?CB` z>@0%l35O95E_VIdkGg#mKq0_uR3EsxMjE=hjUc}OEi;74WrqX7F#|=Y^!Y$a8;)_W zx{wQ+)P6tvg|LT{5-Gk;?&Yt3;9u`pxsLd-4GPF`EGq}jR?~n7l1UkI#C`dt#f%*u zNa};&xD_Ns&fE$3SNsFY)*d;SbN!#`zG$xZM5%Fz8XcvbEh_T2zhwzTRPotAar||g zx47?S+qT^6q$F@=5O~HGJ%k(*26xQaidA1hB^SGcWJ(!mP=h8)@fld|0Ctp99cKKT z7P-DRt{^D&)|1dt1n;8vprxPWfqu3pnURJHa_$OWthUH+-}#oRQDpM(o5CK{sS;WC zV#XW?xR<=cP&Cl|cpM`Ek`*u^YfdhNPnOIS4Sp-GcMy7hfT9chOC8!ad_;TW4O3Dt zVOaaaboiV^F*yGQ*a8ogNI~(>L3hQ@Nraj*(EQ~~vLP^-enx{7&hn7)Nzk*TPR(pk zcMuc!@2UdiT3Mpo4D6Js5g+i}Oq+=9`Qc{V>wReRs%PrOGA8(%2xZe0_=+0-#3a8o z#?XEOqtpN1VB(8gncy!u{A&N3i$v+kr%cUba`;OBrV34qbXwK#rS|ra+M_F%+UT&v z36aZ99URD?lR;}N{l6Rn9JA0aO7rXa2V~UNO_s&}1MbJN|p&f{BD8KR-Xr z^Zsj(!4F<_clGz1Y7>sZa1)`|dGp%U|JOac{BiTP(&g_r-MOsD0IPj3=woed;z=*v z<@b^Q3F}Md6m&sDG;v)1KR|V+iJ^&+K)%s`uedjTfuM&kr}*!3e%j;GYY1fnSAoyt zkPbOeg9`BZax232G5m$g-?8PiuSu3#1K|ysYw!&%VJ$791W=-YuGIhggp;53QKpd- z;D4{rl(MN(*#`#)nw6I65HR#`F{f|+?}x~@06d#x4mc|Nv%!1{fvKloGKP0yIFxb| zp+&{E_G?YG>ApHc!-p%$m;QdRso{<9h6mbwyz+tS%TojgGr0II+OrZ$18fGanuD`Q zr)}=tz1uv(Tj??>dql3Aq9YA8Eb=8&keTTZBf?j9-%m+jF~j22Xz+9c!!#(a zI2zd&uVV(zZxP7A(QKRYx1QXIvZ(8$jpE4QW%CO0YRKHu^5bRKyc~I3Y+og2|N6R; zr8D^c`4+YCBqyBquPktJk|(mvtTzfP)aWet7j7|-QB%K_QdV(9V*C&cS5mN0nqr`i zLlq*sb2C7|7iTuOr&_yZ(H`&zqrnchCchmL-${6;89@-$WyC_5_eA*9=mT`r`j|cm z3*jH>9;3~RAIb%1v8_y#xM{CjM+QZVPlh*$yKo_FtwgR%?H`32IdI+x;fE0Y>R~B( zZ!`7w_di8WlJG9?fvs6?o?pS8kTw86Oi!mI-qj_?MiW*MyvQ{4Z~ktT(=CxXAjeD- zgEqT93E(=kYkpv%QG1_&L~cT#Ol+r>!})}}mig+d^W9if)6mB0 zmdauFI2AS`VSgIrd%bG@Y|=}}R0J{=U0wfHz_3#D1$e$;(I&(U2lv==^bq!knzsnt zt6R?mT!a!Sr9?rWq}JZ;Go%o;q8@d$Gd}uAa0^9FqhzoShr7_5CTY))>$LvzvMve; zTb#_RlqT@Lmd|!M{F3jdeNVx>eBYs8d&fqaxj{ZWz}}?#BTZ)4y47Z7Ni1oH%GBiz49Qcz5cbSu$QQ8vA&V{><(eV!!@lZ zkMlP|0BCFO z1rSN5r@P9J*iWHP1{~wxvLS7Q0I&lrxA_PN6*${=x?DxQE5R+n9d?-Zr&>^(-|3e| zO1g!kn8@zRqDa)tEUiGN3spEnx2Jqg#}mYdz>Sz{mOWW_|Mr(ZENUm!ELAEp$d0N>FF7$X>{t?!K|eUvg|X)Cbp zz~a98>yI~YI!<-XOv}a_REE}7ozS<`Kj z+=A~>tV`5nl>Tbz__%7VtmnS(x_9?U@X|zVRHYM(M!7x8hrpSS=_am3pt^Re`=gcR zr!m#?^wK%%HHCTA%j?8f0<)8Uv#->^z(9>65?9SD0HEZXp}@W`5CLwjJY-~K-}A%o zTIZVJ8co0xHraQlB9Ilf0zp{Q#`oAxpzN9-ARTUwo-T)PAiUHSVQFcpq?MtN=iWgo z65tzsEl&wPF+ofWieP$qW;ru6980Uet+^ErS&ymiy4Qqwx=mTESSbJ;NABYkXv|(Q zxjb0ojP=zW-JO#1D@93*u$LOU7^$%1x?{v18F6jPExZdb0*}8%_!phS>#M6{B`xxq ze`aPZXK?C9Ho{JJZXC4pH5J|oK29H_t1Kyy%#m|U;hpqq$QIo=_=zK*gY{UiOmOOt zueG%|54$XhY|GM3j%4o!%r1gQ>7gQ-f@mlL+Fwl`(BX!Se`HF~2y3UzOxO8j!$h#5 zN`Sj)PS(kbQiIL)2pbZM0J%{baC0QPLmeZ5E&tlUk~*hRijfUFobZ|PD_^xA;YT-x zZK&-j?tzt974#|A>r0#U0iIy*x-TsB0 zJZ_S3+UJ5wk)r*IWqQ0Welj1ngvYGhgc+7Fs2AO;E#Fv}WeqS`mqrnI7_Io`_Zeo> zUv`3}*9Pi=dXS|w-fCMs=}($xHf(Q8r*Ps5nbE5~q#VXve{(fGo+vmP|Ap9F$91)f z_3Mcai}W6cjxj0cvzeiu7);FAYX%$GrsZ-xiBI3&Lug8+J|4S0N{M_E6Bv57x&%4>!=DhOXr*}rQ$Wd%#m30x~KU2J#?x!ouu*O zkr@rB*}j^pVy3@T{WK7`OqM!-(!&0IEts2*wYa$n(qRO^ZYCmHUtJwH3;-Fd6UoHH zMAQc1oEPu-oz!yq0gnV!poWU75l=9g6QeB~*8&M)3*pq3v6i3v>2edFuq3#((~D0P ziUwYe{m{8~!@J~?a=*r?HDeTiCs>QMGr~oT+Md`&Nkxe|bATHE?!7O&CNJbZzsOn$ z64G9_C=ZjyrMS<1dR;`XZ2F_Zz}ve5@^^Ge@K2h~q$jJ`tY^dP-UXiN`aKNSQ`?J zprMJ0-|y3~nQd>}{dP-$^UT<0oMYOhi=D# zSQNUaX7Q`3c4f5)H@-B|d-nv0HAzWHV-J?ahSL_N#@|^vIP5i5agQyUgCfv7G$${) z34%^_N$&shPYf^WkTwH*Av~+X7h^A)-@gAGNW!v;VHulspl7W)^RTRJ|LnHEG!fx% zenZsb;SFvN+@yY+seS)UK3_%1bfa4n9v;L~#_Wt+){hTbu?3AKYt(OAR%J^}YG)3a zqfT|xqDMaG<5waJy%#JR(k8&B+CC=}QT=p(n{Lo?L-|Qa#Wc#TzGU(Vif9KPoc4tR zX29PrbVYTQH#9UQS=DOmQH*W!142;lR`Al%QJ+seJP*+xV0-_tl(7>sP zYC4coHWOZ||MI0Xo$`j~LT3b>g^gLd3LFm)k2dFv-J zP8c$~M9DbPm6r>Ys94O2&2!$M1n9_~6RT(wO}c)3{{AO}w0)dYLXR)c`TY5d9H;3? zZtmc6!dhT`t&0gQ`4I%7+4 z^3~XbL_$MhOb?)5gAfuj5$xi^igwocP!2{|L)$6bNl&p1%EocFzWAHdRP%*RR_%Qy zH(QTyGM0>{l8INMsbw}G3Ta~!{aw;B8E2(mLAWo#M)gVa*xFEgvLYPy2D*IaP=pVE zd8O3*YS{=k)a~i3Zq~BbQHd1_yjLs>+7hlKZp`g$hp`~`UmpeNzxv`OsxCiEs2D0T zPf&0hkKucK(%N_PiYygyZv7UypXC z#Lvzmh6A+)ciSslnwgq=au+i_5e+p%e@%994Bs%WoteJE_!Kh`9e0C8VEPZc+wtq2 z>ol42-ximsxm}#f2?i#8%QyzIC@(TzXSmJqkz-P6k-0v8xlpxHq{%h8BY=42ySB3O z;WCvSR(b|Xj}H!tyddaW=>z#5Xs~&TIYeW3AMK}!WIic{03Hgu@Sq^H;|gMYK-2>x zV~{-r%Oen=bIdu0W;7iD&e3|_5p%EfEz-bFdg&VD499IS#Mw-ddCG|LMdA!@Jp7p+ zcdyBaOcJ|!V>>(g$pmk1-smMU-p%bD83(8X3XoI4olp!v&~vRxFM3#hY;FxuM(nByF~_=oF$c+Mz8cU&g+_eEL8 zon>M~aW~R~9JzAQSe2z7#dUXt5&+e29_9n|z&%w0X;2Fb+WMduHUP+PGM}op1Aq;r zkl^VG6mSZWP!6vX7D5zl9Enp#zd=Z2Tm6#a;>L{z+1LhBZgQY#8^Te<4`f+~eA&K34%u(-HC5ocw+-^p`y!c%3k{@c^%O>;c=@&DR6%*#|nZUT=Q(d70a zJ6OG1i($m5d2%vI1GIz_U;)l)dMweFz%7%MkpY~1j>vvQ_ac>Ss^!a%T-R8{r=Q^roY|pLlmBhNa zIgGDM6I(e_T}QOu`v0rO6@`R^z=jDNbme`3v%a*vJd|`#i}aHDuBxL0D$Q_O|5{t) z_BwII!U~656^82Nru%wulLZ++0XdzD7k8T5nB3!PTXRv^XiJEKUGwE245RAwhDgX) zNuGKqlOfq}GRW#lU*!L#`S|*O|LnkKgJof)lP(9kOjUWeh}W=e7SOGys-J;=FxYbS znndl<;)Xyo;(Gkj<{W*E}7`phUt#RAtSD_ ztZZ%yse%v4-xXS|R+n~h@G+x2j z=OB|IM4kt>M`D?eqn)WlJTBi7(E-*$F2^Sw!9qm0*La0_^YfZ!a(aVrEI!m?Tf4&V z7PZr&o)WtmiqIS5a9Bb|HV5WyS7e$-q+wk0_;J9=uXA|QKfh*We6-n7x(>GWL!bm7S=HJCoo}!b^SG#yx*SfH^XOL zsG1~AY|@&-=k1A`wCRY@!yhwnI$T%(Uxy{7J(PgiZ17RO%@6+@SR~*_uojlYuVd-+@fg%g)hFRC&;; zl;uAY$~NMoq%`^UHOSGF<)hq$c5q1C<>#W(D^auF-OU?xTBD1FeeIZo(xY57O%Fc$8?V#DffP*i2vD*GtN_*H$F~9m6c7M#4;7)97RTUvgEEiKKw&5YtFEH$Y2rV7_Ta1$d$?%cdq8Ic5n&UxOVH+6M& z%@HmxkiwQez#y(_xydaUmBG z#Qx8{WB2;hL@adlWN_qWO^b_j*eUkIaV!YNf%b);vL8-5Lz#E(1w zmIOY>lfbg?Lz*3>mTNE9n9>`roLE4flh!&AALd|80)3_DNQp3DCl91t7X$@Uo0%_e zAb~KPMiUb};|XW|_v~O)(BM>J9t#dea|~Sc>r3TL0*wh1u!aYka~soJ;zm;_wzCF7 zUAp#7zJQsFo#17#N9g^`uIrw_K)st(R*)ICsinv9Os%JmYci*kXW7lwYSVIbu8&kp z3UD#tAkwX&i=?}mfTIrRh3AUGld`hdoNb)_!I^56KJ-ay%>AlSIzSj0AiHDv%xVi# zv^nheKLA`oQ&lxii2UK>X21o)R@@AQ{zP4fLmu)ZL@-XN)5Q`XH+yo9Jc0ZWV)Uhr z>8ZfeG|Wu9V4+&YqL19fuhJ>*+=K#3?Z^41<-s%X=P8|it##;7GW5w3DILQ{avh=i zX6E80SyWdp!Kp6MD@l18pL&ZNZ`g%$6U|PSJD|yyU7YUj=dotb^B0ddXXX-DdrTDU z(dir#>#*yeypr5GILLC37_YKP^Xh(xK&*43~11LE!!8g!P|C=S7 zB50jI1fGJwst|}jUccI0!Da-}`UYX?;H9?(RMLW^!QG4CSN%WM9=U3;Z{V+;?>5&s zQq|~|#Ip#)-pFT71EYvVn0mER?HlWFHh+CcfLMuDTui?4y!N!l*OjyS&RkX=703L) z3SBs_pkNY&prI6iEr%K(iBe`@k}Dj78_@ziV|4|Emdlp>`hT?)5oX})2YO_F*Iwj$ zmwMUI-U~t{!FWS4nMW0%FBkGsUOpmIK${erasTJK^-NR{{=UA*i~B?89Q;+=kZsZM z&z))=WsRbi4@WF}zuF>y%kUaX);RZ^Rtl+0{_M+k@C5W0L84BC47{35RZE{5#nn`_UghH@B8I&jf%}cZx zqsJ|sLCGQZ;P!1%V`0A!@;DsHv2q1g{H=sHZ^Sxxydk8=E~BHno8%ynN#gq4R-KAf z+ia7>j(jKk9h*t4^IE|;D9D=3{SF0J}$^I?Yf6sK$FCARif&JAiMwAqjDR5;B@E@Wv z3MLK7U0xF}8$L`M<&Lg7y~}-%5~n}eeSvbyfP{&{P~fE$ z>YFh*$N^OsXz8%PCypFAe0w-)fJMDgZ249a4i^q~AOy0rSAi=0%E}5H4o;4a-&5{3 z0lW?G-TT&vy+2x*1rn3I(FA^q`NL+yMAp^M<3Fv|4vyg%9lySHA0&DJr{=;gLHw#< ztkn2+LOvrIIbz?BO_>FD)&p*5x@q;M@8YtuIVM`RO}5d_s`KBFfgKfPq~>*6+H4s6 zOnh|o*SVi%=uIOBdja=>)mv3=t62h7JUZ$D8|)o30ajl=GYj>gV^o-wL|7?rmPKoV>)tnydby-xPCv$MhZ ztMxc#zy{bF1>J2Vc{kwghLiH8lJ$L?=QVKIwc{;ND9i7)3u;{^e7aJERHs( zLFH~U^v!T_k!B`2Im7AujFO!a)6_0*d!x6Ce)@CyPm`asv$G|Q=rft4TD{K?Omj8Z zI6JD_@lo_hU;XXAdU0;koh|KOF7KZ8F{}Qh-v{*?YHUpGjCU)Bk*UWg2t;!>TVL*D z-?N8DvGFZNFl|BaCF6=B2UF^#alWt{&&)^hsP=GD8(r=I-O6U$Kxct7JZ$W*r6jaO z43``t$9zb(-@g56Ujq>&iOmW?c#!q@Q-ik`xF+;KFAyXNSZ1ef#y;!ctQ;hz-e3rb zMF#LV;hDfZ0xA!7u(|~dU6PYvTDqhBpUFBL8sww_r>3wqs(#1I8?3EF}8V1Dc7X{ylYpR!^X$obq+LZ zpu69SlRUQ@vpoHw096=p3~QUXym8EPniBMev(7cEZ678;_78XBe>3J4$IU5D`+hR>T1#>ez(5A@k{}sp2QuLgcqd zo(c30Lf-E|8|8W7X?&Y!Wdf^=_7`(7ZCti5oMcFz;U!r%OAu+x*k3<0Ri6S|^MAj-=R$WfBTb=PPWi)5NvSUmW)p@Sx4*6)2W*HBT5wQ6>u z7-E<)KMfKkso5&7Ync6Vyt=y7db_W-1T_4Z<*O>M^ak_*?WabWHYr)@$IQN0t}J(d>kQp^ zA`>*VTwO5Yh1X(Xz?P&;gHvNcIPA-Hve!}rW)dL2f31iZH&)oRWWQwhduKA=SxnTtpFsYfSqhHq7zwPe6&805=+Z9NX5v$m$o5Jnk-1hf)I8qeEtouB+ zrYpSatcdfZD$hfn{)&pae$_X-z@on|6tnsZVp>2a>q|-8l}y^EmzU9t$wq=bpxk9b1jEY|WdCrbDC18Om}?Hjf{L>h?9B7w2bhnzzV_P?bS- z1es)|QAc_x+IK6MoT2ka11_mE3?x#a8TQ6?C@x@dvoIdn6Zl{Qc=&}44az9aL)DE( zA5bzeuEljf9s(7wd2erGlaod(Qw|^gMgqm0hTW4jU7IPfb16yj)%y2;IxIfXclBAD zThG*5O}33FD2~o}*MZUJT)$5rr|akXdR}JUl&OhDjm9DV-^057P-;C%+Gt9oX=!cs zH?}$un}5Z-5FmID4A5`!sJyhcVJ}_r*&rILtNK{Y;V@DDF&bM_dZhZ+eM-tlj^$O$ z>*M$D;N!EJgsPFJo9l{nwAbz&``RCutCt;aObEvcg%cPu65ih1%Ug~ds$5F-kTTgT z-k207mp6Am`EvcXMq*;_M0U^Wkgn$js|{%yuvplKM*>2L2-xj@b^Dx74u$jBXMBEN zxcxiHhC!|Lbz!4dH}0;fg!_q=#pv#JKh;#9h6`>d+lzCEIG~tC_2`kDeo$L?TsRsA zJuSV}`NmBLqtO|SDrXP8!fy%zH)vB*5{xRl5894cxVzDR)Ln9Y#^-HTXhk8Q>6%rV|YB`!1UGHOK1%*ghso~*R4(9PhokmPR2n%T( zjHw<$fy$ z*9o+?QeZkLSX_vf! ztLfXPHVp({%xU~+#ICX(30M^cR*fqEaK?b19k6dNR#{aDUKNagabrgIx&$GFJn1y` zhgNGvMTK-cqyE>ocNOv=fvABNI`k%#p?_|AWAxS3t89?!rT7&&U%w0j9Y4=Q zCou&T%F?Foj1hCx&XIGGaI1F8n$m#kORC+UI07XEUGX1}ZjM0FMi6vJIxSy?#1>w5oq_nFQ{N7w_KhO@(;@87S+ z)pkqvb}|x#!TK0*bV_+bdmH0+NJ#jF@tO+L!S?=CqiKJ60<);54>#+xX9FFh>=!HY zlPc)$XEWM$mdbn`n4~)8o}8>g-ypDLbcCAae!7^Ow6W6Uk4)k=JY3)I6pO9U0evyj zsm9sEeH4!)6;+jYAtARz-mdsacRj{knZmzxh{N$$Wdtr~HZigHemE zx_UQH#3 z=ciQCsg|0>>+5t+7&d*DMtyCpgckc2iRkIpi;EL^J=mUXdquZG3j462rK_*6ueLW5mt@?14z^*0TN`~I64T193i z?~|Plh~Swb;l-Z{P6sA_e#-rzcd|ZiSa_gtOI#e}=lkCg&r?ageH)C1fkpZNuVZoN z+q$^|2C86@Hf^zW*c&>#I0?nULBJBoQSTq_9GlHHkZ}GvK8?zY3&#qoJlU-4;y)F| zaQAwtHpaTaF&<&eK1-Aq4Qb(8rps&!mjx)uf9vilar$OTvA4aVP|%;kIW!+%&cYs! zjzR1euyOL|PxX%L2o4VKRTWj`h_fu`K%nkeZq%X%#kU%lsR=MtO1u`y_IMm>I}0u?qm!jiGOIa1w>d#2y=8W=mf`l%;nu+e(}LiIgK zP5#qUGW_dVUK|FN$Zk2F5nGb_k1IW0yy0yE7k{`~Z*n?n*B4LM;{mK2#m(*8?77&K z5lbo^J@G!ab~|LcK!Nx7^Xoi=rkYxepr*C<4`W>pny8>wgRW|+<6yn5zLc`1UP&<- zObjg9-p==3Ms<}oIluLSp^CGyB7SDS0DZySXNK4q7?V|&T{@*kg9}|Sl%mMY>@uhF znViVmYBygl$hXwKK0#eb|48kJYI8cu4e*ON%LI#|{fQ);&525S>tA1CCCH|6#U!TA z=%l)2|Yk}y>C|3`*Psxp{nWvGwR&jT*ft<>|C2|&>`#Mm2S&A zXMd%$ur~pG-!xgbjvhJr?Szc<$stSQhKKcQC)~J0>F_`Y`Ha(yGB1Ct% zcToS144P)$iz+Gn7rR+I9w57tG=t=!-X|g9yT+;<=QUSO7)FQL5z-O;=_cm-w5Ebq za&lxOo3Vt124R;o+}B}2I9rlI5%DpvSKr^`E55#(4Hv0&bUe7p-Cg2LD1LH{_q7ww*YH&s17ki3||Vpwz7RH@lp+JfHXJ0zoS^& zSjv8;S=+m09nz-qbOh81rd?(uu&`kb8>JVp78|H{>^~-Tg-HpF_a`PNS7mOzl2OQu zzC=4}ZT9Km1JxQ9Ey%e{);NIVHfseV3kwT3x5oj*jF~=26n|XP)({f9#(5Xus|hS- z_YT_XC9-Jf=pHT8va{pqPU+IZY+4X`-?KrN1=U|4n#}xvw^8!*++SK*u@a(F`1wQc zBKI*ngD#0d(e)aY4q4bCW)Mv*(;2$8$rGZZ9eHb79>c6&iJQu&j$wkRI2;c%sn?o` zaEwmn!vmk~d(|o(;l%U1uCTBlaGEQL+wJ()dstzma5@Ed%u7p1QV5q*^QX~0p=VHe z60_6Qr86^Qd}h5TYVc!pq|4tgwouJ(97hHlmry!8G*1!I57Y+H#NuMzO6$ej*Az{V z&8N>J^#^id&dIF_jV~k4M7F>#?QW*X$dBPM(i@N!eie_(J^qrMOc_AV!xUL)rs*pb z|IGAVmn8!YHNNZl+45HV78Ah(jFTCxnCNKFou)zHxd=W*41e$0i*C-%MHncC;j33P;o5_c}3*K|T_SS|Rch zdP{5T;&Q^oxv!tZRa9`rD{5=GW>1d8=3uC9Jcb;q+qzehE~&!sba8Pm_GhX6?yj{? ziGh^k{u^+M)zMmi81+~xc`Q%qn^CC+#=%zqd0IWUZ^*BPi;l*lu1)*atK=WZXKqrX zz5EjXmEz5m_(*(qw$RFuy!Qf-$2AU1o`26zg&#jQDN|3E z`zRf6n^oz2=F%XjLe1-;V#63JDRVx6<^6oKsIXXMtw5h5?R6GQnkdPF@6gMt5LceN zX{59fE9)pqjDKc}TUs=?strw4Vy8{Gt4(FM>fVv^)@~NpQOc&c*JKzxo!-t}>5OPU zIRQcMkJPFB4kquD7?Y$(eg4d0rFpv#E%ny0Pb-PL2*@lekh)9f8(NrvRJ3GzD0cY0@$}OdCgX|nnFqvi ziCoX-kMBiIPBY3$H`r|!t&WRitBG6M+#bfsW z@u-<9og=yzn%y!#t`~ zHOC?8ZoH>Ud&epT6_pL%{k|xvIOm6lllAt6pM1NJz z&zf(5yQXFmo3xZ<5|2}U_af8Efp8#}?uWp1^5(R&f$&t+nPcvQwRA&L(G(kFKn=ECo}P zb^0;ccpL!l0vj&QcJlIi8deA&bhW60QP-R?x1~5!!ennj#dvWU=CO&qt}egJ=2Uq( zOXFiyL?JCT_0Iv`iqC*tx5Xs&GC$UZ29$un)dX+^LrV3(x%&`e?G8AQkbx0^eRVI{LueckZEIHxDd6ATRJt{*j^qYnb@9()l2jRP|fQES>!-$9Z) zewj$<$}4#MC3?+QnaV)VX>d?s7M03o7tX6~SwT%O@q;jX{?{$8+v$w8!_r%f=8%~HUA^j7dF4Qd@M#-*UtA!j30@v47+VrGKjZ$Lq{>71tB%OqWcvoLnO`oew zleC$AK*Dc%vof@6>?B0>K}&&O5h9oqw=hVU6XSf_oq_RApPPqf$u$vlpQ`f#^lZPt z_FZEk~|#nPfre>l&IZj6blwHV+CXA{qdqYDy8Ebzh^e zRNN+rcHX+~f;=|CX(G8wgY9jb#J3dc7@fvhwhOgd`z$uTbLgp!687J!HcKS`Dqho{ z(3@$Bph2)S;(r+_P~H1}j*dX}OUx&0*3zP6hSBx}(zr6-0|!kQE$q0g2qIEN1x!t) zCMPFFC-sJ*5Ct1q`SO*Omo-{5KE#2o=|iiXir=I*rdD!^@u@fb125;Q2><5gy)~jk znu5ndWIZ?KOEeV^+UvFytX-DY$EUTmFWir`ahZM7Bhjug$2|PVlTxWCr;n)4{zp!K zPD&mo0xm{2V`c{!c_Ze#1Gwp^hC)7S!!lq-lB`4%b}8>1lzl+*o-UFNfEP=${>>n# z0;N58>Se=Nlv44%XEs!zMjfs2fy|8FtaGSy{QM@9QkU9oH!?su=|hz z=T?f3c9&eE@DKdbwrtU2WOx27C@|gflS>9TVf-@_*Zo&4@~Y49Ha(7Ti!z}1?-o0@ zacG^W^9f{YdZME_L)v~_5EGySD4#Dd04%(iqz{FqhhDOP;nj`E6oZK=#-YAGnTtnL zlW%e5cZtK3PrKNEzk7%IRM3t9iOv5Hh+1+lxTEXH`PJQ)=E2Q9Ibqx(8tL4&#l&>< zC#(eZSlm2S44UmfvYRD2&BF#(xvZEc-LM;T)aK^Tc;T@KvB!GstlBV8470bn|tx#vuxRw z)dTnJXVM+Y>&`bsQ;YBNqN)~acL?1TKFM0g?xWm-w!ZLn* zW(ETBE4s6%kFam~i75Yc;7z+4CX(j4y{B(>BTFFDB62j z3J=4NWISlgUMFRx@FjX}ui22mb3AD5bkQj`ZfllDs%l3bl8NSi`()^vsbEmD zOwN(7>pq@9+E)UMbhS}&Kr$MgE78QHtC|%9_4ACB`d&~xDiQnC>nM>_7L#^q!&JfG z_QLkz>RmH|bUCs+j2k|}EG25|#xaFDpG*_G9S7oPW;~TY{k;Du;U^!edf?!uwA3ux z$$#U1Ry4tgA)=tADAMddY_z%oSGTu4oAyZ9u}u3rM(a_}qDt&a$Oo<^{EdvsoJL2m z(_>{~XE50XsjN>#f#W1h(IoJjfRoV|gD!dw&wI_4&sz;)5wpM0=Z zvAwNt@;dds&cQ%?7$cFO(e9jgG`M!qGtAE! z$_9A@(ihcn<$D6N=~$of%YQgFL~%g>avEDwpE_L$`A+cmTgk8kOVevt3?sFksTaS$ zb#1GnDuY%P-zwf&0M*}jLkNMmif^8;hmcw}v9j{IF@O^!B(-eV6TKQ8+U%%8S@Vqw zZ}Um8fxBwifkFMZA*u(=2i^`ZR-w_m;Iw+7;0|b}ptfHDxA9~WS*oh{b=` z!t=+|TVHiq(e4(SFByf9)8O0NpBSmDUW+D9Z88;PeYO0}tHjv!^5>+pK(iG%AQ@?Z zq5w$${}<5x9)ih<`^16j8UZ3~vo~~gJalz2lt8%#$6YBe)ZKrVq^CqqswJx~C5nDxr!YRTEd~T9 zJ-Y9&g@Yc?8SE6$OTU!6ju=fJF?ZYla~;TZulRs;*B~k%?ceT9&iE^S_FFF$%)lju zIfpVb(<3;3@DGc1jesw$vA*E!=$80_%G$7P>#+t^BAGj1}N@{(^62 zl$+>c^QB@)TZlkw4z1u=-%XB<)Z7)3Km7Fxj1 zV-cqDXsjPuaL#;z6Dp(5lC8^)A1Xig7z;6V2gsCu@4+k`ym3M6Dgg{?_a~iUAO(8# zF!CBL(!{&xm!@+`M!fcjZ=?Pl+Y{aAJFZwl^SiX@dhaCarS6kFjP#rs*Rf;+ur$It zHy*5czJeWn6DNKS+AC>hlODB7O9JK#&@5tRzE3FyO*_LSP+UFSobK)ch+4tO@8&{~ zY)$aKfEpZ3+(20|9;dUFN;>gt4`{>;kB&0$8KqO%!(efvWJTiIy%qOOd1L34gx`h#1XKWu@K7QM2LcXjj2BL`%T@zWa8o^{fer!g#~j`FIoV3@Q=D(GpMq9 z{z6xTCq`B=TPi3#+;l0he76GFgiI;yHaZrxZ*-B?-iVuGo_rS{+x~{DOt*Kw#M3R| z<2tOzC7u+&LiO?6!fZ$wyZoj~;C$~7-0Zs~@ZHbZKvR*zKt-7hx`r@ed5RLYp@n#* z2`l!_>uXni!Q_MeMjX;_t226<1^EVurU$xfbqiOUC%$hh)ffmWt=ARh77}h`Q%A#J z-?HU=LSiE+8I{not;9H?Kb+O92@bd6n<#g}3J@Q#K;Y){YLhPt@ZG#{H?t0O-M|m) z3=gxqRHXnX$o-vl=D?pBk1e-YaQ1HeyW4%{4+iN}XLvfMi-7%o3Y6UOuNBGA{{hod zi_zlxzJI#DO~z6fUvspH1^D>+Sp;%_dg&%@A1#R_P4+sQH@)MeImmul6vTk=`N3Mr zkpc|1SLwlT-|7Jt{%7)97z+yG3fS-HL&|Cd*bF0ROr1}aPi}1f{(S=8U58tc7Dew4K2nka#l@zZuF~YvB1aZ8+7fCd)eky^CApi@~mf@6ZalVU6?d;|r%W@99%Yo1H_VSe z6Th&uni-w$ayI`-6=BfDD?f1SUY-&ekIA}sS;h5~^DC~FGhY${NjBbG^;f#`+y`RQ zO$}%)A1*He9iR~kRp4m*Sc8WPJShvsC~_x1&mR2B`@VV~@RL?5$6c>BNRQItPvb2n za0U5`2$r?(=oyv2?P%nrGbj}(sVJ%#*Ei+n##g`1qF*H{R8dPLZ_riw?uU;{B{Tg7 zc$Xor;=rE&zz?h7mFkpr)zIoxm5r{tI>988e~j4fiDM9E&?XO7ppJ~}VPyrsJzsjq zB`FWhq@oIpxCJ*=+5#HOA8G8v)1-Gf`GxL3jX5{B{I;B86+ldkiAJG%Jzdkoavz zI#qKh^f4`+sQ-rrxSB=oK9G@EHDka{d{ggtSJX%p6({|V*p^RYeF1`l1Q(1?BP!U+*<&7p}_sgk6K^c)%4u~V(<+7MyI zdF})G2~YX`tB7sjdLsPB|9@*guLtVX*kE$4UFWP_W8YR4fxNyi!g0s;a`HzFbp(jC&>;U>QU z=Xu}f{r2ULb0NpQ_Fi+%ImSKi*eI&d8tZu&_<{km3q@)93+F2;<*ZKXhdaI6*8EAy z9bfSVm2T*C!W?^4p2Fa(W@(@-XlS968wFsz3V?B>C&r-YyN6B!-0mV?8Fp&z3okYNI4d;~cin1B)EhIwC^F zeTF`j^>FUb>9;s1Az|)76Pmbo=niY@8Tr*|O987`$Y~8{Li1`(p@sD>bK`q9B}h@? zv#KjdtH`AdDmhLn>e*P?JdelK!A@s|o#z#{s9BF{&gUI!qlOmc(_^1eZS6ZZZ%nkm z!2zn3OYOx}-;t(9s~p8z3TFIECRNk`2a&NBd(zOfmMzgT`q`G zSF&CflHPR_2!8en^FF7DVbx0#<`2JQs9vyXmPr}e)#~Cb&MIYy^bwXKrjCa93O2te zO5Q>35((#ncCqVoq&ISIK!#w}JZv}WQdjZU(VD3u^`O+=`PwM~{7A~;Zp~0cS&OO>+ZY}9+83m|tnBQu zlKO8gtgVf&JV2hox#er1{_07Fn!H$5^kh6AtcTIVzpe!8`YizcZ39?bJ z7M;Da0P&);N}OM2iXi*O62Elt9nXj9tWSnZDL?w+{^)eoE2T9>MiyG!7|(vvKE ze48K!1W9bnEG!aoLy!IjgFamh3?|Gu+=WNOAaIM^9Mkg2j@mr|V>V4YazDDw*@p+& zq}SdXmNkQn zw8AMHR!DE~y}!tjY+YkYHuY3DoiG0(LuM0x$Zf+DN6L&Eog$;sRsZ(3N$S~s(e~uP zXLR%X0e+`RpA_lZ25AFsWDtC|%;iu%>$5TKay0QVplxhD_{`S#6p9cdbfyEY);c`2qeZs>3K?frii z7Zh;`JRjAz73**D9lF~SE7QG|78lW!rO6#wHBl!)D>rIE!ODfG#=4p$e$DS>`MF&O zi~<5hWPUp6;!o6QWMxCv@{l$htNDWLDMYCs#`4evO`ZPqRXjiRNk3p(wyqZW@_f!f z{W*Eaa;<6A9;Org6Y9cbI>|*tO_U)V{ zz7(LKpt$FUcnxxe`th$cD+0diT7(%gpYiU3qiIZ$a@(i6dFO>l78Q=~J;ZI^%vJ-i zH-;$)BO|f09IiBfn13|O=KmOuEM6+&h(8tFa3c>%=3nsw@e+EA>a-%xVys3K{Nodf zlT4Xczsgys*mT}PwbI)|g0?uJl)zKvCxlk+erQQ1n4|IHMeuPS{Nz3^NyfX=t7{;j z!oGTv{(GHK0JZY!sB#E=k_HYnSFhVa5L(Fw_S)9}x$Gikk%H+?r%nCg@RfE4c!^6( zC8;u)FuIwnak6^z<|)*3g_mc`!U-(8HBexWU3+*Km=l2&1XR>J{ia%`rZn(NXr5B ziS$ufa8?(1_W-vFdj9*Cu5w+h!}Z>0>$1&zQ;vdk0xbku;>0H4LNKvt@#R#*5ZL+g zZ+HG4`R3!K?UGvrCB;yA0FSThtj=xUm~HIh{B+ZqA5mHWa`u7mNmpu-tJkw91Up)k zNJto*YERH?#^t!D4*F$SA$CjXm_@JdqbxHXDskQowAO9!WB%T=2Cq}P5O**L?u)qE zquxy{btk(WC?vn>hRyT`u`DXZf%!e8*$2?NflX-z@U5ZEyUILB7S>T}x#PRN#lNg9A$S6kqJFJFUFh^eShxleHI{j#^W2U3d)hZ{&XP5+)fA%Sx8 z@c^*z4>cQXrugzyuVkP?ozOyo@#a`&D@xd7 zCOI(?adEmGi(%Y_V!Tv;JiRU`J?wL_pDvTYQmEgU#zf1$5CsXWltI0d)ee%D7*|yV zyk;dnD_cxrLMu{Hx`f9J`I^Dd)cZPIt%`a0O+fD;NnsuQuNu7gOYQnH#i6r;EYU~D z)840>^&^)ptlnUJ%a*0`tgHG zu^F6=fpB{MM-+ouzhP2ErQCT_t6Z!8^#qr_ZTexcPIU>0a0<06_f}*s$-NHxfEox3 zp-4>ymyAsQ=f&(jVT0jI2x$hQ7apr#SWiMgy@kH*Y2iuI-%bJigF7mRc?O-vSD8um$Zq=P;Ey>?sh6PPsjc3a6|Ky&gp zh3sSt7+ca#0CjFYN$yw7JrBM*h{&e<4Pa5(anYZY$0+?uW7APN`B_{UjzY#-Y`*!WCBObqhR zy33|JVb|iN%ZGK`4lWj92Mv`O8BOLKF%RJW;^X4(u5bYfUT>pbUPcBL5k^c%xZ3IU zKM5AT88D)zV`c^(5Ch@_h~V@ghwCH4=LZ9jBMWr&qN1&ict*&F0rRXwpPxw022Ti%HYY}M6=VvA zw7{m$$E4(Jw#g4ZUp+pQD&Q{|C2Fuk?8KLPj(@bRadj3MjJBD%l1*uHc#oh#XXFY! zDK@Qqowr5t*zt`O8}1Wn~mf7Y6Tz* z1H-|K+L`kR%{{QMJ>?$gV-ytBWr(jRFIQ7nhcoLLB{^e&h#?>>+P3vh&7gE;M|{yz zQ#uPvv&}!oq+`wiHIp9RZ7a2*mQnY=j6T@O-hY zvWEkGU{wcX1M~~$K(MybFfqwiFPQpf=x0WOoDBXxTzwu)PlLtSY^Mbjw%<{W_h-wz zFb?CsMr>dc0+vxtQWALJbI#V|h(8!z#>6bJxTVK+!&eFYb^Z@V@X*$8^!9={WKiz5 zLZI|4A3QK{KhD|}yzK|%xTA#~?Cp!3Snkb2tLhHNk>=+=Ai}$ZrvyDnG^Xzb^&31I!WX-d2m}IlcODq$JbU!031TiW z$c4@(W-f-YTWu<1FB2NY?TNxAR~ z(EU8sWqNg4;6`9ZX677dD?QJ4TbH{MMNyuJE18xe;Om12bET0Dwzi~Rq0@~RY8myf zFQEx7RJVHlx-hqzBGGLjTGIP$o;)`<7gVrs#o*`Xun(vETp*@{BAfrZ!ubLaVFUXY?fQEBFuE==h2 z*)8E8-IZukh&{Sj!I~P=F1y|bnU$U%F~f`C1Z1p7eI0E#%`9GK?8 z`Qh0-bbWOXnpI%ybDam?Fz`$sprY~8Dbymxv$2H;TNZK+EB?oCb|q%9QOjo&j`D>nk`R~wvL?r z*D_gn#~$D0Z6X%Og{@>BOyB~1X`d>84A2_ru}3fIAL#x0PxT5qbu~~f zOUuXrcZLBgnC@y96rLb_Gj)we{I>}*{U|>*L~XD^IvuIG19R3Hl$9IP?;2o4j&%FO z)zHfVir+vEz-0-z>}gT~q<;2@$8ja9+w>LaiG80@_nUJ-J{Wkf5lR)R?;|{6{)OdV z?MY5VG!C+26OQ|0c%iU~21x4HlJ~u`15fTK#m|C@d!$-7vgqKiy%y2`g zs1CyV+VcL;X4pBSZz+mU=x4|H`@fIxNK4jXiR)}(%Zp0kZNYl`k_t04;N}g5M>uo~ z_?$_9sAX`tr#QM-9cy)P62~`LYP(HJtG{w3v}|xBlA6Xgo7)qhp@+7N`8Zt6JXaSf z1k?wo2b`MV_;^DL_C;T&|EE)W`)oE=0)y(l$OA0IZ9-Dg?yS?V`$9ywukuyFVvP+% zI=`AIL;8C%K_&hz^<89m+W!v0c2}O#SHl4E0VmN&iO82{7%l60saUdc^fc0+v5iY` z^18&UNpX6+vnFlQLKUj%JGRIi!FNevC9B5(Go&^4pze=nMl#kPRvu05U&}7FIti~o zgsQK*6=e4qE(4Y43&mdp^^^xKzk=UGdEC*?A)teYM}ztxJ|0q z{NnMtvfxnDL1S7a=U&7TrAxJ|yqShrmDHoS17n&;1&1V72ZrtVG2%Bv&gS>&-bT%8 z7xqM;TWKT|#!m8m-P|0maF($uXt8ucc;2hV3nBEFFlI{?_DSQvGSj5M!50ZeyX&Xm z9okx!^6X2KIp~l;s+brY5>n&18gqPu;@f*M%B7$6U=X&lvh$*x9V45R$3iv!zj^l; zC4!DkXJ8wo`@>|lp#vr3ZZKhgO3Ei*@X5U6NEec6${07swrFi~KYh-rHU%frzG{k6 zXlBm2f{!FsKB#@ML@6$I#35tkw9N2JTLIJGU0jh2EjkqJV51g6Qb$z8*{<>!Aop2{ zj$@X*7Ej45lWKWYiaf~x*|>X*kDZcgE0vAa+7j@~BL2HpHkUdfF=Ik!3roU;0P1J z=)j~j6`mBeNU-XogkVTr)uBL93UNEo&Q_#DLygZ@jd>bunc+(teLov3x>K&a91=jf zyO~W>dzAIJ&CTsx-OdwK6g+I%62q*nzGAoA=N9iuGsNVV4~bIH(~76_B}C~`v6>q~AE;P9FsVvg|g6aR)(?^?6yJ)q{ zuc6;{p_@Us=xHJqqw@(=M!p@YnskSu+`qT7mOgZXdKqB|FcYY!|qK1{)V({n51cZ6E3 z_8ftlQKobu-oyq=WoU2KBvvpuBvwt@BzI3eue4j+D06n!tgU^0*DtktY*R=^h)OI| zIe3U6PwTOXmQ6rF`{SRBBH_NDA7W8{kOJlPyM&&E_x_Ym8;g1rHO#(NXExf4&rAs} zG+2&$j~54Lx{(JZ^S@Voj>%A^fSvMSF^g;I2@YRsQF%EhRO7Jc3JH<<9fxs&D8|SX z`ZEc4Z4fR!t`A-pwIE+S`_C8P$0d&E1#{B3p^U$&=(X*uAyLvYg};sbG6t>7GMpJO zS2mpO`Az@CBE<4I9*f1}W^z?eey425?t8Py)u}P1n_FmFF>srJ4dA6zB4K%U8y$1| zlHaBdT3sw;=~z2%%6ad5@mCxrbW304vX_^AoEY!Y)#Va4HsKg=FU)HnG^-Y)3=4~s z6sI?O75DUM$LPy!HZfxkUJ;RBdDx=4vd9{FR8-CR`CFawx(Tc<#Np_|#{BjW&3;`! z1E|XMgeV+%s7gvo#zHU-9NChL|Mlw^D0|rkK$d>BoAW(J&-UUVetmuJ8K}aUnkelc z=}MJ8SI)n|)-d~C{8Gz7H0bfS;`9j9axUU(ukmRvQ9?F-QliHXTSI;c2Z!@pa(IqU zDMf1F-F&OVA}fPRTiG5<$%I$izJMch8$F1TL)DUv(8}u2$>}8UuBZch<(mGcv&O5e z=t=2fmgvrw-Cc@TSc9*Ae`%AW!47VTc9zd1X{{ zQwpG;$So$KMyo(WDJ+>Slu)S;QV-;FrRfAdZC~URGzVwoz7x-Dm$Jb&-oyR-(EjZs zafWj_ow?T3%{x=6LWG>8KbGU9`^xg7RdU3r!jPXjPNdpYc5l58QU2I{B7;k+HZ;Y_ zIVH65s~3X_uXV9Ab>a8fiz8}kUJiOqc5fXBdX8)Nw}_=Q&5=|Rc<$zQTD`v+AFq4k zjq9AsJtQ5lbsp^-9(ION91xn=8twl6`~Y3yuzE%8yN8l`R!icI_KO|BZaMqba&X`X zMpPZzP;--WaX*SX>TAEezJGyKpbCWK9xx&|q_`wwDu z>qfm7q|UQtbkz%N?Z_l^7>qOLhB1QHU1)hp>3;tJz>gm_hqOqK@3dY z<+zNVS^K9p3#kdRFljssUKLx9I-@dj1D|6a6D6@X`26^zA&n3$|L$IC%32X+dZbp~Q! z^SQXNu;X4sRuMbmRTe(x*DsVGws*}?!~FWw|7Umf(^Y$u%7Hi2#wVZDf_g3_A{EB9 z8NYrw%`$?bN#*;lkL~MelVA9J1~XUy1cX_bD8iyok%Tkp zEPGN$-Q19sl-TMsa#5x0oAi|Xb+pERI$LhACzDD>a>i)Oh8Zn&ef%n0IJMQ*6QSF{ zw7L@=*c_Cc1g8u#k{zjK{>$P1e*1$JrOF9G?=#nM35QlvmyPNAQ>gV}7To}KBXkcS zclfzZh&Esk!dA$hJY|0i9#$EO=3EY$W_RO`W`Db1EhS$HFr0qk3Y;Vbqd9~?T2!k? zVcy?3WZaZ2)u85GBhgL2r&85lS*S;TsfRn*D3 z1CWtvPncefv8-#APH`pbzrj@%=AcN9mrPZGcDJah`Rrxn9`tqxYqW{e(0m4yCq+58uPAqiY`c7gORNQD;q35X zA58cuVxu?19^I#=$^XDgoXq!pU}*Cb9pLgyenD#~^4t?{cVa?9(Cua9(RJ+x2i zoV3LBY&@Ir)jW;{cM+cI%Ht3#z&LRSX$zLP22W}atZvv=AO+3|<|z#EmWaJY!2Th6 zZe-Qb+U%ZaRAORcYAQ2csGB3X`LemY;N9eN*0`fjS0(^Rm{nZ1)3P~$2@&*@6a{2{ zv6Yli_|SO=XWL2laem&XN*8UXnGu@%h`McY3+)sqTrS25!sk1)`)-w!DFU{7I+D3+ zOb^reXTF&!z?wGVFMg(`J0)&oVev2&kETXOfxOxg;?diCtVwPyRFZ%xv2n#d&zB^Qt~o@_XvT z+kU~=^F^es|A!0EJUqoGPlxrfyJr}$^B#GMtySr_RMjVRthTh3ybg08Sb#2`3bg4# zzkBO0II6p@-mi6F*cJjRCzvnPdmNuQ)FS=x`jR(C;@4ycjXgk(97LLI!RqkR(i)$f z>~enh#FvoW6sY%t0s<+BQs6+>>A@nR!45pGgVytz|MhBlLPQlzz22PV$faG~Qj$yD zSQ~U>baLxh+p(7_3>Vq$I6$&)Xu3n)#|V>zE<~%E(xN@)*AiZ=D%HteXs20EMM%hG{$D`om(_%@WrKP=6ZJj)m!+ zfH2830>V&KM8<7133&3AeP9fg7WmLq1JN_A>s#tPow#1yi&&cIJTqiBW|;D^>Nj+G zE-&AY3DYaac;9oNIL^zccumMdLx%l){bf$Sc}t99^h*41fHv=rR2J7dl!#?jIaTI_h}8{MQb|g52%moK zx9z6fboO}lD$A$h4$|A3oN7AYhRp)mG)hWO!SC;?9K}TmAPT2RR@c_{Snbb-`G$5O zLERvPBfPe>TmxgAIO%LNL+}H07)tB<_Hn`&)HTR#x_K07obO+*}SZN{NR z5Pozl%v0%T(Z4bFrqr|rKx_;ly4*A63D3Vj@ARq#{Q4ypk_pKaQ#Qv;z?=o)T_R{v zE61$6fHQBBKk&}U1Q1=W`7YEfh=afBH?UeK_1Ja>Ru8D6P3{K2_{^+VSCs_H*MJNo z32-D60f64#-X7dY%`zr7p#Z72UqrcLb>I!4vVnL-1~|*HeTJCuXs|32X5f8{0#R%`-C~lko81XD`BXOB<86<#=|@bB7&CiSCMH;er>wS_{ ze-E6<x%}gh1Mfuhmr$9lKfTJai}dnSd=!`WJ< z;Bd!qrm|)lJP{&o`gN6+=k{lx-x^YV!WRtVvp#c2x2bc8dZ9@d!3;T6d|d`eBM`tp ze*6eppsR*YbofAk;s5GK{(xuh{|ZQ+4}7?K#<0ln@bEx*VBDJcJ>tZHFBKd$z_+w3 zP5^fVg_tgYVg-!&j|2Z7Y*t*JvgWww$I&-W(&{ z<7J|v@{hA9VYN(xq)gpcPal=&zpi(5M9XJ9LSjI>GM$;Ufe&Iq4$9>dmsQ%=YO)6&d5VjZntap z(`K~sj%Zwiwu3t&a&h#oI0`-ZaY^CR_xzRCzmCOWXC|^}Sg)_mf>3B?)pPG!U?Pek z-e6v=lQ=nUYGc6#gXuM|mjo30o|=bk$Lv2vs2!HgBXL(<8yL}`KEC<(S?<7_()acZ zs>a4tkwTfg@k8eK|A)jC9qWJm_I^5*zv2b*ka$6UzR{Hq1ze-y@P`z3i^S(SY>8hl zZ;4Yr9PphFOt$Nna_H!TTmvwWID=`{$Q=7@Jg#IN|)wJ zWVD^`GpzsIp9r)zhONfmE>Ql59EOwdpB#mE%+2o#6THvqE)w1Q9h?Dm!69KwwaaxS@y=KCKM@{#3U{h9_2QWk!{!b5CbDs!~WiMJ9$2&w4@I6D%Sk zw0r2oa?+tMOQ?2NzSHRI2Ge-*3*d4`J|_>H>%;e~a^tz@@}E*AZsoVt^Ka~Z0w~jp->QiGYD(9W)&J61c($}_($*2Wub^|RCm`!T3CW|EPa7MOfVU6z98i^D{99C>Bm3x22$jf<;_;5Y zzgiT&s$*a6-#!s%VB|_JI@AqjN`Lz5HJIk;j` z0DvVPAt7kpM&w09?e+deN$<}k(Q(kSVSpurK@S)w~P0HNlZ+#rf&X z0#^zt0p;H0k>iglyT8EtV`pQtU+y(qdl*G@xAHtSi*Qd%qG+|zpC;dX*#bu(oIU5%@RR~RHS{a?}>UbNpl=Jiy zadeb*cmI8`x(W&OZd=u6PBl4Aw-Jr=j?;3thE=;iK4oXM~tenmK_YnGjgU0x3>emY>YO#c)ouz;zcZFYdGrSuBD{A_8-YBn7pAxvPa)~`Q|Lf zm0aQ~-`pCsJ6A96AA_p9h%?Br=@q{8{LGyIUw2B1=j@NS`S}c{FTP0q%K9R|{C-5W zI;BT9ARz6xXr%Dr;O`(Zts48qS*!fPjEpzP$WW^J&8$2jn`2zyEdSVzO(S1tvN?X` z#@AaPn!p+v5kBPN5-KKI%Y$7oBq1gdBJuTMS^{6HJVpI>hKONqr}zhOmxY*9)dMQ?}}lwUfDhgju(9 zfM9VHOiM;8i>a*MZR%jT_DkDFbD&WjU;~rBzNhZzQIP}w{!d}e2w5|EAojA;&o}7x z#fd-H@QEIMbq&{ATi(1G9Um`#1qngan37Rj;Ki-y zjo9CuC_apumyEpF%1#Ko+nm%Anz$L$Ex7j!o4Z(-nCu~h{sLJpK0hAcPP;3$ZnH-GtZJLq7VG$iw2YU&i+7>9bjCDOu&DyNPnZM~ZXco%{xx%UPI_y5g{ zOGcpC<6j(3dnA^c<;o@Y507^U{5c)@jzKIqp4h$_aUZ$8#=_gt@!+sCLyF31I{NHc zwz6EBfE#Q87h^g;AaFN4=&bid>;c{`l)k-xV+|ZXnJXtn5a)IccrnOsj51Q@v#7G} z_1zfS;P~`zsK6G)aL*+qa&p5}y)RPNM{EID08c5wZ7iqq#>?~KJXA# zmE2fKQh};o?6r$i?$4jYAobKvM8pVqt=okQi`_m8(XA>f0~gyoL+i(z6X$39pwZ7E zKbsA<^*J@%6NwtS*a;Gj)izmNR4e$fx6*LC@wi@+o!yKc=RiAUOjXD8EYjzURP!zJ z>Cptae7ewls>{Wj{qBO+2st2E7?Zg&!)C;~U9%2$4k{ReWzk}fWu(-N*MR~#`R%Ws zX)yOeU|L0mdI39?SpSg8F&oia1yUqCa4CR&=(^D^0~-LqI)TInFJDnO6Yp{Mx5;3? z*l)%Q5TOuPg0AU1t$YnXf2x3w{vHkmV*?XTDIL=NcCS!>G zn?gRO>ceLNsO4Ilk>qZl_xiI1`CVc-_wks_zZMH?XstQ&^`;BTko_BU=%uEjN#k{r z9vS5^-59l4T^06R%Nt%=%6u$YbQm>_BfZ!O%*9E!eR%KVt#Om5$*tKr^0G3gW5wRt zstlLl@sY-!JK|@G4o=RpGRqmRpdU|MAxAc)GU1 z<*atQA@Ubhv4OZa?*JJiyTefu=Xz$=D>66ZeZ;;QDvD4lFFTA2-x5lM5uDjFt zucf$rylQPNzocZ}v%z4gs|&G@4>0oiie#iaLqS_Xy5vM& ztG$K1;1MYZ`kjdsV~l<+&D@jm;ES<{+;059-$3LSR&E8qABJd zrR@e54*v_4^=xKsT zTAbhyMLLQ6J`Gw~FOu1)*%;Oqg0X$P7IBxR!)FlkVd~o7UQe(KpHY;GWvJR9CT2{# zQ$1#GVF+Aql(L@x#VD|?eQl$sS1NyeFdymhb9iL90kKvfJ5R9})d&VZ3wbJ~4i2G^ zroKbr#YgP9^Eb$>JJBJpE+r4+6`s)1LM$#6bD90q#o z#k9k96MKa4#a=>!zUx~}DYC;{4gFMJt6?uXd%W$^iPu2bM+GYR-*U3O#f0?UWS4;yUS42_n=yoMRn2b&V-K+CF`XU^yso#( zkBL>;s$SM+OWYv8bluNRxM*Xdige#?VJ0NhJf3O%+s&;%Q|~b{Ve3PHjXmK(P$-v7 zMk&*l4tXSxO@l=;JP(H&AsJ#Bc0l-q!mse8v-|hLuJ*8?XFT^0D;v+B@cMzoR5uF+U9B zx)z&Ut(@5q8IE*+X*oF{N?jbD;xWRDfx(?hfC0>LcO=dzOQ0yI^WWh0uIELj{9 zzDz_oG{sQEQ`{{lM_zx~VCGfYuKLaEwCvy@Y`vlyF?|c;z`JcRBm_p{(Mn2wT@3u( zBXUamTcb*2>xq{WR>jO(71pvwb3dtN8vbptoBoA^PH;0*J|WJrqEhCwa=ez;`M(8< z<(`ywI5svnD=!f)jgMvUnDylWX6#K9;*{XsUv8zPQP*vdt=Q6R& zL4I}Y$B~L!?rRHOCj0=F|{qk=X3FMZ?6Pj-}5h@2OkxRc&`ji zLMSs{v3u6x=zmzBTt}nA&705uz|83Cwj=%c;>Thl!CN^Yr*{ri?8=G?WgHXd+J83E zf7f^IPuP=XdoK@iYa1`z_p>6WYYm&H)<-mS8_pIZ(%u@YT9$(s0Prl`_l&oLI5;^7 z!X?TjVtGBB+jr-01(I?b{uCtU>VjzR;P7}x95CvU(u|&^$=dC23H4HbZS`7CR$5wC z-t+^{hI34qS%5<}(6Tw11U#Rp8F@5Z@I7W^G`l!!tlL8wi-w9PRZnVsv7(x5noo!w_Tod8>L>j(X9lsvt|65bB3_d%l-7rE)cRQD9}=G1`6J| zTM4vqwjovL+H;5=FyJR`1R~e()*%0Y7w4tbZEaG~QiI@vvot@4Wz99Q*vWly=f~Dm zEgM^jy~A?-?(YKlrgP*|rw0eWS&e913VXQRoRRQa4%hErX<+WGu%?aJeq4dAA1umZ z|0a;?nePWYx(5Me*#fV}F8hI#d@j6kf#qSTN1ygUL@O1oN}%kxnEHrx)f;ok76T*jCy)- zUpcyVDByg~po{k1&b81sFT=h&wgACnljGwxmO~7w@(Jcy)8X7MTRNsoz(O~yj2UHr zP{mkqn~*SnbW%riEJcydaj9#@ohJI2FS6C4#pe**C5m)CK-RYk|AVfkW)@IR5DUer zso%X*V-lpE5LD&(i0GLJrE5IGjLMrL>z?^!Y)mJZ_GxV65b-nkY|iA)N&5557c1nY zNWTQL`bH-vI?uxXYoH9w%~uL5r(uU>{hgHeKH4CP7L!Wu+~WIhkMnqqaV>3d-z7io zacN6Oubo;y%ppW`D9Ha^{2?t7pb<$436`OZwWXl~m~M3T3O8m}99=lAr@7AsUs#dI zciWWG$925R%-ls?LDJ$2V7p$%Fs&!Ej`J1n83x<7UPZB?tTFO1!GJQnQ z)zkU7QpnrQSw2FFYHf4X@R&u1I#p@`eIP=yjopU0RI3mKOE4+IfK-P(TjqJ1c+0X> z-~zp|G;bgPq409gn2O4Rbaq=*PSu|9$CPca?exx0P_d1)I9{ng0q`s(}j#zNHrG|KTuwL*v@xc1D2&{HsY-R0j zBk&4kPnP_Mt~O#e|GO0uKcVK&RktE@TlkI~ASdBmK|_+sUu)fmV*UP!yw|ck(nse% zVEumm!d(9O*X|MKC=BaQw;OFMCtCGemiO=Z-4Kd2gN&OXaKLzk^g`^pYVa#fWev&J zTHAWu`*%ksoisLo26#AcZCKkX$S7Ry`C&v9KGvXXD_71t7!|(A6yW7`I}@n30)wrt zbhkTqaEFHQfpXx(*3|b{lJ4#7QMpxnBdPYkmHEit6wZRmT91uis<8(r>6epz!|H-Q z-bqb6;;-iYpQ95VdK{xC$yOr}3&X8=G5P9~o(^;*WS5Wbi)Svp$wL3V#G;d}8a;}O zf`0o9UvCJ6RKJOB#m>8A2LfISoM6dxDJcX73QP$)hYo2gXQtO^M|a|0o)lkR%=+o? zpL*HW?Gg=;uFW>N7mw5$waCeQV5&9xxzt_k>{vE5*rgyR$M0VD=BJcb*vW~PpI^@8 zCx!Vx;jsL>e?aSeBbjxYc<1cK1%PrbDh6CFx~x z(NIF;*$^(HdUOd?JGn2K)YLeMxxG(2E;rV2@K=8s<(Cf;75?~r-*MxvFRI~z@b%sC z_4lJN!TL37Ah)@>d3cx=WW`#e)i}etuF$F1F7NLA)^uT2b+l)wPv>;3MgM86@nvkUXPP zXRYaBRUpe!oG7fH-RF65amsq}7o*Ek^wzDWX9fs4?snXe&!4GE1h`!OGMI$46xmg6 z8!@ZZNkwJ?W(=SYlpDZ+@F!9Tt1cBvkK7a)eY3YamMUy6PL;FTilHZuUGRALt8}Dd%C+l zj>hzT4*G_X-`Z4KU0!(Ixf5V4I#p`6EN)v?S~@?Zq3^xdo_qCNQOkU&C{G1t*wE1a zkmX?zx%bXbR3H9Znm)kN+k9X(GA(W+ldb%Evg)sb&&fQPVumr%v!+i>dWQ7ktE#I* z{1+*o<7}dtw_6K;a=QMG&qZ%>>jjl9*hSQ26%_0j=${jfl})>^`+&_Ym#ud^j?Z!` z*aSvwOjIuOk@fE~FevL5eUhi;ce13)(90)jIuK~47pHjhDI4Wc+UwD8Z#~H@ZEU7N zzB*BUy_TMR1qprSM7>#WTAB<7i6mO!JE5eb0KYLT3nuOS_my0>EG*2aKs>z#icD|B zBDv>rZKN>5cxjPIHhOit&EP((7QibsrVgEFm7cdlesH&3_v{=Od$htb&&U zZh!EYb=^ zDP34qIR-dYSn;yKVkMSC-CcDv+vH?q`30vt)yv*iZ0F6h_RuR}hqjcsA0`E$CV>2X znodhgUf=R#Ln?pejQ4302+%zb`YL3mwvufdq zq4x4(f___fH!Ev;ay)0~DqFejOj>T*$pyB8XX96EdAK_(+LLWNATmM#=H0c~VDGRu zSsgzwiH>#~^3`&N3PxhSzz}Dh*w#7%=dyiok#V?C`?BqEBqtYHb<$|(M`7XSWsKpG zV}vI~nQF`Qu*^0+(j1n4R^K<>TS&6FWmi2c)fK6OMY|%b3sP&AfgsfP0Hk&2;Jl5s zX-xd)mRCNH3Al(sOL2aFK2f2&_hZFLv0w;*6woB01c)T)$L6eVXA_nD>SwnZu@cRp z8%7G2pv5{DU`$xry|}zc>ydFRAYug~V8KufYvI!`;Z^ey{9tN1M&z~uI!Km8u#1H5 zn_tC+F=dKB_BioggH}p>wmr`oYaPL2FBPU!sZ7kap8jXm_i2d3zBDq)GOhgKB3+pr zm~aE&qlA3>J&UsoHZuD1m69J`Qar!!qtRo}Y&f670HkPCw#9tc)!5TJT1RL|?YSr8 zhxRFsP4u7%FMM)K`!KE6V71=w>gd638nb z%(8VXc03}rv9EoqP9Xb?D>#j8xxvdT+oVR@wo}l_eRR7q-`Vkfy-8=uXXOk%R-fGf z73-0hDiF=OML+gfnYo30lUWUE_iIs6#3t7DXY*Z`h>2$Js0u5IvOwq9tB@VXRD&!ZPILom_?egibYh@Nc`t$k|M}&1a3-B}hGNv} z0yw4O=5;LEU;UjCV@S?w7TGaYb*4m~w~w)F%-g7sOY}n(c8biHTs1nz^9xJEkY3te z^n^ialwV&mZiLv=qjOA>D^B|JAc*FVwzpG_*~AiF%1(J{{QdLE%%H7&ePHXmX}~W-W%ASp+cShjNm03eH6p=1u0`&VKz{$FEIbzTf3NQPLW8lz?Y=RH>1G2X1Saf$ zO+WJTFN+$Za~Z%Htj}m4P?bUXfp3N<0GDLU;Zu9KV6_%A->m$&Nnw6}_g(0^zzr2^B-)BQF~uyfR|9a#_WC~kBcDOpfKIxaC9Uo_oZAAW9=dsPKo=3I18X_#@GikINE_~9}o#5ap3G!CC zN0?#-ws`lpADLy%d2=_7(HTA=Nb$sc82|3-MvHR;01J+lK!VX%ks0Es@%!(-!#5k! zLYI{Df+$g5C?whC$ySzY^sOY#JK{e&`(tY(fkx&K8jC0bkB^(2sX%8H^aCa z{`Ohu2t-l3l1z`!pDGd@ANRW`SDlgHv>>nHs{LS!T%0po{j8NLE z#Cm^ez^qq`)-h&wX_#zAsZUT47p^xUYtG~9dY_k-T(5snVxP?IBU&emXd+vQP^R)_ zOlwI#%1ayXjj_2UN!2wA?ZO}`;Ny*MJ%q!+pC~iq(fzhS-o-_FYy9{>Ta7->?lqK} zw5N@i#~XdDfjL`&ToNFkR+y4Q`oTeMT>C$7^1d9twdlO&zXr9Kvv@-3{~uXr8CTWX zwR=o8WbT}7(k>>W=Z*CXuRABP^-P=aY; z6aHETeDjdZ2^*gAfWLpfO4LP?D3}Chv~PtMPU-hWOAfE@!<%0CMJ76i3U^I3bNV*% zD_@dgorQI}{ZKaU$;-veUrOgu?VL)=_*+fW-<`E@W`9(ux=1rf9xRlPY})+}>3pvs zm-4G`fGzAQN9wq~L~dxH7+h&`xDsp%P6t(0!&Z;VwEtyUGPmK63#|p~&|n0tdPF@W zBh>QKp#eOK2DUBH$-UL@MG2|hYJ;gIXLjbMRd3g14A}yaa#*wM-QiU z=UyFmDQ{0V@ewDR6a?PL>gUa=x{89hbMmiv3dNA=?c=kl$1^N@+tx|h__*4I!w#*B zMs*A`#iz(>z^#3kfLZjAR~B}^PnMB7%OHy-qU-w>#Uu3+-UuelfE zf%XR*ZWsX!_b^?Y`KG3R5o7d!F*gxEq(G_0`+Ls8jin*QWV{w%HE6*aCu#aT=XQ4X zdFvJ@`c*46RITzy>LSWi{fe2oxA*H>^&LOHUTd@BqnE>WIUL!l<y@63>K`%GMgl#X}LFeb_*1tW8X_mv$h((e)pkJpPiJVB&k{c)nHSImf+j~ zAr{Q6o7NHheZC1~3D4qu9^Sq*HHnMI_7dVgPZV~v@qJ71ae&9tkt4*tPjF(!c~+7~ z2CeM;Wzj{vE?cHJOweL(`j-f6}5{;qhnRv$9G6=SG?Kj3XHB zmal(HJi!xdCRbu?*Q|0PNOXEBpkw*^|n4CKLc+~0~y8z*#Y9p^ucxUUR+~f3*!vdx8 znsIVknq01zm)DmjbCelgcK!;DfnGZVw>W&tvB8B z?EFPx_y%!JalMR4(<5rmXNz_xi}w9*@3yg>tu8cwAd&4xh=KD2o4rv)tc8qy2cD=^${xQO)SuQANHF`@OG}wh2^* z$wRYkxzB>aZV{S1(0mk~>*lbO&8iu9&`#)&^)C01^Q}5D`v@7jg8WAVJ)E7{nRX1H z6oO$D0aFIy+9; zKL-}~O0|i4Wc4nr5-Xh7O0vQsroe;6Bu~OwOwzggk{aiD1awLPG5gK7dPPhMe z<=#Yp_Pu$~5ZlJ4Ov5VUXO;4=fV1Xs6O+rnpUq?>?wm9j4U(QdQok|3h*EvP=C}4C zCjR=t2S?hFMAL9y?^)a9Cw`UAjTyOglUrGYJ@QTGmGzva;z@E?Jlt4rf=`^K-!-gT z^{$Ve@Ga&)y)(Uh%dH_pkD}aGcWbtdu1cUY^$`<_Z#OLB$AX3b>xj1+{u^(SzNR#u zNn)4aJLJ26&99mIM1?Zk$3tn?s^%sC_GRB6~u zGtXxOt3pf5vQ#0<$v^t0s;U-FPD%WdYsw4E@qHRTF0+X*_7XXlI9aHvmw2}h)fGN4 zv;K;Wp#cGJUN;-=%^0bj{M?HyUChezgv1UEwn1|^w5*MO+wqRDqEd*%gT(2BgB<|+ zz(;{PBl4rikeEYOiek95#T>smW*|X(7}1jhR&3IN1m#e4^C?r!|a|Q&Kp= z#{{hI-yeER@zticKPrl>;i#aNc`OV@KNThm%d#|HKF_nGh~ZEe9APkugW{g+uZeY*LT1r&URc=1{#8Gc{fi@^sru?+lS%4&kTqyGcwF;vk+5L`ls7%Kgzk> z6eEi%bOk(|OMTfSpGR6&{5sy_ShTk=`Z_+myt3s&{Eijj+h#KVq77f{CZ@Ulvsw;+ zEsj`D4%MqyrdKhyuM6g@NN(o3eMJnJSPNOgxCtrdFGP+X1~j(*t~&_B8A70bX+_w| z2WjG6NGrg@GZ9ci9JIFy$8*lFWhiuVrD^YL?Dp{gC>saZ%)7))66DX;x)T`V*QJO3 z_7~TA<6!-`ev@iegIFpT=`JDDf;1O#^t8{f4GVj|K6fE2H4HT|dR+YOg++VgoTuhD zuWM)Ev@ai^pOw7Fd{nD_PX;qLU`O_azkeDO#Tz_4x}xd@t>xbH(`!a27ydat64sSW zf6&*X!Wd(aFFIp?Juq;htt~BsGJJH7h-fFFH_JcyYqp+_Qj|(z?C)sfS|f9dkf$Z_ zdAZ*^wLg!0*~nAOu_H{MkA|7S+ zyZhDPi(H;Gu|!t?jey}lXq{p0Jdaq@FYAFvbOW_BhUj~^Oh@>x1p8&m@e%JMCJHAq zPMETNO(ds46&d!9OVWfD;Yt@SDJ@OX^mEZ(y=bAWu-)oWG!X}wR}5by{7po)t~f*t zkYP6%lU+1hG%Dund{lWW8k3Ysz%a->_TXmtMnjNWsvqy)yF@0y1A-8a#{xcQ5-la(UDUX(wsozWJR9d1<-4Xqk?0 zqlUR)U4Un>jQ0umttege!)JHiE9R>#kVUQrY`pBjfEmD^^lYoLQ9;}%CV@dgFt^mR zg^Ju(zp^ZS&JWM660m|Wq6XJIN9&;kojfi^QAWfYw$3Oi)9yw0NXZ_;&)N^pQdvle zF^-M}y?J|X?U?OOr0iFRyJ@{+jSt7pdWSLB96<89Yk@AlEl9Q}JwJaJURI5Ql%5r3 zqZ6aVmxAsW^i3k77ez93F_Hjz5I5+omtj@u6ua7zql0I3+&(_jF!gzu#E$=33yz!d z4ytFP0>h2#ZDjJ2ta)Zhl^W-;zFRW-y|u5=#hW*8IHP|XCYNXX1~Vh2+Q3go_M<4| zBx#}s_Mlt`mT|0QrHIvX(GjahFgg*IOn3v;;KjzEVXa*x6`OmJQvN`S1UMTP(js;y z+ZjTn-s)ZKpPqyHhrhpnk0WTj2@a9VvKmhC$Bysri*4+m@_SA}K=C|=U6-jhR?;;1 ztA*6PY_~?qX@3-1bP3auBAzF2QDIHUN0!|5d}6oHH*<(~HYu!|+&8{SB2+grqJRVM zJ&y6brhCGjt6e<`*{?pn<>44&lw!SW5uN?~Iqo}+PeYOeOkb2}m6$|l+55I`?YU7d zrE|>Zu{Y#*GBc89KBLrNSh$6H*8fCB{Bl{0HH))_;y#f_!162f)MDSZS?C@-}d%)XXlMXj{9L}-ZrUR2eo|EFai0EjmCBzrfXJJ+hPEf(F%ky&Oo}N-BJ0?&1+g{ee=0B|5|Q`6Jk6j$bV)?YKgec+!v@L-J5)^v zEu7$QEFOu2+in<`jU7NdQB2KB?-1(?CoT`x723tU{6c}NKrC^~n!Hm#Yv;@N2B(15~}2neMajB4Vp5ixxUUZ}pBl^2+5 zq#9iNGoYiRBhJCO?&*N)oSy1LcQ>6 zN;(nlNwqFwYiDP-TXm18bG}dTK~K7Uji8W_5Ou2_JNqrLv++hfR*@ZAUt3$-*r4T1 znY{O(Qk+&WMo^ngl>n2XkqB84{J7WzO5+|A&b)%BD)r*p)0CLu9nUT(-3k-W?%;@O zH<*`eYm=7@lf(k{^|Omy!pA~4^;vG$*k1@lS9w)cJk*{r6zAK|ZC;ltwsu|G2mMbm z=(`!$*oHIga>pOn?#41iO2#-%z1cbM6nNR^2F0!DrXtbDjpgMM+f@Enek43JG!eD8 z=V1HQAL91WJZV#yjVYXExRUu_fo@@kg&M;x1&X{X@PNbpmKtlj^eRh^yf2g9|_b%c_}HXaA!F=Y`12&NZoh6At22H zz~3@ez0OuF)!(BM_9Zz4X;Stu)$en3 z8b(|&Olv;R`Bi^o_h^sm+O;^*h@gh7tStEJ8Xl|v{YI;?^0$z7`(`1VsH9W`py4v8}u|NH6`sC7N!aN;GkBD{)2{kLiX zRG7cpS>im4stgGrE2l=HpskU{`zjMwPJ4k~7^49|2o~=UzZ1__i7EnATKwv!$(NTS z#Q+ig`{8}ZhgC!UdPAcc`@iwM9&iyg06_#llQF~~E(LI%EB#qO7F;JlBiubbe|HC_ z*kfa3LCjq^I5af$1N46b`N|7#Zw0kMhWei`CanNOolds2iy>HrK=Y~!dRizWAnXPB z0ie(pb!A&TTe*v54pwQ-%Vlg4uo7d;0Oinz~@>0oz711ZFZ{c*#L7y{u}E5 zBg3ErBq=DTfqT}IE}pgX4-UEh;`;CcAOrys2lU?r9$T{GGU!Hv+!{;@=;hOl>X42Q z)f`Y}f`2NDQbhtGPxrS*tW-PZHQu!DMNob#YYjV=zM2;&1BCdh>i$_hz#4w? z;>8e*|FAk)D}H?wz#4D4x74ewMTlY-@4Imoh2l$0d_0?WZHzfgPsu<(8!ah6x2~n7 z#bwHE8GcxO=ZE)$gM%Q+tnCT^kCY#U;(e-+$B@Ant@9HuS)@_2vf6DFJ94PpJzj?f z<&Sg`U8dNmV}R{#Ow>eggtSf^Mf_I_Kw*J>pP!4D*A+mFV3Y(?u91?C3!RaEepf2j zVBz_Ow*6gr>`vf-V8tlKNQSf61#pTk{(#CjI znf9%c%uE9qae6wtGX5juSx^EiFOEFyz*SbG(2uhKu}XZrgm5^BzowDJ%>R;!zs8JO zfuP(KoE01>RyfR(F4oKX43r1CN}bkTR7#@+GlpHDqkK^Ss}W`8Hc$Rz&^GtW;FomL z_q$AcxwyI}^eiteMbQJx;;{|5MhJYx3{}{jdrC;^WiDj9V+|fWvWR%~ z4vUI3VK06Y~q)^+#@^%0Pl;VPgv?JkIF>$CnXSbb}C2 zOd+>j8qW0C*mj$Ta1rcJoJ7UN(f$_n9;W~Tx_r`xyy;EuDi}rtwCPt$T}3JW`?f*- z=3`Nj@mR>q$h5Q{VWJaLQ)HNEqfFOEpji36CxYb(4el3BDmo@ zm{*G{NOvC-k0zutiDM-PJ$55ok_v{UA#;r+9YNB_Mw zl3ZX81B;6k8&I9gMuG5^zMB7O*tsgzS%QS`*i-oLf%=ZedC9*^qJ@k5(QikHrP^j^ z#^^%+HS&_c)eO8Ap^*cPp2z|%R>DjJf(mm49UVp=MP@FSRO@md&RZ-h#Sn#Td<=X~ zKT(Pg#jH{=S^QCto%fO6fYY-9DA!*}at?a-Ucrp!9w{c;$@xXgPmwT$FiT}&S48)s zk=ngjhV@j4iP6M%R3ZLmRALZk;~=7qew&ReMU^3H;3vs|^OnKSm;M8){V35p@j8px zvu`Bb!2e(njn1DY-#vXQtlPPE%WdLGyugg}^%Mxk?`*rWx=_7cJ$gwQa{8YD5^TpJ zs-L6nh>L7&{|&)e3ZO^oDd+?h2UYGNDaz8fnNA11FaHK= z&RMQmMar+K^6MoZFh)o@(Eh@?kNvZrJ)BM#`>7|t4B}#2wW=rLfI(lS;3*y@nOEkq zN&lQQEY^X2GerJ^h< zaP9leXr5Av;AMI>f{-e^%`?rHVEagacgt0O2`e2t^3sgI=N4K~7k`E?ZukrF7jqB0 zj97%#sXmx-%#=zfZ4&bSNW<2}b zZ%nFX$Y`4lmeNJfLp+~D29B?oAet-H#OFkL7#S614{+ix^wxbUJPaq8=H9Ze`P}j3 zZ-s`t!yGfK(cjDGXfUs8rZ$~J8BKjWY7(l5VX`}E_E(S@SP=`~6YtN;n0?8lrrBG9o`~W<88iFXNtA0PXKYQpk3$d>}N)&8p@M~;r zrU{RA_^nUgw{_@HR8Sorayp4>n)Sx8Ba)s`gG~e()b8MkIe+ZwfvHSTF=XN2LWlvZ zcSLY>Q7_#8@4NPjKn%h4Jo)T{s$lU{%h7uSadT%;8R2*SE;x!`!hoU3tdeBRRFTkk z7-TNbOEZ7V{k-u-cpYMG^^e=+a)$;=@x$PD5Z?Hy=+MMVAIE4sW>IArHY!Wj#URu*n`DsrS;{p+u2uj?yQkw*yRXHK_I7ZD?t`qMSHFVkq$#VyV7}#-_0@ zt8TYHm13AX+~;+7Ptjgp2d$#@qsxjZ((&7;v;h*DN89%Ao&E*r_&LH$VDHX3q!bHN ze~F2s!^0gmLO6yn@lXtsF8R6HpMIY~vEs)q3C0P(tK%6s%k3sTgj$WBl!!s@1ddP6fl0=>iC6_RX z%sTaZA7WwA+`*npSoh~V_RdkcFL+*xQr$7;;6o3Zpo_M&`za*2Ua8^r@Zg#*5X(yCQSz|L^PN`0mKA!C7jSFU0`BZ9qX={X?-Uzs_AvR!#D7au@C;xp|c1 z`J|!aV&ZW+AG>z=&8Jm;60BR{n0=}Y@dXv;29Zw~PE4PDyOKBWm0UyE_u#Q-WYAFlX&n7)t@P3%(7~uJjtK;K&75{(>_YtPsO>ARhhPl7=_t4w)(?ueps9fqcOf`G&r&boT zYT}{qgkA}!|2bqrNeGkUSlxJO3y$rC00j2{ujzjY?N$2nBXB^5;SnWarLQO~!Q|EPP<%6va5R7tq$Uwq^cjhFv#B;J0H$ zw@?=&+S_cI;-lM%XUCKXMZql;goJotW-Y&y&byYy-Eil)ImB~~(R}4+b_N;3yvX~-N@lv zW(Y}9d>JG&KfXID$4G1?z)Z2Pd2~CGeMEO|go9(?H*}<;=3K;v}h5KD#7p8q^3{9czBD`9VHw31F5Rjh(V z#nF2K`^{QTpXucW^xH|FUXYI)U-$!0UMKsmphf}36J)|@(6VTMALdaha2A%9ejl8` z?Ad9wyl{&d=Z-0uX7rSJdkRlOh5@@7G6n_48#?CG*+V6Sve+C>_(ikeS$=P;vlxyg zz19!iBQITfS^2vG&CZtGc;7$Ezk%&zIN!W8?{5|V zO}I+HZbna}COfB#nHgbGfH=Q+Y+W=Pmt1x@e7G@f%SEgW`EJAqj-A}{S}V-%o9Dy!sm9`w2bBUefEsarf3o?{% zKe-yV1NZTnOKFrc`Ur6_uEU!P>pfY<%q!7MulanZBXvPZ+xlZ_x*Sd)m(@ja<=9;x^yJ84(oLZWY6P@2HLzx*Lr}q!bXHdm% zZslB=f0iHkH1SNX=m#OTmyvw6{#O*<;M~>k-v^Rk^bV{VIoIhn=Y@MctZr)Tn{U~P zV>Ywmij>yRu<37=sgX%YE>u^r9I30aT`sn%OYN1g{ntsI8K#V2fXDE^8mST*1vfzc z>9VC$npFhd;O<4J62PtxxjN)2R`F=V&oUGqfcpW&T0QBhsi}Yw06my-6%#xYlwj%w{L_O$7M?z)2R~n0UrEYs zIx^6kUKWD7*G6q_^w0~=nuP_k_(@)6y1TKl^lUmYH5*y)!D3=|@Ay;98-((cOvrU0 zL1n)uXuklYD`0aab6dtq< zGe%$6$B2EN{roaxjw`*V{`us+D(q8*&vH8urV5@@(0@nw7b+5FLtZMCaC+6rpA=eY zjvj&%Ng3|c-!O`2(MJfT&dsIUbex2;iZ3&OFz=4j zq6|-F4i&3duDASrw8#EK_Bx^as}Gm?JrDGGKU4B8(w{eYll3}_p}fuc$go;0u*Z-A zohEE7_eZwE+=A=+bst@S{^EGbdW*nlqMT`b5!-v71S~HOY$k_V=D#3nF#hfm6lt*a zDdH_UJM4FaV+X;c>NQZow%;*&{#+CWDZnBL9Sv=S6^GSe6Y7skJ>c-ulMeN)g=6rH zc~xWg`UUb{9>EzZk}du4*pr2^HwX1d^8bz!uEXMrJ z52aJ&Or^g5qN`ntL(rAw);fEf*Klf<6S+J>*Gki6^mAXPX|T#KhZ%uNhr-7ZgnMHi`vq1w5Tf8su|tSogm@ z)*paJ@f*1kwczc6sr1RQG4O7QPfnK3#S=5=zlQmZuZD1aNG)x!o$=qXP-EbW2RHSnLN5!vIq{r?`M+IY~0sQp*MaNE6PwCD=MD#=ZoAX?bDc8Z28Qi>h(;2e;w!QF6yDWR)oJqzFRN zzU+V2z9n<}+LcR*p~&kP2b0gcJW{Yd?p=$#B062~W)AX3cH&eywHco&vp=W)R%$VJ z&g&~2;jTj^Y+Y$N-s}CPAX~eC<4xY?QYH9(InAPwzCl*kKW^Tr(C95!yMred32!{} zi%%Jrgx~rIW-smuFsy2sIR#-CheM=5Ejk> zKc`UC3V&GX6#S}fYtbA?ssfmL_myBCZf=H^G&uwVtW{CoUWbZ$vpI|>ii*0spM>oJONh+59Uc~wgJ9U+P)Ck69&!qWV@n4iw&XMUc+$9=9Hd2yS8=K%z zTA?WSr_9S9s9M?%(pXohdnyYt5j>`1WRt%5p zPK~E{Tj=HP_jLLB6jc;OzyAmaHk|85NpI_Nyt@M>?Jj^X_w*R$Qbh)9(MES+P<7UW zbRtp4NLE>tJ$Q55CvVUK3t4-EkeINTorB}o^mJeOaRvx8P$(K__f_mDlXBHQa&IbB zPi@@D%(+tBZ>k6Eh-QxQDBsj0(9b z?{VrDM{FPQe>pm&BN?w~-k-k}BvLgVg0~wWHRv3Km5PZ%7oK@^=u_irHiD1&)3)9% zX~TYI>qiQa+u`KUxNTpm$TX~o$tIDLch9-Gx$7nAUCULTyvDKMBF;k)CGBq`EGm*b zG5%FTc5?T-yX-{4A3>4^`U#x(FyUSr1rCT*z8B8S&VF-@n6-no`SJll*{Dn|%+K1m zV?(=lst;md$2&%W6R(zfbf5(a8H)e4Yu5n4hxhQK0%#)sZ*{<#3nSpQ3_Us6Yf7pb zHH9H{)il^4 z{y(*ht9}$rK~c|d{4E)Np~AVrZmKdT<~$3uav6!tg&P^$Td5MNcVNWBQ2NZfiKP{q zj-=QoQd9auWb*4yix%#uOb|M~5ziu;7Islw@Wu*n`<@U%Iw6Xz$U&hb z`fCfaO^KYjKrZP(=f>rWYBGLC>(TI~J}{K6G+#$o17FA$ai}AN&nW ztNt9lpVQwWWm9zce!x8#sK>B>fo|Gsg6Y#LM(*<~F*awD=a<=cL;_Nih<>hWVa{lKvhh_?d#m_l|347=0_rZ0NQG7=HuuEcW|z{ka=mNQOJX z6BB@j3C?9wA8F&cdGMt3;6A~4FO@$WG{OIe_ixJ{-&E0vUh+?r;#;cI2{YAzkA*Qv zA?kwiU1-?CJrGmk3t#FwdOdHm4EI1k)v=C%iQBXh$M2L4r(9Pa#_Y1q2@QG!I3t5TOuMpdp5#HMoZwVXT=|jv44_Cvhth&C! zfrV+)!dM`*$jj^66;vJVi5xYSxO4V=V?fclK zpR8s7HnmG4(swd1O-hO8f87QiiC>w!ZFn|QE!E+$(0;=FKzpcXE(@;ogN(;b(_5jx z*uGFaX=zEybO7Q3L4I^O_ zZsbPPTpj@pMDS-M6Lj5%HmjOe&0{94e#gR&`~I!aF*|T?<=Xhr=7#%xKK2p)u9y|j z+Bp)fAf@@jcw0~7gSq=?X(DS?)9lB76GI0(ylP?)Q$Em0San7xoQm+C`S2EM`?<`p zk2Z5F=L5vR3<@1kK@)IZ*INve=m$(@LgWtJ15-J4+W78{+bt4dSiSTFpla7UK{^JN%Jmsr8dGT3!mI3D3ZOgGYKWe=#Z`r6FaG@>rga{Yfig$0IrU*S} zN6}3OM)_Vl$iF*DVyBQB(NCG~xch5B#=c7&fs-52oHsdvbWZTF;e_jJg`+IS%eZytU$PqG(Tny1kVcYf4h0>xr z=NwZb!Sj;K+Kow<(PHDVl|SyG`1YlW+7{Ovbdcy`pu?RJogzrC*%7&ksi~R931YB-Br|XY#)y?AXVD_3V!YIf>sXC$Zt&=yU{I4u}vh zfJt$8&lUZ6H+&ieS?g#vO6Xk*3&Vr~Q?cWos3TdEZs<<~Z8I?lhF_MCeQl)Xia z>wD7N$%7~9;83SqWn)~&HFWRVg@&I71Fn{9tO5hgG&zLX9aVA}msgrypJsfh*V=MM zKit^TuZw%TVBZcyhL=mpw$RBo{Nevtr`zLj^J0mIT)&Ph4hysT(MnP-(rspj5G~Y&A4L{MpYjBZ~u zci1#tuGjK3zI$}Sv$mj-@LtXK|$2CB?=v%khlghT*bB zcM-5?h&Hl-W*%j@pDQ&nfB)3~{QOE&x+cAP_2mUR6LX=aX5Se?M5upi>YFoP3IZ|z zF*QD4Q92X9Gc5Xza>&!aL4OMM^i$iqjYk~d2mxdKGx>26}omrr1Z^sgF4a#k%sW!v3oTz)H~K;1fgCXVbhLBo62gtfbp!D2+%! zR#cWXG=X{l-Q-7#x}svnpoPfM%rz4vuNpLtftu-k@KYX|=!1I2#)g%1dTL5oP|!0m zmd)R@#rtSBNTh=hnQ@``7M58K7lUOm2hwyiE)Mv(q}UxaKBjRgDLp9}zm+i2+F-VR z5ez1}f@7EZg_9b4zH8B`F*NQiL|2t)=1I%tGJM}UOkZ1Z-2pz?cEjPfp+rs9gWfIg zD)%Wtw*^lIxn_)N(ol8%d!iY+l&X&rB_OT?ZiXya1Q zqM)E9I4h$uKly4{d-`aoDnZ6RO9J~oab16&&vAE!%k=p--3uik7`!siA2fj8x<$pw zu*fB!I&a)|H~35s32cr4tV8~CMWVhl@eA4I#o;Y!De%^mMK~vKlxf#p%y)>;%|?6R zWql(wH+2eV>yk3=eJ8D~tjyMQ|9yUOapN4n+B%y1F;1+MSmPg^3%qUs$EiJ-haO?P z?kor80wdipjNJY?IFNNBQuCDTdiLsgPm>KsfCbIs)xk5;db;s^x2n{nH>tbC?qq)z zDt9qYbowC}(7U&E%dBqF}5}j9-t@GSkJ@sT+f8X!jrDLm*k0+4>-S>Vdx)l#c_f02lbQ8Q*pPCW4XDdiyp0F*2Hfh4M56Lu+my)NS|2FHeR`giaWa)ylfRd!H8S zVrkiZP4CKn(|Y0sBp&IV_0a|KuISV4_(raw&yJ_HP94M~>8|^VyL~>pW$BZru_Y>f z=_1gEOHI}kb}8nzA5LiA55>s;iJ)_g6o(f3n)U5JrJzG_YPjx&M8yXtatf*>bUTYN54cm;C(xMq_?ete0 zI@8IVb+b3|Q+Ep~Ibq-hHw z?^3MWl>6bs_HfgMHjKu@u)E9FRQspTcC%FP#P@bOoMbo$%la-}&9=6`D0Dj91p6%k zk){uyKOaqBZ1_Z19r8?j3gsSNN}XNwlgC$UU5Q*Fp4vyz!$j7~$d7%Iy9gML%T0DA zvO#Fyxe>_j{a0~DuP;etV_{`gKE44qu#zD-7@uB4^KC+B{+1OTlz|oaJSd?hvw%QE9vf+$#-`qVV-{sFixj~B{m*gLRH-d+lJveIeE4~!}K}6I84M} zz-Zsnan+x~;_*CK)Ac!#5c&S2x8X7)2#%9Nwt9BwU-`CPTOQL#f2!CV5Js|43qILy zTLY{sz%VvW7NVzx_Ih4=;74~Y@1?`SoA%t`UK01Y{3Q+8o5r&le>RazL3JwJ&>%GQ z=c+Q)h>VjH&8=!fIUpQP)W~*(N7FLfH1YxYV`!w>_Rxk-fhoFS|7_1tYzZIlY0CyDs@^(_~cOn0D0iO{DIt$9qJn%W}(Cwe(lw53~M zNyv;E+3-=4=0;G~UfJzj`RsnPdQTn&nA3*>is(aLUfzqocwO(~Rwp?Lt!mHK?`oW_ zz$T-I^Ro#Iuq_`T?VV95GE(0KOR4DV&w`n5;+5O1IUuEkEpxg*CtE7VfNU8%Y|Oe6 zs1@}47E#Q2q46vvr)AFlne4KcPHRIu^G6Na6Ao}I-2fT6t6HeVs;2*H$G5+ei}2wD z>u}}a6m!YPk0Fly`AIx%P$_<2S-JC0sHAbb^|#X+ET3+bqjezi4lVV{14VOTX%o!a z1Ek~5P6(Uy#P4fWJDS7yCL;1WY~m+YzI+q64;@`b*QVDa{x?r0aDwTUz5_ z`?5a4JikEwv#;l+fm}d4svJYq#F~7StRNDd}Nyi@;trjf2(Y?vRBOEIUHTVKa|euE~1l5wrW%I|{6>z;PG7lyn! zBg=J+@}ElLBvLoupx%gxxNqu8L)X1C6=$sJ5ngvWtn^A2H;OmTsr1ZS^HtZmtS5N*Pa~7@=SiVnRKyfIxnuTzX^Db z@qk-|mkada==|bkCb1D!YpDVvF z*d=qcBr3Lq-47gcUb@oE%&VzP_o#ouoQWP)I%SW^o@u(*(Bx#VGYfK!q1e4zaHwlH zI0oZy4|n%_fnN~9Atu>sKc#Ox1Shd6k&9PT>K|T|XbX7!Nb&Pwijhhl)Nt9Hm@!^| zq-iTJuOTk3VPXP+oR<%5%q~XjZVt)~R z=J)1r_p=uCG6(yMCJA!wYNM`j2v5hBPaVfA6B6!SNf#;lxZ-HJ=H~KTP8LhXb;4$Y zrvvkWh^OoBKt95xhXT<~OY3%*E`r}>b7k6`@-H?YHl{3o_5FU zGULA8s@r0fy96przRC$A{o=J28XF*{=H@REyDoK;*4CF^(i61@{_jX^pUcVJEKh}4 zkQR3};~DzZ23B0NGWE6JKT_i%#Ep)N1K!!gR(VG=0|Oee+bp=dVdC_l4Gxo90l}&r z>ctxY`vplcv36s5Bj_ifpscq>a2URraS%BEDSU)lPLLknJ7S=M0mZmZ%d#`61QKe5`+S*W2H<5_<_x;tJ zz2(Az-wk!n+&qtToWMS2VFy*~doMek?xo*#qgcq|Us_vlfHgN*Ma5$FUty0kuiHT6 zIz&e;SP|M2!TlQtv9G+)LC^lG7}Ukjfd1MkQ#fe9J#(=)C7lZG8fgc;r1~qa4VOYP zLpD{aDx{iC-p>^KdpJ$yB0r{)O%`kGzS(v|l~q!TX`3BfOJyZ|$HVVi$UYFs6e{1Jk|MTs{J-$rW^J#0$D&SOK#3rPW;^Pngn$U7vzgN>GfiNc`@{i^$Ek%8u zfz_<~YN0bTN19fNF|l&giUu*iBe?VPnOfRoCYpF!<`+Gh)pjRgLM{>`J{ngKOGB!^yjNrT1kb8P?|sg8NwNeU|3N8>?6zQq{#pLDs{uwc_p{T|^0Phv$cR zxzK&6BpWF+-740GHMjHjEzhKVck@-HM5_ZVp5XSmyBBw_udl1me;Z5{ zkVt!~=RJCH&R-PQL(^xYr@#A&kVSJTYxQoMaGUaHGt{Rrb+u8`dBp;7KVu+Gfxg^I z;p@<-E+aQLH*n%gXV=W&Z@&8R0bvOG zCN8|BX#Rd@dxa$hUCF<}$16u^G`3@NbkEq(@R@AhR?W-gYDnHe^2=lnl6}y*jRGl^$d~1!Ki4vcO@Jjc?^Gj z9vvbrJ$-W61U4EDBO9ah9l&5d__JSsG~wW97_M`QNcRRPc;Rp{O9IE@`YJ*zBM8wx@n&>W?NXf>Hj4qD8vz_qE zz36m6cUEf^ucxFe45*~Os5|$+&3loRB|KGoP+7O-z1~Hy_DQE`V|`)Ql}KG3V75L` zS=f_ny=Nal=-x`sWWBl`p7b33^i) z)tE#^YYz_Mb+MPio$f^iJSCBJ(fXv^zC&(N38O5ZK79fwkedNd!y?;@{rt!4b=c}+ zoAv1B|Hvg5Bnr~n^i3fvENr_|PHk9g@ho+@4Gl##H4hmXX$1r{X>fhcb|lcT*J*Fn z13NiSmKk!qp$_sbLGOAPo?yWHes*>fUM;WPE^=+EV}Lw^#UfRFU|?;Z$n-<@%UCrX zDo)d0Cb!d#Lnh|%(TzW^=Iy_Q_rcT?Y`Y?;KaBC|a^(g`taK_g>`xrYr-o39vH4X| z?6_S8$&RlXg8e)Ti~jzXo5)98j1w3`L=Cre(q_8O#de%FC=hX6&l>oue+o0wb-<}$ z{n7YsIC$RDr)vRJw+5(POEKhpyT5O-MXWV*p#NESgL85V5a+KMl}o?9GrX5uQgwLV zo1E_TJKs-#-}}!>mPxevAQn##gjTuc)~3sAY)$pfZGpCHD)(8KJ=Q9Qi#3~sS*Q(% zQut`1C%i5(q-3hm(ygY`NjsnSEzy(&2(G-r#oDhN zpriy{2^1cGba&rU*GI_`Q;oIR$>fS3k54Ce_+v#rzIfIFkoV%34-&a8|5U%?gZV_8 zs=Bf=ukJXXri+t8zw5-rzabDKpLUtPjd9CV$76$Ow^;Jg<9F|{jE&LRQbB|>3lkX7 z27eZWjkzfjxr$C!eJCMvGCJ4Z-5F5dFy1-taon$_;})qEKBIiUHjy)0%f?n+J*a!} zSsupBZv~_Vo)|?hhH{GpG%~tg2l&TzE5D?RHLF-@X#-^HFE38P;D9n8yYeHPtW}Kk?8Vzcbm>&84;2lw}Y$ zt!kLe!jg5vi5$4vQi3SGhrLXgYAri$|8h_dyuhFV4zo*GPprQ}v;^l#^NM=iXC4QQ&uhPujZ^3}tfM-5af=}PZM&ze)#Q{oVu9EP}0ypscLLn;}qX&vdkB2lePF7=p{4w2c<+TP|U)!Fhc zTsv-BL6dbRve)~9rNbgN4x9SCn~EIsw7mH}SW=?)Qdvsxid z%@-<%!x>z$I4&8hiW>a;7iR}ZRL?IMJA3dI7~>4J&3fqVj$7F(jQ*m3$@vW=zPCNl z#8At|gCAo5g>A)O62d^RN{~UG>!NG}57GWDH<#HaXBgR(`9Q3I)NtEHcErN}YOjE} zT}c<;=}QvDZJIu;u;^37p^=X4D;fB)WHKHxOrI~lLI!>ND7JQ(%}XZ{AM^cqJ>4IY z3RL%Q`OXMm$C?i2Uc673;_Wob=$Xq!qUm)o5E=ld8HKwQ=bs-u>sm84a})2$KXB1o z{0bJ8CyQ?2KN>t9Q8O#nGt72k#l{_U35Nmrjo*h8;QGqq%B$juYj?XcEw&h2?269AmE+MUox_Vzz_uo=*Y+HrYe7@U0^ z92~HPAD#~H=LZC=c8QHhSbKf?x9m|+Qi;Xo=~p4g(a(QBN3JDb3pXyo}3qJ35;AJ(c`)R&`NLb zjhJAv;-4D7*VT4CGtiIdMJ{wE#JQa9&5bgfnzxbX)o#>^2qlq{(!0(D_k%DKdrS%C ziH{5drGDWI+C58{kV3W(@X7u9-kwx8y| zxC9DO(AWb~#sm{Rmt7H88}yVr4b%w75l>!@lVmJ!mmg`a*9C($+g03|t6iBawXY$~ z>yC2qhmPd+I?LnJBNOvsL|b@x%6hF?``2d$#i1sqrKjgO%34~b^(=Z{DJ%PX^a_G@ zuU+v*x64F9VV(n1;m*#^i7H2yBR5vhb2pF<4|s#rZ)D^pMJPA^UkVe-^+~SO+P39< zryA~-=Byi6OFQ1N+G|Of2Rx0uA6`8y;Vfnv z%BhrFUCBx)`b1Erp+qUXe95E#GwAc@&)`uy4|?mK2GuTL;Yr0YiQR;rd{_6in5VRAeHCvXR{FD82Xzp<< z+I5YMjdDT^D1nFO!~hoz0hUKdN?HXyb6gjQ&>cD+mJuQl(g}QfKrT?VIe-Zfj_@g~ zu&`%)to!A}HungYa`MW!m za|EPhlI;(>7MHb{l00|GqMLb`@OdqTiYbWr#rlhbJTN+XZtJ66Dwhl^`NbPX|~I+P3bRMj7R_Y13Pk2V4RY~XfYFlv5p7Z5-=awnFIQoTF02y!S` z!lsC#HjQv%mGvjZzOUAL8`Si4Sn;r|RIXxyt6F_}J?7@B+F8sa_vU8*7g1lGYdVXU zV~=(eL&=tTY>N9|+ZAZ(m&YmL@)z;kzc2r$q>>gN*vlJcp1h+uMX8cEa4&~FC~jGU zS*jq`1-hpDRx|NCUbq1u0Pju_57c(sf|ff1H#WTt2#JUDxHPuS0SMsA0YL*?k#PK! zFBR4Gw3DzV=PLoJzl;)6r*gZo|I31N#hI{#na`IcZCzH%xu&XLydRj}tI@Qo6Uont zdpVkBPPNCs@3<6@62G;-#?l0Jnq;U0cy&E|`LUffzDN-lEY+^lZ{TpT1L581Jv z(Y#M-^iH{ruHgS`X-`}n9V!I(ot#JHOrM7b2gP&Q@zvcWqN@n}IKZ89W9aJ+ggi|92z2{_K_TB#~%R zT(V_wuhso-{WcRzWN{ZT&C{NI(;_CQ()>0 zH#D6IJ*Pb^)YPI%$BD27Gv5M4SDTjLyE>fTG>n{-`K3T>J(EF1XM(JChsjmz&G zF2OL*7q6YskF-9)CVMUHAZ1qO+LR%AgO%&wDef%w$ikc$1kfxjlma?*5g_vYQe4cz z&tC;*5v-5y-#6L3dM9|XZ-y@7{$G8vrBxN9m84&jys9d3_0nZ^ZgnZ{_NB>RT7Ns( zx3)ELJ8MR9pd>RIU19n2RN|Y^I537Ycqo@S)beBRaKid(!_DI<&)diOkBF%{Z&iyR zkrr$?BQ zM1SU{@Zl46^)WD#ZuJT|-MQSI*>1t^EO%pH>Wppue_Vit!OD1H|WWUXMNLyYUbjNijtC8 zE~FFv`u?5`01n{eM*~v^g6hCso7sgu^V&^pP1`Qc8#iviQ|*UMemn~CNb?c0GVwfY zkcMKweumV!Xz%HPT4k($o2BlQUCjw7QSC=;^2xQy(3NOIYCIt($%HB6cpIq zqpC>A!Yq@i;2&t5{*-2-R>)Y=FRiG5Y|yaZK|?Bi(^PZIX~NsdL_|*szk)_Gji%$s zEw>J@8PESnley)Kp$%1d`#w2)4#my`}I}GbJ~y)qL!ae2iWwa~HIE3hYWu={XMvK(U+~Z(d>XL|UN#Y{-yVDMhyt6SYc8pH ze0ml6{pgtI!RpkF4@yflm82)K%7%K;Dl!)y=xU~!0-WNB@nmT#w)T8ggDZC}r&dU; z0X0#2@F9dKtT|pLuWgwxXH>XU(Bsh_Zr}qYEp( zFRmlaNr1V62(4V?t}4~VVWv(~ASnkFbjQgAyXj+< zOAVQg4tqvX(^Rjng;`l~X>8k^4RsoSiTjCzjRlzKfP1Id-=C5rQRp)7`=hvZIQL_g zDU3&)N(t>y2)kuA)t&5T2P;MF&nL>+zisbd5x3?gqiEjiB?}NOah=FvR;}q6{kNJsWash-kx{;c=v;?gN zB84A120a-N(&;3==_jO$L7`i{^CA%suO!J@KjVlx&8xFSyk@bk08{(&n=Q+m>J}7% z%@$l$(sWUf{6n=wu(2F#Ma4(pOy(bYD zc}m#gDWj6wqpAyAWcItbazcdk6i2xLoA_3)c^aBPve64>K zw=I=;*33IM8Tib&ASM{Li>TuozliC=ET{n2euiK4iyHVAlWBoWo3zDqtPyjA0e`Di zoM9gQx~5Q4$DD$u_Qgq%)C0rg0|d|H8yxfM@`*XwRFGtcaFxrdE^!>Axby#=3uk`6-R)-zkJr9!7MZ&y5#|X z$Ag3^zW1@RLcL1e62iOd!Jl^_BUlWyM6RI?pzLy#1#g_r@5~ZcxkA-alFt~CJR}r_F1s0 zyf|w&s@gm=rCP!;!@fuww3@gq|Bpcm54z1;N#KO>Ei77_#=)ZYapw_G=&&(02m=ceqR+|Ry zRG#mTH3vTpWjsp6zu6nkMI8T?2A8AD!DPT!hMaxjr70;{Sr$e{Ockaeh~B>a4n0A} zv3KK-R>G#{_+L?mDV78q)+5%dovc1f1Y(!NMR5N&P%_xSXd1c=9}~?GQg;v(W&00H!z(D7PqPO1cXxj@HvvXxL6j5$f2*ISd8cO_i)qYbmd;Luj`C_I#TGSoA?wz_>ZrUoHFF zoqwP3HeVSg=3Aa65EK^y9Al9yEx_Rauyf=F-azp3Gf+=c$Wbej_-h^&6bX%GcsM@$ zj6+r12D$OK|0aScB;nL`KYoZooCq2oR1j2zokq3*v4Y82Oh|Arkj5XDmf)E{CHbyj zu|hNVo@B_YiGMLrmlsjaap_=nH>H0W$|oRylv~e5K3{;;y+cTu!H#dlkl_EWR0(}n zb~Y3HniWq7Ilsf~5A=WPYD=HLPDdy&>BFAV$;7v^c8Xgu@OWr7ioM*gdJQgm~No*i)UFoQCz zVz@j#xN2$}EqVEOm$SoYT6}*D42)JtdBi+Y3<1%@&y>i>$i_wy$dA)5dXS&TG-SEy zCX}>c#RD~Gs~7wu@5qK%BXyp2&3Z9>_F!q9z+ga`F)^08>~VrCDBg8JL)un3;*tu9IDS@XR;`3&wH# z|E<9w>?#o5*Letv%SUPTE$x()md?I)`tbC!iN6fJ0g5)}=~o4l^l50Xp`_k*5gZ?E zF#I^JuB)qSXJ_|22_(<}wVS?v{pzn^yxaz;PfLe&Vm58mPe-iGp0zu@I%cHih|%#!5d{0U5HKAR`QmyTYFlwlkN6i1b;!FQg( z{tcT}m6i_fGSV+&h0i6ycO!-A77CS=l9Ce0M71jw7j}-|vsP^?L{t!u87`YgCbOeE zqcq^uX;r(fI>VZfpCZQq3x`akdqKzV@HU|3TR>v3wY z(_&|goXWpR&EuEfV5Dbi+TPtw!Tm-PqUB>EX2ABeRT@?eEr@h@B*Ju_dw2*{Kw5$a zG04Kq>V6uv3mZM zqpmrSnEQy6i);4B(|dPeeS$pq(W6I@KJ|)Dx*u*e{Pp}8Sk=9x`0t_~ixrNq0h1a2 zc8OdC%q>C2F`9`%#c^2=vJS3f$T3_!dqAC^(7mfs{2H29<5#zXo^VSkeCK%hF!tUlhKhF0x|nz`oGO(WR%1a`)}!dCOx z>K)LIi($A8x9An*|BDYf9nRIN8p_j=l_!kZKXQYNCU8LjPYTxA%Zunu?#P1xb5I-d z^72|e1pSOOzCTS%=$x>eIz&X#mUw_Jbgi-JDLfAE;fzuwQY);$nMr7Snf}*~s22t- z(n6Rg1z#p2y@eD>md)lH@wj)W+@NcR`}+R*px4r60ud#916VDee#cM@D5+$(V5y}ZQW5}avJf}Tdso^sp?7Nf4Px*gRqI5{bO z&V#NQT0;5H+p<2|uxxy*`NmsTC3*R~;GZ9O zZ9cTjg&o*J;kbW~VBSB;5w-h@cAjcRzrCa5&D^%o*>OF|j`p{Ii;)j{v;pR?K_gH> z;Ss6HOs^caX7ekR#CIk@eA}O(d3jl+Bz9KEZO%#F&Etaj?$Yurnym5ND#qFdoXr*5JZsIv%$fP?^{H9`;=eM;wqjyO=)Dd({`B&&pA{{dw@tpui$!a8-I4w42ehAy>|lS+p3aE zN`%fg>3hUyK%8*%V2L?EAaCl)uFKgcfr)P#w=XLtsI-!Us2lS$EycE+Vi6sBL=W}Q zq5`d5-6(qGu6glb-AHNV4ajCoi6lJw;UBBaxMsgsQ{_0`J#>07l<#)S*O)M)j=#AJ z@xs<8g{*+*19TX6zLA_byudExGu7yNlj*S)Z~Y5Uu|HcrDG(TT9d-1L{X_FSU*Q1Mzvf zF-b0evRLz5CKr+)&qFiGE=!5 zEr$H61e7K3auF?_Msy|W z1SoJOFP5p%p6ZGS_YQ+Q{*O?pRs;6$)8dkwRSetvxfkk5l=q#!DF?57`qwkza`wp^ z+o9uHko)C}wV9D7m<8DKAS zY)*n)Nj=T1+AjcPDl2#?~J|3lYd*_h&1Xnu?&{1nOX;%Ou;T`N954ZeTq z?ks|*N=@{k+08$ak`^iK#oxBH<&^n4Op{qkT5+?SEcqin{Kj68wlmD5;bu&tk)p)rvp3aRq8sdgEhM36I>#uB*RB&HlW5fjOL!xD_E1VACJu zwf~IaP1U$EGM}55Jcl_$@agpW`!6qWF&>G{k`-{MK0qi6+=$|qB`Q(B?cVriT%XNz zfow>QV5TS_kr**r)!68a1R1`#3SmTIE>%>qlCyfOW-@O1gwU9zkZYgF-K3tSxmc#KDGUp=x0pXXjnB~-sGJY%rcZo#`!L4-%wjF74yS&26)FtR6OGdVL}p6kh!3Wqpu4Zv%~9qDZqM$UrYV&0satH8 zTWIS9JylvOR(Z)Z=#Ygu`Mvis(jlS)FEBW9B+M`xJtS-%G|d@%6Q^RDh?3^JwI=dR-wCRqRIQq{e3EB8>pF4cMHvW`Q zboVN#oiZrVTfOp%;BrEgez~=`IxThK#A82y@ClpZeJBY@tSkc|#`X90dz&r#Fk*RE zaQ&JWMkQ=TVW@5PuT~rCsl4Z1qC;WOj=QB7#e$%t3%h04^nxW>`i5%8Nm0+Cg1?)H zcH6&?LN{uq0CvG%UmgmnM`>3-oi z=YT&>$yD!HoH*_-=MNSRezk0|BtrT5z~4J6DuXTx{fG@hCXIG5yfs5xh{+!oj%MfN zES7TF!hpGozj}Y9e6qG%hOt7)Q&5r`kA_|{EuBF@abcdCXy?XN+02XR{5_;ivATvu z&X##_ZO$znUsR&MU@aclXR?M*8Ai=-fwY&EHALst%euGk6klVbVb$T11l(m6dG)qs z4jqe>M?n^<b zD>GUuxpj80-MRYAsGm7?Do{~YJis*Wlcvp&aKs7;dQ==OzFnJ4r z2JGiw-;ekc=qo6sGSQVqrE9&B)r=o_!#zB>LK-IpxC0gTEb&!rzl_?c$IS0M!DHLTAzeWpG92BvPFw+MyMKD?h_S(5>Qd4Y14;FU) zGQ*rw!=Q2-;3c*;cq#!q=MTS{2)INN9-oRNV#Prn3UL>WusN-`aO!0pHo{HPXgPTn5m<71jHbhI>6inJ2(==An4n9oRF zD_oM5i;ASPFVyU`+V62%iaW3><|Y)p+De#eh#L-JY_)%2$}zw*>?IdK;(k!k6&-lAqc*z%qqcCB<&@47Ud!zIIN zl1e1g(2V~Wm9@THz?(o(p?NsimIy>a2{*455tXcym(Ii$Pt)GtkC>yA4j>40!tk*g z%Ll!*dTMX8Lk#XaDBCa3?QQFmEoZDQNUOwnf7i+&as2h{cFXZ}H@e%o zXslT9<3Dq(l*_J;aafSzm%RU}>o{n9?}EdB>*{g$h|~Sh13VS4UfKVHv@=ReKf}C1 zBv?0Etq2g$Xa0c%aSzXuD7uIo4GkUbIcs-*6pRb{h1!L`aI3Z(D?UtV6e}B7)Qrz} zQ~Q}*7$WKi<34k6=fgA1_8j}K6)h(;%BJLxtX~qolOzR%80;lkE%Fu%{j<$Nwig>) z0>iy7#%?LHjcQp6I}9t=QWMuwfE$6@#7bL4K>YAIf&US6lwZ%%(BMia1#-Z&*PU0# zvFxm$pEcRZi26uvVKLJfL9e3ZurWS7HR!YT>Mo2%{+k`W4OHB6!ZE>b^A2xu ztu4wyrDwRab3Qg{pGBuzE#~50JSKi3#1>kST!8XQNuR`MjH9cM_Pc4x4|50G`-?xU zCzA`Y{jN#Q>qr=;eb)RLsv7l~<^}C(Hq%1(toPXozk~azDc4-a&8AD{*S|v(WLTu6 zlr6;D_kk0}`ukzRerfsjT<=Ow3H|LO?6GXP9Vk}feSPyCQE8z)@^_>ue04)8H-xP6 zyO3$4xn>;Sa|R<`7#Z!pKl+aE|K*iJXMErMS`r6ji%G~6!c2q#NO1psS$wE&bd??_ z0S!KLle5~mKNkXP-zaqd{0AXLa|H{t{E|hMJ@05P8p>}4hJd2&vCazHh+Wi-$E~oP z=pU@BKy1B(R;sdMM40CGHq`7=sqUQ4xa3PFYIaFAM!_YK-a(%6rH}Pz;phw6| zB+m5E)bv=}W8v_f*O~}k=;=;w6-KT`LfcHx9)Vlq;Qt;u6qMS#qEyw&D+|xFgJ?#12IFMP_}E%U6s6vb%YZgMc1#IGv{TZ$AQ)jq1eTpiX@M*%}~$8^)>r^ zEmbjIo3A^LJ)g`HY_l?nt0t!GlU8R= zLP7PZ|{NoGt4Ebqg^r8&m z))iTZUU)sA{IYDHAE7*b727qNULGHHuH?_9-1;(Sy=`?k>25Z3tw%Bf$mKnpF96Cvb5a`$TJ3WC~O|Dvg6q9dGx1O=Q3vv zE;=uKB1lM3DP_E4>#%NqZZ7GiMBVvRb;8#1-Q%|u*EK1IU`+A%_(Q*BqbixDMP}qD zZ@F^>(*lWLAU}NUDCwVCz<|MdJ?_Zb{+b7n`Y(xzWa8qn8xzs}<4b>53(wEGBHolm ztp)u2)}Fb}J1^(ZzBJfjFojT3UVqP<7P%x`bUMTj^TY1LS|Lf}jJ@fLT-~bp0>Q1mrWI1c~3j zUnm{7T|CK^Gjx7_@>>t;LU%Uv6ZkUMagXS;MPbofPuX{IMW zhSgYxeSG2Z;p|_A`3mX&WJ@Z0uJ8-x@L-^zHyMc2=stwMFO!Vi1Vwtq+B+?7A#%M%?`)bW+{+#@5k64f07z zc-FZ(hZ)6ucmga7UiwaNQ~y6=`TzY$oDwOoW3k)s(s_3oVX7$8T)(OO9 zrcjL8F^Y+Angx+fRy2fVV{gbksDjk!*Gj_~77YA%ucZnJ3_Dz8@uK}>lQW3829&BE~>QdEuvMU2K*mx$?U$>`+Cep!sv8^EkO zMykrBbBHjnPlS*9!}G0s^S?&`%@MNZsBk+I_+c64g@%Mcp!M6{nRXo>J!bAO7NyN2 zX&K4ZcCV*{e{5C+rZQ~wyvisHYA_!S`<7Be0(@j=3dTgJCjapyT-W2gd7w zAsiiyEvr6V$BgPoV=x7?kxRna)2FYh;^i3cGYeHZvQ&ITzuboB3t8f?zk8d)Bat-R zJ@qWpW3!1e@mt;na=Btbn6|BxeA1#k>_ zMXkrDe1#BjRB^xyfkwQzIn(rpyH@-pCtWIbcb-5N&8KmYd#cspVSS;c>kKOvLC2ge zuM(hdZ+t}Ur<-u{#`9;+AhKrRXlXR_UHURlu+i4`!l1G;@l@q<={S2)kzcGDt6}?` ztk8XY|Jou`WmZ$H675ippL1cDQ7Nb!UQ*K1TIE*Bt)AzZY<&rLm;i@h)h!ww$uVFp zv}btmVD_+XtZ#h01N=)xBR+j+jhQel`BplFJL@-9zO{Ih!U@K|8cd4-%z*EZw>OQC z2pDZU3ryAPfu>eNJ@&}$iNk(5Fj|ngRd>0#)^n@g+?qK4B^o;Aags34ytbADKo5;{ zP6#i{UFyL>j~q3<0{)=md01e*xA4Et!wOl)^$ld4*7_ zzX1dI=>`fW&ut2uO%1DX(e4q~TBRJhVKRueAhaXUyyLj*&L(W@O2+F- z&NOv&4*HXXD54Yj9UBy71s@r<4}42>ek&-`dZ&vU2TPEU4VXAjY1Aw2mOxW` z#xCl2j_%td?O4u^dMr<5_jh`@rx^A;1BLGj)h?{6v2W!))Sx(7mL(v-rvO=}&(7j~ z1O|J*0hc96Vm*_b7gIvFM?`TZ?N8QJ;?`o85?wdEa9ZO@Rr1cywHytN4Y!WmfUH-X zGJBEeUYeVH*RDrko`^-8%&)4;r*XHy$$;X5WQgV=?)*AS?fzJ2cz8d^C?hD(^OJK! zI^A|Ngtb7Q%XV(Nzq_~ZaXRBSzaGV0GCNW*5EN8_NnE?1A$%*bZrhhsOpnd^4{|71 zaKoC?X+F$sI9tBu$EK4&+4yAN$l)<#-p3Z|vUB^LMYXgv18SkWGj?Vd`A;>b+z;AX zDDDw}y}|UwX4Bjbc#fhsv4R|SI!fn!1wNguLm5Qp$fcw*btb?4wW{--&R2%Qkyz+ip-)Gk6s`6EAlY6LDNi8Tix4Rqxj#?d}H7w4LcAW&? zJ;BC8^=g`t`>q6eY11Xh9m}c?{m?U~y%nUs-l;}f?GzBF&iBhMh|8CQxzE|0wVao6&v|=&>`#=Wz0n?rJ&32`l)x`Wz*-wU!N&zdmPum!U^|66x5fqgd=cW7mHK3~&cKY>- zwe#Uad%gs}Q`ePHWtDKGAEndpW96(nv9bH)0t|S8FN}L?kJ96qRFIU~F3Z)M@MJ9I zOrPa8EuWqRvY?JB8ML)fI(zrbkqfxJv}Bd)?9kw`)Havu1iJvEBEQ`iUCA^=feVC) zA2JB=k>x#iw_r-l_p7#gdZoF!8GS*yxZ(GL_oNv;E$80)$%e4=?2leizimv6LR%Y; z!#PUsq2V$vZqMyr$+?|v3_4k6VVB~Js`1yXc4j5bw6q7p+aCar?1(vevp;u4`qXd0nW7Uyopjp+tWQy=3sPxZ9b_vEv;A3R@u&>tr{isJklIYKJ@7l-~dd7v<`l^OyjVKNN*@~(#4paTy)^N^A_xfZNWO7Ka zpRZ(jK75#$`fnl{ILVR8?EL6Ox{#6%uPZrF}IB>3uy>WE=&VY23`lr-#)^ zXRA>L*9hB1t0vyCWL$i8r+9}lSJU8mNdkcb_XuFo#jZH8dpYhIAR{0UB2TBkS&zL+dl}%F4VqHxvZ5eD`qgO=fB!`cP;OHFORmlS-d|(BYVh? z($noXvr*te4#@3K2lK98oHmDgx^?^vZhmAGALX_K_CB5)HCRmoAfVkiJa92KG@7ck zz9%k!aZojV1ACl0^zgWYMK+1uhvuUnX0L4s6;tW=t5;db3ZMUw)BOCRBD(zWkXy%f zEwt|JVN7>-oAcJ*FhO`Y(L;^>GF6?N+|1+Y>2n8>Ck_4q0mMnJ%=vC^A|hSO{g$Uk zJ@34}wQ6Y}k54P~_oeqlTWe>m7|RNlI2~>Kj*UrDI#K2=L^ zky-O8h2D9JIAzVn`S+C-OUAwho3-hpr6K+e8lPKsnYn5;>bY{}7r(FBAbfAczxZ1Ps$WkNr`4rykIAqXT3kUW??=(pkl?@0vwNndkd-C>?*%_%spI_zfE z?xvY7b;e{cpC)WfXlvK%IG#RNEi&p-tJwZT&M(wgauK^ab++Yx;C^f!04X(6G3*xG z^WVvDbVjrFFFaSTJ16H{8lSF}JR6#-ajiX>61WzV*s}(zt zKSoH$aqXS_>`LcBDsgggo}C;@#?=T-=T2792azu2kN0feyEs7VIG%4v@;jo6CKnG3 zbU)fb#jf68$r|*Z7ChbDo|CLGmWku~;&~yvzv^H7o%*1BtqBK{UaEDYKch^&$SAn3 zkUiiX$iO@=&Y_N6c}*$|j%qVjJOPf$$ZeKxcwXy1g(vEk#M-kBXJzu)d`-QnSZk@% ze13LjV}p-RAX|32IIFjpHCMM1`VAd4TD)f`j@ql98+D!yjXsEz{j*ii^Ndt24*O%f zs>$=Istt$E(U(egUsCi2qS?GqafC!Op6_*&TDs}>raXglI5b z>7`%*Mnp`k3hhDXWHLX{&LZOCvdkz^GinV06I~($A@3P19?3k8_7DE-gyKhId-pV% zGbW7!RFt*qY|E-%(8p8oJ5(R1$$UsTJU=1z*e{|S9ymS7_7_Szpck%iYz_c7%d>6} z3q90w8IR}P0XHjpxc@`sq)#~E5KDg%yn*Cv7A|}4lRdU1U1^S)>|iQ@A?hYJkIt8$=_wxo$vL6v^=9u+Lm}!jvl<`~C z(9jTn*52LD*A&XLx}WEE)PcF!-PPIpR9d*0{HG8&}4$se<2_E}ygsSEiSeYHXyprH)O(?$A z7EZ;u|7gFMLtaC%-&&hrSy4Z=&0OY%tZ-APR4gA9V!4bYLIU?5_3IU><)~~GJ*>}O zUCqj^Da|e2PrgaPFkYIY?_pz_+3>pBWLaS^YiD~#j$vcxPJwCnkaQf8wsmv!&XOh5 zgV?H9Ph2E^#+eOg?#TX8;?-i#YbmnqN$h?!*fJuglgAw68q2TXxhEwt_ilT;yT^Cs zv7sRknaW0%en`vO`so)AT}#T}uQ*9g3pF(~P8u;;peW5mR#c{o9}vd=fiQPcA`?YU zZtl9hA&p5B#bg|_H`w#@G&J-YF55D+&)8!+y-;thw>N^dX%FSapT&%(f@&r>ThZFtWzzleQ09}#-*Awx$0!k)|i+Q}+* z>ypLmZ>q$kJggh5NkO)ev8I@QhJmBM`Wjy;o)Z5XF4crHQC2ZMfvLy-+Bm`|!q0B- zSA!R&$Dd?f0I~!Vfi4$%uo@<2-JPwL5GB6^*$h~Jz{T+fF{~5<=EusV`jSV_t_AI{ zPP$IL*a+mZoQe+%>&?@t1HLXSXk`ie`Jwv>+r%vopSdJ-oBY}HL#sW5i*!Qf(4`gt z2^V6bQzb*NNZIs${q7-?1#5Ctue+R__P|gk4GiG(WF*1z$hS_dT6>ffNi1$X973Mt zI&7wzm&oS2A8FG6Qzn|#vEk~T_E6oPiW0?un!L_5L8Y2tk0ERHuEbP6prp3T?Mk5t<46dH01AO9hMO;oM=FaU0({hDjq?CgOINu9lU zUNN%2CcN?qqPfTIPHOq#nez@&5IKMM8%L=)hp>iM6XjczMeadM;LL{ZQ8zL`h=ywD zfbr)Sa@zM2uKOShG*(cto0%c|Mpb|5ZY@ONboWdb+atN()Cu;zuUu?rG}f_`Uotch zcitW~u5(x`DKhFjTk(}S_2UP;9aS;*;(0|!AaC}xmZGS+u!_b5)57O}~> z%+JOx9diX93Ti$40=GHBQ*03U{Y1^x4PJw^{M;$qsJ9?+S`s+Ke(!sd2qW6)89mhY z8K1Y@Z3R~V1fxpO9Zu7gf$u9)sH!ua*(zDN?p+zuKK=4#G&gZd4Zn`lKI?9`8yMJ^ zi-2K4$_-5BIM(FNF|)d3@M*3I6owq|6_b7=CN-PEs9HNM`QA!JZM^3R75b8+Km2`& z0+k(4Z4q$8&yR=e{vg=MYRSMrQtGsYNRvGBoAwUdwr~aKFC{JOcr{lyur4d$UAjUhzor@J8$L0r_NA|+ zT=&zr(bYBJ%Q@rFQyv^7zn5mz6|F10T&V&y_IG|1nYlSyyFM%v7yU^RMsJ|SeQo-H zgm2euSZi3n`M~+pr%z$lGPe`DXNc^L51a9>C(B@A@@ai;b34c2kqx3#T-l1a5>o#A zJxB!Vrad?7-?hd&M``nY{qlQ0$;ISon>f+=rvaBIGSRix?QAbB#&EpUKb!-)s|HcO zL=85x^RtatRIE$kFKFZ^%HK@hj~Xqt&w7$qXTCMteNea?!jFnY<~08+xm&*)A0MAi zCXpB>2#j0xb|%!HwL`*4`@5aU%cqa`MpEaWU&8S&w|HpyA0Bik7ff|C;*CF z%4)p-EL>@l8TUhutrb}1X}M-RM~dL~uOQF-u**2hu1f?xMHcW+mRp}yZR8e>lS2gg zfjt;y?@_uPFVn+H;dnFQ9cL-z5HbpnBy4#-(y<(A`d2t@cmEVr>Kk*K_mw0eIxZ0zgHF)CUp>>x5UGO`#~QBYIsWt)EWD{F`U=9CL^?HcMlg^-(7lkc9f zJ3*jYIjYM`@$JrloUna_g|VIZ3#Y<(3^yXqZ>7v?cXOY6w&0UO#th6}L#fI3^ zI#c9ss*EwAH&ao?q7tL1d1hV?qG={@sR!~`+S=M=g^vG(HTluQD0uE>&9ToLGJl^=OcK0li1ylZCUCx3k?IOmx@N$ZZ!E( z@>#tay~S;pmdKe`d%Te6E?v{FMd`k~!k8Ct6H|A(EK3|j@&7UQ7En>GefuyL7zn5| zD2Q}-N=ZrQ&>`I+Fd&T}qNKF6bc3`o42YC;x0LiyA`D1>_W+*vIqQ4h^?zoq<6&T8 z?|bk2m)GyQrVjMc32-q-D622oS(9+S`jtF$lyW$!t)+hoOpDKE zJI%0){lOBCc~^>Fy=#fK&fG%#d*;!E7=~dC?_$L{w+Lfy57UE{Jbp;+URpe$TJ8qZ zz@T0}ZnIRUIH98P8InVMoWmE@o;iJZ;$3t{v~aRC!|?b^2%GU>@Cey@slZ7K%O<#C zc9xj_v@34vRIP^v1^v#>ZaqD5QdLoLZtMB&y0z3zmUOJTxOg;LsD%u*_XOLPfyd5M z!wZAU`}j>xs=mISUY5747d9)%G(ZU&jCdF7y4hftc^;GlC41F|6ra=7tSp_O8Fko{ zkn_rCKzau5A$fD!t&QrLy7e*%U^Q%o-DZy-?vQz`N8Dj1oZ?f0xB2cS_Uxh>*vAW(h>9js4lQZJd{EOiwGhenN+Q?izo+2W#1%LVS zFE_2MBCOeX?HP3OfJ4zpe?KrSfc!BoI8si`(JGI2OE zQJDkNjOIV<$&x)ohWq3WMtHQ7a9XTo%L~`76^9L!-#+{Y3jjf|_X=%`8;gm}MbiP= z*}h5xh4rk(&a)XfpnNGee=hp^P?exJwM1x|2C$@_)f{b>zv^%oPZ`eFa1Qiq^5w-CeC;tbuV_N3OX(*nVF4%F&1jYl>E&yjiSSS zo(4B3w}aE~@Z%M!8J~?xjl1Y4KWgF_^^aQs`A$I7T<^nUHTAu@dM^*)*4$xc-99?~ zRHK{^R~owX^mp z%GJ!)eQ$5CIYcFbz-N*Qx^vdfY3Mqvz`rB&7!<0`6F z+SXcHQ=seaCjE&)@&pn0I$UvsE0p>~$-{BW^ORAiN)FBhW;{YmqjV@na*s;Z8u*{`@bqtB32vLj zk1WnQg^)(LFG8B`lV%5cS8x0>bj1wI8*t&dw@i3mWFj8{V9#)1@|?n}uC1&WdcSlz zI^h;2bQ!?w^etxxOg3~uim{#kdc?=tdU{jFfN0fg07ep)nKQ}3PCDOaYNdBas4a=_ znpb^aEE8Ahc(z{^Y6=THaJF1-97|KHCbUO;JYtRu_`^1lLQd}(-`n~4Ihvrz)DWrA z`uLY^3tC3~!vN3n@lQ|*-lFkxry_M@N%wD)_GAOK_{|iT0Keu+W2wV$X+gdXe2fau zpAXfN?yBR%z3ZMl?tk%PQ+UHv8;u;HZ=hqzxpE@(vOO|Qd(=;rgtreFAiI;S(3uZe zgd)9#x_zTo^_b%taRThh2UjVBXw%~DFqr+3mIcD9rB;mpLA~(9&P#NkLi{i9@|lvW$fnX z?y?T!{KxUUqoDUrS1Z-Ra}a8top>}w>)-f!dRxS)Fg|4kZA33WM57*;*#g( zy(NdMEQnLNCyb$@TIBybs^Ku^PKrAs<7BaWs^O0F43JxR%GMv5yzy$C#k9M-u}3fT zpA`y8r*#p2K6;8_sOI=TR}K7>tA8(xHYg!`+C`YY79zoLdxgByv0`Lk>=+s*p4T8G zu~|iCg6w1`4%D_ix_WA{_~cQSyo}|87KFnq*RLg`Aa!%^D&FuqQqr{9Ony&+@RX7` zBklr7)cUz__XI@+WLIr4HfuWA?bDEMrw+)Xxg^UoKaS?9~`>uY>n^iSUwlS{Rm zshjj|jZCSyE*Gkt#4cd6@?)v7#IN?LA3>a=X;LS&w8rn>ZYSto@oB;1H1Zhw>=!+0 zpK8I57#!H}IhrgU7~p?sOYi&_jr5C76z6nm;G-G4beSWRep&w8@^g;(VI(D`tbG;d z78W`${w)!wh(WaaKjDHT+>c)J%AFkYZGJI+c6N%1yLoG8X-Us@>ShB^X8rYsv!<$W zVY`9;>}R8Yk(#OZug^W_JyucmA2dmbie_((0H)=gG=^)$@{!&mcM*4|B-^m~ zGqqLC#eL{C{p-zk{ERL)GfQt4)Y7Z3&dtr$+d6&9P)4@Ap(^`#i_dy2WkB-Po*?D5 z3*e~;=6h0Y_u{;{Ge^g3LA%J1^}w)41GTixNqO&kWOeDd{pV)n?@|e|NKxLC2p2y6 zGD7u<<(*BOw)Qi{GuzP+B0gFC#lU9+cMV8@5j~mQB6Wa?X%mbQgb*bQ+3V}GQhLDC zYWZgd6}R$B_Bo<&FZ*610B1R_i{|1rg%3l_KQdaP4>HA%Yiqn2b9_CujSR8LP^cas z+*9FLKDmYiqtJ`mpDA&l9n~o)fR`06U_C#c!_MwXOf+YIX>b9{5PU}LY4w1i?b zu*s*WWd0MSFCoFWBo`0H+3B~dJ#D9U9J;NXyfY{OZP*%I@zzj<&;*etT<;5ZwkfN!$s4b$ai6I0 zE;q+k!kzlaMpSOT?ES}3Puf!6&8@sjqLnmuz1w3i@;j^Qbo6g6TA-NU?5xZvPBTx%E$Mw~irPdD=Gan)iao&(EEC?BB zIFS?f)pG7uwB%VDJePscShf6m0v)c%L)%q(I9ZG>l*`OqOwZVr6h?v3`T#ByMV6|RvwK?lfGB93H<863bATnp+nstYpNE6Z#A(+WGIseZcaG- ziLJoQQ24^g2hE&1l@ar@<;{dbc^k}NfO=BCB<|ZP^-eRt^2b{(R_PtYTAZ{2dD99CMI7amUYh@aE+ z&*$iSPgFKsqS{E<<9Bb}TGA6JsPfXR_Hb2Qs4*h&-9fQ7fGoVesoLIP;@GX#879cm z>pJT@viQkWmRMM5s1K*me)d(!=AY6!c;i>aut)VmT()L@3~fd=J}*wKyYE^jCVacC zQH=1H99xge$uy1cx}sHe>u_d-bP9oV2)QpZGgzu+ZGET6z$Y_z#bH`x`6C-xJJUB3 zR2)tHECQ&w3?c=jxTIv=YrVdISa|Fo6^JRVl8Wvl!b!ZVUSN54 z8XNAy867i>aTPQDnc@Y~`qS1gvZuJb&YD}F&AZ~AW><4i&h?|y!t>?t_tJ%xs`rGo zNAHVW7rjZ>p?Vi8a8hrrGJu=RJ{Zr*!M3_FvXnlu^hvHEKb+96yjNa^$kg?^NxLcM zSx(j}a0?}jPMP;b$VS|bTz-8x`r23pDPTZfhDnCV5%E!QF?AhbZGWZaCVD<3j}2}Sw|2~MR%n)~@WX#j8-31wDdYxVk$h=eGK6dVa<^(s!hnn`9T6_W!s&-1jafhQDk1=P3`b32>6 z?t3?mwKam6rP<=&POfKc+?s!Qt2=TfhSL92!R^2l+d>AU8{g^!-!H>8rVx$gk^+HR z!=`)Cp4moee{?>K#hTwc$!VW(Fl8+B_L7psrToUN`aR%thwcVq{tflhGehh4HoH7r zH?CeOmAXAbMWYiHS!kJ86|H71S^I>kJ0-$UmF$_0PTw+ipjgl-iHvk9Y-+mWT2V}l zEgl{dDq_Wsy(`3d;ax;h(@&v#F!#_G+&SIJYou&XUoO1M?$!bHwHRPfNo%g+dgFrg z1jZ6|DB0HcUV<*_#x3F91=X}eP<$?dzGS0!WG#@71(>Z@m06bReoorY(%VfOh%r?k zBsnFw`+X|7iH>#S>hPSB81E2c&?Bwe9c8(++M|zht|#{tj!q)c;~GC0v73JE;xltf z8BQ?dgqdooM1NM0W+xQ>eE?Q##>>DP-mQqZ_AxQ+5XyhY=YRz`cCcC<8Ybh zWRBA+Qj=G@CIL+>Rt=Ga(;~XekY1r`&>`2|+~r^Q_S3{{5hsWhg~zcMQC=U$aNX}M z2QT9hg1C431|8AT@ptfP5i@IFS8w@|2YySRv~?Jptcn{h^yE@A=zX2oi^o@orxwjK zRb*dLxu8=xzY)g9?NQc0Mj?$anrdAcRxvp!M_n$`%ks9OL&b}ia^1m#xbm zugQ~Xl@gxZ@4LBZv(XCEtRq8zhDw-ptSHX9zkfD2o8aJBM~G|JGBFLCag)JLRcR^n zgssbonDE79g5*P$b8KBQn(PLEKvXGYIrXso;cH*gn{NbDKGWvu*d*)YfD@+d@NO`v zCc%}kw7kW|`DYCg9=euav^_EeC=MK!568bh8M!?1QE`QVfiH$)YkM2*gDlRWB<7B_ zxDr?+!>LPKUd;mj!&VB4!_tvkeQ5}vlTNsCPMANhdB*(ve9RjRey=qWNTTkxK32D` zZ<&}eaUl*#Prp;;Bl)zD_GjrW+qF>;ARh?znG{S(B6A3dFkMf8_uA_iSlF zu!O!;>%FTY8qVHPIBq+63PaUAfi4JQ0d$FR+ty4IYXAgYPN78Ko&Mdi|lnREh_TfAVI|SuX0k+tc99yYY8T9jPadZd+p2EIaP>C9jOlM8WXhj zj$URx2wO_ZfmCcsMIjzcg#9j&&E<=2%;6 z#%FdMytLvUh7#MIjs=v5VJvRn@=}c);6ZlLhq`&NZ@J>7uGFBsz%Ss&Ky0aga4oW7 zLPu|7xYFR~_5xXjCMF_o+=exNXg}ZGU%!te%r@$w3#_(ch7913tu%QVt5Y8<-A1QU ze)`hd=h@`?8@|##-4;i+)EQK+xjiP$oY5~YI5JN4w}Nq=75}7`89l8z(k#e#Qd<@& zEs{UsFQD}@N+(|2cb6!IX?zW9%q=x;OXyxgA)oy*jC1I_Gv0h}i&5mSRal2-^vILryz9tmfO;8i*_3KZh7xBfkUo9&IW2AO%~tCY!*g6^uP6BoiPlvc z3F63uDe*2zBG_4b^1EDIaa?8bd*GBV{z1mlN+@T}n{%yZk9qn|36p6sN=YQ}$Sg$O zoWl3VX025&tqHmhUcQV!T#X%&JUl&a!%YAh+z;%kj}{alHbNq(VoL7L!{KVz2W%uQ z66_ZsbX0*LwERm7iVq0wlf5R~y|Va3Y*(8AmF|&GU&O<{UsNHGEa2dw9TH5jgJ2H5{mk| z38M>SFzRQtioZz^>dD0Hx)19AIIj5x1;aYklSR%=PQ=p!Fx_f!HFU^sNVMNj7#z-v= z>JQst7jV$#WI&T&B#Zi$uQBft8S01g$NzDre-|e@HWrjI!7F{gm^s(zJ_?tL%(O%2 zOI8rY`FEv>_dPoyCRU&re8XD}Q08dIjIL4T(`2aO2M1_;$lW0}z4zvn+9|d@+K!Wo zC=^T7zJKkmUNAdxs8uv=5KyBkr%xB6x(N(Md!$Yzu|%l?rbfUsXylk%gnp?$G;qpJ z!!r^&Ir9BUhemz60-!wKn1byuY_-m!Ze8(vQ2mUHieU%{5<=I^K5UM`9=`s! zJxryAfW0|1p53Ai5l8OPPL*y(dw(1j>aroSs$9}3jHC#}OD(=J z00mI`)RvuBPpwG*bNk%GqfstnJo2p16$e~j77z(F0*Ho2K{X&VWrN@;!}(>DquX8D za0`sfo`@n>Xq;}ejX?F9lmEutg}&z7BN999qfraj3a64N35_Zdcq|4CON5Z z6dD6Asny@7_LRTQB>x)Il2Ckym<;@eDiDLq2<6DP-=a3+rk649I=2cUNu_tbEfz0G zNYi!Ceb9(jVTvvD&1v3X-f{DD&T;ooPV5&Y6iO(~iMsbqb|)Y1 zp5;`UdVI}+#)CZ){<~D!!0Ooz@hDHGZ zoPgT=u8SM*P3#}TW#C8?97SXL(kwvf)hsr zJ3HN}3DTH?Y`~S3gkr-2kLF}RM~AG+%mm44&j{7~ViHvjt0vLl#?LMD`olkFL#H9P zaRflnf0Q2v29|UqBh??=_Tr=R`T{C!PR2#wXMwfDF}*YrA_TM@OqN7(yiwNQ8b2`# z>q7rL5Y}Kt%vZVnK#UIOt!m+S(!%Dw6Hi!>T$8V+uAqsityVIhn+UY#S`+`d>B6Lg z_tHg1ui{2M&gQOF(K*oTKWUTa127p@;z(FR$Ci=QfUfvrr$d4Tr*} zKowy6ai_(xf~3pacE;6cjYQ&+N^Wbtd+rlb`n@I38cWPg%o7%L2G}>yn+giSOgs5G zl|C?XKjwa`t<*ARY#+t*`6-z9t)A+7?TWG7?cp89#S(Vj?E{6kNO@ON#~@HR9UjPp zDzD(D_7WV-K9iLV9;pPTm-x~{I9Ro#H@UKx4d04u{1uqr1ml}G_~DUXb@(=<@M_{o zP-gTe#v)7W;aZ9$0qMv;vw-&z-{J3j>4VA`nK-5_6gY^<@`Rox-oDp6JiNYhKrA*# zqQYUud%prj9=Yp&(P{PlQVv9&P}eTAqC#y=8z%$c`y{nnpC`(ftUM~pOP3GmNhvC+ zc>-$??VCzT(W7}ZO@e8G(#Tk8xoAG2p(#{+jprO){Vn}F_%2j8@ivV|SyjgqStiFn zOGD1(3VpSt$8qGp9MQhk;7nNRNhGCTx;vpKy(aaKso>OvKbBsWSlf<(8hJXn;szQ~ zf%+e4D79|w10uhy<-*^9JiyRm1!TD zTJ$243zXEypyY(FO4FD>(GHUKw7Ud?KHA5(Z{Gr5dejF^x0$e0(a`X4b6e>>|9eC) z%^@(*=(f_kY19vHW1A>9-424rXgQiP-4ZhK*JdqB(owaPMF}U_lP-JW>*N z5=``+ot;YN>uB!r5l^JRJhAE;{m)B08rrYCPQ7+RX&J5rbuJ#@rriT494zEzjg=xx zm<}gW811J+)0FJs{EYL4S zkjx|3My>Up>s}hBmpPyHK#y}IfV@gKY1RfS(AMvCBbK_zTGal&`a-o%qJP<@ibh$0 zVurOm&YMsYp4zERfHSStHAg(uW{mxgK>!F%-3yvM%KAmi!CKN46oeBDx1l)I1%Ui3 z5VSKko^S62a|OUALBDOd@NhbOQ$%~&Y{Gt*l-B`(rvY{_D^5RMK8x?N9V5aszWI6O z4Q}~CM1ndvgRKYAi~AGWfqd(O_wUa*S3A}z>L7MXXgh!?6AC+L*7Xr!Ou<=Aa&PPyNxC&KlLm>v3X%(!5;$~L~Y1f2ArjGVmCce_TOwwovhG*Ij=I3Pk-1_x@W*)!Y;r;ojJc_?M*H9g%&_90ND}JllcwA(3^)o9=urh); zH^moobD7omduXJR=Ln6K?UU<1*2WP`^iqtSWPC6uL5&PQ_qW|y>Mm8q10e_=wldsw za(X}gqJxPS4tjp|`cd^zQ(-Ck_Do z^xRjo0EFNWz_Nv1=hD;*GHF3H^N1GHYpmYaKpnT50=r66M%W(e$e&E0=N!>(rc-Jp z(HjjcztMwB6Lt6r+zV0d&ixVuc(}NQ1`YLDS&PoH+Q>tjjPXyS5cFd~t;dI%K`*{$ z^MFzdmC)8|&$rATGN8>1?9Hw_e5O|$15KoE&|2@p_wuq(n43x~DmE-7Sl_;L2YIMU zc74U3y;?e5nuhc?x_gz#-5>k2{*(J#4Lh)z;o1*EYf9wgH-lmtvkVPLVmFmB z2?*)XG67D#r1he&^iE)S_-~#-`Xng5#fXg%bD2(f0Q)1W;kVC*O(+wPkdW{I|2up9 zb?W;5ySL5T~E95kO7mZQ1xEV-_?thp?@TMmt3muct0SNjO^rnPu zs&##!Tm{<-AugBf&&I)_I$Ce2=EGK5d;_gd?A3)Q_Kl@TrWeHlhHZPox+HlE#sH9? zoECim+f7eTPvI09BAJ}d84S->h3Kd{ZMoJzh(GPY_IWipkX63iD_pG*!$Fq^08)T> z)?9N5QR3NRQ~DGvwGZHhcB13y;S5es^YT()Crp^^6}BuN&sIzodiCo?k!;iZI{mF6 zJcf$mpB!MhfF5=}D$i#vv%QYieC^UcThI|=N>V#II)dX<*41T9?JfVcigXWdVfQ&b z1}HP2Dgxjy*Wsc#*X=!2(?;oLs#!>}q$CkZ*s9s`vhuRlmUh#-(;myK%!h>GjCB0T znY1pVGlfwA`7Gph=!~wM#?Tr<Rn+M8?LaQ)`8dJq?Z zu7jwVnVGe90jPs4z48OJ+TZc=6=)b3*1*CsF*8?jR?+fP<wwpfgWARq5w@*DRlF-mU z7&JIGlG4)h(wq8m}xQpRs3YGF_5g@dF~q?OZ}^vaPLg(2KJGM zt}}Y9Mu5pe6*sG>5;^5MU31nZtlk9MaYp*S@JJnI=*+uyE1=xW%)}(gO%PDMMlh+E zgQ@N*#`y&~2#_NF9`OVNld!Ml1CU#AEe`=h9!ab@K4+)qB#uHIyco-sm<7WKXMPaq zJUR2459Rq1NrBdkcX4fTT!En&o&+4<{E*U&{N%%d%*wUb9-M@jLFr&}g35Z0yQW5K z2wA2OGd1^R^DRkn!@*K)c6MAW%ht!UuUkGo2Y4EsL&GQLNGoImpffm|V5$>5L424yEPQF0h*-3lH9gi5W%ko;~IYSYZ5YCfB=E+g3ngkDtPH{pTLLRUS=sGms(32ahuvFdee3$gSxcqdZ zHpL;OgI7mT{q4*a3qAeB==92^`DA zcnmJFG0>iaCNMd+(!s!z#FnuW0Ce`+Fv!$!7Ylf%Di#39?w9NIt9gKTMXYEnE-o9m zHr@3jf4UoNa6Eso4BcR=kVGBf$&bR#2TD&ZAsUgQxX1>Ji?2B!lrO;L#K)4d3(R>g$O*zM-jGgA06`ymBG zqy#IekYjU9WZ_G$6{y7pp+a*d^di&!KlDeKUC4TY&wf)w;wBnVkq2jy&cMq}h@WVK=_L2r>yCq+Wu2lC zj>16ihO-(4bJ394HZq^%h4?!J%z$fTv%NIa=Xjn>AbYEJjalz#HghvovP8htf>yEv zr0(Q@H==rVDqd)TZ!?ot?6AgJvg>qSNr?t-3yrK_;aKn3U=Uq$pvc`v{JXBeosc<^%fQGc%wv+TfH zfjST-PY7w<4hVSIRL8&IT>D7HOHXgPe9!h|)}IX!;-_*-C#QhM?5~I?1>ujptT#YO z|3>T3*K3Q5G)aqF=YvTKz28@QGFGm*z(xC33(@@zVy&&M4PMO!0Odizf{J0QV{2$LF)qY|wyJya?DiwQuor(mu? z-4K92{rarmZe9WPnL&n&sTVX~CnW=e2D_=+s$Q3u#1hImqco{!okmEshF)_{LM%1) z)1}j+-Whnb%><|Usb}I;v2{az7-i?2!yinIT7IqZDqF;8oh(Z-FkWDi+_Ab64~|q{ z&;ev0hRR(ePscVLoFA#j@K^vD0Di|m4$fq3E=8J=!`R{di8QSK0q}`yKtoSEjqN;xidEV z?c21bw|YmFCCQLQ1a>}4N62{jP9WxZwRvxAdiwX{pLamDL;}5Mn)_#pY!I@`ZzysaK0R zm%`mM1o$N@KypSvK!9=ewJNhZ-fbc%e+Icpd^cB`Dkq_lyqWq)$>}c)cq1z-3k#U- zNSr!tYz;m0oV$V4@$p%T&jZpK@j@pxaR$ueWi4Afc{5CeLdSituXWmenOn%MO(3qG zOct={%jkWYA*4rUH+48F^@z_fzVXJ5hQoQXhW&;!9WDJwnCKYT4-+_E_#XNfoFQ5C zJnYviV;E552^hjBt69PL!)lPc0AOJSNW+f2cQd+MT5>#aOX`1jKt}a=Y?|MFrnPh5 zf`=Vo(9@@Q{BDPB!S`eBy`5Uu#}_^J^Rd$$elLi}S$B8DfUyV*=al9h>NcCbj^F*N z(0u0&vA&UFy~Na1VW%az^6{>AG_YisrFb;27=U>{@LU@$5%z3VZ5@_2Qd0IS`)FRe z7o;%!3Cu3BK%Xf`x4wNF2X8v&{KjwH!)=R-NJff007FM- zm2EKN4)8mGC&r-u^zc>`H4!GdG%k=q37U4dmeLw0dK93IkRtQu1uFsO=jtk5Y?tlf z6`pRgvYi70n}jM#td2vp(vepA`9twOha2|22hwY7Zt4Y$YoIM^u9=;ljtXMH5bhk{ z5b`KwP3l^8_69m^8Z^^Dr4vZ9imy3>a9Z3-Sy=1=-+v@!vYYgO2_tt=QBes;KF4R))zsB3JS_$@y2-P}uuTzP6Yda%Cv-C@99b1_A~e&rmJh z$O(l>J}+9p*uSLk|Q%^@)5YzFO2k&kit&H2UiIJDCg7dGw%&<;6u7vU+s#)H$bZvb{xpvRx zNeQ{~LuEvV(t_QQsColq#>?E{Dwf%Bb)lb)KQg1al?$-~T``W`Pf9z}+tw#~(pWEX z;^5T0D$35UsmK=9&2KKLt~oO^6w;vZkGiH&_qdOqCkhUlco!5=(VJfZh4Yt}?554h zkuD%R2UYViiksgiVwW(>-QKluKYpyd=GbSgn-aMcvxx0At&$pt>J;$mNEV?Qbl|S2 zK=nRlMHm6dSFE9WY>Io#NG~$7s(XH&>TDo$|Rs7YBZD|o893%^F($u$2|L^9QabgN?tBo-`_UfkOSlOh0mTg32;F(F~44ur8* zoFz7PjN5LOs;D)%~KDD#{E`X#Of}evN2cGTE*?XCuq3 z=LpnvYX6eW@8 z#20*IBFT~yyLxi#`=))r6Xj!Xc>scqnG(*VMeJ@_kJBW6XiV%X9g@g=goE1+bu z`xapB8b(H64gftU9EppT6Zs};q`ex@w>jtc;YFl0ONPU^N$aVYnsOg7%PKsytZo=k zG9baS)O*-dGG4q;pgOpgCn#A2 zg7J#Aae`mgdUUmvEhfZv<>6H{A+D61vgsO;n103dr0!Lv#Y4+@0QD?~hSq2PcR|gW z2H+M^S#b%(`nHw{F|$drA1v63lF*xmt}pAFmyxf~`@I%>Edu2o!olJSPM3=HD`TV& z8mVlf6V2gRL%P5lO<6NP$`MgJg^eefSDF!a+iAt(QWdI3Vz!2R)|->8xss7dNrZ!4 zl4O6`nEc8YgIj~tZ?6<_zD6mRSMg_0nQ7+`D1bzsgF!?M`uYcQ|4)n; zeOV!`p~Ss#c?%u;B=*%C8RUe{{QjQ^!r|!OA{>xmXHRbn3W!YZO*Y&pmd%)O=vo_hEyi%E_#de4_pU@NZ5XmWqtO;3-l2FVjn_j zA(^K4+ts3tHL|T@GndNwK15h>=kZNDJjZRZ0~m?+H}iM%qn6v&-T(O{v~Zk#pZ~5jo!L#!HBhNTs7QQ&$3c|ays3%M8ZA~4=*AJ z!j0DyOaAFOrp}vn5B8%jt!c4r`6seBO}@vsdkQP2xJAadyLvx1C;TqFoOI{t9;oPy z3Mn5IWUmQdc|7d)vO-VqqX;=p%*-iwGopZlP9^hs1O;9=o$9EM6AcCZwFnA{Al!@J zO3>@8fBpmNpOvNs#~N_MGIr`=o+FpQh5zST$B@%y z^shMZR&*BUfUKY*uTGyO&rTK(A78s@BsLbm-anJss)PQfS63`)IbWxV0#`h#p9P+T z@v;hal(ejLWM;k6+2PF?*|Gn){_uu=df#zAYO#Zyw+~-HwhK2GH`52j)G#WY0 zY1~Ij!O+j$+pGpbS))3$X&W*{rLV(^N@jCRnkP5u~9P?jk&o-YdpHJ zYH6GV(*uXTGfQ#@@>$_~SS?E~5(tVcPoWuxlDc&GAmGaoP(5Fcyz6rDKkQsbCaD_CCx+l#8=7(n_f*$mss{28!Xg zO`$4d44tBo7|aPKy{X`v1R_VwI+%V_7S6=-mei_YqxNl^Osv@NKSV-gpubm2d z&lLNX@R?N=HQe*X5W<$~+(#30OSO7w*pg{`Y&yfs{k>s%fepKEwrM_pcSZ7tEEkXe} zsZ{e&$JXC=FAZpNvGPk8*FSN4%>XUwg|$qT3D0iHJaysjR|R`Lw~7NJ$RNOR@Acy~BY5LhTyZ0BH56c!A~_02ysjvwO~QMZZq9Du4HWP6~o<&rNV* z@`cVop#Mwfy#A=> zawt$a!4bf^aU4kB(Mp}eDAQYbJHSq%m)NWl-lu86RO$qF?mPCsXIH3Oqq21mCr}Nl zWwxhlt_|TOREsvJS0LSWLeF?)7v5F`XX^gmQK~I9@laT??5w`Z3VQ~yHse6jr!P#5 zFGxx_nR{0SX{ai-Zj=3T_wi1THqCD?&92{bjWM;;VkaEhvP={$Q{8$G%vkuhOJnot z2_N;K*LcmiS+I?gfqm}ej~}`F;wyGX@RYV^jj+d`&ziyVqe+X4s+Bo;#K)M%!`CI} z*KE#FNf)-)_YDW2pV|P@v1KUhs)e)WD3^`lfyBo|&uIKL+3_12ZU?9F6C(aLN7E6` zvKGTYLlm2tMRH?qI2#=v2+Wn>mA?j#qaFh6>a;)kNET7(zG>~CZR z4A_Tt(79hfhj!f*;-=?6$rh@wWvTQ(X~kB%3A!u3xnokPO{17n2nULlDmpp^`@Cqr&6n;7ZB{KmpSiQ^ z5g2#D!(=F+*UWzA;Zs~hkBw0vmS%6Vh*dhV`v~0p%{+fEVqJfJW~TU-C=RUnWpZ6K+~Qxfj#2mP1)g*o;at3p?eE(_nG>ev{WTuRqq8a3n|~X9|J9Gg zL=xm9j8fWMT9zR-synUD8QXiin1DSk1?UPiGhDnC?Q26`zPpolYw0K9+4@jo+~f9zT#UIR{ZJB^?8&_mTrNj)~xlvg6-{D}TEUA~%^P6C%8 zGaKVB;%zp13FDd|)=yCBLl34s#9bxMk=+7g(jv!(e_gIA13(+^lfPr)h)NEfbBH9j zv$5*)z;BNFoNr@ehe`j|TF+Ab^?5;d$9TX4WjWA9TmcDO^7Iq(rQCe}&eh-TGOv4? z^76q+^w?P1>3)dqr<6Vji*|j=)y;^t|} z{(x#*{u_*CXS=C0oR z-$KqPO5nqYw0j!~W3c|^#wbv3Y>*k264cG|xh)5?s58_PL)wy3n%Jt8yIlp!OR5%a zVH)8pwC4_H6msIbEhRyCZMUHvL>6%AuuEg_XAGZ*S7@bASXj0;VOxNH=#}~A(=oHC zyKnC|Y#AvAq--dCEy=aYpuAhA-RowaGstH@U6&;r=hE~7*uL2K-3u|;zA4a1uI%jS zkbz?~N<=3m*>EQUJ|7{I?;ik(B{vsW@44J)6?WVV+RbBuAfp$D} z>{|Mq?~Xe@sz;M|IC2e}5w`rOe6cH-sN@(~B7C~(3Nw#KH3d#S4EsJU(Je2JeX=5DU#vq=6!=awX6}PLu2XM?iYa?MfI9F3 z{NP@Js`=y=2&E~pF0EOg>cSUKK&u33z#fujlmuTF?R#X@pDqD{3Lv?R9q=q-4Fc)r zOrZ4FCc!eu3>2Dr9WJEZ;8N7?{5$Zz7TjI_Bj@V;$x(P*tfbvkxrb}Dd^!=&%b%uC zB!@kEujjpxNvf7!nx3-ViZ$N&%Hcu_btE)25 zeWYC3-qlk@MKwG;BKb02rhK<*5=A0?w(R2#HGj;vao9q7Z8wYeXB8S#V1ZNluF2BPVR;^XB*Lj^#0#Ex&z z4OdGUBEdBl5T)}QAfoJG8z>~enjnD?Y7+q9&7%r%(8Q*Y`Ejr59{Tvb!5=H{Tz+ z{9@9MfE2XKC!xA7wG$ItGp+`!rN%Q_^`3`a@d|OWFhyCXoi*!`r>Etqm1ogsUVGz0 zCx_i11t&KhuKPDWB=h_=xaHGOTgL8~is7@H;TBAgV{Sqi3N$N@_7d$+f4#;S0lMQB zzg}#pZ~XqcJwJgIKAOXxd4(Ll6-6`C;90Y`qFw-z#UtbWRnYcma;kQ}J(EuLkr#q4 zeDb6bw#8h(EoqxFs8|TmgDmbJ02Xd^Y?6`2V(p3NJ0%T5PdHRP8tRMfPOM8#09$a+ zpTNGMF+!}sWQFCZaG`v?adpk@E{@Tj)CMyoBK2ezV8*RAT^yj`g1K;IfK!h@3mI5d8(JXhQ?^)!wRM| zn>)s!?F-oYM^lW*z}SDAvF^(jyohUfDc$`UQq}@bv$V|2mWW)Rtby+0Lb4KVW+$Nw zOz+5vkoASgf*8suHDCR^FK0Sp7}@~57KpBQsZafSCz+uP8J3QsUR<9xwy=rDEG<*P zdpVUZ;Sn5EkBli1k4^BdGHR)72@ZeASGF}sDx!3hDpf^_QX(oKT}tRpkltJ9#0rWEo30=rARwVh z2?(JGh%_PeKxooyKuQu?$bAC%zWXiXjPc%a?j7gDSsyl%y;xb#T2GnJoWJ>>mGH@8 zyA4qr*nu2fG)rve#N$#*=hA*^+=r={JGrM5FoF|+k;$6$By z>QmZ-kH3N$Xjar_XRV;2Q}h}EhzVHv`X&dFgsaCwLxMJ1mcY(w3&`_I1Bq<{w8)0M zG8$sGF>j{9Zt74)no2O+Y}Q*es|r|ejHuqJ7r`?8z)Ejso7tIZny9rJxm2VCO4`kJ ziwGN87Z|edz{yLm;m09C6A{cVD5t@1FP#LSB%mB6=I5zxIUegh+#wq<(Zo9qsuG+! zdU6SV@69A9swx!ngpZpF=8F4Ap&nW^%Z%8x_#-jbVZ^O=>a-Q(dR`h^qCc3p!)LM=-u zk;u*Qxt>`@Ml^)@9_BC+-vCOroCFh3_0DEV3_l=out5IuyA|SvS-yS>Vh(4vvyz&w zV$=4nXcjPS00F`FX2%ZuWy2;5I2Efr&@zfNtetu9WId+9H1Wm0HwS~s={PD&qJ3Z^ zSA$%gHj}khoe%(LhrpI}40kVuF@mGlblhq8?@DawoA8LKyvaCS`C zws_@uPrSn?HRnf6609mY&vZL*>*gw*3Hu$ow&mzfhu60_+Pk~gW;2u7BwaaJ7ORT7 z4p6lp*dHS=&V?AtbBh5>V0$|tt)s6dkcLhAi^p`EONNcrfFr{l)m$i}G7X!fQAX$X z*fhiiKHsoKJodEaHF_zaWc(>Dmcfp|a89fj0|eNkdrh0|6a;ze!D=T9?n8pbCe8E@{KNdn#2)Ni?dNzhEz zVR3NYrQEK0ZB_%Qm~UcCyPV^ty%0mrBZNhi;tn3y%OfJ==Q#l+PcK~OE2Q&kX0L_x z=2w$i%-C-Dt;KX@$S+B^GVpmgajtnVe4$WZMZBTODGUZ6M6}}L6v!R zoy!X2c{2Xn=?y^K*|Mnr<}l5GQKg^P`D1)`Uf&a@(8*@^@88$dbZcu|MMFmFuhNv* z!&`ykse`QyHi__Y{^5khYe3|lve+~BAAL*Z3mw1>13b;iDHnl|m1m&u8JT`ui2(@#US3YlI(sA&q#FH>a2e2MPV7MyE@m8b_f#~{Kbkvbjki`> z;!a(-0$&~jLMZ1e$UA09@F1drIy!316YE&A_WE_T%aC8Qnn8cR(~|$-Vp|SL2Z&5A z4f`LXX4}RcV}I|9?}4n(YMe6&@)#;FetpVmM+818fE~DOCQpVZ-kMp1JR2G)H4Cag zXUU^_r8r60q3_oyHg3Bum>L^mcz?@}Ho4@scF@=}7~1s4jcFD!!-Z5$$uf6`^7{@8wcWhW@l%orFnpreeYHQ9(|u; zVcn9@|7`v^#j7k8c>b0Q+H>t493)(Z2Uj+FBK(xj+`Wn$OJ{JY^iU# z)vD#v{2dkNDqmn6OrOij%L$m^g>(!rmMvAGstL$?02CH|xaBW3>6~((kA>#slV4jv zXm|0_{n0SiqNyKBg#$<;NjAC3R!|1E5S_*Za~w$mKA;|qX#(I@`u;czW;3HpW3qN-Xm2t=D&RG?4qk)c&JE#)Ty}`t7=3^u8NqL7$_TM4bnlPjKcLB z+kiv&gUpT7?vDO0~SK+1bpIRg#bqKhVQnU11pU89zcRZPy$YsP(Cewaz=Bf+b9sAGi5v z1Y${8Ae{7(7;$TOp_v9asA40Lb%z^fz&B(RTl{8jEkPFW8$H>2aWOGo16RPtLipRF zi0W=y;-fs3T=nQvB{~p=MBM+xd~6{{1G4dLX|=U%u^bGy zjPKtc)P>ks*@U#&bcZDS)H;_Y8?#4#1oj&qH4z!e9@JOzqbmtLAGiTlq@Br@r5!9L z1MD**dPO02$&sLxNO$Ntmx@h$UUs+kKQD%pHZf#;9Xp$pI~T~jWs?2^UW^zN8c|D@ zA#YD)Y4fTjmd{Pbo%F_aR+V$10vkU+Xi!n9hD|53J~V?*#xOfqdd*nHJ?FM-C~}Yg;4UQ_+SUodXujmz90je~hr^V^9z3 zf*&6`HZ?tMB*;K>6pY_fdv3;C2l)jByM+Y?5`ULpQnY;s8!A(9E`&KXIK3s zDoF&FB%d)y-gv*+`t#gMn`59l3J`$?rc9wA7@4r3Up2hAHjbWx#3M(tll+}WJJYd! zVB@9@MW&Z+RJJDQ$*!tC?6~JY!!G^nt9PsjI$6wtAcomxshY#s;Y+HoY;bnTU&wW| zA*L_`UxR)rX7S?c*)8ITnSp5#sZ~Ow2`$0&26X@XZp+EKdD{(}_(T>d{>=f$Pzy=6 zQ!v+Lu=k0Li7^31If01#d`S)H`9IDW3&#zMQbxfSK0o4OrROZz9RL|tN)D4mP#v|z z!f+)jBZH^hfU0B6^Cn0gg8%$_0AxW`Wg-wnt7&74f^%CHBHg-PXrGyg&ekc#EovQT z9b7L-5*9mzz_zr4?WdXyfd3_aWW0mGgXHAoKwyL@J$QMsl4y!^ZwO-r{9ZR@Bw8?R z?YV;64}_ETKqfDo8hbxQHX{O(Aa!q8vRvc^JgNKdkoc@5kC|p9A*+&@=`p zdZo?dox^gHr)gNJ*I85D9Nm>0Y%UyZ`_3O~$wQEMMbIM2gROY; z{d@IHg3IaMNZo$GhWlQ#?e&{1G`Pa~EU?#e;?KvZAO^I`%F3`-K!g+I`&roVYu(Jy zfewum)k>wl^GacQF8};W)vG0X97~SZ0*5;$;odFn_jwFTK_f$Fu6+u=FpLGB zt=*d~h`m-ew3sL2YX@Rav7Gx2*mYq&`3Q;?0P#pAUnBTdl8$!{k_jSr2k z%Cc6%&aY0z=Weuh2byYNith2%MJ|wX#h=QNJOZ62;=#=y`g@S%Z*DQwNG>m#k1v~V z?fbQMT}z>H(Fla08fwAsUm}_1kD>{l!(+}H&g!NjQFfn&X77Jx&y_t>v(UY!aM}1A z&G}>7seDWpJ`U505B9$$C;gi(a<3O`10~0N^j5*hNKPXr!)69}GMlWF2&Z9+B1Myl zu^FFOj({nFi+E~F+R)?N1c`$Z6;vntSk9_6n+lz=If zi23N5QFtY({W|Ya8^Vux?87E6$GnOpYOjNSKWx77ZUMI3050P zImS_RJ8~mC@T}ZnEC}`3&hWgmZpk(14-_onN^=Xzob1Ok(QJaiM(T_GKW~p{jQ_U9 z=Itd}At*Y)bsUp!b*gm0EGs*gCS)y%<~-(<9=7v!j^T}HEAeXVeWI3SWxMiH8D(ay z`Q47aF!z}1L#tG-3+wPn-o?ho9~v-1i6K0w=_~$?7c&!6Ex%3P++$&tLbM9{hnUg9 z&`7Qea06)7!2APBx4z4|9}@qd4Mf|r=Gf=$WeHo(%4i+xIZqq=AmzF5Q{RPJ-^e}3 zBiJnTBLiXfoA*#d`FwUfEx{SVaS3ykp|#h}fmP?i?;eqO&frtuMZmGn#tpEbP7?Q2uQ1BSyZlkOa- z9*#=Y2Fuq2C4wel;%eB$QG=DHLi76qwJ8t`hJK@>wt7Z}2L$X3_U`x5vm*1FgSf)a zpFi)~#B}+Wvd;^JZfo5cnpdON)|Utq<2&5GO;J zxSP@%<>VuDpiBK{qs_1A-|Y})GEuNB?|<)9vR0xG*6ehl=r2QMnfU9u30xA98bkLb#w3$Q_;6+wGYxy^WI|YKXpze^}4|g5+4z61l)= zU8F{jXJa5=I8z^?m|9#Cv~+qw-W5i2Pn~ z|CjBRU&@w&@g1I7l*sYJTz0DT_*UU!J)s41;;DWM} zQbz_rl0KFTLG|@*k%mTwhU+wup%%)oY%k+jg?hMJp35#d=kvNp@g2{?nlYtz@Erf% zhRd=n9YD6+;`qR)te0`AM?vgDEn-eD+S*`+G@lgFlT{+~$-)&C>a4s~)MV(w!q@L52f6^Nh9VvFj$8>@Or4JzYn zjZiRfmQH4W_)-6dVFNRbQe=01*1bgab~|CAvMxt~?7_{*xbNf3wm1IK zWKh6y|7okVKaR$2)u(? z)l~2w9OsnJ{&@3y1nt@_zP@F{Pbr_@^ZXs$ru@bs_qzvDe)~J3BcPYp?SGi^ndHlT zr!(c3548IW?cOi@tdC4=k9})nqa0WcgM9vG&lwQsP~_5yc0 z*t#WRGJPtCLCV_lrPkdrd*;s>u%rMy$CCA?=O<8Vd6lRK1r<75&%5l#h$N5f%~9=9 zPJ>^7m$YqAJ9ZLe&4q@BzLMFkJ72uN0QwaI`zCOUpcLuZ=8r&Zg1{84?%wXTgZCcC z%qR#q)s4C~5F@O7w+Ofz^UwYYlu*{A<9ki}5E5nO3zAJ(*$;ir%9@SRkew}wpj?6D z$^I2KK&(a6(2&1nh0z5Bk3quK?9}cVU%&28%r5{wp1AC%6baJWFoT1Gt*ev^JbJwU zM(99w`VSv|t_>k>r?fv(Y6GFoJr)4eGW22ufCd%S{@iqTxrsL!sHhfKD?odI^!(+} zRLpL3&amt|F>V2etBAgL$_>%xbX@ro`p`+C%gb<>@jxhc#BW)=gDtu6#BKH>?gq!UYwxtxctSV; zf**yxgOmD{4#cmTzu%hUk~^M_(1;i+G!{`3)B19W9ubjF@P7FUhY$eraQ|X*UwfJA z(+sH*dHv5*!}Y6@J=0nWmIS1SsCBEBSj`8f6D^~^Hjb*9Bwyyy#*%rMxeQ#>zjy20 z%qSN6j?L6)esQ{gb$Ww_HE*Dz-~aRaNa^7NRI3Pl7*tLOi)C5kH8d2m==(N_;jJCc?fnmgi(8|IO-jh(EMBWFJT`uGv~ zt|WcJz#i%c2qT+JRZwkmUd5CtydiD!uag5n%H%ZzWX*K6C?uq|yjCQa!4_dQa9*gl zV)%jgtIL<0w)&TEdA;FJBr2af^PJFRSUyY za|xzI1xj@R%Mx2XrX!Bc%dA9m3w>_~)|zU2s}^Lb}}K{J)v* zCT&?#TU}3A-EtU_Jyf-k?9L~6p?lMb{W`s)-t81ynZthK{^XthB5OPHeA{~uq9f~`Bi@2PA#A7C>A4NlE|mkv$&T)T zIe1S)&Szh%cf4J?XZlllXnxh%t#pBQ9d#x=QEe@n9&%!TFJ&QguHF(X)nLTz9FEE& z=9b=j{6S8WhCEfebJhyrEvoRn4et z7SASD-?4@TKfwXgZ9U`JZE7j+rl922l@@#wcgYVmH<`h$NK@;g9$V?3t2;l}J4%`6 z4Kn6@0S$)MiOxmjc2<=^Q`%c+4QQ>W3D@4?lK{=Rc583#nYj_UNjy(qukC*CkLLiN zaYLIJJI=>g&JPVtc+SbFINtBEVl-&E=HH`~@*!1P+s(qu1StXZ6BSNj$KA*i>jmL~ zZ1o?)ilu^*Fy4-lCQB(`j@8)XZ5}1ny^qakbpKGUuq4-h_Hed?j=b){1KRe0;h7O> zwKY!a@>f^3FQS+IiQn12J1bYMv6RxT*4vHQ$t(OJqyoerWSm6rS>wQ3e)sJ3?!Kzs z<2X+m;uC_t*Pm|faD>e2ZMD|a%N^t;z}*eSB_=qPG#3qf;R8?ABa7x(}-p# zcQ0i}-d5@CjQf}|Pgx#jF8(&=ZDOsj562~DSB_s}N=8U7r(kl4cia2_1sen7Bk9rJ z`bOo-gV;p=Fg4&&$!JekGWvZ@wfa&uX3(>Jsmq_`+he^s`z@m!8cpM$sy+Uo zFVMyPehK93=op6B$x~6jCYFg{CnT#AatH2$plxoBEIyTK+wIQ+&W8U!n>YQ%*pu$H z4{}58-9KZjDjVbm``X*hPs=A?G8y;WrJP?tezTe&??j5ZZj=k0)BOP;SiBFQ{e6QM zbWUN)J97?BX9Lq{dVeoQWqu#(727qb9i6+#qXY$B5;toVkF*wB$JmbnilMu}n&fW; z?TTu#RL;?q()z;ObOS&y!k>huI^B5i^cwdKd8_oZzz0Vg)iSx_BkdkX3&DBbJR-;O z+svl$S5H3v%TB^X$>+erk&h$2zq6fRzbc!yw+S-RU<(jB0r(N0KLG@}`6dO|3 zI@gGa$;qKW;t&OP@TcQQdXG74^SPBL+a4^Z1(~@WXGcI~?hy3^uC#H`z3aDa=4~W1^x^91g`EIJ| zCaA4%uMCh{;@}Tzo&=Ydmy&mgK;}(d_FK7HLUD*s<_Gh&z5<(yr$eLqMGv0B*l|hI zQg9vHL)#M_ilqz;ix8M9vn8?SsRo2-oIhx65l+#x_fsfQbJC^7Q6EpW$e4d<3vjJ1y4FxXl63H zX}-t3OhedbbZ{{}!@BB^{2}s{ERByQ^zOuiJnojvbr`2I4O`k?=WxS`y@vli2*$oca4QcPfw2m zs#0CuoB2NQX6NRrsZ->nRz~YW=0PO;+MVE2j91LR0uar6ZAP=w=B1v&yLU=TN=PrS z2rK?Kbc(qAfA zHY8^Q#YBYm$|{_^)+L)yj5b=eY3&pi`T1HoF<{MO({`lFWv2li%_4na!*$UMLt2ke zJW9=Y4a6ovD9YruqFx#oqY)-m>&^G?z2h48@Fvy7n_lflgz)%NjEs!flLZ8I0Ci8i zeGj(rGJ8AswTFNK46pELVD&C$_50L7C*NU@Yy&3j&h`e7*sQe~o%sI8z7%m-U@fPwK= z3dSAii$-t!Ab##gRD}*;G$ZvcT|I~=+-YyK0@@b!6h3e>>ssj96{Cm?% zSqD{|Haq$-^Qv;hM$v%@@1-AfT58CoSF+ylv>jdOx5+-Y zi0vtblL1*JOB@&}sSX;(V~m_ihNNJE#)T8n8U`@5jKolozq4sl$HPeOtin_a5V}M| zwsK%yrEEU8Q25v3vVIGF`6K>IU;a3|kSp+9Heb(whLOwRa{g>ZJOifIlTkJdSAf;pXBzNA|RKDq+IvX4s1cSjE22z?HGD$ca6Mw`; zMqUe8|F!5l2^O!G`qbJQ=Zzgt- zatT1vJ*EKPXc)z-v2#TrTj^zWa>@K8PAwsfO-kHyb1h?PiWatT{P007$?e&cJ6)OT zJ;Rv1j>V#EKp|YkQ!vZNF#iUKQ@A4btm1DBF73Lwa`1Z4V!*FOlo~ZP7#c|8$zgx= z5)sqW%_1UHX)*YvLN>6(X=rZMFPmRLijQS`ecbIV&ndQ>p2Ml~PMI~HwaH@%eA!Ol@|4T@GEXMJnsm6`&V6A zr9Zor`^3-3hf+CSGeTtHQ$K(^hrBr@F~E@hnx`w$$hm)|O-dynwHTdtdYFXIAMu+` zv}y>4Y$c4`U8cQa__3E;BU!L@4^3<14eNJgg9HVXzJ_(aIL%p(E5HKhj$_|vIe($W zosgp-_P-Y`S_=T;6WMzCl#~7Z{1g-v7ILo0M+mm0+;7Cen1TI_J|m&KJ*TI_ApBn3 zO8M15AemTozRbP(qtbXon3un_6XwIQSJH09)Esx{#vS7dy0&MD)ydbbn&19$wwOpJ zz{!}Bq7HVw{Kc54Re;k_g8mK9&9AHv#|n818;JwVsU!v=BB=l8n5TVm_7HZbO~s`W ziZU{B!fC{cz~L>ijWHCc0W3^tvkIU2?{5-Df{gs7NFCMNJ^6&@)*jjI9THJ7uRw|g zElnJJ29m)@d8i=5Q}(-g#fG`{K+b8Eedky7#cDS)$vY6AJ;|$X8;$~#`pK=L@=uqT zBcWH4_yj!CGiRmW)9=i&%oWrchu#}XfXKynC|Yo z1-{~7er`ge!xtpI#E;Rk4FbAu7(VD^oqnQ2_x}CQvwc@9GbLRT1I88x%T^O+4f@3s z>gkpopqifn8@FEjtN* z0VpsH>>pU|v&$PBHpU9^Zup)%!PMD#IotCmMT$)TS1{s(Lu%?7Uo9ERlOMhRY5nVC zZCR59n+|G;FGhw*K5HF)#u=UZhTf^l;-M(Q!g3s2f~ZYctM$CO)Y=vaD8J7o^#j-| zUnUWF_{yh8fpNu)FSa}nmSw7Ye4(k=K@oRQI}?z(j|E%6*6LeG39mYswYZe_2(Qt2 z-6wrOjc1WnN=sWCAb@Fsl3Vc(g@r{BLH?V827E%CoOH)ogfHKi+*~=!`@`BJ|NVPW zg7$m$gjQV>sF(8R!ivH1Wl57fx3jzod4Gh|fj*wRG7Gp04RoU(ZC4#lhi9ZyFQFAS`{%_>;}Mk02w3qd ziq~Gdd8?>!(9Og|iGn*MprCfNAaP;az|O8C&xG{{Asj!CEM47+EC)f`1#O+`)O9G* z$pn#=W!D-n#tFpfq3r_5LAvTMm+cnHYrG|`NzctfR7JdHnVpdWKWMEJgD9%fjMO{ezii)oml>rTj{UQ-`fv69rT{w-O|hmt_Hl z1gs~(<7p({D8e--EPb*3_DR!AObmDaJr=Ur`-T|+#GL{X#8{D_0vru2#IgpD8E`DA zl$W0-KCl1iSX3{d0%SC2B?7mX8^9DK46N;)EO3K@Y zdnfhTTw}^l6t&sx&T_)&=t6VXd-B^hUT(>5eyYc@T{r)FXk@1ZJuT(F(03;s5_FZf z9wdJAs>|~|>?~oFYb?-5+_up-e{m#^hH<4&TLT&RDNrb%gmX#U_y+3ID`{td_3`1? z4|12)r)A7GJ8wWHfgKnG$Y)9Cv2TaAh}AowntTNsQ0>C(qSnJ>^%@|l0z3yXF>$c= z*^^y*Qc5mn3cUV;4he_m5pSM;hjXnzjTC%T4!> zq5@FU zkOqWS+4zNbx|(BfwC&!TX%3T1L;g$fplK;i#qeHdEhrKI^sRF})jl&RG;9K4Yo-14 z^{&zv7JkYqhO-F?2%vy$O9(Y{uhUa7ir#X6F&3@_NHoRG00gr3=ULA>%NvPpAYFl7 z()CvCWY|(a(ZTGh%|r2}0lgwOZHZICY%UX);fE23>>WZO8O*shH(bEp?-Rn$45kiw zh0{(ZKF1;!8EIv-%KNu%s~;n3evO>t4NJ5tMG)LQJV0JQEt_;7b&=iQNY@S-S`bsZ zxgV7JRvsH0OWFcyWk=|2+U8$sFA!;wJk-bmk-2*_%fa0JfpbcVPY!5G6Pr2&jJ)d1 zL8K)%af_Xr(iEx>Hd1uIGUHp{S$jaTp}yt zkz=bH7WNL|&cG255|uqsmH~wxPJt%ppWahF8=2S|Izg`{KOD8CQ$N+4CzFVbtNrxR zV)ZW(#7{4q+4>Ei{XHRWFU@;O=W9LPQzL&*ZG|+q%#rzP2~JP0U?T?cJZIYJLH*jM zr81-2M|=KLmxdDwxAo~`@o_2W#kqq_;fe!OAfIfkmkqB|#D!b+^=R!4u$hz1&zv{l ziUyH*fN*t~`&3nlyQ}?QIX2>9{dgVE%uwAEwrPCI#U-760XG%3uw6EfrzqFMmAwjF~3&ExANaI&_JG{L$r! zLawb}T>k$hT2!JhjO2NvrrrTuc5i%V-zdnbeQ7E3q9= zx)(9xY%fT2bl37e|J%R%OXCSg^z%9Z&)jI8GRT^ZlZpf>tXFZpISZk#ja;E35XI``vmU){C<=atV*}D zq10Zwayrz(s6r2L`2t(_P>(zTnYxDt1Nvq&tGh6a@P*$FT#w)2&^xCRYo^u~Kfv># z86S8L#w0pi`>(*E1}sAGmG7hf1RNrldRM17jl5)Sz;|gBKJ1SjYs|`1OE_E<-1`xJ zdp35!t5lfPlXY}ay!L{nD=oqGwf{AO`DaD{!kWG)|Lc9MgK3%ys8|O(6iwcs`JecM zL-Dv~?DaU$H;H{=<9&tPTf8KK%3T!^C-1OHf`C!}`I@)aD>lAwh=s02RIcmYO=gpF`#u}3cJ(e&$_UQrJQOKU^cv5>dxIb2%AFH9Qlw9}tnKkUP}X$ld$H*pzR z9%nvzQh^j)zTAqUNje|`nEu||l}^33OE z=T|Uo3LfGLO?`8nG+f)`G4D`a3g>T4H_Kn#+Wb}pH!$7oSkXcaPzT#0Z*_eFNIKJMx)B$j3Rma`R76K^(d{W|~q8=M7lhz(ThpTxFOy1qxVAhNl zP}NCTsyx3bxuASRJvoGmik5?-3y`ib-p;-w7w?#t2#4>)=*iq9D^-frha@EAkLWLc zoK1@IY z!SMEsmsbk9FAf020AxM}m?Rp{II^&2ZyV-{ zmliA&3|Eak@I$?RGf`kvy{bQ^AV3TK9v=Qi#4FM|^Q>Z73&@n$ukeHAG6r(3T|Mwf zriG#yvv66H-ehC6rK7R2TU!Il9$;=URpVf@6F8aZjn&JG&sjIt)XC8m2%*JE1qC?z z-DJ9~Fh3u+v*XXay1G#z@nF-j5u93%@*~ zkp!F9$`(VF6?`r$h~~;3Qb!G_bzWcV57CKkc{8yZ6JY#moK!z%QXlb@lT)#I5_N)8 zV91$QO~PZg>dUWW2M37$dw3?&ISssFmRMjenA67lFD8pmpRZn#8c~gR*n&?kfA7-B zY_guYbG04RaBz0y5fE6`pZsn_zDlfp1#Xosjr`nCML|l9>}$1wWX5EwOpeDCgeVF` zJ+H;9XVOp7#0~qC zEn{bm3ITN7)VN6Z^EZSoT(5`9t0=e8xaP@Ot&QQadt$;|c6o^~lwJ9|jHXtN+9dCL z=T(eI`kh?+2^j2b=y|}k{OopBN`1fsrd@IO_9(yUBu2hahoBT&K0LeqFn7b+14&F? z(JU6(QsHEeOXC~H?&xLd6oyN=U%iKac%En-pXZHgNqmS)GwVlnL#n2Z{VK=y>kyF5 z&L_ON#NL*+0hu0fpsqq2r&py`SPBF$0S%V@LrgkrFn4;07MmseZu8-lGB?gGH^r>& zZ+Bx2UBsifW>vZb^rOQ!{+RuB$KNVf@zJSZ4E0ooTay)ym&kA##+FcXDNB`e1r7&oFJ(5eQs~CMB zX($xeviE*>|9dCWZzd%KY$SAbbvHHCR8<##KQ>u(N17rK8ICeKI>!SAWVN!geWUh< zD!qJQ@HKZA4UfHcUv`uowns4S27s|0<&+OOX2eb4WH4}J!7d2O!E7TKWN zT3f0A{#{wxnILmqR7y(fekPEWqa6HPN}V?8yi)C9o`3m!m^?q~P9dkaiu=<|=4i@! z*r?02&-Y#}wIP4C_P#*a7ta6puct4AFZ4G10jd)Ia_+UuRF4J>Kqq;G(>F6?XJw@h zJVDim(8}tzN8V08NcAO=(l`3TfTkAEBWTa0dL(q2;Z;;r6c7WWEJTBClz!#d08}Ev zSZs^`NdpTcXr?aQau9-EKH=TD~K} zr3z@bho65{-)?i@5g84_a^m9RZOM@2A)n{6C#hVeD1Gs>+IeAPNl=ZVDT?*#G*>DW7)q{}hN^QF(g*>!pPg6bL?kmYY@ zEiElYs<#UPg?-dOC%fl%GWe6e`p)aEvSH!j5a4|#j=y@AS%kB^@{ zdv;@+wSw0Hwl?{jWT*}hAzYd#G`d=irCre{wn0iMIu{#2~=`vFNDuV{JIZAoM#&dXn&z%4A z6WJ3@{5?6mkXj#J-kmV0K0p1RG*FchQGtHTE4tnR#{BiE{jnAXmDQoYw-d`_k8F=%C8tXpZeGCi? ztknIXHGf1H8gD8n`7OLsg>rutBh{mY1> zYlZVWmG|zuWWm4t1k9%>bBA2km0?aRw%f{l>*ijpO)emp|S=`LG{PUR=j1!atzOAhUS)53lcL+yFt4@;Bn-k5~=gHZ=ulM4sL2 ze5cdmZa3_^@3}I{loW57U>jII3yu7Dz7f5ZG13@?QFNWS^HLEZ3qJSoeTqiZ0o9nK z3%nT(szU6UdLz3Q!WV+>nj8h4&iSu=W8-8XT0HSOqxr@jME~vYb}%wAA3Un$%kUR2 zUPb$=QeJEGKK?5=`DG3^mz0DMqEp{X{?$nV_fzU%l4#XMw<`VhB_6%W!pJ*rdyhNQ z?{8S->yz=}IGbm?kN-8?w;=N~IM{O4l%>>+_3v1uT(wbNse_N`uyRkm4!l-(SvJe_1}K?QTs*IU5lh}W}VCh z#`UY7wP(OThCS2$uY8k#HA^SUz?HH#KWvp1j>F-QZ^HZeBRE3-4=o@PY>K3`r{8v> zERB~{?mr$SW-QBNAKC!RJi~`peq$cN{a&p>M90(5C%Npu@=Zpqb^hnq8QHRO0!yA+ z;eU>)|Fh#@ZkjZ{)Z>$)GSPNBG9VG_5PdF9zV~m<9NP7zD>vYaD5mi zUzGyZ%bQb6n|_~;xcZQckxUT_O+eFp{oDpyv;9j zJDk?>BqO_IV#=k3te|q}uZK|#{{+{662yP}!9Qy;{t2%CoW=OZAN(^O9FPS4CqMY- zl5>Br3iCSwcsJB>_kPb)KyAlUr_=eviKv<+Sf_~hi|9=`D=?Tb}<|A!W^zA%!e6)Ve?riE!{`FQlfcx%c-!sx4zy4P?R8Z4mM&O!ogr%GBReuNn}$p?56c5Eikbqw4g5 zM}Q_3VobXc8w5lis#v`rE`J5nPi5RUA&}WZ;?6@y&#CPoGmkQlO>SqpD$9VP3`Ux= z9^(P9nG->U+d3XoA$m^SZ`ZM#Hp!^fK6maK1JNg6QRS6(Ozn89q)|C0=CeA$;|@=sS3LKQC20u)0)Ba)=>|qoVCT-AFK(Xy z+LI1H^QEkR-y;@$LMdLA>7~%CaP*t~+db*%iTH5ES{E9VvCn)h)@8hPk?beGcL$@D z@h38b?)g&Ibs`fFW!!G~7BR`Ul&G6VHZj2rev8+Dg)Lf3E3o`r++uNmgZZ@=;NL8S zOa*`_W?(~Ze4L+2?>^s*)80Fmly;QudmQi;@p^R;z%iP1h~>DFnIE%^+8ZUQh6{VQ zNf7$AT&;Njr1FxlO2MFDloA&cXJv*jjCuRj_(gNvgya;9Vu8xl;m5wtOf2`4&OY6a zg@C&g9{_i+Ef|iAs_fmxSxI()F@5FkJzIA#SHKo*Pu}Vpy?rThyc*s+k)oY%7-)CK?4-kg2na#cXu%q6p@C9iP}yG zQP@j> z_p7=~z9no~fup0#*pl&w^EAq3PSsSA!%(wNR!&pzt2}0MR_d#|cH612GJo7Ws$`r= zbhNU=d8#Z?M>>hiQ@x->$G*{`*=$K|`byQU6{(Mzw7w;Zx6#yPN-D#L5NL63(j zl{TlQ`(-w%^-#P9wR-2voZ6*P7>RI5GbQci@-Ak7z2bFTl?JDJ)P8xQt4!*>oT93I zpSS{~1J3_~nqWhCm!Iej@806bpKin5D6GorC-W9XUKQuBeB zT*D-1rd;Pm(QTkq`qaw;ONOkDF3JwSJiyqV6{=}UwItszSV~u9Kl3?r z-yM18a~Hf56m|OBc?WFuMOPP1)yVaXLPh&=l~9!+jgFx8aA?wxk#U1!$gNW6XM zXvU<7K?rJbbKT&2PAA{EZe1!E9+)3>pk@$Ws7BVvwN24w$ax;g_?1xYa6F)=7<=hGGY&zx0Y)eb;L98BDCu^S~m#?Z7cp1hfx6jVAw5 zf%K5Uf6`z$IHrDI9kqN<5_vsN#$_pOzD=4k{H~ENX)q{N&%OH8P|swf3UwFN=}oRe z$pL)zmFNdAl~RCA)MTexBYM(&S&~)Ty~?AkSh|(lypKE^)@i$su)3K&=8@>WFcZ@2 zrs%_yu%-j&_ZlxAyXYc;^qSIJG9?~FM@iPawe75#;LAqWVdMn`!ot3bH211?F)cn_ z0N3YRu4hy0+8OKQc$j>Kvr^;?%Wop~?-zQ$j1y!Q$F|X;&*GhUxOK1qUvy$c;i)*! zw{l)y8;|-GO}ls|XNtrPbS3vUE80(&4)q*bUL>5~hnNg3=7pZ)+vy^|b*`4HkO~^vXGLFtNf_>;=p?ZM zS#g}A5-OK$!DoZ>-FpwC!R~c}=q0jG*r^+O>EXyFa*Ev4fDDf}Efd^{Oura?+`JjR zq#0vwNa}$-&ko#ZU3OaSL}L@%l~J$32NVcLjKTaFMr$C%)!LAzd)9*mQpqw{i zGq? Zt$nB}X}y(q@~e7+Qzh|@ zGepz0|Bx*h{g|ViQ0}Zd~$YL;0;;(%qPf#nM=8Bb%Px&S!<;Bz2E*_bDU9M>E`gOJr<9|$*dG_ zo)+oA z!Oj-eho({R@=kBZ4TPxISKx6_0Fd0fkt3fMOB06!1FdA6<)c+8FRX)4Zf9~vwUmUY zo89=vkKzi<=L}w={bV+$SH^s-Q_;&N^YHZT^C*HEd9U(7C?>~3^Pz5M3Yyo&%6SMeTd^j@h6WO-sg#Z&Qq!Usk z-Dxbyo--S~0(VjK_io|{yUUH1mQZWV0-?D;ufi_h8xyJJKsYVIS89g`CIg{Qy?jnd zxY0Y_>UnPn5H>S3364(6FVCnBXqki}2KogQ;0MsUdN@TXlo!ING*fXO_p@3bE3Kun z^9T;7!JvEs<;Cb43|dX>p==Dj4=zob92Yu&ZhY@4saWpB@l?5?0#u1?v>2afk>8kH zD@UJ}Ykk%Ds91Y_LySYPAqrt3VPYViH~OUU2wBkN`tMC-wR7B97!I_m+?CX)?Owk^ ze4DD6NH=pSaIYNy_3``N@~iDyUJ5s(?&@1-lE)mjnBo5^hJ(9Qt^zKq7jNoCaL)N&kgF>A)jTl@hmfo^7%=dRhC zfBCFo+o3{gry5kH+A%b0!6F_^G3f)bAvP+%o26*kqo<|8!9!syH3bmGb3*pJ=8ib+ z-IkG=59%ES)c6EBVv=m}!KZJOi0q1f6$Zu9{RFV9(>{s1uQ6eK>DIUHYz_HXN1{4S zyLm~tA~D`Xu$P-_&CF@paW(MX=MMVieOOmrWm0IX|5_V@GHhn${VeL0m9Z9BQ`;?W zkh<*8lU>Ia=PyH1cbBKsR1Nm57}?S}DhBvOr0ha9L8k1ivm#9fA%4{gcNjuOx4Bw#=H=OsF^9^!!@tqVQp8o)GS=<$z-~ zm3Vm{cIxSB4L97LSG2e8hkP#60T3HC#~bP+?&evQD}*e1V4HUqWNnF=vrD5Sk_iIX zjgG*+UR!A6&KPrx@ms!wTJy^1_gRPmhLn#@F%Pw%vO6j#xRhi7t=&jnpCRpm4$yOt zN0Sr6kxjj=mi@cM|7eN_{+A=O@7B!MhMnqLQg)=^Yc@SL z%v@;Ny8LmK10JN#qSe$}k!+|NTuD6sgvR}edGIionwh<)g!gsX2W4RZ{t&vTcUBd9 zPG@Zv;blAJ<#xa2a%LIS)^1&|TEe@Rug}n3Mc-2{6`l-#JPLj`()~$=lifdj^To`& zAHpAU?R=DE>uvQ>*=UDP}d(Rifd9jGn@pE5pXIM^0N3`2X5Qr6ej)yPLy z-#x?@wzHKj=-HuM7Va(=r%t|*Y{eJEnRq3ZgxLiZ$aU7e9dEuI;{4Kfx?*#qbhwx; z??7zda}S53l;KZ8Y<0sAIqF3T#y?_7yJN=7%1WUVKBZJbLaaei%(xHwxnRB4-%ftyU6kCYppVZG9{e48s`@+YrYvRxT6 zH;kAk3iZv0aX*Vo5)(6Y_U>IK(eFEM(zxZ4sPhY<6WILa@@{U{s4kV+T;usMl&t)w zoxk47yxfp;Vb+l|m2onMym1sqex7Wv1NwcO?$k-cp@zZ(^|T5i$A;-RpVuN{{P5yH z=_x5=-DuCF2dE!bJf`+oEci!Y*VzhdqBS&z1%n@Ix!1;#Ll2+|6?JH%qea7`T-uP< zu|B#qp_^u9HG*Dxx>|PLfc~jp&wX8qpSH4Pz%SQ5Gj2VH8}y-kjF!!*3mV)BU#<6# zIy?j`Mj1mT=retU2Th;y_c=`!$6|-Qhhr#@_Td4wcG=y9POb><3dQh$>Z2V?!tYSK}`pO4>e@dzz!db&;W2Ks~tXqv=3HkQ2?QwMs!|Bjb=l)Rf62 z`^mbh-4i&nyGlLB?XpA2HCB6yzzFOk%@)<>iHf2N}=xkfvw9r~Q&{aE`-R%+J<&~c9?cD3G zYt72;R3^QGNVA0XV|Mc>gX)?(BIA49wW%an5@?w)XC@$XIZPGgi@lPBf_ zUGZZuW5$s_^^Z+Wi$TkegZS{(7Yr-gXB1+~?=fz5bHe zk;WM4$VNbaXg}?JRTZhc5i{Ish=LUK_we`+g%cMeu&QedG1VHonySOxmC3;m?dOIe znpxN^d*f&QY9_RRm4u6(wE=Wm+Wcn>ZTcq1W|3BR);L&^e>x0wglgTER;WTkr?5YA zxQTBoe&RLOvFC~2{E@{s$KL2?uUDJoG})=0El2p_5PHLX$7wxi>r>%lr`@%K)6vkAGOy9(0@k{ zZ!lh+YDAUqxM~UuLRX-)GArI5oc|@Q>3pn z-GHBxv|Jt}s8YH+XpQ&-A&@KQFVvS-P{2bO6^P|eEQeF&tO$;zPNG}e+g3^HFYaM@ zy;x0jX+izyc8@;$X2Mw5Q%%*CttOX8jpz1YRa5t5|+~A3&TO$R<@LP6mII*Qx-$M9VVvp?CH; zd&m86dvY^)^9+995R(ye>HhdMIVB8eh>2y%SjDZDKZGZ1P1nPO5O5cGAJ@}a5Ln^1 zXBB)?e1+ar5xfG~xHqx~6eR2+6_hCp1cY#tL7`ymuFTvt?@B&qXkU!0a*@FNV!GxIGOGoiXbNCVfD zc+Z4&X0QxL7mIrFlPo&fNK#J7mO@Fx?*ao@&}d`HFD7>>0y-D8yEIVd`fK+Q_mXQF+-Y&#K7j;f?&Cf!c-p`UWGnC+6aZ1`JtjP(;5nva=X*LFe zfiH+-CIv*oyP>t1>aN}nMHkyO+YNJ)bm=K>^*xVxL`otnv~ioq{h$NzFaa$zI5P4! zm!c=!rME|hc)c&bT>NA&NKm`$ph&i%fJnAoNF5tE*dj_=xlhGa+kJjcc%-)VvPLgS z`^=mUGHGLpoAY|q4sm!gM*dboxT1NgX5TQGmlS0UzA21I7)m+l|EglBM~^CkCV12a zt$i9<#!j^Y&X}t|mNeEF{CPxr3^NfXgreS`LX4X63p}sOOP4IjkKmovSVw%f0?C(N zDR+@bWdZwZc3m|snx84EaN+Y&<{XgW#LMTOS^>>qPQvSR(xSKc2+92K8O|@C+#Cji zWZOjKyO=^Cwe+N5Mkpq6Iy4`fc_$Y&d2@<301A$iwtCvm1*DL#gi6_J`6R6qU;1nH z3ak#8yygx=X;&8Ay$d9J>^hHhw5j2R%RG;|A?>yJHN%_oS1{`|7qVglx6E5zj%M=^ zlLL+tEB2%#eQmw@kmX#f<}&4%^LA>r3iiM1>yl3#Ry+-$;>>Wx)dv9yU_1a{#DVX( zPk`SA5_hI5AN|j@12JvL;i2PRm>%9z9LD?IIIpkJg!!^nk9k{tq)Oi|j`}k|>GbjC zbUBaKm^N{ApU`Pjo$nsAIWHwSI7ynz*hsQy)#K*81n9wcx!^V$ShKo({kiha>0as;z)1tmK0; zw-#s8IghGpPEXhMo}xumFJ}grZ{6fP#hb0x883g)0_t5|KNC_4$(7|*eNaIJl|PCL zwu>+nq*NIHTN_)-x0r!&kqR2{}+f6zH?E83o%mW5!2z?fWF&q%r@MNRs7} z61A-TDg<}Bx#%)tgqLjXf)_~_3|v^lEwx+q z74ecu7S z#C{&gNF-?`hAS4QzuS&ne*R~GY+J%i@7XSeq=yVxv6&edn#=$33r?9d2L`d4hNjip zNXg}gBD1p!Jm89jYMIR>C}FjeFvcg-Hr?|gafs0-87vs6KoShy`S1`cp|?QNAbR%z zSP=2ZH1uJPVCa={2pS_GcQ}PMaXPpw$$wUSz|AB&L5gpjFKL-=Mxcb1il!21%RtDO z@v@n-It`u-HY&V0Q<~u-bN}4w;ZIdp=BstXYOsYHLt`-yuN@&3URRXAP|#iiD@(X& z;9$%r0tQXifN=#7LCV02>TJzJPFFN`v@;U6PHceju!8Fdvk=bGxCwz(o%M0RkXnM< zb3&F2`*<;WeVofFOQ#VxmTMDc<@v+PiP9;l(yjP2AAAD0D~=vj`XtW6#M!0AE&D``yfnQIzNf^wKhrvLQjKTv>$)&84jSGs}79w;qVSZ)DpbA@}#8yW6&%*YoNz;eMh~@ z{Z6SRe=c{suu_N)Xx>drezS5$<`yMvWY?6MU`V!Z8cKYnp9?GSKW_O_pi2p9|yCD6Jf zv{y&{i0k~G}9V&tJ*#FmCS~8YZuDK)~>>{dp~beBR8a= zKztyzpEG90HaI^@B_y~sMbym>CR^PL9pLM_3KH^P0qW&$D)sIsT{YRj4_tfKJLI6Q z=~a}MQmr|UHBE7HohDuZ$LT3egq264ggX;Ls9$q?PGCeTk0KDyj2vGl?)ZTwL+lnb zek4N2g&H6H@pOFD^z0A8{0r!%YTGlJ!KJhCEmcJ028FKF@5!+d-pC9TosNN882?h{ z#VzE9C=2_Nvy{Kmuzi*vs8@dgx&n%kCMaja-qrL};g>(xnoaLUk7-n}0qN)@&Gw%& zf-lz#u&JP>`99q1dTC&`P6B8jkO;9z!(GH)MvJ5GeeqCMJGCqWFJR?1HyVc z1>1~y&-Xk0qB8bw@SPu4rSNzT`=n?0ADQMTrRCV6?M;oiS=&DMyl}g-qwE1L_=`vM zZ|QTVa7kAMp-uNNA;=2D@D$Cjce{K z58Q8CegR0BPB6wvp?vBVb&7@W0eY^jgQg+&B6p`VEIEtp5XBziBjNvn+(%E}^g&?%mfz|p?uP1q-#*?E(_L^7rmr;XXRpia^SA;7jBCE@> z)JPzaH*a6M!kT5eu^!6e*w8Y9Kts<|m76$``ml;#Loa4QLH!G52Hl4Yk?sfy z6Mm1qYi*-!$9g_K|*oQNcDgJ;Mvsh_gci2XGQkZ!>+s+qhSAVy=v zmOJ+#skGb449I4ha?Dpw?D)jL53n|bs}*{aWdF#b!X%d+^!;M`m`mAlSfpaln7nJ2 zdxN#&1FJlG|HP}{UyHO2XBI5T;uKTQvu^TUu(8c|Kj2}*Zu79IjnV8eLHBVg|HOF8 z?UPAhzQ@8ir*mc47gt!3pAaPKUa>UGPw)n@jO zpV)kFZrguivekbgLNCVnxb4}YKA9QJ#WxeuB%Sk^!g6R*Q0A}#eK3JYZPkO$HOLjz zM~1PMcO&PV6M3|4UV`khAqO|YvO`B(V`lN5LI~?!tb|SfEW%qKn8Fo|Ij34Q@e#f8 zvos=#OP>B(ZfF>=E;e3Z#D?;I$;z-0w<#rg3R=O*!${2&kx74tz+&zChXMy#b|tnO zRh;q?b3iYrSk3}QvBY*jX447o0(y~V*Wc;|3X?N$e3sod4b6URc%DVfKG3_uNEX(@ z*GF=z#aV-=z{+i>3IP%MFw(iE@Sd|8?b_4I+jA%$(-aZQBeQTlvU>?t4@pbJn6; z7qn!%ZVs}vb>dlmZGQQ!ejG6>xVf&ERkrzLH6iElFWo$<&5->Vga`E9i-$jZ4!o+P za@rw7wL6_&0WCr5?j)d~rC1gafuWiE%+y&t1Pk!2Kf^rYK}p>Y1=^H=;D0Sf+wD^2 zGyEM&Sg!2it%Pt~Yh3djVD17!jNYG1>gA&pI5VZ2-nq10c%;O-b?Stlrc9K^bLu7E z!MmN3bi3vEdeL`IL+qFD0wA`^tg+mHp7d0SFOM>EcA6tOnXt`(zuVxf0 zYF^oNiPnVk*z{H)+_cHV6sl5M&phgKU(6>EZ$jFy8&h8LJf_j0PM>S7hCWot@+W~g zL7Rg=q%M+ml^aJju?{L%+F2FN&j-N;&{ycX?o*yC@1GTxu^Hcbb5RQ6qaslTUo-a` zMmT-;?;`+_m|j-_bS!K9wnS@`<*U-viv}oL`%DKrp8l|ei>Cdn9#fu!dYMG|*h!Zc zx`4C#{NCbhLI{K9}b!2n_YuqN;8s%md4m8QQ z2~k}DPg)xNb6HfPOVzX|Ar)^ITo4x3^9ji8|I{~RQE}1V0!uTs3mlDrT5<0->E-WmgrytGL1!ng+{=BP7S(ifHNh1-U)WWjuPddD(9bHHZ35LL zSd}Jie8LWD43P~s@IEL9cruXey!2E{It-OMC@x+fx>O^sH4|1nd?503vss8q3#9J^ zt5r`MP$=Q?jO@VJhRNx6s0^?G?KpDf;*_>Y{;H57CXVgAk40f1UKX4uLnkhRn4X8J zbS=Fs{@zLx@~+#c_x<#UcsZJGmu<}+s&H#FZoDd({mia8mFE(IFSc>@4jz5O4D{Ay zlz*5YTXEin%0vBTx;$F~lWxrx>L}os8_42mCd-T>JMI0o@nZtuemGZL$m}GKc z2#LZzZc$BtnH6d%asG~JzI3HW1XHvD)R0sHlOgbVyH5pCN8ra^E%gmzM0`&r{IG3p z7-;qs2ApRbcob#*g-QoLBi5-dCQE6{rJ-$QZ>eB6)s5jtR`NeOGl`#E+_jyWGK&Mw z2Eub}`e;r9(;N|CdL``T2{@=JqcHhyzCNI^jguBZUIEUP;x!+RDyXH11Q9ltLV-5d zDX|MT8FG38c)ns$;{$#I@W=$23z(zGp}jI2jQ)T_vx3hKDJf)AC4*dR2ZuhAT|&)9 zEpgj=ZXd${&u!faQwX%`y^<<_$Z&)ZVAx|m8Ibz8Yo#_6?p8n5Q!FkXc!Wdv*Q^Ku z^+sH9N|rzO6@u+R8iQEQc7)pMlULh9a`rXFQ}qs2KIyyB%)Lha{PwE_%C|pGTQE1X zzswi7aBjPfy_*(5L~wU^*7BfO$yg##V9UpS+?A)eXUE|dOZ|znyLRv1J+w65mb+Py z^A&0ye5Lu*B!VfP`6_6&c%5B97kx)8R%~0sB?6eJL~?K&IbJFQwg%|m*Fs2vx-R+V zrrS=fa|<61o}Ve5ZKhw&+|D1~>he;G*adL-e%=Xk$6-l9KLbw3(D=jdwb9$5g0At1duUu7SMd_S(+~x!r+&C^b>!TzLMm&hp{>8 zY<242?e7ur+1k<5w3NcPf&gZ9Q_K-Kr$xqdAz7NB!Ll7Vfbmt?>JAhx=)MB%>)5lk zufvy|vEAe<%eH!bbZP4tpASz?ELJd!0EcF!GO6!!+}Z@OZ8u!7rV`Z$J6%LRp>$N_ z6aOV0b^dLc#CGc}HG8$pt<5Q4x#j=ptI@44yc<5a>tCbn|L{5aTj#QMy484Xzs zoVJFW-2fIzu5m{q*8zqnlOKAX`Py2^;g!J7o#v#pd0{4-+d%$RYPI(D*QW7|lrz;yc}Mr>HsR6K)Wq6#zZK4c0_+pP zEw5Sg-W{)VBO+B&4e9+i9X&vPqMO1y5Xfu_9BP(zR5A} z@rw^`qzLOc=iY)~df;NHoVRl3p_$LbIXqA6WLh5oF>HDDe_cS+pY%*Y#tk&uefGTT zZt^du6zt?1ef83W-1A!R>;b7{)KU@%J(*o9X5u}azc#Lg;-yll&JB-#s&=w%EMn;L zH)3V)u2)&H-wT!J{d@MzeKuO0P?+`9GIHy-m``9s2=^ma`_`)1kOv{_AGGQu+cA^8 zpSw%!NY0-ZgF2=%+wu4*sjdp$7slt+RIP;r{_=5{9qSfb0O7Cy1khH|_g1d+c%6Ul z{E=d7V4J2ZKIQH>L*q!4si1V9%k8rHI==adjGVg4N~IB%lgFD!oZn|O@R>vYo>QQr zK^bhQwd#41iUkn@iNpuStqsA%%c;*X)aMR58`?1&2}l!9)6Win+sR)~g*x!$MCqlz z#c_AX4|jEqUEO5I$TN07}ea|BHm;|p- zF!3DW(p<9A?5_Npf*Do&B#j)F9sS0T^6)Uz|`}S%zz~y&Nx8t{KasNq4>zOgmqUamY>Ht=(_v#D} z509Q%MxhZSSqIpC*6S66{)&#REC!wpiR#I}7zHGqdZTg+UIRGBNW()b)`BY>VWXL+ z`JR7m{N}#Ri5!|u*~U!i{6ZtxTZFpl;NNYl2k6NF>H5~M>B&3SfFG&<$l}6-USe?> zwk(~>$ic}*M@J78ljCBh58~9mW;m44EIyxhf*x!63~|i&%_4P$5a`*6ktPgay*ImK zw)d8md@G9&0gKjc&A%A->!SJKW#^GAxtQ8;Av(l+b!U>A>!>#k+xNUcb6CP`zmx;C zIwbe`rz5P_9*ga@{Qla@=e@_0?!EnBGGme;7yn``=wsqpp&C{8p@xRH`cGJI5%nc_ z6A#uF^F6qC^1hSAkJo0*_gDos@z}9hzd_UQ#q8!K*|$k$n7U$SCJF}%C(L-TV~5=kTT}Mw%2Zq^3@kjsBr>iRB;!LpvY8>uZk&#^zo2UGo%q)~LTHaA|}; z>axKyZDW?ylW#j+%WZl;_xiDSy_{cLxe|ll0`r!cT>&=M6008Wv9Aj`GGfgmdMTa> zSeM2*W{Dl&7=L*0K?t1PWpBo@aNG|MZ{2xHWWM?A?5fIF5m$=$VYFis9(dl8xWIf6 z0>o~%*K6P9aDx}nQt@zkC;7#E&6H>B%6c7-h1VFWS zx8KRH5Oa&lEyn@Ei+(S5Px8CgD94*YHi!6j1U(tSeS;Fuw0zMFBYYeNcLag)BS%;a zzTcK-e)>X*0010(SZtPhEg3vZlqk2bV}i+^mR9}-aCuw6O}DhXIkW{_)zKEFZvbcT zoziBRO3R7N0AP7I0<m=@a zjNukF>fd;J)wCaL?bS$RZgIKg@c0|RS?>aX>q$tscj6!b-1nE__kIJoysLny2FGjY zHHAco=;BbDYff?qip#MkIr2+qJHP~}3XGSj7+MQembgyZb!8hDzz1;e>U{dkJPFS+ zGEU#i-U<-NSaM}oH}j7$tu%e&`4?Y0^mTfe=K%kQL`YI&LHBV9klSBrKSIrzkK`Ul z&N%N&S)&ZDzS}2K;al9rWY+n=$fq4u+aK_ z8Xhy_P5s^q0z7Rec5I+>`^CRB&r$V=`&V>D7>&Hw*ggkkyO+w^SfGci3Fl>X}3`HyLS9 zKK{j*jOMohq9Axg=AB;8?za}Rn2XMJoZpEJMN8W1xEM}c?Go)#hnBfb8<22_QUOJu z=jXMKJV~s-(s5gjQo?-VudVhslqSxK*fSAJTr&h@U4(;J4{_WOM0KiJWw8yBY4bYQ zIv)+N{KbX-ZaD5q4IXhL;Z8*7rx4)uV)F}Qxi4;&>|(qpR2dA$!PG+etuLYP_ z7#Q15#G@I&Wpm#P$a}O{etdr3xGCO*N&PgSg`QPkPWpzL7gh#@?pUV1)9pj!B=hId zZC3&HTOVHfEq~+yVDMp&v=h;7CzLjQNr0Q+fu(z{Nj(KZ~|JS;a-CFH?#=nabV#GI}3_V2QJy4zusj19p8@V;rGVhzyY=g zuqS!d!i2hUz)mO{FSLKlFiZk!v9Q1FtmKocrjg;WOLBl(WW4|Si}oGk@jD`Jsi&(O z)f6q60i|45le?`%kK`8=ENDy9azDvXuKEYl*rNyd9QN`a66KD7N%ZHqz2i5FrnCp} zXJ_N9X6CXFL1yRnDy{xr%g1MJO=WpbGkyNMR;|FCa>b9TzAL<7gD*?CX|m%49v`Pr zTE?1e!OVFyUYPOl^x4!>huxo@`6fOn$N{eG?_V+k2_&oqV1$TMm zy#?Il!du?aljcH|5^M||Lce)ocP__gWHdI*PG+hv`QJGDquQsMKn_pEI;(%-kJL*5 zG1`1@MA&aRn)U%f0bd-FXL`US0{1*h&EFCpjpylqw4kscz<{ToD;UwdnhbBe*VqM< zV*KnpeESQK%r(236*uf+E;^qSW_HP}1h&^re|#Y>Ktjoe{(&5MPXTK5Sm(iPGqy-< z@RIUnny-a{i3KI8W8MNTH$G8C{|^p^nHMlXD~ImVdE+?MWumai0l<{!<;0iqXHEkS zhx!4L*oLFP#eO}`KL$ss`da|VGu$z?0k|}c0Z&PbI3AhfV`|&W#d%y)t(n#I! z)^^lasSS9xbZnlz!`0&m(*BNiz6Mp_biN0Bem6rRb0z1J**cYOVYO2l^FaB;y*`;T$xb4y@C*B2RXBGQ2sM0t6@_Tyf~|NZqc)xGH<5@B0x-^ydA)Qx7+CySgJ=IjCtcsQ^(Bgy)ifacX~^J7OChD; zs`LY2#y?>cC}jV%3dfexsb?m!3I+3VkEXlTL(jxE90w@>pY8}yeo||CWGlFxnNM*2 zLZ0bk0MjYd1?n6=1zgA&&V>BN6k8%DVF=7VSA|4I0`iB~(=1N0V|sq!nDiH=s8kvK zmfeiTyOEKTU7)fcKbM(BZ&u|yn_*visx>Sh)lxvCdXe5_WVTGVi2*E&*CX8e9ormK z0=V+y4kli}npnAg(F;eebo6~Nso6HjFhqwhrKmy)Q=;s?Xjdp*Q)xC=cZZyVM0eU z09JY%q>XzD1S0OOur}S_zV=H5KH@%M*n+s043|9%XoY``1LDtZsd_>rtqzEOkdLFg zlmPRKeo7F3oS}V^uB9ti)LL2om z4tKwX=-YRh;@<7X(4!R=f`?)nReguh>3__Xz#@U^MxXeA_)UL&0l;7@bmpbz_2A6|4Ll}mRoWFI4~Cv8j- z1|nO2{3$_EwiVB>GZ5te@DMWtK$_2GZQe0?0046WbTs;RO7bu;0l=lIVT+MnAqt9fbT@Ikn;MxQ+e?VS%E7*YaruPnYVD; z^TU>A^YMiV{zh0O!!6Age2*9YUEq=?=-i?4m>UhOUvSzQ{%(trRShY8KnzGZW@EAw z(5&(rGhfn>EyawtfzOt)q^W+_#;nO-=v~SK@rprEog1@kiw5G#X4y&Y!cS=>q-h%8 z#z(s_`!e!9?*i}Qto21aNwU#9t5idpw;&;@B3Dz(?hQI;e+MW&ThMSG-q|z3mh(ns zu{6te^eT3+YR5(&eHBWYbE(jzB#VUONQbFa%Wl=6oVSgmt9rWag5q+Lu$_A-_KgsQ zdw40EHW*>1v5QECrIgG^Y!AJri!t6vvz?A+ThX7L(l$iU{Lw4zZHCix z$=Kx+RXMm}q+xE&#}$V>Z`{VzdvyJTgW36_4ngCJDz|`&83VHn2P0eC?2?aO-l}`X zKE7csS1^-9tv|LW%8#j92>HeYeg8$_0#}uJEN|G&dLH@i{>}0Dq8{?lfL8OmqOvL9 z(+0?cedl@BKiUUb6@a!2nqfE%&sM(lyl<5%jPC#V?)0+d1`69R z=v8v*va`JPMvR<&ZB&;Y=1KmeNA^V-jhAOiy5sGs{W}Zpso8g~bhu4+ITUau?d^Z< zxz_&1wMmfv*^z#GrBbNk?OxHV8p*RJ*3tt`!N%ogn~H8W!~m;$l7!tOX^7>3r+Jzt zQcEc+Yi%>uZ4$H`8rJ>d9$!H=L79G!w77IKmoGP^`q?(K5mr!xbkLMm!8aLy7ae|ysWTqvFR!fhWa{VI!C=Cq)zZZ-qA9{P zU-a!U67Au}6c%-4wyOc$XKPxPNSbQNv7;7Z-nKcDRR?Zsy@H;#_HF^T3}S&z!acVk zUhkx)+m0+4cRF`yx{;c6NsK4p^;%`149oAVy$O{!HafI0c>`r`tv6nW4hn8m8`9KD z*B>fay7pLJ3tTc5nTo8yb?7wdK3IugrY|^==CtJO9VPTP%NiB!q%)1JGQVu1 zPCp~h(ZNj_1i5FvSzuYyxB#S9e*dzmQ-g;Be*s0wReTcJT#>YiKbZOE_`p%bfjPvr z5_bHd3U(d6`Cd)TPI>n>v`6F``pp>(*ZiU#^w#fkMsH8}-k+NQvPOrLUI__g!7_C0 znO?Osz6gy{`e^6?+IW9UZlzVcV7ldf*^AOm=n5gFek#SPpnD9IqVu-Y(SLF^;s= z2-7@o`bI>j{m(vC8@$u=VuxO9!He?p4ngW@Ky+JElUH_W-%QYx)<<^au$f#n6dwp< zJ3R^ky-7nBDX1U9tX1P0rz1<@`F9m8A69tQbkb!a@5KIibzrr)bZRAR;=A=rBue=n zyXw$Da#L74!4|X*q9q}2oht7-x#n&RE$nlCDvGg}DsxX#SnIR0H;*pw8L+jbE!;3H z_xN11(Q|*k9b_QOG0wMKHJVdUu{kN3I`PPj#$7r~;I7jihCc8~Q=nBS*ckp`=!}+Q zC8o~Gn`sF$?=lZu!qcq0mx?Li?_vy&m**Uyt4nF9CzD@{Mb-Qdd1Z=-6;e+IFVvF% zomH&8PacBg$lYv{66{XZw6Ugyt4ruG{83kAGy^F~Ma9t?JRGE%+|@`A#MoNSU7sqm zIu31qzOifb#0y=$_5b|hb0Y93mQ=5ejS@9np}i2dx_)WsxY&v3V~L?IeTi8Tb+%pE z`O~CA(qQ$YBa6?DUE>e)*X>@`)yu9~@yK_bgf09(&fYu_%Juypk949{*72Ln_8LgRzA&%-Cm!F$}+ZTFyE3et$mS z@Avmdoimyl_w!u$eJ!uo>$)C|;AZA^2Uw)nt&=yQflu*LG0wAgSF*6in$5eeg$eEW zb+zAL$+HE5gy`T#WVgNShkaWW>?pjv>)1dpIon6f)1@~;+-4u z8%@2_F>RTber6*dmj=p4eBaB|58XJ_Y<2FmT#T}Jssis+*lJq&s$h89e(3O1{k6ZC zOL^ILmCHmp)+g=Y#^dY4%ysL+sxXvb;RqY%^ylGZ7r(^*QS0KWtwH-gM2c0I~=UN^~@yxv@UC6tw1YWPC7nFgr_~(X%iwRS^owYm9!l&jiU9q&@LJ z|ED#B2t0|)Pz`R^Vfnp({SnS37OmSk{(_K~sYw2lULADOfGD{@;d)k$ms{|x*T_EE zYC#bnI7@Uk`a`O@G5W!euQsj*ekW|<2-2+yD|Si`1^bGyIwKen_J6?1ODFv7g1R4vPb) z2oK9a^;BN_2P1j|K#%F;G0NTNpMFyE7+V|n7YnMH)1NIJfDS6G^ekQVIyqT4f?^WX zDod;cF}hdYTW>US5r?A(^J;sa2HnZFtaOO63}|Jqov)*~wD%9;mHf*yFak5EIc0_6 zHyYtoN-rVR8iU{8_he?RGjM6rJx=}B%%fD_hB541r8$~(Mu93}zA=+ic#*&6d8AlM zFG?#-epkCXgNY4j6J+>V8VNWPzk4kK!@~k`jY|dYiVphc5qpBY`;!{hYKp8}z84CZ zqRh4>nzIuKig3`<)azDL_wiHc%=~3+pP~NR2ly`hoO6B-Bu#5>Me+78sW=;lnOOQS zh;3)hqdcyAG5}p0uDd9V9R7D=U7if`yUsnwkZ$9wl5D{BaJSX3`G+B^?EIjmKPwha zJ$!Bnln%o;%J!uDJssrwi2*ps-c$Ui(rGWorw{~{&p$24w8#uoUj1b-WU~ygsyVY8 zy~rsUbIPjH%Xku3FDnm|BzLW{)rC`SxJZr{=VOvo&(c3vYMv6Ihd~99U$s{WBd$90 z3y_pv%suHCH+WyQ+ot9(`c6^~mqk&}~p1B?35Dtlz@ zNN9?*^xn(zG0Njb$A1OAj$C~OO4MzCOf0#w>QTQ&P4L$*R|9IT%wrmBichul*XoAw zXJ-D_l-IgHa#N;QK}&aRR6RAqRpFfS>+Mi4jOE>n0k5J7m$5Eo*Y^l;&oz9pt#{(JNmh-TCMDWC$r^LzWuPZ3eStd2PSlxaK*usaI_j<6n{#eEBcVRQ=Ahjei*1Ax32>a#O)H z-rv1s->@PgRbY4{YiRksX!0F9dOXjRzboyq495XCoe9yypkn?ox+OX0I)4&xuCSK@v zYqY3YuSj^b2wwk6yI^%XpJq2BHJthaGtM>PO^`=ODV(ugYQ`V$51P(5)Th@Xlx32x3+b;3$&xE= z&`}L_>9enUieH3=Qx~Nb_Fhgw51{4^?#shJTuY|jzrU^UX3fu{;p^`AHG9&@HdXx? z@>BD~?6kq*Wig-r8KK$pWz3~%S;5js_ZEgC0A+m7t}F|_+NmI#HL00ktC!V47p*0K z?7fcONx;t)Rqa%WZMJ_fBnI_& z>MqU8rj;wTLo|djypL}Edh@whtO|>g&1NB{>-XVfL_3YOx^m})&>y9xN;R-+bQJdj zWe3aee8l8C9{w9K_yz@8f>Ve)JW!5`(Ml6FdeML$)Cdkyfgh-h3EucpMNEzqO&y?f z%^qFxH(+0KVE0=Kp*5*9wma#)fZ3?3`eO{coag2M=+m=IfO5A^ROGa^5WJ?d7dYte zi}Zs2w0B)Zs!0#Me8HR?;)itgQj*VE#kIJ*0&F!dw8Pd_ z=P!TyS^vDvQjXZt+qSfE3!_B!Dx@0mOf}kXts-QSW&7H-T_?+u=W2$EO?GVzN3w$Z zVX4kZb%eR2bsh0>rAKjp$K~k$z>$&R*Y=m)Dr;w76A-TND>ptX`%hbIJd)g48-foA z(Vp#G9*A33x|J+ST-N-Ga9fk8U9Gv)8I&j;gM1HPpH%jzR_)}x#Z0?C%U?S~2C$N3 zS!08RJNJ6w@bnKb=W4V6OrJV#C3b;a;j#wd{5VE_m=W>kzGEJCoIwRj=Vh=#+x+&kYK-gUQ9(46wM)|K|xv78VnwN1?R%QW1x z9uv6sW%;dZGyxRwFF%C^SMcB)mL9t1AIuvjyHzQ;PnStDs}*8~3%_R(h1342I@TLm z{$*C?fi0<(cG|sP;;=0|pW1qcw<2G6i+=6$DJnJJAey`UH5jA8veTDKT-*VxKn_{H z?G_VSKLmz^pAiW9suEqq)b|;v*xu%Hm3NStcP3?#$dw@em!ajSx1dUn%!m{wY#@^_9QdcmI+yk;@woOzfC7V6Cth_urVV~w z3%}*}n0v#Fqtu0Ca)p`-UvA-h){pdG65#G{uIf%!L^2q`t}C;fm*~Tt*ef8&lo)<( z3$^NZh+g|_Ismn`vs9`ai*9hJvZ#7rqvvhfJM9uq#aFy@TOpgf;sT@OSDt2e1RU#|atMQvLNU#mvXGE;9y9=BvZQOYyFBbg~A)&Js^q?H%CT zZ~@aDWgY&c_!s7shf`Uo(QTPmI25Ckx6;wNhmA}!z3IF@#5Y68-Ds>N+H(WwFU6O% zM)ytLIqTac$n133P_p60on2oH84bh|eAcm%aNl!!ygSn+ z`s1C)6G5)m=L;;an0il$+DR#uwe5nS;6RwTRS7>S{@por3x6Kr?D$@86>T2iR&*vely!=} zyejK}>~*STlAW*2ISL`B&eYDWW)c(iAu+>aT;yZ4U1|K4#r>TJsWQ|Lag|@Elcx!g zgS=C;Q3|@md}CaJRQ|k6V_B_+-nCwDyEl~^U-tM<%f?}yVQ1Ide1_%6_7;!c z6qw~_uH^v=N&z5>)*o&A7-{q*rBb=Zj%bW}`fwh(zIzb1wlV}KvxkBRVSYsFE{eG7_@>4yfNiX@yxFD0Zt#+k2X+4c!X1h%pS$p7Y z&fC6-;rcmGR&YMNHKKXx%Ti}$)bd^1lcBEkD~a9@-pWbeFt6W8SE{%1_{e`EPAl!^ z`u|D@_U_OJBo!~T>PNaJsQ`#k&khJA9R0r zV&Od7$`@s^6s@4QoiVm6gg^nIn&D#3WT8XM(xK#;>h*Es>owG$OplJ}=V8v>3R{pH zQuqNi{o1a{%(y;u^^8@mqhD`R+`F83EvY8pEXGeQt#Di0VLUZUbHk#!`{qy^C9b|T zBgNGK!j2P*QLc%bW%{iS8cP&b`6%8)`rdi7)KK%6%zCeVQPA{ps{Cd`#T%2M*Lb{z z_jB4(gq?31fBC&$qz!a^RD&$Et@Sf4cGOT*>oL!iEGRTwYXTyN7OS17ODVOQJR|@m ze|`fWSfq$e_rrKL)$H%Xk(J#GV5drlJ2?=&eG%T60h8j@<;taKMxoErd!b!I^aQ1~ z)Et+FQ>D)9YofLAeqr)dcw}2g@J_0GMGnfh8NQ1VH|gyT7`~;e8FIh4OO^W|ay}E} zJjcpRJDY{#P=~_Y_X@b}?FMJf-U=UnPZQaM^^5qK0I`UYUV$THM4&jXzvK81U&6|M zI$nSns^ImxEkd2Ki+>da&{va@bmBl~BC5o-!n8MYoN(clV((LH$~AL-g-&IEVT>*q zz})y{y))fs=*ujj8+SOI`qZm|p3)w72ld%3h@xJ#Q&-1Kh*mLF>1Wu0)3tYhz2^-n zV(PtJ1SPu87F(D5wwSrGpch?UVwEiKQ1W+aaNOt(W>0#DiC146)c5fabI!yx`X@LA z9Ji&E>~U@L^GkO-&)Q2(Belo+-86%Fr#@ygVCZNRvO$R13o@*{gWxuEc>7 z-Au6>F-X_Im$uzE<<5B&1>U_l8K=xQ2g6|XNkOW@7}J0&ngen<6IqPTo!fb1=`{O~ z6a5`2ZsWiph}WGz>L#<3fI!^;XR_%?+TiUfP^Y^%`tXuPjD@GqWFI9CKZ;J+OOy3(m}vDQ=FG_KoVPdeEA=h z0qa{H@q)9S;@UrVML4iuGdFyuU`!+Uc#0B&edU6&?yW#hUu^hIya+yeg!l|Y{p7&I zxV{i$yXJR3r?`c@vvm-l?VU3kaSh{*@<&Uof<~`op+|g@edPl{y!N#msxgh!u5o^q z*niYKmv_8H-XxA{HFt?Ul4puIQ`sh!RK$31@R(qn<2tV9nQ)>yX!;T3&L>Hf%6MvQ!GJTpV|HnQ3`yj=dtSfOFR$-gxNB@8-rdtPu#O z8jg)O{`{UFoA@t4u%-LjI5}7Y%g!jkZ@YqOwlr$T-|3hz*b1_+M7p1+lKEX(o+Qtkv4zF^UWo~|qBg(|XJtV->z z6v2}ePKHy(Yv&{FT?XhaZ5eG_SPsx>J>|^b?E*>1PkT;W={BcTCmrj+0HmaWVP;{;x_PNqH0;5D=?^kKAzX??jbxWopfZGSFAlJI-;lMHt3bp^aC`4?`tR#d3EyJZmbA~6 zvqNC1dUtNkoB8=ynB`%A<2h00ubxPprO5xV^Tc5%mUv3^mWRaOzv*5SOSH6Ln4Y-_ zETZR5_b(c<+$Z4u+jiPD7eCQT+f$hO7@&%&n$ea22$$lGZva{LZCCyo)$|kWj4Bbn zzt{K8SStRkt^=i(NRuiJa0{GM^0xfktSaecEZh?B>vPLJ{6B9%E=xm~A7Q(M1iyQz z&=vX?=s*t3^Z$kv{zPT|whT+aWh*+q`7o=!`dNn@D-*FVboK`#B@lhZTsf{rl!#Q4R2hUx~ z;X*n6qU>Pf5Qn_MK24HN0l;z8F`vAb;Ep&&Nnn0Bj6(J`ftHY5n_^Bc_CYeMkgja%uBNW9~%w~oi6UQI345u{3ZWuf$l=6t;iP(u?%Gsvc`s+6`$j! z!}ZS(t?zspq&ZWWaT2piuGb-q+S^WHjyxrSM{6ALY}jw|KaqHAkQ{k5_^zUE9Uh>JO` zPM;==&CZgN+p2&oTJ?){q^gFjP>94l{ILI=l0Pxk$0BW~;OKH0R#|}%l0f9==YNFq z^edM0oKUC8V6zkB9mdU3m+!^S&dw?dRrrhq%Id_nNu%49mMs*>g=HSNf)d;TqG_!V z{moX71`C@TH*TDK{lt3)6|}zc9PeM}PUw5qa@|#Nu8!hy(7Da&PpAIgVwBj6$TE9u z6l%p!vdyNAsF;Y4#$Q8SCYzAKYKad}0)CQ8In=rj(rDY0&U4wyPLhs8g7RMPL0gI2 z>hfILD?u}+(q^eB9YLk$Mul22H^Q!w$Hit9A503b?`fknhJoPq`E$J0`z-qi6cIe~ zQ+#>^aQs4^|DDnQmEX^|$qwQs6R$qfw*U{K?8Ju9${-jK`E`mZ^6996C+I>bvC)jz zvi|ZI`#8!ozp4lPuy9SU3ENTxj6AUuY^XS$J>x-biYFW-u#ceak?2rqP$H-|Lp)v_{T^CF2vYk)z zifg5e`2&&98V~ky^iG_Ftc42AlO9Lw)xk1+P~?hUtB>&!1q{_O=Iunwr#T;Tm2n0B ze_3-rflDX!USFcoviB9OE|>Z0GnB*p zvm+hrq8>}u9AAFC*{jr>@OU$S(a>Ly`RsMrqpJLXT)xxu2)QqRt@QRskA{HEh6ZRa z0r%PhF_rBXDnlX;WBgn2mjY6=BFki|tUOvFU`=-Xk?yF9f+i1aS%Xz${AB)0iv5fe z^GjfBxK(?)wQ2FIVQSs`)zUpmIqyDd)KTQhuQmHwADX9+M-NoG4oq9Gf3=>jYGBUv zg%VAW*f-0yQ)Q70TC&?9_l?*5J3%jeBYcLC!0`THzI}W&L41AWniJRfTVMKrr}qCv z`{OFQu<(7GyRfIMeMh$-E58Vlaw5t7xP6Q`MTw>R z)m*FNSnwP7lVQIj9GGbeSauh3SmY*UG<<~f4tT;wZYC7WvzP`w^<}9FKBaei zWvTJvc`9@(BhTj|jM!Z~Khxo#fjT$kO$&7WF6$ta zFwI`J;DeY}7W#vhJmXpgU@c9GO7(*n-S7d|DmetSgcI1W^@sfgXnvW<0A-NnxiWLl zfq!Vr2g&%{FlGr%1{wU;{0_P!x)t=eICRA4w+78`eOa~QI#g4Ubt=pB_Z1lFr|0Cf zxV;|z16dh=)1ja93ESh0!$2n-5b!=cEk{3ybp=gWP_Li643=pQ1r1nMtR}2@)pTQE z7juZN((m6H0jgQ7vcPXw1&TULOUtF4AV$v8SE-=>{gM`wlguVz7Y;2k&;rgnHQ`i| zt`_2Epbak)N)U}v9x4Bxs=_f`^lii!7{;vEuVKKio0^WrgmM{ ztY&uF|_Wdsx^q+N6YyZpzel9v2KV%Q3wx#1FjKV_&hzA)FSVssffx2!01P$CmM8E?&8 z2UBP?HUhzztC9wN1-9#fK(bRd6MI>*)yVz$NozT>a{guJG^RB1i&97k=pxn!7pYGG5V7S;l8kPE*9LX0j9w~bzaF?@4 z;VDRyQ(fFd?C5N-GW%Na_8tp7^IWtN?7DlYRegZp zOWvwRg0WJ=>d>4=k!2COzFt}1P%Pn^(DHP@wBrm3d%j*flu>&U8$mCl0X;7K^P77; zGA+G&2W*Ol9&G1(iL3vti) zZZOdPs}J1oHDM-S{rrQbJx1voOcT|b;@xkqUDanRdeU=!PITLi<8s$;#~+PwL&`A8%fj<(=>wNFt3i_JqA0oR!-k^=>WWnCqb@heX`j}2iALX(L&(nF|=6NE| zf-C=MiR_Hv(VHf&*HQtRJid$V5MTSNvrPcA4f1A?$3mv!bi?wW&Hsux0R^SS@tojmhVGtd`QN`Rkh$ywF}32-3|)Dn%5D+PDOS90JhQaep{~2jM_2dJE)n z5p=)R0B-HeVgQk~*ZAE>pJoDg%(PKi8+13Wh!yFAxvKLrx~Bx##su=>J5Wz|3-F{S zsPo5qcpKF4a8X3NB;?ME1m(C+Z)<(SZ?J_|s&=~6qRcqW_-t{kC~o%7hd?uC{*~4Q zN3NMj{%qSpdN|d?h{sdQOkcj=yd4M$!46P6U9v=_*tA4l3a4t@>}@uY@z}N8F;GGg z9T(42MD0j|=a&GY?CfF;UaV@4zRjuga{e2L2u z3yaLNz_q`6uIW5kM``~^i|A3r+nHOUct^*bVc}FWO+QJ<2npsZX>VFfA{*&t!P0QO zb!erkpIU(VLrcY$m;tb&!|5v#4rt&( zu-h_ru>S?JH>u`?+TQ`QC!l|%+WIlQdL-WoqMd~%JQSto@XE4>gp3iIV3?g2Vu@mq zLlS*i*ax;25I6A^7}qeE?iCq&@uHHYjt7p}RqWfvG}6!FW?sYSIKiGkrwoJ|A8+m= zn9j`^Yiczc2hld(Dzxd-5Il7620{tW@hcco#D95rQLjv(CK}eBT={6_-rl7 zSk*~uSkGg7GF#7n$Q)5Oi(9NKOkVAl3*j-xIZ=``%lgW>XdUpajoZ1X{#q`2q+0w{ zLO3-NU(AE@zW>^1<^$|@qs1<<9{bd8#K8xQoOOhi(QfNnLm*uw6O8?^ACL1NoP3_s zWy;Hzd23!y7-!j**GxBaHoGUG{+ouGQ~l zsRRBx-NE@cHv27azqbou$iYGEulBrgztq|eIHhkAZKzv9@71uifz9=U<~lq+NeV_zqXj~&W&Xy6AnCppfN52?Ow(LogwR91h9|0d@8_^>ic61MUAHt1s)!cAL^0 zZ|@I=Q*|B%0yrrnYvRe|VV>khMdzMBQg@^QuUq2ab(X%)T-BAjtYuz%(*+#5Z)cl- z+r2w9X-8yg;8K5Q>%a>kL%EoGP{>mVI6^nUIEZ2~s?GqG3)Dw&X>@_=Ui^iU>&ypZ z?8K{YHU!#N#Lga4fF9OLdyWOl zK^v(*5-kjNL;+;S4In-a*+7!LRyg@}8F*&$!`Poqx79+w=feFU7hY{+VS@Q4vFeQc zNC(v*dC<>};f>xLec$iE#aMFmnH5RXlDcl23GSN z(uF9B9|U+=`g2A>$Sp`;Xm?+CtZ@QoVU`Ex!Vzq?GKqSJcJx5L)LW$)2)mwQda;%u>m9UydbDG+nYfNJgKh)*c*E&wz;nOs$&%0*@px4Yrb+UTViixqy6~xD!xJ zL6tp#Y0jR9`;o!Ykm zU5S>Cm;4{*DNVA-to0JHU$VC;&=#nzR`A6JqAv6+ zLefcs;Qj}Cb=Ac##>L)MGsxjdr9H3HE@2eL2JcHTTFja)utq#&f%;fUqma) zhKXuI#%Zz78>a?6w(r*t?ZcCoyX{7xJn9hu*&Wt2?cnGzzhT?glg==TRx`pXWF;XR%ddtjP$oC1-SVfK z9mi%>=c9xCNX7!RfS$*CW6sOTBWo{N!8%1N?e^{y=Gy=j6@Tl11IMq&QY8%Vmv5k; zi2huaVM_$F1cZdXs;7zQ5uKdF!9Jk!eV{9@-Q#d7Me6F%xPfUj_=8E=&3U>T0TZ6 zpeIP8#AHK=q_-L{iRL+#u$FsS`>77YXw%7*PnPbRdQ8Ar7c1?w(Y;f52p(ob`NvXv zQqH}(dko@DuGbNKdY7;dx+3SYjWfJU$4ysf|E`=HTaWdN$G~8|Q>tb{jTb`h8r+9# zg+yZ;5KPXuTDSsh{%E@PS4Z!#dgmPpAwsc^<6jgRK>iPhZcCAe>=bV=snKSm&LS4>pr(c@imw zmP2Y{N+A^mcTI#IS=824MRXV6$XdYlkv1yew8g0M0#H~2nuDx~&Cg1NfH#(O*c+ws zjM9jHfMdX#Y2LJmYX+^4xPrUJsf>MibHbpOS?y?bOgY>bJ)tsOAz+mrBcpM1hUBvX zyasH>lU88O%x5xs8vrP@GrmD86}SW)S&?&`KcTwsdX)6dK%4Vf$V-NuUUa4Jc=Cl8|m#FpJJs8flEEV zj%WZt1!y#xP1_Elhl#NS=uO9IoO=N^9^jk@gL2>Fi!BFUwJc=KJSjh@X9F{+z5mQq zYDiPeP+~!PW?OjI3%4zL-uVG|-V)>J*gf7!nEOzjO*@ybIH?`aL`quKT{yq;dKhD5 zeIZ;SrKd2Gjdamw7KWS)|PyQf-;i9yD}2KubFpj{2m?=r4x#qn$_WG zH$%_*0Mz05!~RL9a`^eVa=4O|PA;a3;Sb9A<9V_(`BlIYBrL*F5_GV+ceRcH@4#R^ z%iIE_+4+d^oI?NJ;sD%;qD_Ik6_`2+eoVP8#r@vXQ5gf~^3GNi$e(LZS_XUIxN{KA z50k6n+`IbeVQ)cV%_Izkpk?eS8X};%z_-?uZl5(J8xL?FmbXRd0Z@Q}xVoAVf)4m9 z0YET2o+-)|#Q#Go;CAh#_JZvgv3^B=O|d_m)nZYepuQGRdNmUx1+sg)?)M|)Y7ipq zFP-3c1mH5O|1#q8jTEbR15I52F5toi*!G4LD4j9iKsPNahEvCe08`dC)q$GgjXh6W z%}%sRk~m>PTbuQ15Kzz_h`Vz*_8!g}mrU%^*aVp;cZqJpa2x@C?&*bmTMId2HTa6r z`q6VMyDg0FPl6=+^f zEH834VS@kk_;_u=%A!TH#{h`FRMR3G$X8&?50a*(A~1|8@6`Bs!Ah1bSuv4kigy1G z^xd_U7xo&%iSCnL507a^fv&A*FsB@=x);``D|P*~6neEi zd=E4TdJ7CZdwweZ;tdiw+Bv^YiuvXNp5=pFz2OM>V~o=QL#8VB=uUF8(AOv4HD!C= zh&5|$O5+t^(?DHxW@gA~yk8R@s@(!M*~V$CHsL{omrmk&crfEYTtTe@7os zM|k7G8pBy@+ylyrV!7SW7!+S8MVP^w{t7xiGyUE^P^ks=p?hLXM(S@DZVcpgBjn&gh)C5t{ulfGd-{1?c zVpg@&2d?g4)y}t-nC2)5um#+5;h2{zVXe%C1K{ZZs#lUaVX4Oo+@2N=`+f`D_FzWO z8|X0jjQO=v$~SZcD^CU?w+W=!DJ-x>45`n!@>I|?>3hOoCwZ5&iAC(v{$!hxeASYS=Q@Qu!OM!-l6(ZdK9U|;g zX@JqV#bPyB5##%!6bC4=U0+%9kErcMzv<#8zis&zFpUf(P;eC3 z5@SSDdnG_59AJ?N-w{;SqOePKSzdCWXiEIA)(5J_XxZPxH9EA z_FRaP=R^ccwFO`5w@+5i+`wmVG|G% z06`7UT%HUoLc=gXFLRDo)tOyipz9RYY#4~!@bUKU2VA1__WdW{8_#|IoX#46NJ>tL zE56!5GE$hprn$48^-+vCUkn5`6<~JUCGVWJqN`QSV`~(wtdhc_1(;V@QZ?e7Uyz=B+eQ9nL{CpxvnTm&MeKeUpeWH=>n2LekUcNT8VlU9p=z3mW zrVVBubcT5@0!_eUhJ;k$PW&8*sWL2L-LHnfZIrpXEEZKn*iFc`k3c%^a+WTtdtbu=-o(Rc?`t47AjxKq)ioGK93(n{My1uMn`vk+Q=M z=(

h#T7(deLk%_-iq*5lW2{v{n_f2-2Cj^`C?ujbOmh zE|x*ICVn3Z(TP3#_|Z__LD1@-*LbF{L^vW0`pR96`^&D`$cF zjV-0)+C)$l9!}6gL$RI@nik8|;gC!xwb=SIoFMaW*1deytw(eVZ$*?Ud+mKk?L>Sk z1O253FeejJPSh2Q|FXtC1&B&MRHqr2mP50iv8eHK1Tu}Q&*LKmV$*Swk(o%CKb5%H zp1ijJfQXMs%G%8C1EIk$n@zF$ka6*g=dsy$11W8?Emp77{l#$Tr3du|?R8u;gmXFS zj2pR?VXPn4oX=Sl9e0uhI+5nyV!~dN%dVY1<1UQB zKS?Pov}{|QkNC98v!mMS@Pou`-`?VhJ|nC9FNhCfv7nwfNG7YIE;pCDc{$F8BqsF~ zTjB&H%FMrv*6JLwHl7ud+fx7jvNO{#jbQ|^E541rw7J~*jFgPtux6Befb;GG zublalZ?{RL1vl))s{hYI3gc%m0%tm(CYfk^X`{As$ofEWyz*=RVFreW`mJ$a$tRCzJ02>(FUb9G~uRJ^ea70#0sX3vh1zL}0{WHKuk$cc* z8M9Fgcp;(3rv(|9$+X*7!`vXrnZG>tI17Eo>@vbpg_Yw%4v;*%j90y7MGiQ-&^#W|foK5> z-3YLKw#0K^QEyZ_AZ@a@@q>N#3ZikRta{FH1!cL1bjoJ-o6-z8Hf&%laTC^ZgCFd~ z|1#njd=iW?sHY1<%{}e_h8+mLGSglxdcO8LjlWTIEdjZt1Bi(1Mvz!gKzm~#Xh{YC zTkt+ZZ6DyD_8tStl7%!79y}G}y4!xz?9zrn7hb&N5~D}o=!p$D3XG;$Mpn)m)>v) ztj_Qm_7jum(nxG>i_;Qf6lL|z+hr6wn~BjT6DM+!ehmj<{dpqePGzVGk4y=AScp%X z93&*H`}8783oUX3GM^Laim52zSTDz(Cq-Lrdr_VJ<@OvQAsX*C+~m>kIFqmJciXg9 zr_uz#+5BRz0RRCXeQ+pgj^Q4t$7}<=M|I`!3cnMsDevmGCGRQ!#zTq_=G$JRC;1C^&3)kmP_I;f*yo;G-0)d*Rf1I2Ef1q%5xp2Un>ksxbS0!l}al*!l}k9^Yu(rx{=X#Ib* z=igKPjvXMwL|*zOQA`8fSg*$(NldfcYonmV)q*eHTgm{RTx@i|a{Y>ShR%LKBfm8l zdzh12p3}gs-I*^Y!ZP{@$e7~a_J#sZ?iarEey~ib*P>o z+O_Z`0Q~RkF$@y0%r~F8cK_AMcg<22Fs>3qKqe|KSUElB!6fWWUiNZ?bViGP$Bcg^Xmv8y zs0!=~`%rv4;H;n4z|Ys~ptz;(cF5xisXD?KnP;|^wG8?6iUPwauvcKNJ#D4%^XPZ2 z^Wc(bpE|;+roF|agu5VYVni+mx_RNuYx#-uxAp<-;?r4WLk(7Kbl1p%_qW<8=UZ(w z_8+xT4lt{}Z2qZ>YinM@{0o$6PaS`^hiT?}Tl5M3YHNzCgJZm$Jpia`ultUA{WC4* z27^Ukw19Hy-^?Qr%9#|I-A-dp+Y2mR=L*#!7&bIYL7dxD6=ZdijBZ)u<7DG^=W=K; zQBR-n^TgqHK?KR?oS0of#OnCMypW}N_TX~h`SblI-BEm7b7$mNuD9mpOZA-4hkTW( ziN90G(OC!P*y&%yXuuBWN4jgtbGLTB7|vS4)uNT9Mu0fk=cL^Eymk6W-eG=ohz?P^ z(gdU9!0joT@(_g&YJ(gsm@SlY;A9%B*5WVS*&!9IRg*RmZ^i$_UN27{xaO{JTx386 z{Oiz%ih_0Vh3m{VGxte!^My~^0GuWo0RYTh(*7Xn5*L_`@)1x{&MuTw4R!~X&-v)`_77Un1qdQN`{}UklA@W&qzCJRQc#pWoP!g z7cN?eaY{I3Z}K-A^VBlwwO4yrE-yfcrQ*L_c=SPH)PSp^MwO|}_4b7xuAoV?0%vZW zYu=iAv{QQB{^0YjP z`89qdjInQiXLylmGwgQ4>%tl};Q+#RLEC)w+XoBKN97bR2N|1Cv>V>}hIWtBd>jK| z9=>M6?m%QBUjdJc?R&&DSgj6`6+6?~5qh)i^a?R8+NwCFvbZ$j#O*!cF(}~i9os#Fel4`wIJ#Ik zk=tIKe+bBR z0}_m0zdl42~e<3ZVIn zvP3$8fSZ^P*x9YS4rv`Wr%8#ta0=M>#^`<(&n1wfZBj;19rg}x7gLk1(WkH8VaM=9 zd+T_i$f-WVXE0yQhDmA{w#d7>Nvy!6B(5&rMP1HGZ2$%1HB3$7gt3;oUhN2Yicw1K zFzbC4H=L=#^+(vy7rFwf37& zN41*O@^=GDs@beIsT*`Ph!t7l1SS%EW+W|MpJpK9iCuk85#!^lMeczgD_#0QE27}l z{|CJJo3;RGMgZD801`6*H=nk7_ZVmw?ahINY$STAA!|kmh%#NRuJPX!1`(O>#RsL| zWBz+lfF{lTdbEL(`R*Z5mFb%ox4gU&5gU@A#m|FHNGS+`LzE_};d8@>A!CU9N;N^g z$yG>eAlXBSXMVB6k#%3~O32ltNxK8M_*}w;yphHeok#oSXX0HTT~cP{$6-O_1?}6mIXn6Cp(&pS^VJclFAv8WlFuub=RAMg z^lFa^?Y7@FRjp=RD;@yvW8hxrHB>C`WWw0zSr3WJAxv^O(&UsYhh?tZ266@4LBg(c zX0<>M2wFxYKu6^DT2M=VOw}40837|Aoh;(tq!A5-nXG<{*q(8+$jk#SRw_mZ3=GhS zo`?7mtG&+FO?U!0i54dtgS>I$4d`OphffAp0BH};j-sKH%$=?&AVIRalfjqTB*imT z7NLB5BWS68OJ8Y*{DxB9L6rk`&u*elbE~AV-9IAEpZ@OH!vi)~*kcWBdd@yFU_T?C zF=?%yc_cIZ>C;R3J75GT=zPUcv6uB~U3;EiSV0N}EJ%YEE zwsCM?%)@Ek+q8}2y;%eoO3nw8#Z7^TcU{)9jz|ch-mJ{BQcZUPYrlH_T}{Kk7ya{> z-1A`lYg7ykT*3ttQokZcQ`%!FUy!oxW*v2CyV$CUFk>Fe2FV!d7kdd41|ZBsp3bn< zC*UueY}B98!F0;okz;LFf82|oU(32nB-TI9EA0;wj4~cV=xAA29X@qEnw@PgXS&L! zE$p_NkM8B%z0UUiMbTgP!@NWI!arG*tW3mSQm5*{V%uWY7kiS?)sMRZ%qyh zrh6_B$FP5ag^!$?n&%6WT(?-O_RQBx^9q>E;1@o!UKg6258?Vx)4h47rn2Toe;N+u zZpn93f@GlwqV^YlyP;QEcbT=+;L>OebZwN|4RH3#f3CMH%uQdAr5hfknZMW8vbMXV zux_Qw@crcV*Joky=Kqhgw}6UrYukVo2N^IZk&+lvP`XsQLjjeL5F`XdT9lC(8tGI7 zX%VEQb6@}|rG}7_7((gp=HCzJyx(`u`*C``-1Vv>o^U zVKL%-z}tP@(epYpp_65?0rvIuA^&*tHi@IgN%$$eMCz+)CZ z#7-j^p+)@H%EqAf1A$clt8Tx$dGMJTEa}|Ul&uT@u%wKPjK^Ybl#R*$rds7mWIY2m ziWmAnK|6l>P^V8c)ROe);_~x!uf&IewTZJmtM^Y9dJzu~>@yA@JR2~$4zOSU^-#f* zJO`WPrwi%)AqIRsMX;H@Tv7{^|9v?BWsqLdQqWFw2mHV9wD_M-X=a#;6QKhOA~=dy z;{HF5yeA12?9>J?{DTcrdKhlcv7fHq#-CqrcjL3ZXFm_@?~Vg{HXl#ukQjht{+C0d z-h1vWW4Y6qvxSK5$gOg4$5Kme@J}_-rC*Gld%(XNjP$BYE^QB*5{rOd{*#q=WiDIK zJ%&KCHa_#<2bE7@vg`6~+{tPKu{w1R&UA16w|i&qhgU;2!M5KHbyh$t!rNxEvGI1D zL$Qr^0o$EX2Pv8Tx%I+4i}p|$+hje8MPtxdHMgttjhn=cIHBeCEzmXAjz z2i#@l!?tK=oEe7WlD_#9SvSgSb#-n#1r3*Pl(eMo-2~d;??~MhaKE(1`+1ue;94Ki zU2dyMq&%jr0?he_(~B&i6AEdCt(DeC3CY=54!X9NhUwhjO`;E$%9G1y-ZeWH0&eIT zt_ia?3Vc1gnNB&-1+>Hs-4G3yMIl??aoB?BN(8;nA{QpMG#Oy%RUn^5bLp48b7wnG zoE;{ULIA%`l0v{}1^)*_A;Dt>uQHCv0hbjP?IKKk_77i0yjQck;gDoO=|O*doAKBU z$v_VNe!3XEyJ5mW=0We?oH;WnBXzhp_>-qY`ybBhd>~{wD2o4KIYnKJcnT%DY`dja zB-fZ|#vHNYH3e>hGA@l3Y@1yClKY5#p|xeefkov;FCh4+d*wQF(Mr!cr5?AqXf#y> zBtFX3nIN=)Z3YCX))C*i}nD}k#8qvGV zB36PwVuBM9V@;o_M6{H`3r3VwSA*9^K^yYBef_Z`fGY^yOe=4s-_;!2%@tATN~&Ra zdUB3fEaDfsP-cIzB7r)gqY%^Pwl=EC@HOnVK)boA8zrCX^Yu$)Mq=Q6(Bt)An?yS~ zsmBR&=qlAZOesiy+2fwlHzBsp`Gz$0+Z;N=HziAax)vQFF*i6Mf6fzlqVq=Ng82Wi zlh4E;Pb30)$v-`jv(;(P5wRliNO~V&c<6j=q2vnfU;$QtZN}r8+Ipma?Cu7y{zD$b zeIbw+6HE z;;D-4h>F>3eZ?{&amVXqZA^IFPK3o+L;?lgHVd z!{Tj?73~ArEzD_(@PrJdLqKEZ%(9J^sa#^UK1v@$7~4;{tk<_5YCGQ70f?>CWw63&O1hmyxT6-+* zyl?m7Bkj!)^sOLq6|@)Pvn9nW;!_om@k_goB~ZO(*dQmL;wQLE5`pCUPW`Y&ems;) zq#sF2XR47UtW6k^(3*|O=;Da zyo&d1wZ{#n(FuHJ%Dn4r@;J&t=rCm^?B&7+yvvL;`30gsf9D z&EoNf!A3ei4&OBDeA<3QBK2ZU==UlaH_CWU@}3zlX%mX=Tf<)fw zxaI30lL>!gGW&-ZZZbRrd5|wWn)uQ2KVvr7Towc)0(Hy!?}@pk9;2rgrLDj3Nd_LD zocRN-m*gW%+;UI9y@LPDl6uVYvV9m&E)Gsbs@~I@tzsb%#ayItJ+7yM*pvyc?D^03 z^vrpIsRDO00>=KE@mB01h^6oCsZ+;nA@I&y+`U-8Ux|ziT^F_fu;u;g!9zba zDj5ZD9;-4`ff3Q&I3v6nwE>O3s%JIwnBWRpTxsLQ#AO@^s_YnAwDxj%Z9(}VugLNf zw(T`*GaLq`KMnGX>&ql=Y7JsF=0ZDEBLS+*ZGH=hIhAG)}#;9`MS> zm5Gt>sZt+df^n0zWyJ4c%#BE8?*}D@q60sd5>G@DiY-onI*m0=ea~n>2&D+}Qxpzd zwE7S6&ezj-lT;WSUwFZfQU_2qG5mZ1ob0BX5q0g2W3j^k5)X;amejghKYM$yFE)1% z_mpz815l(M$BGO%(n&P&ff{ux zF%o}u0d{LX^V0~mMM5Ongt>~elc`GnCcOJ>y(+#j`L~u>Pkd5FJ%zdi3UoQH#dj(s zFd)Xm;)Yxc+-mNiOO|*~r8mUJ*Q$F2VV>tANRe9X*g;<8q<2m(E%1GPm+wrjWWLvJ z8AJDnG+spUB6giMKeE|-y=vom-&X1t`B1spFc!$)YujbJhmH3oY${}@joF$eR1UT` zy4TncV(FwO=s}M07Lc)ltqonRs$E2wTHG+!@7rMdc!x^B_Ct!OU56&pF8^NQlKwBW zu8&{YB!VIS& z@#JMF$?SO$WoOR^Rr&wZnfB^N01L1`{ELsC#CFWf-lhTd$%>nH04P%E*EyJu-B?s6 zu}?NVfteItSerp)1nggA0zQDi;gKNwKLvLh@L~fJxQBn=`N;rgBEQW5B2rBmu@9@U zwaknOcV0a&im-2Za|sj2v%^7l%qPJl<38Jx4DOG)n;pujSEea4y-!N(^<3rCez_LXBA-hN=H>9< zw^KiHb5?XkVHQ7MIV(Re&I~npZD_a6nujB)97(aW!~0R*~f<3S`u~-LmH@c`)_7RmC@Xhc&94-&?$Uz zrI5Y9?E?wOtlqyMCVQ~@A)==s!=J(Z^{qAU#Bjt8)5kVnLUNg^c07Z|$P`kwfHeG1xEGqM&RT1#@g}BESv0v#IV-5$&FuU+DL*%I)l5 zcI)El?%(|jRuR7OI0xiR!;~Il)Hk5ax}oOV?X?-vRMz8>J@4xfD$tU^Ixl()au^9U zUHAUMou^cS7m0DMYcmr%eR&zao3Dnuy|;ewk&M5}cQsfJBK3L5HJDw#VJGK5?x|FA z?_M0zRIW~5Mg|?`p!&-u)sDPJ*1Jg?W?1Ou4M`!}j>WZahq9M%vwZKVbUNDK zI+lPll7aYFZXCD5#p&c)#igeSUH?_s56)#@jX>%(XaIzTNjo#xpa6x zFHV%AnzScAvoAZ_|BPou()`3Ap`@9N3wfo0y6@&;8VKPb@f01!Nku^y4wFimq|_|o zNx{CGMi$Dvb$I$;r(~ex? zZn6-A%j`$9-lbjF0=;rugQykn6QE9uYQ|^i3}M2Z#pSM;cswo#UD8#cK4cATJ6bhZ z)+iB4bc^vNfzNfsn7R!_J>a#>QF`(Y#=L-r;oSrIwq?yO*RfTyos-kkriDb?dy-K` z5haZ2(Wv7OD=+N&`Bc6JUDy6;f96grD7?QNdec0RZ(B6} zfmV$Ti8LltQbt0kirBWJ&Jh7QD6@PjdE%n~!HWo90547)a2<pB|-zk8F)Q&mqW={4cOqNz&o9|}ssQowXG>fDFw8o7F5a&bgUdV&n9eDDB zTr4<({(-fMtXw#wNV+)iix?T#en}bYcFvwhtl+{KgT{(1WnPlk`uw3J)kT=#0x<=n z#F~?At(-S+$$ba4gd^({Zad0+u99WgehDgGWsGPX3zeDInQ8Qr1^|d6ot6?igZf|_?hgq01c3TS z4^6gSDIDOMc^e>RT{mGS-ml~R?v>`yA1CA4_4lY>i6$!=$Niq#lxD$-~u#dQAKl z4qz0wKpqe%a!)DQpcvKvYqXfs>x?rdo;~eJ(bK?Ta1r*@NdDx9vp2Kdxx1+xv>*E) z)pe?iE(w;q?Y(Fj>XjSDKPOs#yG`j`5s{lX4b;!b4iOyld*71E)1s_BzJ9=4Wk#h3=Rm3AS-vcV$p^0j{X3LzrU^ zYjs`!&@w}c<*RmN$}-l%rMoyRYm1-vI8jpO&KKfV}tVd6I@H z%-ZR5@HX>Bp0$~&HTkWURKxHE_@-PcBCtI6c`6W=IMS)}xd7e~9HwUEriFzi7YRIyh>V5dA*Z>RT^yH1^!Vawcu9D;z&5-sF+z3>K!B#Poc(Ep<)UhE{goe%OYBAP< z83I@8XbUK`B%kyx-&OMqtbX0Rzae?z$diUEvD7fbeHwJs>pQ#5XIkKdDZb{uJ7Eg} zR=_754+XBcAi({cpTBTJwW!w@#yUs(G$x$>(ZsgkQ#NfTX%Lb zUX0HDxw;bfLwwc4C66nJ8#7gQW4!Nv6Jnugu+_oRyDm;hPVMG0gr;By4j%L!j22=p z-|a;Hc%WDb&G-NynsX#xnI45XLO4U>^dr^a5g~6<7Cs1A>|;~Fj23LN?r3L$WIxua zfSJUzv74nnYahL#qfVv9c&5xZ0@K!nrYc#g%|r-6A)$mM4jKELCkW=uFH+7Qfm z&rj3?D7nEa@tH0}z@43gyXc&r~9pJ>bP+oQ8J?)km*31f>LJX=Lm(c#D!Ik~1o>8sNdQT`+eOkwdRonB?w-2hg8o z?xP~itTTsu-nA^svHy|%wKZFO^`cMcnDb2Hm|EXy#5O&9*1O=z@p_CX9!(6l!A~td zl-7*xRRAF|lAL+GX`3|?2OKPLVd}i;JNCa{YuTV{+-)CSlUhp(mW+wO9BNVx$;#~W zHnOAm(HL{y52{8kiat-s$&HMHf7Fg^Hc0s&=EEIs!--%S=3_QG3)nWC&$ z2P|wV@B<~oTe4fRDnqt=NNcj^AP+3p-@1Y)V`L8~8pCQz5WZ}*prT+iw|AqjLbupF zI;JeFL9vG5%GnFBg1XeRiRN=9ENPGA_j4mlf*qW1tNQ(T$A+l!-PA=FhPWPD_EBgo zs>tj|W-2S4q!PPK%fB;2h5|VX;T$x5N1e?HovnBC^E?mCgrvaY0VnO-50!+WLK}GV z0OWQAl7<>$*nM(5aH2wlU~H;!ztrx`u_VL&EMAIxgxC`7S;q?7#GM@10FvP3p8u>{ zZs5$u{XxJHxUuzt1hnyyu~BH2$$mE?FGn%B&i!C%Monx@4hhEhRDonBWZS9A5GuC2 z9AQf9UvDe077yFi8en-p&@qyD!Z={A^Fv<-1qoqw?zxIqyhS~6M0F6k3L zQ=r~Bmh@x4AM;$TmgRZy#WX|fmeDKAO`8d33C1jrtfT>YcR)4PTi6?21EDZ>YyHo_ zuf1ddY1>|G5ZEG-zo+V_#8Tn(7b#EPMvx@FdAs$HQHsxy2o_Mx?s5a7!q&7u-SCyV zgQt1{W>f?57*qIdSdU}Ja^SaKuD(qF^O!_@n+*}@v=~)X}tQyZ{t)qH_Pv8jLzXX;O*$C{oBJUrl&Hy1K$lDN~!SW>lWNEYMHAq@4 z)Hk&u3Uo40;St>HB`oeL{EV_WMFOdH<|&cddSlN6{Oesb;d{ZgyBCtj zL*_T1ce1+ycgG7=cvNchefLh;=Q^ zug_~UnjdFI1yXy#j^0ip{?jW_co{eiHPrwB_!SG~%wwMutzbYB?p3_*dMW<|obWNq zL7_~r`4oWebW=0}ae_7;%2odxf_+O8} zhL2a!&!O?TBBo~1Y&k>n$nws!s)x|w;x&R-Ph7II-x+ZX$7b_9csVkyBYXsfO(-ma z(9pEz@yZq!am}%vZ#j@XX*Jq284Oar!&5G7Wr|zf0>V*kY01(dEiO3_il)LuJ0;O0 zfNybm;{bx;YhS#xCS4D4pHC@U=iH89Nn+W1ht5=LlUS`tdfK`tH^I!2up?JMWW6Au ze{Gb&cl5*#s+HefRHP*Il7q!HCo=$$B20iL?AKZggSwn*%<1l&C-4&A9&DiVI9!vs z{cXAI9tTxqHT;ccL&RDfz%Em=a`a>OFZx!GoKW&8+dMfoEEM&zL_MKigl;n0(8@q^ANj6}>v7Lg$_k$nBY3O~3z>FfDA6Pgxe%?i@G?-_*+D!gd#||O0W4}% z|6QS0;7C{ok%e5H7q(|ud7J}>Jx-3^HjiRZXi0$z;+Zp6M0?i8hstl+_AVB2T#Dyx zy)*nBxhL5<4PrLLn1)krgKjUR2+plo5-Ho6^zQZo4dOmNo+=S+JVE-_E+ArE>$Boc z-5WPNg3)&-6%6tan!TOPy|CPTXZKp#9Z`>mp%@M=!pjo7Mkn{~vYv-+xwtRA5z=xc z#tcM}%tABHO3%$LpE@0Srn-X}a&@upqxna*Jpv)Vn-AV+NO@kb_)%&6r$<|##BPv6 zti0HdWI&L}{Xvjq%HIZ*3DCz}!P8>wVmVGI1sP?bgz$5atg2M&`$^9wfe+Zk_X14L z&yCsyyT-h1KaghuM_5t1S)Q@GaXgvd4M3sH^T4k$I{?CNr1S3@1C16bPl3)`%*dty zX)b*MCW*#ilHq_$qRe!Mvsu0!keskhGjAtyY>`4ELzckI3@%q_M zq*LCn4BJd_%V;>|!?#9^<1I*=MEUKe6;SJQLA;(`Y;EH%x2wbKNB_^UMaiPdlI=+9 zWC849`ZpwXOfhFVBF$o?y1Ay9P&zhdk2{dMAm^RJ*E4REu7O*l-5~&8aIg$oS#RPJ z+B-iriQcBR_%0;l7UTFFhuTr~8e+e3olM27aORqs;dbTSQr~SBDzYAS8y{|(Gq5-^ zc-@`bkJKcOUh+sWd-?yD<%ER9e5^hE&2uDhcW7s!Di=+=FkbA%$j3>x+WT&Pk>x8> z<;CykcDcFY=YZ)TiIYs>yAuaLK`W*Hs8m()sR0th69C1&JWzXFN^EYuKNAV0CYSF2 zRS_fBKi`y$RJaFucB&_29%C{9#lJuKI&Rl-rV#*nEc2pDa6vyw0>??V2_i5)aenGu zYY^&UkA&qPWeyYUI+>z1x3Y{9=a;L1Qw74HiTQe+tI5>;&LEAKT5KgI)bJtNkRYwk+JFxoH#w^uD4h{4N*W*oEa4}kGSnc~F#=Hk@ z2_$li-0GGA4x~Y3zB(lmRkwsslB^2Y z3Rl$2RXXpa@t8c0x|&u}6twvs_I1_l;xPsQaxOSkRqy&Srq}Q_gAKloQ|A1q8~s(# zDYzB=(~=K!_p2w!S<|H!{lcFT$Zvwt^B8?Id6yhDTWJhinRyt*yuIKj>b$reBWa4F zd~h4sHo%U2srfKgGX$7;&Sx!QHX}N?ydox4hIy4Te>3&*XDRn+&#dWF$<2d{5#; zylU=ilTz`VGjefVDBn30z3>H1^tNWp&4lJuPu7JG>lE9#SN`-nS@L4;T(TlWzhD1v zh-vTs3jp;_l<^!_3xH}71aH?!M?mvE3zS4QC@(Z6gW}3DEOW&O(RJnc+7FKYwVoKv zj|+1XL_ba+^Odyc>+y!mqV18J^C0Zyw-vb*U54VKtI4xZ*W?cOuAlw!8+fIQf*^g; z9|j=Ah$i@uzsQ<2%B4KBHj{mBKm49czdD8PV`^STyBpUkLW`x9hQv8OHr7G4!uIR9nxj!ofC=gAVuHd; zZf)6m@l-$MX4ul$yL?pUIBqegC{nfU9*XC$O*W9R@)B=<;M2HKQk)MrrS8p6i7{^8 zr=mRT5tNeXKt(B9#%JR(WY@MoYDsU@UNQKRs55{o2;%3t@m$MIFA2krUt2)Gzm?K{_0CaJVL_G-&Mb77`&LFSC9OhT@<2h17|yIF zfto|O$@%HQ@LgO}Qr!oEhU|L(cAT5Y?{;2XQ&@+(sawpEd>1`Gb{hp){|EB>OgJ;U zwb8|j*39I|(JFHil4mN6p5hyculjYDvva=Cz-EOAAe>+75$Wzh?TPEo(TYc{V7K-o z0=g-YVwM~1i7%tjOJ&2?u>PvgGm_n_@@=^hN8>AZ%3Qt@vJ3X85qKa4Wx+cr1fNOx zCcZQB3Cle5=Iud*k-%?*foD4=Hx2ToJPS+o|P{$luU zq0-He@qB|-LT8`4D_%A#Mpye5+vKXt7|Fq%KVQw{b~!>17=Ovnes|g9i}V;f(xIi+ zB-Q^6*QX{&@G!Z-z9=Nb&n9|M8e=O!3w*dC_Y^;U-|N=Kq{VbrJtM}ucj~G%V2z76 z>NkyO^&)v_W4~5#guXJtvbl>)yzHidzd36P+vPBM-M`aFu6~i->03~b>dQwgni<(* z!gRwG>?W3Oln1R=&LBt?uW(@Q@|p|JNp+75qbNz;TVq3{@j?MjfRhh|wIjL4Ih-C3 zOY$!NLQfAn16diU0vc`ecBri>aZP3GG)^`q);W!x$pNc{Ggoln%dZrTQ32-pGDqM| z9R`axtel08A5LZ*GrpDCD2X$E1x4Apu zH<}@F;j^VE5Qw<6|2q&#lmI8tl&ru08uA9Rl7t|S*%&F>-9QBM(I>yoz9R9#H9!)n zcIZ4ynC9;DM(XXZBjFrD$G#u~c+)CBz*Ji*1%di5$^3Rrt;(VE3g18gl-^thxyvM0 zBUkm%ndtdeg@Vk!%c5x)=M{LDci{6Gd9C2Nz(L|7|GKjm)3Nw$iqFG0n;SrsUwP6CYldqFdt+4ZUHI;2&!5isMvJ~Y20yo9_1B8? zrN|wS0Y7}R^^1n^LJ+KQ>8tyBlW=EhL5Io4GzZc^rt?i|t$6drg!r><6`Fx+matW3 zylIIy`Gl1l%PrUD?!I`Vc~(;Q)t+&3eQ%T+uki5$-+C_s`dF4U3-Q4#5}H3&X&Y`W zpa(T0M=3_%3ivp*ZNGOdIar3sBl)kO=nGyqXtq#aHLzE+94`l8+sa*_)}nsP1c(uq zi$)&7ZUdcc!%sFKY2Gcet7(FAzhN$EyWH-t}^4DGPNKCZs}nHzD3p0`t|H^1`Rx6nsvT)Gk;5iA2qr4}>T0I{#9qT=el z%^4z~2O>a*a)L-=M*={E3l;!8wo&`e^pUA>2(-kQ4<=zpEU;d&!I#T+Tw8_jnsB^+P~|2ory zWk24mOkH!cwoY-ovFa3*?MkB#OoEZ|bE@#p?-lu{Z}Sq}v-;9W?=iWU*NmHKHBt{m zUHQe8IUlqs{3X)1J+kI=5c0X%>&8X6scyVhHP7%9@(lsoYrcHu5tp(X8x9YqBBmrBOzf-R7mmMqvk}=9} z6G$v2wdo{&Aa$Y9&~HJa=(zN=lo=Eoe8#8;WIow9z`WF$Jx_uSuS_O{yvi`BUGpy{ zPoj5;Q@7tKtde*;^&2bG1Qm4bbMt)BbyQ)VAh0;^O0j?j`h4$-FImh`u^JJ90m6GB zfI1k#m6RClfUX+s-v50^C$WX+|I1egOJZN_Ts>d{6{t^w`nLKtrLxEX_qE9;6*-2> zpIk1(p{UN9#z69^R}dtEvv=^wdNQOrp;|NU_a^B7oT+Jf%nY#wqNn(idZF;z3`b_) z6b)+$_z$0*jW3f z7n^qw73FWM!3FcOUzM%%Er^hDtu$+0n6r@>3L4Ih<{S&i)1dLzX{-<=e;6~`GR>!l z5NA3rYJ?9}4pwOPs8LMW4i%aCXZL?}%+ym#oD2f45=6lD>jmum|if z+)d*0l3Az{XgNY1gElzLYlOpmH#q_p;_fhYrAeIuU-wzP-dk|a-hhy{R(9H|(WtNL z@dd1ahy6e%6w}TF4PJ>ol;TYPg`m$9CnoI)mSmWz6ad(rh2QQ*qW5hG#uJ7JJZ3tshOFn2v2+#0SO8Hxh@j}x>i_?`BLJ!-3A?L=Q@PIwf$!4( z8IBkkwC^U*JGT0W2#Fu536$M;mGVROC$4@<^6`~=i+2_LAic3apu3>bKuLA!Jo*7Z5r(5K>iPX! zv&_qv`)bg^0N*tMz@)1JvOv!E$2Z9@=dyYwlQMUDdd~iDrw9DUhc{Kd&TwST#eD{S z8voVdfxLTX9r{vGi-*|UYL|Q|aI_H0Un*$Kr2;U_nFO#S=KtxA{MqUQ)bWewrieXu zeE{y3C@WS8W&nwHUON7T6J08Ko8KHUpc#p|INHCW6**SvcR?#sV#MT!V+6^whm61w ze4aYT1p})XRgeOWHgbPru5(xlpc5lrrqP1dkMYzr({$p%7rfsq1R7ob-X_vc?jiBz zB2z}tW;)4Imo#81P8)3g+@FEVLIPla6#OBx+l3lk{?F0;^mG4gY`K0=ce*$0)^Zec zZPkjkc0_;rHV*B)S43XsOdwbtV*Vr~dXsN}ypLf-C>wmY8mKde2&Pmhh>w?+^4TiR z`!7vRP(#UwzcrNn@!avYOQ2;YlLvBNOLS;LYC}i2gVPc2%WTM=~j6&>^U;{f`d;XxBqc z|E&vK#ivUlJRNXCT;IM7i;8dk z&{+QHPya%Ghe5}iFIaCl>+<&_n)x_{p?m1 zB-c6z9m6&K)c?&Hm)IZoN*-w-!PxPtj(CxU(T9P1fRhn9&H@|)gw!0ALDa%xG4`tM zQ+fiZMXJ1w8_hyp4>}XXAJMkzQYp%wfEmSXq2FJJwAFy3U-~+S78qi3( zZd+p~GD<*Y&$jmk5JDxuHrOxo3Ih0NIC?-|{p4R-0GEE+KVsLw@cYs`h_0tlhB%D+ zk9@oyZ{CyIF#uXP`c-&Q`bz$~?ZLDz7aOc3C`4ienzxdE2zc3b!)EVy69}`-mwxr)e7v#ow4(X(C@}$bpQuR;~Jh&;xHdXYVq$tjP zkV0l(^TEyUL`fi*^k7(SaiJdeofmFVv!V%&kYEYO7)289pJnjfY!^wF{zhw?E6|Jt z9n<5C9#%UB$47t#lsn+wc=`miBotzVtom8@mY)F*UTLtx!So&I>_}kU?E;!KBP;?F z-$Z^gY>|vgjWT+Q8i+Cib>Ix3=O4zg)&p&EH?Yxiw=nZ~ke`TVTAe@phnJFsU(L7; z7`FQqrvW_Yf47+i?iy&_0TFNWEufioPJ6F{$xeUJ{-CyA;SZPPV-p;g2<#Gy zt;uf^|06%k6-%-iZT6!a$IR$G(i)_Jh|r+Xtt3Uo-Kw3X5Am7>Qc=l585gvODWX}Z z@UzwoH%)wLk-J0qyFv z8HvgMyEn0P4@7qqM)coh)@9Rn#kd1LD}b!WV#fdaRnpqfmYTLGxDFG(T;ZaFitDdP z#lwo+`l9yuuIk)7;!|OtnNVn|a@4UdPH3W<)lW&)TY8mbM|Evf2Z3@D2TCoEs1>H7 z&-;ohvP#LSIwVu*glLwVN|xG@m|4A5b`F2mPXPAw-&M9`@vRHLxhLPfXFKIh>eT5h zEfe(a4Kd=g`r0UH3>5uV`K~z@qyTgi=#dsOLY)_pYCGm5KYr0Bv?XAN-bA>Asa&8c zD2lB5oDUb|AOZ0n6BqX<6Pw1k+yU4WTu7I4;OfwMlgEwyW{!)SuFdk}quhh- z+h&ra8}aaws0)nC!jaF0_KSATF*H`dHC0odXzq>lV=Hng_(Uc7On>f%9Q=B#zVD#Q z_=IJ0=FW8UzAleP^D@syqyMdep(o^Bj&}O`-FlhV!j5K2`Ee-F4tim!#jUNev&=mE zy+zJ--z3L&i{8(whIOH_62t=NC+L;;LoY}#2ZRG~*mVLusFl6qOLlS6U+qIpyGx%NSi`?BY(#Z?MqpOD??%w_pFxe&DNQro7nf zNiCyzq3V2tCqX=*w~9mMxvuvBbrMTR;?Rw20_ZR?5fL zucNL27gpW6voyLX4aN=}=h8#ZXaGUc+W@nypaXb!OSaRsBQUSUP_A7o`V1_Rn&(JJ zp)yh{R4X6vZ1&}LUc}Mi-Uc0mi}R(gjlQdF@0vSFht?mG^BL*>UfyYQ1%MM#uj6~Ltfx|2<~PcVb#WS;c>>%Er5iZ13#%607I;&9w(RwV`1h~moh_7))VYI2 zk`}~s#gKk>##nv*ohn6aop4*{>qS7ci#WCCt}roPu76`yaBkJ~o;`#~eMQ#aZU#Lr z6#W{g7)N73+*e{69@kwx;m4&5Y|!PctS8i~=dO4=Jdb|0O$4xNx{sK)q@vm^paakn zuJpp6(40fFn4O&}!WvAUxq7Jc0`Fj?W4{{={aJZ`Qcgf+MZ^+P1q_c-3dh?P+1(AKEM!7uX#BkP~9H}^U}k%_&{aN0O#%B z8L{@r%>!um=$+D+5Y~L2)XNqhFQl}%rq_@JE;R{)tCk0{%r`*`b1w76MZB{R(Z-XO z&%fr}C&uoS!uM63&6wg%G(fqIk3It(w(Ccr&F<9Eek4{_$Z??6Bz zkU-IJm6Um9J`S;uI-m$-BfYThbDh$Jm~?e}2lT|3g6=r;_7&og$dwEF(ft9ZT=yu+^QHBtv+_MbPWl1Z4PR6!c&ce=eREN|>mLbwI zqByADC%STMlv-^jP=zHG5H%3FivND6;ns&PJiOQOJa`*G-n_2&d4Rz+bK@<^xS%e- zUr86ot~2d{8@ILO_g{S5?BqZ5i8E=K0#0(ax(Z-tywfDJ+Kf_kNhml>r|Knei1<2u zSUZ*ymIt558lul>6P#RkUC{`W(Fwl;wAF5uSVy4jD|Q9~ua%H!!1tTtLwIb|?#5NM zp{H|K%Z*PX_F|wRMBDc`rWRx~xtE_}6b=$;V~~fVg8@db|kG;Iq~ zO0`Dy-d}?@bqjA=DgFw`Ogv!-jYyJW_QjgXn7U(iA`G;h_n_A6t3COEXRqif%KP+; zxH#I=q9ZQ4WVD^`tmLGoZ-n+7)H`RZfRbfHE9!2UbkmGd#^{cbh33$H)@4qVr=dZ%0 zzt?-nvGPDkD&_(&2h*rdQbMgnjG{;V{C(E>_4ym;3w^xbN zMWAtm=hyEfO;njREtoxVjT~cvzw~h-jX|f-5H_vJWHb`de660c@Rf=zXybP7$fl1k z_~5aD{306?A9u?W#X8&Rn{4K2k+|*SDG8=11dMT}$7hyakL_?*d}3%687P)6&Bkx* zdS7;^ra(N3!ibzB)To9DfkLk^U7tA_q~vVK2n+U1e*P07F}MuLR+NA>>lA(s{~n%~ z2N&5e*e*Bdq7M=o_^AtEd(BJ9!Zv!d_nG${6s{1??Oiir5Z&YcerFK(u9@2Jn`jgA zwm>H6YFS0dm1sNDjmV-XL8_)f^Iha7;rVS7Lh;t+Cb8QY4|9w?9e}asuJE(pHEO^_ zT*1pNR+ZT=qU&8Dpn$5o@ivekzemq!=bV2fs?Z)Rhe+URp+hD}`na$9FjUyNP0@-c zAIxPWFOThDb}IXF9-)JIFoW#tgqHcQn{K#yWW(Gi$&=xgawuq9@j+TotfeA)ygP+r z9RQX6`_wF`Tzp5Pj8A8>^o|3dl-{A4v+v#1p;CO*G9z&s$9fDd+;D^@AK##{`DH_W zaN)_Ww9tliAmvPQIY#m;`^nrW!lt}i1#JxU1d;H&%l)_8F`>`z6k}kJ-+L=lNF%m6t5r&6*DbB&u%&_wiK<2;A_CDq`mt!!bv&sOf zg2KBrP&0xdkXr)0BBXqypWv-MRIHl*!79;PP6SAI%O3_8; z1Zolra*^Bi5KN?L34~@%8?dEWaOH-(#$_fQnI#ief#}D){JB-Y%5)4^r%L>@_eWB( ztuejt-Y{NGekwi~RP&f)_{o0g=WL;=^|yH>w%+5ZTgA57dMm|P3HlptQS?>Y{0JZ~ zVtS?y)JzqF+5sy?-1~(LhjjX3g%dZgf&n$jE!X>z)IfGs`LQ5uwq;}>SNH8N^x!$~ z?JGDg@}6Oq`qEM4n(?*>#BlfnwcCNk(tEjcgMe=$#s4m1f{G~w_!;ggLVW6lwyyX2 zZO$Latc%2jF_UP}Qx80*1ara6V_S7^z}Q{M0Rksa2vW?x(sR=Hxu7!Wd>i5FAQ2FP(##}`_xC8?);JlFh_gI9|qZRTLz0*q6p z!ziw!Vp;Cs4yQ#%^UBBc+D5Y{_m=2ZUi*uJOM~fF^qnn^fV!h1AGKsvzf1Re+-n(J z>Rs*e$aTVxvI@F0;b`m0$=2l+B_-?4Vcc;)3S5mu=brH$X_~a4B*lq9@&1~>bp{%D zQ%Xn%)V^szIq_f9qMUR4fe2DPp?4{ewVD)VMuBqpSq zM~7G)+*Lqn#TJF~VGO(}3c}xamg-f6^ZUA~6Dz$zP z@cBTh33appfdG*O=&C5EGeE!|LL?r3DP8{D_Q9jInb9H2QF*u^KIE>Q?wq=71WK|q zKu6RpOp7gbh2T8ovCkqRphlJpmjLjDLHw=nm>%L@82d*+;`}BSoF@As(6@5E`L5R) zhiy5#(-+5{zw{$fQUqw&%f+HcPNF2^-f6=T$L@Pn87M1}7=XbT2e-$crp@ zTVh7t!L>UoBt>r^A-@6izoNtm-#(Maz8HBcKL0sDe0vWhV)xbW*D`@2cU>}I9^wQh z^?&PI`hQ4!>#(TbtzDdy5&mQ?+mohM)^{nS!Yu)#~_J9sH0yGgsJ<}?n%>PfR z6&OmI$JQ2)Z5jhgw}tT=I>5q(f^Kx>3Eo03IcO`aPytBeEcbKtRtXT{OM7PggQEpd zk|;Qc6%e`i-wYZ4?^RxZz4hH2l;0HoFdG6XO3(2S2-LH-dC(VYh6@J~53k#CfwoZ3tgq)&{v zgG_Pp61eDMiSSOgqkZ4h(4{)ePhW=vDvz_wYqU&IsPftlm9CyT%n0PiWw3RgSUm; z_i~$tkbv%w0OcaBos&q))YcLpiTV6=yM~sb_8oU@C6uh&9+#iu$**iQf5>yW*LP7c z#Zl8V4GYP^j$JRWGY%H`o~{L_NCOYU<&=@(0Grv&^_?-Wv}bt|Ggwg#L@n-&1ZrJ{ zK#<~cC}t1TNmq*&gIPQ*g99&~Zr_W%{~0>%))nA9*;V})pT#0=p!dBf0N5m=x{w^) z4bb+0(hs69u-FS#%MqtTw6OcI5gx?R8Bo2s?#sJU;XRfEXY1=k)WUVocOl8{q0;v6 zMLrh@4L+$d|8(Mh6fy7sO4Lv9KqJIMNM$JWKa9V7l+*aEhj4Ld63|2;y>5p<3;U80 zXb^W4ATd@4;1(M@?VLJ^r0dXN z(kG^^Z{r+JfuWGgi}#skD`^Vhin|JKu-=DU3zHSflqhcoEVv3CP?85ZfnA zvCDwg#_<#unKEi^e5`lSK;hGk1{i+>2)>-#WBFWxV9B+W$vGmC-_+mN?x;UYYQatM zrU!C*Bs5Us8uhH0|2|mx)Qbj+=?x`m%sV=pSjlfpPHpTyQN-I1V~Sq)-QderGU%Fe z-?;f_%}%OrMh$XsC~)tzKGE~R9#0*6H!VHXe!73sq9+CR)EqB;-$6FnVTZScW|%J!%fiRT>tOI3ef@_EK53YZ6tfzRuNX=*3=;BXCHWxqC<=fkHQ z@{@jdX`A#NkSyO{MBTz;P3fW=M);OU4ABOBTN*q&~ zM$TkrDNIjvHDuwb&-O*mA&By{iS?}T+xx80xMCVP+nOhMKhm_A!2OL3yUoG1?+FNM z8{$((U6=eZHOH{ay&6fhj!gb;i<1v2Q);86h$p_==)ZaF3VQ&~VW&I}aLnj8be$+G zO6N^O0V&&kWZ!2YZp$6~SH$)?)V+dqM(dm&3SJkF&WfVFb2sHQ0_(t{(1SER`97;! zS@_Sp0S{ciI^PVo+~QGtIBw?Zx5lhZoY#%n<(!M zXQ}0&dFdeo=T3gh&o#lv&z_wvNn@+9hLbylp>JOS<9maKWF%LLS25i?jXOzU2m4;{ zTq({{mLl!F*Yr8xlRo>Jyt?)|{ieMI;`HQ|&RrI%C>hD!BMRv%rGIh(&`FzKS)MzI zQ|o7^Q&?}&*SJFoG07#QRL9`tFQzb$;1g`Dlg}R3IIbUkNN1ObmfWhxN9J6A(XST$;-E90EUWu_q|(7yXriLHJ=b_m8YEPGQE3*51HX5P@H_!2zh* z{CLDGRF61##EDEcZLD2O+iNGDBy`Y^xRR=K*fwk<@;sfv5f-`N*wj8 z4Y$)qV+aT)Qr>RR`{Qhu6b?+CZnzp&XdD})+h?~E!3{IC0K}m0is?E!dqn9c) z*(FIx^DAdbD}erYbIS&FAl5nDE+A%t7*B-IC{47E<7wjL?u~;0){}Z~5Kv5hZ)X6N zKa&}7Ct$yC2u{oGCofgyS|%R@iPLQJszxAG)hvTTV*L5PkuYab=PpU~p#Rwf>Iz_N zu??JM0XU_FI1c|&Rve!KBdv|~aPa9R_~Xc7q>ny;?>M_TAZW81!gWALH$w`|bUfd&=Cwz!K|0;hJ*XE}PGI)C(KN*fWC6%zJ}XKBpehiKa^BvfTUIn`sx$c}NU{MB*BcdD8u? zVZ53-iGUg2mLa|?D_`Wkv&iO!HfxG!n*>XoSx$@Ko z)+~8+t3-f*(sQ#`BWO={owCBcbN{1QQN_N!QTGgj;89j7um(DOW;p8k6)bG`P`SB9dkixu1lx?(r{vxouru zp*xk~e~sh2&4U_06M}|^eRY+eO|z#cpsU%{LRt=xT7@C`brt@fkynlB+<3S)(-3N} zJ)YRyPtmA5>a-sRx7MOB4R?A))w7Z0M+femm?GYs`iSrOQ;j_v>y_YnUZ8-4Fb9FI z1QMP*OuwC(rqJ1znhu#^A{H}$7TUeLTTnjxf(HwHzExo}{+qzpfnU=b-F9GtOf<`> z7i&*?cFY-YTi9~*TLWSaCDnnz zU67w6k4J})i>PP_kUmb4nlSX<8$eolm6w?}*F{TVEbEM~UHn!41eLh&3tDfnQvo*C zDP(mYVvq%`4{R?0nZ7j-lokj7TUxAP0)TOWzU%<_dPL|7FDe3y1#f8VzJp@_7a4>K z`ruoos{c!N1h}y@37i>rZ@@<0&(1#Dnao%Gb}o?z1sgB-*;iK4>gq<#E4B-z(>?qyIhsqq6Hm;Lb!w%sTufG-qZ9k?$0hqUW`KJ);-Hm4r! zRqD+@BHGXXSTG=kg*_W8A*VgsQVsHp?6)eN_^w1R|8o!5%U(fgs=~Zmt-CvHZ^NTnC#e4u{G9jSSQFbpfO$ zQsaejM7z$nhl&l7#FaqO(ei{`rk>(KAfzBLnnQqAtGR(!>~E)+fW^UpT4$MhEGbw| zH&y1G+EKplj6d~K^|C|yJ*j{#!}UJUpZ$1UbmriY68W*W@CPM(?Gf+JTuH18m{VN7 z`2TytL5F}&4j(s4Y?0o0reg&N6ymSt4SPf)w;=QVo@+SpFocsMMD^L37 zwZh*~rVSS*O16%EE{)OE9V)o?Jr;2xdIJzIu^$yNTRIkWou-x}FkTi){8urCOF+@& zpc2dL0yRY^fHlydi(j!VrQ8c{cPtROJ7Kq3u`?*+lmpIG@E!@`=OeggK&TVcDx4!EzO=8hTG<`K`o z$0TnSs(ik^Qc2~tbUZ`h8;5uZ>TwmC-Vc@m79}ctwfz&oq=j>F>|sq*+}Uh6-~MUk zB7pVu$jlEh$!F`P$AUWVVpvp1zS#gzq{%541$qc`&Rk>nj_d3OZKHqf7x;&o`ZmuS zfbFfdx_nW918|HiU-nZHQ*{6b(P$&taJ zsxs=3*s++VwLQOV>PkrX(~o<4FHQaN*%HGpQ^7?z)_?E?%7Dk@!LB>VmGRU6v${@xF+rO^*)+L47W;O}4e~bS)CwnV>AXcVK@2oC}NE zFPjz$>$3u%`6Bu;4CUEK+)G%q&>|v2>1~w}hS!|kOaIL=n(zAVZ)I0VXJA3(; zCB$&ab=6x}>n2=_mSBFa%M8EVi0S0Khc>J&6vGT72VIYtxQ|cT^|4?qTWk5v#`l5u z0a(wsOTz(3@%^*?_D|1yyy8@siQ#OKR$BmayN4zJTrLVM>DupNnTRR zS?_ceJBw_qCH1>2ezD4NqiPAWNyB>7rc|Sova=TaYTy=L^+;KNSEu-C_YPU&1mE15S2t$$bG!8ek~Q z=Jrlz^DZ+sOp&fx}>52;;-iPf^->&Ggy#I6}S41HYbzg^1`cNZcvzKlv zk|v}iWu4tZD{S-b2BZ)zF8lV!kl^s}DX?!BA1=Or@zxHr3bz^92Ea`<*5N9aMK7)Y z3u)uk#XShLo`?C~XMn!0$F|7h_NuOhA*^M#37jt^E#30MxIJbVC+LV7~N0qlj8JvKg(c<8rcW z(E_R&R+s)~8`9Vv=?SO>2K(~h*ahm7PcTkyUGROP9vLqHIR`DXfCo!Qgs09g(V)1aM+AZ&`bYd!+Anln*RcZ%L%ko%bg z=&Cq5;fCROxc5hHJvexvjH>iKaP?h+dS4inO(41yYMlWoK<5}*Xvjb?q66~gf_9=F z!oL)FE%0oByX!61Fl#AX1i2k)RQY(%1z``9c>k=NY-KFvnHx*hpWi&*pV*R}!?;mP zw#Hyq0!Bhf$t6;U4HVUoF&s3!bCJd#p zG2UnM6SqSzf7h-vYYuxxvI5Nx5v(WEL_RE5(8U16T~EP9Gw%Oybw!>eo$s04txce? zJBa{Y`w}8x(-G5I+Ir5e&FJ|F{oX`B3G`j`+TiGfohPmRp8vzq`OTCwk2?1AYXO2v z8R8c}r#~qNZj(xT@YVk7dY(HD-z|eEE5HA#(7GBdS`^kD^OykE8b)XPf?J9G=>n!W zY&atHCe6F+{=YzT^SUn29Dlx6Lh*Fgg?b997qS`E z7QhC^J?1_yeFayc?CoN=Z8LDsUwl5aO9P!M{5nFsT>Xl!JBHP7em*{0uR6o5)jE6# z`>IKJU3>$~k5{F`4-L*ez7mA2YwEvfQxn5eNgFQvdvVutw#gF@{D?mcb6ltbII9Sz&|BfTF;bfh8GQ!z;hx*bop$51;)COwK~Sf2+!oKn zojC%HB6qAL2He9;KF05p?2}`XrF@TKeOD$ybKrQ1J9}j3QktQ%y{FsZOtAQ*EW}(o z+b3Rj=X&5THW{C;oi1|Gy%ls{MUGra0oVAG@1o`vysyv{{q09QT)DiKBa7Qo4@8fD zSAN|>WCJ}U5!7WlzIk@i+$*RK%+98u*0vojC&c<_TVV&*)-S?=F+r|^_XTq3NtSR< z_+YuuYQ&Gz5X62!*~fm`{iOBJdr0QG*~&m=oz+qF=&Xj7-ct3vVMzOz4}k=jdHy#a z0=Nc2oq`#xP2%SOapRHrDHSW{HC14Y#Ea)6FRCDC@+xfWiw|W7aXZx5}s5 z2}BRO#BYu=#QO^z|2_*kNFo{DqyH{282!_DdNUDoDlB~#%58F_-jAl-7KXr zOoGwSQL68I_brBciwi05H2<7*+WX9LX;Kr{>w0fD(;+ycL>rCkfTPX9R|@a%b8>DM zB$vK8kMkHGJ@ReQZ)PLV=xEJuc56#ZN=CNo6!VpS!$A0l7@t-doMe%sDuAoJir?>R14>DH3s~W|R)?J@ zS$LT21V%%y)T0ND=^!!)e~U-;un<3em9?LA3a0a09F|CwYY9zg9YdBzZ!lQz)GLkZ zNEAW&)-5r>QF|$8yIC8f)&4JsOx!f4#P@0Gv0*Zvi%Q$Ok%Kq&cMc;Rilb zMl6t8yyJ7f3NWJt>az*i%KydOQpZRglEj{hass-T*dyhs=%n5_a8vD){&k#ez|@qw zf7LNEaCdLGHB}3oZ^A1Lp_CQiIE6S|iQ*to>JI28lJ(4vVZpsLknxyWztoYS7&=-0 z!t7Tx5=cO>znF}%z44u|nl+tw2Re541W!gDEeIRwQsT`{^zU7bZ}V9Y@^m*H$Z8<0 zA?eL{eVnE9SnS2;`-9;1%_>!^|8xqn~^r(os8mI zLjCuG5sDFHgSU|3k26SDNS<=NmIWy70ej_}V)6GTY*Mc#PZ;h>2`kirok~Geoj`|W zp>5Sm(RI@+qy)6YwpoF(cq9t1Wub%kp}#4zJ>?rs?;PR=UMOe@WIQr@#Q7Sh{L3sN zL`CC+JwNYkMDC_K`YFSn2JG3;E+fcR$F=xZjiFInH#0O3CM9q?YB!ep5@8E`1*Arl zCk5R>UY{5lu-XJ1#j?Z22}v-b1A7B8CC{~@e!J?tFWR2K&aq28J9@G~6URa%!OQnQR%k(>dT6F&dwMc$b43~?{MN=7VPhdiaGC^n&9Wh*Uo@i( zM9*?bcBmpb%y=&+1cYkkEs;HcGm04tOBAq} zXXyxbXIFhp)2lI%5SBLHN`O%)Z)O^1#N)l88W(fhate5c7tprEnb>+h4=jj$OjDvM zz-z5Q-G23=n%D3B>NX@u~EKi|7yp4s)S+%EIqw5fD|lSCIG9jD}b2JR>msh+}34TORVR zn)Hk`Y>Em3XfJRhK7pP`sZS%<@3Ud5RVB+ zT+hTJ36x&aygQd5=ZhN8KL)373~+ZY&kJ-zY_>OaMs8mb3!nAJGh&TKV;Smpk~ZJ? z9#{CT`5cc;RRif~E}wIEsvHhPW+=u7Fkrd zSMWI%EvCNXNC37etMK}8IQrwHism?zW&FR2mXpQ68Rsb76~xg+yW{^mU5GXegX%4_ht z4wf<*6yEWQ{fW!|>B9X^YhXcfCe@LcO%8N15=&i4iN%_ASs}^f7K81{v-+SXxT*2M z#6cMHY0mI5f5-vM4&#^+j{qgE;>9hXIp+QL<6`vGtGB!B42N$IHvnIwHcl#IBp#T_ zu&1beVF2mA>t$h=a5f3AUTNFA?;Hb4>ipe8awetFj8u=nr55T#nec;BWAeyCJbCJ9 z@)>oEm3St^@!f6mH2-JH&OV3>W^xKa%)eLhQb+u=(o(3U%N-!U2er~{qXTzmGPD21 zcd*W+hZuV$qD|0 zz?M~K_uKgxH3~WtgW%(ckXLr7tGc1)5wo5!p zWkVbKjQshc8AI;T2fkRanBrj!JZ2K<5ELS3%R<1$76H1^WG`N-905)Is(yx2d)Av9phbuF_&e16S zM#J=%;y~W7`!>!@j}<)LUvrSMNaXHqT}MLBYoN2zYxfVcwKw3yjBW+u^nX}70hyGq zLqXH`8kMT$v~aKDHmw}(BWd^OGGH#;di+T1TR{_V^r;X;Qw_e{8$4F>ALqRtZG7S` zrZ~a^Y>`P9w;)wF5GTFUS%BnD6cx9iEDn50+8)RN5lPT_V68)xl2Mkw_SP-0222Ac8&mI5@!a^J{Rc=+543y!63U#`h))&vKgfj3gr34lHEx|Kn z<>S+K;aYlZjMQ>>#~a|=l;oXS$=w?*@jw&!dVBycp!vph&Obbn?7etSv114C#OmMM zCiOQx8%7R+2MdMtDP&!O(hF~%hBy%H=TC2G8ay!I5cuvDaKeC7-UN>lb2sol*69Dj zb7BryYGY>szSYvb{s~~tv2bl5j%?73q@id4R>PV4u0-@LR2oWBn?B}<>~_I-+I zxc_7$Peb>gTmZ>EO;^wftpw~B1k>;($&b(Kn1o;U^R?a_d%&>w=~>;CXC3a4**7vh z0<$1GAn@%BJi>)?V5Y#s9Wk(U8I})JOp(tvSVvg2Hi;~bAvwZlKI08yryn`!;wOW! zL0yZgocwBTyDRD>vR zOz`D4P^;_^0E5`G)|+6+JO%{a4!O&^Jd^GX{)Bu|;HUglTR#ejkTu`+%s(>f4(RBz z0jZtD^k9Lp@ksJ>G#fZ!W9sEZy1UN{jL@e5i3Z0!Q}EDAkKW-}`uNP4VXs8^TLh+v zWxl2@Ed9|)Ilv@pymn*dk8x{oW3*4bv=Dq^G&laNYO&#XKFRs>*0TrrL11fMWQBs|Y;iROA3D_L(J-nK8 zwjnWiB?yR?z~IfD-TPB0DrZq_`(Y#%AkXIT1Ib#2!}}QI_$y$n4~2}J2g!=~b`CJG z+E9WrhSqa-U{3d^mac+1=-EEA)2AuxNNHoRe`*XED`W`#I9&vle{_lD9xZtDbv7Uj zHV$@e+wXWfuoMiPXD#O|6UBzxOXf=wgR0;NhCr*6$ppd4*#|bKOgW>DyCoJVA1cQ? z6v|qqNv@M4Q`+Vqzv&BUuNQeM+WWi%hsq$uz}F&{ zInFmA1OTq|V8EZZyAbW$6Ld#T1w)e+!X5K4V()r{6yt2ob0F$Qfd}B9eI6an2U&4H z6^aO;Rvvx3i($Gwr9wt9t?&mlqq4!<#H<`~<8ZF^K4t}*QV6zIfzKOQ;hm}v>IDhc z9hqDYpm+tO*=$!8T8T8T*IYhYpk9;)pE^^{ebNJf8oo^-pZEzz1)>{&{R?QXxHSq2*n)Fb#MXGScZ#STSg|s2b9s(mYmhqv8Bn#G z&?D}3UF&c%(1erf5Yh(hYG&5r?X%(FG0w^?fh7oI#{CLH$!=*o0XT;DPRNC*SqO%o z_BD5@<8pU@#j99llL_w3Z(kK9c9?IYlAX5nsp$6zbD*5wnrXruMe60XFLXS~`--=l zf(loQL7vK8Q=T&Vws@6bg``)cfM{*$nlkHn)UvdF0nO@8i5Ue0vU}C)7GK8P;R(?G4BwUux!q%K}>#_*uM~w5}J;We{)^TSTQr%sy^2u+ouyI?;@lD*?mj zAFy&6jnaurEsrzQNA0o*cXYWw?M^d|>gEp@jUi#XE|BnxZ;KNblco^z^n`|He7#Z zS#DT%Z2ZAgoVWUW=XM_;_F zw%lG{55GuG{?^LX!$Z&ZW(0aR+*)+0@ndKxiLGl;oW?#Y8R46RyeN`tPopTplI_kL!E=ou_a%?7!fi#~>VK2({I~+s~9{V!xd2IPh5P6{KOk z_Jl0LL1^bDgAnWkyUogad|4FBHY$VIyj?rYQ=h#Vlf_|rkC~;bt6U$B^`D=S!DS*n zyewnP121BrZx+JI!{wdjVnH*lSWew9a^S<6th~VgwH7%bxxVLc!EUtlVJnHK@XZs; zHQcQh7aWC|VWmWvM0;qkbq}wMHKR;DOPZyKou}G3{#AVSvO;S?*W*Ud885;vAdA^s|Y6^(~i zUg+9=q%g(*WS1E|D%Mhz9J z-Utl0cWnQ2b*p-LI2>2!xoit!81|KqH0{RRq#HrmL{X7I-q;Ux8aaV7yfe-4C&tSuko64CQ`A3!{qAV=1R2DZc;>v@v2AeKDw@K%9`cw*Ya=H26CX2%N9fY|2wr zHWI}30XRto31wCOM7V>BuH}zFz^&c{f4Ou2N;(B{(T$R=Qag9V6C?)S)umJ@CSI{p zoha_6xL#;{AdNxA4&@%LlbtT9)D89e+I2bh_&&k9Z+c%vM^Rl#-;8pfzX{%N*%rKc zaH1~;wE}7kCv7Y@2KC(7xm+1~w_7q;vC}0}ZAS2-xfW#&GHI*Cg{uk`%mkHSk}>~_ zE5!h|?y#i?XN)pp!o#^|Swf6|?Gou*5fP__-!yM^$7o7PxG3tMz?+uIibuY&nv&kt zFjuYQg7?6@m2SA<#KyV4$h@S{%~J0xZWPgg*MQz2%DdAsmcKDOB%ru#Gvk){_3HFZ z(lgrzwOx{{-;BFyWo(C4JBeZ4U*bKge8$RNQc#-Y!mZwENvX;f;=c%K(Q&Yk$Qn2q zwHc@98`K`&PBVPbT<)Q#?EZs|x^vEd@No8``6Z1QEf&3s-k~VRBD7g<;RHV{5LWbg zEV5t(*28iZc^e1KhF)lKo@pekRmv(4w}zodX%x+vzcKUKQTD@%E~MHcWN6!6NQvZm z4XgXhQJp*1_~fY*Y?No}BCRzX(>N_7UpglTZ7(eMloM_h1yQB5*&yJXTwGlEWBHx0 z{A({#O0A2i$|8mZ8;3W#yJL_dfw$bGWl{rRz)t*L^94Vh-{(E&b})8Ujgjhjv6UdC z1yVu6Z&b?MrmUE#v%vG1yOhs#QX(C?Z^c z>*j>oES%FN5E<30E7Hb#0?^am{P}rVy6)K>=+CX$so0tiNr5gyAMglPhWcy@`M}qC z>gPa8nNE=f9{+Aiu)bK1FUV0j1!DT?c$y}A)aN0`pA&hu!=LTaDg>@0a~Ax_w6RNg zAYn@Si_|WJy)DG88&$14WS+j3W>E2ab^K8`*aK#jxeObD+a7l_+v0AGBV6q*=@0sU zXn0VN!OMTQMG9}<$5AY0rcGD!1TtVP9QuPs@2~7^r?962Zzhr6o~dP3m6ua>2rd;e ztlm+!ACs59tr?9R=Hq;753GIe*O`*y^Z;JJb?G77T2tc*T=Crmvu*G#95dXlu~eK+ zhJo1Xl(+3YN-{;JvL2 z<;D&S$$ICK51BWKh`Zor!v-KV^gAsn{QcVsgxX=koGg4=ujth#IQ>=Ir@g)`Ug$pG zNj)A6%Kl>7L{}ZD!iu!3KJRUCM{PbUzj3`I{f)lzYLJVP%g5B zAioSBLLnp)e119EE##hQ?WPnU7j52w=o-*~pE+YtO}WD0<@+G>5G9nBF5U~X6DM|9 z?*96jt(Nd8!Oxxyj=yz@Yz}Ww{>CPZp$L~#*n(DR4DL8)STX)0Sm1i8xdu)!hXW4gQmu^)UVS$03*&t6ehTmzoxwHGOnQg?Rz&1aTQ5As`4~2Z zyUo$=tdq*zC0`ouS%II2J~2C4W|hGd>ejrYVS!hisyBB{I5`h~abz?$!EGbg=)S=M z%e7>6j_kEdlAA*!k&Fq=<2o|#RZ_SuwuHSE#fCU1;iluM=1M^@I11fT{t?X~=#?Wh zl}$mc=y&-iEN`FoWU|8ExO?W#_h2ECv1YxEpD@QO5m)964c0N1Wv*$pFg8g{kpJ;; zS%eD_BPm(w7#scYH$B3JLL#m8V?2!i`nu`C#Tq&sD++T2d?XfcG(c5!KjPP~hXbe$ zI$2w~<9_u95&vP{NvxjVuF6P$?Iu84nrn-4F;ZZI zp$H;eH_FrA4y_021Owf$p2tXf_!{#4cs?E8E~X z+U^@N4^E;kqD@T=vyUOe(e|FMLLj_6Cr&a=~F z{JeL~pSmx#kkyaly@zX}S+RL`VIC?CmF zXg8Zo7-PI=RZ%L-J;fXL`ZgxP+QO!5<>BA!K7xtT#j)n`;9H__oUt+@vCoL$POB)# z(J~)Fh85i22YpX$>4um@9oRaamPx{Qb^7Ru&Y1gQxZ<29vd$#;>tyft@&%3bT)Nk4 zno!sv!v92O5_V@UxpT*6C?ko;8nH}7iWfB9B@+n#{Ul1T5HZGAdCT7QpX>vl2Y7*VPwysM2A+pEGS zboUNlmvVF!;Zw*rvTb7mK~vvcixbpTRZfq0={~H!a;U)A{>3GGm!!9EipsmC;k%|K zukl|IQCkaEjiut{jaKY6@@3wL@SK>iS#{O%GVBtKp88fH8M;snwV=`3>jEIOx zXiF*1zxMKR5IMi8kgWxx`vTi(eZ9=hF@@B3+6*gnV|F_privJT!A|SJ90(7rbrc$( zxMgCH z8qKQSe;1X?C}Oyh-ONUc@cRk+Ed;-eP0iFRWbPJ%&p%@9(v1p}>t9y(DHaodDf_Mu z3!Hu%Ypg-bc)WP6WC)MQgYRpH6L}MfhTiV$Chz9)!JD)pqWNYhvr#^61eeB5#`{Td z=y3*G^iK03Qj@+|Z`{N1`@*xrqgEFl+)0gG!l}bcZ)F??id0@A3KmUbR+q-c$_({~ zUv(^p9vPF(n%R_3cD_g_lAj`pupVMr#9_#rd3sS}-D~*v#Nq1z+EP+#zagAne6Mnu zy4t~4W%dKC9nL)TbO(ha(*j(yUColfX@ucEr{v(>K||-kKN*;+kLXENMGO!y=Hw@h z^4_ath+*;60)VyZE!r%)^qAJCadBHu9HHb1W?$9_rk)@}apFKz+e`3+@$qqTVatQN z2;ud*?JE==Jc||X6MEuBo^7+rXM?b!sHO`IGFz8Q8L89l%MHDbBI*Hn-@jj4I}CFy z(Du8XiUJ0{Z?G555yZLvN4oj<#(41x?;Q~0+7yqh`>QZKlkQmGN!Uxpk;Uxslda=J zDSvvA1}bfW{!VFQ=d}XrWaDEHGkE}gf^KeD zQQ@yB$I8iLScYcGV7dsp1M)8UHF!_}a$=8mTwx3zEq(_>gk1X#b`9U-^uGV$bG1dW z6(`FZ!)~#<%a<39cvhD+YV*Cj+c1}(@w?dA{PbLC$gj&_lobmNYL~S42e~7YbZikoBiuMy)9kT>ML<#aCOG41NL$G?Q$Y^;n}7Y zaVm*L<53I@D}5_(x-)6}A0UK>L3*$r9t2kx~uf_}6pnacXuS)HbDaUU3 zaOAj%hrp_SNjT01`jwyFMx$>`-2c*Tlp3*1RykTNDumNZCFZ%2`!P&`P)cQ?xH0y} z8^zV0@6@CUZ{K{qj`LgR-i?(viUzIka-Qe6h0bx!drloAYqq}8-5Zlg)pqf3Hh~LXBd~X0YYm0>7dBj1`+o%Ciz<(Go?qg)S>NhknPy#Z5{_3$kj1=ZX9U@o zS={v=xy6i`Fm2VFADWL9J=RI`*Is)LSUt9S^0@a$X=Pc$Pfme{H!iDl$Ij1(e)x0Z znjE_c>>d(KnTK?TukJ@qUtP8@)4qao7J@5vZvS+&B5gCb(P4GS<}@Mp|HLFwX$;$( z1NXjgwk%a;J+4V;@Kt%vLKU7IWxhha>wZAsaI*%=8D7MUh zfrdH>3&FD2KyD|E1aYBob%_>)%$0Ci2;zp~*}S)eT0v{G%&c<~RB<~YXL(B4qr28A zXU^nN0MH)`UIpET{WDo8?RN46o$a^_(T5;QY6HuLq9I6uGAQIahZKe9Ee0l802`a~ zz6{g>U@$QB{?>Fez$)dqAw22^1y zl_>&~uXdtZX4RdUf4y=hZNrP}JYa7s;@PY_NUi~nSAXcRD}2<-MBmA8vdY{pR>1$L z(1LlCmm6~@Rac^bA?=-u6zzvM+}H5~0ulyT_`Q(@YU)2q=Z|;pc2Due@*00kIa}v) zLXT?MUSY@s412XU*3%x=UtkQIboX%p?-b_fj zd*0;mY4>V6w&50FeP!G}gk3F|A05cST;0ErNRAZyBXQr%Z(B!#y+~(V$9|$u@`CL& z*FH^__J`14B(_&{7ooA~(N?gJ{ssaoHBw}r^`h8&wwmgPW==Ks+N`6kr;RRfwwC$| z6SuD+SfNW0kj2Qbw(9&KgAg9!hck2w^mZU2(_=>G5sr4%p$p^6@vN2w?1jPbw4!F1-to_cL0)HnK zC@sGpekwGI2|WY8C8P~_+JuG453_`>+)LG}&v9czIOeUkNuSM8EUX!0tC_@{KN!AOK@5UwSOBkp3?R&T68N(H?(?+XE&{`kP;#ALiB$Ast zSUwGF_OIE;SUc^nGjz`T%>E>ig)R9W+t+bmXH&3bwMyvBg0JNqP%-mFwJ$WfVPLxEfcRY?rqw z8~^y#98O2m5}agZ67fbcz)6#v=G4_#iVu=OEbw9f@Vx|c6=0ym8?UPODC7NxV1~M` zV3)Z)u1s`F8;gAhFGup)quWsnpTo+#kT><#nC#RxY^pN#(A{^O%MP+>u&qpPKgQ4MhdwUZM)aSLvJc%yBM5 z2PcIpPt6D% zY=jfFQl*j}anq9pPwehS)SRptw^Jao_+rkBxw{7k?Za)~(|cb_&v_{p>%K@vDc_A( zj~o1+-YP>g8&j%=6|D)>|1W(sMo)Hkf#V#Dd4WR%6g^hBDf!C43D zc^qpmO1AizB=JVSU2su#rAXV~{mDt@eK#ZOHNn)Dgkb*K+|Ys=c315s45lr$v)fl} zyQW>`Fyqg133u0s`)Vr7R!yg9w4~BkOaiBKiF36vTd`-6=3QA~4h}8W!J$;vPhraG z`JO68Ph+a8#I_}#!!~OlBe%deswS}?2dsLS$t!)^KX+CW2gvMpx}1lX|1Nrx<`AQ( zo;oChf$TB<0Otqm`YW^`6MdJdxEb^7#m^156AC=9xnHZQEG=`02N0l|Rag52F@#<;Wq%Iu{P>1D(YdEJH9o!3$m?nG?AH}7r=uu<$ zW6(gDXW@}TUFxs&zW2&4%~zfaKHMBH(=4o1tYXYmLuWqXHCRn`u#UuH_L2;=Koc^u<2qe_`RRmmo~k5AA?`9tN#2iq5E zt!I90S4F4Ew&tJLc|6=&SVOyxvtOB;bJ|B2i6gso1!{pI2g;V=9Mr&h#%sv)W)oZR-3+Gf#*f;W>>N6`Ln)6U4O7oF|H1Hh>1HW;|ssSz?FU2@*Krh)!xEjNy|rBq5Rpv2tmQ6%~x4?!*F+p$76Ij*(5b<`S1nmF8z1i5o@}pVWV_#oOpX*A_lL{+~uN>0Zka?Bdjk{U0LV zEh2UM)LoJLiyZ=R#%Gu+IoW)ps$PfwJNL2_4nlPXCz*6Q4wi&MWOC$UCcg*NlM(9` z8n7$Z^|IBDIVDZfKa+NYJs}vC(S9_1cbygcj^D)TsRl=BOwVK?oW4OTB?lF&42`44)r7{*t4^2vgY`Wh-8_szc zH4By*UMLe9&$)Gg%E@M zWpuysUtk<`UYDLrLZNph-Tr_VF4>p7He6;Mi-9+N+#>?v2JTg<4s~#)ezdCj&PcON z6T{+6#QF<3(dI2pKKUXlJ6y_0cdu2R&_ff~YbdPVO!WUF>@B0B{J$^I8HN%;P`XDz zlvWz0K|m!GkS=Lyq6v z_TFde6VDWT6Y1ZL-(0TAmc^h?z4K&=2^tZo0Z{|_`U{lX?h%;N?eeShnI+C`5(dZ? z=OrLO58+A#>21u|?RPULg9z8tKwZxhW^0)P2^)~N$8)2Be(Ih36XS3tCgu3XI<4H# z>IE-^Bf^bYS^m6x3fPgKJE0p?jtzP-@uokNK5fLVgon`OFWjUUZtl6$nO+X9yn82v zYFzZrt9GlNY?g=ALC{|XzZ&Nd-ySxp@4@a$jK_@H*a_OOSDGP*dm3>oih1vd*Y zI5=QcxjV6hd)xOzA$9ehR6g*u0SZ}J=wRPQg{qacaC`6}=9+fh(fG%WEPwx^H+c2m zU~|40H5jFOK)AD@eDd`oZ75H7dvu@bm7|b4t-;G$rK6~r zD9TZAwJb1+1KBRb*kpvP9eBBQE*C4alThOz?DGloe2dKa&*fANi{4|LCvET@6PIeT z#E_P^dy|AcH6e>zx8$p{6`lQYl9-S%y_yJ{U1IzB5a#Eo9OdaLwk|e^nU$qiQ}ty za|biz^}ATWvtR$+M`@vi;e{R6uINXpK|Top?cI!6^f6d!4|cd;9&&sJ0n^;y02FkCtV4)_1U8St)Kj>?L&o_ z!NXRq?F%^WU%oJ$;beY3zL9BvUEcw;uHg)iJ(slV-qi{l1Dh>cDM7_1jyn5!0}e(? z39!P{$+gLS7G4jij#gK&M1tJ1Mn?m_74jdA2qZ+2?Ka;%yT0}gsL&=IZg&de$yf}+ z_${y+lhX5&9nxE<*##+G)Or%?{DS;tHpV)*+v#h0k#|CbSWI$75)R9da0sBDrg%MUE{%n_js|SbDrGMgYs6d8;d%>m?jlG=Bw-76AsvZML3ZP zZGc6p>*^ZEBH2`ftOg(OZ}6U57i+cyUDSi$HYI~oLQ)A3#{(}fZXqF-I4c<*4x^!&BAHeyht?@3-@=Qs-Aj#D3ut);sdp0 z?lnkDE3cIv{yFb16MXZs9kok;eZz#{+ndoINnFY%45DoQ)yYCj!lROjy!4?p=dL%M zV*{oc$^%X__>I_Alyk%gr#ETe!Et)b`w*!D@3h zF){I^&dVul8}f4M%sD#ef}fX?JXqkip?zXJ=c|%r13u38f4&!0PF7iDkQN$g1lQKv zB`%0o&NKw5I4qr?I+d|u{_2NQg))kH&$sWNZxnO^sb@Cyk->{SS9uG*O^M~1RWs%& ze$6#nS)H*>0<|Zf3{tz3Q)UEulD8|2G&fiOx8%W_SIsl+Q{zb`}cZql-ZUYW!rX$SCj< zh`Z*@D14Ftb~^Q2`Oo|TE>kO^r-H-epz}>2{J5_ByKo1e%;^u4PiD+yLtWoux!*_+ z#Mr%!p2^+IZ$Js>9Sr{#w3RBB9oZ^K`$|c++oHL8d-s0i^}!jYY zC!jaEuR&wDl&M0GvzXw=e~+`%&P0&F*<`QdiI+UCKu+U?C})j7)8P@ke;B0X(MT5; zKjmB7HBCOzwTt6W;$QTdp8fsDb0EysmNjZUwdmI z=L_4Z0K^Tl7q6pNG7O8YcqpcoGZwvcbf$eE>j>K%*}(suk274BM0jvc_zMn?Ah^RJ) zAf-|-#@82$Mf8)T^oF>wxdBct&w5yBsKv`q53%OhFz)gC7fW0qx`%NgM439(j?bC` z9+ua5T^#rCHuMxzv^k$_Pg7I<#K{`KzlSq|e=+K*c9xmDo;1vAQbtZ7?^~8_Pa90I zpf1=DQBxw1I4y-z)?WU@L5vrR1dQ z{3D1pT$@2Ih8ff%wrE+%K3D5+*H|Ze?)npUSzjEl&G7SxeD~!pbQz{W*}X5ovLbgT z$%OE)lL!_cf4IT`Vx5m42&T#oCT?J2;$rD11+oC{V6<7b=MOLqN2%+3MZ>))B;0!9 zS^HnWMc%i~e8ds;U@U0^abD$_=Oy-Nyx7?DU>A7%#hbJ+v5S01ZI-?3+&N}$?g7N4 zp0YUbT^0*ERGmLp!d=W|1w@V@Rb%tjtyaOtU-$@Ap8wW%uB?1Rb603qqBhC}%th!=I)^o;U>80iqyf4M zdNf>YrEKxXAu!A927Tu0v)vZohw5DGNlKxcy@Fttm5aNI-h~7n>)V}Z0k6#u3(XhX2$Q{JvTKqYl+JG zlAELo?NiTPs6zUcW5)^#5PK-?$Kj!L1HnLQC$o)z;Su z2QU#iX^T)sV&W)^sccm(hJh@kZsQ7W((O-eeBW#Qt#;zqXrXKt@ho)Z2ri8Q9M2|; zk_OZqy*GT;?fOZvTNhbeV&dCkHzP4~m;~#v47Ab`x=E=0*|IPU)4=^Q)anG8TmByZ zc!1*Aw;H=1k;r^!++#UtLO^($d>zSX)3d2LzTvoIr(+Ex@=i72M(&K)>)JG2IXk%% z+`9EVLuYh_v9c`?mCAzgiYVQ-f%%m`-0NYYhNaPieoJ^ALEC$gD@OXWkJwPRvp+FT zT&DlLph>WHDTyNv13!FNifOpa@GdvuKTk*ysTG5}&L)X?9C~0OmQT9_8)&Ojmk!(r z%yA(X;C|ZqiD&GsQqr-+k>Kw)FUF)URt5UpiGt#NiHb z+_-^+04(U8GfGqM+q-aaJO8==YA~1IPB7$bWnZAXOpwbH>h5^oRsRM;D<+T%1}Z^2 z-wHd8(B>rX8P-=7!0NcK8uZ~e$@(2gLtf6ywy((lrFI%+UP62>&{sm%Wu^QCzj@q> zm$PIHw&ggNL!D`5_3}S?4fqm8QX?<))Bhd)^oy~fpZ=o%@6!*I39&AMkGAN=@T96j z506YpuVs$kiccfdc;db>MY6=j$A4`&?L$@6UZ39%_yc}*89GS0R1M|cI%S8}h%7ID=x!E-``SAKWL%~((6aaT)e!mJ~;v6IIMj#t|u}pV5W%%9NiL*y^;u6_9 zh7U`zhr|&C##Ql2anWmWZ>vN_@3n^|%P70pL&u)*WslHY(H`T}jMcT-^Tx`s#(jwx zcva=NmsWdpJVjL~8R1OKCH2BV&3&rWuPn8{BXP`9Y{gW0L?btTi1A(U(VQU0pr{doT8zwE}ZICt$(FYw1y>@r6wt`M@!> zfstRipEU2LCm}-Ig`#VGJT`P?p*4tGL`31^^(cEBU)9agyQ0l-4Jz?rkUXdkfbiYL z#YM|OdVT;XAf&iy5RAC_nz|=DwJIUhB{Heh`ZE*?H&ypFDoe2tP5po{hN z?)A8l{+F6=t)Z1T?>#|nP@5p!${3J_>*|dzy@J%R z6uOmA+>s$QG~uj-H&SWJ+r(XAT0NS@G%-MJKyE-lnbvgRB^GW_UPzeR!%4>PR zZ-Nai@NFv1KncexqN^gC+7k4HHceeqc_0u@z=7@to`GwpPP=wQ3WO4$Lg5eFU=g_PKkA&_6 z_gF5fkA2NFFhQz|XJn|u3 zi$RJB5i>v8EKV|tnW88^-474ZO;<&(IRr?)V*Zi&XYy!czjwgp&q7AfyRGv|Q8D!g zvB?ftacp0hs1!a^r0Xh}NqmBMhFO%FY!YZ(RMmfLF|zNmOYSjg4dCF{HJ5Ntm?+xz zk0<*zcGYUdeTP&jt%G6bamW>R6YFr>rB{j;$HorsHk29@A67}{Bc2gu-)UAdI2IG- zS+5j{%ar2v2+GTy{pBYLsK%o9_BP%bfHmD=R5CyUcY&rMve&q!=;}bY46IuIw+jTp z>&`rR35UXhgFEWIE{wr87|#j9Yizt8Qsh1Hg0-Iw0D1T=u6Z7~IOI|x7$*OI)%FUn z@tQF4w)rg_uJ9x3hDC={nXZ}8h78u|&-Dd&DIm8(<_f9XDhJx$ZJ4<)&J>;T;Eyf? znI!Nik3Lv-WyJCvuPkXyQUMy#PZ)yTA5T;~2|v%7;9|G*J$%8|fo9LifXMv+#KLEw z8Ql2?aDY|-Xs#U;_5W3Y8rwIpNIdRi%W5>la;HqMmNVqQVy!g$0E17;@wKJV+DHPh~Z%xpM{-wy@DQeGZ-_;JQ!(2E%0 zctPWP$|?|Cydem$Ru0659?ZYETRz~umRG8FI(IRwqSSe@(@=oZsczA`7XV+bRb|bW zqo!y#3KL-t6W;%bW|Ox9bkk(GXfO-)ZRX&OMMmwsQapG`1wu%sA#ba&zCc^3!(g&4u)JS91?ere0OQrUqY`j%^ z)tWR9;?G#(Tk9xOMm(M_^Ym*|bd45ywIARuZiHN29$!11^TN5thPtQ9Q@nW&(c8x) zad9YYXbR^#Uo)F=0d_u_Gjo%$mMr9B<;Z8#RytbBfo^e^-`?UjQx)pKq06paVfFRe zGg&bDvns2g-HsdsU6d<(T7)TILay_4FqoLln9&_WPea93Orq3?WV4k&&Ae>6(<+rU ztjw7-iL-xR$3w>9N6sdB zWt>RcTno$kI!dAj&PUmnYUi%qo6sttp}07pVq%QxSv5*2P&!EijCR(R_xwR}jK_`$ zQ$Skh`Mm+RSd!3(#yR*ZyC%GJi6k{<5Q6|1r@W>u4s^zSBVUGhJLJ3y^Pq4r*=tmL&pZ1vQxhnbcMA^!W?$>?|BG#B?PkRauFJuK8lBcd{#YN_f zFKZ`)tL*&7Pr{;qO%_)Yl=`1I)tW)G8b||WDv^FuXU{E6#A@bvZsOg#@g|>P?!#3* zyQ`A+*rsCx-Vo;$E|RJ&O|6L(SI^SNS9w84n#lDM=o^8!#t_eM$EZ|jT{YE6Rxw8@S` zFkehrz5ZE#+mj?sg5jmSAFYGhjv9ISZJmLKT5o*Xgv>8!9iQkwnCdfo znY+8edK$fDIp{N^_q~-*ZBWd7%8J~49Hx4bdG5jQjIn8`8{JtV~yj@85Wlr`R zA&ePP?Yw%NNZ0|rX~iKhwjhBxj(=m_Bm>?9IUD#5FpQ?Voh2)rodZT@OP2v`R0fN~ zYdq(k8EVZK>eLFEgA49SkRjIWe`x{0TVi$%8olcj{YL(XW5b#smN?%Y%b0p64Lp5Gk7?M^lV|rM*>`Rkj;1* zOFZVl6vutlo+Jt8K=)F8pg?McL#3I1K#e;-LpI`V}V~$H-vVwxf^pcX86A;$=r<~v1;v5k5V!e&7#4;(csPU~3zK&6-|%Ge0e@uUeIOGcA_ zW=AzPPZ2+$62zH`0$bwDs3YpUrP;DkAMgF8XH~9y3!l&4k6pM>N_a7Cc+p6xleOPg z&EBoA0bvj_)Dm{mo&{23W_CTovLyGi*W+Y6-*R~3siyvu zDC4t9{#?Q-^McjqmH|T7;Bv~no!Wy?ojP}?=3b$;J#bD)htBKp6&Pkp@;2{2Y25Fq z#!7Jlk^*FiQfC2S153MN(pQxqik;x{B_Fj2(TENw*C%6u&ts+2K890~kL3q#d}<+n z7WHb<0qatD)Jk|6b`bIL+J?J7gDJVoQf);L{@Ybj9~Mj<^7P*Apy&F`8R1pesayU8 zc-{46qJaX_E8`z_Q%nC>DyjIESJB170&s#)S(?I3;SNy0@y2HXS$$k} zhmp13OIh;0Lfq8*^a@i3Ok zdLe)R3CY5Q;Spxi!C^Q>{L~C#{Tl<6hCJ^_oJr(cQ)BhC+Xpo(!%V&i`iSbK;lW+IWSY_C#|)j1dmd-mXU_#NA#AA0DZnL0t+=(%$tR z(DZh5G#%%ets4r|i*>W3zvbY6x1<$X^BV-9;)GAVhY6CO*8I6}29JEfluevNsFBn1 z@AE$B;Nn1zof5w2{o&7ASn6e#x^G{9TBRRt-@0 zCcB*XO<5XS_WvDDFK)q$Eys{&yv2!Yjg!>!P!A%=gg*4jYWNOWdd2PKN84}!(PV~E@0Y+!zbycHz+Ge6VDxID#;nh8G9O=keq2M9 zMqQ<)>+B|ZhAL~9$4&!RgXi8;q02UHZk4>wqm3xMG{Qqd*3E4}$kO7Su~`w+{cjep zo|zSko^nJ=Vy{T6^5nt3C}a#q_N3oS=vilskh36jHO|G6v*n&huo~MFEFKJ!#?qW^ zDv9qNcAfTqS%PYFfE?`An&#rL2g&y*vGKJx<~15K#y@+qZuSX#cw?4}N(DY{io`k1 zIUjp!;XQh8QI@0mr_1%ri+B#w3CriL3w~Bpp&Ji)!`Q_UYm0kXz4UXFs@&NJ0UOg) z+|Fa^+oQ%^UlsP}XRlK{4eJh>l+mS$!nEaeS;Vo~F4UVz) z(n3IxGV+VI^MtpYOme)nOM577Nd&sP)v>7~q4(tS!{w?hR|l9bjNRSUe!HvQ$rk<8 zLbS_}Ex{G6n54@3I-t3zp()eQ95$VCWRR) zuAhQ+jQvB6r+l4~$Y(xt^vfEZobCNn0JikZ0zZd2u53YX@1A!R4%1W|$qH^1^P+U5i zhK7dZ{h4{*d}hAR7^Kb6|2;+S7`G5##zb*E{&dCs9|x`jal7?xdH+Oo-x z+$1mk8vy&AP>BN5>Hlf|6puCkk6(WexIt%v(JfP~JQR&@u|0DDFqZjhe+Ps}g^cXX zUzgc`zV7fd8aO7uMR&CkYd#=QoeD0eP~xJ)G{+8#u>K86yA4hY)M5{x>HmYYt6-5@VL;<3j;++RHvLT2lT=~*fI%u=sTx{N$OHm zHOUdK6Pqi?pAb1wm7`PX_)O2^>f_~Z0Qpi+#Z1J6p~S+cV5TUyPcp>uZ|JZLa{rWZ z42Rk?MtQQvDdY0Tbgd~N4%bvA!`-MJ*7;6{l)H0@=O+E=yT4!`)icQ>BJ*`agJi;y z2J3Aqo8F6zq4**yBgpStb7bdc4nkNXPTy|Bx)!MpwRzeuPWV!|4b+GsfIoVSiPy;2 z6K*Tb^J0w37aHD5SICv}22ow<^9GqUQM4qC6OOL|E~8*_T2p5z(|N1mEz_XelW8B&Go3*v^#VdX!YCE8+;m* zRTVOp1R_QnG0Nq-ri{8P28%ZX3cI?l0`82Z=pdzYTEfy(Iar47Ra9?P6C| zm%FlJ(GKLCEW%s^@3Ffe=7e%HtH#`&jK!FvhU_1#HeZ2dVwlelj%uc4j!uv{sFp*koYD9wWZt zqE}=;HE<_tYpVR$Hf;?rwHIg9tNi%Ws}EZi^up?C_U3e?2dGRqq^)J?3pQ&}6MjG4 zak+^)_DoEgfX_!9j}HXAZ&nB|kTy>^(zL85iZeLmW-sf5go-7|IrXH)V+Juc&cHnz zX5eM9dXQJV4J6+U+nMia*Y5zcZ^{ei$mahP=HDvKO-FCJ$m9PfOJK++v~llMD(d&D zIMDu_{A=3{CfYdW~Qi42vR-+R_uD0`PTH z2r(o#ROYUO${0p8#Cd2f-88zLCiQ{ij#Mw1XKUG->T@0=%gnbua$I<~rKBLI*x^S! zP8%AYq*rq|2q)<9B3+q9SrHu#d0Y|nI^M$~(-MP$B%}>LKqQ-7*gzgam4{_iNh|L4Ye# z&UREXZO@i^&LEr9YPuTO6O+TH4P;92MSkN?>Q_5zKF=`hYJ|R+;2h<$60jn|mmU^K zspu@6&Ph=`(Ak`-;Nq3@xjeNmTXPe+y_(AGRrL)yksT-0Y5cC(WW%}2*-KgPa)fOk z9IVsk)T?J6;=y{B?hyHWrDabV>X>JZ*?`z;#4c=agvd7rr`LZygc&y;7vdOjt#+B* zOYDq&TpbAiUUwtq%^O$C7k}PqmQ=B66f{Y6KQ4#zt4dw2NFDY-1+8dvZ4dbP8AaN* z-1Qg@J^-&5F6`o2nN}1KO&2tg74NyT>e~BlbD~b0&T|g7pE~QUv0Z(jI3di>3Of^>CchHII#{&1G=;m@xEIFA z%gbB5B-wm=%g^l;sxwTpY-Gm!Rh!B1xCux))^>Jw4mspD7^Pyc);Lx}#i65LwI^)C z{UQ9}p9pk}o;(W|9R}+arySsSaC-b`bM%8c@L2F)lDvcbt0Df=9f7n0y={93bX5P| zEzGPu{YTR=i&l4>4el_aDIXg}{8&^4i){BA&3Ru!{s-SxkDU_pieNyDS9CMA7tNs8 z5_LVe7gGP*ctNMxKzS-$q?Wvd~ zoQ+@>->(ix_rk527aSyKz{`T!agg1_>)9T!|2{w??wqdh!KhQb*}m@P_|XA*!7pG# zS!(cF)ZV`?B7S%L^XaF1DuZGVnTp z&zkOQ9X4)1Dc`E|IN`)t^JfFR!40gMkSjOk+}HP_6yF{nS&T%Ov)}dd^5@om&>7~l z&vUkoI<5cK;P^U6QFq}}scCkY^rABR>y{(=m$%376~|A_;l!yve^-@vXyS10u(8}@ zalg=O6KBFotvIgqh9uGLI5v_i{6p-tb{zq;yS7Olu)#5f6g>G%Y^8@Dev>>_WaYsr z6xTUwSG;ck+j()4Oc?)0+{Fv>;Uv{PA%O1Wt?)|oA&{u2o@a;1A@lNws zM&$J^B6=@guXj{UEd5HbKqIl{vZtU)FFX##KR)Twb(!G|yX=)+f)W0{U*obB&XGV= z*fegYYgI@{eAuFq;b!grP8k`dBqws`wRKO@+B04%+nh4j{Mg{b=H}+ez7>D2^vw8i z9=ne?2ezpvDdjcbv|%~rTEdu*L;nrLA#QR1?jOL{X;9l`5?b$hR!kC_{glGCLm0NCYWfLIWONI*S%dM2z%rikX6-QPb}8jj{xQNTLU-~3@vE)P-|@jG z%&X9K7K$9oawEK7w|9dw`CDX_;WNlS>){T=hSO7q1r|B_piw@yI+gs7u1H}!6zzUMpO4lp zI$`*lv2uwQ;o(Ux^5$TvCBHk*vRkF+8~#HO2iL=CooX$<^#H^JtU|)+Cfb_+u91T+ zt(*M1oH@0ohfLD}L=IHX9;TWrzH{t7>Jp6O@cshhy$ru~<5GU)PosJcrr%aI0=EgXz9rtkErQ-UkBrL&?y>XbvbTCkoEa z&Zf2++s?>WTLH(Twacg0y~eO-&2N=9emrkF!5G!iM~9Z^A2iK4hJn8R3iNOJEP8tg6?6J_FL(W(3{*5PEStjuR&tUK;|WWatpazM`6HS2>4+@Ed$ z=4qdW(n>w)53&L;n6M3Iqwu&ZJ)C+3ld;$no_F;(ri2pqL9@p4_VJ?oq}EoY7%e>* z7i)46UKnem(0qP~BW!g2=oJh>^^%ryh9EqQzn>01sa%yc$6Be3wPv44k;0q3h@twK z{Sft=z8KcTE>3 zuEFw7*mr&A#m95nj$~sHX3n={?&^TN^gA4bmiBeaRVgP1CPDkgau}Rsd4C8ZjD9e8 zRx%QbxW;%Mul02_!7fbf3iZz~-c52fo@9<+{yrV)6K@Dl9n%83i+D=9b4~FwN-aH$ z7loEj#{dLVW-5d>%wwyMi; zrpUKtC)LuV?SsKIgGr( zjhtLejoW&29AB-cf1smef&6}K1962-u^ona{lY;NZOiu)2-E0lGeZJ%C)VDyuQC?@ zAP>S~Az3CVl=Tl?u@Jw5DK(G+e|38-8z{~|v?e^Fnr*7WIzm=-|L)niEPX`HPNkI0 z2W%2=*@WAeu6yl*d_pXX#ET(bPhmvESNO*{!i8tpE(KI?#GbV*QcZ}m%h~$djtiAQ z2{x&$Olkyi`&mzAa!;mjl5_qJkGKY6P4J@o6P(;vV2QSvZ>+sp;V%SLTIhQ}O!sd( z$A3!IGUYGEO#Cm5dElV<&!l@FW)h=k^CKPQd3Hkd59@Q;)+~yaFt7C5&;jqVO_FY? zH3!fkdvc7JP5rx4|58i_i@<*1wkrfeJ}T9w)uO;e++!ZJcQ`45P*b5^f+Kn?2p$ao zEV0`SfUYT&|H=9$=A-AU0EsV>{t0R3XLIq7$-9~2jwQx;nTp;%&zWY+&6HE;3R6l2Yb~WVAhV^$FmvBGqw-rA&moIsBfAI#E zWQ0>)#A~XTmP`x)EqbH}S7Rh1loXuJF4+>Fukw98;g4JU&g@Z{tV_4cO~*`J`lAUN zu0Y*rldtxwa`b0mC0W0yxO;*Zje*s0pLvKIg86g2hs|RBvHQ(tm|Cj?1#yawc!4>6 zKig-O+#8sot@6uOu#~Cbv8;JBpOYrN+Dyv4D<`6``+PNC*&1Ys^E;oOr>aKgjumue zbg7$o8cMRhh7B>YiDb>1r*k@uMOT}(z2s1O!ATn-OMgY{cFvRhRVr{hQhpLs5h7>1 zt9f(qf~fB2q4(Q!(wFSw?s;sGMSc&D+@r8++_Z;}A5*acT!#J8+r~zb$7L#SkF47o z@P1d5wQfPiC7KecyyXuSKmFIuU=DY;yB48RcyZptqCaX`{}W7T;x- z!yU!q{guvR(OmchGew+$81O*9%{MtJWgQIgu@3hh?$+xP;>N#D zx(I28OtGK<%D8x%7ZCGQ1>a=~YX-F@ShS4W{5bQnU zb~5eq2e^A?K1vxR|8MsL!nCJ=CxTaw3*!>$u#Ik_Q*@G(|2EUVk~jDcfRq4{_I~d7 zx#jVe{3Eb%!)x$19R1Oh&>J$L4@YR~XTx4?{QiG4LO}oH4Jugp^!GnIlm9mCGzN-Y zzA1V|KBe%zC(;^fh=_!!Xq(KGowV@93sKrR3nS<3Ypjm5EK?0HrM<+%K1$va1iNfG z$-A2$J6~=JU?V1tGYc$b%zL`Gq35A5^nLVpV7okk5j-8vyIfjn_)>rxneCVtnE9ew zt<+X-6(h&a;t){WvH-C#!YfX*HiqE9gOWR*6Sxi`HXywUrf&n@4BQuAq9{qetz)ll zd=h$hQ5bI6Sj8MwiW582ho4Wm<%OWF)~ux4&FRFo=6(;Wd>U0rPm`}Da3?~VdjfGz ziZ~ID(iEoRn<%>SUZ65I!S>9V$Quw4+eIV_Bs!R=L3d%3d~uzx8>I2^*mi9jwP5QO zZSFmGVWMsFUoCp9tchn5;v}P(r^PM2hGO$6jOw?P;f75!(qtz~P7J2dOUs`~vQC%2{RXpsh$>EeT z+8whx!RgbZdEa_N1*6{@KSG3be+mM&w(-v>|E7|5U81$dg+vX12cj;M);vi*lPONl zqS4opm19KfwfFTwa#zNS7-K6()w@33`B-bv&EzK@Y9BrX{^`6gc5k&}ari5r$CKj> zs|sEIv)1yU^FlXFc7zOt!1)+ndWALI9P9j{px}5c_0Zed87e3-*{!EzUop1c_J|Tv zbCSIWNh$XIiPdPc zPvLCl%I#B(^8AxSC;qtYEBW2{=^2&$q7?(##*3#wk_x8eAsz?NFpMzNEBUg8`0T&s z2y*(F4KpP^$Lscbw@|J60*jKG@@pWStGMW1QP?k>?FRjFYr1IppTYX6KGRX_lh~6X z;zrXoU(QcXD11CZKejN&R%9V1sErMa?qU|{QpcvKOtr?B?*vNBx(tvVGf{uUK$ZUi z*PnB0!I4f7W>VJQ#5{TAU!dX}4T7w%o@f2?P=-eQNcPqeyFf$6P#Pi0XaAm~|IOZV z{NzW=XIjazDkVTabY0vY(DBdH-D??n%Zg9#7s&!gy{_;?sQgnLF%Ge9K`7(_%a)B}rDM>!|wgc*e1|_N(qyB*`y6 z5W$Xm>3vzEZ=trXgVdLpeBMLcPTFaFLE?xtJd?Z=GoLDfB^*I35*Pg9aTM8)Wr~#P zK6pWjC+~v)KH{}V9ZsY?_1y13?JN9|Pl9vm^r}Y^TEXOvOa>mt8ES#7jgDS3n2awC zXs_h%k?gnbbR-dE>CL|sKRBwEjKQmGH*yz2=!%y-pu&XH325e6Gh5yq+7Kb2u)PTO zp7#dB?EE)l?z_MRdvq{d`7~#th!{S&)N7hP;`ZDZRXWiV zRenFgF$vum!&Ep3ox7k8iZj6Izei`^n%(=X=poz1$xejN@kJlFpK)0(IFcqKRJ3;!c1V_a(n31sFwBA@H)Tv3=2H4CRVnpl|5332BZ}`M@_glQYho(dCbxEW z#+UF)C?!fjfEZpnp_=x@89H*bliOW1l9OB%E$Sb_h!E7O; z@(3k!F_OcGj{R_a%;r@k|NYi+h~(2HG1MRZP8ZbnjtNpVLY1E@sU=-Cpy$mM^%I%G z8#+(81>p%Yvc`a$0yOx8h*;mvd=AZiofC);{mTSfkO@HN*av$bx&n2(I5yk#6n!EL zajeN4yryD_>B6SMf!o4DPN7e%<^r%E?(9%&_2I0MI*#2>W1vfOja4ANYURrMaq+=& zG#H!Zl{vk3HsO$Ee@K?}qCISXYUSuhdHO}fMr__;rD8jK+R5;WaNa$o%*-Dq@7$G_ zKVuPK&R6o;i(r;zt%?TWAC*0SX8I$u%%#R<`-_yz^gVj7rHVhP7dw%usS=blt78Vt z;}`OKC*Hc$2RnE{vur7?J>xc_$>aof2Cytg0|gKjGEzQ8N{tB#e``#Q)yQfXI1J z*=$|^fy)l+bIqy$;N>2n4+(osKybS$^8VVvq0R3f5KUNaRyf**eu=cj-amea9=Oli z5_pbd|Jm;T>m8DpfhL>PfzarGYC8l6DteTy#PP&XJk`#bANG?Bdm7|CKM1D_N&E|> zoi%-|+pQ8#t3Vz!cCC3t=b6=^sO($2S9_4^`*+SgGIXMI$J*~j_x_r2SXuJ%1mIc! zdRaTNd+A*385Jsv(;>7rNk&RABtl(Sd(!w69$yk9}4Pi4G%E;p+dFa%}!52YpNU7|Xt8#l?M z1F<3Td!DS;jn{1(dzF$IA$bQK*kK8b)U~r>J%}w>A)Zu1Xk69q1{97>WSOd~ZPuhz zyZtzXeIDYBA8YHY1>4Y;qd&nE4{kF27VG1G8gF&T*M7UerdSq+NCI|^E_Ebs%Fx={ z+Y!RaSoZNG)5NgPj7i!N)#}lKbhS#?D`Jz$w3WXr~;HZpjvLIGR4W5y*X2fuP z?(E}lw|3e{h3{NFDpsX9y9FCe#g6@?n5K<0hW`5Fd?9t^Bj+DJ;I3oDipqoBi03cD z>xHCb9cKHv#(Dj0dBN)Yjj8Wg9u68W2WlG7SHJQFiKdcb`U^Yx>UwS&)PWt3{>JnE ztEK>gw!8VaBOC7jXG`?^lxt5!^dB`aCs6!uocJ!6a2+OJh?=AEv+Zs4P(E{EHId86 zEH|6W(`R2$3Tm^U^k=Quf5|eym#lJv@t#mL85HjS8VxmkaG;xxEC&+^mMt#qan(p} zW@Y5(%k${j4junaQOJgTYUm0Zq<)}QA_$|w`bZr_9X|6E z`)xu5oppN|ElmA$I!|_6NWvALV~UJ#s)?AMfuA#{Ad;u)3`*8;{4gn8>H5Wz)ceah7b-jIb)qDTn0Rc^WCBNS|cyNtHUUs1bdC??sk#4nFA zI9e7KT%DeoowwvOCWsi=zIy3yZXjMB9Ad$L?#RHIZ7lh2BG^^KrJnXDC!cr#YR8=2 zbW?E)NQowWZ^ZhV1P5=QzQxdpb;`f^NY9S(PzaB^hfy4B{q0v*F<2c|9kqmXo;5$# zZa?Iv0$jvO1?rjS)2`lYs~v5Hv8apK9rY&d7J#zL*O-PqB)Srovu$$6+Aeb8+nj-% z;vMA5FxLhwx+yzYC}+RUP|XIbgfGffOs$3zcpb`wDKqv|lkn)ejY{Q$-d}P)lHMzf z^k4hDj^9?HW~3q&807-#8!({+yN#mDI8Ta<-rlMP>E**@jX~htnGK0e#>e|dA9`4<&K>4Ir0=+=>mnW%t_P<-6(NE}}mW=zq3sgcvjJ!U7 z$S7s`L$;#0j(6Ft1JcTA_7TmtwOpt^{VVmeGcF&ND4u(3)HAGlOq>z81|#p&hcwr^ z{$z+HtBX@ouo}2vt?~_(`p)t(iio=-e()2QnkHVO#yyB1b|Tk%59s%1flC(@944d#)`tq z*dO1zjUu=xKr@72{Kd1JobH@oe4{6NwQ(q+6B+5R+$Cvv_g=@j(cO}jY0=)knsu;! zzg|0gMjWp0>O`SqW}~RHp&O}~ILEUD6KQx1XEW{!NfDB8mn@x$PGV_j+{%Tsy?ih@ zk%a7e@1w%x=+?(Aq-dbGLeg`Bn`cRl4apZTzqLdv?3~3l9QiQc>Q>=VV}W?~OaM6f za^T)#%>)?o`cqo72Fl)0UOTwDs>TJ+p~F}AT!}3?o#bs-2J%XeN3wWM`w6lmePsc*32>H znv#K=n`Y_K*Ons4zW(K4ObbVX*JIDqLdU(m@3MOx&0%v*fpjeg1zw^ysGcc%;Ji&7 z`sF3zdq|@s)=1NLjnP>3vkG=Nh_AHw6vmx0g6(}$hoam;?a)iRS>0(>rksw&qQz}q z8L)79`GDjlJ4unxjvmlVkn^ahQ2alfy?0QPjkh%lAqWJdNS7|syC9)g1r!7;O{$3W z8fxfGkgiCPUInH1UZp8Qs77k2h8{YEQ0{~0J?Hy<@0t6@y)(=}$S}_glU>$cYwuO8 z>ve}O@JZ>%+ecNIBEAbOYqSw)Iob%L8>8g;$-j30FoyluZ^;zsS|EDmWm4G>#!-eD zWx3vIm$s71I#ED>2;6gQePW1m0M(1P8B>wgg$*5F^a8D(5x-H|Ym#|^V?ikPv7B^! z*WT07Z?r`59%!s_$HtmxSE{;5LNJ4&(zk%mX00^z^YH$=12)}umF*dh^cjxPZ;Ia~ zPS8rE3Aq%bW!N_$$a2B(26xC-FNszxa(9v5IDFc%l@QVVr!j>=Ao5TSCv4k4dP_dR z^|pzK!(B7>b7>)bk9fYFd_Lgk1nz>2ej5Eeyi4=Qc7iw-*|!MaKjNQb`OF|GpwEH- z`7Mp#3<`>7W%uChST&r?Y}Uaa$a;A(vxgSew86p*@DRzI=QHUmh!ub0fh@bS-+SmJ zVC;lJ<<;W+GYsPD^FY@|o%)_sOF9t|3I?>XsC}QZ{?|i{q#*hiz6X^RXV_K4ts433 z`6wICrUwC=YJsFDYJqK~r)GF0BOVE?xlaT8;!5Xd+mBh#Rx$#vFB6ROSPkcQ!W3>m z4_&`R8y38^t^KTh0M;idCsoq9eBHGZI?i&&3f3Sget5$XFGoP5TvQ&~l_i(iA(gSZ zBK}~ivQwVuPxxu%4nIE5*Tkr3t>{rhCS|F=TA;~nHlZ5VZ?>?#)U2pH`M@G2&y$wG z_4UZXqs9%{K0BQW{*PtzeC9ZROGinQ?*h6Q6mX(k;4sy-aN^Y2oifzARwiOe`0K=1nlUNgRZ8+rRQRd> z^)OMT(XAhHS1kX>p~mkgNz&{cjdWJST@33T+h3*nThM4h?aq3V(Sda4RG19CbiG@f z^YvFb;LND~V8qkgoLTe@=}2Z_{~XxU@(mjb;B;j1i10G8leDZ#c~)0st;mC?pKzNmo5wnB^MVo+UlRO-N%VESIZUGd%}ioYbQ(WsEL!Hy-od@3)j+R_zV93$#-t2$Yz2aV$yKJ!dTv3SAq{@ZJbLcDI$H_m(PU)+Hn3g25} ze@&`!xRXfX#QY4Yc>0VvO)==pngRF;$(EFAknlkwzwN}$uPaqjPl&L1%CSTHkT1m> z%_gDj%~IdS+@~7NeCD4Ut;*li8U9Etnbh8mWxtL-TFvbDZr*4 zR5T}KV#4P>?de4~EFTuwHYYaSJc3&yZmY_IoNqLefT<%BB`g(`K8zk_^1Nv#9={>s zvEzRY-&QA6F3h42-JOwH0jp;k@DH`DX1$CJstGX}?G?}Rm-gR@Det?hCr|3qoYUbL zM}g#F%xRIace04TIH{B_DJiq{CB$F6L=EE5{@dv8_nA91Q3OW**p(a26!K@HZP-Dl z#nq8KukVM*r3{QOkMO?mmQ|y_sc7th72ew2BUj+)MoMa`awE+vZ|Tmh_T99Te$<%| z|5!L>NZFzMy9JXj6&jKs1vetYh{eUnq#6PgkF*~Bu%i>mCY8?%#| zdo4dAz0T$@Bz4|m$g7Gz5!FECviryS#G9m}YaxB}Eklhaj$*$l^Yuji0UL2D@)5qo zTFrx3{&S5}$D^4gMD{PI28JE$D}jvrSSKaZPC30>BY|!Y`#cca`{PC=hx6=yJ3+b6 z*71U@>5kmE9T)wCT;t1n@RaGsLnrog18x85SsJeow4(7B59r3Vtsqi_`Vuy%Ha~rR z{SMT{7AjTv|1K7PU)g`X3JQ4O?-;y1J4>H!1t9M`Vqrja*tG`Y;MBA2Dju9nBIfqc zaFLi5#NUAU0@RAAt6Gu#zRJT9dQ~fC)qYOd{i{}_n*#4BG+h7zW?Y<6R~U34>u?Xc z7B@>=(dr0h=WT76=`lqex||hW?wPtQuQGFgeiOe!P$D^96sMD8^d-lnILGiyHl-S9 z*hj~kaE$;AwlseFh&iU`!Og|D+D4%!cX^)aUfZo@LpEK2*S!IbZ~?;mueS=e8e_hRiMU0;}#Mn z+0{fS({M(r_5qJhM%TN9!itubXx-w$JK+8?F1c;?2Qm?R@@~_`MM)|x>vd_ntx!}% zr7ekph;kCQVLtl+IO31$uHS^Ctjs8zq5@BovqejVR43wM6R{{@iiI2v4MDU5dY)zR zX9WP)vgqRhB9I()_#t^7>3@!NnY2t!AN$d2taK_B`=m71<&XKRR}}m!#90>y=v|oN zF}WKR2cI@OuO1gS!(xUmlet3pn*6h;>5Gfs!dEb^1<~nIOu#X_XvhuumdU`%?n7m? zxH4R*MtOA(k=g>wMB8;OJssy5!_KpP8`^3czR#d0gY1sUM2=#4V-Ia~lunh+$5#fKNEhFiewu+B?G37K@hm%jgQ)_M$bmyN2=Iu5(`I!4!lEMKvZtAqRwVWtF-vI9o*Yp6eg z>}b3eNKGR`h$wzI{fP@WTl)XjKFMH&0?K64q47Wz$lx(ajs9(_k`z&X?IR_9)0+4M zYxPJk1H1Y-5b#R{3rnH9gj)E|I%q`y`dUL1fq$J{~yhLcm-^pzEy0R{q zui@#eKF>a&G}quYQGTw1v1NY5tH{&0(*&7cuSF89k^CUl5ZV5StECzUt&o+mK2j zUXj|&^vq4#XvM}Y<$ep#@3@BehV8_1_prhR>6D2TFpJMg8J(AykHiq(E1GwQbLQv^ zD2p;+fo#pWO#bJTA)aNTjp^wL8({P;v=~&V?EM2Dh9=frwoKExkv59etUqoTmbFIP z!yr%4Ci&;&#-GSC-oTWGX78>=#1y=`;=AWfZXpHEQ>QXKr}@@@B%n&$lkhw zU;+B4{fl$Ozfmz+(nnth6bRGbOBSWmZC8*17n@N#^M3;3Z+J+tUA^NrAp}$jU0DYm zf;G>n2*=T^3@^?O0h8UxN9yr`H7Y}`ZTq68Y*Nm6VW5mp2>&a;X`Jw?l}sw-m+;y~ z3|F$z9cO2H-qAF2f&K@gvdI+hSAuYD7rb-cIH#qAfJ=%ZouO zXQSayD|v@T!P1Q*?-U@M_zy`+sXrrDLhz*?M$j@sLMI9Hk!objYqYlI&woHtWwyK= zgQhZM{cgt>Hpv&`e7P$GSK0zx$NXQq0)fS+J5Hw>g%7yVX3e7#@6SWz7WBdb zykkU(uc>bGzI-tHMk#NM*00Mq+u?yvM6>Z4wET8@X@iB8b*-$Fw=MoY45n{rcq655 zVk`LO+b66K>cf16l}Bx|DPMbS*|kxWH*L|;d}|3=qrMg%4P#hVUc!CEb5e+t_W``P z%N03j!c*pXd_T*8fI9`0eLC%597Aqzs_ka11b&)i9Os{C>)qJeD6jrgO(vxPjhpD@ zAH99Q^0`X$Y}YjE!eeH?)~CV>ZfJIDWrEdu7k;&#=5_L3-FdNF?!;o{2-U!%j1?2b2$csWV-Re%ajjUOkpQw%IY(<>ud zMY}~zlPuw<`kRN%;IV!ggoi6=BDqm7|)zKgR?H$FY(^r zx^5b>2fGM$G?>a7bwV=RACK22!h&S>&Z3Q7qO3+DTV$r}ILHZyS`%7->ez&rQM7z6 zV-qwQQRS{t#1%Up_{TmNq2QYuQN6WM)Ksq-_uCrk+$I&_Da{zr^xs;5TDI=C=>p7S zMdvCECQTUtlqRD@(>+oq!X?@Msl5FNyXtnq)RAqs<&iCq5o;*$74IgikwETR@-V(f zLq@0uuqB=JG>v2P-ltf!(KCAM`UQ_p{(I&8TQCEz^DbX}nim~CJ@TiqVv<$rjj^#Y z1|}xiF~<#m1t^rqdFc&PUj_>QYns9d{PN3|b)^i}kM8&U#k8$^LA9 zx-2m00Oj$0E4cYyP;q(N&17Q_M*Y`oL$a6|uGTuo)PD^cK6f=?+5#AHhZdZ`)X&$bsRU^Q^+60!(b-#)Z1Af z=GlY38J2R35}TU(?)I#cJ?ej+t$Sad@c1Wu)q{FD@0PZ3*&@=Zo#1i_qY!eN^hsH4 z-q@qZ#WC-m$tjP^C-{Kn^7q9NrP^bVk`GOE+KKuyB9&xbD&!GkTa2djw9Hbacq-s&)%QUxbQH z%+4zBl{M8Jd=j1vGO>_yK~sCpHKsZ@cVWS!KA_p^VI^VW_?_y&p_x!Wi;>`Sdf+5} zBrjy;x5T>@zpj3_Had1G`fOFS4Zd~lbwMMgz+{Kdc~B0QSZah#`|~u3TlIl} zGCWjjhO{u=!w`I2-&MowYKW$#kSq2`vzPAbX8derCCbg-D&jPsg=7`LWd6!tg7H+e zGzl8I_)9Q7YB_Xp>H%C`qHGHyfkSB(x$F84WS+C`^nd=KUCw@swVb_87SIToI2U-O08At>zHNANWyVXmNcBGzo_y{5+T1H{&M%AU%e5VCBHBEG8a0vHL1G-~E zQYmPDf2eQ1Xe-TxX9v_3+~djexvpK`XXV1e~a|b=;>{qH+J8)lPB(k&RBUZ470Tkm-_kQ(o`L2Z$^YW6ul2>nO z+;Piv7AbKd-;&WEtEq&>9xU%h>eG$AdZqm#mNts-vd&py3N(&-&oe6vE8KYhwaOOGVioNCdRl3ewE_m&pO;(rr4Pkcl;XR0FT_@*<_kZ1^JAZtF>Z>ht z2(jiEM=*?zav17&98c@D>JaWBF9r^0r{cRwWM=7Z4$|@kcc|a=EFe}%b$fr?n0;&h zGX@Lw8lY$=NjCPSR3281$8c5F$Z$JGjnb7C|4Rrl0toVO*0YIQvXPw*6crC>+9i_0ZREU>(K0xD8k(}pw zaSH1*qqIpg)=P)P{(ueTWLC#gj%xU|*n@2)iqT>pKYYNJR1w=jv^$3iP}CN_TWR$N z57NUwwN(~)U{Rae@JRiMGCLf@AWt@UY&;h}laFjsceo+bTTZwZKHE>yv@T7uDyu)P zT=4oOZRQJgyE;|oY?4x+h73XwcvG(;6TM45-ktItQ63aeGIKmzIgvP5-$_rhBPuve zO)ax!*RMD;38oyP9J`yAEmDs1Y~8l$4Dt=UH&X*!x7A6uCmLv$0WY>Fsnktx5j$^o zTCgTiaJm%GODVcLPKLfUh?Nheb2)Tx(b*>67?o0sWA~!G#ev827SwY`_!ml&b5I-*blxB( zC3R(`SlW}@?E9?#CvdX0y6A0p zF*LadE;arcb9V%LE*Zh(Bt3Wuaf4!TdFuNa~Ke*D|+uVA_9* z1=^IQGSSGxSTs_4J!9Q(;ra+_&;ogKp>%rDFMgckI_h}oyu@=T?8X+fX7HMGlKHf!~e!P_D zJ2QvpOqqQfr6ijIQNroPobu?!_4W17sAl^Rk=OG`lQzKkI4kI&c@>J*#(V{4Dt@7* z0cg!2f%29cIsvC+E3yZwY^TFm+qcHZfA!mCI8A49ojDd zgpe0kvVu@Y+7@ovu%Bx)jXXN7rgj4V{`r2c`IApW!uG6N5jqABJk@HkJ^8i+u=}CfTJS-rj<-KWWp&JAj!=is z+rT&_L}A%pK5MSm!A72k}p9*#RMMe%xj#fkB(o} zqz;_K7H5U9VHcnaHad;qmhXp-{q!xSsvp=8Mh9<=zfI1{EW14 zS=r0rlzV73GR0|AD@&Co)OGe@W7UN_E_TB)RNG<-9mmr1V?8qPz%3h%a`M@j-U0k~ zvn6%EEqC8O;Vd&LUn*BTMM`-bFt93~N;&%X40@rP=fa{y+V0`FLd3?wM0rjU(%!61 zfr^!9J%$+!Jm9Q6ji9ZkUj%!gz9~-66_!XIHnXq=XepmQ{c?N0rrWH&^unI8ikYp$ z)q-3JjC?3M*a3qb~u`_3z zA;*p##BJ3M=~jzom<|}<^G>9{cH=9qxdr)zwqYvHMDLylk62E2rkyz=#&Ud@L9aj2 zam>#!&7FDnWQzuZE>4|$=xbz@+O2zU#+zhgO8^x@*UenJuN?tX8@FPo_gF^l;VErg z`>A21dm5EBZlG|ApYweI2jR|3*F}2tYi|QycNC*UpppHBL$>X{UYH(Ikq%|n83~*8 z;#A5T`Mond*6xXwAJDf$U|fsymj!xoJ)j4V`v22|&w6m;bv{(_Wp(|7 z3Kcui;!O&~HQKAkvC^u~)n=biBP2G-wBqCE7Y*Yxzw4vBwc;72=$VZZSU#bvSUafA3o# zb;pa(8D-<^8j5&O<6GCIE1dByVu!z2n6qHYL;>dlN}e|qn=m(FoHHeVs_&-uI7@pHGJoT%gXBv9YIl7Pd#0~%r~=)7c=;^o&>|GSJSn%aD%6#) zs}vdlc#|ELQ$bIuVR3mT#kcy=!)tW~h#;v^gjvZt%bJdQBXln@na=0pa)Do$DkOHw1Ntxf(R%&h=9x{7I#V-hRvobiCjj4fl2-3pj$CghY?ooD! zaqm;edQYb@Tj)0JkA$&s3#EVA2$_YQJ$?Q!)o zY?;%1{YJzAb4eu16&(#G9~v>nySO-8Y$%qE{Q1y;bf$9qF7jo29l4Sh#c6ef^6I?L zZlWi_S7$lXb@-pC;FHEuyHBXIbXGyxuk^F4w4+GS%~A4REgfWyM9lkq6FHM)Xj$t>JdN(54}-mGjJN?vEB_x^kH>eBKh0G-&U&q&1Gh z>`6wEwzbtM(jmqOH_kv2)+MB>sm9waarIN!hZ*uFr7N}t#KK_rt4=TQGR9-p9r-{} zVfUR*|8a)Hzl!4(QE#9Bmu<2C7u%u+jL(Duwqf;2ipMB|e?nLt`{Ffr|H<iI0cV?Q7s7VW~zAu1f0&XWw-abk5+cvc0KDV zr;Bxz>PaHE*plAocl_38sU8zwPtm57ROdk#Q7C4SkM6fX`uLZ(A@>Fj z^S>&f=#_je;^*qqoCVE2q?0J5d4i0BDftym6arDj!%7A zpX9K!w>pXAiU2ldnV?kx-%9cm&ZpgnqRZ7Zto?3IA8g+Ubh;-4Ud|BkOrq*uv668G z8_P!*S5yZ7k}k54Ot)z6sFrtM=I$3c{chEA%^XETVqBKNDLcK9vF@#_G9I0gK*}Q) zuzq{0G>HzbLDGK1pF27YWE1UZN1JTqOX&n(+Spy(FbOo7Q3J%*6@J31A9{J|B2!YQ zI4ijvwiSn%CmElXl#~!>(@?j$n^mcYK~;9V|2(aX{lVM;FYz237OuJIUG9V{M(4$`^#Ip$ou`jy-vU-k zm!3v$yZ2?ne@To|Z!^`%Z7p=aqqde{(ty7MjoZ~JzwoPz5<`fMG|Ik}e>O&}I(IKO zjOiK+8#A(f&!$k}=tNFekBPUcA{=i4+)6Th9KS*ww=YeQC$Gwy;B&MXt!8=h^lsa1fNKa6*}AX-8|mrz}0~kWN&MA5&qvS!h@jV)brM znT>&7V@`S`Axkg$M1$pbL3|j|0MYg)c(s6`lX7)v-zx>@7T-)!4LhhN%L&|vG~;eD z+I)x{kYnQR5#NKX44l!#&(W5dxr97NH<&Kf>|BeRpkmi5+hY4DXEs9GrXHa{f6tE| zccC!kJ=a%Mo?DJ$8+vbY^yJ-ralK~MWEMU&2fN>*61?tZ6zA$__W*U0j!$KcP%O3E zln^j}s7Wne^_bRJqzh(OEv}3fT$}%sX7Uz#xdV(lXp?_D*kdI1Q;KY?AimZa-1RUU295CZO-JEO^M&ztr?A$--^JnhB*oAmiV6p$Gw;Z=>c_;v-O1*T!g zd}dc9tN6N5z>vhptLO(v*8rWU6$H`owN()Ux;bPzP{xrLx>aY`ZQPc%yoo9BNTEAg zL8VWC9{XipamK{In)}~h{wj0c*Z!l-fdN`qOGyZgZy5`Hhj=m*iCmqXeW~u5`oK%a zM#5tN6$9tYD#e56(K4)VPJdGBnQ!}+p(j_Rj+OxRyL9Gp3woh$+Hrd4V2;s~LGVEM za4yDQd_JBeTY-H$a9_b*NciVEZ~I6uf}~(C6|Cj`D5#g9E7n&>dACMAWChfAF{r+S z3E1-RJxj>yg=P8(CF#l%=T>#hJbO0AkQd_oOSM)jUQ&dijOalRAZvgX`$%Nu(`FxH zaBZi4gas(dd_?yG2sz_%4 zjA*Vgl*{aL;2OoYWE}>)!uCF?w55uEth4$;N9%k}3$>-Ecgxpp&3IYY@Jt{SVUetx zBVhW+vLMxtY<^ zdsB?z1e$r-#kM|L$vvbZ=9?e6pS*NG&^Uc=B8*kKE`(A(XoLCACnQH#QKX{RW!C)V zMRofukB!0_a#eK%QIGnwh0i|@O40$xA)m`nLBc4ssI zW1U4Bf6U$*=biCe7>iNz{sbvhJ@98UeW=_CPn>8?u8c8k`G)wSpn(Ytpc|q*hx08u z3ZfDRd-)AZuQknb2g@N#B$Md0=W|1FJH600R_Lr3!Pmqa@!S!hm`9*>e?J!C=Xc1y zW?h_jH~O3&qdv{!7GOK6X@198jBLB^-eds1W)4yP+f!KE5(}mS@D#D+g8;gY`Yp_j zBdg*7-0!>EaeoF)oesU6=PKq0knI=l_y8lvrR#JSk~s?D^Iukj|9eS-3ZlCV~am(ZUSy@ z$2ARiO4ant4&;T()W#yApc%l7;mApov%iN4f4dRQnl9(DBYFk0<|Hc180sg0_C5)zb<^Ja-S>+kFw|#B1-A?_owVAqR54-Q=yTs%g zm%M_2vR!6~{@KhqwAesjArRAMgO8KUGpEv0r?mEuBuedDs}9%g-vpg|jwj?K`BB7{ z<=WIX*8ur#b;$v{KTjIAi<1n=q1isJ`;3zR9>bauD3eVCDja9ye;ekt}| zMQ`!xmq3rgm{uIctL<*k+__JCT-*#6+E4$rXrl1_3Mns5@gljrv>0E!l*^iY0`;m# z(<@CmvQeM-QRu+8gEk6Kr3`UWd^z4&n$&1@t6QEPr76Ax*8&VO2J1NGNYY zZaFg(S4I^#z%nu6!Bd`^RG^~_v&xPtk{m;HY=)(E?aLHJvG7K$H{Tr$8*syEcU(0v$!losYnWP_62YH-=fT- zaOF*c6d^YjX<9kN+m)mD4+e?_o)QNlspC}PtW7*#(<>S zpS0k$kb|mr6VqR0Ls$v(Phgfk|MyX3j8QZVAWkD_GiVGtVlO$oCNW|IZIH=H_874# zU!2raU_o8JMJ}utm#YYG-BJSSGM7E)w~Fo=%S$`|b$tl=gRaNz;zK_LoCg{reTHna1hRI8v(!Dsqw35UlhU!|^`8Hq=I{^hb%QZN> zaN$?{;}J8`JKJj^k|L4`XU#L|>9u%XaM1kg*X+mvkbuV4 zUK)F9L(`%yEMnigr_dQ-m2BUrbEDljY$i_w00jvAV7HIs4zH(a?v zqbBRC8cuc5(u@nh^U#epcT;r%ShM>2s$=>qyxAyE{|6*NPhXg0_hSN_4CcIRP`R>P z>KNryC;$C4ue060`h(2p1C`NqFJ%`{eu9@d7FTKJ)rI|06;`at@N=Tg-6l{T#>U0c zFs7_y)yL52lWv}X=xHXM-sg!`NOT)ow=WTxWU`S0$f|52c3=cBcPf}H!kd`##wD;aN*vwD zNGVJ9$%i;S9s@Xp5Gu$gZ&miOsuqq>WhZ7!H1@O-kuO-VUEcOz(R1pv73k?nmcOnZ zm!(pw5a!wl@V>#jyKpuWwqo67wL*5XUxaIZ&9tFxo7KIQ4AMdNjow~QKUrX&mS?wk zo*l&wv%XnT4;{v)#tYOgbN=CsCCn{s-r4yR^wP$Z98@0_B4^w{f|Vh%V&xnfTYQ!E zK=xGo5F8MK*TbvQs1G(@QOV)mxy#ZR)pH9%=swPU@=}m)Jf}(BOoC@gEjwji$heWj zmipCk?0)E)cS*zWF?JH1t892DNl({Qt=n5m)Z3qjZ`e4q3LY*S^)UFu&b*N(2PT%+Xks4nY@ ztSHW~3KpXb%R9Q!`0ucOxP0C))OPcw|Jk@sE6bJZ^lM)VR+&({vPQ#RG{7?vjYMP% z<@A_hS4@GcpbZTL)r!&7gry`0M6PluB!)T0i4Inz`}H?4eW!W$INrZ{>m3Vv#!_p) zC3;eM7yr>s+@l%9WDYM_i)B)C$MNa{*R})Z zsm|8R&*|FsCU9b{$9NADQ>7}Be{j__3ypt$kv~ggF(JmcE+!@>d>;hn^~C@FyYSa| zSIFqi<8=)-4g1w&aU_*w7JRfv;WZUW(aWYXpUv_i_8(6${FkgVsH9FhfuzPxd6w*`bP~B!W?M*eU zUP%W8n04;LD^j9Rsc8{oC7SKMx0e#cb z3k#kz?HakE)k|Zut4^otsy!2vVblfqQ!9G$yiEtxlf0sQT#D|0C7!~b|JU5~l11-I z6e0LuTq&?^yd@e9M&`Brz`=lRkH-;!~9_qhA?z_&m-J267qOM=GFuuqStjtBJ zR0@`T16vZ_^U&U5ojKfT4j&IUcX#piFl!07q1}7Iv+DYey}D}_lE}aOrLRbHSM;Nf zsNuW^(Z{kf$>qBX*jTB10{xrDxg@pEc!Iaj(jGTA{ScVZNtxvAXU$*15+B?Erf7=V z%w}H$6;OIa*6v@qyC3#BWG0hufY)h1$1TGxEbijRe__eON@pzlFeBN^(JtAtoqCBL>X!C4yP^N}qN=g3bl%we8UvxlD3=

_WqUR;E{aE(snJ}i$ zB(?Z~mZKc>(5ktsh@IWzi;?f5#LnBTo7XlRNei{j%w3dcet2IOil$^2+40bZs5uJ~ zOTtPZVZlbgF>kr43}HGt?VL&bg)Gd4)tMsODJ9Sgam)093w;D_JEYZ-2TBr)Gd{TK z0EnLPAv19B%+()bE8Ii>;raZ=)5<{YLV-$Uq&ppd(F^_$-9M>Lks(92B+D}ey@t$6 zQ8&oi;%z=9!$t9xWWee(wU>l zIPg7*8gcGIAu2}-*IxJtLFO~2rR&m{&Z752=%XR;OEl9J_XxgAr*C-E=As)0W|FXv zj=jQGyvZ;9p|Q$5@XO3#>^1|iQ{@$`eH?9`5pZLytleG&$=n-uXUh;z$;_or^Ouf- z4M)%z*{Zuob7QFkl7T94u2x;yS4ghIf6ZTp=!6y5x5iB=k9x{Sf2P&{)+@ky^0 zq-0J;DV{A|k_H?U2D}AR#fxyRtvnH&5LHkJ(_lXcR_X^UhuKe4x?6am1dxt>Aw^p3E!|23<0doaOe|V0Rr{@%l#7iNGwCh2l(_7?* zrQ~$UNwX*+d}oqh{0*k@uzkSDP*RtA2WD@t#X2tj6F-OuyQV)BjQ1e-K8RVXc&8#s z@G+%7-qAy40{l7J-oqiZTCoX>kp?J|zx6T<3%Y?-jm|Jfs0W_k ztqpQ?Lz(4G%_cXjB>5neXn>-5Zr_OxGhfO2)e8T5FYWa0Flg{&h+wGTX@@#nD%(f3 z_;z0|KgE%PoE?jhUY1W?N%u-$q ziLNiq_IM8}3T4dD!OW|LS{nMwZedN~v#autrOzfsUw;vGU?1jZ1FMlF@!!)agvnHS z_IytxUj$E*e2YwTXLu*O2Y`}gcR+OO`MOC7M#>pBNzzeFAfc>Z8N|9XWkBJL|B$Gn zJ=~J9(4KTbukO95pegJb`jjTaF|uHS&TxxdS68>9rY54N=RUT1!k$BW)q0NF3Z5B0 z%xB!*w{F2uj(k#{*t3wq?m!s|qNM(;GYSTGk#tvi1u9klI4Q2KfxV}zGjP^-C)T64 zJ7#|)y!AX^ceW$L?wm58je0K50vPWLmY2PAsSf0^Gx^T(6m4w9e=@_U0B999j;Y&QPsuFo|lGe9W7a{~KTV z^a=hU#Y)do&u4nN&cxz3tTT0Gl9h@5>JRiRZ3MXgj3L+rdttnKX z6=^ua-nmmOFaY_8-gniiecB29yMrq5UUvdwC~kZCoPgN&sbTcJXIw3`+Tm}Dx=Dkq zhx#06X#I}2P$Dp0^FwCcGzXeU+68PJv-DdXztgOpWHu}VtN$`XynvajE!~4ujsd>- zIA)HGduFFkDJybi_|WR(GK6&SxVdS%^Ud$A}ZCTF4c~n zphMoskTpCBa^O5GAKG2K&2}xKOXC-H8zu_QJ67g!+jpDPsDhZVTtu`vEy|wFJs!mN zd}yY+2Gkt)s( zOWZDNkzb?t5_*+RuLxAFph1ABox9ad^IL|Hcx3+#-i1G|UtOWfoxVyu?O$rd&mDDo zSE>p>;;sKsRj@^4v7j}8r0oUD??3a z@wst&9c;#>F=ty#m|3XVu&rgSsALd`l>s=bC&e!wvlL4qF?hgj@FApQZKybR{*+_= zuX}l(UP(~zEh*N(L)I!!_G(Xn+{f~|3hx8`_yK~53Q`aW>(V{mPn>umm@dPmbl%m) z$1D$ju4K|xYft0O{`=8tfNO5-yIuYtDR z3w6!MgdBkF@9*PlAQE~X=)|Ja^Tp*kmR1sJ*9h+3)|%F&9zIZj?1TEKZ*ps))@p_w zh0Rd*EJ!2R^|Ho4wniRT?M$Z1ryjDZ%uQ7*R}v;kg)tYp)t3;0WpF-E!;p({9GhPI z?jbaIT{DUl*o2H{@fE}Gr4lHhzAa1>1vRsG+!rbyffJ00?o# zBMZeyw5gBK=qVJ0;(rzJbnCo#TG6E z11ZTGC+G`UxcIDCTA6?A_q zW5)9KJq<|&b?|bKltaK?!llUEaoh0{;QN{&M*0mTlMx&E{mcl$NgP;SA&%>ASoXT1 z{l~`_@GkFfc}vZs6QSGlRGE2_hli(IJ_CCExERy8aINK#=aL>P`^Z8_aMfKQ=#5b=|=H-+?@zd0fF3*n8zyYgrz3(i>TXdNxHH*llV2jtOahgO%^;*)U1 z1@*;3b=J4{>Tw)wG*7ZpR48dHN3AtF@q5Fhs)>TE?|1mvzIxc3W>KuYb*9DPP4{R= z=`N{5Kc_m%n-F1XyK*OJgRml*j$ayOs`~oXdL?UraxRMz?DZ@Om#Qr+mxMhVzokCMk|*r|qXWQK^sF zY^~`p={jWRs$3?9stBEKQ)g&>_hpr&OY4W@o7WjN>3+^PI17s^oUs4Y$qpE^j( z&gqqvJ8OFj1>8?@@{yj~ORBdvCuS_KjXNYy=HyrQPHC7dZ|AymW@+h&t!EyK>IF4uizu~wld%y#;9CuFn zqlNf|xVh8#?(n++04Iv;OH(QmeUBhQ+M<<1lFKt2xdb%h%xAs@Jq>D#p zJ{0fc(`wvBdK^o{U*(u`sOk_42)uv-fiwI;G@p4tYOA_S4;$KxjoMom#E(Hoi{JL} zC2B0{m1s|Wq9sa*2%aUTdXq<=<4kz$YxWYY%(9wBBW6~JpND{#Ka}$Vib3^M*Eq$lcTH9GN|RC0hhKkhrLGqCY1&VJM2=Xkc;^_ zcJ1O<4q^eQ?t7x)-{fw=a=47sireWHb_*z@l%Fl~h;2cuC_FZ>+gq5_2<*A5v4`>u`j}VIEiMASDaC;W#~P@b&M_6H z>X<5w`ZR?Lae6aYq^bhWt$JS`D@D1+a9*c7O= zAJc1je_@hFZHWAaIm-3^j>WjLp(e^AbV)TS(DSZU5dAbqDjMsB-=0t4VDY2nJpA$f z#k;55ByU9I@oI|&txdaphaWK6R>iMp!}lEOg*@xn)Yz#xqJN5ENUVI>GNk!3milYy z5mV2^fArIRv@;}DD&^}OE_0q=vo#INxWH!6SDRb-&pQNuXZ#U!}VU@237$22g<~K zsPw7l12FgIO}%mLzffoMXMd=(E�mzffnT;#}+tvCbDny=lgGDHC;>Q|{EKaFRw( z$kZE(jAz$y(a`c%rl@{c;*LmnPc9zjoRq4iP{zq8-*n+ONHPPWrYY58>&t?>ppUVO zY>25ox*S%kwBehiMoO zw0qay$$^lBTNC|5vt(1HeqL|avuMebkBA4pQb4g-k-mcwvkzhR)igO{&zFGkqD9j{ z+{At0D(-M*ljMHb^U9EyyVBRzJU4@Cxpo{Fm$9Nkbwu;&?P@<3Ids#}u8qSakiE6@ zqODP=E%vieV)?$i{4c4HMf~twEOiFq;%)i@gpVDSKw%+dXOG2WP`j?oD7mN1r?pO+ z*a1OH0GS!im3t|}cLynH6k$cKufLR(HX90rlZrq`x~J(A8D z@QB&=0=#mjI2q^0n(@7K1|6zho?B5Bd8winY;wX0miRWa#t3ToG*b>xsADM zL)6mq+Q?m??j58@qf`87t$h7SI}$8w=mRqGq@wQ@aQlS4{N{>3nWJmIcV1g7_41B% z==&Z{ZixDa+C^&q*I^}60~2wi(Ha8YxS_7Hni{~_Bb2b|f^6D-pwY;#>i#Dkh$7h9 zdMT3l?rmd7k2j3D_wI9?u(5VCsW*~Z$+s>a-L^T{P%Q#7TLRRO`ksymk;aG~{7Bng z>d(A0a<>VIhDTz}QGN`{8*e~I{!nAu;HAYZ|LyMnqirwiih8qDW8+tWRN2l|AEe3E zxg4`b&U$-edh=ad_x7cuQX_(CBh;4euwYK{<)+WH-#nPbjAqR`RMTeez>4dJsT z)-n85GbMiZQSKteA(U3M-@U)?5J)^47=AF>_n0zOMvpXeh*sjr{QGfRnQ-9Da3cK`wULO)#2mW!U5%`VW|H-|z5zzkW z_`q${HUjIl1t9k+AKaJCDMf&3caFIKRs652X^h1m)il9hRntz*RKfGP5j~H7r0ee3 zFdtrJS&QfNR!{h~v(QFXA`+VR5`a*Ex&F zkVAN_i<>t3q3c?D>NGd}xf*41f7daKTUeEkPzWwcCdXJXxZqgj8_k>(#g|{nnV$)> zi5&Md!^+l|mXcCaA9Sroa+JGABRB+F^jy2VihJ19674CY4l_tTe%9`V8sR4}=$cDV ze6y!$;BEwVd~XdSoa+)s5-0s~DWt|n`lQjyio%=ypC}6@$D;)*s1evJl!7={6+$ znyu@N=tl4fALU?10B2;{fK;SHZjS5#4GBl@`mWezo=uD$J2wk^6+%RNQn|G)yU6`Q zh*kq4MFO(ms|f*n$YN?`Bel9^?tE7QONEc8Xh}~Tw&$kZrC^i*v^KS+>-Gwm384ek z3fH)O7VeOl(QpyZ`OMSXS|@a5k}86Ma7V_cU-scpI31zSG6b42roA^3t zI-iR%tz)rr)D#`BTlZt4J94k0gE}9oN70qKfJjIN6;p+l?LKcUx_4nd4x-Ae-4}z+ zg$z5!QUgB6jtyz~brT8_P)&3npy@hddK){MG>n7F7lD4oHK!`w4WADAQZiY=3_5`$gZzBc10KO%K zxLY5c!WNaWvP+-Fo&(@3uYot_E0HQ}B#>wOBlmn&G-TK4vMKFhcIVD;?Va@~3M z)vsGv--MehUmq;KUPl&_7z@H%{0=N!bJ^uKFk6d+OE{bDQ2>Krts zvxtwDXK1|bWq+;f0cK-<0sX1vJ#8V{T{f4mYtUbzv8Kh>!XDW9Cwh90_RVc5I>xcd zU6-bCMohaBZZ(}cxiVJ)uYiYR2lbS{$u%WLeET+SgZaAk;x>R^MP1sQ0*(gNZ|a{1 z{7rm~bXElaesk>pk0Yr+4BkKIe!$BIT-2pg4BT2M)cQ{T&_s>^b3koJ*x#0WG1MM}MziY>kg@j3_;`jPSkO{FQyXMCRMqD18k~ZGZZ~ zHWtn2B%E(4G`EML%-={I9Rv3nI9pl_0lSf!qwP)7D=kTYIsHRfn0pi@io5?@p{J33x zdS54+@7d{#XkoQW7Vl}ars<;C*16w>ckES9FZ5%wDu`slhX533==PZlslqnp=>O^N#$?oW9RWQ$YTaAY7;i?-A$; zC(q7aose1sDP82?MW-H5@cQ!bVm2-rALI=}6BM)im$I{1(3>VeD3FK(bWNh9E4;Dz z6|hlFUg}I@f#al00vvi+c)JH$d0k_)^KaNg(9Rr+g_SYm-}%puQi3QIE^?feazW5z zHe&qe+}wgEx@a-A#+27A8h{SwVn=$~za_NA_^ZvgwPs0^gh0koiG;uat<9OuPk@ui zl>79Tu_;w#zQQ@S1_;Xdd3uz?e!hBOS5rCqm*tlTep3O64cSkb&&IdUgxv1a zDLzo4yt6oMcAaXrm^%tqfuW>}T0D^5fXcgUY;uxfrHj4^Hv0sRD5uK4%j9teS)O9Q zYYo2N+BiL6r-Z*J@0o`611^6xy5&JLPPSSZqh{v1HUZ5TOH-uRSa<`40L>_Uf*I29 zQufQII!*!E8=&g-2*P{G1uQr%v$aMOIZ>1JxzM>^FE`+s213_SpOvkCz-{oYjq_q4NA4lPLCss zN=xQwuX`=cNAuPMc$n^&2Z|C_H&;xC&fnyjrSp5!(-X!>OPSyvWnbNCM9Js;;lZNgK zm2cRdo@PR`2yE|cVYUZ(9!mH~AfCb+@EY)zYWqd{k4%N=J7&xl-wCbx;Li}f?P1xq zzP33;|AH#Zb;N3LjUod$Q}0=%Db8jM-13 z**z7ZHF~b~yVvtaJzUnKgK;qo>9Hp@X0R2SkAzmf^6rf=!&Z=2j^cwG9M z_F5h@Z;+t1n7HG#Xw@5bl3#ivm(vcK)L@<~o=Zu0?^S?awtp2^9z>KNK=NoSFm?p$ zDxs1;^=jW_-;q;Ydi6HF>&#wBr%BMFs!N}HI>8g7U$wNg4aHqTi_-5vWc zq{`dOeY5xBC$UWkV4>u#RiRUr@!O@bS+tzqSs4E)U=JYCjjm`Vq&J5<{;g30;u4R4 zTq(8w$Cc7vOVa-lf}uz~*0pJWBib;Zjcg z$G@5bm^cIWwscQe8~}+*Y4Gbd$`jvVve3>jM(iE`o%xn>0<6g<<9(@C33ll?#96EG zlKo)-tCbJSBW+-%v?q(m)l*K0hgJzvendEZo89#vG*>Kpm0$lAFZIU-_}Ld-o>R4* zFc9D6HBupR+?zK^X)^+GD>F3$!Fh;GinM6)xozh*P@}1u8LERSMY|UgOVKiw5{x_l z1?l%O>FlbVD3m%xrTHp$)wurH8`x#8+LhALx^Y(B0Nhv8^i;L8Yzg@%t-v$;Mnk7l^XU$bNNXM+w z*VPQsRP@Nm><|H)Ec|OPqT`lVNizsOD+$pRq=6ddaib5F^hxkb7fcPkwddmf4dC)W zk1O56GTdg9&HJz7GkT<^PRrNPi7FIzw*$^o5sMKdelXqUh8SR*2;95qadT?d($XG>%R;me`~!+ z|1`#k$p7@%3Kjj=fxk~spYZz1-oWb&z>M$NplqrBAH!m9;4gsloBtD@Yye}vmwaOlUG{^T?U1ZWdfv0XhYRf1F%}$6zzWO9W@6fV%X-&eEj3+M@uO7ARpuzqE-FDKyck=x_!#&RMwMnN#WYGIv zEMB|)O4nqbNdIlGnfbJF%VZ1a=f*b;GSgkTC`_?*2qE&(L`(f>33xlLr!k&rTWtUW z3k|^|pT9OJdmDp4%63J=GY8|%zq&0!QQ#+f``SrH)HUh%o|+?Xw-##U`E+buT&08) z@f}JGu3w?ZH&bT8hPtc*2}M*M2t!S!PF`LKkM1)!>wdXKC)McDoUzN0Yn;FxhUUdTjf`y z0EQB-jDu(zKDF)78aV6GP@L3qIjEK`8u82`qD!$CbG{2%qo5mi@mp~ZX4^Cf8-WKY zykH9kE(ZMjiP(3JeP8RhLWy{+;^AeMtXIbRWw0p?b3v z!TRvW{n*&UWb44ww7FweVEe>V7Z9ijkW%M> zi`aMpYaWVBVmi32OcWsaKFX08pl9%0rF+CZCJY6UBe^^LIe}@r;ET|HU&_ z26!Sv(@wbeSfP2PRs1RW5P2jfu5FttjD_GtTj5pfFPFiFz|Z8pKHyHG&xO|2Cz(CR z5$Qy0^wC#&_`!3OGi*Ekb7zjgN&h8cL%~}#(a~>GJ<&_I(-r_! z2<2v#&7gX0_q!&f&J5`cR_{+)^2Xpr-z$u%cHcgCAW;R&d(LGx+N}! z#k+0f9c>@JbokO){j9~$J4o!x4In1*Q!_typctjFE+J0$!+7HdeA>($u4nL=5H;@C zdF<8Q))05L@->{%y4*|Kb86haXbNf; zE`|k%|8yrDrr{Ig2w-ox@lg_tH0@-vh|ksyepVG4*DnYea;n5%j(x*u_xih$Ole^0 zy^8~ycE|)hH6js4n&Q-AZ!&?3)zNVd=?>&T72{#k)@$6$d7sG}EnC?$OU9?ZX{;DS zo_VR}3A z4H(nWA7GmO!|Q5|Xb2Hfmt<SA18yEmy%IqCC++`He%zGi5ic=M=;qXBMK!P zWO&a)!uBYbnAsWb;$swEjPpWXg>E07H0EyOgFPus-F|*H<=XTtU_e8gK_Semr_5IV zhM7qBXzP1@Qu5k}PU<C+*yQ%90A2EZ_v5ve|XnMoyIoNHlfTNr@db_3ZcbS)?zagU->rea?aUtXSu3 z1x**I>zN$qcrv#qOXWVI2o;VLS!BFO0lCZdl;MR&whWLZU^f6osHA!CR`NR7uf3J zJLLzj3^?Z}T$umISN`Jxw}a&UNuOQ#dlwx{rV|fuS5h_J4LX<%1p$eWJo3libY?5M zpzK5&RF6GfGLf&jORtN}gl>D}yoipDepYP)DN1>Jy}Aie@w56qml~F^o0y`qlg~VG zpX{vd@_>D5IMM!Dj27qT(O2AX{_9yoB2Ks_Rqwg?OQf_7W3Ofh6B<z5ZctkA?6CKg=p`a!WR(t^<9px8!O7B+G^ZvEr<#-XC`$ctGQ zwea8;LU`{Xxh~t6cUovCdil(~tBOXD3@BC@2s;vy3tCAs0M_8^4`aly6iBRfzLfrI zSqTl@|6WyEf{n+&^ef&QZ#17o6JpK4khr3kQx7IhgqSDlC^kl3&c;YA7)xxazy2oTq)nA&pb+ftiCPG=f zG$%A_cAUlx6r^;zq2bi2zY=zXmUCU3kvO#c&G#67}s znMHy_jzn-!eYW?;(u=_iUMKkvA?#nZlfI1!?^x|G)N$BDqi<0Wt~*N|Gqz(XqX{J^GO-{ z=#XvB`f{G)!ZHJAT>pu<0P;EbdglLqAhLtyVImF2Cmg69V{H1V4!AEPrQzN0GA%v^ zTx!}Zn@sjFe@a)BY`$Ue?D*hN?SsNx&|%!<(k4)`=G@A36F&I2gPQiPtkeDVEih9I z6mkT+VqXSD$(Z?+zT!!vcy{$FV1G@CLT1P@*pM7i;bi=ecFd5tw};;o1tzAaDUT8h z^1#YzX}^L68ZlWvo?Ab0fZYG|V(u8x96xuKadFj#f=yB48`V4eoikmKZ^-*xy}OJ$ z(xR$XPv(EHscj=O5d&E>Avnk+^;aI00_f+>m`h+n$l2UaAv_dDrf?;bqbXm%F zRWe|A@h*4`jYj{R@GXiOdi8=9&f#rQWI)Qp`r@XSY`>&@3Is3AkI*dHESgldr%Y_V zAvDbF^yt=1$Ipg?GiVw2^9{Ogy``$H;OEGetJh9S9IJV7QPewU{m9vEnY{WvQ3B2S zRr1-n)cQJ^c)TF9dcw7P4)t7A((GY{r%P5I)P`H&YVUkAh1ru1Lf=q<{%wgWG?02! z(@Kt0&?(ZcVii&`6D0z_DiV-e3RgIsUx7?K6F=o>^wg9<)eognJcOAJ*!v3lQgt7d zd8;ypQBR$v@97a!Q=ahdWF#$VWr1iaSF-46Mz*YC1-Vz}5MdIov+<%bjvMyp%T-em zqN8>QQdrZUS@yPx))Tupju=3na$j?x_p!gfX>nUCICTJ8{|P@H@u5y$#wC51Ht}BL z#o^;NgW`c7yfT$iOUE6TXRT*wrG)>j723$~N&DJO*l@jl4~r{D0Lvi@cBv-X$(H74w{m@L)Q@jeXTOBc zS>$&v4mq$DMdIh49EJIiGBsUTYVhyu;f&9je+k2>JY5 z20BZvHb;lH!FwX3HYC>0nG98w5dR?QkCQAmv*>U>+Y?@hznoKO`-W&@j_z5HT)ks< zJ;$Ih$GE8FP#J7P)bq=;b?};$Mz=30o8jmO4dI4j_iH%sDKjNh`2Frq8wE+Xy5)Nc zc*Ue6o+NcE1s=GWXny4UL)?-a`ssSeG~N%t`G$`J__CEY(|95!;Uh&UQm@8&M9KS9 zxDU0q>)H4m9=S2)vw1ty><4uDxSJ6=$>e)XaY^|MB&Kt7sR!cGGpme)H#=ui%I-(q zYs|*$w?mesxHAnViv$!I({1*rN^x62*RjOrMU-L1LATVMPMGJhtWPEZMd+_GY%-YUs8*;VL36~!8NBfT10+R{YT)Ai`u zCsRhowBp6H^i%0WN4&4hhIaW8l6izkS8p9^$uU&CKBAHMHLs+;2c) z65aydmE$laR-5o~w(>(4r>`h!q?CP>XOTIWqk9ghB5y`KWgC`j3U1fPXYRR@$n(jy z^1T@$>0k^^$Ep=cO-(x|S|CT*`#qvonVp zTCgN_Qw(Y&nk(#CXSa0#_4FRoHzv32Lr%qjP7%*;d=^ZZO_?iPzH(l$Y;UdzEOM9j z#8bN0)hV#9hFP$wlr9h9L`zkgKB^>%!4)rNU=Fdhhp3_$4B}t-pM4 zxJ5_p>$*cl%v-~cqod8IwtXff!|z&=>`eGFAPoovwr`HfBy}M1FOSV#e$kHw^%E? zrUWuM8dY9gFWn;sa4tq{T;Q)w8&CxT4OJoJ1CaSu*jSYxg7b5{<2;mce!vkdX@c>g zzRx`p@ZHGUvF{e^JQ&%&ep%MA^qN6rhVtR?^P#+b)DrfcXTtit%N6D?~zlZKI!&LW5+P_G`nCMx|Vj7%xl%rvc21LEGY%?p|4 zRcZv7|D^>$*SU^_&$e`or~DAF-TpouF*IXu!m_YQ?qGXOWc!_#r8k~)IVI{w^+iY3 zkG|k;xr7w$C8%x@o?LT2flZEl7=|z)ce7`!cTs*OVl$SoYRF{5lLSQLea+!}Q0@Ja z&Td#|XD4cr2s4n;RlA2NtEz(-SO_O_ft8u}Uu;O+98PG3Jyq()R~)DHxX!R@)TAkc zr$B4#RxZ^&O9z6XdNhIr!)~C&rtb3k&Z*MsQY<;#C>1yR`N*ZEb#5aGjEu#rMkbRm z-Rg`2?SKdDI0AqM{>;3>^g7YTlzRs~Wi#b_SABmDdW73S1~aFllX@ygkDgS?$O8^P z5`sNXeo%|olTSlUhC9Kia!2=f-=v`5t1MKmW~Kd<4Cx7b^GRXq8=>h0A(H~Xo@J*K zW#IdJSm;Q{{j|FRF*)_YTMg#Uy(C!fpp{xp7RG#U8fEzqzSjimbAqCCgx|DGUy6?! z!H-)d>lg&zTHSsnJ|)$&NDR%LV(tHFdf-`nV8haojwfBYltjgW_`sN^>F2ZQRBcTx zt(HKmcRO^Q=(NM$!omo3a`K|4Kq4h&82#y!9gDm#?X6q4+-}qj?)4}R=5>c5QB3IS zNdgi+95J_1QcC}>8=IY+m?yj;jcgp*_?$$K$4+ohCJGj28>!C@dtT+O#6{V-&Ajac z8{Ou7>*~HKW>3^*wt^HCv?;FbtGvI$J75{DOiKURcp%528W!dW2Ld1 z?={gH70QniA_1^DlHRXB$MsDb?hq?XBq1E#I2r}$hp<&cFQ-;3#1|N(zJ84D+kfgm zAE2|y5V%F+y*gplo~CujDp+z$?abAw)b^$!iKXxJ=Us5$L;3aDAi_Ds*sF_oBPv0) zJ+y$)#e1?OaRmDM4sJxJC*Y_fnqfEA+20y{pv+wSe`xrh#VeEZ2NW0o7bxZ$`Je#o z@bo_Axmp@Wc7Q z>zT)U3u9;?UBY;?QjYH9oISU1^u=l@=J0eU=$>xoL53f3~%K$@zKT^<#Ma zJ;!!<&)D^~$~x5E3kmW59gje9?FDfwVam^7pN^Jf&`tj@C619YF0|p#ZmWn$-%Ikl zlR6yR_7(3l*@F$1_*ng8kYLc82(YOn(`w!c`hSggYw@5!Bp(2Cn!JAxWkk6n#zn;2)GSKfq-V z>8g*ws_x*QKgB4(#7At+CnZv=rl4^yhQS&5hWK+qQ(?eD6XgIN$NHz!eAT`yj0^~1 z_efk}BuUkQ8BWp}!_u{v2}%*AQVY+`N5B=bFV3;sT~#z(655C4Zzb}}`j_ds#QSFg z@?8v}!IKkkZ-WwfR!2Je-ajvNxeK9MeiId4o8)De; z^xQ};eQy+PkxK_h%(~oD%W2mynpwecV)D}Y&dJF-&}@v=nsQRcl7if=&>Yox0QD;M zcLiutMSeM~N$9oX@3pL0w_cU#w>@H=>s4t8!F`DW>EO z{AekcizM#_$z9n;{pu|c;@b8bX={%h+LNYfz9aA{HYP2vJSO3t2)QCCV%gPO=}wu4 z5Uuibe60kdzSa4(k#I8QP4dB0fX5OqtEdQz-S-@dw+ADA0Vnp;yrXuG-tErehgK8D z(5I9iCNx!uWGx026Hwk-FA-e`t6)A-J%ikgRp={@Gv zyuiXfC0wXTz_#BSr)33xk{`U*(Kh~2JHEs z%{mG-5wNbLMf;b?-Bcib)+hdcvqtJ@0<;-0m}+fVVUu!}zSID2It3{-|4e#GP&E&- zato|2qL^mZowMtZcO~B!*k{(A4nBoqXqYJ0P}Z?bO|(rt z(K3^9-!<8fd|!nO-mmP^WSsH@ZZ#hVXvQM(@pX%}=+q?;&i0OjZ?o&W0Mv?t{o@_WMat_dl0%QNb)S2Uj=0BO9l>tI0Jb-AOmU|U~Yr}r@+YI>q zlvC?3a{eN;zq^_!`6TgQN^D;7Asnc#_!xljK|e3q{KRo?&OBs-Q)P$Nyr+P8Lp0gt zE+{W%wlC(67%WaK=2bmobXZ&WbHzqgJ9R(3>)@|@@Hx`2!rdIOHq}i;HPo0fYa66~ zCwkiDYREC2nEMd9quSLeA}Y#B89+HKDy#fqu=0aT6LN(N_syND;-Pu@U6Y#vuF1Ki%y)cKqcmygJV|7o~a|^jRhWEs0?yU zFysx9SM4vK@z+f#(a2U-d|TtClqbQTFq$vROJn-}Gb)zDuscg3X!%N5|Hy-jM6X}c zUP98go*@SiAmaQ<23BQYV*YTr8nPm07kZq`(TJh)kdW?{Eu-3o`{Hekh|SP0M%Ih2 zl=N9&tjS87(a-Ve7LK_9(au0Va6sWqt4%ro`I|*zJPx^%F~pLKa-h4;NzvV#1W4a2 zgM={X_&_9zfgl^PQxj9Vut?<#R^qoz;M91G?1~PtPRM*v%n1|dCT5?hfOjTEDtU8S z%h1KbuqlZly!#73J)UlNMVa^!WE~Zi)Mmt1*%aNjf7YxP!R&r`r80l3&xQtI`;8tw zq9QbFy{t4g8+Yss~DXq6$6m|$2 z!o04XjgqsQfji$2nPaA^wX|wyjN!Ro@E`+iy`vS90P1Dpijg6eI+87`5RWAajb=c+U#@vwiE!?6d+jv!ZqsT-;*HF zkbFsZ#1c@_&-|P6d|~~ zd7L@tDE9IqsD1lVAt>xyZ4P9_Pw^p3h^p#(WVUW<6mYqrXw1?|r0v&fX5# zjs`c-^KDA;nb_K}xymG5c!2$`9o5QH(QRp>Z z-lsuIB?OwYDy zYzC77yJB}MZSjrK=)KTE`F-0mLVZ&d>S#2o1E%yNUxLuV3UUyOj}J?i5t-|7rRcQD z3guJM?DC;ED&=T&rU^f`Dy8Af+Cu%r!Qp3&C)Z-V>i;ff&xc zA>C~o6~89OU7qAV>NiR@@_CV_B44osu_k$><lasRXTl@zZ*sLSqrM^L*l-Wis5kjR;XOasCf{aIt!$B!RBKs|5$0rl-DV-E9+b*~0@#nRl)TH)Es?kRCH zw48mptFEb|W$oZ^nmH>O=VzH;V|qA^sdk>@AYSM2JQSv2g<{D@<>zg5dZ%oL@b6Tj zf&fPj-J_!F%}Fuuc8+Cd^X=qL6U(F$Dc)c59y5d^ex;2%-P6(&CK7&%UVi-t2WR68 zDQMA51P=oTT#F3GM^kFM8)}?;y*YmghaJfmRS0@W%;X|lIQA8eyEQVhn91+r{fa0- z2%kL3qnff_Hr`6{sZ#UevXB!tEFTY?(Q!3Rw{|R*GJsF}FwZ3f*{ZdRPdGy^ZBw7* z)@=I_4B3@Uzf#&4>a=_IV{@IDOH#rK(tajqVH?C0J$-cLRH+)lrU6gat-!-xt&;r^ zm7+vZ3`dQ7?U|mXG1r?rNMXEBg~3614Jq>O?wFgp7qQ_m)61lJI-_J%1hZrKsLVG{bBHBU@Z|CyL2at33{_yj-M@oy6IgAan@PSx_W&SM7`CE z%IliiTw(yv0d&XKlyZEf;mJbS$L&R-oyr^3Eywex1qRQ*vV9ROdF*PZPAo4dd_#j& zOG|5M;w4QIV+LhHipZ4~2SZZs9(}v=QcP8MFzwUQrPj*pyomuLMcWhF2@Qsp!JErL z4ng!OO~Il)!t^>KLOApEE8b1zaW%D(vgV3L4qSYb-6L8E}t zD&LIHrBo8K7q>bI567>VV&&(!e?3u`|NZ^z@1JV@aB6(}5M4J~e;^WQT{ncNR~u%0 z)Or{yboM1$+np|GvrQpP_yTjuZ>u$?yUd-dV`rkqm@tR}KIpz1!w~n_{lKv!6us zWu&`OgIBaoL(h-edF7G3>E4h5*}Yz^a8KQwP_E;0P*YQUTLiG}@RpbgCt=WRcDObJ z`f1XlN1;Dbek5^;Y3{h(ow}r-X;*&0sw%NBdQ(2sfVcC=2u~4iISI%8DnZQ>^otRx zhv1lC!T>}L_C-1du&a`@-fdJdJXPZ`3;6++#=k}%vFT`m* z%Mx6F2yV-E>3u&J1do{fo@Ej?#fhA<@dvpOQT_hm$_Wm_(e5ylOK9m^-R$nfz-R*U zz{``7G`UAlyXBcvy`F!{Jy_coogNm5k9y%MnZJ&p3@+=R6BZU;nyz(+jC85T+)TqV zdunRw5Y?C#8d7!d2QUen$1Yh5*{7EJxG4>K=7#F4gW9W~tWxoq_rW2q>zvqY-HVJq(@Nv! zstH9Ly@n#@>+?G?@t;I9yA1}nAc2xEV+|s66IsxP#10jOa68(cuk7BcUV&ZrC?u@8 z0}X_+bIRV?iRy;q?i1*wVx3bDi%VN9r}xosnGX}WNWId$x{{MT`e~hJZrf&#hhg8p zdpGpF@~Th`{acNzKuDlJ(%r1s@j5pyn$m$kK`}x8-C>xKr4Kz2CqkZ3AtGkpF?XIT zycnTyBwrzJ@Q5m`2}jC7E6A6?kd%_{lgWa$@Ls?ldU0j5T@G)54tq-7*m+}ir}}uz zoROmcl>M}fy*%7wMa;{Y2I6Pc>zO_`=W_vYxYiC1q=v<&Ex(fo>|#2{cC53FKN++M zh@7QQb`xkLc7rp0lGjrQhfmN;&ywfX5E%v474P7g9dV(Px z&3kikJTd((3xw=Z_w{k^18OK$L?Z!+3=6#qA#PIqiJPe24m}Q$aeJILHk zxYM-6H3*XlyzVqFi~QDESj-j1){5+Mf$!WOsqwXU6+0Vh+x!F!5FU%>GHL9i_M{5* zpT{mn?){$SffaKE`u9)v9dd^cW{+pK0}-4FGk^z(Ki?~M=(?B_`xBX>L_f;;eY8ba zuEu*WhhBtl2r0?1zAI+DFNo+y9q~8SIF?%bg!DW0q?F2Wkt`SLDeusCbwmMV;8|G+fw)Ytb0zJP& zXeU+Mf*>n(VqGmNtd|*Y*?`8SIaV+H+VtF{>m?Nh70d0zr(k4=^&`TFT5j2ilRL zKY#F=N9>{6!}%RJmbA2>i?*jy6l6F@?VGwuDCAbvsuCE_lb656DMyTi+od`I_r1NOyxscMshq;LtvQuD$R3-OqlXFLNA>!wetfWUX`k*0~gH zoj$yot;svtlRM6&6^nl!LAT-30H>8e{1YsNManqX>zwOsL4~f3wM7&0J?YFpdxWvl zxGC;1UI}PV;)189rhNC-qq$xQz1(&5Su8;hduClJLL7Q5fI_PL31dp&;;bV}ZF;SD z5k|H|?~!r%`NzcQY0e=9z{jsupZB8S?n#2v34A3No#~9sWabT}UbG}ln4@^`B9@c{ zDyt=L%uf^w3i2k=uga9J$P{aK$+aYI*LfM|n)UQyu?qUI_s`VfJG+AF_T>q5nNp*@ zd^J#DtxAN*_Hneo)sag$EAKnAe-_MpO&&84*kge+y<%>&yP58r^a3SkN%H0|r}sDC ztxu=nedRFjaGAS!eXCinW8(}9=rq?LF#szw!@-khm_-KkPq@9EfPf7y{UL$@S@1-c zTF4{Q8PVT~Qkad2=O)MJ7+Fr92+txo5)h+$LauPSnrxhJ0>yHG02@Tv;^@`Q&0q1( zRv-Bxt`CUchvS`A%Fz&g)kd64!ESSo*xZQ6(Fk8>9wy>YrdQ9CdhhjsVs?M_j-2SwCoc%k^qcb44zXzCvaZ5-fUtL{2yIZ!uPG4Qf3v^3^4+Ea* z`;K_kT;Uf%eyoyhfI1GCGu3Sb4EFXS(*$2z#Oje=SSApvt_)e?^uSHw+E3_bK^208 z?e@n(c#(S(8*X$UdhV%;>u&w~!%D|pRkLtBP_-N1+*R)5QWhMkrO8|nj0|hTk;q>j z3I>$%eNFKkdGHJMil`^?0SYeUeUo$R|Cp5f{SBH9;xD2Civc?6%yUGG|yV z9Eaeo#s@dv-(>OH7BRzA#iCoM@_Fq{of|tooy_ct3)2XI@ka9348FOn7|p#~ztXBW zQDp_5Fce5EZ;3B&xO@CZ?!r%=06DnXKht&8r;-nN5df~`4Npj1j!VmeTU&YQq85zG zPq7Q%E!dXUZK!ZQTQ&>6v4PAjR#YlD!3QKBA)+^1?;AXez@DFN6Nu_xjs6r`#Z(x> z3p6^eZ}cZ(snn&nj^IN=nslviCa1{mJ&;4|_|0hVea zOuZDa0;7U1gwgn#4Wc!yLszFIFL&zHX$lHkjG6+iY&NLqN4mcWB#MLXN6(EAocQ~M z3ysKsz~wV+>HKfzoFj$`5e1GA;ck$kQIuZ(vu{vGl)zE;57}Df-=QkUH#or#IlVXe zVEh9dWc(dD@(ky#{vaf@6|5VVP9LPakDQ99M24lcji(GnRJG3ST=&Qp7`X9BKORuv z4OLA+21lL7Q+~nOO$U-19vIBi|HA?xbQ1cAE2ET$!_vqFx&$bsDI^~IxW0u%IA29Me zL!io-PMI6DN7BRuqtOUAtuopyT^C3O??-bbl5cdaR@bKu@$}}uip10&b-zOt}iH@9G?cBJxS588L)WrQ{=F+8-nqYU^ zF^oCQV?CRUM9-MDg$dAvnMuU8u1XrdWO%bw#;BrY*GuwH9Vuxng@4n4)&u`4OkQD( zzGP(`=nO?9TEhJdHh$q6m|M62WZ?usKEXR#=Fls_+wQWG{=pQm6%xi86rA6$SFwJF zIZ8$GZMP~+?0XiUy;ek48NO|GcdAQ#zaB+`LS7s;H>=|E67Pt);o0@U zU+P|$9Ijj)&iNdRU71qg9S@98xz3GBJsw|7YpE&Tb=<9-hPjXiSg=pbuiVwNnBc(; zkA8a~H3x*8g@ZqIM4JVk%f9rkA*+8n#c&$1cDMDZ;}jU!`QS{Q)^V>T=F?rQCWhc$ zxDp1N_UPN>{H{gSLUy$^-h_9Hj*A2QPUnM0XnxfhFG=vpuYmQZ#_xIX_5Hk#jZey&oUM~_O_wxEQIPGQl76;yS#yc2`D5*;tPQ)Fkt%Z z_KU7hWf}n4S7r6j9KUi8IQpOq2wpI@ry4NV@%?AYbGG?pEZ0r`%e)%nX|)(s3*CYDeHFy_(R`m#9lZzsh>o1u&DJs*Z+6Y^*ODHg9Kz9vwg~%~k zJAN|OZD1T%)VtO#PxNlF`E;asD5J%Fa?vnP?b&|Jv9aS^DaA4;IW5NNyD760o~@`R zBJaPcsd}&kM;D^fUtD0s(q}REjG`BCf+ zp|lHDWxS!2lXoDe%J1#n`XHL3=$3yGF^5~m{%Ivgy#u9mgaSVzl~|G1`V>=(d_@@> zzNW6MzExR!;1;IviQU%V!wHa?xe?;PSQ5`o@ z2>3q!(zm77M0+`oFBwNxB(zJ8g;}i@n(=}eMSN0Fs!n%Tb>7Y^We0_2<}3A*y-#($ z++4FuRi|uDX7nk>i5{!YnXLe70_U#g*dKBsEW|9W8gTQhd zg#_ulK|y(nxlf!A#lwPQ1}u6-d%beCv1v1}j2qnuas>g%i}AB2MY8BEb5gz_-9TkU z3(+V2TvJgMN{Km*aex#5DdA-0gTF{`fFAx^b@=)9OyVx<%*twXiIL;HQ((yN~2NL<^%2!Kv63 z4EDC*Jn)C!zUFTpNZiglh9M7-fyTL&tM8(HavnrV@k;t8CaL6>f!Zvu_zrMh7SMC| zgyHi{-Ez~)@^&_L>C-CY7fi)&Q~NEV;9Gg!P^yZ%6L;Lln{}cEpJ8}rXUC9xQZtQ~ z({^4iFPns4vUPiiaQ*BfvYIBLUiS}%bt3v91iA(MS+G67zZe@98#032EOR(rz0xsf zB5{L%u4?@qN8CUDgcW<6LX(4ztlT+AI{KcjFdpBdTwwwZIM)YI#Gb_MMDoU=+23a3 zrg=xIQ>z7uRgb?jW)EqrwI|((-gt;lq;fZKI=lhRV!B~ds?LNtn&05*T|a^DTT_!J zlg0jI2GR`HeVf`p>dre-et$!YfOT`m%lhE7KTCNbg|Iqy=E^eTV7s9))*JwkQ9x@M zFj4-$Qsyo7&r{KDwE)0e{boNnzyvWvLc;6d198jLzkYn6Dm!iM_earzxjfCFSISBT zmX&}JS}^C#tRrCUcd9-O!i>s+?svWLzd?^$GN38n$+C4>w1T+Mxas+rb4#^nWlNx;*KW%*#>sQ#v|S3aw}1=QF*IN* zvVx{vOwOGFQtSrQ*-?skyzB3rK#-xJ8;q7RvDqtZEe?!#DQ7pIJvRt*Mei04Dgpy6 zX8klUJepa`@j@tJvd#^Nu|gVnQv-t9Vfd5`Y9fsm4yG`2Z#1(0r5qH0|KQ6`N(}2i zq!^!TU7wZV)lEioaE3WTMJ%xjQM6L6gnV2i<*=F6B%)Jw| zK{2FnXr$N2QkPJ~tG>2CgrWxBmHLrYoXShlbVy(3Mk7IqgvSmxzktB@t6;&`XVF|@ z9pIN4>c2xjL=wdezdI%yTp?m|w>mIIm&s@N5QYhKY@}pW7WU_qq?IFubu}CVZbX?` zebmSxZ`vlhX<00zGs$ZIuv<^@Wcm+pY!Z@GVAtnFg6><)2X!BbBY$z<3}}|ToPJs$h%Sx+h98rAn!(J_IxIk}fzn*n=E1!vhe>-JaBwpcttc}za>y?jSm}m!S(3Gdp^~!LDyMbh z69KVhS-CxfdyS0|TC5HuzE@5bxamI&_*{bBN8^IqndWx9l(u<*2>s@Smhy{6_bV3Q z)Q1YO9}O;zXoNgi|4haqaW!|(uf7;22UR1vsFz{1Q{lI+EO!^~7VRltvF7dn*lHYQ- z!k{Gz!@OOj9h1pca2%~tF|(|nCFM*L!=OCw=A?gURj?0Dl^IGiLo{?jUj1`WkZQ~t zu^1#$z`wjKQOW?#=^Q=wuuA~rE|}isyxvS~#h5M`v9aB!Riq&?nNO{zxjCx1SeA{G zvv6f!fiAwL1_CK5m9rrJ_!;aCQa@!INnt>`r#5hi19=t~NGD7SPx=^^XHu7MxZZEs zo@J>8fo#^~CtVbOkr-$6;J=@m0uCSA_in~=!?y_VnQ4fWvvt|qn0LO%GTPRV* z_7K$pd<)GS{|CmMD%7X_BG-4WW%b1aWA*Tz^9s;Q!X8;V1KLaTgAH?3;Pf&QWgHR# zpW|1h0X7 zFP|wIk1VYa zXAL#2v#*`42_Y=#0uEOi$WqVM1LY9bnq!D~yt#fL3I#!^$ZQWmb_smQk4ymK9Q@IF zb2F%rxS{iCTPl=~A!UeEU)~>Ul8D|*b#NyEcks05GD29yd9!(Bjp&hd*Ber%s%{wmXf-^qwHZ!XCONy z{d{r#NhoU9oHaqKiF4fhV-bFeIG_2es*(ENwrf~Y3Hb%Jg0n_&?)o9E&9f@_ zz*1@26o+diqFSVYJT|gc`z%3(G}W8{-E_I}J6y^a;xgtj&0>?KJL8X3>w(5CCc@+h zS~(gnCj8FFpLFScO!s5tGa|(<^Q(H{?+OS~{tj(Fek6G8a-u7PnPQ0*1>Mf@RYfnk z4iZs6j*xz=D4FQxz;*RUH>Z;K*ZNg(s?FKcfKnvDJ)X@WK#Y>QIaIM!H_8g4y}i{=~MaW#CN+0V+*^h)A?I%8$_<37+JGu4+DsVJBkiTTiz zthF^lN@%UXfG6t=+8$zPY&Gm^Fk9$VnuDHP7nZ3>M9@<=K&141w7zYqP|cYEn61!k zcH~#RYZ>Zew7TX6_@AwC#~Sd*4T4-%J(|E0DtZfl;a_^?I@;y0pd-V@-@S?(%GD7U z)0SzT~&S zq;m?w^E@0JS=Db4dF!?&614VEXLk1rxcR%LE`MvZ+_GOqqYV6}hj0zZ8r3zBzo!{+X!?_Hy;n4=BYv0->xvocJiQ8Z28@x!wmn*5*I3J)YtHRX^$QT6%_g zcA5c1wYUAI7&)x!NYX8@6QQiE_{SE5F=A2+xy$72-!$<`=xORfo^XTUW`OtpUk=Cx z)AUJ@djCBGaD2=;jcB9(x-<4d4IqND*TD9Vf&T>^us%TtRZXTEB#pVia&<@U>)X4# zil@mY9DVOf2T;&sT|m)Xb+rKlUq0*qB}zc^yM6&&7JQaW>jj)nC2lw~k_tDH@;_1P zOqFbrZ2j|dgXQ#{eO|OKQ`g_C7GVAIHvg|4afUAQrC;sV(hClrr#O1KTY70- z{BW<(uaNXoB3`<&PCN~kr?^jza(?ylSPx*j?kF3#i0!rlgTI zo|md%@J-DaPzm07`jaT#)_HH)wMs?H+aI(y+qKY&3b!?G z^o6YP_K)U?v2ux-3{xdW3G$4Mj97TPg9_6y@5>^V3tOZZozaD;4Wha)@YCKfx8j#m zWjA{66LOd|$7~ln+P#`1XwXab=HEgL7M>Ycsg!I;MQKDaqH*gYEeIOtrlJe0PN+Fo z1op=1S#-Ex355f=%EsV21G7Bc7ca!h!WjPu1rMYeUhy8<5A$A0TN}ch5@f&cp1+7$ z<$Pxzr=RI&b42wa&};M?m<

{An>6a>#dL3U7yy zkkD%6lTKA)??=y-Q6AtpAc{d(^+j)&!{{TYx>oP}%BnenSRL2hEN#Rg9G2;p{wmkG zUy=I?H1D7N9~R*GNXe-Le@~(%$5ANf{00<2>nL9&Jex?9 zads}Q-}p@OKGnJDq{^tq<=rH*_w-+#5H}9A5D_5d{OxSw{V*R&baektbZY+{u2!VT zh(fFu=Su3$)5&|#FeJ@8_PlRK7Vtg(o(}v9&yUVQF`bnn4o*+XIaw@mb+Ao`J>fZ=3zD=Xk#BvNw>OdB&N}pR7{BDCQ#Lf6!x6mGx1vmJ=|S zgVSOV^g)a1zF+bDZ$I5Hfk0EZ2r$ezHfo7 zZ57ZPxaZGO7hWCU`IE*UE7p5fLuq`1Cvfh38g~H%fe4`?0LlZr=v>(@gPp(@8n&O@ zWtsDc`?4HhqbE9utlT;Roh!9iXGq!UuNW}ktB8?u_+B%(-I2>E?O*Rxs5arEo^R>_ zDpOvy%f_9oQJYyyUJpJ#T-x{b@v)q&^H9gAYiLARr+;hAbGenKo_e~ww?`rfN_tC! zMgWt06qxO49?7wQ(XiTkn?z_3(jvduv%s7(ODp$%cGfKQ{@TY75uND#t^7UGI<{ZY z(b1h?2WTVB2(f_xZ$Wp_7ZmTo*YkPttKRm^%Q>Q)SLzTQ?d^CcE;l&U-{x6c0@TQ? zA7JAikB3%87r&bj!WB@9Q<$Y8w z3G!J0=5s6tYay3!tyW1ITPD8%_mtA~M%*2mE?RP=|JM-`8I)M4n{Fj6#W*>o(^pK=s;} z#s4`7m{q|+aMJ=LorVEtnYZnYp;nj5o04AL8 z#1&uEILM&us|ObA=d8p`A*P;_MlytI|1HayL{P}!Z_D6(pbDLIahTh)4&A2ZHHrs5 zC7K`b(R#B|p&u!-ozWE^Z?H9(*gD?yYWIS-)htQ3-lV9K4@~V}RKvmiWW0;pP~&CAw;WnGxd2M>Myi4reyb0`9`^jzTRMHN z3@mYhDm0saDJOyS*X#6P5!Z&oB7B(W3U8!5n^-6XW3Utos3t$iwZgO&x1^&$iLDS4OObhU9ZTCD#f#H3c?IJ-XF%tF;5tkVXOz>^r(_ zV!9j@k#*LIx@?lG*Hmv|q%UAG+oE)$qk4xr(fPZ?NFpx(O>Tu!Xpj(SGNHp+c#70w z8SpO$D%6LXgHonIDTp=79ekDbdieby7#(mOt^|OrHC4)qEoEH)OvzPx zUVJzA(_?QcG1gybM_rXT#Fu*wmEyN<{j3i+)qn*H2nkuVGdu)I0UaiZyi`vkqq0t0 zK2Ze6Yq16Vm(ijs1~7&VaHk#$agC2>wkU=p_Zb}M0RjBtaTw(eyr9Uh*c-6f@>}@9 z{fQjwjYm#Lh^nr1Efw%V8>{2c;BBCff4o_${po936)in#>xg`*t{Cu z7S(N)5HOoc(rtXX&wxX+_-FO6KKBhHDy&>ja*OtaQuUiyf#zBQGh|a=iNm((+}*4g+@)Q@16kZwAAA-Zx@qFFLGsG1#}*|FBN$z4ZB-Cv zRm^Tg86v@_l63T|COr{H^Hmq0?J?OSagaiaez4yTD z1FHd;e^8|%16~NQynAfh6D74*+plAS3tjfb0t#BgUAM+NifkuO6Mp(ZKxsX>&ukd2 zYS_uq9!c=?(sP9&s1pM-pp-p<`*(}&{dqqDY{qK8!~T`>EJ$y3q;r+yBMz8cf?h?E zK#UJm<-l-A3-MyNXrd5W@reoEapYHUae}u^KZ~!%x!#9F7V1#C&!5@PCS(J_z4xmA zN7Vty*~r=LJrY@A3qD4EFEVwfzUM~k9C;s5_DT+Y{N&2~c-gWj`I$V&S)a&Xo7&~W z6DiE-P#1dCJGBa?Hv&fMg_tZyref=Sa;mwbqZQh(D?3XX*};g-`Lrkb)HV^%DmUw` zH;Pc1;;TMQe*5bor9aS_E0t$ z{$sG0&OhA`Ja?*yBh}8l-_3H!LdB;@G3zM=s`|DXc&+W<5>}?nHw}E9<`TVTG4?^rZ;vqDFK-dqFOlq3J#v$IQ0~zJ1y1 zG>FdY7x_GmMhu2qN9wk4B!v?RyR!V14CWM-?0WeGABu9(#Rd3lkq5|Idq#Q~wMX@S zvlUgzDL5JQ*8JM}8S_Gic~4%++w#4xp{{^S5*=;wJ8p0&D%h$!#2w`>+#&^8)zyrq`gO2WRLI8RCin;a@CqUP2mv;6itueuT zf^o=-sM}#Y7CetN@fkDA^pSMyz^4jMkt&>zQGz2WHb1As+oQY{ktsS-d0T*V<5*|; zTAAUIw5Zefq;f=y*!9k5)?qDD^L63zeauJUJ!puDrY+(dy#k&mxatI(q;a>hxXX9F zK^Y*g&mYG{`R{oKpzw5MmuV;)8b>i;l267WjS}HwZ-%*hCCLms9*5umV$?0m=*xxqX$;E032gA zvb0J98W@o<6hz2+RQiS~$Y~E8|IRj?1&TOD;Bfc6*0FM~TFeyx(+T&VPYeKk(HHBq zqvJ?c_hb*g_@2P^y;Z zYXD5ZQIOA~9#BQamLD|leGVhBuBRh8e5c?0rL~A+D5U&;&~+MYlF#S?-=mNlG6Q6r zrO;3GU%NJ;3wkT}v;~Sr6_H>b0t;koABpZ4F}LZJUN8sEse0CV|ccD0=`as#ofoV@t5I=m*0jNX{63|o{(e_#pY ziVBMNkonSg{C!F*!= zdPLn_g}580N{1qX3W#f?cpG(F(D@H8ASaf(|G&q;9~&;if1LgqX`sN1dPf5KO-%(i zu7QB`Plu9Ujx)e|O#nPDM*qOC5Bf8x=s};rvdlEg*cW>&P z5Snx0yipNQ>a9t_D1Mf-x_Q}ddyBOT3rXM=@+#tEeAY94^H>cOQGYc*Fd;C_uu`a@ z3sK4;>n?~{bYa3Fta)ypaGN2^=28V|Y|6;x&x5Qj*IR3fu9#8}MLbKZB$#385N{R2SeZD#{rI~v1ItT21lg=H zL0XIe03TR@=6sPvC*!I=Sfc85FjWf;2Kn?Km%MCm)810L6)xo=bRae2#-<3VId7{eE ztxQ)eHok#U?h(vf>)|B^cll_RIYtHsH#=HK*^S^M+llU5+!V6qz@iO)C%Ra0^q{R? zCTBRBjuuDfdk4qO`l_fpiaC*&BZptp#Fb1*#7l{WG6_vnDCa)K8<*!CrA?a!&sbmi zWm4~@HN#I<4k!JV>DK}+1O0MoxO=o&)w~IENm&SJfM&o9q{bRhn$+!S`RG`k$Avs8!9OUdytas=1Xxwno}C`` z+0U;OH!&YdmE@bbZk#){2dw_^^*{dujD$GdTMzT%o`V}IeDQF^A;-Mo_h(Pv;DSxL z5_!6{QJHNIVd+Toz5{6cdA29W9UfHkOeFx&7HDx0vgeNMs{;_cwp;b*wuyiGBS#`A zu!3zZgTgmxK0i2SP^W|SfN@mk1@ewe$6d1+_1HsTH>5}DoAgrm#z(9vooEsS#gILX zbF^#-EN`qnp|;9ErPydtl=|h5MF4=X&XwIC48f`q`E@LEGe`MW0K;Z!0FbZZn8Jd9 z??4S*dD(?j?Er>C8mQg{BW5aC0~n{wj}c~lbu6dc(ReFnMz?aOY#GVi4yjw!c6@)? z0wLXK3GeaBRflv#9&q6U0^Hb%f5ka53+kFDfZGNA@@C`%_hZ=Q8Lk}AL29+<`vDbY zw?kX`8ZNm6YtvzVlN~`sCdc&QX!VcV1Mym*d3rtkRhI8!5U`Hyf;9UE(@gY3UYp+gmKeDEMA)r|dv{nbrY8E^+e%im`yP_&82 zfsU#H>o-WA7-~>mVedPFwprv={T=8e1?0ZZ1wvpWp(yOX@_`*CnSN=gzZkyhbd^E@ z6jW$JB6nWwiT((Th}!Ok`Y5tB)o>7#~kTM>{a1Wuf zhwKeJ-M7XgMcV~4e0f}hEA6|n7h6-6&A&xRo{oW$2fZkvzqQfYbeu?3+ePRu<;BBa zAwo3BuHQF5`}koxj9D*K2Bv|i7@!<_I4J<}A?H)X+M(i1*nBaaAc#qpc59V{FtjGNte&5NF#Dan`gFfv;Y+xiS(}7dE_o3aQPZqF zndT2ScKoQ5ZP{0a>llqFYPg0Kdynx{caF4kz%BG;NEIsj_?V&$ekan?)2A$~LW@GO z9O+He@l9C@vqomzTB{CT~s z!=JO~M4~NVKA-G;wrN#L%L+6FTh1EnCx(x(uc^{#e}kP1SLAozVA!8+kFzwK4oteK znMV{9X-*Y|B|*hXup`Kv-6NrMqj)0A!BuX~9%TDVWB2Kk9hoUC@P>0Bxx|xvwaB_# z4M$LWrgM4$6BjL-rp=zcUykej?axBrGh`R-B*c@V&fN@I9NVF9UY1_&i^@!&dGCMt z#z&eWENZqG00YJ1nlf8La)5gAHv>O;d-*%Pe1LYqItp~ufq^3cuy#6pddRERnJz)R zx@ug#@GI=b$brL%u`Oy}Lhmm^cN*tuj)PR@m(V?xXMTI-?W7i;s<3Eqc=Y5LMIm_( zctL0JBR!$wOMQPgG|E!e73^e6La$io*TV65ICt`IuQmMC&3uAATz zyZe3maR-ns+!dlqCA~`z%VGm!Mu63?j8r|oDfbYLSeR00{W;=V7*@NaWP^(c87!3K zE$MfAmof^YeYf{!)2NG0^q=fXkAP>WG5Q4>^ro#~CxNb!eShN>7zPDgA8F z_P> zpIOU0+O-Vf+#I&)c3#jf9#%q*hURuy+{zWexO zXCS-Jo#Wout1+Rk&gLeLc+V7A+;{r&g66tK-mUdlzeZr;&B-CU>&i^swS96=XI)Q; za5R&-_r)yupPiT2D`Rc;dvjiGj(7C!1AV-u>gi!v*fWn;k3niEmeQV~V&vB8CDnMI zjaUih4)MjJ9{CX7-2PH~9MH7+OWignhoa^0mll_D2k^#7zZ?1qPHKKmPYZ>j!k$K< z;JAWCCDBO+&A{z_L7Bz0D7!q$eA3-?|qo1HP3PAn|sJ_ zwy4QEm2I!ToT#VYSDe85vA%GmUnGqa%2v5|YoG3YGT!!L6<;J-L^W$=S==%#-*V>O z_2nxZCqxb;)w{P&@aNyK;@_1S4Ox~up5MB8E_Iz;+%-MQnVgU@`cExD>+xlyv;M)o zvKzCK_kMkCZ}z$y5n9NCP|DoH9Oq5X%gtbH$!HrYTPJ(MTZrEqIJ(wl)A{sjO!8aS zSHENrpssW88*sqv9I}5LSKt3pLtXx;DD|`yx#I@on2jtPM20S)A6~3ik%AV$QYFM~BU}vb&tLN)9~wMK1D@UVx^vy^;bd zKDIH>Y{%XVo2;2CHSDUq!DxQ~%Z&^|u~t(WN!r%<<-RPMoLcpCWs8HHtVVu!F;(FLL4De%1~=rrA-4j>WcDMD zqq!aEX^_XKpGI$#AZIUhS1fo%s=TVmpclkNrsZ91quA zD2uRdOJ6@M0j;!VfrdPrx#^{={K#MT8y!r^N7WvEhW7MJsGUSB_zhM&| zyNf6aULGkIj}|~$qWe9Doct{5{fo>RMosWLD`JVSW8v)hvA=sRiB?04Nxu_xz<{If z6dZniX9#AK`&w^8-tVngms@qX`!<(rBb9#%pT$*11Q_k1^9a6bpE(D!nZl}Z8nZOh zu5+XvrBOf&0v=jgH6ugwQPCk9{*Jl&3 zy2@6thWWvyi;M^{RG56MqJ|%s47`JHS;=3<;{3ciQWvxiXtL0Nb2^PWp6;-GHC#Sc z%50IecwN6BJ9t_D!spbT{!#D?Ck@8!3p6-4R zqwiat4vjk3DI%(xr9VCi!rS}3yL^(t|HO5N&U zN5&OLapFsPCh|4k#FPEAQZIKv)_w;TG-@x6XirVvjMPgk-(vS^juF&KjxRM?kneYo zShz!IjI}iG#c{!SlC|}TSiudEwa7G&!4n>Xm>o{99~jYHjm43Vj|FSoCR+KsF15U| zP4}{CE@v_Id}ds19@v0utrg_g%8z`688hulR2c+m9?2Ot@%<>t^>{`(lB;vJI_M8J z-!i0J()S9V2~gYsuenh>3^bjlFnaPG1Ek>+v#$Qm54h6zhc9$G0iSJ%@CSsy)yA@` z2ZKl*n$FIc7irkOld-J$CpPKqN5;r3sqY<{EUcODDLW#F^~0oqm%zOFTImd?AT*6e@66L1FRc3xcB3rsvQRJZG%_H*ZaKvvS6+ zfmj4p#C`;~fT~@XC-dT|z@8ze%CsSP8joQL`Cu8J8K)7=$Cgxq=V=lS23QB^#H36z zM^_zHWM}-*y^G0yMKfr0fr>>yZmN>H5YsO1Ut>@aSAQ-kfVvPjV4bKGv^u*H3@o|IdP-D2WE3T?dm&-wag40WoFIYuQg6r`2#wwQ9q>d z8_naOa>DD>Oie<3Fme4;Ff}912ycNnH5T2Iy)L40I-+wZ6$xU!0gb4I8%iwATVd5T!d7jIByTzgsmtfIm2saXhRbgpPq^z1Q) z3-0@=sKQ*PBjY%!USNDxyAHYuA+hpCZjO0wsPF@{71R3m9?NgRTe@)P8Ye_h*cKVkEO*uZ9 z@z}z~$(HlTvQE@^J+~Ud8^pzEeXn`ue!J3!mh)X<71s}o;n^DGLR+dvUNz?Skrk8H zCS21wYtz*#|D8=f;$(e-&{(C<#ry@!zfuL)$12xdG?kI>W#2#Y3wGq2sp-@}#Keb$ zrDq%=T6f3uv91fb-ywY16q%_E=J8sHtmVoY7H7qSFEn+HUojEtA!Nv#F-_|p%K6~{ z9#05zO`i4v&5QEXgSF2Uym*HN&?f z-R&zCO})F$lXQZr?k&q`;mo6_HXu+Z6CN#?by9|pPd;qqDPy6hb@s=$0o>3MTW8Gj6= zD=T^bwv?NiB;HKqC$jdnx|DOas_Asx6JP*G&_YCw7*K(V)TP-(^r?-3%v zEpgLvWUkkiuX05SThCATVbCbuuV2pbl)yXs?~j<42CMs%uIta$igl)6$M?p}5%cA* z<8@zAU+BYGj$EKHg*YjqZ&~p2vy@%d2JPn|kpHdw zP>)vutmq$Q_-XG8+}J(aEG7e%Kt}_=M{l-w*BXlEZOX;5pR!TEz4|%d>SBaNQMFep z?7g9!UWV_nfn=jh# zl_MT0SMJ_eTjK@87)tq9YBNkn>vzs?ku>M0u)Tp^FpCGfko#dZP6$1%9_@$0%N^PJ zl8fp4B($o!y`f_fsWTh7PTurey);k)X^%Z6zrIF~)uF_i4kd#Lnm|uTgCgZ)D-%Xn z^7GPG54(YJ2RB~FLPGdZo$>>j|4erDPNBy@4|=!AtIOdIHSelpRx)*dL9UGD*z-V} zF!~J7aq2xr8fMZx-hA}!YqFm0@h7f+8v`#w^ZAyORG^EU|I{tK-udh$PxUIIy>`8{ z(SBFP#2_jM6!o_OQKm-Ya>qOO4T>J09t%9kY3EZRz$_(}QxLtEt#no%E9OWZ%MbT@ zeR2(`S(OpCLkIouyVr7Iv9Nu)GU(!0?TYZSYXO6VirH-qSJ�^3h?kFr zq94Y7@_rXgEvKO@%%SYR0)WZe>E8_Moy>AN{!zl&a&+VAC>_Hf-}uit-b zu5N+3{Dkp)m=gQLPb%dH_kwR1u0(LQ{gJl{+oaifF}Wwo(pKc1lHVqdo}fX~sK0da z^t_>}+x%DDB6dpacE1=;^7H!0h3onodc;Z7maP>2=HeC7fK>f`Ew=^rMU&CcDzkEj zgm}KK`VQ~XwW$1sbf5WZ!1=r&L0~lt?~BW^>&-VBEyP2w&*qwH`9qYtx@aUCQK!nC zqQ945?Cb{PV1La8ovlIVU=Yln-tVXds{s5vUqAHi_0EdfUU`wT2-a^e<9vnpuv^== z9__8YyKj`h($1^y)4m0hGrZ;RI7?U46U-vzMCX?|4$OJ)M;saqzg=e)4xZ#0a&nw7 zQJ@VW%ivE6)3|6p(Tski>BY1hSf^S!bGcR`~KCa$gFu5$_?S8~QRmqyu zme&weFy}o&3zL0DU|bLN)UoB4L9ubU8}dQeXY~9+d7r69kZo(W(8&qzGj!B}P7AYK z4_5$*NWV2b_TV`4cfKlUKjPbd1CyNRt4U#AbDKIk#_H-W_isqt?ReF-9u_-9y{^p7 zok{Y|fd6q*%*6m5{WHl6(xUFjMp);k|MoDy#_4AlB%_K`v-Y2$!^nm+l)hVh8nK%1 z4w_x(wqrPsbjel6YHq$P7gEhSy1ru}zSVTV9YdV-t;U&mocMVBx}aRJR?-LQHy#(v zklVW1+I06^HqP5N*P>fheG{9C1EJYkV8dBmo!E|>OTWn7=v*_G@WyPOZC#{+9K2rO z%cAJ>tCmk)L4|Rq#%8FWfm}+8Z}mZMS(~<&{@{D&BfK-d*LAjxUQqHkoJZ zx2(`m&$zQWX)1oZhtDiJ-2*=9I!(I$3k=lN23Vwbq=ICgT*h2s^;Ghxh6HF*rkaQ|vR_uF?x?lw(FcDE&qiA8| zJNO$HLl2bpLz<#KUq`fk!t17(0XJ|&>&PUolaE|t#HR<{kSKf@SAUemS{?~zp>Q_I zJOR&p{^Adf6gj`mUhQZMhZLml8* zja(zRnXme2-v6qMY<_Cq?XN^0l0mKO=G_(-?eRn117Q)iX#nd=JK=%CwX=SgEukG-?dv)mpIaoA;2xID2=2-pcA%b~aJ?pq)e)e? z85Kh-+CWM+0&kDrelZUlIBl~epr-!BhKL|B;L|M?#|gSRd94xvI!ti9@VHv3uut7l z(}*da{bG+Q!0PH(o&C& z4i*v@ub>{Cj?9tKkGdq`tx{rBG%HwSO{iczBPN_hh^TaOnd?z!{e-s(vhvpc_gn)yIq6T55Y0xhdlL zSem;92Ol7zAG!BEKZ%~muc+j{6y4vI5+~P!Yl~)2y!numi)Z72EjzCrVN-xs;P0PHZ|qbOaR#m)u0T^ggVi7`@^O)n7GC0!)+|2#7t2 z-3j2zOfaKHu5Sm}wLa<@c70D5L-78C`9&&>P#a)GCkG9s)Dq+BQ|#*8-zlHW`QevzBI!=9dB%D=>FU$6rz)upBT>&3f7;F{=*3jYyiAH4?UwTJpZb->BRdW_(3CK9zd32x zS#-H9V)=ySFstH)s-Vyf5%OtK6@7cv&4ZktjkFcIzBr)bX4Tc{6Z-8i#5q3d1D+$G zLzdfkz`w6Jm=Q~S*+4xQDbR$Xh8?A|a!*%G82DW4Pecb(>1D;P94n*hZIZR>$L3J z%NfE;gd3s&sS{s@u9Lf-M>w-4Lp<2{p1Hz|=fqpW+dwg+lzAC)%f#@)R%S#228}O_ zSiV2Tey{S2BCxqvp_uLdhqI>z7w})4{jI#^Wb;qWABEK_=aWlRDOgzy*w-Q#;O79YrNqM9|6|CotupnbGIenAVE7}ykZ*>mmb13 zQC3o)q7`)Y?h-5P(;-vL0ou5QT5uOMf)<+@udKKK7W02xF1)F$*q8g0xdrs=?zY4s z*1xzumWfT3M=Yz7vhV;z6L1=?N~OV$;D9HOv{#4t42!jKOdK?OWB1Uw^p?gsM*UlQ z)YHOu;s!7Bqx-?$Mj%}!t-V`&30(!{3|l<{!3qsL5Z3jZFE!kl`gsp12Wi`vPr&Qy za8PdgQw?=47kQ{X+cafoC~+F=&*ZQ8_hCc0-uB|q?!5$ApD6{XV61D&*c-Snuv=R- z_cH7p-QftBmN@bV;ael6;ym@A6(=AT z0JhuD!)H*w9JtR-+DLRi;>W~Gg#gP{6&DH|pIP{ILO<+=DI}(FMpG6%Q5-G6kH8?G@YdoAl(c(L@0cJzO1$bzgcKKJf~kKhU{^I zM$=Vdz>@i;!oEwNiZ`ZGNCFP~w*ElVxZ#rH&Gmbr(R6B=zm-crT=m< zfN^OFf`^xB5beO1Rn&U!;v7)7a3jvdUlxSljeP|V4~_^ywX}E*I2WJiz_|e5H*9}* zKWY}d;CvWw%y09~40+-yv-+EjDwL0oRR6_;^bTmW2t78nI_MxOPcEn&{WTB&n=@ZY zmnP7j_m5xb80)VLUcT>caN{+QF)dIX)CVR(Nk-v({t0G6YX9{Y0M}Sx;0_DUz{lkR zzuz(&4qOwY29-xmsK6w?%z~Mn9lrYneViRi18d&=#Rmbw%j1ND?`eN=lEhfEv-BzH z9yP*So|5j#|7W`Qf4m?%s@{$YOw)U_V*S>MCfipueV|irgz<{ZcT?}_mliT?YJk~& z%3qU6(BkrW3(dH7TCX3#caQ@z3KeL|T?~}S`QWoatv=33M`D4Lm~XjuHXEID5^+!P zx@zsAnA?~B2bT!Ek!k@jksOv#;<}caLV8Xqa4ClnybM0!|Hp3+-6`x)twGRdN&N>P zFi#v^U;6L2e(Y9QwnVfq z7_%QiSUvdLHCS2SP9yMQ{Yb3#NJ_@XLWu*m@Ir0cf6w^bAmgLNfockUraaEe|D5YB zJGeiOg;@_5a1UXc>KQR7vJOeamp?|L;juQD(kJ40eNcKp62?xJax zzO~RmBwVtRX)X7gj0Q5!_^s^Pu(1cypH5$M)z< z#tYPG1zj$lI!4LWx<{V`Q2Px;{!!&PtEDK|W$jC@`s&SzgtG^3X@C zNGxw!G^>d{BkCXDlkU5ufhPc@G&SNyO4EI{;vcy;Uem9+y2JgW=COd5X1(p0a*Cvr z=F-Rs-B;^tO^y(WdKPhWJRPqHN!OxBM`vmz6(1Y~m-a3+uRtF`6+{(t{#VZT1ryL> zghDL3&A<9e3$E7R-s4iysnh=cQ0J9gy8?%Mfc}p$34k%}{C8t2z;qZKqWF?r2(``i zl%Q$|m4wDH_>i)+^J~m_n3V^JmsPg#gU0LJz`vf<>E*ZwBz84;DD$oVi=;7kKZ3(^ zEO0(vSDSkNSWlNq33>=MjgiR?b8A8`@;on#>pvRQ-@GX)%JUgb-EXhl8L56`QH;lM z>TtA`lJ{zOfEfSK5UptKn51L>7|B}hl6Is2l1j_+5F}Q|g1X{EezKO_yDW}*O|6M} zH4h-|gEiXLumDWX68rX`1TC_-84(trgbO|95oWZMBiH{p+|uh|HMzTQ%61fHdH5*$ zeBewLw2py+sqNTtDa8^$qlz-;O13F}BdT|+@gb}%1T0HnjJZoKqr1?BJJ_Iclk9^-ML6q2}7WPloM5Wn^c3$e)=X>Ji zqFlUSR;Ad`hRA~2zz*E*J2WHJA-C8JO4tIY0jC~F3v@UW5xgvM&d$j_6En6&Z|Oa{ zWe4q;t477&f+^fW;9JIg9@Fz>86~whlr~FLjNJj#KHUq@15x275STMya!@21$wQo^ z=NE<)#AR!oU<~RTNJ;Wp07!_9Uneih^{Q=e$Z%O*I}&=GORu39a;=5VGkjSKhvZF8 zAzKj;Vyps7r*e4zk&V<8{mB1-)EYC02h@;;777evX$`qH+DLc*@A z$?A$nw^Xw|qSK1>tLQBp$u@l-H=Z7se&b(u&_AUy z^qi4#x`|{)Qo;S58vzKvr70Kxu3k&`P{*=?(9VW+r+1?~WYT~ITfKvH=v28Z&=JX3 z9t5w<`S#7$&(}MwEuYlxSBaWSc1emIukj$T(h{9k=bpo9YOKluoi%UrY%S!I->Dg0 zqYF;yeVcys?iubBE(1aJT<+uD$}g09obg_qbcp>j-vgaUN`eT%UKh2@K=sHQ`>GOY z4^8dvl|+9Z(ZsCk2aS#YOctIN|4+#R*LesPDF@FzGT@-w69g3o5sjbsRa!eq6xj9s zAlDuN{KRP0LALIJs#pE}EQMXIl8cp4Kl;ta0!QI1c?3T?V01~H$maj{1}cgPPPdKb zc9*UoSPO(|)T${Ccr55#|0j<{feyI;h7OXuR*CpMdEWGJ%>Hc0B$_Un)IJW2<@VMH z`ghrB9?6tcx`_2=Z_?wEbn)!*yKL^ov5-rAJ_f#R9=L=`r)2VW#S1U#G)a{1OOZ@XXE#&;4sS;Or zQgXkZU@K(n$ZdBw#g?2XVt?Jy@Vd0SRyC#TlC}Mii$NyQS!UB!K(DNFOZ#DU3D;C} zZ0U2K)3^4F9F3zRJ;lp;Br7_Hz19-)7mi+y0va{H#LlXr|A^d?L3XQ@1SOdgPbr!zAfc??BD0bkP0eg+WJaZ3nHLv++l>-B4-e^osPE^JtR;6}*jjs_bM3*@J&TUo zH4DSDg|^zK`HBUXM-@CQfdrXlB6bO!tN!^s(wG14_EC=Z_0Gl{9lJNr*tsi2btQ?n zaZSMZuHomZks+~q*ISIF{M~yr1gk;*R0E@;bt>2cv^4exu1ejL)5Pdi7nMt>m> zgjK-ofJ)cz?{buyVp)%Jy#n6LNX!)eqN?X5F8iO1;722fsDHdnxl$GbDs+qQlV!4KAKy( zNLm~9DT3CUv~}{ntdY`@+S_Nypd~%Etu{W;MH)4;nI!zJQ=Bdm6rsNrA+e>)g#Cr^v#r-yy z-yvKsF#57k;UVUwKTM874F5Lq4PW7Pja?bh4qisRRu1}VP)}>HPEUQ}+EG&QLMefj zD6x3XqcQdM+M(`m^K1i$_QdLGUpLu?#9!p*kQaC-I$o28n%2mFx24mIKZ)M=(9h^2 zPH3&Ej`rhgio8e4XVuX~4n!nH9P7ryTjDqMyRGtJE{yD3$Gx$eXVunYa>*#G_`1a9 z$0m#Z(N9Mi&QSnILCkk|AJZ>M^z%t=MZUMLqUBBW z%0dmY-R>PO&o%y|C4=55c%5vys|=ZViq|Jf)tUB*X*^hs2k5k0V&D6s<;_5E7Aqwr ze7Ks1a7ICQ3pJ$2R;yTJG~>w$WbwFlhkts`xp7~=PkuUo__?Y?b#*SBJb?C)%&|~D z<-r|yYQf_m35=mg0#yl`i`~%4vn?KM7InIq^|ErE*2%nc?|wdsX0mluG(Zg=Sm`v9 z`bN-}{vP}zVi{GSY~<$!{g&$^~6NzBQXNk3)-xr9xdHs=UV$|Eu@O5*=zizRO4NF-PT)LA9ineXD0^r_|~oY3&d*N!l3M#me49SSC_*ZA|!{8TE$kq;d^ncJTDhb8*6O@u|sFJ zB(Z*i8mE7oT$-}jY9G2kAh{N$hm{SNLTeBC(bSf$MadYa$#~tlqv}oJ`6O@6y`vRf z)(7a(x!*UiCvi=CA?-7CSdra()Pw1%WiTaKm(!Uh^6FpGT)bL zCv6W%E|P9be)R=MXDOYqb4-nR@E)g_*vWB1TC7E6Q|?n$x|M{Cwil8=uLB4rlEt+w zE;YlME-lP0(&npF ziIDW;Nq0ysGy?}{Enio?_e^~q?nYj9Q5w_Ez2Q#(>^W>BnseN6s;U^$0k{}*;d>3X zq%7@3g>!vmrmViY*&7~N$ykM?V5(UPYvjH1>pLH3KWjZ^qNY(y1Dg~A)@GpUwiZ(l<0orGtIpJ|ys9YACx@y~thz_DdH{Nmx@nT!xqu>rCz}d7 zPIM@$yY^~j{gL!Oj5u8>S?R{O^u-|#ogL1RbkVe+DlWF`;b!y zSX4@0KlzUN%-bq4o>amn9(x&SXsV{3A%u_=E9AdeoW*EREweD2W1n{8VLCTw*=rB? zr`**8I84vu%RDbJ>j4X`v$1kxmQVm%&6RjL=|$Oa_>O-R%vkndn5Z#7?a-SaU$BYX zhZ>}_b&TA)8nqDQV$X2sk*_Nutc8Z-Y3#i_u}Dx1)S|tRJjH!+3ug|xTao#i)C&$> zVL0U5H@}j~w)UKr5?`69mUQQ1Bs;qW6`4BBR=8YharW1UHWHH2Tazf5!}LR?qmZ)vTAzHGIrrQi+=@aKvM%>zLp2 z=lVx85lq5CuHPv16T{hu*Uld)*JT#7Q}TA4saxUh_Ni81MWCA?fSQW!`KMYN zeeW`+dhGgnOpmbuo^dneaCiMJUS_QV5xUP>+=X+01zwnVkSk}r2RY1a;>P97aP#;E z<#1Gvy(|K@!60>(* zb(6;(GAY|4Ksch$l_~A&JPL#NEP$mewjSopHUu;(&rX?vSB(G=Ol_DVdU2*%7K<8jBP)j-5= z|t)-3lg<=K~K^F)qmM#UW)T8)kKr^LggUfS3J_fKmX0|*DgNT7|*4 zP=fTtA(Q3W;deH%#K)vDKHc5W1 z!ZEzV`@X5CLGZF~Y{UH98IJI&QaZ8qCx)hMoLLB2NX6tysqVutBXp#N#cZ|#mlU_# zYwU6l3eyby;YxzsmUIwk9j5E+Xt0NPrQ4}oZ0t|+-h6PQ>hC?molA?w<9*McZ1mz7TU#{`f5Zxdvon4pT8 z`x@=POwi;1&IB_R_A!>Xu|^@NEOqRcuW|<$uE|2;;$+{F3qZl1TL})=_%jvA^cQUEPDO?1HU!!}^|k{g6bT&+?PVgg7(- zwl#Y8-!4jU;Kx*!-u|UdFdocQ=L&aqGCGF` zQGn{5l>-UH^nBIC;Wa2=*7rm%pc|3oFWFac^6O3X!?E~nEBPYoS=ePTm9GE7_85<; z_r!kHxv!4pFf>~k^>AiubWLszu<5t4ezR6F3(7l#d|6!Qlbli06jxtU*|0M=ztka$ zOEmR<%~hEew;Lti?P{BLFX4*mZ;1L8GgDwueb~7?DvI+3G&gbWs5C%?vx%d z3SVbC2Te4Tni={;De8w-by<)S?AF#K!2949zuGBfa#8LKeRihAG9vJKZPvOw^|W<% zoq~cp05aUji_l9b0(hewc2{P9x&2LG&Lq0U>{)1#I@~~aDg$F)2Qz7;x-JV+PxEIH z2BSulq0U<4qp&1GFG!HL%~EKlO8*^iT$e;&yqIc1D+pf=+6uaQ5B6 z?v?@;f>9WoD_9)|Pn-q;BxyQ!o6=tu$$aV#w9%h3QKv6NT_tXG<2E4+F?pZBCei%3^)12@GxyTOj`BG z=>L`VSo_X097#P12$?4z z+g;yUN^F=teEw(V_ubhA03kg@eFi#)p-?3eAA8|n_4s)BxAH#hZ`hq_*vwrJx9N1{ zJKzN=BrHUiTgR^|`hci>n{9E=7xyxwoPz%flKUag-znEiQQO{)-CK|4buAaqID7li zR;R7pM8YZKDKi(rEK=?0@++z6L2{nyiqKj`WnC9Gm5h8HLHq31!o#zL6MLX=;3PIY(K7epbJ?25HC)(EdYvZg3+`ui)ru66Mxi}TkG~tt zIfVQ9EYzE818&1qU!#%#*k4?%7JseN`X1ps(Z4f?nG{5^lR_NQ~!igg_H#i|z|*O5@SCmwZ}C?-^#) zkx71Vs%5r7!?-Qomr#=*oHobie4|KyXXt5@Rptw7G_a&P32vS`xNGCF*pkmP8 zb0F;VWt~`^%UYCnP;Ah*)ixilcV^8m;O^WJOmz)1u5z_Fp6* z>$o7|7P?cG*m%=ahb4|S!sXcL?2vt%$TY2(Yoy@BL@;7USR=_4-1gu%Q)Trl_wFzn znce%QZ>r)PGON>(XpuH5o7`i(W=W^z7wrpOvY<5c=aPxcM6gXz`cM52F{bkx_!GBANoxly_?VxGHf-!UPF!HQ z{zcTM$iCt)w zmgiaxaZX*j`P>)vFop5Qvur7G^#hzg8z80ebdzs-I_n1Gonri4{Zm8vQxw$Yt=o@e zTz^ns%OxgC#8Fx|`#$b{dkK9v(zn5%7MT7&W;p=J=gR`c3~k(?Mr^$d?f(?ZqS&)B zr064Udb~7&{*+FuhP1F=UFN?NoLqIYgi}+|L$MHGIsOi?jsMUmx}g6AwZmP06t+;++qJ_n|ctt`lSct)OhPi27=E7NJL{a$RAv*=%%TWUPI9M2CL*93j8MY(U`m}@+jRc{S-99Ud}1Z87EBwxeH z5q;XtH9xIXD7Y8doM4eH;9--Vzh1>g7u|Ul0yCBfzQl!DUa)Ebnf&&(DMM>x%OHK1x;HKEm=L zC#Wx=U+pc%;_sSmv>W=GnOcb&_@(>tyaPsWX9V_I{_+Rcx9N|Xrfgd`TagpCm#6ej zsmU#2M57LJV6g-_M>b zUB4r$+NpgFdFfT-OneyYs~bnu9n)Q=H#^Olst^@b=&uIM=CNz*9%P zfXTIO*)muCww9lE^X_L=Sl4*l)NT*Iw}yYOL0=Eb+pUF!oA+ZM#sxHhc4hp#%6^Ju z(N_CWKp8>qLLcXBe&bWG-RX?o+n%(j>2r*aE`qxGk+`d5Elcr12lM8&n~x;E{(ooM zl-~b_^viX9pk~C8M0abY`dKCkZ9?5Ir0k&el^goIbcR2INO_LZZq3DFNCI`&?lJ}C z|M$j!7$oxB8n*4SW`W>rb_&vZiYBwM8pLFShHjT`!&HD5AWwr-UW|cCh%Frwc~kZK z3ip47*{4y`_&+kE({`xe0ZiY2Lp$vV;FcFpas?ixx7bkBYqLEnf&CPphps(aysg>HHo*0E3uAq6WbzvuF~<{+FCL;lJgas50;&WZs*61=6V}jJ2Q5WO)U^sLmptvdurTQ%2yWr*J|b|m7fX5 zL6>QCm(V<=w^X4yFKJU2*Kn-aVDcD74&m-Fwiao&{ca*OAi4eLK>2m~d6%%_*UT}E zM<14jx4~)e^)=XZ`KCln@*&Je!X`1-boF-tFlT4JD}F%9NoBBN&%np7a9x|Lm+Dm) z!t)V2l@f9&J3H{FhESQiU$f;Vdkc)EVA(7bdE09z>ea4})TQa9heCuZf_%FZ#u7rBrz0A-M+#8%qx#v>{hDe-MrTS7unsZSMa3U zM;CuGdj@iBQWRgk@ZMWPr;)_|h_l~QFOVRhW@m~M-m|l%hvIrE{P6ESO1k~Rm#Gu8 zF;uT{H=r)=Q}7J;yBWy7T~ccyO{jwj5C2v`Lbm*$lN6vr`S+P!IQz(Ms8+3IMbHLy$798zUS2v4x zj~aY{pb9bPkzRn=`M>qk*6(~OTr3V1()6{+&ZP^SxuwTvmz>%5oazffey=to(O%Jj zN@QV7TJ)%cc{e4#AB5STlnEX5r+&)K|T(fwc!;Ofd zz9WF5s+sa`y|rCia$S^l0kVkESCNBfChm(hm34-?^w%bghyji}+)}H`?sKcCUk{Mj zz=8ARK=<5*GYg=@m%OrEdHHxvT$;?ulW)ytKlmnYRLe~{8j0Gr%RZ{s^oY<1SNb8{YP5Gqa%g@i(o;`QSalki= zPzpYxoId6?O-}DQXc@r8JiCZS+>hFqVU77l{*t@Mmb50RV!v%%a1`~sI+D=3{X41B z=m>G%Mb2gMf06dqVNvewyEh^#p@c{XNUA7EiG-38f&qwhBPb{-A|M@tl!PKm52Ye0 zAYIa^$Pm&UGW5^`46&~pUC&zU*?YggeH`yUJjb(KOJ?r-8&{m?=hAIMTkixhpk_C= zo6SoBl;mKL7&llHD7JYt(D=Bjc}}eFYK5eC@#bcBE$)I9&4DMt0wMNLxiWnkhZyk5 z-YH%1#Kb#=roI1>txGbUMY?@VWMIVo3(>c^;M`3cbNA(h%L7lxLkvF;WkZBRWZQ|+ zTT7up3*Xuv8aOh#21>|nwBlFOOdzdR-FkC~QFSHVpSoeZ81s3<8JCG}^ z=DZX=cvVEB4aNY7>L(>wZj!eoY=+k21%_4TOAd8T@s&&*ue#J_54YJ-tw%*`%X>Lb z>$$f#nj@?o5BCIXq$;q6ePNt)7A^;d5^kJjuLp1%1{~S$-DN|+h8CZT6ng@Ec_qhO zk2^^!M^LzP!dYc=03#_Peip@N2$X;_1c%r9)$39t1WK|7~C z0Jl&c)vVyCI7&zH(xb^}bC))W4V25wM;j0&tYTW8mM3K0MoTv`*}o{VPZ)n}xGs6U zhB&<;N4Fq7OM-s#=3CxVk;FAEFC`0Y6XM;*s8Nd~bPrxA~q&{Te7P*6zojg{lZL@_PBzCg(p|~ zsN>lLk-H^1J`OU60b!8g#Z#%x%QMF?B5ayc|G72oXN&V~*&q_3L)TT+@r{{x- z8@%2G0q=4{v|oH%G?*-Oz0u@E^0@({=KfZ&!1Wr9dpFVan>Zq=vAE!k?7;Qlt?WZ= z(LLWWzEA)qTMD14ST?KHDw^QBG?A3L#*d*;LVIaf|k4mWY=`6Wvo;rLPx1@i$Ui#haekoKIpfaMtr zo}h$e&(9~*J-Gj$JuN?geu6*RWsKQ5@f{zMy#lryS$#Vm(pbu~1QguQR_#!A4_er*I( za{B7HAQ3&Q;|CX4O+^ZFIC%{F?M1|Xo%F51Af+XKP!gG(% zX%2-UbHirc1kjgVJ8U|=ioZ7<^rGCmp~N)ejO;yI50M9gZ-K;wz?gizBvQNuy$qc!OeE zv5(J(A>B5YV$RPiq+E{RY^u58`i)kb8!0tcq|9!f9iceGX3R?@8}MC?L6WHJd}T1} z349pUoJg1o!Nrr!rdG9JioSw*LGdogocOdb)vXuU_P5Txrs))R?>Bf4Ov$^y-JR#k zeBKh97+7H0J?UtPDVsa#8cL&ZkMk}{U5k6BY~Vw&$^rnBlClciPPwvsfdjYCwQXZ* z{FK!Bkda3VC(l>j^eg`9dRS8Kwi~dH%-!fR^D7Y>`PPm1piu^mjvE(juYUr>&BI}OpGb6^W^cdbvxG-AB=3k{=i|W$ z-O-WNvL-+O8pGsfm}22@l7z*?cNOcohaY_SA%3z7t1YwvlvZVay^2%S7tzF&NA)!9 zsNVsXY>G2VyiY8aS^EPI*7IIdt9N8=a|_=vis39tlv1>EM9~s zEJb7erM5>Gi-jq1LW`5msT!%a4Pk;CBS)mBs`~E?#@9Ux_yI)-+*T?9(40okHJJjb zXrTHf`uOSN#Za1g-nfMn`0ND4sVdP>3B}pIJzYKb+Pnv;mJRqzuChrnckA2#5aQ?x ze7dJ(>k@&qe<#0;f|q$2FE*9&4M7rX!0)*U1~kQtO0 zs2JkL{xm^aEJK?4kl}l3c4NZBS)|Tov-w7(S+BO6qXi?XE@bN#d^^H+{1Lhj9HUzo z`DSm?)E_7II!9}Fp}040JKi7lw=kpt;BIo@2S8IK8PcC(%n7ZA&73tN$oi{Wbc#YTQ$@@(P}!Hn=|-0f$Q8@IVZ z%aGMn1^@zR)b%i}6sE7Av>yuaS{j`5&@<@%=H$E>&XvkZa@bt&r<2YR@M})$!RTz9 zL7j{vueu7wCU2qq2#~=Vh^Kq$X1{Oo+K-lfl&q6@wsPOo8T0d-)AdU45uSHM zJ==q@HG@}&7bDs)kR0xgsc6{Xb^KzeHz;W023Fsq`~o2zA$6-zXDY^ffK9ohEVav! zPS7XeYq9E(-a;34M^}Ypy5muYhD@R|@gg%C(*=3(Ag3Lf&`_h2de}$^TDX_Rw^swM zS=%+!z{R|r`+h6;DRbRCMg`AExfNRDux7b#w=U*+h}VkybXM*m9cCVb(w|acpMsto zZ|9~ozA#^s7N1vWNHTq$(g_3+Wk{jfQ!6#SG;l}_TJ4ooq{A?6z)&tsDuy5BuG{HS zsUi}bV~Rd^O%bWK_iEiRKNXOYKg^S6++sNwQLsFCd}(9W5La4A_&{#ywBoNa9;~aI z$V91Ni)d}d_$lloafMNdpG50(zko%&ex01^DIyy4a4jG9fTG@`fCg}#zwqqRF~6LU zYgRuT*H2fqAgdF6D12w+G!4y&TOELMAU@XuS6+0NyW7ZfXHi$_1bXF4 z!gqZzYf0YqIdgp^nsXR)-Hl-PQp;PrUP1gPGt1gtSfh-n0%1-?QJDC6>iY4g4W{@) z--MnQLUUN8v!EhwY#Cgzb9Di5YvZfXODVedw;^w{)ky-HmxWN^5c2$!B$7%rG4>9N;uXxcIH5rL<_M3v|$a1wfCC_dEL(s4DcU&~aC zOf;-pJs_BNoBta(hb70mmk46_Dr0K zmVR&|T@hUjED~1>2Xw%JFI??{o#dPqYJEhL;lP~Q@ z3?I$I@StO<8M^GyNIMF&EN^z=#gnh_c^Vy~BA#@clHV{#CA*iRKj_>;54%aFsAQmQ z$jUdxs}nXx1!=0B(R|CXl{(8+#0m0S!dih8f#c4Duc&FF&BO7NRG9&+7&HniY~6RM zTz=nNOt)_MQ+Xb*+DkLN>0w`cOk^XK(G4xL@dL-aU@KmWM;c$;{Mt7WH9-Y5&dP7c z;ya}FR;0qxiEU*ZCzBY&QF|p?D;L7CWyDofp+%MgGA>=-J+VP^Zgdr3G~2d6m7r4& zswF4rsxAhk9)P=tq|aHZN%Oe*g}N0t^Fy+}Ki3WLarP~C;0j7t@w)E!gduAAN@qK4 z*z!G}MnqB-vD7O{JhjOycDIITPrTiC^|Xw!(yD1yc}tvl_g0gF=~ZjEmgV90`8pibu~LpT`mz-?tBJsZw*FYPX#cXV~ucMl2?t=wwV{`JnTn_-pfH z7?fuvOIXG7siAe#!Wz7R<}F(v$GM~Ww+PVmrxiq}QzNz+D9h9e60RA&qF5|BEFclJ zIA;X}%U#!VPobdxVr8qlYKT+hi*$J>?xkSzmK<_`7(=8^PlOSK2Sz>@xBXHtsDwc{}gMb z(-KSnN)`vkk62+)F;TZpy@6b^yf2xK7s=7n;o_$Q(3%G3$F?bN(U)cq-p$r8dA#v1 zoW91lM)PX68k>aAvF|=1O^OfcNT~ z^C7G%KAt4xAyn-hjq8V|U+H%C5zXslE_d0oyS5a8$iOPn-RrKSinFD0j*dWfZ}FMz zrZQpmmy&2Fl3TXf7N=ahnuD>EXU-dEYF1hvXvwv|kEbHAmSkKu$QCq8;lsUnZ3eo$ z;d*jnj}~DveTq$+H1>+Y*jtHU1(G9~!t}Cf)NQty%qIu)J_bVXFtN8pjsWM^9)#Z4n16lo zefpKBte--u+WSR`SCza%(&BuNAQpguBa({;8uK}*6F`Yz>jWL{QWdXS59jqqV8Sm3 zAxIsT&Tj9IQb(Mt`YJ6M(Oj=tO$N)}Mx%$JrFigWtH0!g-|mRgvLsjS%HCW*(XUmE zJrTwZ7?Sw4B{x5FL*qbx6vpodjC?W0&IRW3!SvJ7Z>v4Dj!(uzL`u;f>-n{oK943D z0*R*QxVE>tF0!N?Wp2|%e zXffv_q+;T8z@mTz?a)ewxZg%aA{NG%_d!jVtRSw1|%tLCdcYUGIlJUC!>c z{CLMaJ_E4Rdr>ON1BDZG6NMcA)=g*}B^pu6F~|?9B^D+L@{KACDkCl@DZTZOn1n6< zMVh6^;RA2BrQe%huK@jgXUGH1Llu`GL+`T+C zUj*;iNgQ}t{-#@oW?HHBK=zBTS58J$QMEgp-^L1mq2%9A*^og7W_)HrD z?q)4t+WGigp5N{UM^BWrHgzZe^Leq;!kot9+^LP|FH+a^sR6pPX285HaCX*22~ktO zAz3B|%42)WmJR$xM48WznfgzHn3DAIdGqf~b96>rGi4(`p3zzYbLDUWlGFWup-oWBMe za@{Hggs`@^TQhf_6MP*@+it;YmJuDV<^BNQk znW5|C9Z_FN&&jvz)-B3mF$01Cl0sdB)39>J|Fd$$2n7Z%139RB@J?y|-XF0|nW=OA zwU_a<2yMfQGEMRi9tse2|0*B?9?CbB_!3(J<*R7vlgEqTOg?=}@j-J^)Pt^cH;#q^ z&qjTeL=QN~@KQ=m%%wx=7Deg2r|$E6er&FAoY!SJ@lDkD+jh7U8~8Fvzx38oJ4)F5 zXCEV(Ryud{G0}P;Yd2TBtTJL#IuZPU)z_9*c8k41K9PZ24sD16ZHs1_Madc8kqc@3 z@@Kw-yjs2By}*aw_kmsgAzvA?*d;dfBJIj}eGTA=wK(Ze2uJF^WWIa3lCfisX-aWB^DKJOil`W(XUhwj4J@#}}6Tp|*R@QfqW|F#3$3dA+TF%q}4QVu#r zdN9bvI+GhfuB`{2(J#QVL`l$tuf%F>z#fgv8eaLj9bCubi~Y8?z_weyy#g}reF{7! z;a#Ye0pv1_|94*>OnI7}JIr|<3#RE*h~LEuimJd&H>v)wMO80N;M342J2EtjTfQJBMW2nkU!(85YLlv=)kuNAsV&b&IKa57>rTycG{S&KlK= z(HhY{aFq7L0QscB#!gO(`g6ZFz%JiB!pbS`HF1P(1g%bT_wM)#o5;A-a!pY5E+JFb zjZR87I9=|y3O_)kl^)I<>jM3QS8h%XFHU}y*@A(#8(F$0A(Wbve5A=oS zT1LReG5Lj5c_fAkO(6df!DkO@r6FtQpsUQPTAkDUEs)kmNtoeBq&8IHL`qh;g=(j4 zvmgGnlDlbIw|zEMWyyelQZjn1EG`RTg%1YXF-Sch(XJUiUF+1sOOq8WKn(v|R0q8P zK!1o4U5KU`)-gHGvM*1p_|%o`_>Cb~gJjy(PIq5fpDT^9YQ7;A)40EHCAXE)d;M_7 z%t5;58W%&|5-c@*p(QQOehj^m3t(;Q8?~pv4%Z95@v%a+dTsztd8Qw4e;bx-1`-(368^)IfI)fDu6pXf8`xkg_Xb&jQ^lYdi&vXX1JuIjhK<#DtIB` zCUP9Q{fc_)F>1^svRy`IOMLj3)tOY4s}(&$11u^MYwDh;I!@@H57RJ8SEL}aY0|R} z;Iu)WEh+oHD&S}k*tVt4alUha=Nj$IQJ0yxb0 zLI%7bG|Iq9))SZJyK4F@-;C<_Z`uXD4hVa8^S`xmr~k|D zk8ozxE-3yx!aqR_+Ol)9U!S}Rmn0W}j{$rqc&1?h(g^~Z6%F#oW14C|xYOhy0q*-D zGCZePlhWl5X9HI9Jp<6m4nX>F_~37%!QonEop=9}`~81H<-}MRvhBKAwSXiqw^}EE z{}=d5?*acEst^B%@Adx*{UXqYxRUR-6$pJ zKX(kk=+MC(+^|t!wCv=gNi+!0&j0cC&qGHhG%?pPL`eFgH7JmGi(aa1OF-^l1OOI) zig)s1&{x8{*AttR#CbG-#Uj%T_Qc+)YP^x?k(4o|Z)f^^6ZW@6&7 z&m1hy*L_b!mBeEc=VfKKt~kG6=OUW%mqw^fj<&WA?ZnfFR8&GQ=+QyK0}CKUExKF# zyuDcLjjAyE<7IYou?~3*mH%5r#yo!ET^saq|3VqT##;hmMsos8#DG_o(5XI(XT_7v z!`)j;Dx*zP_5DS8&4#@RV|SJw06hsF^kS&SS>h8)CeJ-jY!PSXyL%>cj4A-D^WI?J zw8^(3-pqBWaSClQ^#BaOM2IoJuim+Cm``_%gmW+H9?GEX6eo~CaN-v|#N;@dx#_IXyw_`iPx#AFXHv#}wB5mCyVh|m0z zjQ~X&Rw0g%Gz69$5X>}LzZf4O6o+S!{(!%H{(QN3BYcE%3fa6>HYOlG?_9p1)1|V#>ZE-8Tc)l3t z%O#GZdduL{H5L>EAC&9)+l4cC0ZjlKGd6ar!JI`Sl>(pV0!Isf&%PJa4=oA%)mmrU zSzI%6dovQ14@cVTS>^gw$=Un9G8>=B%_##&bLWNvC*o@Z>>AN z3tGL4vRq(e+qo$jNFe2mJ7S0^qtOd-urb2JU}FU7MG_u3EJEpZ<2^!rs=^$d!5qI( zIEQ{DU>^r^Fq`d-rGzL%dKWBq2Q|m>a8!vd(w(_y29jp?&N6=%5A8xm(a(8kjs~g2 z)!CoJOgCr$jXpA;!P1F7p%(+$p>D>wI0X8^4uSS4yllR1L$*T;QhRe~Ns` z;U9P#u@m1Do=JO&EfmY5->^4Fp=}X>x?Yt>MMACoh(_W3%t`4wwtJ(b5q zXKudPxaWjG8uxF$86VK&BH)XjYf|(13yys%=1B$cC%4HV=d&2$f>WXayx#v1B&vaI zBqdC;uVVC=ZNQc4%mAA9^=R`1J5XGjEEKG!P(d?c~e zks@4rO~9Fbe@L4uXa4(SUi$c1F5wF@_zx_i=JE??Z;)plYOcOqct23BWeyJWW18wk zGmV*nLd%RvtHS+O)ME1i9#EI@K^nlM29}~$1)Z8-S0uq56j~Cj{46`W>(W;yH_+5U-hE?sf<4R)+bURP|G=i*^|+W77U zY$4X;7q^j}dMac+O(ca2-_4T|GbMfjZh8SXVD8)tX(a_7*L}L*kNdXPUxerH{~O^M zvCP5*qyGSZ!72kshEyq76AP< zSHhWOx{=oQ2he4arL_a2reIy*8yWg@QvYW-rYgKuYGu*tc+kPCy4o&0+1tS#kw*ty zV$-H#;P^aYt4N>M^~ypS31UhfWCaj;V9meYo^Vugr1& z9Gko5>wX*kx)?yMD@At&6L;qrv4A+5XRht|S?M_Cm`mp$4#BL>$D$cFZ7ZjwJj!GF z@5;27gRnTwbu5tcmGA0b^Vr(UiH&;md(+Nb4>)NBLk#@tx_SlRHpEb0nkaCr6#ElP zG+wY%M>HyUymVXsyFH`{8)17};|f?B%>dqZqc20Fz3J?60V$Gr!HoqF++1H_H^aC= zeg8*g@Ka9!$zNZQT>GhJ*rdemQn_zz1O|^lqsmLO-G&_>{Iwe#c#%rIdsV^|^m<;` z+e-8_+KU%!$Od7~+v!w3QZu!^zg%>?lJ+1PL*W08qRG4zNWqqvt%CRWYtfMZjk>JP zwF0sSCiC+hh;M@sneIVBq@)8d)_-U|5!0am2P#m{e{~6v8WxYKMXG;*Y*R3~znzOj zeoKbxI|%@2+I;~$P}gRml;5Yy>Jcaif)kG7X0y?MLty`}tjnyk6n6l5`8Z=#8L?7H zcbVi}=ZE}Zee*MVSKMt9{;FkOXk>=EFt z&OQ8^;{Qx{L<$Ot@$_1OQ{&j+8*->HutYx9%Y*OrdyblVBU~4ayFdSbf5qQ^7jMdR zMHYwI)p+%n9%KrBE*hyU&J?QhTTfZ;z>mzJb#dr|4kBFkt{fvQg6B_uo8d_au{fvK z`kS+!RntS&lGTP$% z-`~{hzn46P)C>FxW*)<`gl|f({nv@r5&7RtdI(OQ;#L2dmLU8QAG!#h!whKL{)BF3I#i%c%R<)%|MB{;r!k zwr^g6{nvDJYkUoX@FKzmJ~J2=U;{V*PVOg$OsEeqFy$5gd5AnzX=2q}WA`61L3&bs znLA4zV*N2FtK=ZrHP|Cb%}U=R`j@|65G=EqS(qFF>*3xXW0?n1n)sJw{Lfq2{~}2uN0HVp2-w;9ro+0!M8}AW zpskIs*LVIEiJZQ(VSb&)AkFC>2``ZU{RvsAjVG8F#|BB)wJL5QGOVME&Pld#=wdH8MC0ZzhnW9AIF zE?7B!udj7(cr^cjN6au2!;#Kc46$yzbz!fW4a|~R*uBj31fn>XGS^;ALRo^1s+Dg9eC~e*u8O*j&;cg_i))mI!y>X%47R%M%KR`Dsv0nim zBV;YYbod@HElPyO9nvneg#0xt_KJhWYIz)$RNVIt6{&fsDOQgZJbz~J{Sc5i@?$SO zytCM+c`CtW<~-ul-P*ZmmL?!|OdncFbRu_ad|S`d<_I1M5r|q@YGlEA_Lpy0g$!HV z7NgD+z=AEJZN*GX5-_Eq60srCwss5KMhWgpf2NwYt(XWRCj<))05p$4aALLCmx=We zn1#_ErA5`RpYsSR2Vq-an8TE9uTV60*%JXcyuywdK@hCin~qam(CDEqUJ=0&uD5JX zZt`x>mYDbKgs(stVLkw&FCRpV(7ht)vHeuUd3j=_AnS@1xJ#{jJ|%s^`k=uDK7sI! zrkwLDgQt3Z(I6YdAF}`O8L^=v_PN^1?^(MSLB)PMWf13qOi$T83Zpe(DF7Gq*l*(SYQw@Ev&eAC zLqY}|uox2eDbuOD!+Uto1-RXu#4}o4nI+Ge>rGyPGvI6~gKI0YiguZHfr}H)35CxA zK=M{)AP0g?mkFvK_Rx+31ZgQh;hIu=Iosm!mk{yy5eHQF{Ugre|KW&pI7-A%bwwsW z^C{CEC@Lg;uRlh3(2nySMU85UzR;Ko--;3wo zfhw}DQ|gMgfd^SzdR7oOF3HnfYoB&aOR(|5WY2+L(FEOc{e>dFt85?@Q}|?m>7{Uu zy4?KvW2%<{5;p1YI|uW|28lO&o&sAfJX;pvr50ffzUBsO$NC$m${&^ef#DvYU52TGf#C^qbU;rS z{uG{2WeRciX%ez!2&U!lDJA>1y1$%_b*H=Y1STXX*%|nUGut@_VQFdF&FKOH66EMV zC-46SUrYd%@hVUo;qUg`_1BLBNUC}Nh14ow8lFy7$yLpYRxR$?gC0xB@BXhTqfh*F)q9|=!n8&oM^JK7o9O?wF zzJHg&%U`+~032y~@;21oWYUl$hetvSqVhCW0`Uq7Jy0RGhk-_T^!Ff^C9J>?2`Fou zc8737G`NIn+YU0&mQqArAkH)u6)4X}i^Svivh*!Y^fSb*EQyZ=oD)9% zz*gjNX9(4L^q2U$LzMNJB~07>LWGpin$5pwBAi?OUMaRbT=MnYmy0vc{4{R8Pj^TU z-$l?y8j%l^Rtn?}zZvjyRs(^k7u$)G-`AO_C#o5u0eC6lD#RusW7#lnrSpvBRewC6 z$pGMIGU-KTKM?m>SBm2gQEZ)T*g!h7zP}vN#DgL+?oPnGL1wn#3Z6{2-^CLRN8xF^ zJ4E0!`m@-3A=1ME!M;sic1uM2yN~AzJH^2ZZH~z^Z1T_-KFQ`Dgw5+#=4!XE$~#SO z#wSoI_OLzGSboc~@_X;HWcV72jJFv27ewQu9u03jj_W_-L#!y&*V@j+Bm10lYFhXA zX#h9bpJ_X@^_mc9#jUj8fMV>q=SbDO9HJ;&v40F@`0<i8TAAjB;tlUJz(CzssKiE2<5H0fBeAAALR0a>nXR~Bp+UT za1u;yfC?7-pYCeWe>K8j0K@(qO~!6WucJXUc0wd#NWJ6zW9NjCp1MxTzHLT3{$!!_ zhyK0^^Rxvp??&pweP)VNaT>JdJM!G^{XH-4(oCQ9ucD&Qe_r0e%ws40AU@0Rh)7-W zCAo@iCDXk(*5!l60yNXs7d*_-bOH+q#__9O7?U_;9N7tc!UIjD~&3lrzjtc(0{BZz^{2%87f&)m~P{V=wZ3J#OOO zt!SG6D}1o%;In%t<^=1VfY^r4u6||QBe|H;%KYj6I$6v4V~p%}UV|Ay8#Y!np_&*x z-~?RCzTM1g19Z~$YgZi{hp6wky>-0?oi!?n>-^0|d4#Ls*vBYRjpwkkYb+5E&FNPp zgUG`9N(vL9MQfZ8p-9>03dU97=~U&?UT+!Qql|Qyy*(pJN;!2K_GDI{fkRj2HqRjxH`eL zi$Z_N#hK*8Xs4`-NnQINn+fRJXL*e=_MzQQncoeEmrkWb<;Hb2uFiI&40{m-3@G_?$MOFFCx`I;>Rwb_XVepQvl?bxn)I+8T(02g6P5r_Li(5eGVj*N@a zYLnK3d6pc}t*_5ZS!l*-^%Qez)Ro@jOl5bhrWVNrHUwIuWL(Zr7hEZ9`RK7}GTC)5EKcqCQO}DEd2wR>}*C2-=S9L zHKt|1RTt}~ZmC`i4DgJsn?qM!ek|fLEho7z;&9o*E(_^Z^-LZLTP6u*Gk7+CruLEh zD-up?E*~~%R|YgZgAHEPU=?$6lb7_G?282aR=JY9XPq=8myuPLXJo{1@okK z&%Vx{r3*ekQIdgs=9Y7EGoj3b&~Ra7qn^*>E))*pT#tR8No(hd7RKQ;uA!oa;( zxu%WJC0{$9IguD%=^GVCy8jZ>iQIe~HWo*PftK3g#I1_Do00y^*+z4??Obo7$E-cQ z-|E-U%!U~x-llz{|H=4jp6#15S%L#Zq$flnAF>9cwM}(RrYEXK&TFx{R?h1Yx2~Cr z*S52D^H-EeT>sjQ2{f5&2&<>^?m!s*GG+oTYbeo#ihT(y?0i`fo2Oy14pUenwDvSw z0>K-_dixmR1o|sVP&wnOm#Z9s_a!oZlqGKJl@tZbJgm*E_O4elTc71Gsd%e;4VjEw^YU2F|G^gi3a1MMr}R~ zQLparidR>C*+pOz_2Pa5siqQPGO%C;*r3#K)3dM$A>Vyp)t(Mx?W|lKmqHKn6?$?OK0%prNs7PtsBZ@lC~ro zDhye=1wpvU0M$Aiz`Cao5RzCtqASgH3XPgOK==ve%}5 z86FlUi^_j3w2M^I2I?=T(o|FC0N};L<0WIK+w((_J~%;M90)@4w# zyN0VVNl%|kI<1Lr&h~LF@~)OL#4;#w1-;BQ(QmTX8c**b^r%ptD#j1a2NNFGA*+S8pqDe z(2knd4?+kCJI{S_%N|U*wkz&-B0`Fy=!V`+(&-M`Hu0V79dZQji7b~Nr^Y+>J#++R zDJCSD&q7lmEl5V=QzntY)am?zPLzAQmi&8F>dq$;1#PD434i2YiI?|2rxUY**Dh!q}^RakhJ=zW!^kW0!Y|U-rhZ!@@ zb(U=sYF8; zs%Rdg4HlYVWW9+dvJa)L;8!Lax^PXN%9dN^lhp~4{dg>Tw9 zFH10cK;^PP@P30be5&Y=X-lsoQMkF@j?l}K^xX!IDLGa@&!^^ON@*#;0-{XI^xE4o zSsba(PIH5@+Do!tjrCAQPlp}ebe}mW-j~)7il)m-S7FXi3z#+>)r0HPVc?Pza?i;T zLuIi6h?Uj=rX0tga7^W!+JrmQr}#mf04zIXpuIgvALA&u3u($X6athFk`DI?&JUSx+R>6u-%M({46)$>qI3-}i0W1>=*x7NK6FyjEl?dG zV&H^zC$WRXe`^1AzFne{cAp+7$q%6ysA-Yf+jem(S`UoTKYpf0L-b=K*H?|Hq}gok z+!`9CYo{cu=g4Rr4CeC;r$T#5Ltk0X8rV=FWa z_{LwfiQhE4HP{{rba#@s_5F~vc)K>>+O-D1_0#)$wxE)1THn?J8uNHdj55ubh{M~j zT8cRWnTHri&s(4?oFx43#oKQGtf+*z>B4M@`c%>iG+8fV9qdhG@moo=57}PG1eNcU zoKOq7&(nH)%3h1?(o{iu6ehdjQ#Q8<>h&?WVM}Lh1<(ctvVLv#;!Z-LVvcj#i`rcU zml8g!1#K~|>8IfbIvx6FO8TF4_fSYYVdh~-ls_H>$J?4r4x=hgZ`d*tJ|xSUh?9ON zuJSGZsf1I1fn||`s_O&P8q*yCcerjtraimpXk^POB)+>}Lzz6=o>j z$kTk7aRdEmM(=g8iN4BkqwX$;;LDe&jG^+fkTjDY#J|%rpz4F< zNwJO<%IQ5K4BZ(*28L*M z|FADY-gT%nZeeg93dH%4#h1vFZ%W>$BZs>ab@uNJQ^fA_1-Ls+QQOW@G@C2@oWnue z&K`Wr7{3tCg0r5xFJ(DA4L5o|zEKF5QqfF3m#U&EUd*_k<1UkhOYv1**1Dk2%02%1 z(Me`+xIWLqN_x(LtfWi-wUYYf2-Xzp2NAWzF?#+l;IOD043avZy4OVGct??C_w~F%al&$zA+SZO5cOJdMCw`M#naMsrmzZ?j(iOs( zvkCNq^BxLt@8NGUY`u+?+`y6}%&VfrDB5=>SA8?(P#)~z%m?P>q#lh(yKeq^JLnU- zRcSPwV|QE8sEOW~U7Ahz^N$#aQ%R@EPOY41_YYK6WSN}MgJWPgSZ1rHAwpM8(dd-l zDkNAe{VqhCD`Nv=ZYTU!?Pea^>_0vWDppTJo|oU&-QT;%nTeIIGJ9JQ^P{*uDua=Qe~mRM0clOM{fx3)qVc*;Do(V_~c9A4wGAo^?5d91Dp z)r)Ui_73|WZGt%MlfL}wkyB5?`wI-HpCJ6vpq91Ew}*SxzbB#J^XPv51aiRPwRfhC zq1jS!N9IGg5;hAZn{eBC$9#VTs+L!{1GdHMzm%16=Pjg(ya4@@DGZz4a!Qf zM1{7)HW8dE!tPE=R67eV&Do_l1ib?ZMm0Y-C;WM?YyX$$iW-n{ffX8tDGg)w9C})N z2jvZP=-|hazaK0OJlL$4-@DvDJd88re!NQSZAHqD%J@_aD-!o#m5+u%f|-cDl&}3r zzJwgv25rK&L;8YkI@a5xP6H6^t5iu(B;B=CJifwuJanrwHAhS752wb zWoz{inMcX)G`Cw`6B2i#QBc~l=}eF0mel=Z?9F3XUTj9UWitFM_#{i`Ha(5~LlKuM z>U7fS%UpcYfcZB4atgU+h)*j>V}p0?jrt3%2eXH_j;5gnI@hCB>M3CmjstZ_0lgO~ zZIM;)m`7E5VdZIaU-ez(ZEWzCo@qXmksXn+Tp*oZtHXyPvU`FYYDP?i-|VM$oK*x?4A>76iW729?;xs6*Ft5cLj%;^>q8Y z-1>3|dU+?g?uA+E|1y-deIZHmGgC)U49@RCn+Nc3p>94s;kwbdWwLC7j=yyW zl*opw6OwuDSWr!x@yL7e%?s|#nnN{unzhAu+S+1-EC=drcjh_SCX}~$apun-yYZg? zCA5XZVjX|{6aafDMmrm=^=?jKp-EY`d9C-+MAJ)Q*kT>L0@}Yk=Wob1cgk*2?K1n( zXpRz&@|@KATDVMIEJUSFeR9po^lV~!5f}TB#Zxrxl**Cf2I`{rT-e zxhrg@+!f1OXYmmOhYW5Q$gyB%v%6p58Dfa}p?ri$^zz4WE6*Eq&k{C6MG|%;2X+$q^G3qkhqAH?=X6$ z@%+NmsTqBa?Gm5AzO?pBDch$<7q=B#R%FN3Hy{7Nw(67o`oSoMPN^KyFj-J2e*E<2 zmbXT+^wXOS8c~skDXY5gN~>WiRB_eKcrlglSXGFG8(!LX6}&s zkA$c@c6A)M_Fpl?i5^n{_De+BRHA8;yT`qr`Z^0_*TikVz4;=8pAWu*+Pg-L!Q|0~ z6I5F4lO-s%n~{$`%1PBI+W8Evw@G}_G^%XgmGY`MbFGWL<1&3|vtTZl$mlh-R9UMp{i_Qbi$`WcN*EVKp zH1BG{BZ_P1+q4}fM-FO;Zxr`K6zisNHk;g7WO&~DD9Hu1=17N#MdukPh>ws|7;t-vJf>ZxCTSmXB;c^DqI}6B-I47xumkwH`mg$4F}LyGm{%F zZOF!`7XIFNpWAVPZgdG!!Y>Bzg&If}DKwr@GS#9c3~=6!vSjz7Wd;;}h%3x~thmdk zL=<)Leh_3M$1|qhzDnPbd^wCh=%c4X4bQV=>D-^s{2-2CbERgd2}Nf!$wGz0oq-!Z zSZQF1_3aJujnEg{3U|>y&-GSZXm|tvvlINte2ebs-=*QD9C~FJ$;1s0F_(3}1dlx# z^JKnnEv2SZW!8dbk@~=UNEm`V+8=$k?(d?xs1(It4I`M}KId&a^85GSIp13DY>%(w zlpJ+5ixagQvk~j~kXIWrrT&)JATE-8K2sPPX4m3E{NLzGqdqFUpudZhUc^f5_V0{; z{(xiva?4{wv)U zrZR3#y!xK+djX@w5#+#tzfax&%Yh?I#t0K#Vrwd;5N@2A;^~V+?<9wjE|9?zj1|ZQ zk=5&^8GSA}2&E{`^!@WmBOi$}hX7)4_h@2D8~N{ZB;itM!{%v$-@o8GBy|Z=>`a|ypLMbTW~*eSwnQJq9?bq%Be(s0In-DsHY_$W!XX) zQ+`zbW%hm@mG$-xVeRu{`SD^-ePB@Ojg;h!Lt?sVI>A$9biDU+6Me}YNT;b8=xz3! zM*sL-YJ`v?P>B3pXzLBWEP<5eASDTe&oLWDy18;Xv`YdTD6=&aK)qiz`Nua7w?UT6 z(wToRgZF_1Fts)66eMQrpw_y7&gTiu{`d2KLj2iwct{z*g|1Lo%Ytt)J*Cd!+Ln5q zno+>S*I}-wt|r|eq>p=3j8NqPN<0LF#Y`$UqNx& z4V?z5%$Q=PNC$j*qAD67oSuxGZ*NJ26i(h`LbuB)=wCCNx-uk5{N_PF>RCrzL3`~Lp!@9+1I zhxfa>uGi~4kMlT>@q9iH4ou_jC$W+yaE)H?S3x5Np`Uj|hB|u9fXSle+W}FO0$A57 z`aru!EY96`k6n6CBtKEaY}GLQE!p5y9GLGG%B|@?o%B!h-H)Er_vt^)R}GdgTmIIP z^LhEf=d*GgnCXwVMdf~P5c*942aagG0Ya`n6NS%^W_5v@S{jV(Y5?BO5xNsuw^t92 zlnY52%+dg~(LL=Q@(G`=&G$o9Y0*5&2qL~25K_PPm~#RHnZyJ~=caW>IFu(qK9Inx*Ub0h$x4_2U*43OVzSs{41NnYs}!R%2F#%5G}er&x5HC(%k zZi%9P*B=L^BnX`|qp!c>Rp%MQv%zccqwpG*O!qE_$MYKM#&OI!1%1q+uAp`ATE&gr z!mGdC!XvVf7niEl*S?5`A67$m1CxYX26%$6gxQb&v=*bynOlN)rOR`O8~y!2&<-x8 zI7rPdw&{1;eNCWuYR8)CN0Wz0w$bnW-gk=S1!Wtf&r~hrkW(|NGy`;y9o4R^A@=A&-T9sm0u6A@3WUWHtL`9SEw zZY6#C!#{^udnKMFF>XwW*R{?k6|9^umRvRf+Ny$6N=B{@Jk!qY>wFWLnw}>(j6+a> z$e`y-MwaS&D7JX*Z|#A)@;tT#yxSm|#T*{I8~%~ak3ak6n+M>kVP#eQ+q<11DN%Xz z^YCq9Ea{Z>)JW3$22&_hX&=K>i3Vuy)3WZj#9@&wZCSte|C22>-$9P-+VUbG6hyj; zbl2|apZ=CC`ZO4mlh~&SU+tKry*^VW0mjdl!7yd=e?$pndvw^%Xg6#VZYN?EG*wel zgB;*0P;Zo-9%SS$knD@Trt|Clek_=Z^J;K_7Hh4b@MmyRYL@#WZOwu(x!`(7%~wcp7Q2RjmVZx;XC6r@B*kR8eYmv)p) zhWWoeY*%(mL2+~BChgfc|4njJTi70L0AGY5qEY(8H?CfjeizZIy#Ftqk+SLK4BS4j zzW=RFA2>r2=_k?Q{idWTDg>_}%zEqh%C4QAE$CbY{Vpl2chS)&Z!O-Y0o;M2U&K0N zVW-LiA8u{*!+> zhiqmMitYb)iDL10JMb^T+=6L3`_>=Kk0_XIe)QJ`x1DywVLJ1l*Y5|?DiP|)Q}?-! zK}~T82s26~TxXvd+x3+xImu?^s=$iN#2EXoUn@5hilxK${`p~AHc2=}h+5bN-)iLTw zNC2^Zc-XYF?uEDMQ6&?&M;0GA;jwt&v0fOatoHf-jQyt2VhR0!uvq3*c^)gl5_9bv z7Xg24G|&XZe>0^gM-O4CzcQzX;!}1Vxq2rTrf;SJ(6Pa=HOte7NI9vw2e#rsmA zhuTrH)FAYsS$}eW$z4tqSBxeb>*UE(PmW)s(zx(fF6pyYJ^4qXS$Cdx12iyor`z~K zyB2BS+mGA5(jGsAZ4O_cc6@%{?54Po8*e9duN-uW{55`<^XlP(nY7P2nt3gGBP1h) zteyjv8iD~?UjJAc$ie?wx9Wpf$b%{5&F&Uuc;J#|NDBn1F9Ep*8zNEWQ{Gi(XL{2vaJ=vM z`f3Zh-vz#)Bd^)40mU#Vw`ixCUre++UpthMx3Qhcz=)T!jW0fSit|A01s_oZA9bAo z?r|4-iL^IAR_V{`BZ4bHDF`_>)5ouK?4Wrg*_de;J3x^n9E5oD;SbGZhl(s>b_6pC zmbSVK@xdrh_1YpG!VXB0l%9({W*La`rRQ7o_X^RF&Kvj52%6Oa`l5E~VhUz)rY=f; z`)n~A1;YVrxhciQBAbtdPG37+x?v{d~tTaiJn?8 zH)8V1g$Adu7GD?TGg$s*gP${sL!o@|^jH#4o;J_ywR1`&6|)+=n%Kmwv5r!U!m-qj z@`)5E2?`wOO<7AMiM-|jq{w)cd3NlX$$XA>kb8*awc&egUnDm<<&t{@UHWU2c541@ z`JsGhr6y2xr5-f)u+%w_OE=pgF!l!ipsH5biTBDRkAUI8yAWRoICj&(U9$l003(-5 zLd)_lS>nF2CeBn?#9_Gqc3-yRn4VqsYSsL1-`A&_l)CM#r`g*j1InOKI?`RVRyh3A zG50W5$a==B#%B3MCG=#+eCHj>dI{E782|RQ8eN7ZiVe914>vQe#Q~^i3*mKaOfguA zS>1v329}?dh2L?@gVm54nz{cGQqvC)f>1dxlHDB!{z5u1hBU^{&g4uTD&A!z)N=hk zuTu^P4AIzGX$=g>OD^1n4%z3?+*v(PkuHY++e`+JK@}z?s6^6V6MvsKatvl;P!_|C zYm4Qj`D38w<_fs|F2l~8EdW21@H)})a9zxBm>VSvA%CTRnlFn_l|^WNh{Bt>kGZxb zpYYza*EZNq1xP*Ik#jdr*$0wLZsEx$s7P>vCo}rYuNw zRM@QgRbYI>ML9b(Yf7|#8D!OrX1}>8L~#+9OfL-K(m}bPQC(A4T}1_O5pLO2Ri{S= zVk6Q(Ogp>x?d`7sAR0+bE_=tXn{@%ucFpBSdx1n|4DT8t4$PB>HPQ> zg96WrICKTw?XZ4-ng}ws)e2Scmfvw7MF4E@ha9(|h3|bEH*ZT3@RpzhS1HxA2$K_nAWY;R_Kch2LWbx7^9(xN)Zw* zmbue)wv%?^@Th*U?l(zpH0`?p+3}4}PV1hCh^;R7z5Qf~Nu2+7$7UN}7VGyL9Ds_SEn$bwN9~@F8h;{}U{Etij`!2^Sd8}x2YgY5@z~c!|DLA7Qvb9n)<|xMtLiQv4XQtUT93yS0OB@gXkw-g9AcJD z^VaRYp2YHvc+X|%04r}4#~4RLG#yCN-LdY7lRc0^d4}KbJj1sT;)qA8GD(BH(UJg9 z9zoV`nQ8I$T*Zee9Dd<-i|uE=yNpQ!9?uuq>4(@{`d`dI741 z$({=J<|M-f5O%JIsY-WCTzS$?Xps+W7acw*H>%SaePKXBnTxNg-iW`|WtweuIP&?vq2Pi0~U257~PECEmC3>UF8Kn102v%4=UW z0v5;zLicD?rZenyg6`r7C}Lut(osDT(|D27`BJyu3T7rVRV3i>jc7od&||6W+C|+# zW*TK}4gz$6uQ;~Yhn;@y0i}nsY(J^AlN`BnL|&#;aZ|EH^yOytjD&%T7X_@Bfqm$J zOW=9A((b+ewbujJ1E`F1B%4Q4(!{zpYXq_?{~D)6ONO_(HZ?2tql%RPCk zeIBFbLmt@XB^Vwdls)k3sW~v>9pL%LY)l~2+r49XvWTu~hzE`A8wQ=+w`hFYG`|a# zJ9i4;yiMt#ryh8&>-kMhDw=GMX5yN{+>9v_sp;n`sE$I zf8uU>V^Cloftj(Xe+q$cQ@*Zf!D193K^$t;H7|~}<|aXfaTGs23E~sQTuM(;o)!bw z(ke{H)_>qoRzx7PP}b#9gi($3-e!Ah4zA!)g9{}jL@Vt`I<%|@u`4k(FU*$E4D9UY zgb1Kd`rXmQt{_woA;IZMRUsA(+_S*w(TFk-q~ok^p<4 zJ+Cj1Nf?d*gy}21<7o4@oxGNZ320vC6TIoQ8QR-<^U?ybRd*M&*<>C`w{ zJz;xsoOLjJ;h@{xxcG;e`n=`ZujyouRS!aHjl>pF_tDk^ZV#z6IQG|gTTKS}ps;kC z3$rfik3&F&j=O+aSbyvj+H;g6B(Q$Vzz+^~e_zapW;A>Y%UikvS!hx&$n}ou2aC^K z(2S0yZw=j1+i|}QlKRz{xLgOhxR>Ecm#yvKGV4$u|PFW@N_cSwB$~~5=Q`O(iz*yFIh`(=WPG4a4?Oov} zxJ(s|7h5_ockwhmjgR4~iHD5x@K9aSQ`CI`OgT@Onx?c)F$xjd=8A-LzBi_eqv*x? zDYS~<(&aVb$R#hfx15%*uYTdP0fZ1l;7=Z6hP2zrZ>wYT3^}hAp4l?{)#m^3B8xi`Nj{=&iqNYvtr zENbG;&D7%DYe6BVn?beWC3%)IA<1Lbx6>U-?jCc$Lt;=t2Juzg8>wBi8>aN0XdlF_ zNWkEn=0zinFPC?`livNRqw}Z7^mmcT{?`=_xMYfcUo!H=aLFvq+p&@68GG3hU?PR` z_f4_*rA!acUfLy?qk-eSv4RGIGEmL*!9>OtbHpVxDfO9F^)a>duNPlVIgB)ZgWWP%9L>h%!iZV^yivQ+(zb+#R)Gs{U?&6|2FZ+E?9deHMP-Xt=U-68DK7WyP7Q>NiI|k(ho5>?bi%-lu zit7<7#5T7ilMmZ(d)!?XweNbF9NzVQAB^QQE_Iy-JSYrtz#t_RTRgW3SqDU=_Oaoo7BV`pxoJHm!MGLWOv! zt-MR2+?Manm)|-%!N>>Qe3z0Af_lkw*D;=VIp7{!_-CJ}v2SGIU>%%9a(wsZO~w-B5~?FUn|Kj={GHokX* zi%)js43(iQ!a7Fk5Ca@z%h?6Dm$P}dwh`R=%EGbXl2amjZ4qvLl}76OaE0bm@?+&^ zqX=CcgQLv%?anUVCW1)AZMgxT(?cTmV~N zz6fX@ninFr0dwl+1eo$$mGUyXEim_m`U*xn>A)B+wm5FbB22T!d?g=QmI(FC1Xgeh zb~ux?-F~rywvy*jUf*-q=G!BU8*~ZrPcP5TMjDQthx4w()2n&T#q!;^;%=bP+0D}1 z9__{zn;y;woQbJD_Xb(#Ie#*(VJXaWh)P(~U;1oL+4lh^S8Y$P!i;_-X}f?dD6jX4 z8H#5tZ+MgUsE4#wys$~&tmppdeGFxRdr7AxqQezaq7>9NxE-3!gudpJm(EHV=O=QO z12=jVk*g@QT{yuS{P%hFl9$* z6eaTF*wNjS?yNqxViJs_1UAgnxpW1*q}uhB`Erle5tkJ-e5ALHuyhMg z%xhOGcN=29XJdWtN7WSA4#&Q4d$S;9S`)XaPg_>f3_-1GQCnDxvlycalTH4p(XIxM zk>6Jvny6&{8_clkjIdUH*5a?N+VCi7%Wkn!kHZQ*f{d7m2gO;RfrS-TahIbFJL$J9q$#SIh0ZpIR}eO0q}`y9 zEJ&!}ncz{;JdsW_KA5oZf>>T(fi0ERtz|LEHELQ{NdGc9z`xrvmr?<|k1y`rV9zbq zFUG;DCDwk6+47At4F4Og(z+ydY7wz}UtQAsmpdkYN}P^}^)PN?a6J1#7G` zsYp2l$0JZPakQgf>Y(@SMoMr^ca*?!|lqB*Cl8QK&(cnY`(!F>QF;h#k(0x z+Gn4OW>(~51&`uh;GOA8hs=CuvnaY3owp+OuBVJOBl@E`eh`v%^ZSjJYq#YJ(mf41 zPP&`}JzDXN&=Eygis!8juX3*e)mZ$)6yg#7VGEH=5S{tT`>*esy!1}0{g%q)gr~0@ zVz|LO5HCB7qH(CM+W5FaDaSUubsL*RGeC&-zDqA4z2_v^Jit?mi^RA(0f0owzdft) zTV^0eQf)42_ZX7bNuh9o`^y|;ghwX^eebnG^#Hn4df5qm*zwVF-9hOEnQg~ErbK0n z**WUW^5%HJE@IntW|{3}m57BwgU$@X_YT~*JP(iT?t7=r-+OMbyzw5SFot`dS{)m? zktjpESz_{Wd4}%TmDddfh%iz?cCmqwgTG*6Zlbx6Tqg4QDD??nL+$!->4mtGN$6lJ zyhMYUVF03AJ2?=gA0U5v}X-NWEZPQmL}66O6{KKt+Myj+x}>^#icJ=}RtZ+j8+Q zr%|e*8w*m0uO{O!c|bDoilw`jTfh6cRmV#6qM5Ot%ri*)!|l!~aO94e)jT6kjS7+I zz9_{^QneqBb-2w}Y23c(a_I*Hz~1~b*_Nt8P!M^)f9(101ynOSX5MfKsY-r*eB@g2 z=32gJ&AXXgRB@imqHXhMl{!*rJ~r;u8;xncyBsS?h(9eMpVWwD*8FgBR@+g~f$#+< zyn-ZtScWi75T}(x8k<)$wK$l7bKw27$TAR`QJIGr`S|H1tC8MhPz3y@>)3Jy(bzEc zrepTO(vH#fUF!R=mse8j^@a?)w$nG5kuGvSclrRrucIYI@=C-dP_3Gdb3LczQn5p1 zFfK~x?h-`x$;B9xcll`IQ@ZLqHs*N-@ro@eD&7oYDlg(Xr-22XIl16ZV+*6V@iZn< z2#~?PpZEps2I(=)F>x2A8a6(1)!B*KTLhU!N_7?V`=13AjVkD; zx6Sv`Efsq#`3|@oek|r}n{VX38Sc7iK(pXl8?F$__D7d5kVUTiwf98Cr>GG8fD|=3 zeuJyvZ79<2WxAZx$#HtSzcTU0M01oSM+QwXFn3R#p_f~f@fmD%=niq3t}s29cwHDcj(~ml7^-+LCWg1xMnHYPZU-A=XV^#jvoE)7 z(mKfArbswc(7+j#*zW#w9Shqa%^Si)xOx zp6)ZPu45y0Y)WD(RXVh^NaM*-gl~`aXTJ1|iAb|mRA%jNl|g@^OoC+_KGz7%IBga|Ck}PpEC$=K2hbx9>tvIjN=#REgz3+V0NHh14k~-@ z_($1Oy*n|yXPWD!jObSZt(20ahE|yEJp?yb6a5m*nQ`#%Mtmsz!;ciKKd}H%3T;|m z92>hmP^)L*GSzQ@dbcB<+NIJi^!W*qS(-S#G{Zu2%{_2!919Dn8~omAunc8{)NIGR zge>y@RHMvMWzp>I%*VdaGn@q!?%qUoH}|iC^$k0(Ju^V%Z6P3@i0hrQBb@PR$A{>x zU~kTYoYN3CA-pp5&e*r)SY9nq-;GTLig&cnl-2_&(glyX0ya~PqS;Ed-2-S;!!omw zWeQ@VO7gs{!K4G?m({6#gX>hKJf~)LIdU>{FvJAh%-% zoX=6GSLzB$=QFa9CQf}d-0WBAre^obL&raeH%>p@Quhi`hG{K09{to8T}A6kM(6jS zlF_B#eScO4C>h0kjX+wF4j>8E2!&5ms9m;lk^w8zT5iUkajD$mf__j#UwSHgwnGkX zY&@XX3||2IHrl&=&ZAn4oL z8Rl49-se)XbzVl56w2){d+ACPCpTVxQMhGEdb2_Kc`Xi4DHMyua@_tlywPXs+a1x| zA6?3y5sSh@WS&m{VV(y0tiTE9Wsn5IiEc;Ew!Mz(*0Zp?O{h8Wgr!wkbmV9@+_8x= zzT2?j{(KykNEcwNTqDV2j#=GiO1z%My(9^ID|P+Hb;?&v7+74pLwPBlwU zEil!6jo^(<>~!w=I-O2F!7P#zuyl$${4$J#d-GX*NEo%YpwyG2orAg->8rQGmm}pF zZnqsy)-PfihBfhe!S!x8tlYYo>wscce{ypBbGPrO(j#+vnY&x_+_BEIP%L(^qnKJL z#qbJ6xz^@**)mool>3xr#)+=v3rI!U&Cjzhj3K=-JSZb*7YDH@1?*mGTOmX=MRS;* z^2OkOp1UuYWJ5ff%vkY^)nmj=Klv`F{5^&8 zseO@?WNPVBG2FyXxsan}vkU^Mx^vkC@GjU#%ix<6EH8~p9E0;=6xH)_-9C|#AYk#M zQdB4SMJia^sERI>^n^*cYmpM*mSbSY2}P z6F;!t@G%OFvP7Ava=K~Tt_w24pzwfHI8#GxBd!3l5PzmZXVXvD{^Lu$#E`dPV}&0- z^tZs`e`9{t0^kBL^{1P?2*`7nB9gz;8Y1FQ)LCcU_zx5RjjUDZlqI@5-CqgWC$mOW zI?(4AA?OITRh-kXe*N3DQ+8S;~RsU&A$^MiW%RLCl*hiR}Frej}) z$9@NmWZ8nMH4N7V5*qGEep=39!fgafJZ^qslhD><0EozQmOpJAnQmKu1bLN`tgIa}Mn<#`lt1~VDqi~= zJv%hvYr9UI-LXb@O)v)ZROQJ`KJdz}fAK5ta?us56TK9;HAP&$M(1vsSug ziw^Y@a^IteB45;++@H(RzQa!d)+>*w#=^6z6cbhEqsAfjW34R=0(!#?-x}T+$e6bU z-x{i-fm76=D@74%QZ)^APSd7zt8_q;X4WU3$GwTTHG2Xc>O-ZL*#6PB@B~c0HT>s= z^BkCG6cNSYeKpBGW;gRp4e77`3mo~W($}@nqGz%XhR38MRqdH@Gn%~5Ds8EAIe146 zuh-@hb#~+tns8ShhEtvSu z2);+G4mH|;chXmZfbpLz0R>Co)DXJEN_0wxgMR_*X!T-yZq&)ZcaZ;nrqB7PK1`Dy zI_mn-kNOy>WP?)8b*c*1RnO*ilgxPcd!&)Q&CJD0d9d#uOs%;X%qsru$-T|Wl7uPN z8#W#@m83u=eIMAQXawr`%J$ip_!#@-a4|IP$5QkABE;o9oRm9UBm+n8ILJH!k+7#FCCFsd zygj)Lw(mUrQAs-Dn1$Anr_=J-Ds8wro zZjcH05kCHBQ)4QnI~BpWiT6Jl_CM|JtVA*%plYOEcCIw_^$DO|2+I0{jvq1?c4owH zq3%06vqtX>eJu8Fp&77g)n$HK?=Q~V(Z484^^#>Oro>2tosthjY=V8Hhr8lJS#5~b zBD)C}*D9luaOjmUS+p*EcmXxQGbI-OTN*_q1b=?EAaZCaWXbZxDRIw1`D3K-G!$^l zX;A%~BK-`o9}~z=%CEK$z}`noOJ$!26K>RVn~(#_EAjfTp!OF56V<6}O04zI5ntqu*7SfF%n)9h z`H-v=$HwddZR> zHLLpql>{TumbSr}LH%5@8)K^q@5h8*)u#IZFm1Q4zN#0zYQz8Vs?W$G4Mj%`6S}>& zja-FN(Y>3e?ObCRO3riSE;Poga>Fi1h{L>sm{;9yD84KtK?o|>p``TY*9%%UPmzH^ zFd^xJg(=?!XBJNBI}K11Kc?St%>2>f@L`DXBnm(h(?^W@5t)h~gGDkI#6o7&v3c-e zC=t?x{jfDE2=8HB`${MxnYCo4!ZrIDYR>P+SC5=tB)IfrZgbY@!X==-+z^T%aZ6G^u#M|q`9z1 z*2h&U@;dRtuBa`NT3d}Fc#07{bWIwblZM?IbblI;l#6w79l1(4vK0#7oA>;#e*eKu zjt3uhpK0ePuOjE5p43X6}8|VaAQFDNk*IexiWU_hlwL5-Mh~G7GPh- zhv1=_T^Fm&rm2tzVW{;UEyN1n!r0&NHfkEY30x?b5ZQ39#nu&$bR0Mc=|W@ZLL+c? z&M_?z-wD?FZ?l=W8GoYA5jeGom~qOia|WK523s}~Dveg3=XoCLEV863^t zaUTJRmIs!nl#g9gg5!w{>G<*tMv zZnx&p&Y6AD0zSJ}-}bjy4^t%(=<6HSIGxcz__V!MQ&4X} z*4Yh6N@e#u83hXnrFt1Tu39AeGhH0Q${qsJy~n$d6M}6AnA4%Ir|`pcz-g<`)PSFn ziU1^rA7we$&Od~mQd(TZtGs#`E(-TXJP2WZLGvjO_uKd@q6+UR3>MKM9-M`$N!3ML zE|Pm(P~VM~ySaFR$m={gJg3He`so6BhX3KP!9V}OqTHhozjqh=iONPEf)m9YRcr*h zPXq8PsKy*Q2|uD91{JF)L<9+Mn!e#rbmGiWbi~oCA0~^wvfDEb;oIa{ougG(tpPe= zSE#yaLQ%?o{<{t%{MCI)&b13cC-)z{M?KQRJ5V^zq)_zs-bqW*~s zs8+D5mRoq|98%Ja=>jF)Sk9mmxeC>?o+!O;b(>VuerqVF(q@9nfykmh(NqXvVRBb0 zkn6Qkp~2oxu2~5{O(P&2;1G1~wA?cvUo~%d`dX^JNTZUQ5=_bPeEb(D*V2ejQ_=Fa4zz zAl&!NPUr1BlvK{2Q^1vMWff~c?T;HrAvt*}>S*agd{WsIv4jtzmmh$=kzlcjW+bZt zRtr%PU@)Q)BQ~}23b+@AYyX3L`9-vZqY7rcw8O@i?C42wyGBz^2O!8m*XR7CVbMPL zQBySm7j!jsaim_f$!@8YWdc&RK>93^_-cfFTyt_r&?OrX(Zk9f3-@_nDi;JzRRI;m z2MK;6&T~_ab26m%Wgvb3XqVGy^d3}>ym|LNdK-E$34A99TqAx;@Dgt;Z4JRBJYjoG zy}`EUJpb)3&%p!JM12tV0WZMDBPR-v!k!5q%Pn-Qc_(oUG->t7<;uWLPeEV|4aG-q zPc7%{NWCt0OM2n@$3t<9CXdM?%Lc<{pvzo`N~V9m5YWs-hu;(o>#rG>M(9;IK*aV$ti|e3;$2Ra+LGGt+ z!XD@}D;uh1#Qs5?{jCWRNe3=xO>vbS1qI0a9Q)h*>;~-=htXyeRAO4qrQ?4}H6YU4-pz~kd?AGEnoMz(DU1wT;CTNr+kiX7$9TUmmrT94U!H zH`%bOIM`8c3VNXN!<2>A)6mFiLe)B`y}U!D902=K6{rhei9s*&K&&3oeHD4ZeoVxV zGZUYpfvvdrGCvn~DjqOtD!hvDQvHVid?_Wctg77~2y}l?bnkH^H*5HTg+oOVd}~Zi zw+^`3qd(m2{lDGp-B%#V_r@WHP0Z;{s!4Sbr~olumil?A#Xb8aY6*b!M)*V3Oy=Br z7EqN&;O9{feV2i~+Br@(J?)vcr{E41*w4+46he5o;28@0GY=BKMKyB=LwcmH{5?15)Q7tDDiEm>GPA&d^nadc3)8Jf3%7Y~sPmI<|k4#;`9$DuWK^#BZG zILXHn3`ABIo2`R#jnLbWWOJW;!2)c&G?-k|1dM=T7?VT!E|U63E#rZv6z{-x=-`f& z;Q;e8TWn-ogKTE4tN{zkis4*_Dm1N=PH57-fZ_$d!CQ)V__%PZc)tS=KXV zST?@3NW&=P??|KS7`0Tm1|)8^&@N*Jj5ErjK&k2)aMdUezxerPAGwipL#_Jhfoha_ zSORb?@teQISGg&@6#YE+W5yNivv~q}OYcBba-W2GnGR}od_MWr2ZaO|U;~3g!|rpc zoP)4Q?LkBUr>E2xsM5!gz6z0Wd-G3`A0EITJ+mE0i28o2IFg+YJ$y9ZRMO;C9TG$Jno0!`<|bMg_CParQI znM2HTuRdrPA(r`cvub+FBdh`#1+d?IBq-#jXzKf@M-=mr@Ca0lEnrk{4<(6afE+x- zg$u{`gAJ%Spm#o7MoPW!DL9SN)who%M(-&HdOU7Kzx(ZfsI;JGcMB7lpH#eqpTmJr z(Nd8P5>@fjhELA$IW9>Y3eH>aq6Ze_EhZ2yXBuTSbx`sJosBE^p@!ix1p(|w4eP`Y z9GIP7e#k3QiT#jQ)IF!IBiEaxo$hd`4R-M&7EWBy6GNB%2@&8pY~{=#)eF3373o7h zSsM(sw!*sYSZY?*#J`E)reU?(o?mOE02=lq!=$44iKVis zdvzW{GwqBYtWT_4_SZQY?tSxFq*KfMJkyUkbT|^P;N4L@XG9Tqb8xUWVFaL0l%gi# z8W-R2kiUAqxzIu#3!c|ENSHCU)R7YO$^~~H-@e*Ew&cLX=sTY70WHJ5ZxwO$5ab!1 zUQL+1&MT296f8ypr@F%!)CmdMcBuk8;B%6%ezgU$TYfiI$LFf$7eHY$>$k$>uG1Ne z>qzA4dQk7a+FkC*W@povW}ljY>-b$@7vWB=LQ1;@`bSJap1pRjiarO12`@7<<{j#` zvaeQwoweiMg%J~|+PW=OKf{2SvN zrfohaUZCHqTE4L}t*Y;fsv+!*^&@I0(l)saQnX=&tU>zFb2|uG zibIokhn$2QH!R^-@D(6sK*G;@52KKw#%SD%pYew^2jLY zEg}s;moI$QeVH)kA>>pJk@zYj4jy*T%V#8BPACMZ4@>4$;qd~GT6;htro0kymMxky z4vh_T@kd*Max!NAvwj)^JRGGyCu%$}2W)x7EKflQV1lI2RH^|;PpOrYm3eytbly~c z0~~^Kvfrr5-@0Cq9Ygl>{EqO0PJUF&dAW0bvP#&N0TOvsCFyK-q9YEaQZR(DVcTkc zKfab-Oq#=axuYe*D#L*h>D*C6!9`4RsPbo$N989M3FW9)(z+}Hxl{LmTrd1^$hr!> zoIs#eJU8(!+Y*i$Z?>iPM+bTlqnJ-8<4x~L^^a)I2qIzAJ_U@eH%kS7{I%!KuV5Bj zRqDADx#UM4^6L&dH50Mr1|nBM zwR3qGX!Naig%@GW*1YIwMgaoSAm$>}#Ip0IFGjDqFmw zd&+qY-V34tRtG}SR3_+6M=-;WKjugMCAdeW@JtGB6hyJX3TtLx$pho^&z85`hgcHE zQ6UU5&&d$=GyU`uxTulayx4{j2K;R9*tf_Nzce#$H9t4&a*T^Od_~b)v|@9_om-HE z2*V+uWu&nr^Kv1z=w|Jb85%kB7AqXJx#`LAVm8dle}iAdC?jWtyqm&nyCY zQs|42=iI`?F|-hEC+&s9SBx&kAA@OrS3l4&I5>f44=~wrL$G}kH}e)U)2@<>5I3T4 z53uVxN2VstZUTYa4(LO}4S^aJNt>X3+y_7YLk{GJ!XA`U_gh2wbg>POX|a5wEHNJq zqNyBrXFn+k9ss9ca#9}bYVPGMz%jrYo>18^keo;Lu0feIn^kwKw8?rlWBD$;d5^@@ zpgoS8?-QmNNRoz z=yBFU+BU1Cn)d7g2&dPggd4j{rC$J z{)ZqP*`D)K{=P6cx22^CbWANk+t5Ep+48jktlsG(BIMvNVNgaB;zU7n#F4QcI~gpw zoFP8`e>h`lDJv?zLE&0|Mlj`;yZl5|)IYJhygAK&me7MUE5E4vHBvj zkdd}@GDF)o)q9&riDe$aA)Nvz`SK3T#hCmw0@HmRW?$;MBv% zah1#O)HuRN1raF};*h`yocMR3i}dj#990j5JO(`z3m6_Tvy$v6P~q^f$7`;Qil2Ck zZ5}NdBQ?zp9TF0r#7)$Dj_SolmR)~UZF9W(MS|)svxMc;k+^Dg(K05p*sNz7gKA;6 z=kA_9_twW&Na~Bvo|}7g?7XGeIrfkcuS~mN@7vRHd2H6aEPXb;Z8p8$);=`nnn&BD zYb&PAv20STZB}xnZ^iuS(-F$5bSwpoi*I-Xq>WoUWODNBK>34VxqM|_vQ~ApOYloi zm_93{LTrdQZ6Q$x1qTMikhuxXEPgl8r`U$%ftHalM%?lu3@}qmvSL{Ta^_Z8Pd9tY zw?IMBtmpTb6!K7Qackec+`j$w3M)p8js;uVKwae!{y zU|Xks9ZaufL?}$nzPCLIL1vF$N)p}RK6uCTB#bx>BpP6&h94Rl54j`V_4LZ*&Ug}S zASNL@dRmH*b8)`E*L-W0W7JF$?i|GPY~kVEx@6b6FNNSmh4kej*@%@AB4!KTAKF62 z{wBtAA#=f5D1vNy(z53J9FzBybN8YB zU^5ecD8z=@;5`*(^rVq&+%<33)c_*B+V`_SWKv-f+ZHkch~Ewvv*kVqG$IyvSb$_E z;b0j$8?s>_+hRA>cC~-o!u^a20*mOuBaV=EYI^HW#3NjReX*1XWmO)um}>jx1XjKa z$m}W$#&vA!g&9eYQ1^vnIK9o?ApZub0f^1i&KG;7ApZFzmHSXUn(E~MFk#-;FVch) z^US}!vj!5B@2C6RnnP&%dM!KVcICr9hVpqtESPJo$1~L7^xG=)iHS4GcSM&9CU=%9 zMXGX2@wPezGWdS%@^oC<$%4!5N|jm4lzf7#E1!0nd^Tq%vMnYZyD?3?%(|X*qR(wt zQLs?8i7w+X06=T)^UN33BwrF#8Fn~)V4 z^_H}ad1VopZXM&>SH`z@z_mHrYjzJB{=P8JNlkJQ!mx^iS4tlYzLEujHOflF#7NpS z+{NxLR;Rx*t#7r=vbSgf)Q0$X0idkot~~1&a0v-mxlYv&ot|i*WrCdplfh9(!=t4W)ud!x86g}7her^>XUOk^l=yluJ3BVkkf z@?7wW(`1OouEE^jCH>Ot`<4EV-C$-RaMb@7O;YzI))P0$YST zbHrA*2+t-LN}+>{!5#|(vAz(oaxB&A6KZ=?lMIsQ_B75NT@+TxgSjm?C08aTahsYt zm58yKy-&Ul31oKPGgZLaH_yo~+}%-V7cfTc+uliQ+*NIvOZMOZ)#ib&KF8Q_2XZI| z%Y33UgG;}sGsPw-F1Ei z9dEorq8>JwJl_>fdAE~S4}dQog0HV>gt8$t4ec&nt4nBG!7aZ z^5}DPk7fFpHh7&DT-~*^$#*8Cs$Rq>)7Lgb0mZNXoTcaviZh?m?AdidK{x&Wm z)&1)ut=2a6@JtJK>iX2PeHmSukp248j;Qo*TC{?3z`$qqWfp-OHj_O%54afK5MsP#I|^0E~#xH$+TfvHDaNr*Dg>Qatii| z=1$kNAbJ+x>{}+f$-sU*urxZhY&k8vI5#~p`_#h7HM#y^=7{nHl~Xb?(}r6lg2d5d zT>rc}l;P@dKECtQ&YjV0{&h3;uOsp-queD#7C&WE?TD8$3z2Az6RER5Z)q)FWpqK= zQ)-38MO|`C|7Oq`PpMDDgMBjJG$oZ+_Q39H_oP*^V=Q-C&<3CMym60DZOsuxRuZee zIun0Ozf<*yRnA1wIFKBVF1Up^hj^Y?sQgB`KaePi`<3OG-voa{(uOJbtySgWqC##n z$q_AsQ)w)Z%);xzp`|lvm|@P{IfOMSthCJpp_JENnHH=3pag^5I!cn0hBYGTb2SZo z5!WR}c24t?Y*K#DPH6A>vXfSU+ONJInw(n&@N5{vWBqAwn3{478teW6kPxgAz%|$O zo|U{VLc$zn;~V@jT5TU~K%S-lPA{de!| z006(0uyv01C`i#TK^UY@8Rao*7m;wQM`FTX**x_aLz6Ph!1`Ly7f+qidc^%?SBTb7 zYVHav0HM973MgBOr<=@3{Dc~IjK)tCP*%kffOIE{y{M|+a1SC5EmtRYDE1?1-eG2r=h04dm{tGs>- zo*!M24$_L8@2^4FXb zmHTc2Xz?U4Zx93394n_A1XkB!>gD>C1$_gEFk9SIJ@4*-gC3qcr2C!vphAQ)zudia zDMe1HoB;QsEmJ^$!(!`Of#@@PJ;c3U*O5|xv9bPxW%dYz1hCU?ftt}2rS}ws!Into zekYPK8_c={35xb!oIU0`#B;t#8m%^uFk`jiFbBd%yWD{~cnjPT6UVZ)o3v(5k)IHS zFz{SIWY~12Wz{()D@U*TLcs%;kOVGuuq}5mTPjdRNU`B$;OXCvFXpW*cEJ2TvM_yj zXM67`Wz3+ecH#6@oWb|jj+dMVZ8roG$y|lwGz)I$AD0&|9H-{y6wxE-E)jyQWT`Ee zzb5I-NX$upP(kwiA$W1+ODcnX1X|n6#3YJv_py~`EI2QWf@4cBwTL;f(0sU&i#3pl zbgy>YkJzS*w6l6oIYcmnVpiEBX>TCpEQ&~`J*pt7<;osI%`RawowpRWLc{8@G%*fj zRAu8BUGkPD8@x;>TV{8ZTUN) zww7K1wZK$G^^Q{}oB$@EFPY6qE>LGRsOz)eh#Q)NoADNOrAG*FseZu2<^@P9uc9zp z&4r-!<>p*$QajP3C&AoiMsBcq-+pp!2kFslmy_~iGVA=NKSHEtZlhM^{ACHHZhRet z)`X~RR$qc4G>A^N3^oMvtRE2H|55(VD87KZBmvqA2Nu40#Q1dz;#XVS_mP+3QJ#e} zT=+=%dI{mHEeT(*HCgj@Zy@0-YpwzbH~etjE6cLzDmS8?u3apuLJA-gym8wB9IH`Ln2L;oF_>w1Fw?Q;WbLDP{W;I9an^)W7@}6`5yhiF4Zzpgy z$$DWE3H`Qi@jy+6a{yFem~}`Ho!?seOFjbVT+rEAyhbACjIOIY!k>irryfwcx)rrz zx_Jjhz1>^L7wif@(zj4Kfd~DjpO2Jljy<6uCl>8IfSK(}q1bUv{Ey8mmuXSwHL!A4 zAe_3sZ&$X@{PHA`k3b!6ddx@y6*-}u917io!Bulm1ihWKj^p{x>P9HsQSx6j_LKj> zyXn!l91Euy>>S+=4htX3h_{k#(6V>FrSJDTzc&r}lnC{Cb_6-?tXk61 zcgcAXnFV8py|lD7$lXs{MgEY6ssZyyHe{B&&XVy%&ZkH&3t=^M7dU(`bKS zP@Pr87OR(9^dwkH3i!?>5OTMw^7r0KNE%0U19!Q*XK6C}eXGjczd2M|E%IOz?+cvy zW{`Kl8^j^yZna%e?RSFR6UF_4X~JXK(8XdL3R9b5RjkR#U|o}99>_paTmY5R9jbcr zf>cjrE&Jw7^jvamzY9JNUoYhqz}L zMEZ1NY9cg65KPK}#?#WI(y?9<;HeOq9@$^pmn%v{B1+=#f#c||&rO7}DEKZ8QbyTt49@}NBB$9eokd9CO>lqbIPl=Sqlc$Jj^jlCiVywA+?H_jWQxkcOhhKnD&Oq=mhTAa2L_{CJ9_#X zf(_&gPs#uBzBZv$lVSGcn<3nZn2v@_e#mJABV{N5;lT0|t-QW-0XUeGu6&I7aT>nig8kjmD0Zyvc+I_WzCg`@i`@>WzvzRl)HoGgN5e4HOH%O ziw8ujx*f;cj_xBZ{f_`u7a&?`PC456TytF2gNX+s5STu>{+M4xOka8xcLZDAs_koO{U-`H_;9hFNYU3q#x>hcWda~obXH!tPClN zxvV|&BTH~Y#0AYu<5OuM&yAcs1T zBZnM74nkh-&vZSO9R`|}HS=-&OV7IT=6qHW_Ukix-k21Sj9PPi75#_Tw1A4I&{!$T z5yQKCH&#bqF!8vf=^B1&ly}4!oa%j5((VkMD!vfgefwPSu#Jto9uJ2OUD%iK=xa9Y z8BlF|oq`f<3X~QeD$zwEYzAvAq0GpKIO|v#_;d*8U{2Fe5t~e6VAVSw&(F`ZMD0|F=t}n2i{^sVa<``Fx15Sb3=wBW4T_68Av-s9GGZw@Ed{H{OMk{j4KZeHvn3}s7 zoD5N4lFpML`L^HZh8ZaAnSyh1yq^T0hw?p&tMcgb>^Rr$Lb+s9cxibpCaj9F?6Hp0>27d z9K6wYq$q*N*%EO%IrV%b?=35P$n^^TAzsmF9WtCaV%1#zBBZ>(;X#kt(H8IvAIK$} zA~6m2IC-Q^5fi|3KYY4FWwTGWPv`P$Ryh@NLl=Z3VQP!!kU;FZS(MkI!Zx@3W zOls3{viX~^>;fnA(|o#_tXyT|!}VI1_FhQ70Q>vFc%xVTNB#hP84W@8u?^BpK>L$1 zRzMOyJ>+W}?b@Bqdt~ws$<6!o{iCHKS&NmH zo&B1;|H9&Dr}Z*57@G!$zuZdKhv%t{)PIxXWYW`Bct+G8n6K5qfJ=bGKd-&=%K<0y zpaJSYBFRv}=;vWhXvyB?9k^ZQr>ra%HbLPHQ$rn;k_V6vAu$_eD*ydJNjZ3+m*o^61 zXyMp8p`yyAp)0dBqGM94STi-<@VXJKnBskXy0T-Y=-;;d&jYYwk2$`>&B<6%oPNM5 zK%Yryu9ola?z`U`+neQK8a?|8Zni8au9kx^ttHFaLS|+qsWahiH1bABwL~9f0@=vRn?xBUc;v#Tw(NI$kh?pAx7nd2 zDFZ>4ZAjEOE^a#h4J~x@S%gRHVa#Su>gnp%J^6EphF8a;NYY6FqsHwy=`2(LrUDH~ z^FDLcchV{?^VJs%wY)U=ksEA&dRJ`olybhUhnfntV+0WDh;wDWYsN3zx>jDtkG*v6 zp#8+5a*NO07!NfuBP1+hE=Moo4Gy46SIheUYw6{^mzOHYY#~`1Yl8d-VGKQ}PIs{X zST{zXqIw!W_URe`0W(}CkMXWUr2SSDi@cCvk6D1-G_MsJw0PSZjG%hihup*Wu4a!D{Pkx3)rat|jW&-cg`sE}9RP#S_$7fI6liJfgc zye2rTDP6QLaAQkiJd!+WORUy1v!~xz$$diBV9V*%G8z*@*L^=Ox%^*%zgU9pXo)1* z5@w{1sGU_mP-t(*ZhjSj?fo4%|FS*x`g|r`p+eyM9&HGasV^^!EtpJqENRue9Y)5T(szTEoZT z&`el5guv7)opZ-=7a)00S%Q;jgdAt;xuYPPQy*x>}+(-jSUv}4G zmxgh_$OIVkIptu8g~luSBZ&1~cV=o&4@H7vO^zbZ|JqR`CDY@jIEu>Zr9s$|c{nyZ z&L_^4%fKn{30Jn#@zSv3#HOWLp8^-WF3Z|h++ZzGK|5O%J9h>5tffY4hxSJJb3*>x zJ9`SosXV9)=;3NAkK?E%dX#E`j(rdg{#Kzz?#T}pO1LdE9Hz}t5{y*8Im zKsH7sKUexcW_xmBCN~c#DtcEDL&*OtLr6-V zng2+-IlDq0BKv{MaxLnI4+_h1y<@=>(7kXsDBpqDa%goes#*$JVTAuWnK z@?h_F37*=y!fak~{{>d15z|PzLx55vegr2-g5?MZLoT#Y;i?J?WEp2h%yf>B)c0~$ z1#fdONF8$cq!zp7W@LlbN!O+{0Ur_Cd~qQ^_V3y3h4ygL$ynhuZsHh7iOT>buK1sq zxGX-7DFsS)1mNijQoSW5`O#9ki@DDCu4TLp=_JgXMDskgOOsFg;Mpq!4;fRbXht^~ z6uz=ZQ(E5JIp;Wd1O_F9yQ*bdcgla1_oFeml|sJ2vz4<^xGXd;07%T1!!Q5N!G5E|a!L@m%SRx2m+8kp6I)Hy88IE+g$QzgQ_^`&#to^lG+FH{lOgRecv_^K&sdd4)wkeqxd&$WZxQ{+cHJe18}6)bCia=gw}(G3CI>A+V z_JoQeLldV;QpqepZCdGbvjYo{#YgIqJq{}ctDekcfIzi%riSzyZ)ZsdKwiF1*$tAF zj@_8~5Mg7GF#|U?A1Iq6Hd=vZoM>qd+d=5@-qEQmkJ2 zqV>TWzK~qnNGPn_TjH0C%@6u?FRdkvq&gcrHxomQFEzY(;H+9ulg(zUwO$&(=aZr^ z=ATPo;7@$Z!R`*XD_9a2oNHR7`AdkuE@?$~X zb`#2q10&Mnd|h;VLF%o8P737sz7o_uM(FZeNa@LtI+ z2S_<(V<8BqplMs;zj$8iBH#PFjW=>Bc9T+2f+0+ z(!^a6h1SH>Tf7W_AAX*Uc+cl^k~Am8;z`017Wp?5S?nX9&TjA{>=5x5XV9x_F1v1( zzlUpiQ$ylnaLMM5;Ln6qi9q9~c$mOTt1Cw=MLxIpmG@7MabA>4D8X>9nVIv-VO4jn zb85*Ns|Tyej7USKDhD^w7CA{xHbVuuWxW&zAtl%{M8-DnDbpR4r>0&xH;<+n zIHq{1l3gUA)e~*^ z4!(LssG#dRGmp+-ON%+=dN5s!K8GCFk5m`EJtfib`uN!7d&z(Mayvk`EI^klxXP9^ z1+^xqnVT0{w{(@Mt1mRZcO&x}Wnwea>1j>@ z_u6LLgS1Z|+whF!`o3HJ@~0GLp;+zq`XYP!Vx_7h&5BkW&}?7iz%57S#AKuT1*`ZA zQTr|kM2}`%^xj9$=XmIDQTQsqP-H`-!S)Cp8?9U-pLX zo<8MZP0`7~QG_|sB%5=gd%%TObFb(0TRu|IX=&Q-_~u(nl0zCx@angSw9%hrN;VRZ z)__{wVBdoJwAj&aSFSQ=v`^c@4oKO3VR1-qMee3lIAMpD%9XnSBRO}}w>&P=pn zex1WAQDiLzHz`K( zTnznKZB}l0RA3eRz`K&Z<3%@UH$Qcr%}sT+oRVi=_~h}M9=$B9NXK$Icw9&DYP*88z@cSG+lQ)08d;IlWuyo@;{S z`_6XtKDgr){=liyP>D7>K4*He<)>`-Qq(5UO!WwE?N(cBF4Q*{tl~yj--5(l56}DUT=3jq%wjzb9r!J-WsK+CKZ-IZAf8M2lxs4tk0ba#48Obw4YoqvO0bCWOubzf3 zfz-~IXCjpSA_kNr#EYM*jj1+|EO0#4c1ost!qKR2m7DRcr7q3;)LxHmyq2oLI33ZO z#BiZy14&wS==N3;(tdSydVxY>8oNLL>;uD^Bi{Nl`B1h?xGF^~>k#Gcp|CS%@lGd9 z_Y~;x%E5mzrn;;&Q7#?DGg`EJGK~q>5kNyc&FuR#xWpS-edhv<^gO_U zmlEv{y)A@AwI(~Mt0fqS87o71m|#8pYQk@~YoNs70SM*awdolo_Nkz%E z`^%vb-~?$Y5@US=qk4Jg$Ay1C^cpcFFX`fAZEm10p1hpX3EXo$=YVtpo zX2$G&?lOFahn|E3BUYp)jD)vS2!ePP<=&E~KB+^si|_aKF7minUCBRB;lA()ey`Ko zGeHCuK>O(S<4XlsYw$LYow>R6?B5ra=cp*oW0d7cq0}cN$h85x#AEH&&xk;g;BO0f zp0EI-Jb#f|$)*%9&hi!VX!p_Eh0#1Fh8T1IfBYflaY!Z**(13!shKU@bJ%q&4p-Dn z+J+wv*K9t(4P|#nLL@s;`)Ko2n^4iGKDP9Sf5d~s8sCN^@iX$r-g!sf7+IYlK|bcI zEhCAq(UZ5`F#xYs*OUhTuo0WkDijj6Z^Vs2He1W4h{v{h3Py1Kuo1$r^HeY}enzW$ zy4?a(d+U5B>F^PSe}Y-12Ha`ZoHj&4_~En8OUIyqTs%_V@su>WvFR(csB8%Zg6{my zMByaljwOzJ-peRP9*^0{4|XEP$K#VMo->-BCEhbV*dURn?TtJi8}b-Uj2Yr5H9%r;Wf~nrb`|Bi}R@e z5mPh-Fjvgk8M9v=kx|J1=bym>f~l4SC?-T55JsP`DvjgaACi0XvONLC|1!8+&k;9q zc%&+iv^p+6tLe40yC+jJ@`vr?TT9%8J9gt|FzVqkf`oN`sivPp$Oa;v8hHPdH*V!_ z{fJ55SCjLhq(@9zwPD0tNobpSiYv9K=AIj5|L$VBxVIsWa+iXA`bl$;w23!?X+ZeZ z>!`6WlB_!=8})S6n>l0|P8r$j{J0EP$T9@{*Owu2450@RRNNQHiX16Wwi<>{MIkqC z-(&jU_5o1oDHPo*Qb(*#tH31=TtYVxGt~)=1b^Saau{!2>iAzANMkT*7xNK7%Me1U z{g*uHmlF5b7$3okJ&s(85$jf+IQebnX1Ek(wP*ivDPTNR+?NdP#nBhB z8$-?90FM-)i~i6lXj0gd`pv_oN?qW+un#DL7s+WE_Ip-iFohcDIN5}eRlQg>1&h!0@KcrwGdf_kH5lbd|tQnMX|6;9|{gu#*IWZD*I z6XC0;=EJYW&Kyq4e*Cx}|K!+~@RqN=e2vfvh(G#6v811wt$hgS_m6}uftO1w)O`{w z5@CQMj1yW|wKIYn#F`Z?|03)BMcrYz^yxQ)JA7A9-5kg& z%WxL&;xNBRtJtMAcvR=vrhVqu72g>&>m(Xh_Q-FhCRg-L{ow(>CfrTjjs70{V-m5+ z15Px}JWJ=pJccP2nk%);X@O;}Ne)jWzlk+RJLn$-N$Q}^Z9SG>#6NS`A!xvZq=jE; z@!u%-T4ge3IIM4NlcZL{cfB$0CmkWrc z>;xyzzpPi|Qvdi=GEu0Q$A>cG}Fu%)w%kg`@ctpao~#E-v|fiv)43qE zF$Fzo&*oc>ugY<1n5VFQ^>41-@}ppPcfHL@989#y8%wd%{R>~(ecdCMsk*g~wuY&~ z?4n({a>4pg)oYo7$=z*kS#1U~#XD=%tsB><4Gy+l zZPg!p=4=VuTE@eCy5;saZ;b>I3(VlEEDt7C369-Cnfh^7g(>P$mCrB%nOQmMZMLh7 zaPrM~ok&hkpX#%cADum)@aG&2ydzkzjt&p|A3G<19gpHJMp^m+(o4C!jqfl5aof$` z&0!~EzBcn2m1P4~ZBKtNb{a7V6r*xQe-Q!Xb1mrIbHk-V}xvre!r~R09&IU6|t8B!6(N2_%+jMQQ5e?sl z+ta>>0T!D{1i<`71n}iAGLOBPW2GJmMcx&C@Ex_1d&SK0&{6$zOF3=$A=T&NHX%Sp+t^>^CrgMN%n5K`ZlCUo3%4Cd`aOG>%FiSx;_2@W ze+5D~8el;a)P2;5Q7P&5i~evcy055a+mGHa|02OJ1~h+>w~vT|mJ|$@KY;t@DYR<9b|M{`RGmr)i)V2Ic#1U?n``~2Q zfMo1?FAuByjvtQ~khZg5z+#knc{gnZE?vd4#b!gMSlS7HthF*^X7@D(LErfA7b*=6 zsL{EyKR1+Hee*H3Qv{-EVyHTb5hBKKyT3Vwh;uO_xr+V~YlGczckBx8fVIW%D*)VV zF3xZsdPwgNI1X;nmUxbE<=_7P0DQu4^+CI0ME$~2ig1U@>I%w699ccZ8f}83d(3(e zf8MC7%KAs%HyQ6gZ&Pye%aM@9T3o-JvSjQ=iR6#a58q+j+NfWzf(Aw0Jv+gJQbXw~ zvFvH7T=%%9jGToX)H^@!Lw+lX&z*iBF=3nvL+S2OS>|Tf-8r$xdr zhDl7_gF+C!4CtPmK9yzeeTe7trR;`(ywFUX%jPW25km-oxqYjOa5Q_4ulO-#1G5$( zMD8yx#!~K%OAjDbAg6+!lREgV`E$N`jJYKeW8N9G`Nxay2mW&dmW0PXfnx zOuxA2Skvw5`DUMV!dER?xGO`BNVBK?kF)Hry_Lwvr=xASZ>QaH^e6Zd7s(7vH$2!D zcjvEy{oF*uJAXWFtvMjvR}4ys7}CjPB6+4?#V*LH_Y7vc^;8(RBSz5 zpL?1bUr(Kdt|wFXWHU^$JD#UYk6f-=m1sDDL1l2v56Cwu2-*#xal-cebh(CQu%g3l zw|vJb8Ph<52b3;=h8hyrgw`-3Yy+moo8GLQf}W#?iuGF^OVV*fe)EK=NrIU<_zsW{ zHLs!EDUGH%Rw?dT7)7EKE9cdlk6?S9$c(U7ozU(x66XDw-mR&o=ZwCLjCKE``lJVRnon>~o7cQSsB8j?|cIQeG7G*sf% z&h2^pwxMky_HP$Q4}*|z$sDj2Csn67?P_&>5$W>j-u+HD3^P6;gIh!C+#<31jL#ah z=+}JHa354uIM;TnW^KJ#^C7Z%$IPZB?>G+bE2r!A)FfGb`KZ(K?}$*8P1VuJvghMq z4g{76+wDw4#nP9kj*zxkBB)l`m-sTbz(Y{ode6U*f|G9Z1pn;Q+5sSis%rFSpVsuF zBll?yZ%C{7Ll$`@0J3YD{7;Yg9Pki~lRZ6zeK~$jaGo$JT1_h1vR*r6e_51i z4bM}OTl+{0+p+9HYV*gWf)i-r3TTmYH>EnIAGWSJJUfJrFH*%(!=-5+(Bn83 z>zAah%h_gcor&rVZnT^!bWim6$o|t6bqYIUK!a4hXUCh*QLIf7}Z%80cQ25h~Q zp>1Y!TneOU%|exDAhuqwEvdn>k15if$w|m@&I$z)7GQ3zIUEoh$fInXn&NDde zMxRVMsSfX_6}=OYmRpA3%Da+|zL~#zM`2Go>HupB$TSTiKk>)zHpi6fE4i})%Y{dO zlo-2;90$42+@vvGq4(_`LcbL!#zs@9h>kv-^`yL4nfE0AC82m*l#i*OwA!OV-s4*4 zLnDe(j=>Gv{-#si2bB?oT?y6OhyA#8*=gHw{=jkji%AfcdVCg))a#k(UGl%xH>-RL zd6T9>tW$X;ntrC&kf`w7FCx>43XSJ?JgTnkO%wKy@@)5!nmolV*=NyB5$Pwcgbhpv zo=p(P$XSWtQQpR57Nf~kj%ec?ZQP`L?6%(f@JXMe^TEy&tG8mpTTTFo-AX;Bu#D{M zwvYE-=_DkXk|AJKau21MT4@*8d!0RCWO4|TJ*H38ffAHX0GTMWjvag+{12MZA|Ee;K zc}|?GK5*LZ&}W3{WWY$tq|T(^O?JnD{ShmE%sfY*^$2t9co2F;UYwF+_A z)Ad8GC=m`igt5{h{zRI2viJUaFA;mAU14}^OMcPC!*3Bl-eUWI=`En>)1Ks%lW>~e z6mBO7nW@F|S!TQ@=yeTPE?8lX2K>rVS5zyDO`D*I@p@4T=!Ylzi^}_#JD{JmeQj0d z!yI+*8RNn2h5p9P%xUGo{M{(W{7GL}4mUCH{h*wf)o3hHi_HCWiEt`LsuH0u6LD^% z5i{HA4GhC5?@ZW^)^k0%JXdh$Y6Dah(B#)bbV81zpPIVo7eVhP3nF&_#p&C-bBXFA zXlSQT=UsYu@eN=5RU!Ae6tJ1bBPMT|ow^5CB1YdE{6;?#9@pVu0eerlCofwrMS4z1 zZ61@N{jP7m)JvNsL6k^V@&f}}1oBow<~wK_nU9C?xF9AD?(CQvnHIj@3mus`MEBub z>XPF_Q9jf)@M>t0`OmLL6gY}-lYUYu-+DeD(p--UMa_2=s(^+?YP5gUx9v-ry^{NJ z9UU{_SL^~`HD}iGh4|6kYd=!i1D;Y~SV;N4oxGJHY^<9v>8l|$25luo*c4HakS`GA z?)ImGBnD@USqx4JxpnO*!A|y^fZWeLZ=`mif9;kMGSk-AJ+(Xxg7a~TjWK3;?V09C z-gDx9b&u+WKN7@wepCOa5_satQ#_aWRPvQ?wkaYv)E%HfOKMLk4`UJ9JE_x-P;d+; zL$x6mv>5mJ|DA^;+7!pbptXC*g#wKymCmrqNHJ#3IrH6Jjh@&3P{>0L8TI1tZK#q@ z#dzytS8@xiz8E2c>!^f8{`29zW4txdU@UjzvO_KU(ZCK6+m0^kyL-&cv4sD|0FUBq zyM(i4mh|CXBzPPx= zd1NizzIEurrq*)Psefl%t!O{*5$NpG!_y`j@VB@ zjCsmUJu62-C+2RzbI3mcIuV$94Kw!I}bFh&H6 zD(|)hzZ}Yqn~a~nec2+Nq01gaD*Ls2P4R@KL0}DfXOf#SwU@=iAiNB9w+(YNVmyX~ zQI10%;unXHh(U3rhCd|dGFnKBlE7XGZFNvzw97)eh zCXp;UuiO&qr}L!&ONu>CRJ7ve*^YB4un|foHIO}ebvO&c%Hb`|KBsHpy>L-frHme-V@!v)ykBhxNQk^LB0c z7C=Hz-fe@O*h*0Bnn$(K5MKqZ&#AY)9`15qj26|ODKO`2jKlDb8FfVarj$vvYRFKI z|EHFZ#QTqCU)r@ja$s1Mly_NBTr}eAIIE|0I8JG8Tm!_6JiOa*=A`$RC{B_NAs1Qe zxwLyr68eD`@7qVL$?W~6FNTc^u{Al*?)}ee&&z>J7FO2f8MXV17b?U2M^o@%ddIMQfAnjhHld_I<0lrnZLa9dq zafnUkeT;x@`uY>aR^T^27njmDd*y2p)wP2}7(IE4j-q+*u9?9cOM=Z_jCF0{QPkdsJL4~3UoY)T>6P1VT%0<`eT$9hY5GhxChXE zn!_=6~Rp#|(k@SdD z_xl_;ByX>*{R;&M?N0t6z-cxa{(?RZ0$E5nyjW_9Pb5*Nwz>x2%pNfr*H<=EX-5K_wTY-C$vaOVKHKY- zGrb`oPX+@buGhg0P?jI;yN^{k5KF`a6$b-Om)C1iZ4*21SAY~~0)ZGY74Mgac%IhL zEF@w*KVS9d2!)}NeV56ktT=uUTmp4Z4??dybi1a~lol{G=xnacu*lENs-PFo+GsLe z&+9VRmNsT5MJW%#dzHOp1(T-}M30q-k{zczI;$+m`sFcYeI_A6IHmtv$LD#{dUa?v zR$-=(fr-yEg5F&{G!l9zzFdixIWl{xxALauR@`*|UpSCV@Z5Dlv(ml;6(;rTz`B{Yb;nP23af zN!@*6KQh9m*T#)M>w!630R~Mn+ix$yE+$|jq{~Sz@GUj8fLgt$8@n{xhkVBHCgHEH zMi2-9QSz~bFGEc&U!hq(p@aM8KL|JJ9$J63w8+e;U8>}{*m%K6G@i?u$w5jjH;$nD zQ_pTNG{k^<-9GUZ3t*;( z<(Y`+k>)_H+O9ZIyT13cP)jNm)AORy;X=Fwghq{KQ@%L#Q~GP9XTD@-t_6_wJa>1a zmCbu~pFg}KXFa3JCruwoS32xHmhj@q}-^%WWKU+mYF6IA8HqvB%u~JWnTG6yJ zle^=JYs>4KmaIX#(SUfYRE>K>4Q^2sdFc}6HKchq9o8=MLYE_FEe?=4KQXd&DG)#q z4_-uDHHV>Gd>tU?sI!M z*?b%!bN4@%Ra;u0oZL0OzUCrFi8?*!t4*B=m7zc78VE@}$X;#`V;$g^59YaODOyik zP8ERpv(a@knK*JS_j5RPa6gHp3Pkhz3rX+KHcwAGEiXFrVcW!b#&-7_^TRt%fm4ZqOofVU?-&FG^yi)0fOYl7H& z2VTDkmtb*hSr^ID$ha0E=pwvok`G8D3`dASn)frR@@62qdQigdC38wh7fzr=tkmL* zb>~S(zNH;^3WiYZ9Bl<<7xa?9d}mgBLW59xNgCK~`Vq`Pq4+4*Lyj{@FOg$p3WnaN z(e!9gKyOkRD{&-0g_e>N-RJKAYo~uMu>oVXeLa` zF(h~X5=8J?mm_!$XyayB4-Z489O04YWDeM{2HGwD3jqkI6EyTE!l-k%TL6mTyJY5i zaEcq{5DooXXO7)iejsqvwQJRomV?yhtsL<_TZt`a*way#CAPmGmts1c>+<Ae zH|7dy#fb?8M@<2e@sB_hT$3$$CK)C0ot#RRKeN+Jpn^z0kVr@Xxz>jkiS+|CrdHBM zC8IaYHr{4Viev`2E_ZJdf(y_2zl<=XB=_`my|nLMj2w~_X@><}<3J#omPJ4v=vEDB zPh#DE9z@>LSeWvpj*9AJhU@P5s?Q`#kt~BxK`rtTO`T0IvCAZIIJ-lgwc(^^cW{9r zv}J20NN7=Kplo}2kmVwn+PkpUC@x~g9;`Lr{28vqm^t4v_ zJ4@by5QDr#nkXg`#B{`|lV)^DOFNG;c?a$7t*0h*HSspPE&Aqsojk+yY(z1--XqmJ zpQGlRERW>-T0;V6K?K#F7zLe3grezP7kFIfk+ZX8j}w7^Aos%&+mc=Lt59pIGj*U= zw3hKE-LF5k4Up!Zm^}yUpCLz&Ogsz){@ejihAw;FE=;1TyJDR*?Y?IBS;4D;$CwxA z6Q#OfXHftIup$J#5R>$-6X!~!(1=VDn$=}V6)T*bihFfOsyRz6mUF-}NyzqTKeUmA zMnrE^;1yjRlJIi53juUJM+Fu+Lg0k#ak@x{`GL}aO zcU8j~5;6rS6f7&hv!dhEO6~w1{r4-mcX`ko>*~)e5v0;fogO*m4b-%F*=Kk_e~e=& z`|E@}Gw8Ewdy_8uR1D2gACD?{({yfa$uHDeY4-(wg!EW#9Ift)U>Jv$=MV4Lq;eHV{lsJv>`>x6u?*$(zf^Z-oYIl+d+og5cT{Li8hxq zw?{>4y?2PZxt@A488y@LzEPL;Nmt1%^s)8D{^bm7^8sVWualD()!#2cAyr?}ib#iG zb_51=2`YctYU(stLuJKkMa zc+lYMv%*X~h~!RmZtwl%>(ChNFs+;3#F&-Waml0k(rNmHBwb9YiUxSp7E96ow9X4P zt8rXuR}?XGNPQevy}og;E`~sRE=?a+l8y1??xa;d*~QA1FsD1vyN(_|XT}$>SlUx9 zGtz0|jU5&kVCR@r1BhMtZIsvGgF*V-XaRcHw%3^*GsZS&i4>L3pUmwWwgShVgOl7d zmX;b->M2(;_H=UAw@m%yeG_Gqg<~Rae7Pa~5uB4v=Je+V6$20t?cC3=TjcDxEB2`3J+?mr4q%bM084Vr_RLGHA~q`g=ql~~-x!p$_4xKZZMmBV+>RAZ(_wafvQyGU4) zu*Juaa+v7L2oXhw)dp-)*AQ#T3&_dcgguq_Q8cp+c#jGA1X%WH#*S@3Q(y7CH7 zSt-2XLENdr0W+9{^Pw(ztkyg;3FERVF}mNV2c|6QU|W3FoM%-+=oL6>uc4N#CF-;M%~?n7L)7!Epk-L-Sb#nnLx~h~ zOm|*NeQ3$pmaN+;;h@sFpllDkst&dPiTvsCX)Y)cMtH6Ex@{&{QPc+{G2_BT=A;nt zx?kKL7GVciJm_+N=_U0gMFuRKtcb{1QSNKwpGF7U(jozphus@=iL{oVioi5YR@!s1 zr`mJbH7v^H`?lFd0QMd)y*KW}sF`yDzr)?PrxNd7LBRO>QKj;E^pd}hmB2VI(h=8< zcu3U0Iv7Qx`e&W=jfwPUUG$ADK2>RBoBNQ)cFTHp$`)$&Q${UNU*yrA3Fy2cdGLAi zax+zk<&suj##+Er0kA2NzVo+C` zQb6ukO@?LFB_SsJjU7|pUf~;=%9j4Y%i@TInz~{yPABzfh=*Je<)fO^4JnC$va#Db zOZYprc{u~_#*7cPjSGWfRz#*nOx4}Th84U* zg!$`lb`cPiL1q|cw;IpsiyU~Kd^2eyFZHEMB zdf5VM_h%;$np0Y$V`e`Ca=L>%HD>0&iTnsHq8(R-rERb8WAl6}8xVC^Fw8h)VCT(j zUNn{!cU(}%QL&P3K9T$ZOm^q6)&1mlfN%`k1|I_H==-|$0A?i}=ZclHs z2fAu6aC`MkjguQ?hR|a#jf63sJLYyxn$@*HDz?o3R1V@1zO6xxF<4m($?VR$^ufK| zloVCgT70rkAbHu~T_`qvy@ z>P@UMG`o3SWI@e-38NMT1s{s$KXuX=ZQkH6%$(rjE6-%c%3K*L=FZ z`nxVbmPh+@`EL3n(cBQC^HwkCnLG8V!*l&SW_2EOM#96Mrx30V^&l#o6O!f;Q&`?( z5LGlrbXN$gC7Cs!SwbBw$$E3KN*T6#QPm;6FQeTje!fL4#92%o$}OJ4{rL91FT^CU zciR@ikAUY1Q2J9@Lg0fz7scF8S|_dX%d8w>F;fi|<(P8YEV*WGy{0l*_pePGyfpg8 zd@5@!+wiUtC*y`=gQ{SKlT6T6y}3MmOAmfm!#r@GXhWP?vzXo!*+!8iok6$F%3`(6 zW@;#kOq@tlE+BMGZx+#Erf|J$^!e3i+}Ky?u)c5UFz&=tEjB8gy)LrR=#qIzzZ*pDctlY zD)b`*0KiUx;a5`F2LC+Xeexo+w?e$3DyLWG29=Ix!WWGJXB;6{_2sEy&-tG$l?b~mS>)upXz zbT=pqo($yBW-99(+uy&`gjzu!OI6pYtnD5CK-qKZp=GBg)ln)|N+QZF{!`F6u0LAC zTT%vs1S_PDD)0Y92;(h92w+ROqZLu%YRf3X+>R1~*YHMG0eiRsd6IlHJS8 z!*|$#f43RMU>xD(;ASi%p_L2%y2Z=QQI zAGyFe4Ac?lzYPk;U?|xFlZO}yQv{p$VN)>+2C;8Rlm2k+2lY=@_WQ8n=t~U?JUx1{ zq+wLw8Mw~G4A?=sobmgK2XsgnSF%xz)Uwp4gs4+9Cw(ewh#p7p%FwGaR??#0KdEzP z#)(m?)yv40~1tq;_yP23%Zf);el%T?OVpOA{ZL+X*UqtkWE78XoM1GE0 z+r~6=MPKL{u5?x0kS|d}k7=@LwgWtsXg*lLM3w8Hy|ich&YqisSGDVjO7Ia zlTUoLXWXIb79wLXY!0)R(MqmS1SpF|%)Gj)&636&Og$sU?E%$_%*hGpEOOuI$ z5A%uL;ClOZ)uYS{R5xH;hx-_hZDlnqj^U|HzE0+T+;{drhD4MWpKfCFmgfkEZPH+U zU`dw?dT%U_PG3{9kYD)o-Jvjhz~q-9(OZz@UO^`F^vVx-i)Qdl5BIpvvFRMg_59RR zocGSUR5Eo-hcsbiHeIo;>DMFvbxYyt-S~S zvx7x4pL;+C+8>Rz<sSpvqJM zto+RAZhGY>O$K3_GM_~cZUj^uSwUv0bb~K0>TpHg&Wu3@*qyiQ??NEP)*+tn`Iu~k z?G;(M{#}*>6v^{K4W0les}X;>Rn1an1eI246S_|(rdroJF1nl3nygYqX7T_racnMQ zeJM-(l1kCOm@J~B&g||6Xd=TT{FL+;`^dZ&Q%|_m=uIT%W<^b()pLBgiGuezp2^&Y zPaK0)yoo*k5B_b3R4fT_q7mTiM1a#f*84c$7GqYnhu9h`=mVMJ&m z-4P6;cvN2QxvGY)a=~R>yLZEhQ4ji{>VD1n`N6bO-Sh012rZ(ZfNH8X>o}&o#i0g% z&3U)Ahbt2USS}NVmGeSx8rOWfrgqk&eZ{-M*S*l#i*bH#qZXU{^;K-3odvxrC_c&XUqm2MO== zbmK*k8Eo{S(b>cW?O+Mckced$U@GhR=yB0`>0S5NvvOIVH>h7h))nf}n(mR1k#@P| zN^AgLw_i>wOdUf4Pg_S)cKnV(j_!pkAA`dlMq=UfG{ubOQaOaJ1^pbWgS(v4cxApD zsdW{GesiEgJpsU!utmZp0AV?xZ~TXlHJTyqu0Nxx?G?Gnn{&E1!v>poq`mJQN47TS z+BadGH(I`k;&H18G7A-zy28KM#;3hL^qnYepDyzENTZkgf z#018To*3w3+6rEg|7XV0YKmN&JZP5{xM=zkZ>s^N7(+~eWV5FoKaK7p(M;xSuXnOp zO{3i&xc63P*zYlhvM8fCZ?L$Yw!uSD%e*wIs`wNCT%NG(urLus>xWJFLhOV?+0W#? zpN+kf-gk&0%|zf;L2#$584tD9wy;nvjBWGi%bLd?K*iCqxaS42L84VlAH*y%FQBzS zyUruS`Sc*k=NE0Rez|hvG?;a17qbVWI$#Nw*seYA-laW`@M!BdcKfX9E->?K?0t~u zNngU=_niO6;HPAWw#QbPd#Vz6xEVih3)JmW19iRfLkJ@BJ3&NL{v#sN)htwDbr7&f zZ@3xXVffh(x&I5sTD1R!dH;#}jpyjXHfno6=|#bzcP>n5nI~m9K=O|IQ4|7eG&nV{ z{KDw0%Ua^zy!jwhpqr}@cW17(T*UKa;#NMnsnPP2ZfHx3a+6Weg__9!#=a0;WPH9B zTK|%zSD*WI-(U1WgCI5DBw~<5g04Pi#8-?apiiMGD_g1huIr3ddAr_ZIQA_6!uV9y zdOE=V{Tyk}|Bt;d4}`j1|1K$7QCYG?DakI$7Nd<8(k5h$rwExOA!BP*)>0^IC1lM~ z_Mx(rwFoVkLe`k(Yc>G6jbJoZUsMLCjN08R@; z9Lsgd=C?TDQr&uxLdgm}SG}hbK@NR`^#oEFVGsC8VdHyPq+fzRfRZ3E?Ji;;G8AM8 zVHFE^-&@}C3|_>hq`oU#(0}pV{=*Fehs%i&t-l$`2G{X={vF`^HbRzH6S@rDw*OWY zW8fv?y>iB#?4O+&+G_2Zm0;W5W&VEXbwoY;s+M$3xVNX-WC-|0;8V%=*J-*J_)cD1 z(m6mZ9@P1a$V0h|{MDln#ui3R6UYxSz;NZ5YVc91&DX;KD^l;Sm)Wxzj%m+ZN1{Q0 zV;jnAMd3I}`ZigQ?3hZf84`deTHEm(?8`J_B&6hiQaw@)UP0EB=SBe+1H^~>ukoJU zeE}#PYV@&r>|L+7ky!)O7@5;)5p@BQ+roc#sGDeqS{!UYEKNI9Z{L)E<50D5%_~lU z;n6~=rfew3)z1&#a|}-A_4Q)n1eF+ra(jseS)1|zRzC$cQ;VPUO1&C}hxw!CltE)^ zncE&MaJ^bJ9ADjCl7>gzTHscZ4_#>Sk*fyB;ovxN8x!Ac7#tjN9)LTohy2w>1Fp=% zj2-HsiK!6`%c@6YdXH*GO2XA$$>5z@&(7fepiS9@4REJ@QHf|&ABcTN4g{I@N^qcx zpN>1P7RujhO$d178VpCRwY{+X{%Mfm(_X=(<(_~=l_aLGQ;l?)6zgxt{sd_np?blM z;SE`?6!JM(@iSNDfb==wg|6^%qgG8g9Rp^JkKlS9!q<#Lmx)i_ z?YcA#kNjYlJ}+Z2n|1!gt+~*)&aTyC2z@r$Kx42hu>7^|c;?{E_?NWfY(K?1H*n z(!hm0A2n2;P182ta#c~}e9@z}9*+B9qLzU`Q#Ia{ozpXe_q=f!h-N2p zg=r`Yc*xu5EmcyBtvStYf7~0V=>h}ZqM!|pLu+f57A2{pm84Tk#|7(W8IhL=6r-`+(oiO^S+8Z25KtWtN0BSE)l zezQ1CP@B1Lag|+wEbK-}ppUsucG=B0M7PhouI{;U>7uzP`I-*ICVP_~4|vDrDrozX ze2dTct32aRhfHi9!zT^~jUkzo1Z{5EBRGf8dE#(`AGYT)GHYb3>Rp**IGO}oLMnbs z5^$-_SIVGV{gTCMf-vuGWDzXR2zJO##fNQTW0AV-yRw zpB=PouXIu3fAX4hw{|Y%oAl0Ed3V~!KP#19joXu;pRvC@X5pUNzE>}K%>E!-e6Sy# zFgH+aK_tpp4S6zRFhNtBWPIQ z&^p`Q1%qmn)atTfKmapbAl0joEJo^nzgQxSIv81muFm{V1~l%bN4S=bap0EWTim+c z{mNp_Xi&9*ll3hmH2-0;zU2)I9A#Itn43{pVmO@offz6bVIPav9!Q1{c};49sx$?Y z*aWvCZv(m&$M!)6i{tIax`(Wh>d&7|@xesaGXVIrhks(UWbq|{l~j;b%NrK9>x0nx z-8)2=a}TiPH=%hq7akFZNY?T=1=^XSkjq7e%dd3sw;0V~FiY8)Wf3~&@lb5c{B9$_ z-!acpppqLtBxgW(FqFhYwgh*Z57hRJV{%O`(0Sd=b?nM^cbfgDk?45TE#}32f8Gf^ zc;a<^FoXr842|T8#x+r5fVW5Oe6bbqRVn0O_KoL;6s%heUU_RrFwb0umPNvh??pNU zTySz5|A`G50$d3YcyI>aZQ<~^fIbXu;fAUlFf)L|r?&jr2L!-c(h%BniWF_Kz6K(- zP?vn_5OM<#tv$XPbQYHutku!ANz>%k{FMwEXU~X3it#$A9Ef@&CC zYI{o_FPg0wy1)ZJfmVvbE!#hZTX_Z0lyFCd(y7JSjVS$VApWQ&%W9S~z*6?ED@S8q zS|FI=s;bIasF4agxyRQx3zA+*=zuSRPwf!!TZ9M6o4suiCb{xx6})6DI`I9c&DhYf z<{Dw4^b<)UN}ww3{}ZyqiN@;GKtADELJLH$`$Tn;tSR?|PRs=ZyMB2aaQt}mfotI1 z-rmS4qz5~>PQ3)min(;)S#z_K^x2kX;E znHz)Fvow`-GxCWyLRv2aq_DBMSnvQ!xVY4*!B4nOg6`+T{s6iwt~mqvEiJ3940Yk1 zP@2|Rcu(j!8wlN+MQx}oxeqqa8ym~S5FmoCvY;6tCb!qX$M^?;nD9ONEng4vJ4t^ZZK zM;is*13loKFga)siedkEEzb@!V%G^>bsA8BxKFO}+~I$`JP%x6Ad8L!^e!kvv3r1` zCT(EJZpcx82E)E*V$^RU_#||-AL2K33V@T}{qI~GtZWeYUYI}SAvjUZea-!AtBIK0(Zso!xh>rf#{zeJ+I0Drki0Z>#>%(a8cGT zZtZ?rqlHnXi8fR@2xmDoq6SMn57e26X47{<2-ZW9_1^A2YIKB|HKRHe)x}V}ve>5@ zjwz5eNfsIg*d((Hbz9nlTBv_~T8wu2>#;UFLAXJt36|n+s|gPM?Y8krPtW<|t=Pg$ zl^4yuu+n0BtyXLgwW~({9Z;cbbKG}D z?FyNQhB(j{LmfTWotO~~WhakEuD#)A@m$C%tS4Zc>@xb2e?Q5MAE?M~IoI>i9F$;L ztE1%cc1#4dmq<;@bnV+oj?jdu7YERoYNB}br#p-0Mz826jER9hY46Zin)0ILkUm)} zF|ALgy{LT9CzLidh?!TzKXFh}g81&AyeH`3M<@$=3IexID8lHWy{9Ond|R;DA^gB# zm_w5u{S{Ru0ui)$0j8YsMPavcgJ#BoBqH94DAbc+XjdWol_e52=WSl+?^c3o_7tp! zCYvwZLXVnDfI>?V)4;nTo-IjSXsM@B4{I?5PW7SltJ7aYHw!5#M|LM>aXwbA6*DA=r$7k1yetIncMA@Rtb{N|hvFD8l zFOJj#^f}RKqSa+HOiMUdCZ2J-X!4c`p~;TXXx@vwK?uv+DxkPX$>Iv0MdZSn$%X&cnL<9hYzjD2#oEcp znL_Bg#Hkimi=*&C&kg9K58xs2b=Le^)iS0*-D*?&G!QBS#2*|^P+z0!ck%RN_!cTO zAkIha@aJAE+^}+)j*-)e3vh!jU=J-&jeyhBQP~|a@%nn&Q>*%DXa{|=M9l>q9Gk~@ z`d!?UEd;K0{0~Mplht0B9AJ35u+=IUxByhXZa6jmnF$kn+F%~iA=VzyhaHWk>NcLM z(JWf(VeoSNi0&FyT+DCXY`QxEX>iN)fnc&@cfcDhJ7LBe%nSGG_4O+-LjfH4andja zBG|FLe||Tp-8l#8V|X{ngM9?>o~T(m2PwzTj|WjU+C0qu=mjW_tA=Q^rFh8+Yaw{U z10e-a1Y6S?6A?ZPvyaY=^<;2rMGtQ#e;i%9Gg8_E#}|MVx|4hz0@SK=fcl_1!;};f z959d&Ft;jowr^-d#LJze_6Uci1Iu<^ne)%=KX?Ei^xz6c?uC~Wu^-YjISW^FgWQ&r zfc6+b-ABn$2+Lg7{UIzHVNmC_-Dztfm5-$LvTlw(Rr@*7+=|iFvpD(b6pUu{+x+l0}!M$a}w8L8Y zg0{T_;+02`^%6^jeyQa#R{KGagcejZ~`mZ5e&#tS6$avSe8$%Ec zAABN?Yz?dccvdB{AtJ>X$>TR{a(upt1GoP-z}5YgM;WPO=Qmuu7vagJ=^C{^*ZV&)l z8TiQ=$`{+TXho-eP_R&v2r_=u&`QA!7<;kpmsqsfm$u~ueKjudmZsD_{wQKRiiVGg z8{>0@*CmUz0Xi;Winnc1Gt*dc{%DPx!~${MUl6iP)!eVbV_p6`mhAykx?lPgC~Wzj z!*c4Y1o0Omo_%}4MY=}@-t65FS7{(XJ2}Z=;3I*g<$H?CC&a(EtbXE?a}TPt$#(^; zS47Dg>pi;RCVM>k;dQ<7<7pxjnrr!QRV0tgbcIb=W96735yZV9GGFLeju zDsCAgP|?<3g>c3U%Fg8H@w5%|rE(~+)TNx0y{PH51XuqM~qOWLG zxmoc8has`n)E7ZN&R+zEdl_u&ICH7Yh zSA@u6v+(!2xP_X!bM(nn&ocC4o*Ca>;7jWzE=BYJ<%Wo>jdowxixG7R##eH_l}w%S z)W)oyJzoG>v;L3@6BX~ssU#~_-Nh^}_MF&h!k&h9J#WCF{n>;D@A&Eyd@1kCcnU+m z#b>S%J*wSSJ8tdQldLjf4R^ooxPE_or?T8b@N_9#?d1 zQdaKv&14^<{?Pz)05|=v6NM*n%}K1Yly*swOIi7~qrEb0?7T$b;|FJ?%$A0CnR$20 z>D3-pC`JP!j-~#!2i&``V67Fm;#$58NK?$4!^8^(5i|D>=o@W5%2reZDVFY%epI)5 z3g|H>H^0@Y3wP<__`4jq^GWsf?`{&-^u)i%_vdVDxXvE`sw&(;Wa%P?=zxI%OU3(% z6JfM#0fX5@IIUU6($;0)Qmp?%?5R=TwKZCfJKaRq=_rZ2xEEdX;TSC-OMw`FM$2k(^T7CZh8@vl|Xw0USLq9WBGZq7&$~toRUkSWs zZ0-_4NN3d}rDUJ@=+dB}SI5fkgUoLpn&?lBuYyrus0sj8K8f+JzR+=h5WMcerl=*5 zygMP>g`mC}Kj#hQ9|FBG{|b&VV+*;!+uoW4*Y+Rb$?mFqJNwHdwa{o}+6_&&U<+6d z2;Ob?SfCD?@lyg)(Xc!6k-zmO5U@k)gE}I@5x<|lq-vrIK2>J$KX&zD(EKB)^b)JM zCo8H9O-1&ObNf+)w~q#3g15eyo; z_xE21s2>jXRcH$ygucya;IX*z_b*}LhERV5)}%ut-?<`o9jU+lM&5%4bVW#iEcQaA z1sjc7F8H95(5)EaFEr^V;G%kp{#TR&R8ZHTMm$~IKnOttO+(7`-Uy4(P{sbj-H)_| zr{I5O5#S`$Y>Wv#q-y|ux~M4JpcwoDDWS-WDL8yeLwO)SrttUJYd#p{GQWKATB0ui zC(BG<>m`8aB}Fqse=OWR;E2<|lW_V+c~5wTW&F5$8FcGM0oiE`3{=qJ7y$FlDNV?< zeJCBhP$|9>!};5Cm9y_$h7hG9VCAQZRB8Nan)rwHv1WxjHxF?Zzp8)7X>ev6Dr7}2 zxFIpSiLXsi>cl4roJv1Kq9A_#Z(xN-F0}aLl<`oR2q(i<85nJ|}WR)Gsl-$p-@^CTHIurCmNuCIY%rAk#1n28<)$)+*{0N9r%f8_LJYzT1- z6pTj!tF|`BzAoEYUA!+D8vm9N zERBnfFaaO|LBuhrSbJ3e&Ph$XDO9ASfh#35?S{fqs)?y_QSP_+-~bnP2cXi9V-Uk6 zH#@^%V8BeKcJ0Fzmpf3w>GN=48#&I+!DejfOS?4%hynA`pmx(}Zr4`xrY}G37xgOd zi0Rah&%}5Fa^c0}m3B+Itse6}_XWGD|6q!4{=i7=xSI}TMAWRXxmkwGu3y0qCL*s_ z#|*9hZYM{N9nskVqPiN3%%aVQ$GHR0H%0*L$*y!yvxt$5d8JskZ1G^Ww*FTxW9Vl; z1&y(%pex)|MRRwYulnjHu78L*#g28EySABE>zRjXFFE&esazDGrnc8E`6{a6*c$=T zsejiV;pW;$3#}_Q`ImN@})>7_-=4Xa5^WJJc{fn|yv zk+ghaHO{4glwx>8gjM=;pxRBna3n_5Ut za&$Lta({$(fNyH>`@*7s(+`G`K@mXEptX_%wIjm?Um7HhGW`oXdVY38BN>q!3RwSd zsu2E7Hx%f}uw-aW(9<1e1M7QxPeN`{W%aSDI`B2Xp~bk< zgDm0y2=^KfC_t1^%@fDKL|+*FaxKeyqkr;a7@!hy9#CvKA+DP0$xF3uSd)QX3ovb% z3xpZa`6F@^x3LU2ecp@Tcak5oL;ZGYS#FFZm|&Od>GpIq?islDK{-6&`VYN>s?(V! zgbQ-_IC(%MzT{@V`?!rPvCHn>)1R`O0^hY5P-`iz>l3wvKG@}zd0PO@grH^EDUf#; zzAtAu1M8uk;7evi>cn^U)tb&geVdKcwlA_z-M7zCx?JE3K}gTCsb$bu2g>|_bzpW# zau9%&*mqi=UPrLB*FLI)T7r%DY7%zMtR z_D77jZm2<>;gDqA*YPWa%}CwzIW2->{SmOO8tA62fk9IRj~G30 zhG7vn2S`>#qfA>TxEf;jb!Kg1%|c$top-v=Tece&h}n9&7JIL%$$K<1VYo(>m@&tF zBS8MAS^kB+WP`o*tj_ra1OV8&I}Xr3b!Yd2I%uDAkAg7caL!)F30xaMhh>xJEqo}6ilC2Ii>*eZ% zAhe@Pa(2;oloQIfPR@f8&dG9_8Itov5SICN`06;x!p6`Mx;_m(P0v6t!^H#l=u`xX z>wZ*4LR{Vnxs;warS}Z?;-9%f9Z5CJ*}K^^K^=+Vr*x?AV#`Oh;WL5A19(+@02Szz zLl6NvLK>l2F>U3FXptd-)Oqdm1&3M!5i0(^a{#B9b-q0U3xpvxLyWitFk z0Po?GpnTytJHrx>M;qxoD##E)DmSnG_93kXI;w7>u269IW0asaeceL9d>lR)i*q&*<|dmi^ENp^3$lPG-a9t1gqwH`sc;X${%Y-c{a62Ni26rEYDFvFAzQ?iM5fg$0)P`jo{|u&Bx7U zDeb0jVCeOaDEO2yEt2(3OI8_rto3Lle}b~>ISDKP{^hokRf5^KBz*gT7xk~QNLw~#U28_cs$e+8Y7ghZH5N!wOP-;o> z1}?pJplq^~b<4le8+ZHXfApI-{-`sghtTjCtBr0dVQ+FKoMZYc2imLL#=zr^|5jk< zdTghJwRG`dNP=bjwlxJvC%~u@5ih406#*LtX-ctn=E_anoBK(gc0Wa`8(fSHVdC>C zAfDTpG=Ugw_#~{W>)CvEAMWOAFvL{JOb}Y|D_aWZ|Jq75>r`l6R{HwO!nfx4%)Q`- z<=-y@d!+v?L4LRKSD&i*O1m~~9>LYlN2MWi92^jl^HSk!ohBvh!sy-olx5wXUO&h2 z@wZ{8#@2s4>kRp7+}H)G8b_nH&3^VEKuGQ}Z6rIf6ZC$A2UX+a>H(tYRo31ImXcTL zjzhSTL+>ZBF%n;&lniq*X&v7@xlQ9Gue~I)g~jz!*CqaIjY;Ols4wFb&};95Izx?Y z0NfnpJLJuF>Qo0wmx7+=jPGc=8^;%)x%M9ePjqa+GQJjIN%ac}rjY$dd3@nS!<=WY zmIn4Yc=h;*K_y4)(FCCq1h*`94!T41dpzPE(bHGOJmaU=lLn5bo1TstTM}r?C*8=E za+jV#V_gJ3AEjOzpjN_+XFqsolyFw2|eLzwO_7?1%jg7^JnMLe~lZA3wA5xFZK!4wuJ`#Luqm`(|Lb@ ze<@;rfmNYT%m^Mlw1(Gd?y_n>je5MC2&08@dHEDC8}zUgR8bnL9-#r0sQs)H(H>Y_){Q=fdTM)G7tkNI8Cpo29GRz>XJ(kwH^J}^%?5o~z6rRrtck@! zRMti7j-Z(_6R1OzbOu@_|4V}b%UK70NwPs5t1xs@safxMx*y)aevQoWDN9=L9*m^f zimsoG3i`=6$3T16UA6gkU1>LF%W-E#XvqrKy*q6V#XKOtE60bLr654if;R1uvaX|; z8Af$#@!|mQytycF*VGK2Fq&1+z1NJ?knaA3HSYF^e;MNOF+~Q2tK=i40Uv5``?wCIs_AIc(Ig)_ETo<#}->8 z!VX*QkQ*-Ki{cM?qRc1EXrYx*etSw_4g?l}M29T{8i_$asM7C5t=WImE5mjB4h$7h zh$>W5t7LTcF3Upj9?SOWKq3^$V+~(v(05tt8I-!dzpOY*AktB#@6-D{&dngon(xDx zfjn+FdXkQn2=DuB?lx>*gK9pF04G3*>+RY^R4@O_#vKy?$(p}yQ&BOPf1ZbO^nH$$ zhJ7yXSUO9TEubDXw~ux6mbpxwJP(uIOyKsSQt`?2d6QlM5bqs;dR>KpbY@>C3@oy# zsgYKhI=&x*s_FxGz_M`5k#2afKIf(tbV>3S2YSsd_m|CDYa(Qgv8OwV!!s`pnyq*i zGw;frp6hpjIBW8iN|%p91!y?2Kqac28ez0xS+(5ii)2L1qhcjU_sxWMeTI2U8fZxB1=81`8X(rh{B4>F zv9}H)0&PT#g;K*j8A`-oQef~x7B>M1SX5fcxK$IoaHIz(#7V>Ygb3d?7 zotj4Il!QnDffMP~xhA?snEskY9$et=9rFDQ!1R4L$pw3a`3*k!?o=z6s)>OIcs@Xj z6Nn0&{XT__Oa%rr9{pc9VF*aIP-XSUC&zbWLxcE+6UW+qDGGvDKX3`QncIKq+ex)s zSxDbkK@c@Rjdq_Ii==H7bgF{UQn@TBSpaj+J3o%7fiQdBT}6MVVs?4pM6bT4GI&27 z_*e&lQ_-rSH#cHx6MtOd$X#%aj;$0socJFzzbIU*fo7&o0ZJ5OA!?cZ@i-&}{{?0B z?y#1oI-mWK3zVVy8rgb-!$&h_-(OY>4%eOJzh)lug=--E(PQHZD@`_+- z!Bu7#n&J|nIUhLL5S1AMf<(PY5RQ8VV;eHxa@AZ8s~wE++P3&NUadkUUXf05I|u>b zIu}U(H++d~@n$o;F8$!p#-Cyyx(EJqRqv1Np>7$tu274b4tynh?Hsh*6$UJQ*t`_t zGXtPVP$XlJkNx+VRXj>5LvR;57_6^;M4)MZIXyM}kFwB{ODU811|gASu3g!Fs8Fto zm>32vcJzZs`~NTzZR>FxH4vSHNmLy5t^n|SrDdVD|FsZ~Mw9^&!--m2U@|j+J9*Ho zaD+WR7!suAr{2VMMdniZP8_{~n1e9(dVsdkGp+velmv8uUYj!%B3;`mKWGRdx> zT@Eo%+h&W}|73buevHn((U8v6iLip@W;-7lY$$%Do6?`*{dm|tBBxJlW^6^LI-#d@ z<6ozgUYUc?bKqSPKYQuyi^C*5EA7jk^iO3qH*fMt3g&*e;YPV<&EDy zC4`v+OdE4AZs3c?)1+-PLbO_`2WzJ9=RJDFhc-z6RVJ@>do+_O4TI&ha9zvZ8elA_J z{dhQ?eqw_$gn|8Le_f?7Iu(?18AmM|Ave99=tHD3JhSJz_6Hezf4ueEg}qv93K*G6 z-qHUNJMbOEG9R7wejXg);#h3+*GT!rSDp-Te<*AE4>3-K#6Fr}^ou*X`JoYx)-*b4 zXf`9dj80~*Sw{X1Via%t=ChTAHiutOh8}L-23OhWSuAz>0rU?&Py~x~8a`9%ZW}pu*M>~Yl{qVTc@M*2Qra;cSqE~wR=1JUwn5G$#{=Z53TTPM-cu6C}Kp$TXRFT@R*Flof57CzY<=yE7oMliu z2U+_c*{OfAeO7)<$onKh}praEd1(Y(r9hpIR z$LH7tP_WmI+MjwvX1aR0r(D0x&FQD@-gu1J#JK2x zL*PMm8}4PQt4!5cNvSzMk3Cj*(OQ8k98ngF=g*z{RZCs?khtUAUBs+*`MZw2$8X&Y z)es8c>6Ja%+!yR`SCMye)Be_VP0l5+y)Ula`*xA`T=<`J+?#yQLwh^#-Cl%|o9TtbsoPrFlnYO?Ov`TaM6hA>xE1xi!zaK2K9 zq**@$X*ZB78VT^9GX9zXbM*G_IOr3nq!qHI=c!@N`CSLsB{fSQe{s3;Ns@Fbzk-zAxp;_ygsW4;<`s-2d{_=e( zreCqEUiQqzI1D&I$m8UJi-Ov0Nq;|xb!M(G&QJR-^AjMb(gh?wW=pKlR-DbZM)J2t zQz7m49h9vRM5ET1vaK(P!ub!ga~2Qt8x9d!Fv;0vw{fj`x5&-flkSjqs5ZZ( zPe~*KV)xvM@6?AmIR#^Wn{sncz7kEHy$yOpFl@7`{lO_>Sczts;?sLc1HBr%MpR8= z**?Qy7(d{v8UB1jVj5&S6FEQCXAaYa@TA`$Gk8^a1(+(R3%o7fJaS3ni@9#9@-L2! z7_sfw2%A#eQhQ-G*})f1bb~PMTSm@>QDjSZHwy=S7N7`!A@`l)o=cXtYNLbRTp=)0 zFooo_WtLYNF(1aV+YOiJS;9}pT>;|c$!Eo)N$`}jroc!$ZJuZ!Jd75?qV{IH*28=j zSB1ycYTR>09?DL`?ayEWon;93idn|(2+Tu{JZs9?VFpi9*&qIx4%w(}jC57mE3Y-{ z8=F;O?AqKtykD0CkhLXCfRs@`7bpEkY*BvMFICIQE^#yz2t^F6}tshPoz&fJMWIdsOi&(%}i(Q zMk(yyk^SEoT*P1uV99G4`zbG=Kp2MNsV{6lHR~G-m}4X41g<|cxOi#s;pOg54`=mR(;p%ZZQ8gJRb~>*&%!5VV?C zNKP$J;*W@Ci{wu`Svhqy9w{(io+~86oG!`JSB0zx@`5q1YKVuCvdPEZ)8j@DGF%>z zuaoqVHq#DP#~oNya#XhiA5&*{P(bO)D7MH=$EIOYOEf6&*<)$xDe?NT8((4nL^hoF zP(j0MTUzfb(&gwjNX5g;1Dj`kV;<}ukALAo2^ckU@WoI|4QK$fx^gr$1ihHl7T7?u zfdT7TU&Ji7VC-oBcGtNUep-7m4?Vs=fPup&e=YQ$et-IhJeadeymO9{1Rx0I?4b|d za9Px>ri1a*aCzQskrkqc^V7Q#YXJNAwNT)>RF6To$3qg{j_SB-}vdtAetql z>7I|Frna~#RB2g z1nO``$(G>RYJ++34#*CEZ_w*uBqAlBCFt-`tOtnq(px5rrcanIJM-2>y1Kf5wmPH7 z)M@2^*+_GnplWiIAw30ifZqdJ=}MSXzI(iXYNgWvDU+eQ!9YIs>-qmT%(MJJxl9YN z*Sh7xs4iPz7V|zWHQQRVc8G!qx!jQm=s}v<@42Bb-44wI#lpSr`N~-rgK4)aWqi)_ z`p>B?P%=*X`0Vs2MJB5_M_yntm$qrhJmYf{*qlYU=K|L}KTrU90~5-#)KLEO?~jLt zVhQ+0S+(6t@i&QH_nD9W`p+L%VwZNzmDo1#_~GozUf+B+P{LN z$Uk&Re|U>ouO6@=hU*mQuiR_ppk1%vRhz9Q(Vo!1zpLFTer+`|HWvu4XZ?~rL8q&o zWN=cjJKV1O)uPsx*3e1c`=2~Jb>SHJvk}C#sRw1rdTA%~p4oTTl`h+=b#L=yyV#Gi zYE6G>>o1jMNB~vb5A5i8Kv8{ed}ORxa)WlF%gGyZuXt~>NftW_%{X+rOi zohnZWqa;m{y@6oFir=5dyQ+c853f?dk56SF$&*Ze6O{aJW6mD!YFCK4AFEay7NZ$5 z{4vQe=YjBYoxWhH$&ux_jGLu5aM|OV|6h^*sZwBw~vJRHTNe;_q#~11QHoq zz%%2wTXlzPVd(h^m_0ORTH?!R3+*F4BM;27)XuL@x_PHxQChO-#-02VOEQ?o8!8BE z5`KzRe%hfpm7}mLPyugBArFOpjJ)^#dsd1=cbbFO-6LTvLjyRx^G%j|f0q1*qCN8pyTVQr%RsS9@Z02{9HY0a+sI%Q3&+UIrqj^n3rk zHOa4LzrkO%G!gNN&U08TXW#YCGP^QIhP`o~$9*+-M47S0rs4f1(QJDEoqK@?$LO1D zDl5_0QELKT87S8Hc{@5Y=?>_$Wpr0%nSVnK@#&O6#hYnErmb>r>OQvEe7M#WyO{}$ zcaXr4T|LW|xPf&V+n_TA=~-q z5Y(vR$)eD%wP3@8G=iC?o)qbTOn2J(^|O4NMr0QQZ#GqctK6i=|6TMHqx|QM^r*&N zwQ4>hvp@q%n}M_W1~e-Vj*}(mK=Kc5dge2jWL|k^ouvQVOXGm}(-+O%dS?A$IpW0K zr6Vo&>)yGm@*!_ZTD0v5Cuq&=zi1rcG%cS8Q4cZfspu^Kwo3@MC&PQtMg=BsRFd6| z_Xrlu)ta{Xj29%nqmj?i`@^^;@uQ~WP?pq78VbQZhf0p3f&x_-E`9%XS^6`MMJtJX zOiWBIP#u0~byYYCHCMpu*TDm@-@pbDmhCf%IFM>^s}) zqA#RNEGn74hh;V}JX*MtsnemiLGPpEf}eaIk0#{J=4FWv`+;;$w3cenov0JwqX(_e z8j*+PWpY0?f@KbsUi&c9WSVS-|MTHNt71E-$52~+IQ|W@zv*(iQ*Uv*por6$7p@X+ zywA_g8`$>J4q7Q4@Y<-d$E~^WI#XAF(!R(Th9bEdG^krSFWT#;qfvDNpT0D0^PvF{ z%8;PLqV$D(gRNJ&bzo#72}aJ}H6KhyD{reTr>`9O1P36z%y8fbT=zkP6{E$$R64hy z!1t>K(9GKm*r5*)P!s`2PZ4yD!2jesA}{Ubdd`(O%jk1LB+~ z8=1cut5O9U@V0<`hac<83GEW7}2X1x;TB;8*@|H$JDEdNsu2Da#6uPl_Aewc27 zblef?m^KnVlDh%TH-P?TwxH#V%U}{T7seI0P;k{nRX1idygdbS*wo+zy`M1r0wdTS zYi5Qq&I6bXCAw?S141r|fx+}&L%36#(3w^GeVDneCh{O+!@Vp_o%*+(eddVoot}Zn z*u**t)5f?QnJseHYx+C{_W~XUXa@0l=&LAFm#EJPO$l;vD4T)5%EA+m z?yyehCcT+I^$nI)a8=-m+uR|$96HGsjM^9)=(kI91*#ghZUny&$Ab}9G5wqvufjoL ziBu@-*_Bn#{N}-5bQ&+!&r3a^17&Np#@*#`?mp0|8w71v+&~z#d8aXmU`PD9yFcl@ zVOW;Q4%YXeYO@;YIGY7Ru1E?xK%w={a|p%X4zA^NkCLX5Ucv>>aB%zm6@ekEYylgz ze8FMd0u$Mc&;0Fz0L4c}x!s1u8^D@W2$K~{;Fc!w%-x?SVKX}LLHblg{c7*$6;>_R z)j5iKMpW39_68g0Tnk=N?{>mQ!^gAM!DWq2c19!ji9{noRlQrqGwVlzC>NsrrUv#g zbr24>volM%z$V{nQ1*q*i~i~p>uMDKwf80fO$TI!W**-KK@cFGc10r?*`j#z(E|m* zl$h(D(8Ce##klbnem^uS3I_G?p=MSe^N*Orq8V%^BiT$5Mk|fSh$Dq<)cdhtG-Mf$ z++681M?02#YP8d&ZpmWC^&QqLzo~O$YH{&Q&<_TrfHy;5GefM=+9AXGeAe z7%}S?z~cGX@g)PLBVXE~x1oSLFk0zONujFGeAEhGs6-%DIsz?F3rwCoL0ct{i(o;Z zZhw_rvAC$Qad$z~L$j{e?S)r@!uVx`Sk6&DwOzyBNN&PspYv|1%vEeNz@06BPqrAR z$Pqt`jH;J=D(IA7x7&YrW&T*NPRld7Ha+rRB79FsK64%$1X?GsMgDc*H<{^;#;>2}Hd<#t-0p5`1yocNT8OM@{+oO0u&Z^0{_`9~$4MA%vC$JN}A zNbEaW$9!N@?3d}Q4Ikd@fLKns@cd&uayoKu|EPB_2i0UIg!?oHspvqt2V^Iwz#R2M znB?uX!9TPEaNzpD{l$iMJF){37JTPM8z5n8b*FnfEXB@1$zKr^gmXY!6|n^f7vuUg z#>_1r$uaCK^sZ`PjZk_hzb9Xj!{tl#`>KN@2L&H3Glu2?OM;P#^qsO>8{qf;$HxHW z0BH@%x1g&hu6U-6RKm<)&w9514sqx%LOxcHF;KOoVxe zqqWJd+O%_svtiU7y%N$)y`^yIS~8S`=;ht}awtoTR1JD>fh_M&S5Fx1z_s@hwaANg z37S!9t_P@C`DH8*+-Y<#fRTP{S)<_N2%Y~j2 zOih<~yHO&T9Bh0mv{cv}Ce9rc)5B!?NfVC6MsU?g=1U|gjI;*hItseYtUvMQJGYM6 zmKkal`6gu)o$;9iQp=;lnYLk4ZJX%DSd;(g zwgmVVil+!mEXX2=kf3J`Ww7!>Q+P1uqRclN97-zv440K-!Ft#up$Pi1< zy1qYt&HgOjW$b)C*P5OLHN522-{CpDWq4F2-vT|dy}1i;P@+2Q{5HivFy~gZfmwg+ zYn17HpJJxoJJkEQzG$hNijq)KH(}01TgFwbP+pm;5Kg=Ha_@&MzVA~914qgE5}mli zqoAukI%ygjv^ump2CzX}^g2)paT_ql0+J8b0ASV(*L!thNSk|w&d zq@T*4!`qpOWpxK;Ql3A>;_Sv%H57+lWRl~uq|MIuMTz$nichS>;QDKo6VCIi5&D}0 zg9m;2oPDIFPMtR(k*u0SA9~H}Qfj`AbyJ}B^nG!7-_)HcoHS9|5X{X6+q=Et95KAA zk>WGhQ6ykauLV#tYFIu`op+@bF>gJ!r(M)^pKX&%v#oTy8x>cse8RMS5B!ZZ-nG7) z-|{FJYyPLuCT_RhsA9({}as`hPN#k6e53BNos6l>Jy{$6mRoEBf`zstR{L%(r z@l3D2I9dpF{`ZG#?X(TOwy z8w<6}&s3Y!ZC*#4fXm@tz{RM4`I-C~i2Aqjx7sT7XT&Yz9mU*qSS7>6&zeZ%sIk1IfI$)_8$WgX^3DaGs`jM@{R$fRmu_E&CP z;#KasH?V?eI^+oj?7OASI|S64GP#2esrii0Z>H}4+Ei7z^6&=FsZ{xm(RVQ_?9f_w zK+G7w6~?jU8gD&HaNZOWCXIcnD*7h4)|4`@k7c4tvY8}@ z`O9i#8@V}hyJ&A_ zSn0+I&X5l2c{>7I6SCA?iK(S}k0aVcuRgf%f5A>lJ*5?)TZN{;6~Xbq^2O9 z)73tfuRrcvN?q4yBo1Jnwk*>dN^U7p>^IP4$dhD%CP_91KCaM$oecEmqBqvsvimi= z@9CQYq0er`HsvDDIEXE`RjTjaQ%e$-AaV;5ICrr9=8b$$7(-}oA6Cy>B;Y=;&14-Z(d(NQNI^|lX{xO1wAhXp_$Zu z$!?#gtHp;KUuUOMKPy8s+tiL8XYmJKAaFi!q#W&#^ zUH6QaOq@MsPU&kazp&m3TkxeoEOgXJa57cbkRyKs)iA^CC_jz4lWO2!SYZBJU$?#e<|e&1;LWWpkO zRsXHY12FplV7pVhbrd-Z{i$E_A%gQ|kt8JJpbu2Q2gXow3w^mcQP^m&gR%M_x_ z?zw&=x|0i{C$Pp|S0tBhcrsQn-W7p^_zx?5e#Fh#d4y0>@1~epwe2LX?doX5Drf$a zRZc|P#vDAWTw_jq+IhE6uSd-4UKSZm9yj##tvK_;vkde2{WJuVFjW zrx$p`;{j=qzUHD7V8`H+voXL*bcryMcY-^rwfw|Ay7ROgJfnSuI5XiPJNPruPZXUl z9Hj*rs3 zutD=}1zU=7mCs`)_1vM5kIuHE*)n%-E~{qYlX5Hj^4-PUa^(I{tuvnme{bYi@69e( ze^;Vx&khsJwLa&7GLPU3MMHfgFW+w7XyVrM*1qh1;x{6wFe|k2EhX=(fXm3qa5?}% z!@jZsyNTT=RQ}KxR%~B>LxCRl#j%4oL(rk%h%7pUj3;Cg9?u24Fh2H{UVb_0B1z?f z59I9Nd1+9*G*8W)V?BMM&s+w!uz7>K1XcTlm%Zh@)~Q@9aR7q8ow-hq<8yFcPU;Yt z*UPCl^K{lQbuvZVnC~`G;n?AGx;{kBy;Z`t%;^@Hc;17fVzIjj;XV@Dn2X2o8GfK z8N`1@elYfYcQ@}+y=6+3YRe}?FoSl#@MW?O!ohMgPuu6-JTw!}<@XC}EdvM*w`fKy; zt|`T01e0>U*h%Mb4a*U3@L-#&Vy}ZInlc_Z+Mh4>p-L!}TW6wi$hNZ8GoyG&ENJZB zhXPU`Nz!Ol4b$3ZTZbz$`^I*ZjH%;;pg!xvZu;5M{PQjm5SygC(#eW|N7t`e+(wUp zI>JD%W$PyGY;A-7FWcCUVk5bpAT}6g6{K-TO3P=?dI4@af6W_ph7}w3djofJwoHpU zzsqJApH{1$mP|Yn50yCbCymC3-0%<|c|MQfC=ALc9a!S>Wh_dRDrA!xI~r8c*CB`J z&d3`IDU2!i$tPFA7J9s}CSue04~fAYUQ$Skm@qZa3oUHQQskhtfCxsrw4O3iGZ@K; z@cN*>bBRh8SjvfBqkTJN@HbUV%^D`$T*Ntg%_sp72vghoA4{`NJKBwE%4J_wun~Kt zi5LPa=W3Z3ObfrYWC2Vw(th(UT^%5`X0i@26TyX~ku7j%G8D$@rpm3-55f(*mk=L; z{^;0YS4~X`n!I3)r67}%gmhyR?i+8?ez8>+VYSTkFp_^EFJ!xI0W7gUIUa9J5dqwR zFhsj!{oHefid)UJd{?!H@!M5~uMQ~Yv}!7u+oOzMsA6QmwwO8;=-BaruV@5c5_Nb& zjM^CEwPWy-^qDiZw_FKKorLkLBhR1OR$&@fdeyP;)ev4fnd~>1cvPP+?pjvu=9Nt8 zUUAUiL~_Xwom*JxlhT@`-#pAzk7v^~s#iu0cIhVHwm+&$IR-bM0YG-u=r-QbPXkS|{ zi?$G{{o{^ym%}beJANN_Y>vQs146M>k+prI2%MRBwl6O9}oMd~>HrQ48Z2OySR5|L)%BQvy6Ap*PaO6a*Q^niJwJc&c@xA0FmninJBIKe0{o3^2Wjm%P+C+rdoUERb+U++j6K5aY~ z(<;SEM}2G?T0JV|!b?8;z8`=MBxPi4pe2>;Rb)gN zDVv+89g-xnizqW>uS)ioz3%MoHg4;-e&==Ld8@al_v!onec$)}BRzxLXI$5Lo#$~L z$8q}6=PLAQvS_E;``pHF;xn)H8tqZ`r&Zw0Hb0kjcyIxm&AdLSDaZC}Z_3Ca3^T^E zztd-$Agz;MwR*G*<8TvqXTuJro|0^iZhuRSGlB2(KhBo=>E>3Y>sD%>*6EOtHxlY( zo!8WU;Kv-uY$0hO=P&7yT=TU%ar860OZ%i<(4+aVgAt{Aqow1@S_i}d@4B#I!)yJX z$MqRAR&kx2>)VID)YC+cYwv0WV&;O_!9(AIbkOD7bZHmcVyix^KS2X*2Vqlw+yS!V0=MLe^> z?n?&-h0G^9`IaRO$T<1NdS^MgZY1W8CKb| zE#@$`#FE=_VLT|GFfow&j1`VA^3Pd2jhn0qY8yG4O>yhXv4ix=kgr2U0cEAD-V`(JJG_Bx-ql)Uj%% z;kWd;1bOI|E_Ri;+Mz~WeO<#wnop06n%2>OTWlembSli^h+Tgm^V z8%MK=)8Fi>2srtU77_aW(x-?%|XU!1nakdp{+AWE#pV zp^CjN<+=LN)Dzz9xp>nM(;H8tSC|fPJF{>w=T>qTbAOC=omg9IO%{lu|S! zM~Ev(X{F%Vb`rWQ5SLfT@PA&oVG>+U!nkO2|4*YFvi~!O0VtN-S+gy;ysuwD(f)0I zftMY&1W0(UgmL0EqBrQe)bw!>1%E0BzqDb_m`%ZU zhssy33ZH|$P zL=xBnJM1IpIc+I2u8cd zCFe$RLQ>9a>RthVjz^Lw%7P>%m0~ouquGyo!jdqLRzw(^<&bXd`ovP{FR?dEZ91%s zwta--sK^Lv55J?|F(fb+`M_{YU|k2I%Cy~~ZGRK;_)&Y}{Pbu?dRqgR<)=H80d>{6 zv+pAq*8ARcBQvdw(ezSFl`#>epM3-bM=6P-pNgo6(Btf7Z8RTx6l}FV181%sOw4c@ zvW^2Gg&2bZ1B=doW{-NME8Exn`)q0$_6~Fh-Qmj8^UK3?NB{dbl5K5Rianx?nE~LK< zJc4bn!*p>kChI`{s~5skbAQ1ojmdlctn%EGS@!bpaJzwwSpD)qCYI?BYeiO9`I%)v zV5|WK1^#%~KgiW0gq3n<+o0)vm_t5r2aJ2Y2BR*xMnBWa-;~&8TfS;y;kie#4Jfbd zXU58o5cWyJgbERZIJLThE`P<=lW_Bj#|giDzPIsq-SB*;?Q*fPW0I%;H8Z&14dB97 zVOnSroNr|M@`hpl{nam8&(U4pPCQwF!qo@KS_kwcnF^RE=sD9no zj)CRUo37%zGk@|BqQ*fh7dts0OqeN{IvId-_b|v7{UkD`_7ed7JFQ`ZDUqw%Vxda%MoqD(saV>w#*Dk?9V1tE}B${>(~(8_3X5WPcb86JTlr z6v3>z!CYpi8oK+vFjTkdEbSr~_fUV>ps|t{EXTw5$G!&Nrg~&iCd`>+(!$^l^K!MY zXRuVxm9g=_##*oh08_*y!~kD%4-Rf2{V?(cx4A9z&MH&D+rtwMyw?&~8^2NePhu0!2K^ z>_L{qRX*D9gJQ}DX?o2qFoW?S49^kW5?GQbHcxU(V*d~5-@I?KJQR;@CJQ44v9dQlG@U*`bV$RA$Jb4q_lLfxi4 z2+FFs`~cgIqESW2Fstk`uHCOutY{OFPke{=>;v%LOYtXlTd5^h9%Sh1$50cOVa2v` ztI%}hyUR<)Mms|VLZxt6%WETOu95DRDGW3KK;3XHo;Tl@E{UuzX!1>uE2LDTmZ6!O=OrfV8!oUsS=pK zr)TbLhkD2z^b@&2OzfC!GBvpHht#NVn)Rwoqne2N6mwll_CF!QmAs}`>Fd+e`yZka z--6d0w?NJ@FxeOV2pESEH`T9s!}^1iXCrT zyFiF1BqvIiUCQO@%ItX(=Lf(HU*8_;dA8r)jsU)3KF?UsWrSscYosm+KLYd}e$0V_ zr^wJC-??s~?1vzZ2E`g#wv1CNPF{HsRR9Zx-VIgSs(q5|JjAZU6aFBjtt zbA$<6Y5+^i755$(sQivn$+}Zwu8le$CXJy}^dXF0yA2cHzJubI!`C*%nHLL|amw&2 zn52B8>%ZaM3Kt+KnYTx2nRWdhkxJ+0h^*h^->-*?Xn2TPXW-DRd4B>{+4IWFwIM&O zGW$+;mWOW@!t;U_@Zr;y?v9^B$szmv2I5_Qf3D}DpkzMBF4cPK$}Hj$ds}cVi%A<1 ztJHC!=70D=_GgTIBBpV`(RO8lVe2pm5VUP%-*{6Im+gmb5UV;#1;{$1k0+rZtcWvws=2a=GWY3mL&`3=?!LK}`BTiMLZ zAH@gy+=5j`2WcccK zCVg=L3!Ys&y>iqX|NJ98-Sh7)ivN!bLE}c@Zu4gI{9G_BY=;Q|IxrAY1_sq`{I-h* zWlkP&-dL&MY+^Ot9goP(L&d3dD~ASDBD|7|h)&3`V%xgBdTw$-Jf>HWELRucfrd$# z-c6s0rTS_m`p|5G^5LPbySU&A109C-63Nah0QyS#Ed%S*MhgCLc_5CtsdicPvewuz z8AXkmC8qK3M~ywLy_r4YxQE~qkSC8JD8O9MCBFCfA9cwU_Uo7v{88H3gwT~NfAwWA z(FzlY7GvYFM6&g_5EVE#Cd0$B;e*hn_+=-YM`|+nRo#C)k6{1tqiK-!;0Zc6XdsEE za{ilN!Viq|fBQ>FX@A6}1AHztO&|q8(SQG5EFK>Z`CN8 z11&CBL0+7WT5|5dzyB@#Ks){Pe|9Q#ro1?0kOiP) zz;^fNFs{Jei%U5VWRL2qWiF=TJb!~NIFv>Bfu1EcxEkmybNhDsnz^+LOmul`x6YXT z0a{F(%z+6Lp=2k!ce|oF=D7FniDJ)Y`$@^PY;q!3kCc-zC_x8QigCL6RJii{Coxd6 zUTcW2hoKLz6VpLVnY&q&9TSxB51P|#4)#iCMnvnLDOpF;KN)KA=-is3hzv5Y!VZ`_ zYIXgrR{JM+6~u3$M<*I+N^kZ2sVQYR!y)HeEqrl^f!#EoNN0m?EFDxLZ@GKi(vH|u zd@f*2zACw;OQTGIY=#vEP%fLcM13%T5#31Y1MZ)+qkh;q{rd0*W#JllPRI@#Dskus z#8d&O;u^m1_8z?(N$!2_t$#{SbE&M{<{ZlQ89>bnJiRfY&Yw$gTY(i+vm;bl5;weX z?sTb*KpRfk$SPF>Hxu|}-s6x3rqjRqwhgCJ6rN#2Hc{=#zFf~LBIKm!;&EV|ML#O| z|EWGToK&proNp+1OtSE3r*VLWUrN4VjEDBe0S~zpnNeRteDVGP`+*j~*fPT=ebbtn zE@h9(rAYeT2vV1|YHDmPwfl29d~4~0(5RhIu^@3e>OWYu`bAm{W2679_5&4l>}G7d zq-@zkDM3{`V?S$0$(3zRI=gfpX9*7}?&bDNj$g=(ok( zOn#(~ceEb*qFFoC^3zAXVm7q2fFJE4o?ES=?nFivXYaT2)C`N>{C|}Bsbo;)jrPf7 z(h@#^?$j#FrbKs;EZ4aIG;b#Va~}2D84jVJq~C}>^U*nXtt|b0HnBPh@Xs-?zjR={@uGZ;aCF}KE7%Ielc zC`JqIT?M)A_D6XuRo-&ihwN;gOnsqvlDxSAsi-EqnjbB<{w7hAz|-zKM11+D)1b5} zH%9BscPmT``f^aD#FqbCvE6&EuNB9r-B1zCbRX)>!-2N_Z)^RYkwVV7L0b2RoD*4^ z6wF@zSH=Kt_P9JpE)ikR5>ZAfh+23`pNfd`?9vsEtf6N>FHgONMAz5>Q- zrWe*g%5!jw+mCrCaMM|FUXco%5gUKv16k8=>7Z4Hws)c^gv^J;j&Rs5Q^15MJWDv>j7ES z=z??sh^DzmY~635%DBUD%lCNCfvu=A7XN8wjFjmDsXzkyC#W{WptR4nAlyNss;yyoethKdxoU zs*->`!c%^#Z+Q$9G}|)a^<)IB0GQulRmuS0`8GrMqr+&0c(Kx7M`}~8(|-+G22YUD zYnUBD#E(&!rkD%(?tfq@0JpI1FceE22q>BZvjQXZ80H%(&XqLXCUNdw=L(*YsV)ie zS(^jGX6MaY@mwU$E_NGLQ#{b_hJMvj8vzu9LOw{8Y@D#CLo4vi3NIR`io@;&7x zwnOtda(UiPB&NTX8BesIpTmr11J&V{U(wABsD~Ru|)*tx9~{K2-{yCOg1jg-@^O8Ja$-3$6VY z&UQD0>iH?zxK`*q=eh7^ZG*ue4q#L&{(h=KuvCJs&;H@hdY^>8& zSuxIqlKC)xq1pRL=MCN-Vb0loxX+Iiy)f!y3F67wjdKZ_5U+Tfppa;>dqqL>MhoJX zMn}YAmMFe8czO~3p{dw-%fxs)iNpD0`z0P^O<$UPWvOMq?V6YN%?l=zvO;Q=K}tJl zxN9X5Y2q^BRk8`N9VQi9pMQJpFs?HWen-zyBGExGVp!~Y|t=I7L}_48C%^0dd5-#nH_i@ zQUp&hd;?Dy&-kYKbo7M>wazGg)m|jjjm~1>#x6eOlnO2_LL;ru{)s*#3(P-qp$31dILo2N=^<0h zZ1-h?R(B58O19Nzj4!_O9Qij^YcAaIny~5Rl8g2|nW?^Y3oY;_cb|U#85p3dyOX?w zlqo}nj{06g%!cHto+#K_j@0~Z2CrtD9fkq$u(F~bluV0}q=hnUW{vv9c>M4VIGWFe z0fnhvV1O{2(d0F8gGqWmqqkwt!W5JjH;sDX-=@PR+npQ~W0TVb-tNnqCRu1d-~e-& zi=OQb;3e57v8xT9$*}zsrz!uI!l@g$et~VmLf>8d67`4fJTa%wyvK-4yz0`_vw9ur zwt=q$>?hItj{lf<<;yj)g7lXSWTACls%hx1tn^Kfl6vo(rVt-2jJ%^mBMqCud&SNn z!nCE^NP?W=8L!z`A!q(-dX0+IMVC)eYn}J4esm1)t#RX|7$UwyrW{jrdLp-8T0yF9 z6l&Z2_FR`Kf<7Tj#pxum7;%=M-2=~>dTg)6;k0R*z3%ht!S^F~z!UJ$xcKuF8Peb^ z^n3*mAvWH9HCB%6B0xBJ^DFnTuiuhQ?ZPXz*LDJ|MOymmxTrjY=11lht^hw(1gk+n z1;iujZF|n#qx#|=wRc%GvW}Jlw(?L-Q!96o8fF70t#cF zef;RByX%Y9;?2RF;*j&J?UyD88v>}$Uo}3TRDPk>`wI_MBweh)BU8a!4;*n@$^c&& zA0m^NmO;(fMB_R_ zyQk2bM>%){e{-3P>2?>5W+`Gu9IOM`uGqU@X4U(%=f->v>YeIgtpmEmmzA5eUq7D@ zr&-GUWRnB!EmcY(DrX70Jy~8^)?y3O9S&(^Ut-cfM5!i-C~#-Fwd$HWTV)PtB3Vf; znlN3K{KalL8?Ax%RYCes+m+u#N5L9!u{Xrsl9E4wAD@V}_Lpz*L@Rjs8ypTB;+6cqF6{lLBh2M*A{I4V8lb{L>f;-0+T zzV{eQKR*e=tHFC}iFpE3K%iqD^*0jEB1oWk>%JJKufCT>)CtD{-wg2ZnPeS}XwBvIF}nNgq?VN-}T0gh#d z^4wXlZxU5Ekdmd7H+rpb0bsSgae@1`=lB~i#JMcgAPtjoEqgiB-c;)X9wKh7Yb$Yf z%0wPDm@4GqFpINg&bHW7xZx$ABBUGak*oRZ_O%)>akg(Ooc4J@IAzM7>*6KeH51&m zFw>0!Ha_rsL#4Aq?FA^-q=MFG0Aa};i48zDA4Sp7lN$8}?}8OZb-vi*+;|+cQbgpU zEiGoC2g(SevmODBza;V**2B01VLyDx< z5N@Y5L9#P}V#26YMwWo8r-^TPzZnGoeAun+&TE;^-5DI$sJ%+a#eH-K;>9R%6>M`ha-vLv{plrv)_-B1$-x%0E z{XLXiY{U>u^aQjK_~rd+fI|tQv0B4<+5u{utKSy0icrPBQA-Kv5Iqr8o_-q-goBk2 zhNWlpx0m0SBzF*4S&3fiWt|@{mt+Cn7;d=m)p9Fg6U0#2UABh+B>pR&4wSq|sk#G( zD#t+#wuXKBZOJQD1E5R9R+FA-s;ZvxVOEFMQ@ejV+CI>3OyDuHjoszn&JL0%uxe`haRri-Vev7tU>a85lif#1oa@Q9kbT}dDJZ>bbJn+v)Q4nFHPb+x4Iyx z$F$!;hM_NEhy=da@G%g-(K!mfaYzULD7|$H^^iz>@LZMpF3ICRN-u1JkActnkolp- z3d<9%miW|Wyt}YD)uP3&b2ZF*(t28Qn}jTG^&avEJcAaF41Gi9;U29fxhIGhK<>L! zip@#W?I=k)9s4}x6Uixh3nf?L6CojUgv-f)C_XcOIHu$g3E9m0Cz9pZ>RDI*DuX6c z_%g1;zjTYL@QqEm@F)5L<4JZ0qfI;s%)LisivgsU5`bFDb|=~&nH#a)}~Ds zSd4BV>wH_NLBUF+0F$SD(j0rjJX)FU-~lSR9w$EY;Jxt9>udIqzf!V!PQxlM*L{@4*#|AW>IqRH zSa|h+ci{!WJ)RtB7g-%y&>CHC4f^EwD<(qXr8z52` zo!rW>0S3j&sU}@}VeBqOFV7|w=nE5z$oSC8dplrd0uL_k@2)%vwDMd;VG3$e39QDM zb+Gd4JR1x{%hT4vmwkEGOAjX=R&27Jhh(z)Yr&^7gzBAY`r=#24zCkDExo+M>c{|2 zdhTbEws%{`0%0ItCwE;Pv(5g%qfTN1FV>Ti>#RFRL8DNIYv!+N(v@e=giX5i2Kl9( zU{f&MC9&j^A<(j7hIzZAwk_>ia(lQQcX}&WfY)AZCnX=FW5ooNLxteK6El_kfS!bzhL; zHvV_L+~JmVmxbx5SRj)YK_gegt~1qo9qCy0mHp&25B5TQIis0v0jthk+zk&;YH7d2 zvA>RV&@`=;@Qw6ez%kK-B0A;=UQCg&%Q(t{;Ke;l?Ml2(tJ4oPIceXqoYXK+FKcNAIy>2wq*bbINovI z_P^`ZmVuySJD9K>0BI%t6<|Nbh>vNA-6gRxI!I4O@p%iJ9bqxpRET)_fikubfR|#q z;Uf}Qbpr4Nm0a3^qncBPW%OF>l?WkSpC8id zfoDuSfH{VIv2Wi}@?q1hc=O-TSVry3<~_y!?o-kJODu(1-~RRDmi9#77umeWOpH_` zz+*Y>;NXyZTTfgjmy&V&lTUnj(TO{hv{(A7USCjFR;I&RP59&Yt~++0%B#?mQ)oB; z91}UsiE~oxNoCv^b|2C&c>=OU#oURAw|2iE|-f>Y3$h-i`UUs+$=KILkJ)c24bn*@B?+R?t}m}cY{=6IyZb$ zJ>NP~Q!+IQvj#oyLKt&Lml$_KQZlM8GAz$Yx4uh9z0crrYn1F1d~a9BD>pnOf8Ik) z$>YrY*V^jslJOxDbzH{|EKI7iD5*4%4~AF=>FUwHbE`f|l4<^aq5JYoa>Di6Dfd%t zQ=56nRZ`3@8-}{ubd1;AoOPqhe}}sgbxoWp2;Z|*cM-_(FxF9Zc6aVGz^WsR&93tv_MsY)sXqe zbzJFA4!dTT|0>dlHQyZ?f=;ZPS1#D}IImip6>gPN#XHWY1*j|Kmm97{X>rl~d1{~2 zFMT9yNHJ&Ui=}y5KU$Gv;aY@qsiOGyjV-@8S^XB}`PnIN5J8LV_zL~PjT<$*v{c>C zU(L!}5WB0}Yt;{!|NZb*_zeIxDttMCeb!QdJ;Lfh%0s?Q_(td%KS3Ui$my1F`x1p| zSEGm6?KfHaN^N1L2Bb@Oiythk3EyZ8%7Hdyg9(xZ?MD@7XckRi$9o35_ z_aB}ylrSE8s&W}#lRG{w77o@(>~4$+W)WpsXQLr6xwfE{edx;heF9YjxLDYWtQaj) zdB(oP*0ZM55xkBDU#;$O_`06_Qud7&|REEgj&xIiu3h~e&;-|M=r}P^8Hs6hrGchqy z7E>>|I^4XO?P{oG&8Dx@6c@v#-qL)9$sn5?iWqpw$7q5*T4PkwUcBB)Hp2WqeK|`c zjda>d2AC6P^I_le#xWy!GC+k69244?+XXCp@ot^;WnuX0hK-E&cLKY-u0jz;dRoZG8}MW5;}| z#PY)>=dY%AJy-7paN-Flb4uo>d=HIW+>y{WgY-i;fRt4@*pSe*FpD!SyD*);3GPc) z>XyWAsD}i9vnWynP0s!&=R;&xuaY}4jLpXWkiOJH(!cYyqsazFL2j{t8z2oH11aTa zF@f&=@1&w+2ngI9dnj*z6mX3Fi-g$4ebB=@eD*C^=Z}HlNoCE3ZLE@nO7|;Z`==Ot zg59C!{sUTK`n@Lwj>$=q3lx`5G9Uo(#LP^k<6G0<>&ac@}QFHMwtSq~2zg`U=Z?7$Wu!;STkKpmUb1gOV%^{DT z_Dnjm&a3%QSX9K5JwNIM=t&{Cp|e4rN+pLUyz>$vznB-bdkF7wUCF)&EC43XzZ z1>Cr+)eh$cHU#wDl+659^w+H{vWUxCnieWdW(e$moiMbH^#FWz-;gQ>&meC5{^npk zUo*+{2j^97m{w40BM2Ioe$^~vkH3Alj~hNf~afNA~`Dlc1QhV@2?hS9OUOXfp%Z-0(b%;jfr@l-M&x{0CzQ z(0JY`AA*C4OP2#>Vh3J&WErOWjT2M;J-%pFJUIWWRS_sz$5}nFF*34?63;0kqR*bm z9NC;EpZldvK9`Ttcl2&4yK}pQy|v+EdvK%HQ18sN#zE$1caQ}#Kib2pY*M(^OlgW$wBj3j*N85!ZF+fjhYVvm=0l#6<;OgP8Pfi=$9YhH(wB9?=Du!{>*UHC8ZywzWNZ}I&0jgET?R3%^iA|nC8q6l~# zm;0bN=v~Bo{oq`2a{-zWr}RsF%r(vdh9fo;jv<7f>v<_GURpOl5sUGH^sAu2gS~4x zU=H?Tx5F+0(Pa?Lyq(BYS%7F4ocdmXx1Qmboesd+%ZAAZ?e7Xau^8v>aK3{!Zxp#Ni=bMl{eu;GY=T33rbzh;vpizsHqVpei!1HANLeD-1KU zt}HIhkJYN176Mu2%K_OO@0!ciZ_eLbzWy#Yz-s2`vWvn|pKZWIO9E{mm+sGd)S9g2O#-}LC zLY>;hDLHe}@L63Qm^<)dr}KnDm1DKy&DxGu>W@K?eK-s#Pt!e_nR{;dIt>fAIk+SX z!<3*y29KlElg|<+hq!X?Q&V>&o(;XgKHnoTCH&&B`76k`iXpkku`x_YW1a$M>8A+t z=4|1YyBb>OM`B1z2(W71i_B>3f#o1-vVd8f!qAr*7_FKE+pN#(iV-3)ySMQ}is&#qm<&Qbv3 z8Or(w4q$ZtDag14 z^`uYD+333Ald+EJs3{%~jk}5sts|7ZEHeeNN5`jt$h^iIpWZm~Iy}d_OtWVZ3|5%B7rikv z-XS(&o7iOvU{DArq^=t|Y!#e6*kzfgI&H7NmxLzhYu)_EANvsL{_rF;U~`+JPzP1i8nQ_6Oe*GK!hu%Ow4ybxu{=H@iw#0|-L0n2>(ECik{jc9=W3%|p-g7h1?B5RtF@xsQz6rCSsp0U=|I%$* znraVLi5oXgZ1gKWjXAk^#;@pfX)mFAI@V#xINo-mKg4bNb)3i)ujA-;aAP2LNRx}xFLCt^1)04rs^8+aT~4mIWEFk24Ro8$XNUR%`h zrRisGvOeZ_A!i=#&SDtT!Tp+Xza;b|+xkXtucfBK;K0-A`Q@B@CmkFz?ZKVQyUNDU z!oDwz{I!g&_}W|hGx?|R;G)XU-|o#YA5A47Akg-39428sL!mq0!|=-j^!nN5#YT@C z4u^Y4v?g-6zbFjqd0DVy<7$4Zm^!J(rVn!O_Ngt&YAj8BgVj*x=VY-$H_PSBHn^@xDeE8Nw@R*WbyF zOrt!s7Ly^K7DJ?E@r{+Yzp5~;=dH;B8DZM3wyT3K^t_JRo=FShOp&Dxul4a&Uxve> zZ|GYhZ{O$d%g$YQBG#hcuKfzHL)wj;?kU=QFNXRF46ndzA;G$b@}YHnXlr&I3Yu|6 zE*#U(e2>YC4!sYt@M7pmJhG4wG#}LryR2>RIN>6J(KLgv`cp5qX1qeubovgViVrgp zsa=RZq2uhpamL8oXK&y#r|$WA2Mtd2N5c=f~6SBvn_a({93ck?$qOAh2Mo(R(c zcHckm8xn`3h@;wx95-(ER(z~Jmu-rbF!{8Zm-}vzs^r?(%t^Hu!WLoGH8s-e@^33n zxR1V-ci7ixu5VdI!_e93#`Az}UXraF2-iGa)8Tux|C;%NYtp-<;-DA+0t~|klyWm+|(pheC`O4EZ zWQ6T+O7RdCAyKa1&R@m&WVw)*I)v)z(O*_hr1Q>M@<9@>ta@QHE)F*C#O2!Y0{Pl= zhDM4ta2XcxK)tw%m&dxG1f^JettO)8BsDzT44=>ghoBj1_E*2%RK76&{_lCL%F)SmuCe+7n8=DXFU-lJx5#8ZwY zH{Up&LOMD(Gmf1ix4V8}5yW!)#O)@zXO9z5Ks%^kvdw1XGL{Kz_?-FsRdNVTA91sa8xhVOVYaemujTDgFrFLNvmzQJJVf4h_o4e^C&lpzoKN zJ?ds!08JG=Ab%g!&D#J4w)+MK{u67cnYn>u@|2h{z0lGI*Q7|4rm-0a8P{^FW;9D15Opjdd16!#E8G>g3 z7IZ)y^jg+0(U@F+Y@t@^_0T#SVivdCTVr$C6xew`1E^p+CC7`Qdm@h%IN=mRyAbhx zTZj-VjFuj;sYb<1au2jB{z9w7Fhi1mbw!8>=iSVzV9Z_pE zX)=aqOew{sjNh?!B=|W?T-9`cEBp!6A+nB(vsiD3 zOUIbq@UO!^;+j(xvcO`UCG)M+G1}`sbsEJ0kMEnpViqeUt7J;bq1J8VShbOH@Rrnb z&Z>cFZYtaTz*JU#;E^{4L7VL?WKPOuz5%(avEJ|LaPApJxP!c$cdemX1Er=zBD$lWKQwJ{oA?1O{>Jy8= zeZ0&0dHiVbZaDjr@5IOIzQ4lmunwX}IE{2IktA`h6jf}MY`=t+IL`WS8)nD?KPEFP z6RjD_a}-a4b{_%`g$AiHn^WLj!Ak9$mC^^zzJ3^aPYE?*URXf_>dwMD``zwrjRqDd z-m4JOa8!2=Mw%8epJ5!vrQ;+j!!t0DD0qOU(r3|B{jxcjJ+6I^ifJEGYjlAHgGu+b zxm)Dd;C`;3b&X$N0q1ZP^l*QRFyah`g{nqIMpr->FqX$?nvzsthbS35MJV?@&3c+m zs&9ww#i=u*EAqtB+6JDkOH&_K2{mdopS9x$z&Rk!=T^b!Li zG$8hZJ=arI;JaAql=`Puk7Qd8sm*+%&pKzRSt_;#!{pon?=^vK41jzIzdgShJ-#M2 znRq^C5-qBFeOixz??bB>wTWGbVBu!NQ*2UE7MELZk{d#&`04LNUz`tTU9m&1I^M%By|k$rZQ)^;SWb`R;*41gV1QRuIzaMH`vOE9WwMt=$j<@@?BC*%jKb*g-_1E7 z?_BpVU)p7BAwVv~oExYHTlFNM(%lVI18!C9IOKHhK(YG0#VmwXVq7md8Rvcyn&8I* z?)wh6W~#$DGxqG6Qq!Zi9dhchi}Tp~oHbUsR!#g#{C#Q`s*Mw|*$ZiN004NUrKNQT zUA(h>0lPShxlt-mR{#}e7do0a1Fd&{I`6aD*%P=?23DOsz+ezO|C@p910YD-H;19c z2c~Q3->-9^9;w7<^}L3KjrskB{VnxK?vtB5UY`RJ@{QDKZ)+J}Ts$2Gz0~I?%$SKN z&0CZd%06ErTttIbeX(&t_59`ZfeO^_7^Z4QxlZWC9T2`HS+ zh~Jd$(ct#()1&6&UE)tZ-BMmpx|K(57o<*I2}wr_5^1DNlTx5-`6e|Tdexd7`ETYH z_Pc#p>L-7mioAAKMC5L{TCE4q@aN{?e^3UzVBhCQcJ0DwU7Z^3pcHz!p#7-$-VdCoLJMwLE|N4Vni>kbGAf| zZ1RW(ZQL^NU>|2i+AZVMftd79PlPSH3!p%eyEMo}tB~UNP7v_aW>DdTIEL3Ail1|m zX3ylYbUpgP4?3#IPZFWa($~4G%Bcr{nZfsUn`J5xMqY$iRo6L4vpdYB7_!fgbrtJD zJjqzQQT^~_E6@C!@`)lE*X;S)`*cczq_cZkd!T`RjU7GU9no(1=NQo@eTT(2TO4^S zk2-kA*@oG(c}q|HB7@f_fjGSBD&{qpUBvm4h2vre&#GLe8(34L z5j$vC96~oUoIlQcx z51W0pBkp&${}n-?K^dR|FEIXNKO=$K&wH-h=n3D`%gW0OHQO+MR@`xJdZaoXg0Et( zl@UXqUmE+29YrWl@Ldvi*~ibomEo>2UH0rVcdKA9q5Lz-q|mG-rb%Z>d$b8TQ=sAmJFxUirL3|4GuC2ycJ?!(~E^;)Dv+nE8JY zL(1HxNFc}L_XU^h7xiwX*+WML4k5h!^CL%>nR>tnl1Ck*8?!^n_wV+(;|VtfA;SS~ zg?UHb$?MmLDp@AS{W7l}syu<^7h2d#_ICZVb);H0U38Vogo_<$o|PKWG0FyHta5mZ9;BZnn+X>qpP_I?A~-rf%PkF!F<@f9czN- zY&5j>Wr2?i|GUSa@Qf@uY-I?XT{8H4axdNRYNp{r`7mxUvCZ@V`7+WPPXXc6_*XS` zG8wd0p91GbAPNJgeEiM63&~sgww`5^+Mw8doWyw>B66P7I}5h~6w$xQ2Lpy7vrso& zHQ}Hr@WFsCCMJ1WUt}j7L`ebYG~$(6=F=$xpH9>DSA06UH*ep1K-wi7wFsb(HyxK! zO5%e!Ga%=_ImiiZOBx`o-P>mYM=%yhqJOW#1X}EP3Lhtixz4*`lN2lJ)6b|L{IZFd z;*S`!m)txKB;9MG&c9c;b5%sE3svUvILHNvC<1@0qjqQBr@h2$ zf}HgjoaJz#C)qO{fF=6(2;zwK+>z)1&kGV*ut~J=$WHNDE{1X7s?@WM1tr#j{ zk^i#w*IN_mjf|M176DdwfjN#JqorN%Dp1fI^Ad)|a}Qekd>3DM%Gk~V+41jj*b(DC z-%S`6VHQlMCz}DnaC!OD7mq1`r+b|fzLdID64M`wE2yha&;E<@%VahGXvpG+FLlt; zy#mdK|F*@KY^uHekp3B!MbMsdf@sD?-DTT);EBVY1?j^EC}`0}24ob7wttW4JO_`< zozVg$6b>(#fana-CJ^dPrcF@hG@V7Y4t>Zn;dCFgqV~)Dq7~J=&L8Z)QTlvmLOxJT z6`HZ#|7H7Q)tU`YB4g6_MJ<9f_&E@A(*C>R-v_|by1+ym;vY2g^rnVe{>zr&0mBN` zRERA(1QyJkc|*EYELwuGwMU%}l^s3?H3bJu{(c;H4IOu6=wJqN)Rq3~w^b2}kz_GW z3NbRI^E;|pTEO#Q_pMvEYOEhATAXb>A&FVAhxNQ3_c7w(I!+=T@5xid^D+E6`|B5n z&XDL4W2Knv1>3j4yC4v3ufi!l&wFS|a6(Fc2I8&Unaec4LT9Yu*g&H0c|1Vn}q zHv8(da+lD2DF*zs3s`Nsu6l>y(A;uPD(Kw}@OLSKR@M<(Q_>FQ=u~Zu9{Kr!xX@pDYoYe(y$|fx)1tthpORmQO*>Tm)4_ z+tuSJyK1{P-ybUUD%>OR`Vy^?D2W;h`xQ|j`oj~pW1Zm2vT*)keTu;Lo)Ke|1;~SD(N@XQUWn$|twpDIAts zo}CN;zA!Y^2qjt#sTQ0w7M7GtGHp-6xr4*ZfEV)BMc9*Uq{Brh0t$O^e0i~x;?z-tr1f)1pSpt->KYj4v z3}P`laH{M!xQP&Za8lqxeQK*O;T~D1$a1a{Tk5+2-f$B4|E-%oBQ=l+wHy77UO*1w zVbHoY!=`N#_9?vzeK65}H`HY8n6mxL44*%s=ODW8m#aEh4zIQ$7(4&oBTzYutVV?* zn5+8p86a%twAcaLqR*bb^cvK+hn;~^eXslvz=rtvN5_t`%9GBQRI+&Xln1d4N0blD zqtTJi5Qc-g($w)smZ=K6;0~Fd|CBQD;~5Q^ba}pqYAbJW&}~#z0q^1t$7oHYaxpM{ zUK+7h0CCDJWC7e`PdPY<3oaestTZPf!DU*;FMci)@c}p)gAu~hjJ(|NZQWkgID%*#6H@(etf6X zhrL_iY?D19MFo+(SxOfs=&{Yb0X7l{!GfW`nrZCji3qF86FU zNd@0s{rXU0WGHj8s;y)5o z+PRmW%rGO7;wUaO8&qtn(B8CW8Cw{iK6|N@_)5c1Au%HK1fZt;Ey-UoP`c{9zSKZ<^{$D;{HF6rX9>T{ z2?P?UEeIY1*&PuD4s^Wirq~=I-9qT{*1gy&g7Dv+D8_#e0BfwD)*a#k1(T$g%%!_t znja*dI(++ARYz7@x36(06agN~teR34=ID~c8`tz(^`olvUJU^45%XD*Jq;t0g!v4h z+2!xn7rEI>qZB5WA|jaQqFb+s^e1LlLKp1RF~*e`yMfc#o{ftki;Q)a>HC!A5~{9P z=ae%BNUtY7D>}qqspA!v6*2Go#<;e;90n@xkedsdUg!|_;UQ$K9nxCT#9YxPN@H9z zV*xUQH4Vpj?KxLjiT=(wKqwm<)fzHvEUKF|2gSl;p6J$NZ>uy!!K(2;6{4fvG-I`8 z^y_%W9P?LkLyY^%eJg5!IL6#q7%~hjqey(?I7@BKJF3Vne95N;u#e_!whk5P&I~Iw z^j^vKerELU{Yx#z-id6#*#qR6h3Q%RveEKc?xRM-eE1B!!<(Kr8z z)gx@th3FoEqU$xgXOSqV(&jROWGl;cpi=beRkpqPZ!!vX)V)bdHMcwz<`bf*zZWwnaTw^%`z$QCVf$w>C;FW_Q=C zkRX;FIY}6Wq@oL3ntWA)X=$euhd{`6`7jf+(gY!QS!>epgt%ubZ z`}}52dro1kTpV-EeiV|?=D*8c8yBw%V4JYOoTDP%Sf>wb6qU2pZfuPp=cHE)C0CSA zcTGxC)1-I4F{p@_kYW%|$k4GZURK>S@NN&&_S=fZYKleJ(b*VrW)%T!|L6O@{5@=( z(hp>F!pnjNDe=-O_jiv)<-EFiWy5z`EQNYd2o8;M08&upak495E!B?cz*f=-VePWw zQLjLWT)us#@%2g!9gHR^M_{55E2EIfu5P-cn?;#ztskGCaXA0y{eGuBH!uM>dXxD`O140%R*k6<#!XR3{rTwE-|23S9j>*(M-z~Kw2>AXnc(y8#{RKyKT0-+pcIUy3;}Y8XO-d3J zD|A~q{D>zY@yq*+KZRjw&2HD#7D^&;4~Xh8?zfSVIT3_UIoktt0FVqnOtOP{OrLcPW|T`q3^Sml`CI*FYgfO{r{+Y^KdHE^?kf-l}bq&$`FMp zBvfXLWJ)C}GpndgA)zv_m0eOPV}^{GGE>H6SV}_56p;*>XUnw6V)1)ks(p5!wom8# zxz4qJ=Z|x$>uRr-cX;0Cxu5&FZ@5be%i=!GFh*3HWv;E8blp>g95&-Hh5&>|akQ!PfU+Iav zt$2FwA@jH0|F+$EkiK2xheGrxBiMh1-2Xgp=yyzTc$i|jOqNe8pa*bT^6CJ$THszZ z&xP^|gtC{5EEW!bF2@S0Yp593`jxuy+c#f2V!w7!5#1h$Zt|elBmlkB%m36t1x4-3*FL(7!l9DFo;l@s+-b`a`u zSepPlC{-xqs|?NeEj@!$a}7z6Tg&xf7|fv6jyTX~hk@eh4_)cpE4OpakVuM%*w-BY z`>{I+Cj^?)cYj)D79#Z9OKfK1%WJlkKb&#bBM{8^*Rsz7y!-c}H=2*2XKB+LW_K%# z03(Q+`uc;lJ9?sEcM>X^|3?@>6)z+LKfgDdp;d)xg?1%J6oa$XJn8eBfMW!2wJL}COWL=(v>{VT?!dpc+EhhtW|Ho+op4J)LT8*FIV;<;0 z;qu|Z5$mD(aYawTq8X|7HAeU?^Wp?jK~S@qcqitbMHqX{3d1utfg6RHk0Ei6uRQZV zPjAsK0Ak*$D*rs#2f};)1yY;sZ9!b$kJ#5Qbpiku2cAe1{PAU?y}`OG{k4jSruJbT z`1o%C*fo%RWw0MQH&-9B{%{0WhCrA-$jh$y)7lRU=d-gkWX{3a#Pj>h_w`H3@xUeX zzv)SlSPs+Ljrwu9?YCH8HUaOQ@CIt;&VTUqA`Bd$XY!LN5Fb?hkZSl(UM1l6ym6PE zjC?W$5QfIUz`#GbO?h@!xg*a9Up8TZYYv(W(Q58N9*;pDWv}i3h@fcL85ACVo;0b! z5uLM#q{-?n{a-T#>P_+7a`XAV)lV_J%k=p6u7cJ)7a~cSFTf0dK!}*twSO?k032|5 zVMlTrh^8QL`ybq+eP@bR=$@^hrj*# zu9vcA9X-~Q4f*-%`Gw5+uNrFf17dd;ndVv3K_t8x<o!)lm98gue?DMZSKT~#)w40;jhzvR<5TDC%TA}4CZS0SEv4IbR!gt+ zYDj;48!Ex18fd8>u{@Uqz=tWE&wF)k*6^tDe#)^5B$LUPCm38XV$QLbTk1*s zvo{u8%Ch{V1(T_)skU)p*Mc9kD(ebf&7b#-T#%@FvfDOnh}h*oYq$W2{GmCqOU-;B zA+okN!shM7y^`{&(|by*DUlHr7(#gf3Z8~2dGuO38p>J@beCIFEFO^b4$bF}v3VFiA1{mQt|B>CiFeXUOuQ8>Cia334JH^< zCF*4>A^|{?`V!FexlD!Pa>9vmQfwc^k_5de5Hh&%CL(M5#0}mNpV#AVyGx}9onmUg zJV?o}4-8EX?|LQUeFPXE+KzS{v$i%bzX_~-(=$OFp8m3!@k$s6#;dbh7&8W$2}jI7 zda+d3gSrU_dX|A0R#b^}f*6gMYka=-$vnQzw#Jt>KcVXgzWo*asxPMoh>sgYP945< zmU7^w8I<+0L;NA9mH-vdt0Kp@C6Mj~>zz7vajy)*G6^Mc$(iQ$x41nG?y>yi9>}}p zQ)lkhvI>YK@R(&JGpz!JFg-A?c9?WYZJ6pYP!s5Fsx7S^3`%tYcS)Q1ncfO`z13Vp)pFMuI(FJezTfxX$%HBuE zg2=7aJuidA?uawaF1#`sc=yNtnzX?N^XP-`2ko+MZ6GOnIV6B!vu)Le26;<1(&n~{ zjV7VLQ3>)qY7i|j>NjWt0E{m5M~*8@Tt8Cxf9R{au2C8 zKYq+gGc@+`%lYGrWVLlGEjtE)lxm+A0bGNqtZ|TErISdnJ$dxx7sJd+q8`Pn;Fd!r zUHG#qmI~&Jdym~WUbtm&cTMi_IB`AzN9UL-bRjwXu(>&lY<+HQr_c24jk%eGFPYsz zG@1EmYzL(qfLr99wpo%ED&0cEZ*{%VPPIn#whJvK-M)B(7?OuPBzz%xb#UXL*;;@^ zXJl$FQw!%fo&8rl)Ys+o(IgnDmjeMT#^duf${ZWi6SE3$=N>ykQ1Aj0j5O&IGzw48 zgy|8}6BT!miTTjUy|qiy^3i*x^tzBf3ypIOR2OK>Y}C?Pn$E-?izc6&GAeL%W9{uH z%p6$h-;`z85TkzfL&$5h8$*ZyckGb;oxYP-l|0$D8Dw%E#-xEB(Ojj<7^Nmooug)< zZ^M-l9&ENQn8B;9=FYj5T%T2o zY-B2mqstmz)si6&j5OzJVzE_r5$i$@tzU^Wb1%Iuntt_$_=usEqf3InGs*IlfN7@UUpSdcPs|I(OowtvTiYI-nk56*P@(X|#I3o!4-EwK z1R)6~qNWULNggtatvhN(Io=XV_lHg?wB17ENA2kO0#G*~AC>KkrF#WkHr$v6r;hhcXV7bx1NEfNok8JTXN>ABdQ(HPH>Ow>zl>=F07Je4)FrSQb?e{ zM%N&JpeAG;BT3QOgGHi})wO4R%rzPF!m=?@Gr&}JRIPT_kFMS0z`^S_letNbz!Cl> z^C82B*DRaNK>uN)XWjVpx4Ol3fC<%Vvh|>pGQlcreE69#sX~arc1gAhAh|gjQ)n1gGKl^;^nw%sA;wOu9#jWq%X9BF_Zn|vzv z+XUB%SSs@24M0h)+I^`3U@NR&-* z0OrEe-9a2HsS|bNB9g6vvvZTzm)Q6;`fgR-wTp;X08?-INECWloYUCALqYV`(e3C=?(E|*s2O5+S3a}M>KutaE#q$dk1S+ z&~Kb4_*{2ltBmDO(wqs5{V6ykgr2cZ!*?^bE;O#;ZNRqO#_s>f^c3)-beW#VHmJrPYha(%&BV~m3wv) zK!Av?za=jR*&iqxDS3oD!I?V;^qp~#7gGff&z7jto-=~bW}GHxUZq&Mu*ir7n>Ek> z#_{EP-v%YEWF2~z0gv%hjvb$Dh&-M*%aiT})N+poR!xeDybB}1Nc3rZYWH#PIgR%(ONoQWZ23Fdq6%Yd>h9{Pza*vE zSZs5>F1Av(&C5$1ni5i|pZT{Eq72n}Zs8Ek(xG5*04o~j@?;@ z7-FrzoDyf83DTpn2f0PJKR77rKH=G|z9WkQRgIURsJZJ^gqCX)mBKAr`jnK12h6q3+9=+C z;fuN0bggrm^f;Gs*h&Ly?4?6LsQPUFV`qg5bw17L49+fRy^-PdiQ8p56OrEX4y#l)@udTs!h*EU#>5{dKP4!(xDAa6>8lX z7vInVbE10aJ-xK9sABIv>yE<@Wt_4tfQVOJ!a2n_%bIYfLv!;vkY8vopUiI+s(yTo zbsGkk59shdX@_`~`;)H%*+I2?!zy&37!@H9Dv6$!6X1uV*7E$37eV%l`3+SNDkrVQL?Sj-`iY!TFC zGSacn`#_G!$SLJ*sKiOAA89OByMFB(o``?lPFrD%IYsa@i?Rpl(|inVUORDqga|FK z?0v*F9p*H96gFMnb0Tw4_w7Ca^ct3pIVm#}h*ksxUFX4xeT-flkWYp~pOZ5xeL=|v zXr=j@jY^K=%I`j1oGWaVChVNEbn!ZYHTF1FGk^|C#~VIs>2+{W1O|Q~?%-)YNbwE& znMOE`NGzU{6t@+K*#y<@dle3+-}YgsR&B0UBEvj(`9OUV2+5sj9+$3<;*p&&$aBwC zVKDWu*=?w_^M#ey3GgclU@ zKqHR6V!?UFMF#)=Vu%k&jUT?NrG5w$>-3d&em(|CiU~acLv0lJ+5WbL6nkCPCll#X zY&ZmVM)_(t8a+}$;gF@@L^*tho-Z7x4oW<9TTKlzUzxTJs=LT;F8R0<{;+NA9TQdw z^5sWn4H-dCVX8Rw=X{qX%rj4K0_3?$y=0W-9+^>r)Ssa7OoR|2t=CG=QWQ-{C)xue z{J?|{UnNs}6i?-CtL!f#Eb!(i=7pEs+wf1Udl85UAKvm3#B2j$=(Kz>4Km*W%l(wA zYL13M9i}xpN(6|ad-Xa*iKIALjyoL|^zes!Uw-!xil!gsUc4iX06zV1cLW6UI!nX3 zI8W?{5fu-nr*l<-Z4DD*DcRdVXhS*1jKmE~{q#IHRV(!uXAF}ypaw1K%L3wkbW}jf z2t-sZ&^<8x`ojEoEc<=2Rz7&F{1N#w^TPZ8t}}B?tc4q?zr!F?*=?ARx&-VeI`r2#%P z_FEt|*Lj7~1kCbj!i8Gy3vGo3U{;_5Gr8^mRV)9k8x1}XZ$4QOhW}Gves6ab^Iii! z5{WcMXD0qf_?G*VtNCtmem)Arf2J#~&gDW$J&y*Rws-zNY{6xiwN^{gN;x+_HzNXW zI_Ufy<8rY$+XI7*`LNMdYU$4=7zD?34f;>o_Q2uE{r6A)V;|WXD^w0!qr0wt)_D1Rq zN!$(iB9MKpB0>hje2=19D1Dp7*!lfb;na7p$#`sIg{BF?vpdFQa1v0_JMS5Ane_9ztHKXkADsAiURR(F zw2C}^4En&K66>gF_G2NC^{_Iztj1x59I5#uKo-IO{t>Q!KdT8_WV>^5%&6#016SxA zm_Los>KVV-Uz>ANq!e~n8ttya(?(l#Tr7qIFiw!yy!8kW=PLZzQDH_cy_R9vkxBF* ztoha5KXpS^#4}RvSP-K0TSWfWujA zyR%fmDTdDFx=b(izSHZUoGots1d>E-l2`cNG)dZx2!P$qW>1ZWV%h#U*HBRFMDYgt zs;q)N&=KF!19S7;TNz(^p6;Gjyg>aI65m%{b-~$0Fdh)OP#d$aAM6HR+7${2RS2iQ zZD?#{@QiFr;5{0|iC8*_nfe8osr#V|RwIK(?_o?w+g72Z4Q>-Pb*4`tGS^S}_izLx&oz;e8p($Wq zYd{A>D_By)VK}-Ck|-hNOgnTv3cvAU^HP5W4VQd`0l#|er;6cvkgNZJn#y8BJA0ar zKLo((kdqfq4Go@Nx1d$L=TrF3o{#zVbWH`{ID31-VRW8L*rUKsZDs;s#&Vb;N$P0p zbvz!-#VUCv9^B487CLN$aaz^&Fy0T71BY63;|aXJ92Tui?*^wyTdHXB0u)?Hmp}N5p;gJ7{(I?sq_^WBB~a+GF)>(c`;3 zEKl#DuI_<$%7?=q4w_b*E>USXbUwbO!QJz!nfnaKs{{0375-o}*-#$iB%TnUOD0S|)-uFRLcE$#&Yc z{$O(nxwuePLcuEd#b6gzu=snTRg+wN+C{=HO`4)h;92Ciw(B&F_siZ~Q2!5;(uM(y z;;RKsX~W&uuELj}c7p>@0TYK$L=23KOS#;LQ9Q31fG^G3%CO;9%qH8`8?Qo%wB6Gy zh_rLssXy)`aBfPmoWAX9hey~0FNjLPWu@u*j6n-uM^>e($9B_8s-(VYwnWlOSI$EPb&^SeMm zVKHoP2Tm*`2sNzAgD2e_!VExG6i9fCm-25gO09D31S_Ttu5Vll*DLVHoTCy-&EG5f<1Y1%ScgMq{5nq;JLaz&bxw*TQa0l z2MX}_+5;0-zEHzXp9~Wpgwb*XKsejW%R#g<&3^n<&QAK@HeKewoS0@>PpuB)cPzh{ zGRS>UB42z9jI4{TvY)3(Ju{5$Rwn^Zt4&Dd-EA{J2RgBt%{CQ+<3+#Gm6>?S{H|=u zO|=kFAVn9Dk-Qm$OMiNf3yk~@z1%=ewN_1~k?PRhSA1K~pJE8bBpbg535LXNH5$FW zdOLMeJ0Bdn?^(Q0^t5O4A7wk!X;f}{d$W(c+n(Mw^y%0oE!#4o$zZYORP?a2w4>W0&j;0Yqs0VjSv>*qbsM)v9rNo&?Il<*v~W5I$fykXMdO(O6l-^CpCeBGG`{mJG1D>KiP7qazn6{&;tU_s`<+eB+ z07!KJAU#bv=PjFkFW`>5(hBABUEjUjcrOFUyvV!a9zi59a9AF$dYbY72-Cv<65H5K&5l#Kf5c=_xGMz|W!Fl#m+uoz= z1`NgDD_w_7g}db1yD-_{;9%bcHfj4&zS86g{h(LYQ8b*FAIKH7RgFK`%(8Om<0E+aJ9Ko{G77Q+O7-UMpe@w`~3&f z<}3uE!XC=z?zv56hXJiSs5Q_#C8$JczQp+H$m)KR3bTjyX4ID-SRDE$=3+<18+OGP zxwqcYCx#|rJ;&k;R@|7(66zn;VmmsvjMZOEaHzN!fom&9npl!A=SiI@311 zT7T9q3^Z}^nw%#&D2k~2CLY3lelC%;*ZFt0@Y%qs=NgaqtE5#A^6J1>NSw9Xa26U6BZ=~y?V6;21? z=;}WO6G4(KUV`_#R~i@ChaOGc7DLzhRs%47NA#T)6C&K>IZ6yLy|bi&wCH@oq1*Cg zoq=A`2yeMQWe#b{A$~c$yaAI6eTIEfPOy&i=@onZteiVpQ7JeB66*fbY7Zt9IJZEb z zRXCRFGC^ud)|dwDkq?KCq!|^&K-#U${^k>B!Th7^Onz7RzJUFKwN3A^rt8u5#}|3U((=R>fx9~RdqQG>AX6DB}&`LjYtH@&%{zh`N()FoJ zNV^W0(B&XW{6|*~jYKCKv}8kDLrhQZ5tv;yg8AXkf4$_cTx(VDHz<~s7H3HFEW$cxgk~I5pUnFcpt+`(f z$jmE9z&xKbNMZ}V^%ASkyR4N!FDC<~giyxs?|k9KJU_3n)^ji8Aw^Ef#id&N;NLiG z@FhKTFjdcGbu>M*{<2ieSvVsi&NsiliZJRXREAJO(05M;OApNMyn3}8lSoh(fz43| zf`G430j=e85VyzSX*>m{N{)R8G8g(l0sQDV8SbcNtyd<=k}TB&-8@2v#U?n zwNYBy%Ar#k3wV3^LRxGrkHavC6ZTe{57LPv-!pd^ZTz#gag!Aega8Q)_4A$3P!C}u z+0Ir*;x6Ufwd8?tb3XH^^nNPwBL^eDIgv`aBD)BHlYO5pz`=Y2_oR8-O`0Hi@}|YC z;^K~KoVQU($zGtCbZwkuZ*eQ6j7e{-MfKSTNE{$j7tMIhyl=0ZUQE=bG!5cQ(-tZ_ zo6qp1NwUN=NS&B_*EV+_@g&BPwBUFdmluOlUaMQik^3unRNf`cbAAAET0i4w^DY>~ zZppc1cs5x=0|bb)9<>rpKPok3X~)qQjQ~0FR}OV1M~s!38Q(dI^dR|+s>BDfL|d9R zp1qsGc!;i+IrrOUA*tiG`Kg@l2PcpFfCAqed-(qpQYSPl@P zc0-OHpoNWLV|m>W=}_>n6a*#wX^RG{=fF+gw=f2JM!RHIE?PFF!5H;8i{o}=x^Z|x zFvH@bhy$p2#hO-ym)}1*X=?$9!Z`S>$T*~^y9}Hx=PdY80WY5*A_L&^7h(gAHW&EN z&@HwhTLUgYU^i4>Hn5w9THi8o8qQK}CRYR@itZ2T3X|bv;JvH2aYffxGOp=UE3J!q z6Q$^J(R$qhhYba48BB?pK@Yk)6L3CrNbVCV;6R24nWLEi1q8o3k;a?=SIx-UN#YV* zHCPuHx(f@{helvWg{=WsVL$n=lc5Wr?N3`<8c-uLRt+Wt+PMNtd9qjuI$i)x4 zw0RxsjIPU*n?lC#f&$9@>l^0WR+@_n@rbLC5hDYBoP6MQRqk}FQ#bUzWd$sTyK8#~t*=}+YWqYYWT}7V2cIDg z;uxgdxz5ApSU=RHLfWofSzBX>1ILYB?!kk15~H4xmJkuA;n67p8|b5al3_npP>>FY zpDc}rFlfr**V=+)M0qX-43OLi9+!;#ia1@2z&B^d^&%fC@E@?`4P>2*4M zzYvUCcH3dK;<7oazz`tHaE9V%{jrj?+7U z!b|rW%oq6*+jqr(L~W=Y6lx|mW%19{&m^-(j(c-d!idul)qbi>U15-@6N986MF;F> z$+?8kE#D1P=^x>??`nX2dl85{QE>gkO%%Rh3{QQ>EhVYD;&q%Z$t2rCY}&l!n_2#w zTVuRpaYmW)8P_nc`dSGoPR|hL zDhOpTII}gTYBpqZFEgaOb_2Z^4ziFY_FuG?c9$oMkDJ~7Lutj9Egs(s^F!~1HK2khz#SKXTjk#^t4<^0aBSkhseHhhkYt-=hF|#M26p(jKv;k z$cur;ZNX(nGb$qkdRD2Vg3@^!L9kO5?tuOCJO;!mQIY_tc{B-DrzMD_@pbbIv{ zU%8<__vqY5tR{=G)(tNF?ZVrn3CC$ahFDx`Ry-KTc%%bA63P9e(B{6nf6+a}3P1a) zc<=hv{S)(hU(A&7LEfOR1v#*t`0_b0hphDO$-Yix;9#>xZF?5;8SlcW$N4*{XwGq+ zV2Qy3MHOrnmC==xm~OW9yWyWFRgfd^D7di|H#?jTGL~J;Ay@Z(`Ie%yK(42TC2QI! z_wAG&F#IAArR!5EF{t#gk!2+;XvTi3KEuP4R$ss#S^;cq1;~U!FXw%bzViFoDsnoZ zgzh{?B!vbY^k1wWYB?#u^YEP;wT4_*w_(j`iJm`mg{?6;rtz&5Zm2L&A}|hCEJq!u zM_l^WFdVUq$)T+s+#o$U(SuwF<3JJU33b0|4YIufGRx)yQ3}LYzl9HlDQVy$qD*O= zhtcP~j?vzb11Zn?)Dt~Kb3G(aCJDsg%(e-#=o56Iuq~0_{G!Pm4ZtZ`v@invC`zeX!jP2 z=qt*O1rqM5AYtMZIHH2D5X|8go6t!=rz&!r0HYWRfi*DN96GlElEzp1c5yT%?MH4S zNTLV@^T@2{RfS-X!7GCuo((#3V-m@_RN?0*90-RYasG9P=saQ}LC)nCK7WYEt7$!) zMW>TS^ed^;>HEyQ3$JjqZz2HW%kM10csZ_7!A6h*gGp*Npl{2wDsIXy90ihYPpJ`= zk&P*YFLQv$pZANW#b&j-RnaPR#wv<%WbQ?QJy|_W^1#d|P5hNZZTgdhhGbnX6iqej z1Ybr&7HxBX1@fbSpsl8+Rt1lI17MJ)DQUe?i7lz7X6f*aq?tW3`rW<<0K6G7!k|<>-XBJr2EpHUkN9Z-Al@ zo-9NX^CwFp*Hh#mRJ-ONh*F)~6tRZN2MV-9!< zR5eFdX$!v2#+zwqyB977QJ~VV^SkB9TC@u6B4$tz|e$!TILHC4NY`Kvj4@j#05b)BCQ zTU*213dnnTZp7u6Yk|&qd@+Fn<+h61?l&_#PKYAVgb#rxjLSY41|SrO410L3F_YB_ z$}VSnHgZQ_-xgCv6A%c?6TJQuON7Gsw)br1rHwLipz?!P|^&j#^A1e69 zAKzV}^f3NWE8XK(H&ILKY7U{AsAsa7TV(;p0eM9$_vS9K*M=%bY3h{F)0%ZB>R=km zQGI?51&!aYf|WcJKG<95mH255taccdK0K_O(}li+_(tMGUc^nZgLZm}9`zbU@H%$&Y>Cx+bZ8+(RLXZd!A9GNI+E%GZQYB5fVTU7y_JWz&8E@H; zD|Owc2Mxa@t5th$JQ97h!Pk)Z^5H?Md#qx69lXMXO>XTM6ARpMeeRkdAsJCx5D`aiQ}w%dYj`Z=2q!Q(y?6Zqay3F|A_o*HNp8y)DT|h_ z2QEGUc=W_}=TUjPG52)<8=RsVm&k@7D2%m?|=QyRQt=5 zYiq`}Fmbq3EwY~h6`Z>}YC%>T(oM9(tR>kxrRqR8w|f=Dj|o6V2zv1_hg{{S}_R$Kt=vcz-^A1}NSlHeD(o33!6^+-UJg2OZQKUd8<)21cPmS~#U_W*e#;s!vppixUig+m`~CKb4@N1xlW=W99gYzyK#-rFjC zNKaoM*=N}@q1{76qCHzZ_0`n6dT3-YT?Hg(M80_BVnYoFMf6AImU*tJD zVJbvW{c!ac%XRobAd&EoQXFeUb!O(afkpi(J&jDkfVi|oO+h{B%Lt4sF78; zqz(4%m)i8S*Ipb#Fgoamc+=1dI*%Wl*4Fc^>1LMcSS!q?u<$rs+97?B-jSjo=s~a} zh3=m&WwX5}pqHrv^N_lhiT1KoG>17K-IzqEKZK16m~FKk!};Gj-G-buB^Mv%X~XT; zT$9&D2s?)-8P|03G2Z1p9?A!`UoScS@&&VY3sAZ$pKS-c(q1%JsSGdsIyzM!Dl=$#}-6HRqvBOhcWZ!)h1UJX0BLE;w05RoxR zh>UUi15sOePJcsE>hNxx)&oMR@_EdQTonF~+9erLxOt<>^wzvs@(ciR=Z2fIa=%RH zhWmXeLv;k8A*Mqife@xPWg!%VUFu+h6fq#A2X zP|A!rynuUe^nPbPuO>vefW@z0-|Ivh(F={Kya)(!N3@kr+W{4PGEY!Y@S%%qeHxZ< zEf7mUZxc(*wnr=05I?3JJ1#ArLE2o`W*H+FRnPSvpU)zVd z?oPYScfa>SJ01QBR{_D-K&k}8=xeHx_l_DCdyB`N0Xd30U_i4h~L&ip&F&@j~_pVwp#^apg3D`YM=z z-UFFec_weYo)}z`;Ctf+)E$iQlRy>6bG28%T`6PE=mGi6)!7WKwloe0Cf%NVik--Z zsu!6@gkQ-++?s7tkHQmR&L{<7C0P30^E|*AzDSzcUfjzG@8}3h<7)ji>cd!BSXyNO z$M54{)|G~_Iv-$C#3zSj`S(1lJ6r&QfHp=ucyxOe=&FSGV3}hX7iVMBmXx%<{gOGv z&n^Nl(-RAD>_6riYQr!!b$yxJ$EZxPQOaWkeEV~L@WnBW)D zwkrig``fG}<>I~a3B0vSl#EL1i}f^{ihFYpE}A>cY(Ly4HZk97bV=JZjE>@T7I4AZ z=H`3;?ZZ5S&aXyu%#LPB4fNjfh-%rKO84ibKm*xuHx_@HNKcE8AOvP4Pxv&DC7=q$ zW+Wdj@_@U51-o34s{?f}amq?APoB5vB@r9Eq&<=`<_gZ?r8czi05;s7^6R4;z0{hY z`#<+U;@ckF?Iym`WNQHftKfIkE)7R@+2tP9(d@&|&zdK_33M?yV%m$Xm7SDsWq;Q)1^SPXpFur4!$4V)_rm?1?AHmnGsJ1ucc^U zJ*Nv0M0fqEnJBV48DcP*k0Mg(T%#FBG28uxp(bhp1?@1O8qRk_l2Zta8B{aCR6 zMXN)Jf9_HOO;{i*e4Gqy%s2%PQ|rRe(t$)(1>hb_$MNr*CNSgZF`q~Vn%1JE*?-G} zdL5UWV7J`}N@*lK_CqcMiD}j!C3sxTx`+~HI@XnL9jOk?DVLRSc>!3h#bFJiscz3L zcuDvETJ-`SNV=tnUsVW%%+)~1ynzUr{C7X7L(2Sb@WRc|?6 z_%3+D>~Q@$sJm0nj74BGUz(1U6f4O^J~MAsIURO4>wiq*YIli zz=E?iSXW|$NBE03y;Ynp=c8-yMv)ei^2l6jH@85-{1_gA}54VD0 z_5c6!m%nLnJ9lh}@CJ-Y3rKx@R)sT<|7(_9mXx55e9dB?KGlF4e0cBt3DlWC65I(f zD+|yvZGN4(UgnfhUFWeU^e6a6g6;lKc{+R`5O=kq&WJL7GCl(j$;bH2C^HK8_c!hr zLkeOkK<>B;G#Ubt#+e7^6ym}7_J~7KmI6$T`gKeTGm8AqOjv0PYKFUcJ%*Vtx6KTH zO$MS0BF;Z#1y0KIUxRtj2eL9z7{A~O`nCb%7=Dg}ds6uH7E7c{x=W1XPa?-D!1RWE z_irntBaeXJ0Q9aLZsDqjqRIfCSZa^C(+0?sy_?veTa-u-`2tIUc(^`XPqu;fC=~4n zqZlj8tQy8EE-sR#DFPMEfQmH4{*+DQ4s4ps4#1`fJ)jHRQQ@ymFLgY~`J;Usb)FX-;71 z0!>%<7wg(`18eL!bnph|jO`D$rImV@j0^8mv8uAJA*(|9XKMg4cYoWofEDNTCJi-X| zOoyiUf5|x^;PEqM%Cf$%q^}N~Lc$wKUldk{G{}=972NN(>YjyeJ{t1%=0?ZeX3swG zRIRCU2RVMEjAZK=;IFRMW=B$M1$R26xUmQ0%IHp=IXVMqZ#gjdVnJf4?C>tR$j0y! zEemLDIR--4L69$kF}WN}?s5KdtFX@!0#p*rd>!zR#r%CCzO-`_(0@a;I-n+YfvxLW z_ZP5@oDI;H!vG9EgRHz8n|70;C-v_U8{U6n?0<-|pwoY5LE&hWPx{mU_PnK1uinVU zM^17i+k@!+InqFVY6smm3nOT&fkEJ1{zymWlzQ8l< zniSxV2q+{PS(h*(M+)6+3*BzsCmr5Jh#iFl<$XDH&U(uh-q+Z}0QxURpd9QyN3k3I z{Nf8$iu~cy?M@csH`oSZFajDe@{Z&BH#QWhac=UFqi?H9?*gvK-@Ns7&|qsH4~5-B zX70!o1QCzKX+5EPo67_swl|oApxM54`ckp7K{$^wilbxRP8q-X%}&{ny1bl?Sd21$ zKyY+74f)@gPyR*ayb%JZb>bJa0L^IY(pK7xhz5Dbf~1$o`vNE*$b$4dUlF7xpb3yE zVFo7N>0qY{fD>Nh_-y<{-E<3ZOYY83BL~<<@k0^M=5N0=m7Un;Fj=GQr?d%ZsivH> zo&M`em<_M^z})zOnaDdk7tE9bjN?LW?jq7ny8W0jNR%n>NL@1?((U;*El%q@7`Y#J=sI*ZcnaeR7?re#2g_Me8I^S82W^( z;_nFRD-I!$DnMUr$7eK4Tr3Lj2yPW%jDJhH^)CXUhdm8gyvybZb+W-rZrgO3LTAERr`gE?m&PCHp5KesKx(^>1`GV zBjUpg8gX9VD0O@0yQq*y4#q{7?4yJ_4W{Jy2HBrtLRq$e&J#J1*YTsRow$8c4zu7iHMHC0^*z;Fue6hO zUU>Dh`3!(g7Z2uDB<5fy)c%JosmJx>uUMzkoZEY%YdRzOGC-UaKZiIKpqKqjy4Tv< zD7vAk76=%7fj<*2J=5jaE+@VjLWHK=>;;g2;z3&L>#$O>xH^*HYvA>W@sEr42_=LU zL{0gP&TC8LB+C_{`=^ZVA7$O6W%@t--|1~ZFnOQ*a>H82-MS9!G1|qT4aMVzVc+~7 z`=KqvRNco+LK_}wpQ7Dyp*tm22sYhsx+rpOId|u)w@!`-2O8Mikp@fabWnqja(~c2 zGid7C8aoGFLs7fvs#B62LaFyxAi&P=xTI=NRYXLy;*C-#Dl~zBxCOba1@o4fkSM)u zIeT+1Jp>510RT;kr~)+U|5Ip^12MF_CDLw8IvSBFi8%ZdFuCq34R!!e0`--{u``XO zvb!=&s{(p@dS2Gwm3+fO;+i$`j5IRy3h>_}hgY3(IWdXq+GmyYaN`hX?DyX75hho(lNHvTj5~fz_P0qgW0${tAT znWmp}e2Un{fgfc*98aV-jc~a(Ud-wkw}bLYCxi!-LA@{_O2DY{%MVP!OPf{6H5!PR9xdDW0T2`TUETYzo|5k@e!%46~d6E_7xi5jkzs(q0 z71L@@QhDX@hwcea7!z1gKp$8VMC>*@J&MBOGu{x*&v_fY7Hsty6^<46Y< z{D;S<)qULi)FdWC+jOP{t#?%WTz8+&(EB|cuKBK?;wG}F>sw(9C*^eH{-bG_d`U>t zYMvi4F^NuwS;&N>QFL0UGjXYyXVNxZWnF9bqhyG-+T2AZdkrZ%``$Rk(IPL8Y~Ls3 z(?tx|L61q&JWD&{CcZ!5^cq%dhF%5pGQC-YwTPUIya>64F(5A494S^j#C+DfkYOH% zJ|buzkce%VZQ1ow^{=Paf7r3!oS2W%7ca8d-Yh0?hb*-V?ZM!~>D$j7wu=N zM37i^53~SHZFZU%2uULMZr8qBE~uf+wjop?G)&9Aq4ICWjJ!zk=1i$gA(cy@fYxvT-o3 z&Z}vPvn{Q+*YR!fLwlmoST*E)*zKwN0Y)5xreO{%9AW*X;i2?TkYl&juP#nzNg;8> zlD$rV4(H%G%UHa?@rNRc2s;68Nu@w9v^Q04Qn7O9veLk?nsQ2S$>9U_4ZgMy&@V!> zNAMDpAQOH3OgP910lg)Uy`SQ5l>D65_SKe2s{ueAc~|8?r0pgX4P~?i83yFSHdgm9 zBp3U~y5r8K(h2Sykh{c0=XqAU1iVp-ocPrgG3<{U26YJgfic+Wl=nK}Y2bXc@Zh5- z^Ji2J*wI&Wu|T6=JB|s^-4W_v+dp(nU9iKsDvfY zH7uk~l`{nEI>Bz3RbEBZ54XjdD5Vfbwm!=f`9U8Uksy>bTUzI&VngA(MZp>Ur zLsk4#R&4EbDf!0aF#dLSz}3*o)UBRp@j@?_)`dh-Hf78_o=8VA%A(+n=j~1<6b`4z z+IMa5k2i{sxKUSSseSSTUbL>0WwHrdtBX~)5+zwv@6NDD+XNLhwc81<8{`_? zk*v2p`oZ+n22SDLd@}#+sP^ra#Ehzi{ho?X#;3yLXDk=&jI)TY$|D{-yPDGj?|j?0 z)8w_i%{-T^NpG&mZus!k zSv=w89@!+%fw$4 zx?xv8=-Sku*5-+u1ah4bv|T@T%RQ5|IQOs3C09biOh{92}sIthi zNo6oD$n*=~x za7f5g5sNg~n6sPRcYNGgen6hm{CmmLWHmnULECT6N*~kc7hTb{9Y3NwGIjWagwRDw zestAfa>^H}nt3BPMy>k!V=W))YHY(kO*1XEVFzK{*TrhLq8?FvsKd8;Q&xtuPX`~f zsCA>=l4t-lqh_8)K}USm;+wJ{OFRg+8FqP0vPm9$PF$o8!r*Ztlf_Ghdd@Ulpu2!{bTs^c{S1mbU?dGN9=!; z?!PW)4=}(r+hy|*WFBb%=!EK90*u<71FvnA(7`0%jw~oXzx{JxIp6H-0l#e9_H*cU z6SSrFRsoiq(WCOie@Am=7odiPV#{$*j(kQYVHJDx1n!_2%s_Z@^X_8KJ%JCb>(Tii zA1ENlb=}4E=XBzw5)9z*%3vtszwy)X%YX>q0pq`32T7m`UTR|nOzv-oX?gYmPYF3*Z=T@t zlHLi>o9#cgJ1}sAh@7f#=`eFoVAQtlpW2=8q(fmuI<)y*wDKR@or`sRxqVR{aCd+$ zhXxf9j$Fa%qGIXk_SdU;U9J@7HX7}I&Jta!7esGNwkJyfZ1UIO76y~vIm8XiM>ZM9 zOymR%yR*njbdgSnCXFnsw$Zl<*Kdc`HI)YSWulfzvcL6Z{(5zO=?*)JIZ{r$P@L4) z^gEp6g>Lb+?0k_Qe;_TmyUCh6|1**GM|NMTF&#TZ_{b88?LU4G<;4ik_#gTnKqOyu z#Rg!d8??`_GCK94R+M1n*tf0tw!Y$eD6FRbhr(*0;kAdzmmUh|JphacB{eFnfg@^W z?dkr*5iP1&Jff?XDQW)?NAwxw3bBA=>gnlq-Qf+t{7WU>^mD(8X$b zkRB|-cwyS*IXGJAqQNNbr|uh}*IV7eM)&Q6eto!HqZi-0b^n>S?$N>{DL}x_b-uno z4kG5ccV(`igovrv{)d1_!zPFlBJKZBLUd;fFU&85?nF|Y%trPvP7g(*UTmg#sls1Z zSMIYJ%0lvBPVFax9RKGm1auvAk4yG*>jKJ>4=VgWL^9AaoXn{0j0T`)d-1LwHX8ea z9viu;-JISJS48YSsK)}PY0vNe+E;rNL}g^|P$zje7i%JJp4MPMo6EJDT5`*0(UNSG z$cDoI!i)_*T7ob*ail3r4TRUdRh?m)n9=1u6vPf0*|nH;aYrBST+h7s0pM?@0TZ$= zWNrySg2hVXy{{$zEv+v(Gi^~x9bi&F!kCdmH{R$MMkV5PnoI4E~m(ghytn- zjvM_fU!GW|n`F{Ala-zQ25vsGZZ5|Ix?1Jr#4NU=A(uTF# z$tmW2$;tI3jgb><#oo841J86Om^hXn}r^ulV`X zz4u-mS!mKaHd~ZfTmENrXJw`3}_2($K62h9i?9MXxmO&M$gi%j7Zo=Q- z#x+HRSqxMzvI^lpM{E_8`a@Zlb2n891H4N+06IlxsnkMdG95q?>nj@;W~#WMhxD>Xq7fX~(xWpPA63)%TTFm1uD-hW>g6kt|CW>DFp@8z z4(-^~2j@(LFBzj5jXD0lxjA%yB=J*D+T)e4M+=h{kqt5~h(rkUn7`2u^yRv`2XijI z-E<(?(p%>NmcDK4{(V?uSKEEl11cQFcH8RmhlpG{XG@$^XJm?;q9`nDFDO#x3i45^ zR%OGlFw&B2F2G{SRQd>K6jJayiPPH-l|ZxzvG@yW!PGu-yj$}DNhqlAsfqZl`KOBp zD`*%L;!jm_g2d`19h>89hEBGo#IG86*z!W~h(3euKaX{R5$Izq!$@5XvFO<2TaE~6 zC0uTjQ3XEv{tKEm4SD|`dv5|(%Ok@I?wZ(C9?gCtn(Dzp&;)s0xwhN+YDCY<7}aH7Z!3Q9st@m4VN7X?MAwFZsNx}T zytpq=-6?3;A(H{VUvJr~pLKyKfX{kWWW?H90r&$^)CJIWE&l~LJ({d@P4f9NLrYd;*{FWa7Fe1y(w$_}I!stn zySy}2gO#&=^qQe+BtIYvJx1t+a8F53(^SNgW!Tlcv~=D-1*|N9x}~!u6k2p&bEW*{ zXFv(P2cp1kT$^`on$=mppvpCXW)D)n+@F2b zvYM&4&79!*WOil3joOY)gxLx-74amM$J0N7Jya0b_^xc~>eSs(V{&+ZxUb4tK98a9 zd(4z!m{)%@JCow6Vq;@-mbYj`^O+DDMe`;AfLGCgvMFgoXo5-#%z#h)u!esrqy(WG zpo22@9QkVz`^Rh?J5f0M$K%1)R0hT)!BpsD;Xan4Ck!D}F@vueOcDUtpzINf8~@-j zBIN`9#FjS=ohUGaxWM%Wb=S=4uC2mV!8*ei8t2!q+p zzFu~`>m#y{is6)j`yxBeL<)#0n}EnIoVn=&`^*$UnA)%^^3?#B0#TRlKkVc37)T)4 zW$*Z%1pBkTaseiiSpN+ZX+;|O4Uzx>YbVAdcqv6lYR(sN_#Z9n|LeZ|bD)$x0;hu% z5JudSbBy^*1|2BLLzu~ej@hlxUr=C#!8|l4k4$-C)`C`KA>umM0DtGs9g{FINj(7` z7SAQrKK_V-;hs04fwG__Uv3|CT{H6#b3vg}8fE}2jw8?RM)gs~;(wQms~}ULI!B~i zD=035B}`QSn%7Dd7PEr@U=$XejUUi7VBUpQxw)M!v~0msF#9iwm%GqAQXXW?dqC+D z{rK^obo-|8V7-zacjQOGg|*eEy~mrAOeu~bkG;a7(>VZq|C=^;(5-vOL8sx9o{Gp@ zAeTrfxc1(L8BfJP)baW)?dp9fdr)dSf#25O(4?YZ;0z{{FEHF|O5M~#0N8Sw%*&q! zbaCte7QzEj4ZgrXQyM=3HA|~kZ5T1MU?})sl5L+H{tnAefPx(dSxA4G0(DcKr6$P4 zEN*_bbVi1(eMakds@(LBa*cS;d7oY0WlBL^dwZYMGWmTlyk|Yy&Qm)HO+nBT936!0 zbOKMCF`g2ToOjqD4hh(PNW+yt=~rbbhKZ0KV#`FKDHsKdCuRo=i4FSEn)#pGUS=b4 zP8rB%k`SU?=Xomeo(Rkp?OZw!EAww&I{SxaXs3`q!QL^QGPqah%rFLpT!)$hHJ3aGxf>378IzS%`Lz zOm!qwRxM|9!r>7;%aosv8&IhvB3{Eus2H9!E}g~w?HKqwm2Kx4?((wXtA1mJnnLtc zpP`GvnEbBlF)H&Td8I7ZNglawUNICY8cZHgOqmBjhJvx#V(yP_;zhbbbgV86AUV?T zoA!=wG=vU_1!fMzpFmwj?s&T+C$?6o;|J@~{sK zXUHjl8%OO-cr7msFh7aPKiYt5Dn$MfV2g$2D}Z@2kRzP_vSg8sybO9QvDp*G(iAbl zxEAikLFGp;mvZvw>D&e-@Eh=}SsX2``MwkP(4*8!0u2l}-v0I;MExvA#C%Km#+h?Q zpv4}_%#Kj?kgHl>u#6&QueF3{oygOdcsMY`Oi73F((zb(8*h8Kx>24;JPi$SzY)tTtrs4&s~Y6l(aANvcHR+VHQhP#IX zi4=_mDNz1(c)u=Dhyy`$f8>oN;$v}LPEDEqMrUrmPdYYC zZP)h-RG}SEBemh#o%ow>v0(joRan~P?^}8sZ!`(4p}0R?Z4&9Dqzhj$m?|{2gMyP~ zeKfG~@1b8Di;kY-w?_{}P6`dO7(y7?@&L@h^F9VHDw)oL5F+=26Hc(7Jy@ajwWU>F z{@x%_mY3i;d_egAbV;ODh6T zxCrA%pcLF!kO6(w5rXnVaU_s}+A>S-O1vIw4@`bw)<`9>G zKH^pt2^H>+7s_)Sy0XltAEXZ%bU;CfhvDb{-CXgqIXdJ^p*QryLk@?gVKS`w0fCCT zN6knz?IqWNYss1W3ZLAIamQKy3+TaPRfw}qDO9vv@FJEpnm?*%jRbo#L4jhVF z!K?D@f8eH+3_Wwc-mS%dPYy7^P}cvSxGB-#MrfZ0=8uBIijhIm;kKWRlrO~ze@}yc zHk|)BQX;x~tp+~etJCa%;3Fak@1CN&!(1ww_6CyM|HvH)rVd_TE{JJ1dqdw7X|(N* z;ngF-h-hb+1=m=z${2;n#c=JQAY8%!30=A>?w};8^8#Snd;>&}znhWeLjs|A`a1MI zx=PEreUE;GS9^=bMZ{*%n3|nrZYltAycc4;!P=>mo&$ZzSvWV;Wr@)D#tmvmz}pTD zGFaJ&2D$@V;#Y>rzhI$GfQ1G@CN{k=?k(t=**tP5isu_WKl1>_8Ox`J4pS;6-_Suk zBBypS%|f4^wI(TV9Pj(~zfNR&J0qiU zG|sqAbftUNe9J-^hYxcW_)i)lIJJUh5YLC~q5Ao600j0lL-H@5!?P-cDN0XMm)c0= z!3^KyP_{r@sF+A9F%bX6O$Yy^Mh7fsni!#fk76kFS!@2bzu@H>t8RhDp@C;EALrv*GW zI1BklMu6KwUQwuEGfv!tc10m#<8fI%;Ix9x09({l=_km+Qa~T5JHYEnI3SS+q+3+0 z{Z|tHo+;W2J=@B0?j5cuy%0+-M8XJ1byZw$Ge5P%uPz zw0LZgL6D%-5}vF(zC#JAqS0jUn(&YnMnFv@Ng=-o-2}CBD+rPRzq~Qx2NjN1f7XUI8odNk zgZYuzZ|o?!HVAg7PPq-k(C~*iljD7WQmFT*ER9OBdv9>R1&!fD)<~_|k6LrQv{TA_ zMZ+u(=5E|8#hs<`6=xiW8;$JDX93o?TJvsT&Id8DmW^I3UwVOHqgP3MAPLUN^@FJ5 zXKI=H_`A3QuVXsv_$fPF21#0{7##93Lh03QvR&PcwOB7aWhvCt8iHT344AYfBp zTVl;K5v=I|>Za8`Xy|MT2tAvp1-0=12?=(JZ74eH7P@2%k6Sk59e*I!;&=mpAp5P` z$#5t)iX2^b$ntecp`FE0+aD4I#}hz`Td=tlUjHGH=Q5=H{LkkJL5BWu?ijcS1&bHA zK1w@?vA4F~i|xKXF6c)GDwebbl2Vk{vg*fEM(8bgL7|FY_#-}n(4sBJFLz+DgMDCk zUj#NIKZvy1cf;jQy%S#ywptG4R^a{_2>7d=^V*QagZI5=!s9ow;iTf%8h`E5II$0Sw_ zk?jogb0VC&-fQL3OYM;#@D_jR65&`O@qG==IqB@uWY26E;`6ZP)}Jo;aVm?VrM2zk z^!R=QHpIKtW#Rj}9xvPXnxuVidZHC(Z1W;(K>d{qV%u=+=V^L`VT z`15BPAfFVEj1_n%uP!<&XFM+1#=+-b+59DBoo z7c_~vaqBm6VeSk1zzg2_UwJ_}a;O9lON<=K0x)bh2g7}$AE$59hzQ$&=NjJyn)~Sb zPXbrZDCR2+b7#M-f8#~ANYltA6D+;$%^4PC!lCAoTP)QiRF+p7&~7DH@t*-1XzR3< zUzYG)37}E83fRn6 zHM`BeFmSfDd_GWJRW2JARMz2!`%L$-)7H)yK1+v=}PF$?qk1t6$^&slaIq%R=`kOzeygh9xM`2 zIZr@n20McJ7CgMUe5d$MmB@m`pYZc|A6zzjSc);H=g#CE1Zx;=mSXAbXl%IJhU?@_ z8e;0ATKnOmId)8F?5YKHXN?bF#l;B8cf^8q@uGLdJ3Iv{ECt?{aN+CL1LC_R@@z92 zR%bMNBq$<2A&j?P<}gxQle-!XEw0CLSpAT*UblTv83`ULE_OdX~jx;m`&YV#ZjM_W7%r@zo6`_%MRS6Z{-cz$nT1it(FXB~q6c3Z6Sq^=*o;K;vZp_s znV%2SuG?T_$sOp$A7=M7u{RKPmxV&#@Zw&>lae-8P@?2lWWOTbINJH5%w@q8bsqakQsWA zIfqdbHkFxy8_npa=->{cK|HWHYXq0@_}zSbnnWuCC0Jb!+j6M;BWk8Dbv^_3ccs(t z*HvynwR5UO6oP-4=1=!gCJg?CpY~dOV&_u^uXaW`7mNwi+YLlQJ zWFi5rjQuTgW)RIi-)uYkb+(Qqe8;1yFmd3Iw(vjpro28)77IipXaKrGhA{7AGfmW4 z^(Sg?MJ|qZz3usz{tB$tQN8bfFgyp@=lj0YHr_+S@J|}775e$W2A$VIM{WxaI#R>OlAhqrmUXQ~Rm3E!nD64gBcIKUkpFmzTc6ezZ7|%HVW2xZe&taZmh zLL!EICQpoY>kl1Ucx%R?dHaIO79_mj?IiCc?Ziijg)!*x zfhynzV|gnVS3a$wf5FPKJ&OGF@$IV>NiCK(>x|)t(Gs!B+Y=r$nTwY8?J9VHRZe$o zHRIbmM;C+JT+&JIn}^4WW)w>q>$~QHSSB2~Ly(m7?#nrzlsRY{P%dbMPm=ea1ew|% zk?p5DjLM7$`TADPi4v<%C#)&X4E5z}zM8W-W&9yMpjmEGP^PcvKS@rE{=P&yHbs3s zIZTkJRieGkq#!gj;rYA-_LB;JU1`A!hQl6#ja_z%vU+d!N~kE}4d$-VI`VJ{PfUeP zvxZ!m|0Md=D4Mu8p5qeUX}&02glFp1sqv}|Gi;wbzAKcz{(}TNzHr^iM_5tE&cy!3 z4)s?TBs^E~dgNHJZsQztiV642X%A)Ik5gs5xh}D>(fb6xrK5@@=F#y042NREhoa+a zUTg0bQ6AnecCF3hOOtiD*ygRIfV;QIpE|TV$x$NyX}_@)Pm%|%;~-h=u0OOpau?4a zO*l0fD~g*M7g3nhUu;kvMkYmYn4oso!#b8tR4}DkDmyIUiZ$OE7Ylk3^|7$D znThFOFBnME!fQP{KfIWp*uPXjoOOD-l)+h_k-g;j>>#ysBSs#SVl!FZ9oc>LnyaMz zC-vnV-V?da2Y$}oz4$8`*F>x(mwwYl03Z~Zi^&Xjxk^$}$bsj$2{+&czoJ6VcsCN2Da&~R0wUXAC% zYdKjp_#QL78tFEJ-k~Ouq>Bmo=pHWU4Deu>NCN-uHIZ2MvG>)a7811JpX=ALx8L3F z+FReK`L1T`vn(DTZHYX;1yb=3#AJE-_~(eLoSWqHSbEcb|4Dl05AX5!dv=15`w@(i z(>HW*lz{)2hj$hKDZWLXcRU;THw~$`hqKnhc%+EbmZw5@O}KAezh?Ex;d=fjV5Zy& zJ7_^mgWAF(|4IAqtlt9@n~t_c&T+c}mzjhr`eE=pPes6en=02+MVba1Ogj6IUlSJ* zpae(6B14KE-br3%Y2MA3H52S$JECCu)6w$RrdNo2*KMg?CF(zE$|~cyu{TiJ%)5l= zzSc8U#z{ht8u~4)<&i>1y4~OLZ*s}LNqsC7+1hQU#9o|Lf@7NOf+7bBK!`eyhbMp|z4m?Yf7N|QUu``5z9 zJveHxB--9wTm71bgo^5$h3mMlC$4)9e$z=k+rV5S`)ncj!YVlK7Zlybd#xe4)zg}9 z4fiJriF-`l#=Gm$Hs1V4iRb>!Al#Ra8;_Vtui5U%OnIbXpw1wf*25C?0 zg1mGFX*W})T_84I!oW2nt3|ME88`L|C$n2XkyhqnNJ_o?mGQz;>X z=_2R>2Yli2o|081@;>zJ&5cz%$Nfo5cph3p`f(5`nC0uSmi1;xbRQ!#{?KZvxRt`ej;t3;u4-2d((BtWAQP*ZM@q;tiO%L;vDcM zx@%EUAZ#8A14a(dqGlHGL9_T4GHMfbZ@n=90B2$Eas58tFtu|aRgzBv9)@lG^Uce^ zLEcSx65n3o9i4Ge2R35KH5ZwWw!`2wmi9MJu|XKXSV;OM?{ay#1Oc~X@9xK zW&VpRN&@ZK|`CBz~5=rt;=DPd~R2OaPek8H3&%d2Igf47(oRxy!jCem+&+j z7~FxI+{~`+$mP7Kz}f^>mF=iZVG_ctGf6?|^Mz35vD znMlNjPV(7=^rUSXP3hNMuBiX`{^#(wCLBdthMte9lF$k$({Ga+vbRGf^3=j zjs}Sk?)pz3I5^OmRBA0F3Ps%}8-L&NJv3dts6f z3JXj*$n!CnDpHGqt+7>LuI=KUxdCeD&fnZ{a4e0FTmap; z>{FF2L7%nj14AaEn2BU>107KTF);GTVTStFr-G)CMeF^$OnM*C-0lbt((c~UkAip* zV0V0q4@xQnLXQs8Mkt0q6Yg}xIU5y$Ze3|)85RVhRr6VXm7d$!9y3IqXdP$?gk z2V~6yI$ZG&$fw)YjwJHZnXL)BWU>i+#Z^U(Y-k&!Gv`03o+ZY^tGDY21WO9o0_*|r zX_ML~M|XO_$kl|Vj7+(_(gl>RQ24aYX^9)OU~i^fyBa)xJXFy^TmQ{L!@)soaD0eu z#96w;V^$2(9*3(2MC5&dppjh%#PNs?KXurq^k=*V%kkK(-+Do$8~>tFQJ0A9IWKk6 z^k34>(0~|Kfrg1%f7mQYf-NZrM8yQ$yp9`MYkd@VgpiDsE$DI?FqAnB9M!DjTmZ?f z7M6W3B)(~IO8+?~9KL(nJ3jy3naNHGCM0^~+JiZn63lbG)M0+}7}T{}@j~KuCr-G- zTeY>BIl3AW=bwfqK9J;f=Z_Xk!*xA@E z=v!HLL3@~begZtjMZs`hHUFpX*Znt|^w6XhD_G^~AXm>p*V|tC{WlDsev4<+ zxg|S1eMsvey5E%*EGOIF6{BttY$ewLwZhZIdGt!X1W~MLA-!+5Xr#SG8DW@$&GHPR zG0nD_m#z@3BHMoiRh!3PXh?@Df@WJ z>20pJcZ5n&_pKhbwRUbllkn~`5pRf*GBq63~! z8dHz7R-56QZ(c~MBH=n?u%Z}@MAE?0Ym4K#0A5vCi&-M05T-hY&xBJJ1klPl{Av9L z`opUmJ(SHiJT}BBlBHT&SBrUG!xnkiR$K8M0yj%^*hvnJ@sgLNeHO7krT6UKU)H9$ za*lbc%#CrlNahd%$wCu8WLn1yiIXLoJm_r)hc36}(3YR`%FhW+xO>ZSf$K3DnZ$l- z;fsu5HfQkR2*nq#M{#!ja<1hQN4dIr(ORA6%MqVq;6tANGMe9~Og39`RPU_jBXTBL zo#~!u?PWk8F8V}1Vkgj1kTi=#tLG0S?vNL(7-ra$AG0rh&J;RwJOQat^NtSoonY<_>~ zy54+1F;AYjdukvy{r3qD$)9j7;E^ZrBz*wfa=qMZVSeghMy5QuDDw^AQNbIvp!0BI!H$;% zCvy>aS6J32NVYwbhwXkYa^P&msRCGudFSOu6(9vZ}DDZab}AzEZ=#hese#jM%O6Jw3J4rDcOi2@ zvax{9z09^rL-Hj1GuQAKbclX~fF$%rup9qX`ZkUL!fT&n&_~M9AIzA3!mJ9Nw(e@L z?j=0d=Z&<-|Dn6QTvQKaLSIq6KOY#7G^zlgk`WP}8OCr8H_#W1zpZWz${5{c|ENm- z?^jOnVK0dADAVqdqM6~OBv;<46i>@8$$4Kl;}{$omq+3-NwJVBJ%Tdu5#aZ`sRpgk zn%Es<`c4&gl=$rv;|t=mb|o;aPp1e}$adNO0V|K~zD=R99!!%TrsZIhq6s2~vkRzb ztnqB1Rcm(N5<*=B-3-a`O+3Dgi`Jpdw&Eu@TizMSVfq|VTK$iS2r>+#+}yYEaWkvi z5)%RpAKhQ@6gkZc@EUlJ>V$Z=Srx;|J+L(Pr>Bjj_+NMOruzWkmj7mqD&Ml}n(b`sn;ZRYG%F#FrFAYXa0 z&ywf}0cX!~eEI7hcmSuhS@O4kRS$d@Jm4l5{!uZVhpPUK+1)AY8j%tjm14i*DL$#4 zBYF2aTEPh7U-9d~D?S*_f>_sxCV5j}?#bHKLvQ%2#97DV>TZoyBwr7(zyj!UV4x}f zFK~|W3kc5qksWZTM>63){AcJ16@tmnoBh@`N_%~tX$7>~U-2zKyb@x@>NGU$!}eV@ z*FSCSQ&*#3$QiI51h(b^h= zK5Uzm`5qk%%W3md9ks}*6v>?p;eXi^aS**nuD}V+NJ&wIBiHY+@z^+q!-8w7wEe>$ z7|u6$-zx+RjVF{+vnnz+M42|1^XuxST--Z$FU*$!FXbF3P<$BnHM-QU{0QL+-Xz?9`mz*WnWM)IerIIZW)R!71nr zN(+$uCrzF_8Rn}>6Gw7toXfnnbPIW6pZF<2HJl_*{T#!vdAOrBCz!fh33H6RPib9y z>maIetM{4LRg-+fub2^gT{_8vN&~v!S*54rdB8hH%rkfN^xF1T$Ij>Tqznj5g<>1e zZZCJ+06BL8dcd}4ri64Z3V~HGSmkN^wZ20rgFhCOa3nEBw@qz=X&z@o5Qt*YvpLHS zpX6{IpWU042IF?pz}iwyY}G14nR;WRXcR_TUh2?a$VRAo&2V%E|I1kOk&EVW*bjz8 zMs>W8*Lqn?*_b;}8Jguh&+2S|!IkYw&xWg>UYK{NO>U72m)XS_HjC>sKZ zFpk+*H??<$N|0gitvAiuX4{Yzr2mP3n9<$tdn7<*#S(@9pjzQGErWxao;8rp)eMa| z{!w;YKY^<49qnBg*%uOfI$23Ziu#xkn>@UJk-IbAypCX2T>{7yVWM}#lK_`d9Lx4t zwwr9hwTo~s5^rhkJQ;PSK>L4iCx+X8;ie^e=10y*FZ^NIA;+f5IezaQq-8c7xoQY?skNdE;&I*!s7P}5szIqNN0lKu zd9?5Qs4p%Kb<4Sd)K&iji2&;KC15`#=js15r4)!%Vl9a4ijKN>=6mX$eLM~)p0Mj0@vP$6P|0|vXnmQHI>}F|5 zl|kvM1NQl6e!=eKHb7ypLXUn9lGs!NvDfd4_ZD6m4b0-sp_P9Y#VEJlIR)S*o!`~Y zJr4?MgETxi*imR4Eb9>lk^J_;Kgo66YlwS`EYe1up^ZQ4*!n~TD9bmTc{NKvXSl)D z{4n$*e#N(dK52|=E-g$y2ki1y4ih|_f5lTEt^ntY7<=aeDgv|f@>G7sQ+zn;`v@Ge z9{agcDjuQE#jiLcK$fn^ZesPWYiuhCj)kmf{=CuSeAa=`XYASY6$KpIqnBo!;=3Hd z|3e_~{{{Tp&+8tjEX&6nDa2@lFN)NE9%D+ zR@4GeV7K=J!9vbP;g4?1Sgv>j93j5Wftl)wB&9OE&SsG(qiM9=@!_LzgR4pdcTi6f@73kEr5BstUyTk#MkB_ z5@@7jRH5 zJKn057=m`JaHma6lE|*`RYRB8u$*QgI3gnX?I4XQ_gPOzDG1rt!ay%~4U8t+eR zPuj+|%$JeLa3@&4dXP{D@)dmPJ}PP5#^P~Uq*DyK_-@?$%>6_{XBjvVm(vho>f^LS zpb<_~K9y3~;hR`v0EL{4&HHF@+8$U>PVzWEGWT-1pk1BW{5F%aoxFX!&E^>)=>;GX z(hJ;1>zcxmKRsy81s|a?(q|)8rNR;x8ILJiw!fb`%-n$lqp>qLK95|-#+wtBm4N(H zO#;m-7xz7Oe2butgpLipfJ{hs zZ1?&o;b4u+x}^UWI_2$EM%9;U^2?gY8>b4D5JC&N+8hKljMgKdA*jDL8Ov^V?{F?t z7^KxF1QJIwgGsbLuS=mei(x2(~l2EWR{gDNDufcNhPgNIr5ONKiG?W z-;}Mn5=VDsFI_)etjHRulvX5pvhJNAvwGdk@GC@{(Js)c1d<9g!YV&{pQyCVFmHOb zThVCu?bT$N^2~n4fCz1ac}D@(FhuSCwxFbV1yTftL&xT3>8+H>b>H;xcDx{O@;I6i zpP6AOHmO*By_h>(P+WP;xA>V;^6IiqTYFFA!517D)^sy>m_RK+$GTt0qJ;Y3PpM5; z$#4~YGngmf6PNIax_$B)fCVZ%pXxWsXRTDAue)^aNb@$!vQQKk3|{TZw0dXbsrV?d z)41)tp|T^L5O_?60Fn!rp{@j#IH{P!HO5Xzq9iI-8tXpO%WY1r9T(~Zui|bOb6l59uYWfE%c$>FaSat zGsfgMvxu0S)$bK%IfxD)lQ|1tRQm7`!$b=h5xHw#KzK3s=J^7SISJBJ$|73G(ywht zgLw-h^bO|TW$=bEM)s>O)32sFklvP<4W)Fxbj-9=uG#L%y5He_jNn+64t7Kd5jCDu zM?#N2%&8qZd@S95;MQ`GMmZZiSyzJSE%w}7ll}T0lJ$_gF4_+sT+p$N7e=W*T*5dz zCfPyJ-#5>=iSfQOKA#?Pn+nh6!dD%;zZIAj3pXHgX?$|)d;1LL$VS3I#qF6FfT&Ru zn9w{_XEEr;Kj*HS5Atd!3_Zgqg>&4WeDqhr1NSqe-pc_T*$k+dezK=&hQV{hlLoV+cr|uFse@D1Q2O**97K>jOo2;3~Zd!y#T4 zt1kaC7g&z!=g05GciP5O5#E6q&(H?D z2ZB69)4MBcwkmPzB8K1i>9V}yav1dEVY^0Ai&Etc>iu>n{Ihy!KW~kxtEoIpzpg}s z;0MB}Ua@f>LT0B&Ory{&N}8f0@B&`I4BVz=0htG5m$+c1In4f|fS7x|OI)VTf%014 z8@Q&o_hqEQU=X{0@BSc||%Zhixyy~Lv$BPGPUMCn#`7c219xiC<7q49fToni9 zYEqr^``tTHvc=i}_ckd2cslX66E_T2eQB2^W-d8Z2lE%RMtifbq6BLc@;>v6><#wr z`xyPf#O}RST4DmDLLFOuy!07f#!rv!j!@bn7&{9&W+&z*9t9-bs`S2$6^tad<+pix z42_A7m#V~!e7aDrLXc|JUX&y@mi%1;A<|{B2~*W#pu^j5B(W4VFaR5DgMA%;=c#j- z!OnrwWiu6oI;4E+_uaAyAt}-{5n-#Ah{KsHDGQ$L1PZAu=>daYg=txV(iNY_%h6kd zc<`U!`V62FF(!PCIqr^(_ZhkRD5tA~Ipp-S8%&-*$zlu$;znM@7eNGpL3EHy=er#PqNq>P{s! zFCWV#JrMqP9r$B^CsZy*O`o<*bJ%PxStHF?6QpxYGwe*EKVa^-#$|;{B$dnMhuxOb z89x9-qVDWMGLM!ioRo6MSgdl^jRoA3c4P%gX#FNkCT$kRWq#!XaFb`<+j-3eS1Y+O z$he9#XwG@Y-SX%uGDL_->i`kKu=c5idgb~dxM~Hb^!s|#hhL%-qU_})T5)gz(2Hr+ z?`gPpspqW;71_(yoq=)PkLm+y5Wx*64<_%W-X6=euLwhKE?YfO$7?Jn&Q;xbJBJ@3~nrfm@8^xuF;L znDE8FzN`q~f=(!O8D1pN$`r=7`dP@KW1_ChuOsyN+iOP9-&)>Z{S*kn-s`^j8Ro1A z^Xh+N1(UQdxs7g9*Xujl7IRZ7`T0Y}`AbY(a=NnDLI_7Auq5=7so`Gzdq^)HyM0hP ziGE{;C-i;$=1)W{)x89K7)STs8ZfJpKog!oVat>wAf6YB#Hfjd8dYgH4py9R^)A2= zUdMspHpPz{A+M>!-$;)AXGD7U^c?me9`BcjLL~!ydknsAZ=@**HgVX)C^pQk*mec# zxDGv^N*#<6e?)wQ!$?`fWJ2mCFr%FA)7MM?|jE(gwi1P9ANwX-N z{qrv=8M4_z&Ew09X_fHH8kSxTgI{dyLnC2`9;Pq}cxP?4D@-NV7Cdc@I-LEGfBekL z_B!MDq14X<*0!Q2qsi=#*R>>Znc!K_h5BPvA)qOmx_mrA>CL8Y=f1ABpcH5JTmMNg ze@x5clg~6nqKi4q@2}hl&Mc*<%`lZBqMxxCMef@x;S7h{PE>1u4PZMoBE%|D2NZ7k zATWQw1r<&8*LMc&Pc{sOsZ%5|^ed{2+|r6Fk0YJrL3n2~Qi=80RyBkL-U#g0e`-0v z0>h=OWf|sdpg$>h@Vzm2D}ODEU#~k7h)s0pmAwh2pNC~sCI1t!Vs!#kqdGgadi+9; z1E!AJDvzT+|6Hw-vCE<(WbMu5`->#tXS>et-W5rm(l5?}!sjliZ|nnesi`tDqLEN9 zC_av;p{3mC?$4?PP}g5YUATWx>h9+SbK(>7-$=s5k%EWE?Bx$#7|^;}7cj}^ z>5N6uVhN$6{_v$E8$W_`*f-w=gsGYnbuPY#8S+N>1S$eZB!VD33f^@cs72h3w7BR) zCos4R3m{bdlZ0Z851j86pkfj4X(D2P>=W@F?y)EV9Oa)DXEtfT2kZ=+si08n?s+=Nh z5(uX?b3mHYFU`dQ0DWAT0b$Ex!6prif!wgj9?1yKw#j&&n4dEIM3|g%{U{7eCZiZ@&^k<6zk( z*q&wvTolzO3o*xzP1G2>4YzrtNjU64OIt}^zSoklyS=cz-f{4$2zn2G>e#d{XVeP> z+RHY1Im)|zIkLY`c5$LAWA(G1-RIx}fjy&6^7fqvTaIdSiZ70QLIxfAIdM{O<~PRt z^S%91+}rUz+|oz9fJRwJCO7)RE~`;k0O$J8%>jGv*blEKw5TZjuWSEGaob(cbo>dd zY*o524{wVQtgNWg@G@<*vX1}zD?4-HdJRL9v%442gu#I_4XIF??YE$FYh8DBl20E$ z?3#e^(b+%+j%>{Q-#@phBxMCt=W2cZw+Jh!1Pa4dKjIsN7CyF>hK(Zu8%NQjS0NOI zMKYk3O412jJ*A2%Y{#>ke-P7Q4N}wR!5YkiHBiP3D<1^ttno1fmv8n6R#aH;pLuf+ z`JhG#PR?a?u4@MqtPMT&nW=FjAp-Bky>HbH!QN3sdnbyV`)WFDJy)PoSN$1KA$1Z4 znabbELf=E1o0NGj47AW3sXKxE-4!+iqRXG>3-;dTA7ZUs&W7M8uhC9J;(eH4e&s)F zdF342qivEiWBlk{<{S@{l>TQOU!*gIxq$}@n5FjEtw5Jf`p;TkB#T4bfP}lm!6bVm zun}H>yMJHM?vKbRFUF2#r@5|U2 z6pL*q*P*Un8Vu+f5#)R;)DKZ59F5hss?&P`=L&PettrCDhVIY+w5oAF3lGN$S`r;u26n^}b zp^gSkm>ou_bFP^gYf? zc=~-WxId3K6yr_noZh@oTn+Qw)^q=DM>)ai`NHm6$H%R92nRnQ0uM4VOyJO=wPoi4 zQsx#7j4{Qepy<9eUlF}1LnHORD&tUZ;tJjS@X*9&KdA~Z0j{Zh@lYObXi@5;)a*b= ztKgqQ+G+OjpoEIFW8;+%qJ8zL-_q{t&LlfXsIZ$m6g9-?b#lpDolb}-ON035JGxlt zV$Xb?En|4Q)t9EJ8z0WuYV(R3u=MecWAu}t{? zQc?Hys$hN*uXbEy#Q!hz)eOk=1LPrqs#K`TRZu zHC8Lfx0__cq4} zm2iyk<*4zIwzPCzvNE$6n-r0~g5|cg3%+>a%_#^#6zBP$PmDlqaoBaOdqDc$9)*5=XO#}0B@e_;>dwz#N z1vuw6tTo?I=AY*_1ynO%3rt8fdGCwx^p9RttapXF%s;q^HSX*X%nt%e(A(&nFYRI3 z4Yxp>2=yEZIE%K&yN*E4n>p_f?}b<{iZE`WM0z#)x!rHzt6N2@Dr26G;^ri1mGm@Z zXK+L#)wi_)MAG$0^QX!U=pso}WH$~buWMKQa0id=d@lky2I1_W-gE>IX8~l^xt=~_ zNPU^}!7Kn(B-uRlD|%)qMV)W`vnjMi1Em^|b!NQtRX*tbqH(lwIQJ=g(XhyFadXpt zG-*kmnnSC=fP;3lv^Qm+DRsGYsn}z91^~~?5uz23SE=?36cw|uPiHU0{(&|;VVvtr#%~>3c zLAZI4p_!3Pc5Bme`pH0SPJa)92suP1%(D0w^}7RX&5$?GR6Q;X%yX}Rbsv6&<4`%? z#fGjp@F}POZce-y1~6gN2I?f@T11*OaD#@pAdqNnx?wEKPVMx1q1qyt{76J?Dy5oa ze4iu=zsj(a^4q1;63Q=OZCAfQheHF|=IeNDgnqR0?pFzI4tQ z$TSisCOcp1poK%yF4fdHYQq;7Z2a%Q0D$ju?wN>0%W7cuOK!kea%ea<$qF!ZiiOzd zA;wS!QK?m(h%{hgBYD#*5TOw{{znJkyxc~wcqkIsa?oGg;MGB*Zr8wL8@-fkpG3h$ zz8;0Te~ZDK<)s^E2FSJF?G(ubs9S8IFiwvL0E)e}%8&~h9*KrQ0VX#^w)O|(m%2cR zI&Cqwrnp=FlTaau>zBmc?AI4Vg9Bq=`?(jt0Pj18wX}06kR9=ZBIdH>giy`5OMSM& z!IUN;M%O^rhl~;;vt;L`4h7GgPJR4dF$e<{0G9=0Im0+il2Pi(73mSTBaQ~4CL(4&!LuvGoU8V) zl?_HyOiXcUs*JwkjA6FccHSJa5_JzcefNRe%|$aun;<`QB$utdm>_gy@1v3nh&AG~ zb`8P^w@p}23PF=&bt*Q^RMqrtOjw9$#)790z%+Xwd)8y+FT6o(3PfZ|ay>7db! z^hE{eOSM`XUcHJqo4#F_1!B`m$pp4 zD{;UQH)P2rIZ!!ls$OzmYhf7i-6%9vwK+rf9G4;sZ;D_pB_JC)f~s12+nPr;^+M#o+DC9tJ$UXX%#h z;!Y7KFx<2I6&9BR;G$>v6ZLpAU%ziD!oz{6qUqY??RvIPcEJ->Moe_iP5^_ZOcktv z&NtC|sA!hdE7ObEFJ|K>9eNn=GCMWwUV@dQO?7CM)tUQyv%o;}K)RvQa`PQ16_cdFk~^n-)#-2kTW7yeTIo)w_sub ze|psQ*&B#Y`m?$?Fx@}{H{y#sbkAjK7fr>B?1Id4c2YmKxMIn!@zU!@E?`D34BW5D ziOEta0AI;21(zC@4wH@J_GNp%II|aGQW9WkaL_`C-0Bvc{k0tRwsU}5^UH*X7Ha=%O z24y`6=AXZrB??7mLbCh~&Q=G&PRa3V%Vc?_p@TKqab6V+5Q%S(_G-InRxfY3j9%uN zdy7j%uptiFAd{mgGoNVTfD?)sJ&8Q1lE>^{u5AQ|Nl0F2{NSjs608VV9cr`g0=_$Z z+7oN{2fWk#qPkLPihehNJPq`0* zs2C0%!?7IP;lP9tAaZ8|$C&+_4`-0bHe`T#c~j8PeVgRRQ(Is_*#TC!NdO&IXD|)O zL<1p2dWdwrtodg)kc3?sFNJdhmEr1-bNz)QIS6cfYKR2~Zp5Wt8dY zVqEVd79ier`_Dl1JA6z=6rpQY0ggBoptu-pZnj@{1aQbbb-sW@&VbyvUgIV{GB89B zOpOdb!Kg1QAZ=9#?edV(h#+;Ev#QPYOU-e8!npl1s%@ONrG_{*85a(FBE0WX`3IH^ z?>04C33Qm(9E40(v2Q|LS^{us&E$Qe(VX%C>_O9yUeD{K%<08WU@?;m16?!aJ#zOl zsjNoovi=hV^!N^Xd^ZZqL`DMfaP>(46SrIk7H-s@({u3wwahHcr>ji=BTbxM*Ep0e zJhg8cCdO;Z5HnTQzOlX%`h>UMUg&`WcBjS)!w@l&xHr4P$7G*8aNyz}44W8tR)uI| zSOdcBi~tzrw3fUaUpl!z%-C$y6*uf^g^a8&h%t|hxgl|oo~Sx_NxehKhMmoedzv8B z)s*fFEBx?wYmR9)e7&n1v(_wwfjiZUuV96|v*+*HdIS2?gWFK?`fvLvJA9a0@8N3H z0{^muS*)SDtKVmhP_NObm+A+ESld~By%cuO!cz~0J|W71^Av_xb)dGzA+q1{CiYN< zU}mQ}=Bf=}2f5qrG-_YHn~FNC>#Zj+)6%^THPP10jc^wU9wJMH3A%O(7`rBGMEIs) z1|A4<`ID?+4!cP(b07QsXRjc7HysWGrtJm8Yj6O%>#0kaSV|I&w%xA&(5yx>3jy*w zFXhu%@-~Qh2rJQ$?HX%N4>FfK-oXjR(Ss{db!08>y%LWK6HP;apr2gmlJ-~PBo0Hy zu(rm(e?d2G1NH2yS+Y4_cJqcwuP)lj`na`8x$lZjG%#!|^Ci`=O!qk)n1GO^Xg(Nk zsE+|!Jck`PdTq!a1_}Jv1O6OZ2 zHV1Avy89~^;G<CGhuX;Gmy^Ki{7>S#YVtv)fnr>FB~Qo~0J{I)%BFX2dR1SH6iLsew@E?m;=+a#i-jYcHNfGgtA_aU}Egfy6kvEVf0q0x=#S zWHsfUS?;G8jV)dq8%^~hE1&@3t9ac+f&lH*1cssLIWfgK7`L-wxUTI^7!$Kj#n&gp zKlju^IFA5moC2v(a=#}4SP2msQU(6%QCPD86V^{O^5#8f_Lo#5MSnP$QVpQW?=RIx zm?|Tinya7{p{#_QDXXbhyt;;Z7~^TkaF&p`tP-o2%C5|YeiXcCHKUQ{Gx7Lh5L=V2MvGX3vI zblUrEJ7@3xzW?|Aea$>g{{SaxY0*J{e>M_K+$2E^(who)6 zq^u>}y>W(tZm&G2a+P{)x{AZB-)(N7awB1x?^UYhH5~K7H@MF?^d&;p`eME9o8Q*< zsV{V@KjUAwh{}S!$zQDqWn|+8bJ5Z+TWmhgcE(KfK+xV(9GJfob0x2DaV}=@ltE+% zl9kkCz#WvVen;ZnxR-mC%80fozdiH!6r+YA-YDM<`$;dstu=X0O;HHKTHRj^YnMy1 zJ_G~l2rNSW5YrAg-N79clZBkFzaJ0x`rNH|_@7^wOcxb?V)i~{;qE)h8nc2vKt6W! z@__**d$1Y3zb#;i8Q!$SFi>43rC8So2G!zBEDNJIPbE9LBDFco?B`-bt&ENhEE z38i&*-y?j?LaqBTTE;a_{1kS1vr6}aXQx+4;;8yq5>0NkRr?&sdhTE*n~bzPsNWE4c` zzK|4G6XE0TPzP^zCV}ERI6!2s4*cI=y)nD82`1|x7dS*S%tvLf=`XdFD`hWnh82s` z#W1(ablpAmjJG@mklbBvGhaX5nO&;%7w1PF%M#;cG3N?q?NeL~mJ%!>m^6dr2ldGY z5r`?hR5Q}5iJki(=f<2{`EHU>Is)*%D$?%QlZ;nZ>M#=5rg^i zrB$m%)+kGIB;sbn1ohQcq;Ac!LH5xPyDT&&#tky8; z@e|mddIH&RfC{EC_M#-|E^=zbk~-teiVPfELKYTA7IC^V8eVw&iIY77A`_de8~EOB zu5o0C$(`EC5k86#P+t+9f9lgh1M~hWygqI;_3LpNU(R!%S=*Rdea%tZ-@j5TFT8WH z>sp^V7mgGr*MrJ!5w5SkJ_evNRN=3IHvv>NJ$@gfBt^S;Q+oJwE7G&2=%Z5#qEqIg zZJEY#(!aSKh?P&wi&3AQW-PdAzMUFo6mUb z7aJCdMu}g?fF+H6=w$+|ZHyY!(4z9Q-3o-#iN!J5h2s96i*c^+$K9MC$Qq5w7-_i0f4M1x ze`r@O+z=0JPyRgEZn787B>N(6cG9}JwCeVldG$rSx_M)&$tNtA#T}W&=h@EQGVc#O zxz0~v#}r@bTUWX3UN*`H3;$ZuJ~#9si#6ODO;xLbDDHF6j2$KIJYT@x)SH?ftn$-} z8B8Msmnd+6!kyNB0uUJuacGVKs5V`i|5?NSJHW!ZrACxP(%yjqdO*ACVkD}a<1cT8 zUjfCXYNHj`c0i0O;0gX?c1C0Y6o@rY-WU{Nzg*5p01w3Nrd3A@fEaM%^?Fh=S~luk z@s%!JY(&>CU&2HWQ+y1?+`WZOu&K5t{zn{~E~F3&wgiQc*z^S7y1rR)N#-wSJ$nJ* z$g-tHl&WL%c2R%rF#PZk=vV+2;63Da-LWa00uW8w(kVdc*vb1h)i_Q`5;}uxkuntS zb153CHNuM|N|tVm=qp{@RX4F389d{80_NAdV2msGOH^Q* zgY!novT*DT5{~_3jT!@#(U6Hem+2~-M^8WaL#iTacOnZBs$5oS&=HMo zK6xxq+G4)o-1emwC(@3oLc~;sVI+ON(>Vlz@)g5(NP+0B!<%DBJnvCJ?Te_}NMVP3 zt*~RzD{m5+Tlnx&eNqe>ct|#Z(veA*s>>HZ(lGk}TigGcD9{3A?f=#GUy^*y?30px z1lq3z0B!{VBIiP+^943rDl&3i)Dg9{E{9Roi9`dKPK24y{!(a}BYnQuXi15*)b_VL z`a@KCr0v;2ePNYjK%3jEO-7iGeNwps4EmoyPW~|os-^_i- zw*XaGiSDI`g9&B9{mtN(s`XvkwcT6`Ca#r5X_6nK{osX1?6Pb?z%dd!r(yojbMY5S z`pKbMP#Zdb;Ek{#?=`8Ar1`=T?ea7I!-S~ZJKQjqdtoU^9=B|5IkWcsDAg{jo;+1?meQORU=d5Qb- zli7P&Rjx2<`sRagsXYD1 zE+;W?(ZDs`%ipXh`!0G(z4Yo05-*JyE|xbwvMnmj8fWmRB*gs?k6Xa15fKXY+eHAY>2vK$<&Z%XX~C<635?#-iW*!`<$Q9|^uAGsMyEVjZ1}g}(myW~^Y2C=Ic#Wl`sT06CIzm^>&!E} zcc6Jt`*rVvPIL0@+2+ELlOx=W@rd&0d6Hbh3y-=6rP{u>9MCp`iApdi6=B8@P~$wh z6+PzM*r=wvZm2GMVV*tzFI$=^w~U<2VBwm2;ppUo|EI#}!?Kr=j75EZr_YK;x(XSM zPxr)qH>Q!H8o3$4TQhxlyVN?ed33Z9N{n#VSB@jC3oaha)pyYi77Ektf4XG;4d?G< z`wb>5WyEXH&2hM#4Ux@PsMo#jbYU`~`+-A%KR61Ek2 zG;$=KnQ-uP0!01s!~WuAFgcn-jsq)jd(cGAW6nAIliY$-)Q&j#|H0UJWnQ_3W@NC*=%=PUfa|5`a# zKGN}?;cu!Oc`nAcVX$ivMU}FVABPJAHLH8HmGB)|^`0WL?*ngZHr|oV@C}sB(7P@Y zq)4n{*ENx$BRfKO>5!!I7G3!A^B!mOFz}Oyxy&5jXj$Ev zjXs76Ebs0@PT2q0T-YksA8DxNU{nNb6`KqEYvA42CaoLq`FS^w_c#c^pTsJ~8f6yU zBZ(hx%6r`Ut^D-Lo<8QusdDebZ)+(#o6;@EfyN?mY)wP(qrlem1G7pbp0VU+@%+bv z=1-IJkSk|whc7?v@e>qhcf?T_SQUMkfx}z8!}g-z^6s|Ta7WgW#hS6Ng~^tjoSH|` zLy>rXXJeTMoG80Q&pBrae#P%w_KudvT$X{~Tvp58SAjw`H@8>sop?yi8hiGj=JM?5 zTPNG0uNVRoExB#o2a+;6VdkiYL}sLrKc3INQ4~VO9tahI;e#q`(P!N9zw;T-f&eiU z6v!8bt@Gz!>u1~TIkr9&tz!b;tRjgg`&wAXlfl@hOA&|ke<$Jq$e|5Z<$)jPTO8X$ zqNAgEcIm6ZZVb&HWP;sD2fI;Obt(bEOT6BC_%d-`==+v4hn0Qdt3h!#sne=Ik4~8-*_&CB>C+Rs0)}4;1bsI z^HYbr-&Mf${qkgI>QEAb?erM>%g6TSm1FzzHZn&#)_YWGc#6J~?kh4yq>4AnZ67x`|mQ4-8g7?)9vxz~Xbk|Uh zMa^coSsdjN`fy?YgQt#D3b=<9Hzm#agl;BtOUoZmtxj$TH|=0sehd>&ralS8ivV&% z=dNvp{=}3{0Gx!zFmxHI`I^9oJ7}slPPbz|`e6}QuGKc3%qtIj4JN5}N$d{gGw9fP zA&?bPCpZ{#9`YoTdsltpmw|?+Nupu(5o+MYd14ET%<)I8}0X!n77QQ5*G zGfVO5;jWelNM$G)2(}TlagZdzoBjaI@#bWu)zU=XQDBgj!FDkLcimKAVVmvJSIzbF z$4h9denfNRoQXrwxErt_4(=c&m!dHg#ELfVprt&40Cn*r%NLyU}rcFIR(n5TrQ;e{#$$? z7q!yfy;@ec%?V6}!3Jm;@Ehl?0x9R$mZEK~645t#^A3m7?cJg$+pm+5*=z){hN2;+ zj}tm7)}4jkv{D-+D@@w$>Y**~IIJHggUufN{PJ)`r1&?ylgyBQ%#}2!v5wB1`!dzB zDJcQARgX!=4VTVz?pAcB`F?$-A<4GQ5a74u$g9w`y@>f{p4XSOaIvkeZDhMw9*2kA zp0()QR4WqS-K64fSd(WpCjUSg&h$IWAX)ya2`~A-Kln3Bh-E3%tED=+o|6L&zO5yi zF~4PldC=0kh7c-Yr26rAq?iWidpQ8tI9q=YSx)@$&ZV#Y zx|~3{yOptFw;~2>eemK(>T**%JGXjG{kdQSb{D`o||)gWS4%Pc@9>FS;?vy1CYfwKg{Hfv(eL6Q8Hu4@CtK zt7(OWHiQk*dcpEXPW`X}N>A##>tr zvmA!P%if9FwP9}i?~>Gdq!tzaaUL9aj&-Mq3Q9N*?^MNa_TREz3B9RX3J@P%;`jWr z%0oF=%lq6x*t{;6A2l$Yv^+cyAZ%dW$w(<@L4veVj9QW{I>ZZE9oxPU!>mhWAZicRwjBCloC_Y!e`AKqbK6C@C zB{IXE8kzd+TSG2l=GF7wy-vOfunwpCQ!epd3zHW{*YW$TKr5ilOUqqwyevqC-E5eL(In2!2Cu{9IeWNG z*HoSn-hdqzNVe}@sxeN;pgLXP;V-L?F;smp*|IS9@sfq-S21;}g$Z(+zuqNkrGM4f z!mZXZNAa^H+2qzLu8Y`$Yuz7(tsSQZ8#`qW;|Pvk}^;0SA@2_VG7gHQc_||l6QA`hJA`Z6Z>D^|Q?%&r<%dK|&e6p-! zrmptRxGBstzk-dtIUd;E13!Pe;5T3ajufd7+pD{i7YQ+o0>(vVChr-9PUN4G1$^M> zI}1}&Q}g_h{@I;#0dBGlzj?gz_t&L=z#r<^*h4?1d1ITFgC`Tm8R^hx6PjdfmJ8!n|bqaN`UK3jBPA&H)ccR4Nb8@BDOw_(ixX zEqO5T-OnFv_rNnLEnSKimJNI$);xaoAk(ckbh1yRUdyPp{<~BD2lb2Ja+2s=Al^SkKS2F3uJCtvTHez&MMb$ z)A~dXBUfq8z`%FGPGC2mx|(59=4)@Fksat%3x)i35=JU)SDyH%_KTPnBhE8%iw5p9 z)u977*4#d)r&su{yRa#*@#*+AzlWRgAsPw>D$f*d8h>uE>ecd+HNN52{W-+S5C6tu zl-A;gi>^P_#EZfk&N_GJ&g9%{q_*|lDv-eo&lM5DXUXQ#DyGZSH?c6JKQNm-BD$$T z-eYQNDn78a%fHf~M_gEK=Q}rrH>DTh@w9Tbgopv_-hl$xT zTWH2Pl)#N-cj1I{&%Jy1M(`Vs9nOFLn1jLXRcpG2(ayNnPb_);$G|v*AJ|Pv5VwNv zH&A#FIQ4!NR~(v%6(mF3U@GwW@4lJWf100e<3|%2QYQekMS1k`^~Y>C)o!sq$aBrO z*AY1^ajEA?+V|fTZF_1xJ#9!a)-GwEofdfiOP*^QW3qQchV!N!Y~3`&O`P3RpU+?4 zmLHg4w8qu#bNP$6rF>^u`Y;COYz2^GCnP5F623%A^^Cr(miK@;ucZ*lUkL6y*I*gi zCb;Pky-=aO)Q6Z*Ugk)aLa)k+e#?SM;XvCvOaD30a^}EXZz@`p5y1TnaYE)yYaT`x>Bn7Q$pwRrN z{P#;8?h6WaH1)EC#fb+E;E(N=|}|Ha;n7zjF}Na+e*15!{??p0GzGYgBLo)~wTutgYTx_8&EUDdjo_r(CvIo-&;TmgSC z6W}lHgHrf~%df$Q?`gBRKi&%4DEY@9+zz+f_5>zllo|bbHU!>o+$lJsh2SDEV#p_M; z{2*x}B#Vi3{&)t5#ws+j z{Be!@5Hb`|t!({^nnny#u^eAXK=dy)9{l4EYQf9V+QZm4bn+`I!gKF$k>vP&qWWYl z;=z=Hdv53Fm&U2!qV#0HPqY*u_r9sJzh4e`GnDXVMB@Tme+5Ru_3gOB5#CH=s_7qp z5P<R9sey9C%b{4XuXSs2ohdZ{tBu$|wX;ESK0RvOaiMDGP)*8lQeRMC53`k#3(XTgUw6-35` z?Lb|Kh?I2Xvj|{E2Ny7D%0HYx&r9gww!i}aqIvU=4=!Yk0aBn8^?m~)685O5C=C}n zakNG1E*SmsO<$meEi(K+v_~15jBk4Po&Y=w}LqZqb*I16%!h zU6!l)AG?dyAO2;|cKD-d#$g^$wLey~`!Ji_kvA8gEx&l`yaHc-98WNpYS8W5TL=K= z#!d5VguYDd?nbIVM(0Kp*1!Dv&UHdz-CG*&T>VDgKmH)N3B-I!U+u>2U5juPa3c)0 zv$rp~$>K(zr=&q5RI`J##O-%?96Z|xK7dbJZvVOqhPuG2gU|*0R{9-g`st^Ym#{y` zg#Wxn%n!Z*8^a_WlkrnirADB?>Xr5(``(Z9`Vp4D2UIx+RBSr@8pSb$i_Gf0I!7Lp z_S8yqcjc_ffulx`!~WGkDa=a$?MVKbg|AfZw_4+PNWQmzSN@ijPjg`@s4KyW{358s z{V~in1wq}$B;}7k7*7M2O9T6A8QG5e08H=Gd%e#FO#Hm?lamV8C&^KloF|p)k5}gS zQWo^<#@`saYiV8JuFXu<{^JkU00$+*a znS3DjM@qQ-fOphURA>1$hO7;@ZNz7|ZQqCFE#vwt3(0y1I2~CAzN_IJhG#))H69!@ zx7%h0glU{gw|9EC##4~A0YW>E@WCtOihlGo6&D06t__4!46uId@HR`+sR-7oysp#1 zRK2I{G);S2OXfQ0>PcE_bdWQ}Xj=iW1^hL@@Ry?5VvtG>Q|1R!A^K%i^|GmZvxaVp5}j1x(* zL!5GHatytj=Burk8KJ;rrU zG>+;g8|CvQyUBIaPo(jFj`q?3|q7X_l)Wef<=8 z+EkuJu@D8}T`XD*)esVKQ%U~F3AX(m$RbktoRUj~^P5%6Q*%qR~rcZl#(dB@_5z7Fs?sR`K z*+E5}a|*l83<($5XS~*kw%h>G{CAkh;%wwx*1S}rNKhN?&~2Shl|FL>$D@}|94EYa zm^k1-kjEJ{R=&BDbUu-vAvyX&uLT8XH*~Rj#M@Ms>d0(EZTQERaMm-H&N`n`J`ArP z!MM0Y&3hyix$1r>6R_YHY|sjk_mFm(+O59ZUi0*kbBaSc+KOkFz>^^R-+$|>KbG&6 z4^>IYA>90wUL%r8uh~kaC)KY>@nEbTzzh^zO>5pQXp_s?ExPb}10DJ4e61EAdyw zE0QI<^}G-hI`1c<)CQ8On&#$6q0Ok)^e;@dw$d57pW|bBYoco6Fy#e1)m}%^%Wvy! z4@XcMwC;|j8F23vn7nu>ytjcckggHYmu_Zz<#67JK*PvGiF`<$S+llSd^6iOw*MXD zH)+-r{G@r&eUryzzZF9X2uCBc3!_!&GBzLnWSuU>1JTWO1Lx}VqxRopn=_2PPC_)$ zVCpkyooTj@KJ~3gU|-_Yd-|VWwmsj+cg&9e!u znYZ-hbK7r;yE9w5RR!_a>4$fpFj&0teB`=u9qvY*q$rIowq&UP=&RQkM^8l!>AaVx8Z@^`4p%alaa>vWdydgHa;1aMf*ujeyTllRVV$%7r= z`P30G~XKVrE*n zliRTPx%=S!H6G9^r_}IUGz-SGo8Bruu1F(XDp5+c7i5*HKAKy0N#NhrMq+VX{eCmB!{w3k@&rqWzMCj_!Us)?S?fM+S3Zbm6>Sz7fR8b()bFUUXR{z}xY zPrE&R-NS`crY(^v7#e?vR>`qQNNK8NeR@8IaY#!`kAqk6`I8=UVQ`P@EPF-zX@46SEA|e3$j>7>6CsljOk>k zA?7G3yYo2*JhVTPHKZ7+R}flTTRSBSfUxy0`bueIpK1cW1P`M{)EN7*Ia%amsti|d za8SSS7-=}T;~{i#l8^m5rQOczZsb~ne^RxpgO=M^Q zY|VjO+a9$M#+#Ovw`sO{mbTRE>FPqoX`mJ*!AV>kW2CMcCG~SHMUdiL8~#3Rs(-g#`+NU=uj^~7gi(1 z;Sz(V+;K8jTpQzMXnr1qboWpBb#ih?UOfewPV}*T3()>9gATS$$(|GSio~&R#oYe* zrUOsa;~snSnLcRTNm{uUf3pK7gaATpdR4VbQgC(-(fm8X!Z;8Vr-eP{b(47mr?fx` z&EO0Pyh-PWKznJC^@%YaZmk2g^^>xb=J;l_j;X2XHurop&pOXF>w|7!jG~XJyAC+= z+3Y5Fr5T;XbeD!gX20*(S+m|!$Nz4-1kCF|-zW&=%}!9?y-N)aTqu zNh(Y3niri_lkitI#10Bhv?0Er4RI+_Q1bc;7r+X4Spn-UeO{(M_{w}*acCe#Av;8j z@<1+kDjqDu6Q#*xxNAJ@V-i7cCc7Z z-SQYAd)Qf7!eXN5J%@`fFV9GN!v9j~V=-oHvisDG;8sr^@)_5B@fuhF-k8--2=vbP z=g)QV(^6iRYsO(E`NY?jeg@Xe)2ysB&_M{5GM@xrIdRjHZVFcF-wGg2+6{GxYV^q= z7mj%lg?54w>OEizQp=yp5SLnebGpgE%7mn;XKgr7Vf#p77Z$U^#s^L z5fh#>jK7sqle2Fd9l~@A9)}0FU-iKmzCXC>)Gav*GB)(!T}uyMS$Q*Qa_2)_;r2ak z{YNtw8aqmP$j{TYPheU5;n7VIa`b1Ykw?Ka85pgG`vG5Jxg8*mp1nyKS-9=45UT0f zbRdF*`VRDxfGBcQNol=5p0r4~{Isiz>!UCxV@_uxK=xB1Cyqwi1KtBg*$|V6+3vB+ z)KWJU3f7ReC7bdcg~u8=`72%&DWtkPa@N7GgFE1}SehugJT(Oy+T?9$le@afTmm}2 z^fBD0rHy?LHZ~V*Y&mq)wPpX!bIF2hPZ0N37Fjp_1-J$}f=&S%7U^;6HVK(MEyY7> zxtGdz7mWmQoHA*ZLKXXu(mnRgvGzXL5y6M^Q)J~@`sl`ofu@aO)qkaF1LZ#VvoKJT zUq%mZCM9p)aP5vPxBFdd?C2~;MwaFEBU~Xf=l2(4T&7HZo)*234tODntM0{i7f&d% z%76gb3H~ADkP?6Wf98Xu(1(gWU~rGu>skN5^TA;h(gzr08MK&w?j1P34ZP#J3E-Ic z=w~`o^8UTl@@yWz1@?Z#U4l)2F~&SnFNjBNhhy7T(?U@LR|bE$iE##%`tNVRKH>Z2 zorXj%FD(&CUb>Nqj3SeEd6N^{mp3^?@4vUnfgqd;W|*Ds;P;_)wZCr9rK=!YiCGh% z3jDHUGB!Fg9(wPJ!Ls)mg{D(s@3T0)JM3(x_uDAC))s|UQxxuQ|1$Z}*gQNWJ%NMQ88Dti2(~OJ^rmZ z=!i{r=IlK&4qRVHnHl-{txIuJ3Q4Zk1jf$}cXH&=akA-0$*;pNo6*FkYszlPX*^QY9kqK;=agerU zV1oJ}`Dxc>$<~?P{#oPy*yS;MLYJK_I*kp5&b3A!tD=SjnuX$W9#r zdGQ(==*b(+uX@{ik-Lrg8hyAgV0;1Kig7|ujB)T`*p@q;E&;Y}zYRsjHz+EK{Ozdt z0Ij;-dRTSSl4w}z{&+LuYPEb5J zyIUfSpQ&wYOrt4d&%NC~wM8u%g$!e=JB$=LsDnMM8xDrPMCHh@6L9JiXw8$>z?!FB zP=__wT3&O@YyWi3L6yh}ioKNOPK5S<`w=}2;l*YE-ebqUMp_6j+m^!%xP#NIVAFt$% zfMDL({COh;bAA-epP^vx@VA5c|J=vUgl%F1Q;bR$C&r3d%7BkFTEYX{Tv1HqFl=*5 zw9U=XHsAHXx6OA}H#HGkp!)9uMVVT+hC|VT0duwcBSV&5-^sp|p-=VC2As^;&-d_}ExfxV(ohZ-9G%TqJrKFlV|`5reTkY~(&&J)LLqX)giP zFy`^_|=YLUnSW_$36Cs^cZNYU~;Jt9V7!0xc7zJBU3ht`{$%6XEEeW!w7l9Fjq zz>Yh0Dj4ZD)O+!h3b6-WI`xHXOx=|(orx!bR61ONv!Z5~@T^%!M9b~{G!zB}83SQu z5Ecrc4RXYKXOjB1ZsA-+#B5CE%o^LG^_-5}3V_cFpC5F;4ruKg9v|c-*j_HI0fhW3 zAmp1g+M$6ZvvM8s{=@5#2B|(kM$KJ*mr3MO0e2kShYVjoL(ik1@6K!LvmJ%rz_b!% z00R9}t4w*wTx))pxiUqG(Tdo{C15rR3@$gJJx2 zD(mS3c=!2wGJkxLSn3XP>ML*sLu}K)*}okbAk4Xb4kvDPxyxvvE)Q>(SCQRA&K@P= zu5hR;x37lgd9sm#5nUkEZo3yp^sMtZ0i7=9@j}m5^_iTMoRR(Pe)1~rlQMIo?`oQw z!lk0dYZ6pYMJ?PZ-8TFH?$MjE)!vnZBa!>}lhKvx++FuxNWuoZC-l$YT%E^nK>xWb zF$EU{O4@VWhgJ%vs@{P!Vb1~5Q1bdUE^q?q7=|Bpzbo@W!ZW;9{sU0jOEc7Fu+lLx zRC=e3&Ig=~8#oG2XpFR)PY}HCK?Rb8Mp%PCrL?dfID%BjvO*(fUY&r$36!!zYOqd7 zeEY*%jB2evCE`r@`1~eJv4SIz#t)`!lc10_Ona4n-7KHk*&O=;0@F9bYHyZ_hpf z^K%LQAp6t9uRG4-I_jyPV`DIwYUD_ia2vjC;?1Iz_!dg*Y|Q{UIN;dduuOd>v)g9jGmYb*;k5Df(*3^ z+}QT2tH1Yl5DealS)A)BS)7GL9QuPyiVUb&_IS@l!CFP_`E?^Hn8GkSgBgJd48auy zQI=k--ba7@ve5NRG>kfqhirH!c53hp0oGDFgCh$iO$%;?uKE zMJCio1DL!79V%!M;xsr%GOE4PzHB4gbVKS&yT_$AoB^m~gXY?jzYUmBJJ-S@`M{}o zi_~y`B@E=Y65^_0IVyH!8+Gk`1DS&vVM4JX_>OFkE7WzdfZwv*0kxx%=BnE!gT@J_ z1YZETVywRe()j)UXl&X~jw<$jXHt&iAcE)xDp*by z6#FMXP+17cm&Z)ZVz3qIip)i@KwZty1z6riQm4d3$j(9YLxx%%c2WAOyXXoNDfVr$ zjCW>Ej$W(#BGyk30Y#+#s-Uc9BlChjZc{!Icy7RFxNMwn7o|VNF<NpM<(D@Iet@ij?H;%-be}@F6=b#>}-nmLq7>WM&V<4mrhFlTviyh915A^Ekj-r z>(+f}Trnq*RZV*K&eQhsdN4KsbY23CggtqAd8wF53zV1S9pIa1Z{N&LeG3?pYdqtr z3vf?Cxo~=*SMl31+|w`X_Tg{e-~fK+~nfB!R%gz4ybA{DHlp9HpAK&ytYw_E*D()eRiC`I3e1Q9$@rwyNaRJZ^^ru>b zDDk8mB`FMfif)!mc>46|#WmQj&%`60K)0bIXk8sriK%g&ZgJ$^oTDH*07m5tk73Tc z{B0IlzQy^r#r-JbNS@Yx?avf7voAu)Y^2!!;m0e6;6fXSM$6oJ9F5s){%8@MP9bdQ ze1dmca&mI#Ws7r%^Ndit!Kz8%eBrI|oAm?H3lk^~*xDZS#|szHd&ubn?|4%o7{kmq zJ^rPBfnpP+9ntR6@Xp)rNP`m&mK?670pV%r-^3Cm$}0n9)iWI6hKdReh=ZhD_VfFO zxvcu&)8jqq%pbm<-w#BWhov$!w@!IfI*#|8(UKud?6Wv`=`aVD-bSeWH+d3TTCWv~ zrsvtU$Y05Myo5WLfF?L!g;L~fPrt=^U@!)mxCa9K_ufrG7_W9nTpM4T4C(YD%I5Q5%Rq=|X9Y$>9JHnqd z$mD5w;$W>OVy^Fy|700;btk+hAnJRNo&uunfbXww=>s|dnk-Dh4eEAy3V5KCG?4!% z6XKxPrvj}l0u2TWGA_|50$8~O(y`CXba>-s z6w4Q)2db4*dfunFP4c2k@OZS8xVWfc-c2G!YbN?EMZ^hm-c;k`TOygmKE>xY3deq!Ml53zZ8dmmciu*$t4YdS&z z^WfbRU$X5JU1x_f-c)@0RA?6O$XVtF7`7QH5b;1x6dlccCfCWPhBbNfWV#`dyb~d6 z^)IsLT^hVA-q3~}IQLsF_;ioM6!&AcwzlJS{m{`Z9dVnMMEdrAk)GHsM>wz=L0!!O z1B%2SmmSwm%q{}_OlML?>oLYYtgG;H1_*+{s|GJ~K{(2R$VM!SGsWYR4MsZ_j?k33 zoZSS*45yaTf~Qr=)&cAO(#pAAG21O)_G4oenP88uTzl4?VQ*j3P^frRPJ23`(gxc5 ze`@YS;(3l7d3Ti5Jv|l7J!IANYQy8ZfI~kfHx?tK5IX+gB*g>Ol==DjagdCag27W{ zZj6QcRorh4|$Rtala*H+wC_8lX3Xf_JBi=`iA#c$f?cl7qrWJfNe@A7LLgo zGz>mW(4_Q5IbNtnbl-*RESXRgyyY(3V!hSu!b87+hh}yi&vn^6L_Q7-e6h|Cfw2O< z@9)hJGfSN+De9EaE+BraaiH5sdI{uwe-dpFM2izX#DSHOeGR-5;!3wLZ@F9O(5O7} zZmu@Bcq#i)r``V^;(;(KgzQiuv~AUGK(%FY+X@%p9QpQrI;_Z{JNgO%HR0}_1Yr2? z*-hZ~bYnwvGWCP;i_EU0hX}~!S*SK(r}+4zX=QL|k=L5>ME8=b{NN}T=|+>9{U|Sf zwv7zXEnVE)xJuv9(EPcR|9O>g7^O6Nw2;zF7+XS>6SL9@pj_?*Ky=oyu#*O&tjlv0 ziaxD{bZ?Z+-AYyup83xkFgIv`M0gKWTM~o}Ag3hb@%XdAc~vCR>1=|m@y14|5~@T+ z&b=i+^ZHWQ$4K#sN7JDFI{Z$n_YHbNJHf%h?MqMS15bEkJ6W%45%r9&NA@q(d84b;c?W*^P65PNd8gnG#hkG8J~N7a0^!axfMZR{0=qX2kh?!8?3|@1 zy&UNZ!={4WXBQXR7K6bW!}xa(Shtt_Np2QMw?9BdixU14+J5tRYqQTArJdqvW3H>+ zh-zU+<(@+IQn}Y#uA+E*XISnSNJD_-o2ZX-CA_9(TWO@3;U}LTuZQwI4ubP9)Ca#l zuc)LoTrO#AAqf7RlJ1a=5=y+J$@odjwK3v0I@hS>j*tX`f3hAtmjgpq>E zy1Ke%@QignOV3zTaU*Z@Hh>UY!r^=#rzE|{ZxpR>oKNiM6}Ra)@@WJ0O0P|bh|%J* z1VpzQiRS*RnHfd18XV3kdpMj9lCPm!C2m}9<(IFt^8epXQ%``Qy8GyV9{d)v?Q&+0>FF$ zg_vfp2Ex! zj;ml$MEKISa09Sq0ME_}K;xWo?;UuT53QZMT77u*nR8)MWChJa>+yc)h+C(~Ze-@nQf&23` z>os|jwY#gsundHIGaqGY#WHqlMDh*eI4f>hXU_;S0x8)wCpyb-Gu-~acC_*+7y^ci zsnHIh8q*A86$pYUD?xD6KWm3RqX0UN_X7Phek^;QOjvZNs)r(G$s6gx80z{zVTZ22 zWy#;}`dcBFs@ZHfiaERV;3~qdfLIrQ0F4!$(my+py2p|*k8_PzVi^noTR zDXGmM*GU7mYxe~!But~>P^2h+Qa;dhEME?kBZdwmt^0vrXTN;{I$c}>BLf59=!M_j z*8Ed{0KWQ9Dem(FV0h5<>gX0`DIUJt0(Li+kZ@$Dk?J^N*f%)1uV~r;s}2g35WtU0 z!N9%~xLZ?22x_Cy`d+{Bfga!vB#8GqFd=L8Qfw-vCj2h7=89(xkEc>*9&^0`fVU5> zGA@Y6Fzup0ip7yE!fKmUBf$}yHH&#_dOCC=T$#;dUbh%gdw8Bv7fe?k^3T~$HrSM| z0-i}6z%kuBpPtvGYrl)?4^on6Y{f5(CSR=hYGmOIua9OhYW3CA34q1uPc9pKU3p8Y5ZXEE|6Lmdi9L!bOgs9=3L_1LJhm-dnuLCahtKZOdr!&UuNaZx&uBd2uCmRc3= z3%NVQ0Yjbo3}m>^iduIInP188(6@xz0zDX{XrbuO}OJh&8**xAKHo6ya3iO4( zyW*&Cslu8=#S|#ikbNm$-8Qdu>zcgxNg%q$L9k}Leu^yHBHnS=L}@@uedU|G`(!sw zW0~nn<9%K80AbYC2B*UBQR2Z9d5_p+?N5USEQbNE5Cs$_V{RzYKI+=2i}!Z2S4c&I z=d*SlmZ*Fx&`CcP;+k4IOe3!Kv^SX1s(gGRcFOvt=bj}rdxjjoEP0pFJExZoR zoSen>KyWZwn4j%})}or_$t34B<2{Y%OSCAi@h!LGG$xB=p*TtT}%_Mzg$aQUG$ACC*yN?M-_}nrmvtTfnbMAzwe! z$)8bpZ{z;rCrNNJjP>`#$~cej7D%Dl+Avo2&epG~N5O=ArEmCiAI0E#VllJJal~GZ zzeR);z1_uIU?+4lz+1fJ)CdrhHGM|v=*Z~3iVu*p(^koQfGrlMXiaSd6Oot`fE&?F z)GBE(atD9DQsKd8fvrW;K@U%TqfhrTI7&A_HH$g5JI{Pw%Gb3*Hjmoc@Hr{CQa9Cj zYL8D~(erKtohAkKThkWwswVR6HwgO6n0%gw{t+-vf2i(q0LQUzuy% z(ryRce<*lWNRT=Ku=4G?vbgQMTHeKSMli{neMrOG#kY|~jRX5NevsOemHZX;gQriA zLUkR)ZAT=sSBFVoO=j#%%jbB#@1(~O8;SDRt)_jq!?8kR<>B2oC?4SgPNVz^J;A*69sQ3Q-yy?AWx%52uD{Ly?6Yqo%bzLYzW|vpD$2{?irJ)h;F=<)9yFjc?1Im9fX+EuXZ~xkHoAoTU z4!}yt{1k~Tqa0fWF1?{<>^rjt+CRRC@MfV3JH=<>Z|@Wf;EmO$P%-w^M!Z}L*_Yx9 z{p#jFqhGD_bQ#Ih1`1Y)-y96iV+T0oMp6f}JO{RU%yf!kW;fa_7_?dX{||1Kv%m`( zFXc_y%^~_-v2gIxwrN=RZ?|RBlnS^JNwO{iNRpa8f14!v36AJvBNj+|MU5$;F!5VC zqFesi5%nYE&%*~H=S8>{_dwt~XtizR0DN?R>4QoIqDvn=5*mkHypOn{J4(hCr;IxwBAn*}S*3Dp!cI9~Mk2w19aB%!)Vto+;6jRjQ1 zDV%l_`Hur-qR`xd2R18;3R#enAVtMfkdl;SEJ;beXL5i|-4a_#EdI<>pZdT?)CY5$ zOf=$*gNa@4Wgvj^(|a%Or$`k0R`Hx>R0CC&_S{faPX6txQf@yq;M1>JElk6yU2^dj z`oR$Xhv9M$IsRt#qeonz5({vJ&flKbe%59nxrqP?A;h9omuai4D_`YZJcZ3e~qV3Iuj-yu_*0yzTY<0+w@wI=O{K&cI&kJi01<<@H^u52IDpCVP z^Wr;5^YooqGWDr+WT0`#wJ8XQC9hl)K}KmBu%82927uop;s7}QHw5pK6fm)acD&t- zsuY%?Ys7ug#b^IFCS8!sf%#<#I94IuA8bq(qqFzHwZECY3feS4egj|X+sdE@%aF&k zV4?SA0wn9J?FFRPJ=M2F7a)v(0K1$Zrsq}4ZMP^gr7v=7wRBOaY&C%+EtIern#~kEeVZ6s@^KBabM8-_}2Ifm|TvB^f!PF z9$I1P9(^;I7y{b4FN9Z|P#&87L>&(X>bR&<#J?r%$5SJBWYnQ->_CQ04Vy#vJc=?$ zdt>rxEtTxt3seWF#mGdNTV1+F0&Qujd3-Ixg_e!0KYc0bv!4!BVm`X@CA5VHhot)F z-%oOFL=#B6P@}o#2n3Tnj`js7;AX}u_y$F=_4#wT;>>TTyabnKz3$2wewXQCFt%sr zuUOwPa8==jHTm4O(J@T-$%sFfUKFqcWh~at_&9u0sC$h+K*7G8%*|SKO-~Lw$Xq^( z_1>@hT|HNHPvg7Ds2uU>W!J2VM4zNU_ZyffCtUCa)56nG5}drWtD#Czq{fo`)uHj1 z#muN*R|LsU))DewZ`|?vvZ6_}C_N!c?nMg#IB?29Db z7hI(dodcZ*L=c!waiPENX$kE!e#6|}ygOX)@Wo{?wU5iTLsReUJaIA=xs*B#>eMJ# z@*XFhpJS26yaN7`konez2sQ&~J$)>>82Jf|K7yHSddqJ>DJnReAP_;*_CC}0^#8}) zdxkZcZc)R^fTE~?4HTseDk=(C0I7)$Y=DaNYDGYZH0gM=K+cDY1Yx`A^-Y zvu91flo+IfR5S=O4j)}8@L2f#E!4_|ZycHQ^V>wsNhnG@!wASgjpp0IV}AeLyI?k!b#`qLi;Pz7I;6XM_l$52%O84J*LN!-1UxUHQ`mNBxwvqnIe zEqfZ+1J@P{EYl6xk}Lh$>)m){^(WMOi-vfBh>=+?$P?3y-C5kxr&!`aE`VXzlHY4Z zD3w+NKN+L|kW9&J!ro0 z`O`WcF9FB0iI}=>#n-J1UyFLD{YNOzB{$9vsukK+2^qzcEK9r{H27@1$-3De#wdh? zVz=61EgdUML`~Y`pk8B#Xr6y3!aq#_l)p(lyf2JC49@^ko=*Hp-RpKysBgdO&W7#M zexL95T*+qjG(tr_*?Jb#uci})vct~2zqivJ$@yxE)v02`4`W#GLyv(B^#}+hFqf@L zrWHPTuruDTe+{aT%K^hgJGdj|jK&$;+<`ni7s_1+LE|E&K#E4o+Uxnvw$zk!`xEat+YDC^CHgxS?<&Y6A3826X5d8r1N2^NnQT;7Bci z%k$<~nsU*^Hn>WW?xJpUltD6E4=eSVky6E4aU^j5C}5j6le0!ZuIQ@}qo7%@1-kcF z7~KaR&yoG%O#?L0H0VJ#2!OqJ;Cc#Nu6r$#EcAHMvFj5^ejDii#@Mtqd}hHb2@qT% z=4D=pgT{5ErKMV0TD|>^X`hU^YMUCIO8{BA1M{|kFkaW*zTR@(rvWB5;J)?SeM^IO z$Yu{%yg!WEn5XXY7kh-nm3K$vg4RFWmBspca$@(ebHLP`d!1#Cw-X&se_nHib<-*X zgdb4pPeSqv_9V~+%|chh{kn=!oWBjW%4C1cfx6k3R--$)?zQwQaw5oPM;ti|@;`}p zxkzX~dW})M_8OP~us8ls*=z{X)@qcFDzOj-3_J`4$|P{8dmv`!8husURIBG#c(ICz z!8l6da5y7ZHkwo-OL2~BfYzx*ARD3@t68RX7^rHjP&ZDv(s56sNz!Fu^C}k1M_6Ta zxH-l#c8lBZj=$3e2Mt_zi1+W6>Ve{xB4Y9M;hSx|SJE+H(ndI?lvS)fl}AEw4+n1h z%AM82r%C$Fr6%P1YOFd=FiwgLz7Fa z*^|jdJ680d@bwLG(--lejkCWptbzHK?n9BaineAqq_GXZn3 zuDm)wYr)Nn8w)l5P;2dvd#LL6d7$3>wVh3+Sdgbc^uoHgRH&#Yy0Jjqshn`JZCzTk zeOwMV*|wXpX)kd_!rbh;HJmeP+hdYO4f9JwWg-!c#i*mnS=)d?t$uJrZy@(>`Dq;t zoYLFrq8yrE$ayXk(N(B4n$gnFqkYr;3~FiFPV+0;j)vfNQPy~DO}LGn)BMzOMiT+p z$0mCqte&b%7iod{x~vDW@N!~vh`hX*@K)Kk?A*7(?Dxg};Qqy`d%F6>`~!E-LA8vl zT6P~62pnJBNpF{44mEcGauNL^C*IlbZDo7aqQBOL`5PdvZHxaOvmmmvgK4 zW_d3)i}UE6w0W;C@>Q&B}`KV+HxtEpqc&?a<1snp(PxG)hqIV_K0 z^nY{^?QsCA{BtvqxWKRMs($vUnkEuv=6(R+kt{m#%VfrJ5C$ccxK32(@PN{J;k z?Xq6k-MM!ocs4y7E{b4ERbnN{qAx*Ny*N1RT)5S1RkI5PnHSaSDK7YC!MjD)>W3Hk zUf(=`Ch@22ykH(fZ3gNbes=IX4xKyj^fo`n{|05mFo%3iAopaXT*_#OYTA4}@;0HW3!`l*I;t%3lV_VQ*+`E3&} zSI9e^cQX43wC$Bg-z{n%ik7s(pZ>hIsD0_z!-JO9dT?}>>QWXR+tJcrsi)O<=wg1^>V<_TwRq1)!4b%7;Z@-D4E$v1E)Q*=m z|58g4YM!4jZfZVkVdW1>=@~91&q`burZz$&GKxZX-}DEDD|Kt?De+et56LM&xQo#q z9Rh+?Kysg!*I~*oVaiNGccRt2lC~j}s?>+%rvV|QoqtRtQa1SPR0%y&EjnqN8oEOI z%`(#G+`LLh@8SSj2l`98tCG-0ppJq-`blr zczsYv`y^fYa(w<|E>!Jy+GuU7-0F_MHNXb(xX_t=-2@7AO2u&&?@PPLBb!EF$&ND+2*%uaWiC7O`oQ(U^GQ)>qIc`0bRTO;G>C3+-RSsb-vV{R zO$J&+J}@AjTJo&BWqW^1$Zoesvm|S!Yzns~j4zn(C%fXkMXN?$-nQ{JUcARxA?3^H z;F7nq(mCd268u{{k2k&wdv@A%0YPCg+0#kIK+1~-SG!+l4Oh{QxkvNN7sqtbLb|yIe5FbMo zyBFWU5PPO=(fRgGSo>*$pinh4B?4my<26SgX-R$mA3vT&WmsT@;^x7mzc8uSb4tWn z?r5#lm&0y-sb=#1`>~e{YmSLBw5uEAzc0r37i8E1yzjb}Af4mXvMZQj zaP4FabG6{=)gO}fe1Fu>`#W#$RoYGSCr_pp(yf|d+Dyl%u;|&1 z)~T<*=hAmyEFr-@X6^TNOAra-53L^##_fYszZVS$&);&8ex`93x!_K;_)p6_CmzVU zK9%q&8Q0et0W4Z@CuYNs4_W|U^}ca)o%fS_U$+0)j&HBvrwD@+$8W)aUR9SwJyz1r z?5co;0t*+OGG6)p9X;i~R(lt1DjamdrGsRep+71eduhwnDT6372vDxr#U9lj_v$-=`Ux) z6wb!bnqQrbgPnmif4jV%n|td(3BMj>Y#MssM?cNiWA&BP?fdDa>`x29h8#_v@@&M- zE+Z0cpdgy8Sb_h`VtAv)*!!!+h!jw7_cYGqvIf%b2Mjvf?SK7fy{IrO&wOZ(mKKRuc z-5UgO-h=T1icaGJ7y=Xxa(vCb;xUh5IZl+kU-$EJJVMLS{r|*rhzf#cT@mB0deMf# z50B+_pj}O8OIN4NHhE5GY3-b!ALA>3R~}BeEA7H%M3OClXzGd;ML#VfHbEWjivF*5 zMN|;~btXZjkTZzO3Sj{FnFK8wxij^bf7yOAQRd4;uHR1!eDWf?w96Jvd1<9!?VAVS zl%Cl6G4d~`R1clf)xSEWLB)&Atiu*7+gdNDf+qex=vn;y^1#eVsC&)S!e{<$5~Jl{ zuBx>Dg=ubz^6wVhz$h#Co!Ixo7Q%P2NBx#k^DPdH{jdq&Z*C#n=TNN*VrfRS+Clli z`rlhl=+2%#d-n5``QNX$--@sIF|7O4y1mKBv;R$aVU8V{W63(Vlu^tYBlp{(uFsIWVU1FAIjAsa*tSyw2^d={7ZxN(n1+ z6nEJK(#t|Zt%rVi1fBVJG(1k^QR4km@9ThKr6WKmI+`Q)(t7e7`?pmlKTIY6#A2WF zeM`#JCl%~R=)#6w?FhBVMvCn)D_sjEfw-}sThv&!Rkq;pMPK2r0*_ZUC3$}yD zEVz?<I4ss4}eEj#z~G4)hHz9sw@zJ;;Bb2-gN-!l8;0fzxIYWh6W{{Rnp$+pydK z^8@mM%BHuD{=0KIJ1uAkTv0dlIJ>1K1;d(UUw$4Hy6x;Af4HRnu!GXGfe9hM-r`B3 zW*5vXjZ!=Hq4xEC(Wbl5LtRe_BmaL>A;>X4M zc0N4#mMm?`^HDhe28LGzKHWBBb*bFX=QIwT(?M8~zdxsoLG2u$H~73Y^**K5Ls#(R?X$~l_lzvBvaCP1QEI#+VMm46{L3N} zf%Bi<1eskpM{&_x+$(^ZX{Qx1aat1y&g<#<6J6KRL|;~KP{XyGGPi$%X;4JOP=aoH zQ>)5kgBa5{+Ull_&oX0=ei?08`tquYwXAMk-jPKTmqW8N&EE)h$!DZ>SXRYqY-;zY z(P`WYG)&~zB`{m}q|6#FBc?>Iv$zTBk9UBSK&1~!DkjX@P-DC~bRwhr`)Bpz(%?7M zZO(i=?g$$3j)448{}567tSP7K)!*P$r(hJH-f_aXv?|n6{f@Eop#^xtgq1;M;E9u@8Euqd|MQE|USIJbl?Yn_>x47h&$i>^$;q&EJIgUp&fx2>k>T>`^l;g2&%Xm0~L6tfC8+Q4g>C}p+I zC@vsy6(}_WEq-1h+Pt>yH%a+5&%7={tAr}A{IdRX+dgr#IAM4QAMKtv3$z0RwlJS@ z*c`5D2D+xf@7^n0W`BOhp8hQJ*a4-!cQWa5N5AYe%`r(6vxg2^M?giMy|F(0_QPY> zVEZ>~mBeHmZ6040Dbcqy<3CnYqrGJ>Mw%|cf%2aLfzwP_PTaBmYMers3`FaM`JDx)Q_!IF^kZGl%#4*8QO; zE?cV@1l61@r-jv`DdnQcP{1`aInRYrxnunc8{MM6dZ_ zwcE~UEpOKdN|~r%m1t58*#ZI%yqek|_n~~KJVDxOub#N1Cs=+TLFE6Dr+M4^nNk%q z-XdGjo?>&kAOFX0UGD|eVVHGLsVQ`XZ)ub{;l(-7B$$>|(x&}({B?Uvu>a$~+(WDN z=8t6C{RT1`gJACFr_=;Yo~oQQa}xvRliL)Ix`HOLu5qY1dsRuBL;vUHT#nlj>G31{ z6QFTmV6FOab=0P0r&sSpo6AWHJPu>=vros7H@#iC%JrCQ`a9{|DDGUG&vp~B8!jW> zxZIN}>bgyi8xL%#x!1R0EH70NzUi}xnN0-hVYBu5bfJHfk5XRwcpG$^I8W}=9J?MY zi%n=2V0!OSno&kFMik`^$WzS>x^g=+BXP-D1C&Opv=>ocLLlApSt@JYO@d*CZ*b94 z5B|vO)IWBb9wk5X%CaG7g)TpLg>CUWp~G(YG~x0kGG(y&Ecw8{F5w%e&C{6xA565% zMOO4b8x}iX%38iC>0pgm@)1?TH1_xx)n@B(*WBLQ3>ZF~1PYL$-NIGUc_-iBtLOzy zhljR;QS^b4>Z7G?HDhCXBb1|Aa`M8PcS0;Jy&GIm1V7Ko&0hn}CMgtU`f$`zz&0|r zon@C=D4l+eO#3$vFPVjPoe$~8WU6|4UvdQ!9`DvE!G_ilQzRhZ)>)%YDzDPx|L~p# zWh4=g!}i>DH)2@sbW7L8S!o{vYXj)5=R7tAs#U1vM(L_+wF-N#tz9cnhRgH;1%gzX zmxpnNf2Q$)NpZ<#L10L8{IuS|L~X0Ws`b1%pO0_ibnc4f?12?T5Y46Lo>y9}p9ONo z?4c9i5o$E)>lO+)KptZ?|4%2~4t|9I<4ZuRzF*7j8#1%nK$bv418Y6oy_!vw9}G`^ z9aTgV@~ALxHPzOdUb(4eB0euWCb5(rfuU`9_*z_277qB>OYl9)Cw}F$g9T^-6s`K! zjJ{R9S2t*qri-PT<}Y|jaH-&Y9J zO)pGi4rVb^SZV^@i^|5^9z@zk19yRlBpCW%&SAb>1ejID{IV*BdWX+ZO`op`#NU!H z*vetqx)2{uk>zSa5TaVw{5W%2INC&(oh%`TAN{fey)y4=o$kc)>=-L-4p;m3MUJCx z97o`tL{k;k%sYp-WYV{WCJZRlqLl0@%6FP0f0YyK1+i~8vJWu}*4q^o_-XmC0o>@| z?=JCZH%_Ysu@@u3bCar1X#BwF{^hM7g+`2TK!-A`-{959w8WXB77Gd&l!@9;1j$SU zIdM*XcqF%6H{gZ$Oz#x}f;0AXf|1PZ*hj*1SgChAq&^s%-1!{LczirvOt$aXp(u!` zj=ybB|B-MM0!-Jui#(v(>w~^uMN&W`ve~bm1!_n$yYDFsua#J5egifpsu#$$<0l6jx6g!Tmcb0hZ<4Re z3woOB8DKrl+CBWozU*d_KMISjHkQRCtR%G$^+wtmB3&XhlQ2pwxyn)w8!!uCr~kwO zu{Ht^C^dBNJK*&)t~I;yR|QL+)kBK_m6QnA7oRSoG<~dnbaX(d5Xfdm&Q0mN^Un;9 z)OOvzObiTl6W`x8MqMWY$iOZd;1QlDzW6!b=^je9?A zu8R~q?y&+4NYK++J>;OAHut?PFe#+v$?y$`a|NPZDgv_v_%!u9> zXxnSE1ejGHnA2Y{w{Fbc(6$(kmo!R5{Xo>bAVOE~L<1R80;}1A!m(>)3AzV&aJBKF zDERoh#C{dl9;Wi5;EsAh!uDau9^wK)12Q!K>b&aHM;HA5tXPl&F_9|x3s}z+fGYC}^I1t4CsEH})0tL-1?(i7(VXT{AwBqUVm63-?*XXZRN64R+ zQVA_`;=B zg=X?cbj<8W1W_S26Yh0t7#{TL!oB5wJJSbZdD=DrVm7v(L*#_%`F@dFQDD3iB6?bY zbaKgT-wBo27%WkEU!10Dd*FEc8i^zd`OO1~NB}dH_f3h>JTy+|Vdv_xG+_V{S`#d3 zR`yaVhH+Q)0gs8{IiS3NWOIaUYgFyU?k2E9>+QI`c20@3*43kw3+2Rd2W#s^LFEep zolQ|DNZSSfDo>s@{{^5IbuiJU9!8-M zm2dy@k8Hou{%it|TV9wjU32nyq|I$0Uflr#TY4D&Y?s={$drAUY~c z-i#$q3(^%Y!{sbly0mT=u`cCOu#Y_F!!={M;tzUyw*a-ab^THm`+Yn1M`BZ$9>EMR zNOciL6@*_{Mqbm~$3zotIKwhLH;nBOJG*+!qyukV;3pBgUAfbrFfPp)_ex-W?&_(T zTrH_|0ZRltL3Ac490a)i3QStHt8+chcdy@gKG`M?;>6>PF~iXX&^qkySrv>PNN)j< z6PYdWN3Kn||60M-8mvCUghDKY>a>o+#u&>z9e{)0&zdrA_Y%1k4F=n8yuv*IrGTFm zrUx_HcY;KSH-6>NdV=kdhN>v+J}}Q8c5}6#pBP#F3rAcmID4IK!4@00H;W*_vfV?T zc&lCqa$K504#W?}j)_EboP#`CFRmCot?x1@5xAO-#Lu3-2i>ld${=g;0ZKG%*8@{J z)hlAFH-MGF|89EQ1K}-LlJLnyn$mp0#^{P}I3|7meb;KiBjAxnD32pHx`T*?f>YH8 zeFRZUMqk)=RxErgvQGTKs(axbh_CZFW36e0s1Nz##fxu!&%ay(pMUyD?;doe61)YL zQnhjbzxiol0joPK6U-RS-#Mi%T(vEs1l^7+<`&g_IEM2(=!)gZ_aF^yEgPHte0R7c}IR@5n2oCCn+{Dm!WGsPC#OW>D{uE-MBO5P& zzZ}?v--4Vob62&yl`e0LS2WAqhh{_1)Ti=nHrI_4u3O8Y`wD(uK9G`x)>qNj=)$y> z`sB7**%JGORleL0)5YgZ>0XO>%(`_OPAles;yYiokqI(_aE2s=;K(u~UgWTSuN+W! z5ZJ(v+du4CqOpftu;AGV_{5?mZgZ-($zd;-%c9pqM<8gP&=6oNo5A0EPJI2;pTU5> z*1@m4IQbAiaf5>u`6rcyzQ8pttjHt(=J+Au{qBsaIIKUwPp@^sXnS9q5*gf=h~16s z!-Cu=vDeVDtg?c)^%jSniL<-n|Be_b>E*FX48XZaOlZcfu=_nVS_hop!Y9Uvm)1f! zeg4jz-}$E$-N^kY0yE6Lp@T~^&DaAHS7tNc@ihr=Hy1;AKaW{=Jyfm_Q0Jrrtfv2w+aLiJb^?Vx-* zMe%jP`u%$#D&XwMT1Vj@o$`ffzl-!(L+m|mR@{P;hcTOi?f`L>?R)CM^<^LlcExhj z*!x}N>sv0KxGN@Ga!d@}40JfLP;Y}o!}7)H!(O+5bCl#Y(B$P?!u<&4HeSiA2=p_> zC9}Y!v{}M6IP(h}l8daP+u_0{Xgrw?Tzt zs0S(?6tk|55z0!v_Sjh^kiPWR992Bt1LoeaA^I`A_lc4Xn?){6lUsG}+x>xG&Rcj# z)62;cG=8Et9M$7P>PjQyGb42Op3YM_#v#!xk%;}Fi@e8NB7 ze4*%AWbC69-{taO`koNHv;w3VTBP~ow=v2a`uq0Du977v0UWkQUca2^eXr?yU=m1_ zeSOwe=?)U9mM1)i-$*2{F-|%(cT@HI_!q8e?CEG=xY0m!mJu|#rLC8S;d*ID@I7VX z6v^()Ba3*CUr&Kh&-Asi@u*Uz0y*{Js(c`(WWxl9Aa3j(jIpxClNG2;FxZw`Pq86- zcdKtyG<6W3Gg32FpL|4m_<>HDDYyzZU5{h!P+}^`WUpHiXtPG}GdupNLQs+jBULP6 z7761n&jCVH9rPa60lAeE*l}W*vh6GoX0m}PXGscA(W;3`{=96M=$?KA;JyvXO%GSG zxn&+3LVemSeu7^4Ao4Mrfz*_LgO9BZx8TDc9|5B?y!7FK_pLS??G^A;rVdgT4)TSQ z^3pL|p8(EM+PF*L0g6lY!O<775VYuf?EXmgwZ-fG25awbe-;>|8pvX#rnG3hwLRu# z^=$TZC|uom?%Hl?RVn3l&PTZ9gGi1eX5ky_%IyNfTk)%&{2MClm6-(?hf`qgF`G99>1lUh;381xv}ZVk zr00iqaKuBaWGx^;`S!T5g7!D?t3nocTMOTiSr#Wn9pJY5*2+l6i%cJhneHJU7$>Tm z1?$)Rherva|M6AOW+;udyx-5B_fg}m#I+{xY3I0F720nlyvOa^u6+mL0n=0&D_hl9 zqmJu{eU2mBIxjz4(DK1Kt=jrM)dBa)dvE%Y0V;#k*miEirg8mB$6DG}hzhq5U5>>C zGlpLJoSIR-2e3Xf`B}H%km@dT11zy09KKa=Sa5|_O^iD287NaGu|M4laRDA%D6P~2W<1XTuHl!CGtaWQs*f0 zA6?_gke=VTy|&u9W56)__UN@x{oKlm+G2Sf5J1ST>wxQ;Myl%7&?iX&Z3{%Z>VO|= zE`&e1`4ji+a;$7E0R#EG>v5aMBl%6^`Q7;oZsOs*?N}wZkxVU zF`D@Qt4B8L+hg!o5N?WL&c@I%MSX5TzJGOxVDvh)iZ-x{d(bMXuE%US4zeAip0%Mh z4WDO;om?aU0#kWTtjB+b%wl&|2f?u12i}DPHjUH~hxeDH{T@F5eO!}r3u8>VBrs?0 zToau8Q~u8f%}1f0bZ?#%Rg1LIf9xs5`S_3!XL*%efx@+dciJo%eP00egbvNdbNA`3 zJ}&n~dj3UHd$M0RRt~s&yZOQ8H_wW#AE7umXJ$yB;io;*1y=GCmI^PmI&bgeV?$<; z{NsbK5B#peL}l#_P^``RCE-J6cAICt0TskIvocSC`J&=@W4Ot$Yg_GZ>al`EqC`+_ zI!GFQ%Q7fTQ_dK)&_~`W8|9Gk{-b?8P?HGNP`xni==>$v1alO`-Zc{zBh8)C`6dtr zqi-QB&q(pzGk#Fgj-2lTh~DDt7L47-&~&fzK4I9GJO?szl4=5nJgCsD?LI!!^Zf2b zWg4Bt$z0-IVECV6l_KdSnVRQfqLmB8&FQ5v< zEDZFJtF=O}8xJPWdGC~I8_OVJ4f5ff=TEFf(e^d)qf8qVWvU*g;olKSz3XwiiL8d? zwJjhr+HJCl9%bcfSu?j9O-sd0KE-HJ4_{V0nA4{Qpq_Yh0QjF&3x7!0s75@75xAL{ zRe^?uFU~?^P$FSMly|to`O7O2<@9;JFp)3YwLOmkBd>IIparjRi$P83aFA$#Y+#SP zOp0w~LKr>(R_wJcT%2c6{rP(;;n5)fpoJB5k6QU zJsTYl<8Q}flY%3?^+A$hT=WR%R*toKG*82Kq-P)r!r|TTp(a+i2&H5xVzNcgr#>Yz zLeYH0H&pSRDnG`z;fH8I8bqgL2y(Jn!HnD#c0QToiXy~3P<%9YO|RkYi&0y@9D~;m zgvQ&94p*Yomzi$wo=K9%oJqIcxhgn>xB`u67fhTpYPR+;P^D;(qqzoDBW{n;47aQD znHntF3qiz__UP{H8leOU(Z{#{iewPD?sSJQ0F5U+<p2!eVyN z-#HaABUHeEUtTYb=#A!owh~IJ%i*)Dvu62^LrQR7k5%BR3;M;$4#dE*hWQm$6d1xt zs2D%yn$3F(XNmzLsg&PxOYom0@OPu%K~235n!~A^;jbgoG~XKkx*ASfjS0O{bk0PD zS<%KD^iww3daO@h%K=^RcHablpqL1NQu&a(7OMq?H!Rt~uN0wRdb&WQwfk;AAm(`Y z??W|OPTq`rvtC?xBLa`@Mfn$g20B;l;nOhG2)mConNPCP>1DwL_G6YHgChKx$c!TH z#tbjOgh~7Mg!Pj|TY!67`@3n)XnclPCu5Ti)N~wSHVPF6N@Q@K>9PE}Iv)x~%L2}` z1ukZ{A|UBg@HSZ{_AqC5DRt88c&-x4h#qcFs0OkqrN%>hGZa&@kAiwWR<nIo=)0oFKCbACY!K}`-VIVD}Mt7Q}n}>0SXj~;uIAO#H zfx&6fSAa-%sM)KpwYMhr3yEdMOC4diG#9De>-${kmf>3+qn@QXF3Rl`4ap;e_=$yT zE9C{dOPPCQQN4E&J#GzY&Wh3%G6OK>oC@4D+v8(kiw`B|k2YDQG1E~I;Nw#TM9*3p z)6HPhYeJdiC$F=3tSn+4WB4t`J^0-Cg8Q6B?}(z4P`EGyJNLKDYJ05UNaQ{6!ILRz zoPINsW#G$(EC8AKt{*vUO`(3*MABG`b3KmJgfqF4%=a(9uf=J+k0AQRksCOOspe() z`1w)i#H`>m3G=jp)#JR8Y5T6cK_TAf-X2LZuCbC%BNlI2ijPw)501nS6NJ1z5VZxYj55yA1EoY7`8 zRRJQi(jirkS-~m4oIZjL5v%dx$S`R52ef)bd{pgbGdIw6B5+dGThT% z8AQ$(hf=SM++4N-zDuEw$0hUfThwt(xx*y77AZUv6v_H82$0zCNZMUw3M-*40gnpI zRlP8PdlxDWrd?zOPL4g0a(!{vy?k{0(LxYyr26R^v|LL3TD;xFD~Y=0-fdxcY9xLQoF-ordO(K)rcKta8%7eP zI#+r)WrQzl*6zb_l6kk(Tv`s<826CkI(A_?CiJu1R0vMjp*5NES`8d{jsY{2VLE z%HoZZOpQXMOV&eiRFDeDyCvtSqOq*PQ+hoGrrK^?g~e+Havhi>y(qR?N-bTu=`7ZQ zZ(=gwpo~phs71X=VWpFv+4*;WnOQ?V-I;w z7N;fa0Tg*hdx9AmbjrmE_V4L!b1?DFRn2r7x1E&MAqHKO@oMxIddN7#1 zF{sTmo~%ohB3o7UGG9(h#(2tRg|(f>_ePkR;sSWAW|FScN$wUmXvXAoh+j zl+Gk)YGR%}9$oPkAAJ=}$<>R_h;$irW&WMZp!&T(F1Dd!*2CD%?|1|*8T^SU?mmdh z)GSb?*~TWr<`AF6g`W)5>$i<<-Y~-o71I@(D6hgU$>2Xo0cATjGahS%iUuA)vQ%C_ zC6p++Flg&LK<8v`Mf7SSfF?mgU;((o22f_LftYW20xT*NPp%1B6mRISCgv=q(xcf! z-lUk2%#BAHdT%Ti#x0;og5i++paJ)Lk5KYHmptdYogSSf}4$z`;Li zN2Wq~)rVX+ZJPJj&X=j;TI$DgmJSw;(wrjRIl@;_L)B=CI+;x1ai}Ct4$ri3|NTbmB1qO4AhMk8 zm*(&Mu8R3ln{>T-;yhnu=4%+_hSRYDtO;sl;gk~ph4V~2s zbx!f-FqyNbS-%OlR4I&*ErS`*VkBe6F7*gDm<*GH1oi-e0dD_-r93AAi(h+$J3qD2 zUTyQ{LxoqK5*q_!M&N>oB$XRYJ58y3~oXx4`A%@ZD&73m*1ZxIAaYev)zE} z&QBOzg;v2}8g$u}A%4v)9vREhB6K(<);!5jPbQ|cIsH+MyNy$=qg)(k*IsMe5ifIt z(04oLEvg8c1dkCX+bF3QS$hGIIP{bm)op|;fbz8e=*Fv1#wKO@YSAJ~`aIMD54ViPl zf&{;IZ=1Ug$KXpw`7u)4!}yrbXrOS2W@+0kqMd6P`7{sm$Y+IH@i6B>mruVS3`-CW zG|E2tSo> zWjuaA5lUGaGqzv{+}(TsN7KIl8@WoL7bXR#ELKmVB*^1Y@cKAr`$zAyLVeY7Rx4}i#y#?_ z7w1aVAp*pu-90t0G?w7Ntz#EM0#`5(wwg9;>TA3?XlpsT#@P|Qe*9}J6?6sq<&JQ* z^C@6TR5-C(E`_I)V|+e%e-&hb^Kw)prt7husve_U9)A+1+f3<68n!0iBo`OK$SgN7 zCCg5@9;}($n;XV8BaE8WgBXE%p%>R1Pw_?s<~j#mdK4pu#EfwS2qRf~UhOsbnm!ir zuAlnZZ^ip_PFiuJ!ll?0nEayJPJkpW?PA}|#RVv=uw{igtKtW8@QR48&O!0q=*T(K za6fL0LNhnk<=tc;XTT2AxQp<7=5N_C15vyTn|jX2F7OD;3W$<}S>{m5)(31e?^kUT zzbT;x4pRdMU;j@RBn{4PrVC&RZN?uW=6H`5>@P4P+)il%}4TFbxlojvUxH!eveu0Os&s z3^N=P#r;ylP50~6@30h|CAoB|=IFGu?}y5UH@_p|uWuTEN8kl3aJzHgp5SaAmSxp< zLzA3c`>%*1GlbUxuFSf(4#yOE4!WRuteXQ+;nRs~7m~2PF%tPCM$IKPMCRk>I{jPM z`Mxq~7TUry{+&TH>kvd^CR)cF=W)rQ(Va^d9tEs^eu`h#QyV#~>z$fb2=nS-FraY} zc?7eRIuLy2{sPHEkk7vkgFZLAH&Y@2DrF!6gi07?0HN_ujgQbOKvu4RDFxlzZX35M zDKhXD45g@6bK7#ubx4jJ#*87PxWlPa=7{g3P=9a%4mM6BlBMlY$H=LH$@AV`&iem6$K&kfy3AAv{lCnX@R)Wv2n!dOw(f_lsJ%aU&a7* zmyKF-aOBGx*-qZSH@Bn~Rt3|MGePBt)TFU`^5=NkBx=+FF)gCgqnZW%J7Elh;TQ?% z65j}649b9Rpg(VtY{&TmqZszEDjjsg!7j&v*>hWYqq`$!}ir%J2V;m)yLgGc_%952Ch3tGQUJ z-e>PL;XYB})jMhSd!{n?CV4{|LInX7DyXTX6{Rn8hE9^(H+Y7~hZ-!rQwD$n6Ie8s zJG5eq^0%Fhy@Bt#qEL5t`z6EW!0mFV9{YX&9{>S=TCFH}Im>5i)9D$6uR^Ai5z)&+ zrqf-nD~LEw;n_1+scEZHV)q|Y0b8boLrDW+Kiw{6ORCHWjuK`f>o}cY^kn# z&kUyKo={bf!GNqe6@2y@jLHC@yhec7FL__dJ&GASN|l#k?$V^hdZgw&pnZ6JU-OJ~ z4EYd|EWpdH2~-MXzO$27HP6U}vk~0>Yb}>I;hA2>b15lUj#! z)nwq;b290f>gp3bh**xZzBpj4mMhueT%V9oFNa6(rD@sGH2=n3yd?F)HJnz$B(7eI z%&hMJfGDJm`-lS}WL8s-sYkWfE9PB6JIHD6D5IM&^i9-K0=qOVQu0G{%y9j z=M5f`G^__boU|8}L=4HPnAec3YogjQo(iKx914a*ZI1?ekM%6G0K;qphIz)X4D;Oi zWp?iTe#iLCk1Zn-SAbAnsh}U?(8AoCF2lMjlN!GKLq^lg zpqUT1&>?uK?|O61m}^apc?|Sy*IPW)yvP7Okzh$8c`?rzGiq$o?VssUCE8E;`f_Gk zAEPaMIRH5ZL?*cJh@UtmkSMA1yjvQk_;+IzRqQcIpcRj)JHmS0riUHMc-2pi; z+Q)*w8*M%%5koX&lT&0Q9+qEJAL1k)1XWHkdZ&86}tETJM4P50Eb`UNQ^kH z#IOD%F2v*WEj(Z@Ak-gB^Qs;1mkBd2@mU)RiU)qhC(@PhX>IK=Rc$beQ5$TCa3vQN z`o%cl_ngRAuOR9^W9zZ3pj+UOJcr72foaRg)fy?2*dxL)(=4!Pi?uYr>VU{%9;T>N zuIg9=^-PR+UveG>jD{l!Teu`cjBd z2;iy(_fF0eWNpWCt+@r^5vzZ}Mk$^qYz@5_CYv|_GDRlsi*oP38Y+W{hkh&zPB@wI zF*BtIh$#RqbRf}QVA37ru8UKLNaxWO>)+8^F|1LoCh_~GF{kfGM4^@fUk{*)mfSH0 z%e*RVy5Ln*Ygpz7mB?0Tcbozkj$W(s5!Gl6Y%KbAB0KJYsE_S=d|nkQN#V9FtO~*s zpcw&x?Q)=f;&lgdyOpsv z6Cm1lk)V+12_1-@FwC7m%*kB>HTv4x{iE1oO%HF>$F?v|o@*RxQVHCIzJ{fZ=b;@> zsZTsqi{FIzy^HO8d*-Q;yi|Dt%IdO@md+y(Lm!t!7i4yMo1I#bb|;+V)@7J(KKjHA zXxI}?^-=c+P9={2zr-Y2nVAOTbd$lLt~7|#^xF5Z4NJrrDccokSH)?m!yN6Drfp}J zg%&j0bPg>$da-D!tn>y2Q#S?Ebib%XjLp+bq8Xr{IVX%{Y`oz>me6jLDs0w{Hn9%*7mei4=E$+uy#7^$B48wB10rqdeDLY1cJlNs`lmQ* zpYm5STg=mqc>c8<@l76tlGqs>>4sf0q4bY>O)zLo`g-Y!8|hHpbW^>Fbwm|UaUelt z;Sn2K`s2d_I;i^EI;&o|9xA7n*LbUI*-`&Smk12@NAI5_cpMY?{mZS|>1EAdmJOHv z-1ztB=4%DP{A_MpECz!a`*5`Jw^u{|Mji3HzOql+Q}iur+5P?-sf7_hiL}(@lbf1c z|10K5f!-9%ksEvG3bJUIP!mYHqA9-lx!rGgLJ3X$-w7het_8dyKgU(?rh_j7+TtSN*+#PmSSIW&1;RWVOj+0v}^khUX#H)QA1GvGt_Bs z=-#9XN*R_HrUAJ&Ga7#i`AdHBQ*h5>Noeg>C`0Zp9xA{nI5RoK+%yV-TRpl~tJJ@D zw{1lp?m%Wfm?*`k4j5oIex`hWp(YTnhzK<0aXWF8!YCc zcMY0>SOMA(k&FJBkewiw5bnQ24y)iawg#FP3vTU-;S)#EQ(|`{fDEx7>++)w=&@@T zq5}6$XionhSmR=)H;ppDu|S=2~#ur)1>6Vb~mpa_|~FV!{4@$|7F{z z1s#B}&uSSu==<-XwE8}Tgny+X&z`QCtG`gd^WF*KLEw|`y^`(wr*uZcN;ug{7T>$4 z7Q@Tfc>Yf@r0{jfzdO44CTu>6MWww^?({Rqe7|sQxz0VYgaxXTw|<9Ku04rW{I*Dgbe5bTV5 zD0rzIRk{x#VTzpZNJmzd?|>feg=1>-B!n-9!&!%{&}T54zY3P8wn9H&Am|dzDjaLc zhLQECKX3jL&1gE1P3q>Vx7~pDyjVmM3<)`$JOVmIw~*3~nD`yQ7X6?C5Cd5yVxHDR znR&s-jK@duJ^J_`&6--rrJy5y_Vo05V49$>boqB53h$DKGQ>DyAs?Mn;jbwqrvJXC zN8vX@H{Zm__*Z4?{i+95xB=zni%natKg?D>kP#2fR1q69 zcfjG`x3i&5M7vUmZv0+@Qa%S@tN2OPI^Ks+jyVfhUpGURX>42_sY`8+8klG43WCL> z32nPW%j~VsvYC9vnmZ@qaI#d{>D{<2rHr4Uu$<-kJA|^6j;DX3H%k0&?$^AG` z@Bltk_C(i4=#!R$Ub86x3}J>TTr8ZX?f0t3UVYaE8RM4<+&*T6^w}^UT+_-rX{?S+Rwa>KRm9;8C zXv0yir8D{EX(P?vY7gvT+SC}$UtUpPR(%wywov)}8XyVXvIWY=%iM|Gc_GGcbgL2L6`F+qmhmdP{~FkAOY`Nokm;JSgAXYH zbex?FR!teNg`qz2@Ko+ui^-G`^4)T6G{VTn)Ie^b68avCbAF-S@Tio05yITxH$IWLm|T9W}nQ?@5g14<}Z$&BRtC@w1Q6wdD0 zLpuHG)h!PgL+M}3F?3sCbk~{^t9+# zELK4$=p(cfNjry}Y4KU%9`ZQ^DbykL3kGzXKM0mmH?0bI9ws1R<9UFubw(?or{=tO zP?QQX6tpyIw0mT~)nwns&6|(ucnLVl2>iD0#Ra~$ zJsi3or%<>6gR}??l9iD@pE~w(ewjfblh`JUC=}U%W4w$m7PK9#QYXhkBZG;~X<3R+ zVK81`SjuxPlRiVJ{*bWeYM}FL#>}RVxeLe`BDChRvWZcdvSP8;N=|Dfj zl~)T1Jim3KIyMTS-JU?aX25)SQ-hk1m3j%rK?V2`tA})*NSR|{QjXq3ZBc+Pbx`F7 z_0jU}BkJlD0;j+Lu|fGF2_ynxbh4@SGf4&uH~9kSTujmJhYAH@MLF>yeBqUID{K7} z1M$Ty;D{aQt&#yf_O)iGCX0$eg}B}&r~S54A)}5FM+;CW1mwFz59j8&QkKxMh!{6( zPBxtPN#N_2M*fOJcow@J?4$Exul*>R0|=1aGz!HzGh7*p?i)YEi2N2Jtz&t}I1qmj z@9J88g$K>SPn^zFR?(3SLpbv^y{47p_pz?ARRim?9tYGQkq^JLovx`mo}X_ViN()} zcK*FK23&oM5p@%!~mu zyFf2Lm>H3FDKj!wx!RY`PT-5Kh>Fd#}^SIZRUIliq^k z_|=4JXTT5FyL1%f`l*msu@0IRmsA;Z1G>`Vt`r{w5uMUeR1N!9_Ktl5wxoGvCId7j z8#d;!H>a>)Hfy}?%V=FoFfZV7C+ne(l7`vWf7Mqhwt54`z2~yWb@4MGcqEY_K7~|O zU0%OT8av7l32T6Yc4LfpV3MnhlyeTD$+c+yuvjQxi_GM?iJ@tBJU1rB*JD8-{*Qnh zE7!7`RQn{9}*kw_CPx2R|IL&9bbJQ3kTuGM` z)#BHDrQd*ZS^$pH^@Q!;`$obpotqPK>Glo-@K^bqrH@_vEP<@Gdx^TV@rW&F)rKa9G=h(j5 zPOw3sruH3)gE>gH?{Irl2SQ`nCt}&3V2}QJt6Y;wrPICH)7`a4OdYz4HI7^oG>!kk z1=xTKoCSEM^1#|YXpf6CpL?+}s+{E-K7MZOX%FMorFtH1YfS0Mv?}ec@lQJ}p3UBG zNv3-H*TiYOz7l<@#_aL4mC_rMlLAhZk@O8ieQkv18kn1bbRA}krg~j7Cx@PZQPBng zEt~x3Ktum7e-=0dy@ywR^d7Dz%as;R(TtYpWpdj@kq}Q-%m0RO1`;K$tPCbPlGl(& zqx4Tz#dFn@C$&%X>4s_;H0gW*o>4E&FRb+4+#27s$-7SqHT4x8@O}$8$KJ>nS$4^{ zpW`^JBuHPo@=VHOguZrYvp8IaVILHxBfG%wO@yMM|9XioM%Q-MM@hPs+eqKCqsmYI zc_Uq-S0lz0puK-rI-A_L+%7iVJWj6D!9QU4qo2gm{=`f{&+y5tfwg?ev9*IxiYbx8 z|6lCAc|6qX|36$(DW@n&WviT0Da$EI);8LZvQ*Ym2_f0CjHOO{wj{ERvai!(UxpTI zF@>=+m1ROq8H~Yjzpfcd=XC0GKHuMc-;ewL`s4F?bQIq6eqZnFdc9uH?Zf=Xerk`( zuFMeAN!kkrKPP!PTzF1~$C?Rw8pmoi^MHa=tb0T6%bNkiiGvmel(-><=Tmg2USN?e zo2HUA_j{AMlD9S5660G1s?%JCcYVYdEjBs=6Zk%IacA)5;iqk{c~1y|ftmI(=1l^7 ziR9qHtW#x>EM&+}>h}`T^3+*X0Mn|(7~!dI>8(6qvItgUq0nO`$Yg=_5v%2x=%PGt z@Rh*l&`n7a62P31YI$j-=8l!(W80{gz7a&P{@U)>%7|*<#YF!-LT(M}9MJbGN3w&F z6<9CnaOJQBc9VYtbsCQZShdP9Reb+o1I`_{2P)-FNed@U(kCvdXbpG=SNz!i{QEO` z;_BhIA|G&{#Q(U+m~x%1i=i7M|Ij=0`vPdn_k=+iS4{kmPc2r%jXs^H4KkIo{UPn( z`_gjC_o%~Ur4{Wz|70{flPwM8fVeBf9jFDK=%B z-*+G1ex0#CwC5l6|AV^W+xJ8uANkDSp9m|yFN(f>I!SR5``L*9kh8NAlz`xsJ7BkE zaxBJrc5iM#9j34L6BDNIyW?*+b6Frvb+-MO#mD_I8M>1e=j|(|tPoh4A9sTdV9L)N z&c5$!zP*yS4?y1)`eO~__r2G*@3DiSmyqtyoROzrx9{>CreC)oB}7cWZr|riOuueF zvYh{JJ~8E_nm*mWZOCwVe0RFVGCfOPT;qym^>%17rgs02HL}HZx%PVP5}PRb<727d zz?ljOH4P^fVVJd{L)BZr##`!nh54tEhtijRKsPw9%P~XU$z01>Be18GVdz<8902Qst zDj1EHiSP$FhJ#Is1sI(lq;n>3Plsegoon{qkL|(!LkbU}+*OFb4goTSuD5-w1$|td z$;l9zeefUciML&WC_WNJ-TeALU0!5_;!>4SIk*uj9$WGV-1OybJoC zr1aH8e(W(au-VD1;6iKf%G!2RSM5+zJQ69Y9HGte2uvXpI*VC8$;>ygVCX-Or6S7| zHL9RC=+(VV2f**))aeJ@+kiXSbmv>u`6f(RjAeOz!tnHVkdF z<+yl5lfNyA-b2Mx+I#aT2(4r`A7>Hv^fdeo8rV5?ZyNt7dwL6=qT9Lxl|z8!qGzjh+_sPRwPV^`qJ%>O#@ z?J`m0FP60S>lavW*si}d#~EK^V?58m&{d|}>@RPfBqBhtTDmmw)y-M@c4jxzS9jB- zudZ?gFI;BwqhKa@^zAZ#`}>sP=GPA&jDU}%*uRWP3f2Mi$m)%2A#RRxeD~ZWX53u5 z)?}mUsRPJd#&h$-lV4yx1mS7?GiJD_AKLUo^C*~p)28fM({I}J_Bgp5{)6pN z))M3pG|)4Jq12k>Buj{#Fl$IPE0yhXYD_QV+XNnEpHL=6bby#{`cf)Vg-DTdou1lO z{~4yuAU~9u=&dlU_Q;57!PlVMY7&rt1PkV5omcs-_5yQw5K~KQ9_lz%XwElNsj*e> z$KS?`$1$h_yu}#A-w1d!gPL*-qquSuzVziop&8`sBzN>SRM>W`*{(WjTe0B`ARx9~ zUR}>AKDkS~uNQ~0dcD6~k5r=Jm@A6p06o_j#_+`%qr$-eN)Kuz8oI_mQ#ar2Io62G@VjyOipfVGKTHd9 z?3(pqE%yL_hQ(j49w&b~;8%{o=e^jb3u5&P-bY`%@XdTF(sA0TF!WPmCXbkoC9nIC z6E8`Rg-rIaTAUF;2to8@jZ7RH$1f@k%fxUwf*?F7hD4Y$f0sL`=F+-_mw@=E$ikiWnw=s3mb4bNN(2+c#L z6RAtz-Oltp9MtQN0XG1*MsRx|+}})Yf!;gXbw{FCZGUG~qFGp^VTNU*KV-&)zrP<-Khme?cmR|TntnXr4KskctFbSjNZ?$$aW6cn6TCw~cJHZvfo6gT zW5TS3o?K^88+}&NfjN|!`H>&66Lfm!C7p{xngy9MQ_0@KslO%_$4q6Kd?FKnwL%!> zMQud5hQTW*wGeQTk`wHIaeqY~KRYBtfRH>P*e&;43B|okeWiP>BJf<0$T3kg%Zcf- zIHmB+FAl78l+Y#TeblexO?p86b;5Z?s${pLDb=X)9ev|%~#TdhP>iwIOQf~8>p zR8HdCmzf=fF%3n`l_Rixx{94_NvEsWsjKAwKdr}`&AW>yxd78`$dYr@z2j5|k?GzM zO#r7G{)xSBx_6vB4iRGizod6;O9cg+)9xc^q&CvfH~^&L+V z5pw)tEnS%8Os9eyf3$X@4xQ$-AOyqPsEf}i4mJ7}Fi2}7!PZr*+IoT4=bv;D6+PW!)acGIH z6xY0$bLsa>nAxY3KV2%ZS)0SR)z8SXCA3WTq!h(~9a-69cx|8HkXSlRd-Oe7+tqqP zd^=HSCq7BKuu2(kV`mj*JwmED!npb#T0x*?LUc-qjG{H%6~|25mrCRb_Fc=mTHi@t z*k7vj4X+ZQM#j53WrL5YUh=*GoLA4L+9`Aqgbs^{UCl4KnYNF*g%mt ztq66=uxz~7H#>Q&Ay~ZPV(h)0o72Iep0K?;$*w1@HU?m?n@(zb8@yE&^K7f##hoV{ z>L$DUr*erHm7g`jE}W6ypm?C`*S=-7_c>!PODRbqMW+)?kF?kZE- z-p76@I-zA9_Sru)jo-CC=B`L_&Flj0H<6_+L6O>H_lC>Vyx)rZBQF~$KjO@XzkE&V z0mAP#&(W~q{wfWPTYM5J;cYCJiYb`KCpTzv9s!THtLQEL#ur1zY>?-V(y3Lz$~#uS zj@<#MY8h+3bx}<+p3v39QXrQ1PHnExp61#7l|?r_OrL}_riba@77qYy(+J2kY&B8; zOv6_H?_-TuX8dcc(O1d3rfP~K1$w=Wk#v~FjI|H}4fv*qvuYx_BO;9THcZafl*Is? zJ$^!Z{p1%|knghne`AmGPR5#YY=M}|mj4piT*8+6uYt|6++!Mlp@w^Ee&sW#c!76t z+VzD;eRg_Wx?~yu^%PC!SjT?$3Nh;I7g!U(b${dh>KvRr72YHP68v96-yk0U*Lw(^ zdPZR)lKbm+tn!tGp1l8vrmqz9@uaQ>F9BX1|F1H6)UwR*eDF7> zww~1FV^w|%u=9V5v#(PA*Eo9{A!K07RPg}Z{ADQ9oJnTxYS`=5Z*c3Q$G|%Fb?fTx zeI@U|xmlpKiM@opsMK z{(`r2OL}r2UjxXrsnF zoz6fG#3cdW+H?=L%sv)z5yP2noDooVZB(WS=-0_39`45>rg zA-%nd;5PUa#SZsF1k#fwq+bG%2O-ohZ$@D7BQ;Y+>xEn9|i;YoN0+U|Dffd|Y=Epv{{{=E4y zjdGmp^7TT)*Cy&rfG2V5n5D5%z3w3Kox+`IRtSJ7pbGU|y1w1PE47vFhy+W5HW!)vF_49Mg;iqN2gvps?F7saE#?LqeAMhKiy zxUd<+=avowhI5aAIon0*xM0X|JP&9h$e)itJ+mOOU~V2KmP@uoIbwXA8xGU}Oko)X zp@I~jzoCLGhN}u%FzE2rtaccabHf%dI2K@m7JHr_JI8G-NT9|GA^Qxk!~~+iVCrAM zWB`%1pJdp$w9_0%zZAzp6t|24m?{vf=A&d8Ng})Vwh!0sAa_Gosn`wNH#O2SD2&A` zB|F%%Zj8liV9c}I?i{Fma{5)#XtT2mY|BCG9>HSQf`1JOOVMDL=F@agiD+pHqlV@C zVcLMF-(g~IzO=G`>^|Y6j&zW%VI{3Z%q`77t|IT3HiBvZl?EF>AN;+MDo`%*BENv% zmcervZ4nxXQ`OeEfPZ(1^Z2oR#3y@{!+t@k0HT5e-N2MKbHHTa%BcZD>CKV!@uRs$eKV;s51fp{xXnz%G|(cy5KI-grnF z{Ht8{19{WyW2B45nEVD}9&&HxtHO&NMzQNt>0zEW-~gxbz`ba5xZhZ-(%1{0P`w*? zxbnJYHhO$NJ?-qfDu|(oocM5cqlN$LGY1LgKbl0ler?i98q9Esxtg>3^Y9Z?X5$>q^2;Ha`SJ@ zIb(g;JVwy2G*I2~N<1eiAT0z@+j8`b;b`lGyeLC3?!^c6LaIqK#u;6;2^(0#Iy!f3 z#@@$|4d7zcLblqUv%j~?Lph!e#n2?izBPj6%R+?!a3^uCg&VH7{8%`YQ%+Lf5%9hi z26G@jvQe0wW6OG|CZl4qCYH$+gpU^z7ygzr-bT2_+g))HY*=ob?%BVDts3I!CMz{% zEo@N<-=^B6WB#z)V(rhUE#2u+5WeUl+O-$T zw)ys>z!*aAOjDo^Ds!^U6?Q%E+;s#SjE9pr2J8(IuWY_exeF#JkH5Sf$oWh#-s4am3kwM^>5`y33}40uaO@54viL}P)Nk61Jg_V;V{cql($gH$tzJ)a!(Fcr`tj>uh z9bBcnVpo{enDVH?cJKG?llIpPp=qhZoIfR3{VV^q0UnDqJAukLo(5Vx-?p2vM1 zShY-_dE*3FRFK-#nA1nL-`T7HMp-$J!ybW2%b<&fdq2Vwu_~3Hy|**;Tt8D8y@`5x5$v|IwC?O-~L@WA|D=iGyIr9 z*st3O-Gg8+@zZd#;6zHH3Mo>>uFbY{a1a`3U1lD@XV-rOb?{-ftb%@M-X6FV$rQL3uv7G?U72CO(>oBNKn*YSCxfZBNUD-LuHydD-7yT)4xmen{B}u4OCQ zfl;f;ysx(tJ$BB3-|Yg{;9(a}7&@uf8aNsp&$@8hLJE26@KPZMNlsO*?ileGz~g<> z@cZ{R>D>b}Iq9V&N2&{Rlp<9u;4coQFWc@x^Tr*-#s*;mFL^W$BGd8&h+bM(GK%R$ZPvikQv+SZ$N8t0z&(z+Ua;=U41*y9m$LP-Q4`?yaQM-ux}cOq z9>Gw$9xrcB3nRaN1tS%%wK`JJcLyD@*5Y$>Z%aF>D&PAYz-$Odc78U6F2H?PjL){@64)r$`#ZxitWNs$_v9*t+*;ZRWNlylHX04Gs=J?~2 zdn}|V)pK8}t?ZIXc^>VnY3)l;4V{QPpJcxVoFJR%3iHlL@H%r+@eku??d}OijR&x@_zq8 zyyLGkCzcb?a@1$Vz@50}|LJ+!=azf|)x8nFv{&FUgLnmld}GoyVKSh`sz1WSp#Dgu zenA{(7;jL(iSh8*AJs(`DB&-)LKD}RuI+6@;d|bYW>J{C_IFEW?0T0HU*3d!(qFLl z72uu}HhgUV92#(#~e1s zIMXKklbB9QY3AC^O|cQ$ZI)%m>4yvL^`OZ-mk) z20FN`QK#mV0O%4L=obU=qW{IL;-XoU@U?XpVG5hN=8YKp5JczQg_pLb#_aV059MO0 z;_T!L?x{wc_tcy}Gh6u{eo+jZuTr0ho{$q)9S3QoG5Y0`{3 zGBB1Mb-JOMafa3Y(!;AAt=O7jh)z-8nEWRs9m0D7^%R!#7u^h0a90P=dyTtTC{~I5 zIpGp3A&$B?A&!K`(K%4tJ`&~NuG4-8nQ!NvEB(W@6s}x^*o0LpugqAr_A+b^4_W1> zrNK|j&m(t~tc%`mWZw@vuf(ddn!U!`;6uI7br58jx(}Lm))U+um_bPp$B;X+_1N4o z2R?kD;)g{(dnp)-OBG5OH5}^;bX>XNo+LmP=m~}U!4vB0wSjKgtLM*v^?#kKE8n;> zgMRW06+1rKpN7M1!a(>Jo{%CNkEYQp1uvAW>U{D_`~Xt(4j0Mb{Zg_zf**AB8hn0D z?KhNF%#s>M8RRY99pxd{f~$&C|3u;dU2l<8LP>)GRYF65qqPkblRx(7W%W^t?rozN?+%wwO| z(2M9pGi`PHchAG@MeE(iav)N=^R$G^u?A=q=k&>FU#r`FJH#q#90i8jyd{1wJ*+p3i@=rSDP}TnDO&>4u~&5lWl&k%B#P= z-Dm8hPbE+I=RfTr-YW(fSdI$GoU8L?4g+w|Om}Hr^FEy8z60f-SY0dqRclaykzg-z zJYViO{94T#g=Oa{sAsJjTVQ>07qivxHl$@Y3=N21>;L_K)e$ke3Yrq^j zi7FDR6+<;#~|j!*M|5ON*{e!8Wlqs<%h(T>Ql2DrcUcsFGUp} zCzxU0%@RJU@NN}p)EEdsou6NDX@DhZin)O`SUC2>z$4#$Ot@Y8T=S=OK6!Z10}(s)4nGLQD6WnQX`;#}uqxzrBMcnY|US27@mv>*N_w+ZwI z0eQwC$#n36ZnwGh(?<4~I|bfXX5`Vr@*}~SPnOXitEARli^KM3e}p9L;FR3HGBoRt zPt~U&A!*vg-mv(e_XZfquO0N0{nniyx>>M|OmNYNBdEQStC{D0+>@2K=GP&(N3=j3Bs{uTbw1+MJU~`=lnZ03g zP!hLsv2F9kRxhGp56bH7asPCq-*V3jK;~{=W_8aahyJ;HhS%^0=F~#AuLFd;t0gOt z7k++&_SI+O!2i%Df$OMZzwWt?z`CZVln_p<+=C z7YZbIAIWeJL6}cJo#3vBX%{nE-j&z!>_tuaLd+$$@k`9@H68l$pKY(OCdOccefUny zh+cMALh^O6v>51sHlZ0b3fVhIf{^#BRv}vET?z4uASsjBI^>H6)U>q$PrdsiQo351+wZL&&E_Z{8M|-flvO zBBoo9v>$SB$Fr+~O$p&)ea%{sVEWO#1zGKyfy#_{r4FHBD;h%_-#@=X9Fe8I-h3pT z;3%&EX0gZXX=~R!5`~BRX&;8XRx+H;9`1o$fdZ|`zk`6qf}MlrrkxOATvV9@!?NWt zEtx;F%i+#W514%&fMJJ(>~IY;Xb+tNFh+t~4QCk-_IKN_^C{LFFju-#*yiP;PF~!_ zJXXB)1hR4%9FISSiHo4UqWMVbv92ku7|9>^;R%I70BS3h=~jwNDohI!lb zM%yJwLVfZil+zp5wG0P*O*;fFLH-~qQRsD*MMW>|Zr@%(qf++r@I4Qs@TrDUEQF@y5JF}BrPP8F3|iFD5st%bpKUEKHp9vx)k;!PwRAaN4PHoOWBm zaA~22cM-qY?OhPq;N0hr)i(&r0{|*v$N(KF zvujHY{UH%pb_@cuQ@5*HT_W%WQZ1_CbBlO14TY1s-(M3B_f{CJOPJ>d*!z0XRed9` z77RKy*RRA;FL8?3b%thnQcyi+f5a1!joWWk)}IFV_yqC3!4?zzQ1Ak3;n=x=Vlrnw zJ(ND~_DZki@UelKI}$47TW{Q{GVcC;%&^ z@3hCc7z{iLUvuD|mb86Vjiii)u-%&-+CA@bS_V>j%KP0Rb~wBO)TUi0WU~C^Yxz2^ zwYE9q;bhJ+|Fc)xm2$K=h(Fr4*~qQkxp1!HXHVjgK2;{pPw{v$U%koY6`iz3>-m3g0{)mYY5r5$5{BL!h--zC#LuEZRpLabM(QPGHYJpQo*0GG-WVvGA!$ z%IVi!Upf_5<hA8;aCf$E^&EW{Gb%JEPl#Tk8iV3UvzPBq`SN<;;agY{;U~J!h>WE4 zOR)-ixVJxrC)TkC<#I}6~%@k#7bKx;xp>#)jtY3e|$hJx9T#K z)x2*cyWF+z#5J=h+$>vwYu2x4EyN=2pDjd!#+$pa7OP+_O2Pd?t=|5{uomg3y!z(~ zoL3$$n5%e5`Wj`3J6Pap?mZfwmbbokcE{X?w%7#nTx#2Jo<2`dNVki|9E$X7a_~bS zOjuh-QNlKl*L$ng^Tgi*u|Ks9Mh zJRcU)>%!IBN&G|HAloiB4gdLy#6bz?x3>E>!c5Kmd;3F#z%Fo zWjBkWjRegVYoB5npZf0;T-UN(7sx;(;C7wtHwtOtA6jcG6-2mzdX&I~}@L4#z-gLq5I!jr7k)o#V;F(Gjf~8{J zYqx5P(J2HXwcqclGHH~#xnMo zdN5L$-M8RupFt;8?Yz97+s!#|8`mmF;8=B-FxSs&RaC7i?(0~|&4={Q%lCOGyL&bV zC}ETQ#!{=)6T^+eyFXn}GoW}XX+ zMo>Lo{aJG)lx3Xm=f@kN>U63ijzhe7kio7dx(D@SLp0qE2k=92$Y)oc*8$5 z-cUzr&|&nW4JRtQs72P+vJFl&{k&rRBlkmIQM;i)I6R;nec}Uz*;~ojk7qIqK=EG} zfTe)v&L%Y#v`_*l93j~7aEYBV&3mzg`W$~#%4l9}CixbgZj}@XxA{qq&!BiU<)V}V z_Nk1!)oT}sYq;C^TqXrryCB`E84cT<&9-UGV47R z)G)Dz^f+dXZ?`}!QM&14OAYY zBc?zjpCXXu{Uze^!h{v2wp5xouGD82@_4?k?*06y3S?QrK2RWOl*tH{X!sJi zmO~aOb@22-o!a`%uiSB@Zd84!b8&R(O32oeD7punp|#ZE(k$~DfF4?XV8*?(nA1G4 zvK+S5npa?z+$$Rhg0*+7wR}x{yAQWOqZ&Kv@w-NpkL&gZei3(Zcf*XFUzS4=?yCxR z3HAAQt;f+Xy-UH3ve#Kd9j)Ek(0ewDBrTOM3iB(_oiG-r%VoE5){BOo-)SFM3(_Sm zK4(;}_YIXA*7uUedPs9xmP7=oSs!L|ISLy0HbR+?TYuzT%F9n^V2N5|?T4-~bzF6u zS=sFF@el8hLPe{26j%K6-5v#66AgdGU#tA76s&f`%pF}d}tW1#n+dxwdH)Ig)8Sn5q3BKMVNC}{EE)lL!o)vsBL8- z)JuQ1wNg*;ceWEkhT85&ejSvp<(oLTW5XPdJGb(af~<1C6eXxz6$fYMK5rpqq0_O0 z?g;7Xoo)Ua>gYrYMTJc7pKn6M-1AE`xCl6ux7~Sy%cU;L{82>X*0?J?aHC%iU(2A8^37`qZaK&0p-mxm z3TU_wS0y$SBXyokUZ>iuKzTTmQ~eZ`lvf=$s^2YwG5m;X)UH)r=0y2ty8*Rx zpqiPZ-dO7|QI`L4kHmhuda|sPuTj=xMWaK_1FMHpI3o4WTeZJ{*-_3u7@1mKa#+E3 zWUn!dIIJQFI160fR>UkOQpQFr_bOds`;-iG{#4fa8=~^F&D*t31!RqD6`eZP0dpa@ z?W3L?Y~Mw)?uy4mFez29yowPWczBeoWF&1#Gn^}Q(U=*L<V%J1LYJMAFt3~>Xe(eF zc6y6AG&)#XE;$+vX|s$Cg8YsW!E0n+wedu!K0?K1mByb|T^6BbNAyCUI zdu+HnG5?N)mLklK_A@8$pPsy`gb>%TzQRVJV~L=FelqOZKo2Ee`Is96r%x2*z{I+e z8({XM%@+uddpyJ0UBjvDNCN+i*FjQ17!IL43^sCd#eWQ@mnQ#PBc2dY z7JOQJHg=Wd74|vc)9OzWHPhj0ktX1d*!%O%K8#6QYp>=yO%^^v@4O)(1CW%GK$j7VGLbxV{LHvY=GsC z6SsL+?!{WHN8@WWo zVW!@C-Wusb(J7A|D-12W(7bpHVA5UgS@_MhF&)8`Cq7i-AOJ|1TE47LZT`aTA0rZE z@w6GSr61@pFIH%$w5O%aFtXLH&$d~65j1WSmM&kVRemM}V1 z!8hJF`>m_z7Cn?KW6nX~6QJ&?ZYdNx5n6K0O1@q>j|zf*HY(}e@h zK#kQj;3(%yqt5O`Ja}zehBwY%Lov(wFk_LbfM)a2l|FeW{%%d6{$VcypPp*gyQZ>h z&!X5J{L#pry=M!1jBh~-Snh zF+&)TGKXK<1|QH4lzQ>Yhprm~SvBX2DFSqfj;pj$au!{&c3y|`^U-%0#y;R7h5CpL+4wi!T?aYm@mD0DIm zyN?g9S>Y^Rb8R1@z;F`HtMNBU>+HSqYf}z&%QAj;3EnR{Wx){{{(8q~A3sD=8~F_pUw^`qi+H)yLuVytklkI*7qcH7 zUG4b*=ET3Lbx3f3%!NqfZSVi&NoYIe*3Mtk_PdF?)}RXnwvVPiQfAu&naIE)q|Jo? z`)3m4}vVQ%kb~?}pTkwxJa|fBTtsxU^sb5gSS=YX9oNK$7#jZf%F@OGt5-3-z z!V&+}A$R6qkp5pW4IM5Vh8)h{68H4Xg!#40jOO+8ZfBtn&>7`l3A5bF_CO;;7st=J z0$%+lLR!{7GdxEohJCHX13&tJQ{qErcQBrHE~BcBZ&sCp^=7ZKOlw?9G%Plm3yNZ zSSAt;)Esj|%tj4rd<52Z&=mw-KR@dXGV$IAYkUWzO$C??#`Bqs9u0XZ1Dir#WZ7u) z#nw>^f5I(Y?wZAcw+hBag;9O9=vct)h=e=DMBU=CJBWW1w3;mvcrfp2#p`23@7xnN z2!=S+k1i+64a=FDJ9TiZKP&B6>kz(KqDuCIQqWPB)F@BW0L=7jPYQlD)BoNbgXIeO z$4$6{YM@o%678fpHQkzse&PqxKs6`;V0kt|7@GY~Ibq6FiQUdNB(YN?{!C&wKX9i? z-VQ}!8}aYuen4QtaT^0Wrn5%R+Hye7{+?G;C>(OGTq~Hr6{LisVRnZRRYcFyw=AC! zspP1tZRb6OMu(<|Zuibc`P>HvS3&inWzpObocR{EFjYk+C_bZ&PSw{P-e+t4)%tPS zc2!r=rz~<@o9s2)vdEmzBQLgJy_FL*8AmqhJi^j0GD&*Di+z=Z)t_+IK6e>cB#c{* z90xa*L0!H*`hon z4hXsAr3U+^GL7`(#`XJEe&}EV{vmyiU7IVmMLKr@$)UUGgB*mL4~B@74e14SJkQChpQ)TM-7R+rnyaMwE$F z^v(ZK-|;)Fb95&IH&~Bac=z|9Oq0u`$w?|?t%`coZ-q0=Kknu17Zxs{jvVZC{TuZ zsT?oi{ptKn>L5o_J_C&%u2U=7y!gysyi2S@eRzn17}hI598vE4^$c8v|}d5B!*H z5Q?DbZ$5Bke-4IE=UuNCa$OvBv}O&h|3>rk+Kh!^B_Fz zBMe;O-{Om#XMeRe`d_onak zhZ+~3^Hlb=zpC<*X{jTgJ`M-mmHG0tEP`5~{)K(nFdw}+jE@3p`Fmcrm&vy`YQPDX z8}wrj5PR71K_JJok{j8LtXsYdz$9K@rP{ql8IHf$10`VsL&pHfNg(GW)eoI}9Q8zOC#WyMfd%vcCv~f4s1hqbDc*9|~7d8;XcyUF#E} zNVhoMgMvf~!nsQvuje85a*-GRE%V!(?$wXx`%F34T*cIY}nIe^t|Q3>nkqESqrBdEY6x3a{y*>+~g3h>ql za{(>*^#ZyKAFYQA4&WsqDLq`J59G~T(2uDMml#4O?K*qg+bY9WMfR22e`BJf*SC!p zAYnyTxddp8)`F9UsQ)QrLrAZ4&C~DzG#W^SJotyz4eevK0my*1J-P=8d3SNq>5M|oDx^XT9rT#*OK8$4O z{GcJ-1O-}Z93A-mRq$@aMqS~Qu2da-0HWyl5R)yHj+;~bQ}+KzNW4;Ft4t*!NJ=Ek zZMd^jREd5=G&%jrtb;HV?_CU@7Mm*(Uq1yu-1Q+mB|GPK*fr%FZ1j;z6F?!h*mk_` z2YyV%ZZ->`U5K#JOLs9jc8ED14b3+%9Vxk8H~(5sKlwpYQKfk`K^BT#)ID46R(g&1 zR}xl9)H4ABuUPmj-M?Evwd!-caoNDQEYu&--zKV*mHjkAv?}At0{9Hdx7ZMH#N4QW z(I1|Y`QauQ%h+i|TEA_qX5Y_KLJ9=DG*}(jj9UQPu`68@7=^H-XsM%6x*ySBN!mAF zXX2yAXXI*w{OJ8OA_=RiK`B)7YnikGD$l^$y#XzoVQ(u=%R z6*gcrT8)j;J3$h^F8zjLD>5mP`t^PWJ9U#GdUatjQpC-`*CGPRTy6wI;({PbfBl(Z zQYJ75_RxYmsqS1#qo4b)tIDqyM7*)8FhHX!Z{9+}cF6=~tGfi5@yza&oXVTLVwDSI zntZofx9Cg1rKHswhN~!TNXl3BP&V=u%opoH$^=axXRU#-PB&VP5%F#?=WMizNUF1q z^kf);%18&fs$`@27v&&c4CFm$d^WHzQ+ZWa3ERSfTbTnB)>Pv@c`h^46E|?p#k2jX zJ7Y)cl0VNXFFE*UU))WOKh{J?$E4|4G}_oTBvhGOV$w_!$1v5ZMmlmjf^s@NsrISK zA95a>YiqTw;$F<=bpP{fxmB0gx%Unc8v6eXX>zF;t2j+*3(a#gEqYLX%rT70z}r_e zJGzq^LO|{{yP6QPR2rP4qB-NRfq1r;8pag(69r?7+v`yf$#X~v+dzOWJNqz@m+URu zZi5xBq8&kjmRhqiDCB|dE}z;sqwU~kbGd0Y=h7&!D?l!$>G!B;BqB@jqF73YJ9`Ze zR8M-^WdAM8u&%`QAm;5JK5fTMCs6iF###wc76sL>u1DktCWll^nFgrvzc9yksP!;2NiSQfc91`1&Elp`p1+ABAH z?9DDNwX7Xx**-QyEnY9zg3r?n6PA6Fy1p)i&?SwX$${sdKuM1G27@Q1Kb~-sda@Q7 zgH@6lj4p_KT2%%p)V*#E6{=S3N5QG8A=};}F)b&(JG8#iVz*8;{J6rTY8V6LXRiuzXk1Mx9dKG zdyejg6|IIm$<+jg_f4FDPLcy(U1Rb2E;2(mV%TZ4D&7qR70PKdg9>*wW>{M%Kl`1u zMnq=tqSx@Ansja4B4dDJh=KMhh$7{AskhCo%@_`1XYJ^k(A)mgYjdU}0}Y`b_lk`se!Gm{cq zW-AUhDU)vfG45^tLC(fExb}K-e9H|@Iy3e$7L%1SM^LPg#1IiFZgQ5b#;o3LHcb-C!ue<3lQ1&0jIyRaCtKFa+J@(< zjPejRoQZZ5vJD2G<4kwa!Lc!J)s3{SITPWM0fuSMEDC5=qnn?b+rdL<%_2 zP>%blQ+#gNL~QY9oLkkcyK<9UfXN#VBduNZn*x>wohgoUg>jnsB@O9ivH(TjLX~IG zR?CLp$(%c`8$aZ@$X~J+2#R65tb0CSZ-42dscUY+`#*fk<+xA%08}bLW3) z`z!&nV*Hz2R60jCgiqKuuSrUbsqhLk<~5SNtor08%%O-pA03mH@HxXJ*JxX@X9DnD z1)xhpetF2SIOW6Rv#?@wFWP`{hzR&J#eh$fyWHHx4EJ4dr*vv~#quo}UVl|SCNp)q zdk2ud_AbG=i6w1q%S;v7xzrM`^Z=2HB|%{jEE`y3}|SoM)p44I}AXZ`-|)0R`Aa zC#@jRA3XCUd|^?5n9E>WcInz1dBXcfa6$Yt5xsuvxw?V`j1^Au3|kl3xl5i@;K|4$E3)7N2gvSD2OuYqyUAV{%}HwAptaz6Q)5>o_a@5X#k~?IvBf#Ix7I;COqo zQGUypl-A~<4-ntTHIwx7lymW<#3qhM5DJnCQeZpaV$w%km4|Ib3cxj{64)1d$<1j7 zRc5yt;SeHEJJ*mo|}H z^8IB`v_I0@b-Ku3^ij16eyv0l+DLmd*wd(IAt^ih`9-1{(J<1@FU^u@!G08V^gzGU zd*u|XxKf-=GyiTLNeVO0#OZ++sps)PdyYa!+sKCAmp20_gJTveW!Ty{RmossJKiJT z%l8|>YX(RIa9hFX&`^4Vr0at)-By-51F6;HFb*@|ny z)um0caM50e{Y2B94EZys4GJN@=7Rno7Z(f(@{Zr0pcbSsL3<*zTUWe1X^8Wq-#KN8 z$773aA3*2bb-di72xeK0^*fY8Gt$dP@rkpQ{GfV3bQ`AyZ*?m}Wo79^H9We!VA5~b`Fb+*6rm{p1N;ND<4 zgtRR&NL=dnL{X&Zy^GA^&~2;tbD>laac*H*8-sRA{0JpqsTqXskWi_HAl4weq$OCo zpP#`tg0D;^?&#yy$Z`qzC>W7(8a+ZjEzAe{uXFWJx`J}bO|Bw5>y5=rr7z$e*+rHT zb+=tezN?zSXzrE1`s#-3%RJWg|D`N`@47niJ^P2qu-M*v(0j>a{rtR_Ph1(`i5hte zr{t9+Kwb#~%AD>()r#^;no(W}mn8|Gmo~>A7z(-OU0+rV+)A=U4HP2Z1E$_`yh3hZ zrp==3!&e&9B=*P#Qhk+OeJQ)aO>}7QWUF)Y*uaXJ;MaM?a_AiO(kZ&2TE;Vld;*qH zk5!8ey|6zR*hGlIk+^`*NfCG%9JlW%w>)wN9={gp7?PlukvCd_Wm?y2;XF?FHj<`K zhn&=6Tgcs$NAagg%jOKfQL-->5iW+aqhZVpY1(@1%*FxE- zY~==odV|oz7ol1hQ-xr$Pm~@?^VTtkib?RxZrs5;DNQ_7qSR}KQ*#^idWH~JvfZ>I zu=aXV!!;CF0=-8liYp1L8_B6DUwJYs5PVAPc^yv{CV1s9ND}KV%U+Q?r(q0};-=VS z`sOTrwrY4WYUeGWx$;$9p?N!ko2MdQuk^|8#9Ih}yyp@LVFC-Fd5EV1B4UK?BHJX& zKRIGghU5?VyCMG6dC6Oa^5ljtdNE@vy^+k)uGLFM$5Gsm`b-ufTf|=>TMxb=TOv*e z!$_@=MAF|?k%0V`5HSA1gL$ij=eLQ4VjUXHIuQo~lpvO9%d~!2TOzY zq6QHk`9ByS*mgw}iQ}ksT6C286fYNmwMQj5(;hRZ>lyCGVF%9)i@Ro!RUobeJR!QQ zZKZKzV%uccHX7z`vuw)r(|&ik4!j?3(3fQ_QTR^~y-sFd z`*?u7SpJ_u-q3^DRXdC?&nL8AO)5)6Ep-c6fU0OHGe-SFVT4c{%WTC4o-GFlJ}c9? zjPo%nl-ZuJkSn7PB&sP1O{pq>6ZQ3pm&pD6yi46G>zI4B5S$XN$=!1gCMX%8Bw8(rz-jUR z{64Y#JNW)+iLA@EV)Zh>p>)w(NeWO@0tQTWhEYTJqLptnJ)Ni>+J5ahZ(ZOP8aK`E z6Wr<6Q|q>g0Rm!2d&l8Qp{Tp$L@m!#}}ZvW%$Wfu>AG!_h{}R{&TRi5uaeL~LfG zN43L{2ko{s_k-9WtpvXa=_4zV^)#aPQ9@+iX#l#`mGkniD6P zeWYQpFyYrr<`DXXqHRuW>Bdz=jg>rE`a>Q>T;>Azi*1P1#$4QDG4}C(_Wk_?zxbo ztu-1HE+R1AS_7fZNwXHs^MrcIhhr4Qw=gYd(Hp(gKKB$ex#X8s66*|b3P;H$!>r^I z5MeNy1UtKHQihR%6E*`fG_t~$+*k3qbZ3*+WYg=Z!>*FH=v`c-_x@O{oAYp)F1~Vq z6O;alUknu6a9{Aa4HVD$^yJ~zt36`YxC0T1Z1iQlO|}Fzl!*qSo*wg{56tur#0)~t z7f^TbGOyhAnZ*RyUkd-vK`+#~w39ii>L z32EHtX9h05^*e!>$}G&e&+akS;-87CrT)}dg-uLP(oE)tgIV+WsnW>P&exj>2azS= zt%hakxZFH(6kKAGNhK&LO=grBEI0yO%_SSoBf=_*)v|2PPK#?@!{6D;X(+-XtyU9W zy~?@{>y7n`gW=*P!X@K?HihHqlSic00TyW$5-*0cy!!1ebQwr}PH2RHvqchMk&+b(lIpDy&+W4FAIngPGNCPoFkDG7la;XS!9SUA<2a`>Bg1Rbi7MaF=wAekv1iEvACGt9sfk$7Yz z7k1t9o~V+)?Ya?*zKKUvX53=xhqg@Uhg7tcMc@Ln)8ZF_eu%mTan?dHkH78vaEN`? z4;`Ac+k#g&k*Obw13FJ_vh@IR#8X6DkgeSMKmK-Hot@0X1pUyWf)C6ItJj2nNR#&s z2V9_)r8!s$^|_Y94PRqw^y%wirv@|IulgZGu3_ni7)@R9V_w0(hBe)-H@yU=m%#Kc zFue;*9|Zpwd+#09WY)D03!>my08vq?ii%?a8z2G!#sZ3njshx8#Rd#Sr36TWK}AIc zL)uec%Sd>kXoCs1-i{xHd-(e}`{ zTwI;Aw?+Bc^-;oTa>FCle`(&GJ8z3gDFL;wD$o`}R&W+gz${L^5sq17((PtrHBnjT ztSiVdjtO3_@ci7ELkYfi1!(L8Sw&8z7gitO3>ts);n2`EfdQh-5-X_k6$a-(;jFoA zfpoQ-#EJuyjCC`IQI+ze`^tBhLxcA6QY(i%FV9@RTEB#qp-jCdm(9a)N-FIp*l;|* zb4u$QoAWQ1Jxn3~I!W9Ilf*(yxMY$TQHEiXc%~^FXMLOk+jPiLa|SsH(3*`iU|s93 z&&zv%iZJjw)IKf^%JR7$^=Z(R1kFevNPqJ#bG8u89A&PPKD#^qG^=kspYSCA&p-|g zN*8Yk((`zq1ZY%l;AZeDQBJ)Jb5i5afd$8q%rULfkB2A;XhOrzz_OLjc*|;JE($#N zZ4#YOYW#aD)V`$-js@!QoKp}*fWQ-^g7j9R|$0PnV6K2nT>8HbRt`h`yX zM3#`42xhGLM}VU2;TSnfv)aq(EqMJ5bb0~WUL|UtqwgutI0z$iC)-@WYq!v$b?DscW4qlMs9Pe zBFyW{ay9^NLB&Ak|McrF0uSLWU@g3V`T&|lzczlBC09Io8)P-R>@(t{j&3>lz{Xts zmQ?#}{xIQPa*=l;5om{Y=$ngxRUEl+e%Px-()$OX0t_jHj=~}k>VX`(TSSOHuXN~j zqDf(b8u#&)*~Q8-f#=2`fqQ+S|F_H*?e=&xc$q+xE8Qr+^`LN@{|8IcpLTswhxF76 zn%`f*oY|lp)Uh(7hbPe?W9*fg7;g4i@{&mJqFGY+zqoKwSG9Zf(IXq6V}E^pSXvmG zMDI{u8->zV_gLf}B1xpKu7j+3>OCFgRgw(%Q1XsfCsUvWsa=BO8Gr&%)&+SKW#Xub z+|1Xp*=u+>G7rZ@dW?b(WthuI>u*XzDAGK)L5h^=g{`1vf>jYPgm3|kQ{mDx31?11 zGL0nLs*yNuht3n2*_mK{OHuR5eqa;3F1o5{re)SxRf9xE_!l6a_&pBPe$rv z@G7TLhh9-Lblw|p3D*YYdnOWVEdV_@i4nuuY6qUP3IGN6rr8dgP?gk3q=5}zo8Pbd zXG{IG>HgM{E7`5M@Q$J;WeMqRm~&1XNb?z0gN)uK9VGOF^qCO}C{T1t>%1ikW>~6E zYbUP0tHLBV8<4b+eCcKYks79NCy7DTZX*(UPXtY`4=?MM0|-*B^hR!(iGk^Q$ZI9T zSP&hYPWYFp;gZs`OV$WsLTc8`yI^4Mthi6hY&dVX3I6B8f&cgnY=evi;7_Qa2)R2< zTV7ofybW;tnrH)CeWVtXf`mV{B5$S`REeuih1+4yFlzj>`$)t4a$eE=Mgpf?YwsJp z5+C>4Mcn6-iVOgp0106R%c@(VX{%}&=y_8&7@uaK$2&$tKH;FPw+@MGgp#^b^s9KZ z`h}Ub*Ovbz91gOenukml8PN0c^3qNnu}1O{xV|90`Qw#0s?U9&AszP3^v4pJwz?B4Pca6ZtK>A9-#c zEqtV0vehUYRG7NdpytAteM|=oBDg{B$g^38B$6|&uJ?wJvs52-sF08rdXC$CaW5EX z1n>P?Bd+{GjfkGJ7JAN58zM>KtJBbPrhxt?6U5>zk)-ESaDFhwm;hvv5y(A8-^)6R z^yE}>Ek3{HZV=Fi%ITZ=g$2CTARt@yP*x)z0RcW@Abp1xYhQq_R_^)++8{iFA+<%-Z5;5=a>n_$Pl2a2-;n z4m_IV~InD*=>SFp<=`)}0uLE*8316+gXIi48WZm06%K&E5B^>@bgp z$G)V}VNz^GYrxw-0R>u$@-SdL@vzJr5aUvWfBjQHAh&EuLl1r-JopiWsdd8HW5S}^ z)M$gH;V;$Nd5&|eu}O4q5g}CYc#6?)^H^q723}YU?hD*{(37umYUkON2t4h?QJ|B? zEn=AHB7*=X=nb*9YIMQF3oXw*$6b3T{M{Z&mN4$tk2f&vt?*US`#%*0W3c-xaYw0O zIxu^=hM()u?dCz)_2p3pwXKWO1K|XiEj?RmgO)sPT=2H3F=>i>n!s%cCfgR*nSLo9 zTPXUd#Bo!P2W}4RL1SJ06h#%9l&9R)>%?@_0RM0yU4Bfr1`?P8p3S_pfTy^ z^wj6gi=kUhUBY@<(}9QFbgCeo2^I;~D-XW5l<5442kDgiSb8Gu%SnSB;u1P(&=&Vv z2yQ-+Fz1f#I&%%zT8%6Ywm?92e5w806qs7ffl+?smBZ}~Cll<4iZ#}BX56a+(+l>? zxejzN0zh68n>4_iw+fwI?mH`eUtE~)24h9c>tQ-+&-4QnkK18<7A$p!)2r8N%$VSf z(!PLkg$>6^4O zhdYZeJ?5&nX}shVH%-s}kjX;&fy_FOY-=h%j=HOF6_RsLZ)4%2*%Db!du{^*2eW|5 zNc9|PP5sOp*QWlg-8JnTSIHm{oHpn-$jc^CB3&wxPsFw)>VMo=^fXen;hr&f&6L-7Yx301-#SY4e1{W z=WKHjo)&^~tMhXdoS4WPNPs4RJ3ZI4?=nCRnBJ1u3+<)l#jQ)R8<8p0MP_^l>>R6} z&&B{%FXACXr`;O)wR*g_z^W~N+q&1$YB-&-vKl40&6ZMklku!o@c#Xf~GS} zgZ0f0keI@_Zx>KROp2Y#6VB;wLel_PvseLoo7sbjGpJ~_7V@9;?Fct9sA4E}2W;oR za_+y|@ub%X-m8l?@r*Jb{VGa8+m#xqD1KQ(4JE8Fp|S|L2Erp#%FRlZL3NPbPdNnQ z)HQ8_-+UW=Yi+YX8hs3eHew328F#pPX9S!F&57hS!6v;X{p@8h>Fv%TsMq7mjV&sy z&!;nD>GtXz5X#K1i(#4Xc?YN4*}#)UrqXzqt67RydFKO9&>`I@5EK(ce1`prUV@Yc zYMJ?L9L_lUGX5DU%p%boEMPg)LDYTYO4(owm>0_&4@u`V*uMc(*uSj)g4*J&g8bJ= zPXZ+$?kkVcGKlZCS=g#v@FqKAl?Ij-hvqAP>Bf@rlA(O|2BxzOty0)fX)6rOx9@$q zI9v5WqzIIzv)Y~;OnO<22k$GJfU&re&s#-QBtC82fLnH0ONb89W8wR07ZY52OxTqz zB`*n&;|ce!$2X^fk&dL7FBVe8c^=I;jOb#2Qj$?D42~bn2Qv6BQ^rqMBi@NR+33qq(ynS6f9g-vQrMfPg2Jd@;J(;gN z+t%v_Zkvv$wbKeCx31E~dnHv;jqtq(%HqWhAy@Fbs9;0U)q!v1+|xU(MZEulm5aM^ zOX6Wu2LhkeSP>+(50z^$5F$`c`uiwxdSSleRow5~(y{WJ`APdR=5aQU+7`$5_b5=_ z@|HwUfSq3Rj90Xm&@}!FZDS|MQ)`0*)WIq+H>p}fd0lS5yF8r0*2jt}wDma&?>UWK z9M>kbF1-C2wTnZv34)?tLR0hodav}JBjl&k?YjgF=5I-4unckXtQri1UQEY+5lE>< zionrn4U$~EwMEBf)pPq}<;qeq{;lt56Fv}{j3^N-&yGs$BJ3G)Dh6ou$e&4QI9m46(q-{Ms6Cn&4wn@LKPW4x^KVg1i!KN} zlc2z8iaIz2dP6`Ho{U6Mmc4{tejqEb*e9QNWFL0V`Nd^yi7fTGHyYqPm|mDBUyuKQ zFK-B6eN@R0+f%g57^|w`V<8|oM&Y}W#P|-C7x-|m7f3B`Q8 z!D>mtrjy@tp-wjnk{iwfvB{tr`Li-Fgw#Zbov=ApW?u>rcU6jhGpMIExC}KZ zS0gzECuP-`m${eZL7`yPJQ#yzUpmKORBsTR+-kk{s#!2$&K0N&b%}8F$-B%dFw9`~466NZ z(dbZV=7ts3cE(^Wr{#aP5j`}AB`hDyKIhL)5f_y0h%3OWyyA7)Hry-wf-FUm^my7t zv(`8^0Swn-*{vyo=SH?joH5i^sU5Aa!;zFeb2~+_WA*}FyenW!QN;UQCg%;?VmkK8 zeq0?}T@a5a3BK+Ji_!N(%i=3-lRxrx82pYjBp#GfRM3$KS1P7tyT=-&k{L$yk4trn zt-tVpN`T1d0wOTJ$?r~w-`eti3rVcsrN@D+%td;iaMhrKB)^9Bj`w}m#| z9bCN2l#<5F;$e}RH?DAwwQiPkcs&^QR)g(Khx_(HINSo71=}ptY(0G{<-W7FyRde^}{}ZhFVXr4_k6(I9oV zQ>msy4Q+3*=Y`5UtpGQ?mJm5*HG0X^IE*!{<@30S#W#FCo^Z;c7l@#~MWcd31BY8< z4XPPRQT#}oq1MH}_p5IQz3FC-T5UF{wluO=z-bHvCE8B;xgZ|IKi6$2E@`l&8yT7^ zX5cRH5S9RLLvcu+cfyS2ir=^Z4hbz4+QLDnD}G3L;WTTn?&>!$WuGU>q|Aw!IEjB< z5p|rmmrT8fMnn?92F~sT8)?TL?*%)ig{>1`7z4twWf&TqqZcCK91M3`)BhPXfsQU# zEw?z*Sy*)1Cd05m6F{;POU?wF-9z;h)?G`8mT)Bp{NXUIP7gyrT2dh=xHzbs8rTvy z9@KM$_6s9J^d$=TQTi>W$Vw&~-`JTp^Zsuif9*490F0#OqyQyw)igK>x)7HQrGP%~ zcOA0jFv6y{&?*~TVl?18@@gm_ps7kSF2Vy_?B~cNihTgHm`pAx>D2(`apXePH53$9#`6Ov&T=2K#siRFG#1n&N2}%#Zl|z zXz}{2iyjZSr6$;!;1CqUVgW)GxZ{=E2RKyAn~?#bUwsAzFT+u5O~qRXPMfQO3qs97 zVSJd$QfKaUXhknpQ4T*ui5(j2?*CJgMA;0Y%({u?|&HJ~LDIjXv>>HpxG zo=zfxz2?o=yoSvpKgs=20>l&-qKS*!Cu%yZ>wIxqb zIP5fBaUhiNpSTHGq{P}tph!>vYi5+M& zY4{e>lLl(Es{na%0PY%dvfJdf$`j<~VXN{)o2GiRRwafZ0+{g)PK(&{b`V_ZBDP@o zEjf&X{mhK?y|984rBvZWs#!0C1gSda9VX{t{rfx9Uz=RW#~lMiAf5dH+BHX<$3vWiq^uIkmNa^9&+;04J?GIx zCC2mo3TLIkjh)VqIo*(rqA80?R|A!(8Ugb5aV0!(wznZMlp0bK z1KnS0Ba_OyMFs(5iL@?1KP&oqXYrh z`Qrn%+p%DF<|FK@wbypwsA?zr@5{|Mt&DX2aL3i6qnL-v&cN^h+7R|o{Lu}*(e*{a z#plj(b^RYsL~4Br>Y!WgQ)6on!b92oZZlmOy%iVMi?|QCQffDLn>Dgbkbsu z8HcI|9zH(m219+?g=`F3BK=l zF_(u2Y_8!&V~gu~tW)FVX_Kp7SsM3Q3=avYE_=d>!nz>d(u(eN=vfE&L zYcd^vD)2Qinm>0OQa}_$gO`YV!sfo)!1eMC@8L+m-}KSI-`P@rSef?5`6iT|LWt&e zPD}lujxbaVh#K?&gBvcGz1~>E6aoWz6{6M^xOY*8UQl+Zd`X2E0ehNZYFgZNKsS9$ z5@T{Z|4a^8bQ+{MjxAQYj=CUy1lk*l0gVXGSJnu9N>{2Zw!law+BCpR*5VKTSQXq8 zx`b;59lw>Z-BbX^HU`5(@#RGLyY|Ye&slodhRV1O&gsvz1p*rWwYG>|gF`M}9VTr& zN;4mDCR?X`1F^WrlK#^E_l>;Yf#_5m)HPr3?3L0)0O@%CBA4vjYiw8RSB3AoQ0ycv za}s)0=%ji0!;?mWZh&RoAAKkUIm085k3&}G2zaxUaC5=GgX#(V+L~ufWB^~7jE$i^ z9tz2)>+|| zw24%QT~GQy9 zUj!LIGi9wJkbbYW06(^D3%{ZRy(HC_?47UBpx#=Q@DnhBm(3k6YOJ=6Qq;_riak)S zoq|fpRPZfZg^{sKYq}6kTmppPrPG7={c>8W z&eHTgv;Wxy1v$B4Ab;}@;#1sK!u~0JoEM3}+ss;i?;I8SwF8W;GBU9<7DAZny0g7x z(7!~5kH8}C3mej1=8hQf{!oMtA3}77JIN0Alt}GDh7`H;4j13hA)r@{wdqQ6kP`bz`+j2L}C7weK|R|zY)O9IYB4k*mLnrRWaVK6t?xtCXxyOqVV53Aep-Cpf1`mc zv!zZRGC`WJ=*^b2VhH0J03N2B_#ys2@-!`gM$;o)l$xlfjHL~ju1iHxvmb!FIh`JU z&?-N>UCZoeLq%;V>2f$op{te``-4pwYQMu&qhd3VL3D2v>cWxI&vOa!2fXE)YWZ z90jt)@zT|L(yJ7+LFjp*)$rO(&;IAN`EOaOrmj5=`SOj>+sSN{`hxJYtfpqY4&`ls zXGR&*53FGPPqjJ<3T_0J+zV6*-+L^PjEEsc|Qtk1CimW<@)f16bhpVE6F)IT^8k)2u zLUiAcc%e}!AQ%OiZHN8%c%y&_93k7wXzGj(blYX5;a!?;2T}4ckMSpwL`D9W$MV_w zw)pQ=5>Xz5UCKxh1U-;jCwx@%VA_g~$!z{9?>m3es!YF|0o)j5%m>+=M_t!Yaw7KCWO_-gI)FuH%bk7H5b@LQMDqPncl~CG)o)*|ItIQ{ ze>{Nt12Z{Akr;L!$7f~T2@VF7Aixs@l01D~0u3l+44BBXUooulu`$7Wb*gc}M5^hN z<&Lyg zO21XWfk7(ux_s|LFJ;$y8u!!5V)xzI+p_EL+g2Q9DL(?e@Rp(l^F0|_)S}w&y*iMf z#vf}1B8=?ieaLR2kOr=40rSq^f)SQ%c?p3H(HPpU97=hmQvi1KN+K$Nc& z@^#d-D`HIWenv*^p)2(Qb>+CTrI7Zmr=a&cMUOqJgF(d<%&6>e$6l2SZhW~NNt$-| zn^lM6r$V~WD|Wf-1_xbNXBfQEfxNAG!VF~9fk<-W?iNLopjG>`%j&wLO`p!foEA_P zY?Y(-)|{x(1*?v4(=@|Gb5KSG-uXeN*MRz4L0l)^V&x*M4q=f|{H1ST625(74-xCBc@U7EAa~fh3LvT*-=M{J{|qf+e|f74S9A)Xx3bK$^USWo>7QQ% zUlToi0q^tv=V27G-UZXj&4WsBLg9@9zrNl-(+J`umkMUFFuS-I_EtLte=lFSp991E zoxaRb;fk-K21Gb}cEZi9ngc5{VLfm(mZc4sXPMSN0MR9v`Ul5LMgWh(K@HlE0J$TU z9T93_uz&l#bGL@1>#*dxo=ppq^xr+;Ec~bbdy(W)M`#pdf>ADM z2Vdj#wG~JIcMJTx1xC%W|BV8-V=qDn_Wz|QfacXCLH$dn+Eu4f&Jj|Bb$ zD|yz+gI(!)pM8M??j1~+1UwH$GMp00Fu;2@U=P>~y(BgZE)$T=LV|zOX(mu1mbklq zC}H;(K;tSR{Bt50M5iFad7M|lt@OQTz_Rg|anOZTPD0bnjX=a-ucrGE22a0?I(TXZ z+F0Oq!I+?M3IIrpi)ZH`t0goyo9$3IN(e+Fr$Z&q1CNwbB&|hg@Eo2$Y!cxj7Y}G! z&B@!XucDQ6m;dIn6K@Tn^?BJQBqjh(9WXFZpqlmpa{kT8ZI+1xQdyP65q#&*;_Qn+ z%k16!zZ-Rg#LVS_zUSTla@^6cr{PM439q3;Cq3Oh+iT?dTNXcYhJ+L;n6LMoRImKr zISNi^_VNa3>RqY;v44p@>Z@yK&W#CvB!iqge88IorDjV&bAj}A0lNNI3!o}lfba|l zn1TG&pzMPsy}W44tV@5NGX;vWY^*_*2Cm^K^Og-Dndpy|y?H=aa&8>$Zk6E@t8d0DY+htfnj=s3ZA3W>_R=kr_ z$XjvO7!oD+F`a!Q1Fi?*^5XhdslakYBA%q|?|{Ukz)7MMd#pF(Y*O zU2tayP0EqQ2daJEk4GF#m_uCZjsY@LE+8@iZZD>y>E*5e#mzi~JR5;1%Fh0K3&4q{ z!7caFbg*TY>A#Hp+v|^QWG=GA8)E zT#J#sN$0N0O=6(g#sT>4+|qji-iW6eqmC_eVS+YKAEpb|LQ*@~)_W?9!2`JBbcz(? zn@Yl*waa@}XGzZ_OgX#ZZxggP8sy#-E*3Vc^B(y0KjLq z`bO5doX8T7S!xR5e}6{+r;}}{-%MfM4MY_1D=QDBfUrff1GZQXZJx}S7<7PH%c&B% zZvlS98NVh-#_et(giEH2VA%fM5lg-H_&E z3lZ0HyNyY%pxz7g2${gw(eYCvKC6*aaM?F{BtU`-yP^I^H^*A)mc2Fz(6bIklpe@L zEZz)FjGEj?=z%P~F}CULU#E{tZ-Uz8ReT)Sbc6$Qk&8ew2}`^&fdy<#J4f(Z0WFB1 zTF$ZgO&StP1oFa0)I1-U3A2l92fmdl?gm9Cg97$R*`-fhC6JE^|AkG~`72Y5zm&Rf zclVn11qG3X6I78kDIfwih?EC(O>f`VEjuA*?0tW8L(txwvrDaE`{kSs8_|@%>IUyx z%KCCJ0b#;DC1;Q6Rr)Xp|AnU)tKB&NjSJAQc&g@?cG$3~{r6yk3MpxVK!)KTSdN}t z+rjpRH-O|sZviAn^FPhFc{k%7&ZUC#s7c>9L(D%H*{JN-U!k$x1?+rkoUAwtPHr=y zm9xB?#Oz)^@(TARDIr<*N{1FHOBYPh1Q-*AGWPj4fVZ5wcr@uAWWHK%ErBW zB5oza#9N~G@GzZ|qdjts_bS`8OADK3%6+qTyVus(9#_>8oYtMwTGzQ>W)A;FrP>;p zDoLk)MB+Ccc#kyjPIw)Dw(AiN59*e~sE>p1+Xvf(gT@yqFj)0h@aH~vcI5Ov_&Uj8 z*LLiVdb)ju)bmg}BcwK{at}B8a;*Ay?m5O zwQF2{jc#qEL~|b0u3OyaO}){yICOe?FIQ);evrw`-XS@HT6d9z!ue{HobiwX}EnmF#DX} z+rD;l$x1gb+tiB_KYxCdPsU z_9feUg6>VR3W%f5R)gs}e;u|Z!@1dc7=9}|;8c^K)bohnNZh4yHaq5nCI6J+i+~0< zm)*B0HVLUm`NC~^FQ07F=04|SY^YD`+4-}mM`PB<6Lc8T>U|9c8ebpw>nohCC37tt z>05CBX1F9NJLfxQYTAbXoQzx~{vKM(#5JC+P94f8n+dt7ln zpyeM_x7+mb5`Fd7biSmI?{&Q0ao?6TkC(VjP;!QmAeq%?>gq^jWi z^d)OIxp@-r=XTRNR^5Yn$SLD1K&k($M4q^H<;<^hi-ukjx0ia7R@qWUQv_$5;laZl z#u1f!2-f!`@M4z$b~K&16fhK170D@3Ba0^T2Csd7WDw{$?!TDFBcj;;-L#$=c=!Ms zIp6B?4(0P+cQ@{1SyYJ@4}(gmT)6E{sb75d3M2+G^IzAG2xrVRgy0rwb=qLvH}QFi zvc)(UqAZKbLb|tgmLR!t`K?s%;lE05i~t$mvJ&(aYXQ4I%hzZp<0E&?Rmv5^Zn_9pVqXWT|*o1>u2}$sE>^K&YkgZ6MXF*y`0NBD}LR1Jh$`I zPw#eLi;l30<6g+QoRq(6&d%5cIo1UnQSZfhE){%J23NcQk|O$*y&VJO5?(w5SW5(L zI;V&siBrM5WVn^h?gB`9>*lH@WoKSjVlS6_v-M8$h!oA%b)}kSigsZmf?UHNyd^V9 z`bj?glezA`_Ej>?x%|M064kPdAQAs|qMg>CAJ09xc1l?d{GMIz`Zbm=4(qjBTotZf z+h_HM;m@fc^PssIGyd{iw@;V}@oN^uuhYNTn2C#uV_%I_U3+#)2|0UBGNJ1F?p2jJ zsQAV-Je>)Lo_m;2M9KX#Tb`F`nyr0$`46QoMX8W6>vt|4xzXW^O_{n(PJyukO4X?! z6N5wnc)jQmS)|h2(gMcgz}@Hm^iy)L=UyeN+gHN~XUzmjY@;>-=XH`mtZ7tDC6*^BP)7@2E6BR5lK;Uo8L zfBE1gSjN@S=Aa4pydO4LeR}@ck&m35{>D_}eYN|@k4yez&kVT#2eBe>gSu}i%k)TZ zKTen=y=upAw?_8eG{t3dTaVXV|H}s#!7?7zfqxc9c28)h9+laUGq z(|0YRpwcC9|3~%U_iQ~Qr&QJ2y`8|HDRcPdhhInb-NLzh6t2ppuOGQ;$v2elfMslQ zgn#Vj)+@a+#b&pySnzF+&$KfW6L#99L(BEMt@!T?_W$7*?AQySSta_nL|Rl`TN`?& z1-RIEb3i|#1tSQsa%eT(ods5XFiYp;HrU_&)V&0(2eR5^r>Gv$Fgb9jMqD&=y~O3f zqE6z@VL6BjD0MfN@^D*{4H0$mf&YfYR{W`*LN9{%-F?1igKGN+E=v;b@SJSa%8l$t zxwCOq2})8e-rvqPG3be-iOe zAF3JJ34h(=8U&!1k+yva_Sw$DCnDis*yNZcE+s`qJGwCfgI#XvZ#7F1Kn1?Vb{TE9 zCgudWb>e54-RrlN*BH-JkY~pthmMg;v3>2nO71r3ouFB?X+)a@jcqUFQ(x-gH0~7K zJ7aiGv}d2o)1t2Qm?)w|X|+W*InXn_TQ|FVxpubwQEj`7qWj_Wu>lI2ndRwI2VQGgg>C4D_W zN8%>d;X4M}_CM{IDV5#byY%7L9rdTHm#kODUYAz$AgD2tOz{0aV*Of%s*BiI?zUHB zL5@eQj$Lr-#>ti8@hQgAPq*B{Z-Ik3qbvP^(qcPW^k&*vlEqVsmZa<)-hNAd6&ts$ zI>S~yJM856*B$+*-`6v>6EJ#r!&hdycLpro1=zzCC2sYVGte2iVIBlbalcSf!*?M$ zW{V~@wWK30y#Rac)nkFzp96eQ>1pNXA!7g;VqsRVA-fjU`v=2~_;uI881@!B{hxwe z;fV1B-`#ItX=80B9=gTnyZ!M;=>IJ{j*hc!{~l-G5`%w_vym#wemVqH3~ zbJIL%V7$SoxP-+|197*7&{cae^^K|NE_M&d)4RzO*;koT4pLQTrIRt~4NcKj9+s4cos4jzBMl8zqJ5Edn8vQ_F38wB*U79%T&o#oLwPIWayrNLu+Zlrc) z2q?-ohNT`yDw^T^FP(qqCF@o;>g584pW|9~KA%jD(_r08?91TBGmN!~j|~WG13?bu zeX)II-Vl9=3Tbj#aOznfjibvXZLH@{p}?WvVAIb+F%zfm|0$R|&>U{cU(-qt>D_&A zUn}c~5dX=ab&G>f&K@ktwn7pzk}ff#=O8U_(bH$^mYl3@v^>T>wUDSMF^e!}KPO&t zNmYlIEEfyYKyJLAMrIg{W&F4h6Tar5? zC8gE7VulVs@fws6Dh1&KD-%H>5fb7SdVIBEYkO68caLj9>`jYdYwmBQTAe+|HJPlQ zeS)feH+GArdN=ExFDkV)1qB=W>WeoJOlEjD zt%L)rnUoJyGWm{F6m*nuYfXA?kfSc$pFLT+0hl?6Q1aB>xkl+ps2LaAQ0F|Y#<6^@ zbgyQ%#94l1g`Q??2pI!XnB7wdmxs*m4xKuvcBC?#6Ia5FtAYuh=q*OwIY>7QC#%B_ zL>YLDb}(U29}=JE#rFNKT%_4b-PJ%E>~0JtoW%@iiO&Zv%03-QXtY?zOkX}+Drg6~ zw90p{2JL|=G@fMT%)Wp|vF0F|M-%8=KBdv0>a7Dj=hNZfY8%ty!Jr)IiYJw+@LH@ollEEfD3`U{WxQf~aco)qa5XbusWg8Jch?T+ z4NEDuCvY-(qDC>jT)b46cZ8={@1obUSjgGgy&mRNGyo+k%MK9*5Xc=+%N*NpOJrPH zY>$ZyjpAtJY--p*|I~~T_yQ0x+Xdg9i!5H+OY+y1Yu6_En6Qfr!$pjz3xEGlWurSO zgN<)Tayf(V3z6T94t+bLY=9k2EgC#n1LN9D8$l7{s2Q-J6;_{?<||dW^q#R#LTVt) zwm59hl=ZC-{lK7Ry~H0QJj2ta^Fhtw1BcE=x(ZB=a5xl`!)?NLUSor#dhn zJi*g&rAA8j=Ufwc>HQ&JYeUX#Y6#TINO~*Fsc`4G#CAPnQ?BON6C$1hpk$Yb&}gfB zfiGo+|E&&Q4v#A)Y9ZuK2nEH2)x9-s<^?oF*cPH9ur3TFOGQwgQSFq3oB`20gpt12 zaJ&mHqbs!AQ&&zWf@Md@7*N;jnj(Dg9dx!V!3;1GnELdkw_FbGV{~8Epr257jzMF5 zsfZrdm^ZxuO*h<`5Dz*v%)762I-SdqJH*oap)AA^VMy~8h-;3l{Kf?kq9HCc(2atV zAvs4~9qOPNKgEOFNn_^+dzeHF}>{|<7q9|ZTTFGizW@kF{!`Z)~vM~(vprNH)dY=>h5|Z+%Ggz&Bs|2om^;>Da z1C!&~{Op{zAgfVwre!!67ra_RRw+hwuNj4AqLUFUej;llnPWh%CK?ev3}l(j(?>t% zqR{0+yY=J@K$CaB3zU(I-z+8cmSx@;v=JLGvUQ0M;r7+|{I=n5fc5K6O*4`s9Df}p zxqNTRpkrhMf+&NPmLls=H0_Te4mE4oAl}RA5?q8GcTtie5B4?zAyecD04SL_G0P&s+L85#ikn1C0pR9G?4UEeGXjr&V z02gX(=qk;Dn;`7I6W9bTnbgb0S7yqz&!74Sti0!XY0(sERSaP@u?$DB5O7mX6X3i| zKLhdN<_1mi+hes^PRxle1Hb4QZUiaCC@mm!7HJ~wWNVn<6#E}j55fc1Z6+0buVT$& zCy;4iqI0qO=hXOLKdHCjHo_w0j=pDzaP`DrvXnFx0MifObXv=7&vJm^;Te3)7BCc( z*SM-CW#7vxD}VXd)=O}JDkMEjrVTkz0MohsTzk+0SkJzXnig9wmm*~gZr34GqfDp5 z_u9#c8FL@FNKcn*;aMRzT;07xHg!2}+sDn?h)g+Ll>9+~Ee3{RMLNXR#V&3g!V4kX z-b2Bo_8*2%fny2CltUD-ZsR0~mbS3z4XSwEPC^dmT41)3r3=k-fE>mZXAK*%1$S3Vg#YDY)_+kf!5qr{ZsYslFLYk-R=!Lm9iya_eN5B3d#g2FDvj*%h0n90IQvwrMb1vaXk;3&*$J+v=o}IA#D9Gqi+4HsDWqm z+*ev=F626y!#VZto+A5_CD-2;XY z2jTaHoDyLsnWnviv-|hge+zUY?WdWG_b8NtYUUm}=sm4nxErn{VEQsSXc=L# zvt`?kh6k~@FA zawBcMXFtu9xeWu3Gk+=7ELAx39Y_=l#3eydH)oT`EsiaU*+&1V*F0R=&pQJ--dad2ZM2zCS%%peSdN$)R^G2ii62_hdZ(MeKNgs6oe|Z zpMHIQcv=fzks-0R_@f)`U zc>Nq`wn&T#FX^dBYsWPG@r00^Lr?A#b3x1%sEucYmo5nzqc@aQF3aS|S};Pmkz}LF z-EU`$dZGYd!qOVll63hG8Oek3`6qj{N}_fRKOcbvUxH`!+_j(}9q#?lV8S1@_oVqy zdnfEiU31N74}66K+tU)WPCF> zLH4m`BMUij)ZLXd>m>_0oOacsgjtPPoWeV8WtXvYTbqo~C*`_LQ0ZZXJy5zfUeiF+ zK;J6<6s6~YaTau>^~5!>Z;Ol@RFf#7i~J|a$X%Q|bFws{Z6#$R%=-Q8Yw&))+0|o^ z7F|-_87MPbIp%=E)$w-;5hRe__?dhphj%(^F}k%Zr+Q+{r1aT-RMnHPNE*LZ?;iQJ zrNGO|+v#hlqd#lN5nSX(teb*EC87Df}yxji7f=kHc`U$tNSZyU!FQ%b-#& zB!4Le93>fd<$-6|p=VsA)-yPx3Er2JRgenqo4O97$k%kZ^M~p1=8a;)OpA1d!{(5# zo>=rMveXB1bD*3M~QycC|LX9|(?8$F{Q!08prg z>b`-SUrE#fc_&vU$U7b`fGL&KtdGo8N+PKvm9(h1KR4U@P-4KrHGS{47wSz>TXRuV zD;Bsg<;7p*wX^sz>SltJ{k4ZQg|e70!Dx_4z3;;m)zuMRAZo@%g4lzX&0vF+EP|R~ z3lxAmgOM!nmT1Rg8+l?;lQK2NE5G$Jw^f%MF!y2zw_j08T5sY^nPqZs@~D%gxfAkf zfC2}+s)-))4=h!Hr_d|!p~1)`CteWo6)HD)c?G~^>-rMr&|D~Vvmul<7n^H0`c|rwEq1G?1us*tUFwSpKuvCK@+rwa3t;{ zd4yMaNyNc^U%F+S7!Pi@KA~JwfSyw1Nnb)5#U|wi#klxi1Jmf1Ks;hM7kxgdBH2(# z5EOI^ix(ohip_Bb*e%$AR}NJmwLUFi;lzDxSMa8IRmB>rU?t^x)K+vERVNJ2ksgQW zie|aA2$9T;T6@CBZdG)Xy{T+a%ox5`!YcxW+6OfO*8uTCz@uI zh|Z-@%H=r{^Zy|H&ACd>A}8`9(NkOC0pflTCF0j99^ME$EZO}P7;`|WpDzlaW8MM) zoW?5vnCQKq`N6-zL^EalJ3_`FHTOgs2$1>Fe-Vp#WY1#c-`eTh zd>JZJhqU{SXk>TzI0dNoN6-h9*{K-0h`4sF|6`S^P;iM(^@+e}%p?Q$a%Ch~xOO@< zjR`ny9u#l3Ds^LAy}4kn4KXZn9Rx&eMY@wx%=X~s$LG(NbULzOFVIUMxEqx&hCE*S%!c9U|LGx@ue(wO-2#Aeke2gYfGjBtgh)m; z5JbUak>X|+N#2CJRe~If7~&xc^UbxjjRh8@We<^Raw=uuG(|GLi^kSr0BsNNvmBad zk7Q8R*H43OcChh)^_~l6bWJmnT0gYtQsIqG0bf~PD?>}HjiTn(djQddj3Exz|L8@{ zB8whzdvH`Elc6t<;V?L5Kiz{1uPkpu{+6qMFrpX0YYusyi3I|^I*NNViN(225m){L z$NIdfT!efu6-_LZG=ahRy@T0=vwhkgG)M|#Q zn6KjpzDz%B{OXeHZYvR=1$t!+Y8YgZBm!J$oV@ux8)>WKD3t*f-UVwJEO?cF#atw} zbQ@7QM%r2UqOrXeS#i|2{iqvs*;qWpDJ)~llE27KoKnRY%cF9ws23A^&mKxL72Gi0 z1TGwnPlUKGa{)m?SVrn9D_AQ=NO%+pnPt78gsUf!KfZFl4B2FD@?%DOJ#(sVa?-2yKn}y0#xjS=*WrF2LJG*LP|mhCDPzt}X=_>VC&k2Wc6>aPHza`n%aH zE46`slGK@*=NDRUL3bwcTcdIGszmwS$hLuCA4TvNBJs^N{q=3(Ln$1CVy5*qLF?mY z{usQMTnjd_Jd}eBM#MMA_C>un>DMHBc`>kgm7Sy}CCcg!v%yID_UDxP+k4kWdt;6y z%D-h43B3462%_-=TG()m;III>6ZO>7xY4P4I7t7bTe-Xwse6~s{IlWr+F?pzsKOz{BZ7;kr@Nhk=kW@QzR~RX~Hh zM?rvwmbJS%pF4)Edy&Jmhjp)g!wVD!yU*yF{UQT|DBxRXoF-x2vYOxU|6&jbD z3(z~rMC14cA!6jlJN5}_CP%VE$F*RCkf~U8&zOLg%kpIuP_nQgc@QwK zMMz)SXxaljuSa6SHUkvl(fpR-=qUL&4?76N>adBlNk0JS?Qu!oFsE^b4 z+=R}aLXD-wh!R}}YKJ;KCPPnx$sqMG7Qnf1I1{7^4bj=Mn5~*~7!PGY9h&Qyv^0Wx zNd$^@*5Sr%OF;tz!_XAIDSfYH_9^LWo;%^ccwTX8{*a&gysO@Xj)7SosxZ3YWuu_^ zWd{TbO4?P5w%H!qaLnkx`QM!9NR+oRuc$4=y^O{-C~d?3Ob0c!NNkcRTf{ba!dTlb z(S;=;!>9z3fXQrRVMxt^+!q59t#S(tJ93r#elcAb zf-9)se4@YcK?wK8T5&*RUQz2(CP=G7MLTcN&4WNwKJs?Ga&jdUg^dP=sJ*Qz?kNWM z#_b}7gy-GRpWO(Z@6C`vq*r_9HMVIIWvo#T3PyEMFJrRDKld_fO)Cd2#SP|yInFj2 zioj+FH#|M}4YU;ltZFVVmh3gu(jZ>{arv}N?#PgNkXS?);{(B(@EtL15WU`~`;$u| zNj|CkPebAX4Y3w_F&g)B31R9<;tELMxf5AxsMA>ua}f*P zFVhfJ(B;T5K%(YLz5#x7(AUJ74Iv$HT&d8%Q+@Cp7uBYMZqP)Rn9NCx&5#Z`p`q+Z zOQjI<#I+y;&NoeshONj%9(z?rAXIyr&lp#xmL$HTF?ff&)|9&zky9)sFZiG+lP<{Q z0@uV?$fSteBeB&okk#=9mktbn=r5!^4SPt~MgEg)B4N z*ZZ^5OX%ZvtXM}BmDY`vm;4Wm8CYc8jf-rP8 zs|pBZ>4QQFc1l&f1<0!`87}2S`f_iyTLNF9tli$FX9W9LE2%~p#3XW$rcfbU`~CmE zmdi1g`@*jzV}zYxSgFlL$DDx}B2-Ov z`CYpa@?|*L5alB~yT&>F$yU)RUo$mriSsei(oROx!0YjnUFB(-gVy+ENj1yh`eJHa4 z^`2iv>)Jqt(pj>L_dJAam|9B}^)bP14=HT0-dD&9wGCBu87nJRYdIlcNTuYnN|iQP z4{-~rgN2Q*GkN9x{JQq~PENBid-?Q$6}xk0LDErvarbqZN77N_rGRcwFD!XYbqOzm zzHi%f0EXs5U4UAk^*_LT`k)?j`B1*e81j9lHQ0A-vjGCp9OnZWM`30(-vlTTcVHv* z%Rry>{BT=Yl_w}|!d z!0259wi(iJ4@qfYBW9W=1Ac|w3``Gy!9CN#dv|1+m7v|ky#dL&8@Puw?(Id%GdvP- z_7OgH8Cs9KO7v05>*WGCl4U@x#1JNKU9Za3}Q&U~s%>fL6@7|aLdk3@p; zlq%%_w>#}Juw3^+0;%jLRU^3wvO$|zjkT7%!L(Den7A&;tQ?N-Nz!1ZH4-2H78Chz z&j=VAoA@E^9BV`blJA}EdhP_Qj^8*bv_=5S%lx;M+0rS}(}HslyW@BG;orADk^>JV z`6{HC(iqy_QV-P$op|ImG6lDLXf8OZe`?2sRbR25`v(6UAmk;@f4L`+7&P0>oiKuu z1)1#_26wYZ**t%1s;;*C2Je4*7=j@FjfH;Q9qW%pltf!1Hr>wQv$^{RXY*fp28V$G zR&;68tEe%-H;3~+=TWhzuQRo05sV5Nm=H#*lC7#C;3j}tZ!Ex+)1;3@V4lo7H70mH z0v-Vpd$0F@^DzPS0CEpRC@3ugHUa{k41SR1Nk|e>(nlc!esBr7UqeM-5Bi+%;9v%X zH;)Q1&5tYluhY}6kN|uDeb7mB_9*O;5DJ!Mf8EN~KiJ9=l0*=AH^B7Qd=RtkMcWwO z4!vPyp&L6YI~r5h1D|C5++{FU zKAGyF3nE=UaHypKb{s(YaL*n%r64C$MJvXK_4jN7&Tedvmgv!wMF)Ww?LB*a&6hzf z#@ulKMu~0u$n@pc4$eMk^ZluP11-oOwQs(sN}IPJs&r^tqlI|EVo$x_p9D-%Z+2 zr(vm3AKgLY`!YfZt+9(=F}pbT&2~P~2adzVQA;H?JZ6iWNTlCD4YvG3`6mZF=oq05 z6yRC;yh;*v#5Yo)+YNg&G(N?|(8ATK6`%UI373=^77W_}jmUwAWV`VF$|kE|Rgsok z^y&A38knASdvHOg(&7G?b2u30m?Ttxj2_x|3Q@i($8Z`ZGN11I^!_qo=9MSNXuj@Y zXM}NbqE=j2tH86)y0o(N=;c6vC)eYs->E8ttzlhqy<%U3r%hLQ^;Sk7YYvcmKJcSD zGLXqqyIu;VRT#Ks1siN5FZ$pd3I$wxQsafSacaqR_94L3D@L{40G>A+dG4?cb zZXx5V!vyl3t?m2#^^e2Tg{l63jW;82^dW)w0?+bkq(S4o%<8_AiRma#Aihy*sTq1DA10WEw%l$aO+b!En zD)YPTv$)OY=aJuMcGP692h3dx>6ntDR!eYk3(oJ$B==|9mZ;0zM#Xb@1PG91(tnzy zzm<`h5i>rzd94DJDNl?B85Pl41Fy68K$|b!VYNr#(oU4_ISb=GR*O6i**WK1k?c z{|~wPpWZ(wNyTH;Y3pMkd|!PjjjajV$lWdeqW;Y5^=5=jocfZP@{7tl10kIN92A0( zH@5jJf+CR{t5ozFC@Bf@Z=u!Nlz2m1Nn6zN9ibY-FCguwUI2t9fIa7BmO)jiY*C{q zF3e8RO8YM)iZ_j-${L$RA~F3RAC>GjW)xG;Yr5Q0>qG`$+2a<2?N3FDo6vgYx9c~Nj~ z)-=frC^ezBfNXE3SyC6}Ze`T3?>-6#)py*o7D6G(3Zx;Di4Z8hy@d)aM) z@K<`s+fyXA%kJeCHDgmlzmO|`DUMU*c>Du_fCysV;5gu~Q6&buB{I#D@@78(Tt<9X z1JL+1crgQ~s-Y5ULx^*_b+L}uW5ML^{@X!W1I=bt508-o@dHP_xz7MSYp%yY!8SII zhKi$!ZiB3q1hxX?&36?bCZQ0yWI*ye4f2+`_sW;Ua{$)cFUm0M4P((aAF|58b!Fb+qhePsH5S856!e68~)cZ-v zcdIDQMNH^>)^i?50D9h<2NwQ1q}vI1wvvN3hpD_=DU?F_v`JLDC|gZ;ZeAWB z)y`3<6i~Od6hY0%Un;|yHXAF0(u(XGTy%mxGG&)=u6mv7Rs-rPX~euJ5WZFP1m2rI zXgrXa<-2A~*7PBQl%7*xo7KEAhKb~^CTB2~S>RJsUO0QH$b zrXl=m56uFo3tn;h{IVdn!{wHc;tUHOt-1)f~P@@3T7S`*>mNDvE52V+`zzVnKyr0A*$U@*R$ zTN4b`GK={^66|aX8BxE5OmUm{A?S-&4zE+6z}YQ+>I3|w3F2g!rFVguB0?yF3>O(b zf!SZmQ2>cGL0vAEGliQXX)D}%T7;<|ov7s+n1(hhpm*E`LAgK-9nib9VB%BSe$Qx- zZ)1Fx>5j2X8ckZIEA~iL7?j{F%#>b8#*-Zo0`Ep=(l-HZq|;rOl||`5vN;;T#ZfBv z>XQ_|Cu`UMM$_R+9lG7-!GcwTvz8LNElL9hUk_pcG?5yz{fa$ptjOwXRL#(NB}m`P zM0)vd_u|;(oKLAj`Rc-ax8q+9xs?g0!~^TDmKoA<(@VI`DA|{0v^ul9Vwr`bB`8$k zbTmZ-657qv6b6~1hTByk#>;iGI&pPJU0U)9avX@{^;7-wd>Q65M-0dqJ+BBHrO(L} z5E0u*vK9~NmWK__q&`9kz%hfV7;q)!BK!fNCaW#NO{vaehp{c7O3aMN_*bgNI$$Lo z0FV$^Q#s6DtF1aCw3T*>L2Pum!NLwy-TfOsvL@^NJkPOe`8t`am(73G9_D{1KNi>_ zr9<&oR>-qJR?=VS^1mSeG9Vq7OyX78OI5UU-LBd5{I0LU9(;xT!(T!M7lvEk=3V^6 zud;r>-?frETTg&H*@D-Zg1GG5gsH8ndM$)~+tOER?6(m~P?TakzvJ`*nU|I1*Xjh; zugwu*RxA^E-EL)U)!oX!pYmi*%+gp!{n~;vB2ojsuRsLs83A>-XofX0lXm{^e9S8H zaWC*)v227aT5J%PS!v9#I>_=@jqPPj`9-{cP3MaXSM-u#EZeOHWS@cD92RC$UI43C zaL5hW&tP5uJ+k#PsR11AXz$cU`IQUq3jZQ5Fg;~M?tF`7B+#jRbPMcy` z26KSbikuS2P*!$q?)mIa@aoE1d>%e;Ut3`3kRBeHzZo=I#Ais?LA!6{v|wI;;8Jl< zo&#Cwd(IJ=jJ8gFGV1rcgA&eg9ISs7-(qS^Pu`loAhzwXATyx9a$SZ|PJ1ES_N?kz zreK?O<9gj3hr%W`?bAE8V^z2sVSLYK!hL4KKnh8pRCDhANMczkm0DnZ$UDY}+$BNe z4n_leTitly!E&zBi5-aRu?{7LPi~B0#`)}K`?C)@oh5*D`&!AWS2mKvhH)vCy~rZ& zapN)p{etG3EtKx?-|l2h!p?q4+ss~#M?3m=4Gy$s0Po4oYRC$WcLP|VmT*d# zesKyX^rEO-!ZXkF^H zT*GB$Gx-*YV4P?6(*%Sh^*{&XaHkqawSHKPG_fEukq42-ecgf>r{DYL{K@jsukpSW z90Tomgqx%ShU~3}&ET$;fqoJwOeE;zw~7%ihq-l0MB|DDl&0-W=i3M}pT5YvfUVLQ zPFJ+@d3W_x3)dJM)f~|51`bkdfx`;eu3;(0swjZ)< z=kZ`jQM*P}8)U^PXPWuFcttemyoXj;MTa|?C&%`;R;;(YV&T$}R1qcL`9!RvK1092 zdDs3_VR|R<4k(A`{jEDQxFbV`U#4SRhik9%rcwWI4a3;^ z&eu6jT#;-h3p>XIXz)mg6w9RSmxtB&Qq5VoHd3RDxlsv&P|iR zx{+*e@MhWJ200_@=dl{&q0t-8AQ5||tekS_hwZzNYGiaO!l;x zW6K2i!H9?%dvYFEE&zfxb4PYu?r^|r=m#j2k}tnPU&*#Ld2(x_YrsgdH_?`3WTs8D z<(O#80jT*zTaIrUIYFw!!Z_2oPU>h0&vrSRw`tmqt$d{?9P`BZX5Ki95%t}^PSA4x z{bO?WFCWh?f9G4KVHpr`$hd@Ya_thii)Ci*t+of-Vs45l%@JGU=g+;zk$Vmg)_K08o7N6G3awW(SJDszv!_+@RTay0JYko_R3e>*> zny1~t2L;*ijR?9+*WPe7ijS@udw^s+a+gBeBGjerG3wQ6xu}Ex>t3BI+?%;JKQo7h zsiQwTaj{Y7@We3w|2jcblK4c8lYw@@Gczsw^6CTUm~#!me{=o(Q}Lz6FQ$7dzvix8 z+Y!3ghoft9+~0Qr?wNiEU(s$R4d3x`RfF}j@=2Urfh%sfD(Q6>?sm@>PEOMYty1YN2wKffk@9Sppr@sxZ0fYHLs7l-#x42_sKJg5v>?F&SkoV z(dr@P`E+Q{5*D$nBle!LK;4jYk=T6{l@E7uR4Pst6pnGx#6iV85@a<|&?T3b$+XI> zH-(1AB-tXYhFt3n&tmAGU6P_xWK1W}@sOY7cuZYPT0Cqi9T4##Zpczv`eda)(#ca_ z@N1rQ!*}aUH9zX&= z;B72o5Q_Sn?~+`gA0*-?ccz4-o1RE5ygn;TjCH|u{-gasSEYy9NJcB9l4$nCh3mw- z`G#9pni-;$O7)P=^CP!ig^Q4(wBR05rE0?6nq%k}rbi>4&;40^;D~O*D`rv#b+)m5DeAW{%h{I|JzLfX90`?t`!dOTKri; zx;o`o?8@9`ZDvvom@W@0ZoGpt=FZ%`nE1JZA035Q3+j=jv=zhpeIcK|v891d8!@3) z2wa#>@jxqPC0^*q+H)6LYrYcG*K!C4M~}c1S=qs@G3Vnu`CURI4keq#gf_B08$hP_ zQ6Xh}VLvevrp_aI)t>fS^6V7xOW)g($#I2zlURf&VB6|IPJ_8jE2Rq>cV7y!4Ucs~ zGD-w7%sznzYvn#sw`cTe;-UVteqGuhn-?wD*Vh^Zj>adset;$6n$GhMtEd{$l9AFKMm>4yj{5-35hAz>clPXjT{9Be4=C5htt+kB6c;kqim#&GbTfuV57A#J%2lPb57+B=+1rVOH%y66g97I zA*O+2=^VbjK&x5=HqwrhON(;X68qr_3t%LoH{OI6XI_-CCan2 zGlb3)BHkMxN&sGm&T8L9=};}=V{(_>##5m0o9x}_IDexDw)-sT>R_( z@w@O@h^=#8DTxAvy!{?2HbnbnuQelR?6)P5r^$mw4p3mwGnh=VWfW(gjPx@#5L2#w zmDdfC;_KHbe~vi8w#|oiT2XQmhNM*-I>FjghQ&WQ*;(2sEyfpE6C-FT2eMMs5Yb>iJ)@1}Wic1~%}{`L&`F5Y z7-RI$?>-vtJ}em8#+&HE!v;k`AGP@v@{+BL0~nEmv5JkBk=B|U)`~%s_nk*aErv|= z5D(zEq#|2lL%T99GZ0=pRD%Uj&eH_V?VzlTHrxB>cZx#4SKn;3W!tvi^okN;eew#l z;VeXSohjVM3q!9LLJtNiGTAVT&*(L8nE71(why(d7TON$FVYK#`@_l#jI_~I&VX6c z;}neea9Z%A)~~+ELK-Ihu0^V-9sC`9jhcvFd>dFu+xsR2WQJkuEDs8DPT%!-@5pNu z=7`$F|XX}$Ww-8b%Y(St23d<4vT@^o)4xJDq65mRT%e@VqA?@l-4&& z7bnXkA6Ztyvv=>qvm;GX-~O5XK$`1KsO+XCZUbFr@1LFZd0~litUXt=k=>eY@lNsE z$X#QH<;;+E*2EQWwLM&TX%}?Tm$9kNaBy4BI$*%fGjGi)@KTF1hMAA1-HtkmDm4+~ zPlC`}Q{^hGOCzJg9U~28_r}9rW`rLHu7vUx`0KPDtn%HqfM%~+?QMVYofv~bBrw_*hkQCbSoZ!B*?Hv*~#<;6+ z_;6@h91v56M_n-klHyQY!k46YDU6TTEpUJaNg*s7{Y5+7m905@Y+}GoSsMO22CsA9 z`ez1XVgM#)z{C=m*aIdu!T-Nb0sKbO!ccJ$Y*RoYM29N3LX~h%!5fe5`V7vH|5M;h z4uCUJ*Eg9)LDw#&^#)HQeUG7xQ$<-+hAY&iJ0CesYa%@40?4ni?x zp>uw)l*M7f(Rt`Y+f5XFI4t}0oLjD&M(JCntbiEj9qw?>p#mQcMC=BB=ZQr73fr(v zUZllcGAp4v-b1-|z~P{ft80_)3%(+@t@IZx3AIr68=YV74T3b%5egNg*L=O+?kRnbswo^Mc00bcyzZ~_MU)ViFTce`{#B|KF#S` z5_3ej_GO%s+Hm$_s%N^=2ZJFD<};*qZ(R)JrKtZef}vE%cORW>dVUvT&G@Zi)8;Hx z^r+=I^=fr=Bq;pj-p$%iCt|5Mhx7}D!`gB*NJjKmI`;Lu;WO740ie*zb1|Cl#w?5l z1q>pezQc;)njDB-#}j9Pd!P>oQ2kpW--3o&A#pY>i{(^ZRy?|(cNZK{OJ%3pyo#v# zMA^33v)Qn4SX@4Wy+JwMRoG@Da^ALsXq-LKJWq zpnxOHFBuRfAl-^5Th?6dF4)U&d>~q*V^90yvQ%~b=EV+fqOtnP8ii~37uzazlfohx zcJG$33*~_I4Zj~$h!?vb^FHAft(2XZ_H=@CjmQOOa|mwRpM!mbiYA&)5Nn#fyR{>X z2IBHI{5IOmE~!Eo;(>Z-mNgV^N*CuIu!i|3woEcy#a((}@f#sh(0cu=PDo&d}8eNoVlElybX#A+U4`tx&?O0Tz_gbIYYHyZ`fK|WC)B?xd(%I z5i}Lbh7b#S?o6efcTQOI8ZfqSYxb*zV62A%UCBl00^ZWiT!Ng3!cE@utukP*6Vcc3a3JpKo~oLr`4RsP&=)`=3cd0lm_Kh5*cOI@ zR`cKyION852wmqs+Hf3l^aILFmyJDPAdQf`xONi;T4bgcK1Y3gz~V)~F8nI(CNJ(p1KFA()Vus8NQSaB#lsyB zGg?(K!EqVA)lm{<1Kfv}-r&12-)tVY$4-H_Jd&igu(jYFp{XpehzaSOwsZ3vAu`IvXLV; zwM8ZiD_#U?@og_*r&TB|CV^F^aS6x)TGC(*HLk`q7gs>IqVZ^@$M2p zz=iZ^D_2Nfhu69C03l^sqAEPD^O@Ci!6s!W5$Q>VY~)+dj=6ouRVfnzWpYMmTUMzn zGt(0^)!POo$X%4Mv}`7a{2jlH6cX+ke4XFH!P!Z`>itq~$ok_KzCnEJ1BijlOGRBaKzWDBo! zG4Gxhp_O};#j?2%%g^^%FyjRGiPLA!s<U|=(ICyd2>DNG?Ij+ zez>q!ZV(5kL=B#i+4!>0A}(bm+dtWB@fo#Oy{KtKDq5zX-6mWYvlhhwFzoQE2cnyL znMb zyy}W&f=P8*er|X3Yawi1ux;Yx&0H7lSq6$8zwyC7yYBia*eEx{=8N{()bH%G_S-7R~B684|u!L?88G}r+Ci0}tb#VxJ zL!gAyA}7yS5DDEeA3U1o3RZR`DC%eyxv?lENC}6ubv{*US;*V@?bfNtCCRohAXmh$ zbl+<0R8~wDBZitii8m5ia)$ZTBO65onjJ!Z*?@t|g)p2gUv*j;6s5coqGuszPXGqV ziAKnHS*GCnCUIm58fH--#Gq85i&CLo>@D)SJ_Rcd_{q?N`<|~nna{yeH zC`W$sI2?i5>A?2rTM~hSzreufyqI*#`|0#{)TXxAqRlFje5E3NioJoVPrAFh+$Gp5 zR5n^}2+n>x?F9G2)XPsqp^q1!TCmp4WzD$n%srES6xPzEM-uj*0}Ky2INZzNUwo$~ zK;VsrIg7ubuOlUgJHyf3_pr2GR@_g(*+)L4k`h=>Y5A0%FK2zKNOLY(X{k~KIW<7Z zTBS&cK;f?de|X+#2$Jsyh73@yOQom;qdEA=4ytpW=fT?4IJ!UG#@D*xH6RHq#?R(!*Q6A=8u@H@F zl=p_zRZz(?3X6V4tDck9Nb7(YJB)W(o-s2s+PSc^XR%Z3P5HCe48aL8-XWX=FVp0Z zbqhANKG%fa?v5)J3dXc;3m(>?!#*1NAD=8busJ?JLGZvi2yr%cuiM3?j&`;~l>-2F zMhyXU?V8^P=;B<%D*_nUHW#(QPR26WmK~#i$@PU@ZRl8o;`+@KsD~QBt`KLLTYd*G z-g`zY+xG_cc`r~$!<3jLO+RdKf83642f&U=KGrTr7|4LNu!P_+fO=V!pk}Gs@kWZr z#hBGe7A5#WI-Z;;tAI&xVGYoSVl>$3gNCTyX3`V#&Y-0NfY>_$mh@Oh>N@)nkuOwt#U6LyS za6PVdn~2~RGJPkFUK{UJ7E_GeSv5`%z7(?l*nhcq>*3n6mAT1a0CySxhJ{`&sr$7A zuc3{D7*06U5Cs$+gdj>6c<07FS~@7gdM_e3m_hQPGP{F|@HTe!SfZVDH4*s5G>@q; z)I2#imH{DZUcm9Kb59t+KHvC40~F88hmr1q&EH14+lbgDck!5GZ(}5WWv2T&2-(=e zfqWlC;OGR8|BP6(BdhA~L{<5oI-Odh zmX+qyr4F;tXs^R2hL(oOb}tR~a_Bm*X&b(GZ%>)E z7_)P+Wn}zZJC}p-xEFUt8HjtlUjT<(E&a3|Fj=k-E!?$G(fby%ju!4aQAJp(N`Geh z(!wthhv(d0C^}7lty4$r8ZsKy+)?Q&s2Gic>0z)|!^8{S-p?>z$Ztd2Hc1J# zj_ij8+N5`xI~a!aZQ=tubY$5xyg>2aUZ4g{h4=_Vlv|d;Ht6RGk8m)AN&0nZG7IYi7w?Wc1@}cE!?fQh^dRA|8G~zoj!8+N}2`czv(M0QVx zPH0rp@!Y|uODo<vkA1kR_o(4jN*+Co>>|#DKib`# zbk!Z5pU_WVS0V`UUyXEgTy2OH>BR2h07d9o}`(B7c zNiFQME29MO3jt4>ZkiCup{GD(vA;|SG6OzxSgG;iCb^2se#g?_*s4?`zfs|YaJ)S3`*R;k`q?PgCty?Q zaKvQco>Sq-0#UtW^Q;C`qCJ#mZ{ABct_t zz!RcTN=7Q)jZeMWSyD=Q$wINZ`t^;sDcrs3vbc))&dP1GWtT&7H}jFlATp#^6~Woc zfxkrwbT)r%J-sNTkWy0Wx8=j1w#=T2XjNfsB;_{_RDsNeOpU_s&og7eIyK~y3E`z7 zanhtSAL(}~$Pl|WCCbpU8!M67_W?B~PCK&+N2{hxowM#x;wsc#DvbP^LUbcQzJN@U zT6@(8>S~)TUTfkBPfi~RmUplU{^f{DFrcpDymjKmH18xlx$|(LuXyOGUvqnqZ6G6G z({*E9x^y>}G)WEK)WZD4loMRr#BcDKwC?}#JMfG4L7J%Ieym!bTDqIn5}4= zo^Nvy;&Yv8vKsEn+m)FLw~m6fe8ifetkC|uS>XeqOVOqg5j_U=8bY07GHTRYuz~%s zt#q>e!aUgOhPG6$=0b$E(=4X#x^7(=#IKz}Ld)9{$`o`XJUU7s#{UpL`a<0WF9ofu9@)77aTb#y44LPN<^SV4bUf1A|_ zv_u@_LS_1hKHWiJ4x>>KJ{2W+?UhG^7Mn^J5%Ye5>iN-r6^6oNomj0*WXkOX+vDYK zFaD-$HdfZCc^A0EtOov*ZGX~i2IsVY8-Y7pM(Q9yrcv?b;v;A$oc=RA;f)t6?kb{g z@@Dnvxc6rTqJV8D1A7_Sy!&9wN@bJnD91bT!9dz$DL)*4N2i^Zg$QUESNMIL9IxVL zA9e8%KSNmv?ylyV)-Qb593h!FFXNyBV4=oPz?yV-d_WB{5uq@m5O`o{{J7)-Nh_ybm2?$4maKzo;d0Uxh&plXyJDVNOfTb3kfGF8IKTfjM zzSqTkb`OQIu3-C(0*EIp3*#zz_Jl&s;f0<&KTw0tR{A}RMsiC#+q?_CXy8_^ ztHTn*!rX|@>Jd%EwZDUCM)eG2%;wqw+2E=*b-%B8dkyaNoyRIS!k_ zbL~AmuT={)qjo$5G!SzzG#wi3p;GA3kg9)oNM{zJvo?yBHOM6W!LOkPh{kT`jwGGx zR67ecRtUYGLNcKNi!Cb)0pA}rU{A9HE2tlXzIfvR@_cfg4Bht35bME%gPq&9f5y(( zgDU;qE$%H(3}OqtJpeb6^TRhWl)i!WI4TyX%oTmB4+GZ*1Bc!;Ag%5C%=BG%GIFEe zT;D{@M~6*7|OacU^ho7iU_7(&g=>F;!`nu4`ai#DzTt1+|KKLVqBD;$ytuRjW!^Ae^BK4*8MuJ2} z_m%jM=|PohBAYf{;P80Iw-C~Qc+wWg0l~6Ig^@=tY%Dk-1YKQ)IH8m1I{W#Jb|H^n$#$}ob(5{aLUke$nYiS8Wa7J{$i(w#rBF+&@M2d-m94n9kRk(%fu1Hu zPGPy0VZ1sQeXt0HA*N?E&X0H8fkHYcQAXFJTHSCJSN57ru>=@NLVQ*~T*F1pUbIKw$sHP7oU{Q#C_30_*m;{afDS=2UJTTOm%Al@~^d7>^V` zfOECdpM19ngan0wwPzl&Bwec1Ff;W|%>rO_#am16J~+BUqxM`cE;W0z+g-?dFD_TU0hIBSG6)(%V9B6tIQhHTu;6b}KxgN6g5>VO7Rcwe z0Sd=nfF`=bac{`DaW8~o96w**hJArg8&TA6L<0oo4Mb5n2*FD~W6Q0N>25 z|Md(2w*9AAQ^mEYx&+Lq2LVsi5rIB`Zk`VZJIyx6*#Rf()ltK96o^PZAj0>XO+|aW z1tc`!{94p?!axb;kNpDpdl`a@4HBFgmNNId8XKqDnjK2kfa0CSuiwTs|21RyToRuN zgGwSLmT2q_GIqs^oen`~Pv8nk;QQFV;8Tr6ez;?a->5AryZIRMjr>emPe&~nD-3MZ zouF9moof6rKq<39itEMwi|aHY=SvUuz6RgRJ}PgF5|?}fivqa!P}+B>4Kppolr!VN zE>!{t`07s7@kuOU=dqH;kp2T<33q&c10(2AIRE^~S9}52xjcvis3=+XU;?zX zy_OBqxG**f0Yjf*6MuPdb@OW#hGW!E-TOS)IgnW6QQsSUjAf{a?vshB+d zeKNZ*6RO{zrtOBfGzf}A-w}_$g^5+mfZb06VF*$Mz*~C&@fOmVcz;i4QVu#3L%LrL zR_rN2z%^B(Er>)Fu?}gzqGi(G&muw5W)B3i>)S~8B0^; zk5q2I&^oxCP|;loBE9tx&?VoYgRtu){Q0Jm;@i^2s^vF9&2cyE2(bQ4jU0ro{6zu* zYglw@h)l6&i1hj}TyGW06w`lQ{J!)IMgV4N_p7zLm(SS*YGS@TO<{Ji5heUUe~Ma0M#>q9<31dx*NVO7hq{RbaoNhx zit{@$6c5^XEhGgiKbvNf?Aejk3F%E)37ojC9$=}nB@7rBBP5AzS(|V4|X$GF!(7oGxXvnIBdto4i04(D+l&rXgCP83-A7DETNwzg1!M z{aXIr7h?|srsS0%0ND>uxzo^wUsQ4*Je=mv7<{fyD6rD*S&Bg%tFO}kBI4^no-Kak zbdV__M#loBL!txbnHjyinFKsh4fbZW5}pphB%4eN_W+h~6fw@^MYzELKG|0KEzyUH zbeVgjmFv~;$wr_*kN*!e3uq zuZsI(TZc_J7L5XD1-pB|68p;E!lLD^s~+Cw6JTrT(z&n^F04;}Y@iEZO;T@-wPuKn zb?3=j1lX|@d|cBXWP(X^IG23=+K#M27U@oeZ(HrA4(O2_rhYeNUp7j#&h0dTa`o;_ z$KR--hKS(YuR{#a&$#3RQ*56Phv$h!`oWL_nJp3+F@RRCgBND!9Sq-H44dZg=^O@}X$XilT28WGY)+3-RZVRK` zud7>|W9sU3RH(kjMl5@Ma_uGLT}ywvrRPrl+NCmF>x?rMfWve1UA19}UE$)JHZP2k zJ28@-cixd682IEcMb@F{t=lZeuv}xY(VXbKs0x&~3$ViTb{VUH9GKjpNe9AluhBlK zR1)5kRk-(xN0{Gh)mn>N_e+bI7cazXXvf+wxYp{trH4|#b}v(b)dqNgesjS6d-6qL z^0a*Q5NWA$lS}wZ0Yc895l#V8mQwJ#|Dl{+JIh{s~oCuK8%qi{uvL9YXsK?CdDye%;H(3 z09TcqvLS%yv7Mn7{PJwLu&f?AtudwChyXYduytYeIy2I2%5Wd@yX1T6XdC z@N`muWuNRFkX)z3_O-_EXDj&~m?gm14LK~p+e-j_ zHO$*p@lT(yJHz$m?b8RYdsl6*pscy9fLAE*YsGDbZd1DjFUFe3fm_yhU)$vu=l zi){dbfI?x=7fTt&yG0k zAHX6_i1RA&xq)~b)OPaHwLZ0A%n_I!>5iulJvu%srX?lpw->MptFHTPL(u1V*`yVI z6DkHOx+o_Zj=kAGOaUs+9Afcz zkG~NTJ80GYU|%&*pSakUx6M5dtX#TfK*c$6B#rt}X zUNYmr0Q$qx9CHCqa!1#SztuPnrCZXmF(CYeOg_>_NG1wO^nJ{9O$KCIpw}olH%mzH zew`H5keAA-4%ihANi*Ag&7T+fE%x5>VZ1D$Dcng?oYvuq#bymVK>uCB$u?Pogw}Bb zVlrTlj*+`wdox<@%3sFw_MQOrPrhUH#M1e|WgA)EX)mT?HIEJnYlnrK*R+!POqyR^ zF#{cn4^#LGB_Jz!;M5x8pUvt0svPt`v3lV8JY=R7D8eFTC_c_iPtFZZH_i#uP3W$# zhdhzslc553No>EaOcEhXl{x7-49JD~Yvo4ly0FK#sDA8ux~4M{thCzdpZhSJZ*6Hx z&v)Jz?^ns#?{`5K9$P-)aC1fmgFI86b#XsNWI*bUG~XtQ%)@JeS;@I@IrHxDr_RnN zaae1=QGZU`iitQJA1FNlpYdy!^Mn7gGt76;mAF42>2U_8-v6q)u7o=5703`mJF^B| zW#iR$meBK}9emp=b~td4O7FkOT+ijMAsi^eW3niv^0d-2Y=V7^Pc8YS4~#+b?KY_f zTyk}u^Um5o=dUHFm04u>TO|e1E64lxuec|cJG>2MPxrm z*6}>HOX-8r=u};;on3?f{1G;wl_j+2YgudE%Ujd7+&=JS$2@UG8MrE_0U%6gdCfD( z32tO1_RK zk06UfsS{Fy=FTsJNo*-(CWfooSS>F67bqGe9DkG{!cUVdBYmiruTS6| z|Ke1Ja4Jx0CYqPsvnAkYQfFo(lzz;eFekSZ;qk8Bfp{d?go4S1oLhX^G3P&Etcib_OeEhnTw#zehdb z_}ZYY9^U#r6rnst*n}aB_)rf$Qtv@1W=L)YYGQiz=4us&^sz_F7JPk*OjBsrE82zn zK%i=vki6IV5mochh_M03kSBC>UAM zjXIYuLZQV)QuaGH0*z_cXS7Jg??nA_k;3%|@s|;!z2Pr}R++Jn3U@&hSBVluTI~@r zoQcN?ZXVG^`+;YMO}Hzt<@1G=ePEEJ4hJLSk5RWWa~0657hVIa6eCMPOEFx?Lp?t4 zuS$zAxw~<8uHAL3qeCwtC3Ix2h+BGs&GnH={_uoxJk$Wynq5WMLYrb#HY{ApSbZR> z;qDx8WII2n6{?z6c3;lsN*kzcD#~mICxB7+!$uhC4dDOn8Isg255>;iD<_?1Khm!w z^HNmQAEV_~pN=JgN=E~+4I1QUE*(2>xqG)aV2hlM4zK%fvXz&P*g19+gyf)|6 zgJnv zUFuK1kL2GPian)l$+D1jdP2zy@`xeF@SWc=7InMCg8Ez#qRb~+)uk2&wnB-xC6-UL z<>}H7?zIQLJv@qDy+?cng4mQqaWUa?WW5BpwTV^_7SWw>0&>pDN~=g`fyA# zS@dNWx$�bz~8(65f>ykwj(pTn5=$2^3NDe8e-s$%WDa$ zS}!@xTgm5@d}IFJNxA^SH5pS2Fd7+shfuyQ5(NEV?&*1^2?4J29!VEkl=DbxY#~6G z<>A+DBEv;zrS=ygw+K|!+zb`5L?CHKLI?3J5Qh7pj?tsPRC2Zlj#ejA0Jan0S({3E zY6nqyQE&9yn(df{cU0V;reE9uBaY(jlL{`v?GvQE3fQHB5fBp7EM;uAc)VEyru&n8PhoQWt z-r;NipJBG`nwnkAbT<~0xrW6sK|N}}E;fy2rK^WREw47!JQApIZwqtvwIcBH4xND^ z(w62YpWC<|+HQ4ns9;pKU5YEQZSse0qW1*iUf%ZK=ipzV8tOgv+rZ1ZPP2l{B0qW6 zscJ5Heg?ZA=Qk4AFU~>X!d1BLfjFU7W(H2O06cIG=UgaMVXVaTrK1P0mi>@2?6!?1 zEP1oqPg~~Ckc2NE2jijPq#V_F>*6Q5iFs!!{cR0v?11niZ(>@f%zoIkbAh#PS`^M~ zLRC~DOmJVD(%E;zBr5z-16bV-z0`#+c%w0g4yLv6T0iFbnQrp z5%Dkn%)=?Hc*8{vU^afWkVoy)*+-{=A4`t608-^g-fOv#pQ=J!0Uoby#K0Bg^fBvy z)W^^_t~7#O@I!%D^F?qe*}ZaQgWP7WJsb~5Wv8DH;V(zd!nu$PZo9-2^vh+q!nW%R z1insKzx*xi{d}-_sOYL5-Y-N_U8de+5UJwsw7B5QG4$6bGnt2!$-iDTXgmrVqvq9g zVEcV_-=ns)Vda&`)lJoEn042$xwnIwi!*QBAu~~fE6m)v%;4o-*u{8{9Wp?6YNNh% z%=N$+wX{g+w7eJ~(=qD{dQj#fZvJ9`6cEku%Bi^QRVVTMfa-WwX=!zWD&~HG<$@Vf}~Q@|8&e zuFH!L7VR+SzLWcI-FP2S*$PzPRY&usG_Jz&eKcQwga-0APvUVNd{*&}l;30{e5lVa zouBq(whsrt`^S0XUEv(?inINfKRY(_He6wERL+jCYrLaBeF8+9>3rn@*Gg3w0cr;n z1%Qkztoms5Wczw9Eu4%v%>FAXwoELBZ_cHO#qi(07zPG=JBdk;V>%oAl+@?H+aAXA zyI{WZ)RiB$?|6H2l6T?245kS8{CQI~LhqcIpQQ0Z`$WQFt+{S*n-oITwwFc|aUJ!< z*s%2J%^qGwh8E39O3Aa!S@pZWUM;{` z61VR2^|Fl#-066c-SwHH*X)>m6lUOTi3aAtrTV1aa4cYHM~9B zi^J34k0UczH!xlDEKaZb_D;>o<;~-WG5*7DzPDhcagJ1hjhYD8o5mCK$NPxIoKH)$ z1+DTI`K^GP)9vmBBH`cca6{|olp~CgmyF0URZnU}?F-Jr_uJejiPn6EZ-jI`-FZ37Pwg&r zTn87(y_7ueM*Vz-BLp&oyNt!&U5-wz^A5P^>I9xW_X@9(~okw`-T5ZD{;yo9%1X_1yjPvU=B%=-`?!Fue*V7oa ztR@kcOsYIlqf|IU=ksG7Vr1#0;Xb}2|MBzBrnr7BnaIp^$XD&@bUA%GAtNm<#NO}4 z?g5)KXU=5BD)zQ-uuMv86fko9jZszPDh>8rSvExHxTB>0N=s`$W|oBT+}Iy^tTBVo zW~PUp5hR5QV0~#pv-Yh2gTP=hS&oOYFzI+&fBgz3s}-s*KQL}%E&!u^VkencKw8>! z&6U@xu&5~L`VBYf1Efhj3NAdKK6p!L#AmS>oc4+1#bBIVxpOOVJfFbO;)D~lEQR@P z6MLjGDBB;FfLHngFYrJ8>wYl&n+Jco(yhH=n`1I7x#?o=T)5G7*#7aN{4MD)TF*oL9!6|s?6dm7L4+NN)8BHuyvSq@jMmIE ze7?U#!e^Jp=iD6c(bp}5(}k~GYn{2j>->t%MN4r!l710d<9#G{E1XOgPga;JT!jl9 z$*&n98UD>%&wf7{j>meJ%S&bz`<>yRy2Xo^bGG}*8RNY{Pc%aQ-lr}uh0pS0*Uug= z(V95B|L2|EzI9$4Y;Qk2iyB?h9-rmvzGU1r;hvqqZ7;$#@W~4kY6Qj;W{;{Cw=e8n zA^B5F#6g7XqwAwAP*0UW%cPA(x5nMQlugt;*yjZt74jKijW~tmmA=$VE($H4wwkXh zFJohh-_YVIcaE%^S?p&kG$K}R|}iSj2l9Vo|@@F#JjmNz`0irJd%tz zZFjpk;{kCEY+$fkEk-sF-->^-YhZU`J?_&U^qy55&zg?!nA(>;RY?-ZqTun!sY9Vg z;__E@_Oah(BE2^>Q$PDSqY1QY(c>)fPZPQ)4yp2Oq`DsrUn5hoF^9d=U_Su^j!6XPqnI!euW^PTyJUVJxG-6y%Sx836g zCS)p@$Iyi9>!WqleEzh6D-E-Au&vFUQRtAlDTC1#!;*HgTsjBd$JFI~-<*nYdu#bW zxn@3`q5tX06q3M;C0J6OD6`YkT@zkyNi>E@A_YMaiwZ5YoSYhcWK@(MBQ4qAyw>3- z{UpIvggm2=^*Hk1mS!@^ZurbWCYdm(P7Nt&VHpq35q)3`DT%AtwDE2%0r{*gg#kj{US?HQmF<}`4+pacH4oE7LhHf?LB`4?rb4g! zUdI~S&Ita8;{@hk2bg2S_?YLq9rZM@-OEykeL$p>&?G#CILNfVg`o;H?RPUt#z)XD zlnowlW)9r18%WNeUHJLn9nz)2YkobhtaXR`ANjS_(P64N<8T?3qD-q*&a{McioF8u zy4r(Ed$Qz7&j+ms?+$M2y5s8Ew@q~a~2r0#2U6GrEbG+`)WOSbsFxZgvV$FN^Wyl*F7@Q<`cGj0SQ1zcG4ivQX zRvO3ei>)u5!|aS++)S*LV3kk9s0tkY2l?XXZ~sennT@%`JBe!D(@wn?^YCyF0aoeY zwj45V7UqZY(Z75@^ZBcOEP2mPr6?myNI;UCy{?WI{ExGY$Nn#iIg)Bw=k(8fRq!19 zN8_D1qc-C_t|_EVS46*kJdU$vj{RQ{EQ>M`$}&o#; z-}#$|?pqmqRzTCjzuxf={$^rg{qq5vm{>nBStlme|E-DjASFG$w!XG@PjYfHT|ja7 zCo0vp`lNKAVsA`BwKetM;IDr<@BYn^KXNE5?u&tcI(m9~4tr8fO-*T@R50>+q(dyWt9Skf&I|72{E})Iq1$JF{-htd3lnZQsKsi3-}D39%D3W!?2{1Hm_{Vd z`RA+do5$@%Q4@dHKlD#c87~j{){T61Bwtg95b5OQ1>>Q{-@K8rw5rp5V8HNAw z@5dd9N7EKY;(dyL{fCb+UXUaCJ47RVR!PP4viIZ|J)a=K+KGJwtmZ3 zG|KTF<(nh>W+hAs>0L9%&Ah+)=`rsyn+Im9>XXT)KXoHxzKX-63Z_JnirLctz)W3; zf_a|ghME6~DG>rwqH5Lp?IUab=YJ66Sr{quenIG0OyRKuG45Rd@<0=t*AGp)|Lo=^ z9TXH)6A}_a>g}};poE5pYlIXWf0*lP^j~|>+u0>$WM&$j^k;qi_|etBUbuh8OY^LE z+kXF7FwPHGy}uuI^=!YtVZ(;U4h{|__GuklMg9u1vMHK1M=*jhOcmZ~+TZ_%e*>oc zNClsLCuJpx)uDL2#HOtT#TEYn?7)5E^#8E~VB+-uq2puX^k?Zz7UtlXm%elR)`R~n z%o&b@B_|?*e;AvvgWQRY?Em6MmOWfi+EiCxzu`=HNl6Km()aXM7QOy&J@n(^;vQF2 zR6rFQ9~M@}TU>L*?dg9h4soX}Cnu-3v(u{DD%r4M(Is(lahjR)N7W-qgx00t6Y(8} z+)sfuKM$Tb1#5>;D3oI>ThpRZEBBwvKu3M*KO0I<-~d06$4uY=KQLHe_A`M4e1+kS zJA4x$<_~R;6Cmb~oh2%BDh-T`tgNl9qH1btb`;t;ImuZ{hvW4^9?tScKJU*Zs6pazyT(3fU(>6#OeP-m5Pbef9&)bH&g-w=tK!~ zR8IJv!Ge+f?@e9C=m4?*Yku&3fck^8qQAW5m%T~6DQ6+?>^cS@@O1TaS?83{1OSE` BA;|y$ literal 0 HcmV?d00001 diff --git a/Robot_Wiring.png b/Robot_Wiring.png new file mode 100644 index 0000000000000000000000000000000000000000..8b4808bb1128aa557dd8d50bdbcfa36c22b18fcc GIT binary patch literal 180567 zcmeFZcU)83wl=JY0wP5aQHo#%L_p~sY@i?@(xfDy2neBV>e=7D_dEZ*@A*gb3t4N;HRqUPJkK-6n6K|^sxlnq zIC|i~0fxJGZap|~fX4Q~fkX4ON5D5Mk&N8nzk@ChRBs$WVz|B^IKX@0?yc*(&!CIr zG|zPP_V#~h9pz@>Jx6`^d04itwzjr!8HA0Q?c<}yiThu|#MyKgA@#z%u$$K*c;tf* zg1qNy+&^R}b8IW&NGY~dcd=s^#9XYf3Z36d=o7sNGKGY=o3WjVUgi&Ubcnq@J&_3s zdCJu+tgLLDoPx+{Q+C09mD-aJA6bZ)O}_Pb5mn=dP{*?AZ%}Or#Th&trXMPQ0{tKS zaXJ6-+qZ95iL0xTDJc%VAKpYeIXMNtetmp!B|Ip~_q-{6eo--dkwZ)M=T>Na?M32I zL9c`4=yt*U#lwrnqJ{s1KgQ_4e*N12uFVqpx;izp@_~c@>>u9Chac10rWY?CpX)mO&+bQg+AGb2RHO6xa_K7n{MiQ%GSM;*d8X339{jUszt{1rmz2e0 zvXB4C`_vzzqAokbPX+mt-yQIuKfzlRim4Q{`Lowq@jKvOKohLY{-<*(dl*b*$#TfQ zr}7u;`Ty`#UK0=y*#7?gduv-8{T+7}7M2sNtml!_DgPqBBV6z|KL?|@9pDp!LqpmA zb#BL9|JvQVcegFw?R9V zO)?ps^E*IA%lps%(H3C7X~r4lX4Uo2e@DwZb?_jSG1Ccu;eUERa2I9Qqs&7pR^z87 z{^Z%T&y@Y@2M*m%rT?>MGbaJ})otjm68dNFbB39>XkGdEJk_5)`&QNge>>NKB<=J6 zYVTReXJ z{;|1vt>Ln@rDv7}{`ZD2A~8 z!g14P0CdK`j+UgNy_MldXPu{;Gc)`#p2h&)j!a5|JXUJ3;7WeUc%5dqUy>R!^Y#~0tE@{8 z=F@Hav^*6pwQ=f$47FSnv~!V&aVFm4$&<)uCeoql_X5LL0@d>Do--v)pZx_)OlAeZ z)a33wGkBw7<^EhfHgW5YR%bd>o8{pMYukZGTz z2f$-KoygWNhzHgl=+Po-npb*XB(X``(vMd0w|dEdH*H-%->kfg0M9lcpSXf~`E1CW z7@$ct>X>Yuv6)ma=?rW8`irY}C|4C)u2HUf2qre<4f}NnUr}i4W6={oA1kdF&^wAm z&K^=e;P1%7Tf~rMbKBmO&h~tHS;(=Uulr{$aOWKxmGI-rydj4#pDQYOkP)mY|Kk?7 zTc5VgP*GaD%;wT)mPUf4^^cjx_-p1t#l^*~1z&_B+B8mevC0$M#cW1ObMykj^CHgcrfOHBw-1fs;m^x~!e*=Z{k66$SHm zK0Pdi3e4ZF)O>%tbd^w7T#|e4?KdZl%539mx3QcZabl`~3m-mTXjqb2>H7V>@6Ien;`?nrDQdZ-+?wq_UYdGYWW%_a^J&D-E)miw}FB}5(Enr=|`H3fhJ@7;8?abuhix0sj&i38kv$%wqe!;GruEGHE z-CajwuAAY51?NNQYy&khhkv22`TGH#?#T0~cNCgE$7Cz#w(#M4;F0f1?i1aV)w1jX zwzLorLw1{oD`ajHamFdlg8p`3?Rm1<1*Wvh5kIbB~dXk3E04un*BX8hy1gmcuBil;K}gGUdsX-@>YpXLBbVNRQ-jf zra(dkGDMq_%llnTbH-0_uoq)wiGfiBwFB5SwIZglN? zR?5Ol9v^-bAqMK16DGTmeGah?E`Ji>olqO&y4qs{Q@H;0S5wM+|14nUY@fg0rR*@d zgHm#~B6T~?>&xS#!;mVUUC%1|6TP`k-Lm&`R<(0|u9;;_1WN?WtiN=QH8@i`EEKp`ntUz z;l9#x66&6Djz5(4x3wZ*u|@Evkkg(U!&U{?)#%s9LK;kpyf&9Hng&GC&fX+Zi{MG0 zQtRF(x_cd{c6&Wm+jyr_T%~bA3+}Vq%VPMG+X<8mI${T+;z`K6lz(H{2{zkNvI{e?)+$$yG|&q+sl=j^wu#h zw+D3UeTn(@>^m)ZyzhFyfhT#XoSt$0aM`6)i6CohYmBCe4l7agdT~w;ow@t+SkCeD zDo=qiBS{l!H)*mau}UR!&*r<*Fb{39QRw@?<(O3~RRm3z-@bn6f1&1^7-eK;ViTC& zb!4{hX{Zy{-wX8?D*BxaT3p3O4GY-7pT>)P+%k6O@m{%(gI6HP8$zd^ zdz>slM-|o$0+U`IgAclgGAV8;zhM^{_!@D3m)mFsm+`{WzUh(X!|3{f=cw^YHywTb zXsFkcghrAq>ds_>1T2$Gs54z(=%hryauMuUYwIue%zO?Wv4i5JdNaj%v|C0d+IZkWHGwA|EeVQ?4nT zpqxnlV&Xl)|H+L0MT@L8zBj^SGuh*vZ3o|VWZ1X-dkx}KtO3Q_JY&qI!>f6Xd*G5} zmr8s4vb0jpO(W4S3JKBmjoc3K=k_2Pe_aafVC>!B+pNPZdD)r%F_TCf*qr9#odku& zqK3p##)Jc96)|*fS~7Dd>?W#*hb<}*WH^Yf`j+nb!w^`q7`chl;e=N{oi~r?{Mr5j zeUVT)+2-j>eDDBqX6M zW0tZ~d~6WO_Z1rk#*UK8M(tgarC{(A?3;-OV$7z}Hui6J`gF9uhb!$l+RJ#)MHyV? z<5MlHUJZ5;oPP_oG_dc@)ObT(c4;25__6s(@-EE2WM}JJIJ;K`TIff;|DhyEMN|JK z*ZAkoBE&Kp7d)0b?Ee0V10GA$c;t?Mu7|R zRQ6P(`UOVcU-Kn9Ci~jBaL&FZS$uAz7p_odl3($Q7BaRR-@SjNtd<*{v2;OLo|zaj z3f^&KIMmqWm2pq%8+u#%mpNq*U%0oNWVA&fWVhrm9xj_(sr=&&5F0 z0X$j~?KG13Gz)e-gqx?eeqhskXlUqR&F;o1X|rzMZrr^jy~3anI#TXn`UyEY!zk>H zHz#sE{ALTqqKmK|6)i0-@iH!%tnpPIQC2VQra>f?v*?X^OR^u;qB1rX_~lCYvjd=9 zea(O(Kpdq8$Oo%zI!`frc6q-3ptaRD5d*?RO&ixnkZ6%z_xl&b#fcFV3=H-I%&YmvIETFR;MZvQ4^7Oy&kqJPLOkSF! zw{J1olI)=2G3gPCKwL+8z#V`W>eZ$)=Daxa(}+l+AIHH^!^8}(gQ0Ty7gLvED*%vq zm?Y;u(3hi=bf9NUwERQN@L9?vx#0&ih}aGndwP>-1O7wCy_2eEJZ@2Q9qI^h`N?&hT2qeU=@ zNmirrR{fIJJzwbDI^~J?vO3Bqeem*iW%-5oY0CH#9Ruvqb0={db->&7#F+Zz6xNc| zGEK1-0pE2rWo|d~_*S##3Y%0EnPpqPTtefL@r%Xd6;A1w?!~5_7PFN0ov3t!SpzR(%G`IvaWaCWXiE%Ob+oY-HfFJykBnlf zpp(s&W}m142{0t$Iz?hUd8tOXwzeLSpM37#obc*IGZcHoeT+{+UgBM^DF(2NcVNc~ z+Bohxv=irXY00UXn~%t4LKH2Rz;t%Td=K2-$D%9jM$7bot6ImU_{tu%n>Hx1>=1XH zQnt!M5-h^xfCSJk^adePLf!xXSzyb}6bif?P8tMX<0HpvtJ`#CN@wv zVmEp$%L|9yV3dS6q%JKbbO>SHQYa;3? z3^a>w{`=bgc2^fKixx4c_>M!*U%c4pAz6e*71KdeeD^%cvuH;*7K<20d%B%|y1vY> zlmW-1y>j{HjROY>Am`?pC25u97EM~m;}$KGq@CU?0>n*l6|Pq}Tf}hnYL@CR48;V{ zn9BP10u+Y`1-D#1s^9(td$I)^hYIDC8o(sUNj&~Si`!`JUOiV78m%U#`SbD6(twK{ zvsnPfmyihjn*QnTpkg*M#MVhb#TdE$c4U~Z}PqHo)339 zr0h)`Ww8-?;4MBdyB_+vMKk|)%dAbD;u-_^?*j&-m#ZuA%HRq)15l)>loZoNx@yHR z7!s|b;I(nZZ3T@+lSuf&bwJT&KG})a0EI?e=BobB2d`XD510%zn+gHwZ1(Y2p`lU3 z7WnlTIzu(9U4<@VzNzl~9s0J2W8H$`9sLXgTnd`9-l-gchd z3)A0Nf0=rXysT{2Molr0fGcM3p?L0GC?XDmB5y1SI=L4VPC|KJ8X#^Ci;Rv06^EN} z{$eIxNrJh4nkW73_JM<1v|m6@IjvwgXCWhI7!jA0v?P_kzCN7yZRKr_0cobJ4EkMa zmojZXa}(zvAn5i8wr?>j*Y{FgyLL@<-(%Wss@`AJy+QpOKauy`R{d(9WPsr*j$g2& zDLRlD){6Ak{8gm*t6NqUr(}lB`%jDg;!gj;y`J3wnPFCoRMx*<`U}Ls%N$C{3_o;h z`jra!A7e^p{)Zf#Y~;^#aA}DKQJ3`|yg4ZpnV5K`H@u=knjFT{*WP^#=uY5U&I3K-WOKI6k zIh0?u7y3|rF|_D&u-o81m)ZEb!xy8+4$s;2kAGaw1Z*cOBSQc%TEuOkusi>exV!TA zRP%njAaVNHAQIC5(Ok6vT4Tg1W#2bZ;}!Mpo%!UCK%;?d?FK`4F)^`28x~y1N2X`~ zfiGkX;-a=$o}z5}U56gM6p)b6Gc+`e7qbc*$T!q^@>|*#8251P#c%ch-;1yE=1c#Y z06c`IZ}YDBEU}|?m37Q)ZnCAcz7<0!=#^z=94FEu{n6voivYr0-dB?!;|?xCCb+6My1}Xe*VE0qLy+%?p%V zw6eE%wJ=aTI#QHUiX>ZcR1Lp-+3ZvPKq7?AwMJpM1)u!{c283RfjwJ#9W5{O1{H;N zg5OFYNNYtr^guABY*pZpu-l5@t8Qb5nv9T;Vs`NgL4yuyDT4DGEbKpb?V z5tQ_cn|{7uNgKPH8_1*|}X38X3LKY1zTS&F~2w>y2BiuT!k;L!qar>XzGaK|aw z>{`YX-oGv5AD{mHkbh6tztXz?AwMg+^7H)cv8L*U-mLJGLPj3|aXV}~UZ9s3U9xQX z^FXZqs5hfqpz-#yRBncvTdtbZwGC++R7iNZyHE4Z_#+JWEB3)6gGMz>VrSb| zZA{s*C1bSlFlSHVq}-O?7`XvDg0#3hm_1VQF;_xEFN(CzmJ*vCyCq%4db0Pj@G`;t z&^j?eMryD~gh}7mnEUHk)?(dW&)zy`y&32Ji6gQQu5JI0n1*5*yCQAyb8x=lOf2eMY)w*j3V)put zZLvUv$Zq))uHW^?)l@wj8yg=Zqj-?tT=K&GDgk}O92!>-2T3cVD!5(!0E8G*VCde# zZjp#m&{vbMdCj6_e?dUSW7s3Or9}s-X;zzUE~2SUeOa^K+ld!xbFon`*sV6P$YK4= zQe5SAatz_JbHvRF9=5?30b<Z;L9I!L&NWztShz^*((C1z==A4a;8#Qj&pZ|sP{}tq7^{{jN=-$xN{md1DacQBwZJX+ zPK4MQeRRqku#GdmP{GjXb(NVb?Gz2{F7M?QnVL)WMh||l$vmrhER^%i95b(QaNuol z;az^8jhrp*J0T5FiMM~0g&#uSZ1sNAIK0kM4|!1-Ul5my*ba9GLM$_gp5la8dNL@ z6GE(xKZNt^W$JToTsC`OUBMxtyT0O?+g+MNw0M4qTvBSaC%+Ug3qgBr%I?yyd38~j z0qWa>?MT?(eAyVnZxWu_0_po`!PJi&zON_P--Rh%ANgoi&?Dx4SwyLM##a0~?>*{O zb6u1(Lq9SufA)huD23P4$0!Oxl=SHJy)!~~kP|dKfZ^6XNIb0J zl0c}qtf#lV;;AN2dfIP0Ve+6B-kFpKQPL8mwL3I?E%}kLXNr zZ+5usn$tBKM;Fyby}}RPbFem5Uw)X5k$A7z2LFjWvgh?sBYc9wAA|SeOYeOzk)+W` zQ%hH|ar9x*)6mp!s$3`GW8y~2eQH)W2r*P^W4Kg?F#5Aos=SvJp;0U>x>YV#{r0{g zGr9Wx8xFO-$sWXD1k&zy07!riikEXP4lLVTy!hcMdAXltz7#%E>lNjaH>8YsH;NFE zq4KY%jb*x%XHZa}AF8Qe5(Lo|sI9cz-;Rhzl5>V|BS$jXBb@XH-hRzKpU$6f0CsnH zELbiW^v5-)<&OLzmol!fJD(Ny_(P zzJJ zvN+wB!Q2ebefM}4p!aBwK<)NcOj}1v1yZT0%a)&Yc)F>P@qM}7uUm)e)a!&(@;iKm z^d|i43!|1j)nL?Ag7<6G>`)F)Vex&0*=qLMl+9rHq9NL=z){ zJh^2qN=4nudw=QG`M#CU(A>n>?4?PcECrWCRc#!5Yo> zM;8&eYPE$v?*H^L}XnKySF!p6#(HLSijx5z&$`E~i2HMa~ER`NMyWKBP? zvY^zw)2L&|{QbrgYJ$_z=_@TpESUau0-F$UHE`{Lx5cAQPiBF2-GXYIK29YGQ14&l z$IEwkPx;#=5##fW5-M9KqH}~;eG5~QT{x&e8>Ff=7}>ZY`1r&j`?KwS6DNnMxmysz z`s?~aQMImd@Ow#_iQ`ob?BU7hLCpe6uGCak~O zxh~fm&G_gSMOR3Dd-ata7}5@h*bQn%z)viG7c8!ypj9z5CIpw|>ef|?M%xaWDy=LQ z@J7d|d+64Wos?OxWsOQn$`W!A(#2$k_^tPOcXe$A;q__^b?o*#efMj*oiCNMGn|s< zW2EDpdI9t{%c=R;bJbP#?^zcVUbU{ich?h)jA;P@O zvIkw{Fsvic+~*uG@o!F_FWoLwx;Yqk6)g(88+#(y{)nC*>WhLD?6sFz*eh=kF~1gG zI}ZvOqGc#z$@BZX{QgUNssgq4dKNpi5IJ8c=jU!`YwGIrUAFh7=4?CrOjAS*HY!W~ z+!jHqNDV!AsUN7L#Mf~bHuPe>-$1hix? z@s1fjqOvQr>u8_G(|nx~NS3U`yY-g7H0rXGb7n#xmEYg(0|r|mBJ;}$1l;iXmWgaG zrLL-S=a}LbVAf}amFZ$|f!YoOFQ6~<{g_n7$tC|`Ku)ISfBrgu)Qow*qVPnM160Ni zC;gxv4=8tvdGT9g&1uzJwFh9Y$sB*X?H_hYYa4e6FhONn%7w2wGt!N~_;TAir*2*W zjB$nvm{ZAtwbpl3-d7iDuROo9+#!8#6%-Kssb*2Xr*yaH>J_iK#&CO^dTnoE(~tH_}&ceoC+ztW64HJcGQO zqQMBe1m1PdT!`}54EnXo)R#ewJozu^PcG!v?tXsz26f>|n@ZMk{ut$Zpc>l;jj8|i zJCXgXD3N*tyog}ryLV@&)W8$j47xaopPqukrTeGoRz78uAA48`$)w?bc#`5GFb9rI z5K}GpMB8@FW2~{OOyOE>N^7ZR6>+Iq8w_V0v+Zbfgqpx#yvdU&=W)kzpKk}(yA9y>#Zkp}CIbQJLL#3LQ`e1H9 ztQ0W{m(aA%ZvvbE6ltIyH>xpk@5EYm#_L@A0bdFmxEZ)?Fn3wcb$T1o>dIJ7Gwwow z*mR{{|MZA2`B`(-H^*}Fkmv`X45=5B zR8{(D_XtSs-wxH`$N_2N*7mQu;Y49q1UF?hxPY7byQZ95;b6zF^~FbcssnQ{UQd!_#XTY`4~~yr;l1yO|;ifu~>@I%9HBna=MBK)@2Oe2ppUpnL;5qZd zh=daz_h|MLeUVU$x-6ss!6lCOD(D{OdITRE$TbxEAZLSUICZtC4vBY1fx^Ny?2!A~ zLYsqbJ?*~YVSl?9+Ro>I&w3BufcYc(1Q3XR-($SuV9nE-BMUGBl#9!)UdtTM?I>LT1&P}ZHQUH!1nIEUOJmfZL&MU&In&nKGC1em*NItq8ii{GV1#DCFym-wpQ`{jBED?Gb`Zc1e1`|~0+UKj&W*zN zK>Q!rJ+{(n^uWZ-So)L)Y_UqToKw@fX9#UaC@UCUTgXe7*b8K$KcX=6dV0a_x>hJR zu?(bZKJ3fwipTjiE$)ykn(isAt`wc?M2h=Lx(=O}-EHqp9EG2ecC1H-;>d*1L1Xht z0qH`KSKj0f_x_q@wB|h8dG2!FxLd}H*l|sn7PNvBUa~;9z(^v_XmPyCV1Ij>kAZvj z>8IuT&uNXm`*L~)P&c#-z4^By^JY`hw=w9z=4I=Au>ZAUpcASfLmwO-?viYc_8?j! zR`#Bs!_+zn8&%vHEwdXmv`R_a+Ikl1v#X)7Kc>FS=PnZl;#fF)E9%Q467jh2n`RbI z#pa{kwcb7!nkg@lD|@?45N9XTEXZ9seI~|Z>Ygg=s{5o{ObSM4T_ zE$=IOk}?5TjTo)mtVok!Xbl&(u~ ziniJz3YC z?mGU=)PJo7Aao}VyF|sIwSm>6p?mgdfp*}~c#$L5) zeFbt64ZwcR2s1+7JO$w4m9R)4u>!PzOVOWb1&&1EMj>ds6l&w5_z@#BuZJ}a;@dX#Yt~6gWF=?^>59H>_<2ECJe2pUcDik%r3qc;u1GOXqd*~t}KtC)ps3u zQeV*ff)$xe<8)Zg@^Hc7v78Pfv}Pg%uN-3HAPPT_V-Wr(iAaL??`|q7eGl>}uY4>l z{N>8h#up(Y@fbP-odijz8{Y;^Idzza^pPel9xAh9>B%DVH=WD{k%5^!OLCcg@@s zsAhUclMlkG8U_+8J{X@PPYhz|8L=Dnwd4DiHJ*sIHqoknQ|~>t(9^s6Xq>0h?)vF` zBXs3gc7b~-h|V|&`f-$S-P&cV8e%~V*8Z@iyW=#ZMWlKy1S7M_L;CS@UlwnESEM&w z)@@-vjpmHg2+1qTO@p6nsFK^tW5B`p+sAE}0TxOf53?ay#0Whtl|T@ZL7mb1Gyi$$ z7fOo4*823rQM z%=fvS?oWePKb6oSE@^IM^Y#gOGxpXJKPIh>PBkt8&dFceB z?RZ#;JieUl{wYnhC|dXVIh-8PuHeEaYoy`V)@WEDHwfQ`yOFH59 zu{oObi4$oCV40#V7@t`P{n$J<>VjD|eDbW;&vH4@<8Y_s+W1UKg;jFA*(dp%{pIA| zosmULq3;&()a?;cz}FtC?zb2nllu#Ja`~jU@16UPG2iH2B<+XhpQqKD?$^$5K6cn# zpueEzHGm%_ggL>#j09n7VZyt_u9cRxZi7Pa5--C3r2fX#N786NY@we#Loe~8A$STr%3N z*yChg-DauM?hFa

%m(`Wyc9!Ida$aCZN=ft(fAOz#`%53b3$jN)(Y^`6i+V;A-daUqp3a!knn~W8VrJ#3;R30x_P6rFGY)l ztP?+(RD#$9dkH+!60L?-CqG>E*>v}qcN>G~LBftl-AV7^bkN3fQ9ZhKEV`m%usEYF zc#H*|?@|N4ovEFlHV$`jcA>wqG}B~mzrN#}m0~m_ObQIAvoOPxslv!{kXjJ@TCwc& zzN)ud>u65DtlDM+$@afB9lI-(+9t)u^1F~vgVwlXf7co(dWzUeT}COv21R#=%9cU3 z=3ruU_jxd*9h23Q+ba^xO61u3vSIG>92+7Qly`{LoXX+x|LniC;Xa`=5yWuNiz&Vy z{wd(_2&gC`zUWr2?(A?3{2_KTweUEIM;^VrQ+ocNc|!KQ_V|~Essd17v_1kfLoHV% zQGVQhM7)0?4#~znG%~@mjZ4Xt=?q_ck(D56*VD)j)t}Y>REu*OK)%aXJ#!|ru#S{D z6rAE|Bc*U{!3kH^h24&4ZPK{nW;ry$GQ3k&u~Ong|FT!ITnR)na+BczbKbeZi-0o6 zQ_#GYw-%^|jPwXwQgEL%T|CfU;6KT;A7+HI(ViXnbm@SE>D0=&@Q}NsliaqtXVC8i zQI1fl;d=$@{8cD|Y5AT9&ePE0wfENa`q2TpNk(^KV|04nAQBr<;lY@&wMg^AlazAFL(LDp2An@v5rEs zj=b0pA3k`OG@1|S8Dt%m zvt3fxYU5{KIb2r7SE!32xyG6OzGg&8^txsL)BfOk$)i}do29HE3L$+FrNsmJbVL7` z7PUgT8azlLx&329o)*%9KM3KWbjC-9Q*UIuZ|bh7O^w6J#XEkF)$6cev%Hw4KqgD_(*B-D;x z3|0pP=-^9J9ecP!**lMBP4 z6DFl_QiSm@_h$1`f`TIB{oy>-VBvTE6;zy#eoY*GEVu{Gcv zhkV|h;J%hgKw$ABp1C4#FP2RAZGUr5*jgoav>?UR*`UC<3aS;tl|iT@fBe#-a~u}% zJ067Z3rnxj0_j)a2+1nt&i3grr-}sA>j?&b9HulL8Z$tVt8{5sj*VvXiv_Nw9_TDu zH`AVf&-?ME{@8D*2GtGx#zR6*s#&vMNDgIYL>C8bR>}T z;EP-80s^5=;HArL?WH3UFskebEyc_djG~T{)5noAw*-I$3+nbnaW?s~Zg}Z$h^s($-2Ax5T?5FDn5pJdVcUs^iAF%boPv)iKQ@{ z{Y5F;R7UO*0Xe~{J9TZGkE1O1VqA}PCb<@Ve*w6mbItYur*59U5bh0~ph12QXx2%> z>1Byq=Y#v(bbp?7+pl3_rxPbE`X<;{qf^A@WlC_?po~kF6q}w%jNJ^S6YD6k>S)^` zrEBqJgEqi;Dfe1pEVB#!6V^3SfOhY4`Q%9(Vx|zrtHb+ly2?5Sh7n4fxD2?YaM3y< z;ywO#vz&Q~m={u1Y%|9q4{I}CiGqVfz!Ua-I$M#7q8LysnTYCKYxDL%BVNL7#wsGB zg&;n6R*c8;ua@29LELKQcF%X&X$no?a{u;rr1Uj7sH@a#(0*N-a09opilnn|HcVb0 z-L0DH0wLh9?D86gUS6fp%W05w;+$Ad-<+n<%UV=AZdwF<*y511>AM38Gy6bCQ>o+h zjXZi!Ao=8l_0anB9tBdMmn{IBpBQaJBZsfU$=p)-A>n4(vmqa^9(*~RCJA3NK3vW& z49p^f8X)=s1`GV~*UTgdy;JG}^P9OZ8-uH6?(iJ*d@pgQPO5qWHj)SF;# zL+aQ1Yp6jH({KkmxIXjes|HsJaWx>o-vwQXaaz#KA znj&Oi=})(`FiCfbO{t3|nQxmu}(0;;;&pfS`KL z%?&2W9o>RnDp~?+PR%Ap8ijWZAzlmy&Piqo*PfgX)DoQweH&6b9Ti@i==-W%-Cc&A z-uPfcoeuWL$SQ18fKH^lhNBoIzU(#G5^)v~bz6)ENNKHPQb-{l&_QKhitu~BwCGqH z5wMPAk>lJUW`I-Fvu}PqAKo`?m9k{=RUSSKipYS3D5qXiWN;(89`AUVdhzgHtK z;9H<)8y1E0J5;bP?x}oUA46WebP7L)E~$hsEiB%UtfFrYIn7#jV#kD~ETd$(LZpa$ zmz3bShmOe)PfwFOSPpw#RniO29IFNbIKDBriw~rIA5z$>kkFyu*=sZXt<7^3eSKw4 zf+r-NTZYnvh-4&wA}kJ!q2@{jR> zGUu|2s?of`JOeGzQ5d$+w@r@j!A3 z7dGnZ3t&_kHeKvsRL>~7VWc$rdhv3VSE{DM_KE%+NHe(G;q?X@uk`e_ z_n!ez5DY19=Og*Fo-!H`S@_BQy>dyr5!X9>t*pgkZkybgk`XK>&S2$U*^G*{J=!W+ zLw^h(b6Si(ObD5@Ehi&(UZ*XlubQI#z&t}tC5dqEtcw&Fs+TNEmCMNQ9p|kgm(DmE>@gN=2 zxw4vnak;SRxCN*f7kXo~9rn>sy*(yhQ}+7>l*8l%Iu^Ko0vny2EyDByJtZNWcTzRx zwqJeO6`SR7@Y}JJsPjOeXaiOTMKU68g4%P?YR`bUYb@!I7L$UwYiEQSK#o_T9`_%` zl|=}Ia!@)=NE>8=>;4qY%}H&~`)S}>wpPQ;cX9P)9=(~Z9c{e{ptzAQ*(37{am=%U zVZj$)kPBcNnrd{TnJfJhll+uCO-^$odrZzGm#z;ms#Q*sTp*oor}Vdw01;m9F&|Ls zLjveBX)14pCaXsCOnzj;C~P2w73JM<%mVj>R250Yfi|nAP|oiFgL1D{ms_aEShvrY zClbLZ9IL*3q2}(Mrv-hzg;R!(y_p>p?dB;6=04=1)awWZN#|Hi&@D2DYop7T%AcH< z-z<96@Pu2Ra22sX9?r4W#axHG><}nNn!HS`ZuZsKc_>o1W#pk{u=pe5#L&jPM{17Rbs{iFqEy+zMO4> zxb=*DYyD0>%--L7MUVxQRP33s>>PEuO*J~ze$Yplj?xoUuTEKy+#`tVU_B^3O^DY# zh$pcmsOJlxI0YT4F`suXRRYimifNKK66(vW-(A9JZm@x_q?uYoRD_|o^jbHWkT>3~ z+U8Ab3!ja4d%5(wnWqq!?ES#{`*#aP)%m&4bu`pv{)K6Epw0Kv@N*RCFiwvaFNyP0X2z}}{R&dP;&(Y9a_h$---F~SB-)4o308l3lp@2HgdCx?U zyC^swu3$KWY_B&^Iod=M4`wQPH(bmOIMIbT?M^m2+~g@@uqL@qXAP)!Yg4=7(i!x( z3bxJqcB|gYgM40|(=9`=N88@(*P5#tsZ$hs9W4b)qxa=?s)#c~`fGnRVBS+olaU#w z5%6P5F}I9vpJt-k0}gYSvl|=`z?^**nAFkqE5z5As>L)RvhLk5bLgO$h@vr;=xFwg zj(I4k7C3Ob*u;DWPN~Zh7jKJHlX9V_6-d8@CHYQxc)G5b*^Smh7&yhdGKGv=xyo3; z70a2wPgh_aurDTnOtL^5uqJ5iJ=(-Lx_YE6lQ8a;n3vW-BUAo{OLps;#@~zJq^?EBkn* zb1%m#3F57!K{jMJb&OzPWkJEmjU?>*9=@xKe=m1rL&UitPq^*@(}YXiK)!MM1VY3K zPJ%CVY419qZ$iSB-gETBq?g1*#l*dqZ58(V?g*Kp-%oMX`fv|dh63D%T{JQ&_ely0 z^}eUHx0XKXbldn4)o7Q&82gY9*y9T>(=UvQo<<1QuD0Hk-Pphv;yar*M z)=Jt}8?K-{R~?5D?d;ekE5zgsyWniTWNTxVV)uQ*_Z_m9J9{&8HV?D&Upsrf z)@9sr2~|m2ZKEfd54<*X!OpjG+S4jj(|9VIc|AQ2`svaD-xd@QXfbSPBLmA!j+cPx z&u+V4OzPc1Jc5_S8efpos^*<4zlD5NKM-Qko=~_DsZ(VQGJopc8~MXdGJ6f1kpK`< z@>Vru49!64Uy>=!!{1@a3GoRDSse*d_`prR`GSvx6Ny?-0S`J_83A5||yV`}1u;0;({wC}9}zEm32}8hyCqt;t8LwF5@6dSn0Oi0K`0{do6dky%z!({dYBr5 zRNe2D3NHrV`gZbUY(V0(A2kFuPV7}khk}C|K%M_2nlos-_`&qPTVA<&Gvm@k&FFUL z&awMrf@8kIPOuwZ)SqwrrKo?-c(BIm9}HqqfwVg2IVjfHVgs71`iYez`|hpQo{zU^ zC9)@#>x8#7I%{^SS&L6@uA(&5Wbf7ONt$v>IXqDNcEU|MvqsWxIA4xtV{m8EM+kJZ zy<7(ErG=pg2#?Q>NYZ3Y))`KD6G}&-gw$p)I2hunuz7O27iM_BYsh_~?`u{{BzoZ6 zO`hK4Eet5<^~*wg<{uwFHg~ga#%R*6;fgaV5%t`lbu?g{J;mqxI-VP8=wbzHHkIou zx?XG~?vU1;%$259w{>MIY#I)nQkOwH`;a2(3u|SWgQ)~)3eK?*n{$Snmv2FWC;ZJ9he=Gi4kwzhTjD|xOT{bLgtm(pV6 z+$>dX`AsjGh!fsa7pUf_n56qDHk7@mGEQ(Ltchv%zT!Kh=V?@FU$J+x0E%h~-p5nZvpI0`QWEG#hur47Ffw}uQj=~}X2jLQAF%}T$m`ceMP?DKo@ddDzDT~g76DHCDH@qz7l0v*P2)s4S)G|{g)Ke44Pp+gVoI`&lr^G8mAWtIK zoZPkktRI<_P4|uOB=vMHF%GsbyDz06Yx}&vB(R`}UILukP>7~m1U;q~YSss;H2I+e zMr8bXo)8kN>{=(C?RbLIty%gLQ1xOK+~r!&%F6~wt{#5^NXLRyRaZ}j`kS@$EFioK zTwzz`^`io~TiHZ26qIIy<1vj+RlYbt6#)*w#D`WUBbp37wGxg9e4DmskrJ5pS z4Ta)ST_qw)g@ett(>p$7^O5iUI8*J6t!LwIlLtCt*Wa|GH0PbGFKKL>xKHla;fQe# za^W7^3~ma`)EZm!Hx3fkNz#qhIV~tR@IX(ua1rBxl&~k=T_q$|Rn>OS(O={%q6Zf{jF*cGqqeA*v;szwqoQLPkGka#wp5N^K+xuv-wyr`Jybl+?eFEO9TWF9AR<9nl*)hSU|7w#iIDS}W$T(|0Wvc+)z&sIZhxXbTj_`RWUqSn+MqIpNpt&HzB;M40om4fZNAR6 z{GiQFq`UIHvQT5Di;tU9-1U;M2;iud2eex((CZXGPiFU@jMD;TUd#xj` zI@WgMLc;iss*JN?U6X%EO(H9e<{H;q*0Z1DT%N+SwG}JpR(*8Y5-^BN&XsRlmLtPN z3VHM*4Nfe@g>u;rdYqaHU!({S2?0>at30n+-@m@9W0ld0H+x3I4E6^_Jcf&a=jKCp zzH0o7?dNNU%L}z>`ah+`$p|Z!@L0ZEOzEp)PG@XkrPsLb#Jq-o?CZFE_vt>vFGIlh zL)FLaLyUJ0tw)-4Z?c75KAm`X*zC`BF3m{Vxb5Tl8Tg1g0NmBCx^uVyRpL|ig z?+Ux-;D7l|uZDCFEzs^)v>IQHLA_h0q1U;NM&?W>(kQkVe+D>+j2IFP98!CP zOm&c{Rx)cIj;JUm?lygUWWXuym?~T$GQFE^1Z6(p^PW;CbIFm1p5Bf=c`$gJP;+Q^ z?6%Z#x5!V*o$luEzIm|jE9j15*8A?6ng{N7WZ!5n72K2@F4H2_G;6xxQ?}<9#60#h zl%YSf;xSD!xojh7hSKCsxT^(ibG>ezhBJ83Oh?jt7b@%`lLyrMV|#FGHwE6XH&acv zV7gx%%vrH^ygIjS@V@uld*PvSuT*Hc`8NBJ^7P`yk9KeOWL5*+`-_=+tBs*CVDP?< z=H3chAJpLb-kprTz+|(X;~^{elv_u^9bCH*@|Q9BaT+n+Ze%-00k3jIk7av<@hiGp zd?}Sqm<74%0^8N4&ambc`t0)uW*+|zTx>dp_5s}8$!e*Bezc>bF=Y&joN z_A?!vXi!e02n77^Eb+Xu`xH9B~)^Yw2`vy7n>fgmMjc^j>mC;R!Io9LQ%)oHWd(BdgT7 zS{{zOLC9e;vGa^=T-Nafap<%W+s*~9&;8K)qVRea^ta{z!v(ljBq~Ij{pd^Q!@lhs zv9xs-aoVfg@w-8%2KQp5X@5*KN0&pW_{MI0Y<$GDf=`iYjB)hc4aKD0?eP3m87IZB z`Su~9h4fiWw%$boejGZb?5?Db(ceE!6dWrRpyofVwHtV?Tyv*%4Q`Na@F&-!l{U{y^PVv8 z7zkxW3z=3{3<;-fmfyqS!Au36t)g9cmT>GhA+Pni&4Wp78>N`Og%QR3PQJjYD*2~Z z4&zj6Ov;3Uc)-LYGgxAf@du6a*!Nz%xHI?vB|rcJua^g$d9Qw!CZ2u)FanEM-|-?K ziYEoBi4v_&Cj1hVc@U2Xxx&(6Mz$+1E0Ku6wMa=O;&j9D>byqryS$h79OP&&F}Qik zes&ib5f}MUT4BV7A4#;y@b1$)P8(riz2>7FQ?VzwCEmOavth_BW zb#zVtz_!p!g`4w_e~2~|G8~$$US8SS3a>4oTTaXMZ?#h3mo%pdsw^E}UGY9VVR*Mrz8+7!nrSOiNb})Xr{4VbF1GX+ z{hRHxBphwU)f%<#^RE2IbF=M_F?B;OM7k{iW7% zZ0i@b1Wiw04QKOX)7;*&uiRZ6P4F)LQmetWd2VHGA*xxZdN9}8OzhH^M}7rSD%8a* z3BO{escUZLy#^WcC7%*sH*UmN_yUCcgC&us8kvVqX+3*W4li2DM z=I0&w8e$CI>9@U*v-Vm9WIlwzo4zCnjodOQ2qF&hUpLYmT)Z1FZ6#k6$)$+JKltmY zRxA`q#}k_V|C%NZo;+q@qgGN-M*7%r2I5D#mEVrJesSU9;+Mhry2=8PH zU3y!hBo@(QGvyyd;BwFr@G=9!&&7;0>Td6j(HnL~WPIzr_Px|k+;*k|x1hhh#OS*l zApyLeVBqMOol>{vt@VDL1(;%fzsqg9=QlsqFI^t|+ISrEDpKZ<^=KFpi6*M!ujEsW zXLcs8lp>kccsqZuMqjj}^3u(u8Tw!yq7%_}N<7;R#;CCyK)>l}K0(U53$asC!30DV z>h>DIx|6U@;JNV&vXhX2^SfL@O!wp8eM^?uHyKp9jXqxU-SLT+H$AH%(uj-Zs2)2i zTZ3Kjoj*yJ-s7dOsdaqKa&l^vysxyEeAxEy)Q)srKJ)N)Ys$*41E6a1xrO2KV2%u@ zNCIy=L+{1;t15;>7iU$bXx5d9A^;_|=dc_gYgmoW-ZNX&+^OXcZvD)|~9JZ3wj# zOBb3Oel+LL;C&s2mdQK#W<(S>XuZ0JEi`i|mQVoVa7q*) z=H+GuRq|_LbvrUaD@RIS;FH7ddPuKTAzGZu)=c z9}XtBO(Hevs553FICr}BdH~}Qe6q#%<#crGTQ+a}618D2zYBWxsfPy27*H$>pZXUF zXnxo$D{1VP`ztfE!^i_UL6tJE7mD<(Z0BnT#*4qvs~9oqxcfZ&5TbU@aTQ6k<86ip zaeM+RXBH`=e%p(!oaekTIP+v&t!96$2z4-piH_5*Lc8`e<_%=v9WF5qaw%ONS8Az4 zI=4&!+^HO}!iGXUPKl3@@sofm-Lz`VlQF?f&N($xD2*C)coAqYYKW%Dxj)DlUVXJ5 z&hXdD+COtvPN$t28b_tD5_8;~*ST_`c!z)hH|RXqIcxHarmmFJ_n52gXAzME?cj^^ z{l0Ps^UfE)j-<(YhRepWRA?V?8mHxb z)?b#O-a<$K<9;Cqi~;=fXb;oLTYl}68Qq)U$r&VI#+N8QA~%`76yvj-ZFv@Vcf)3Q zFh0QS15_*O_{8#CvilM(4c*%EN>7W^2`%hn*zb9ULewRNUvBKC9A>G}@XDgx?H6M{ zq%f^5FZqkN-3s_0Q5O4NQb@>crmL3>p3(TZt^Q{&T;jlK~+* z12Z$TTBjabPhB1>ej_8Ymq?89brwTn5nx46)tDa*Ot;)0%r>2Zh&~?G5(#?Z2Q79a zj8<#c`_={g7j8+m*5_FSuclVuK^=v)@A*9~o>X`ij~}aa`WX~b zmzZNmO`tT^fCl}o>@nJZ|@vc2BwV2CLzEKQ-uiXxn>QW`y7fogx#!*(zKc_ado_b z*2v}*qtmUL6yODGZ5DY=3M{3Jhy&QncSfj)F_04i@&T}D?DW=a_QJU{@+NWJ{TW&v zAAcLH-8S5g=>?N(uN|&9*JMt#K4kDI-{G*MRI`Y2eqmvQLB#3P;pm;e>HRAFafh}% zovmar$!ya=L!|o3!DbwR%ZuJmvAGM63p~dy@r7UE?+5|kYEI6v-sn`7QBVAf!~O=H z@e#V9zU<~61T@i)UCz!5t2h%yLutRihPi6r%+Q^OSM*>(JEwjOv0Wl%f8=nw8@^Gl zwN`-3H2io(z6KXw3Y{RxK3h;cqQKtXUPeht>PtGOc84We$JPCfZGV*Wd!KE!qJ)gp zFy*Q0fd-v=a{{L*w`sw{Ji}}OoymFE+sl*DOXErAdJmr$-EM;|PQRwB44OQgPnZ0k z`5&2rQ_}bQWmk4sl%^&u+g#60f-C-7?+g2o&`_OIA3q7aw@5mrD*4{mvWkj*Q5NO3 z#`mTSy_)5k+*7p@l2Rt?5zo|mhb#5v=xIIOQ4#+gskE9D3ZVFu@l8V zpH=g-3=a!4S+BWJDYD*p4zKqkt(4d8_SN&d;kWdL^I8X5y{~5rq~lf!XoeigFFP;a zOVr@nq0owb@w<(brZ~{VvqOP-iFBCBW8eKrnOBB$pJ95@;afy4GQwLrrM_<@t;52q zySq0m=pFct_yPwE3Ax(uJ9sC_VFt*J6`7BI|L!V?7mh+C^ZAY$RLOGj-|e+41Kjr% z+z0uN4YpLTV}t=QSZZSrSR7llLsP<1b@0M<2OoWi0ZFB1!m#G->`W3=?{VClesZX)ITp@*s^x^*!AE9j`Y+bkKXtXzZr>G@Rt->9~6A zFUrhLZf*^^aKtIV3`?I84=BP?FDC#c7bu+Ld-WI-Y^smw#^AzfM7lM-yC*ZgiYE3E zT3498fdzZPVowasPI_(F5%Mqo)M>Gr#(r>NQpJp<0QGaco&QvE9`$2n3KupI>l++JTSVFIwHLQQf@#ZbpMYaaV$Enl z#B3J1cKvNOahE?;+Xj0V>{0W%0rDy;Dwd%9&1!4hPuR1gqrm8B)ah^wXLF16#4@0otkZzyaM6{A@{M}u}eM4kBwy^?CdaajWZi=P{yjM zDW5%4earnWF)?s3crnPT(K_Ptny8obo`^tJ7J*iNT&9a7up-FrbXGahZ9B=*rUq1i z;B#I_dS6hG2)LhL1)k!S&v0_tSY{iS7h?<=wls%eqI`PJgBwUgD&hFWGON7}gP|;P zlB-XE+87^J$0)|n-2>0mK6^ruxfYMZEV6MOr8oyuJC#*01`mT*T+9cSRsTuf1e2C3 zMd|a~yE~`NQypMaV}rJ1Du0E635jeBVlj*KEqMz5yP7L^7aD-rq`xAO|9M|2C0M$^ zko}k^vlZy%U`%whILPH1t1V-sW6f}Pb%npFiHWUX=Hy5rXR1?E67iJP8)l-I&f#-{ zH8C;C=rcfR8ua~^^i7<++&GgUk=m%ky7mGq$S%cwQ7Z9+2E(+#=;`|+JS1~mTQgyu z@YA6*ZoOc!8X>P!dXT-g{#2?_d+W14w>N?fydJl&HYYN}w61upYm5^4ZuF1Chn!fO z=Fx51RPCXh+Fo5}c=hUsfDZiUr*hJ$Be0usOJxVfqU}Quwr^bRTbvr4=LaG>I zE~z<)OwaZ@+H;~v{wcAr4}M}|Vn*M>nD0*4NHx3iG^4wayZ{W)1ftg6=W1+y;z;GX zd%hB_xJ!f)@42nPc{RvW5<3O!3*)q*ZWHX+{QQhcQHp5vlG* zXEozgZ&mVN8syYy@TBMrA|sjmKKrybS{BiU^#+h{?EKk}7DP;xR(h~bl-sEzX98{eu&_K~qZnU$Pt zKg?{snlHq%o~jD9c{auF+>5{Wz@&Xg&0&lNRcm;?%7tF-&)}c)Au+IKKLluNd?AjS zzzAmpe^n-&OcyKkU=J@SNCTr%vq4P`bAy#PikbR#p4+cnSTSZp!?onquTCdyzy)d!|w~WK>vIGsB$ezOq`dbuDcT{=~Q7D zzE7p^`K|G67v>j=WQe?;;Q)lLT5Agbv+@EHz{tK|s%yX*#7SZsT&$nkfV z2?&spKrvRMHLeezSrc(IrcD~NK?KONA?G>ALnq}6>FpIPH7sBRs3}q~GV+~}x3KV1 zjZWMg^>kF-!>upep>lfMmoM~ZZwI=#Pl@HhX0X|7#_Xifx#9j3Xv|e(?3ru;oHHFT zwwwSI1;E+L06>psQqKhWA{G$DQt}viI{uGgKhN~tONaXjwd}5K^wW%MG!o-S*i!P( zH1u}cc~AMC+z_HTWAz#Q%Tj*uz56vOaVm>so=Mn0vt zimkJ|G||jlhoY^@u$35%aB`p@Ez^8PGK~_C{?o9#fuyD^mhyZ828d5fWHotQVds4vqQj{_5s6@9&w3g52E$BSj?31!f)URB`UMlF z`xm=r0xaIYmQ5HAqRuzjvVx^a?ckq2{n9Wj*l`IVn)J8tP`+p->kP`xB?Cq(z{u}@ zKj)zD>ylI~(dt?eQ(>u%Tx6SdAK`FjtBlYiy3+hV((qv?)b{dq3=cuT%3T{T38gkB z1AX1^$!<@2gv`ePCQE6@Bg4)edhq}jy(xs~x%& zK6tEZ_#p5oy7HM+ttK`yt~-%xz}b$AgF~%Y&VKPd!RBywV9TWk!}6kX4fowax>fFH z8{eDdZUKxunM6tsmXjKa0&)ps8~8cgAx*RH+rCK{b`KWNHI%0Q44)X9{$nd88?dfo z6mupM1MUEtYb5hNR{+2(1PZ+J$6wd6LLpu#5g!sA0A2vmyjAke*bjiaG=14V4t2C! zeyDXi5%^hk_lOqw>(|$D+8(;8dx0iEJ!3-JRMQ!=nC`}L1cGvlE;oHmBtZM%=w&1I zKfPgKVD`V*$Jhj9Lfez`_CFwN7qAR$I8uL2a9)w6<(SFdSDK*$E%*rR*^s9wEO^O7 z4NzQI%?vKGIR)s@cp%)KG+5~1oxByam=6^sbAtjZL znyJ+H@zY0>(^4nCH^10<>~+I;xIdVjeNbMPooyrK4gzj6_!$L{OBxrK9_c6jyN|C| zL6F3FIY9I{4pdRSS-!nO#TW1>eC}%F6&6n%)NyycJe=<0Q8ZA_5nIPV!vR0n=35O_ z1Wn(padEVMh>%D3xf!t8wL)m;GO*u7fpK!VOxFau@GAtY=4`&89!CM73)$Z`xU{9g zn5)%H{CKmjBD3599pXErKhSAcrOt6{u#^SC%-PWW-kaQp zUc6=ydE^Er5aXMR^gl+~ z={1@49Z$>co4ay=n^(Kny_`Xr-Na9t?Yl<^y}{phKhU1Sw@C~TMZ!UTB5_q^u&g>p zWDNUFz^{@jCl}H=;LTS#K$TXG@kIkvDecxcpNy>*Fn=ni_Ux zU1Ew%7d_mqFXQSDuj=mRR|K|8f&^OC*<;Lx1fl6TwgmDqt4gz~B5=S8y*F5?tO%yAgE9TSHEpL7FJRdX5!Xi+sRILZU z(y!-yj_SRZc~_6=bQfcJG)RAm4`h&?RZW1(aLPRGY^0V@pI}E22%R0Q%P|DVcPcPD zUZ*Gn5@2?;p|jIY#(=nlw~>(gE^3JBo`+eUPzqKK8K=?!Vlg`@QjChpbEe#avY}ZZ z-PXXoa1QS=RTfy^Yq3(?o9s@Fe>GHJjeUZqZh3CCgj(Ka%2#HFdA8YLAswg|vB zx!9D3jTPgl6NB6XBbQ8kK3;V8G!hIB0W`8*0dPAn{Rk(9Uc?A~b-Fyu#cjcI{~Dl) zS0Nii13&b(k{}q`?HqW$1NoR|53eP=v4Htv;A5HriYfxdocv?}X32Dg!P!zw<1uPI zu`sH9jN{xhaW;^M<2MwBSH}eTP8JxDw$ruHim6t;)ZM5^k%27v+4*Q}tkvEi+4_VT zu9J&Dd)31+>X?I#d(_*YO6QU& z4~|=o<%boC;m;NLMwJdhLSHyQj{va1^BvCyWx)>2>G0jtcZo{v5(xV zh`vfF+L|!`fMX(ZHHP(yr}4tG{mACD966f*lnO3}BNt4*TMaa#I?Pu%(_-pf1vqlu22%n3PFI)^y66ZtIqrSv(k zIq)~+Cq%V>zPP*@PK%H?*L>uPqccknXRYZ0clJRD!~KGC+Sd{5b3q&>m3pg(1&;k^ z^nM7H=i8?Bw17pkNJDtN{-oP)&nI~afk=>oqhcZIyr)2-vsL6cfQh>pkf!BoSkx9U zV0=l%W@D*)!zI?PNAs1s)1;EXjFJ|C+}m>2WmxL)C8?j+*lHEH53jBw*c30h>|+Al z*vL7tTRbn>?e{RGboH}R7wYUF-$`H&bsLwL>foa^%YyX6(Wy3X$P&Cxii>SP5cJb) z^3{pQxMTx8u3k|pk(_A{5;D`I)U*R1Y$A$eySkBI(i>p7G71IO(U5hO)d)@dJ7cdN z{vJY=TNu=SpNum^kR3qP3lTzXilLD*qG(WNfRT;>(9q=n0u8}Z>U-2jCeW8#1-F#C zk&u`Z8G`++rQ-&cL(M~u+z8#=BAkL;X)@KTLx5wP^AWF>L=_)pXIEaMwvDd;YO>u| zy4(PV0;w+&w5#GuYn%B!GEq^cUgqKHlEkHra1w;(xrjDB)uNAakm-X3wW`RkGY=Eq zY$p|$*z|cYOnaS>qa%Dy^mWN-gx22d4MubRX*^Q5M4^7 zkf=ht80JHo19GQnU_^&2){U}H+!rD%k58IKYy|QzVa=Sxu^bDv-&=KSDxma3#97b? z3z7n;`XDLAwR~Ws5ChYS8)W(ndIq3Jf`vwFv^hCARNmWZ;5d+kG!T6i>+jp|q)K!= z7f`FFQEOvC3a>-E17?4|T}Y*+4Wo?=CBTY?tmRWHg%Cg5k6mSQhEqI!0|PrA!=oZ( zcQUeMk5jBmp?TPJhB6t&2x-$-_y_u*LXtCi6BCo76f$EYND>2@;Cj<2=A&^X6UQu6 z8oV?-E^))d{blDrdSLx{anPR~ogaX9;9P8Mlbzd+a+B}ZxTRV$STCcjEU7lgBC*I9 z{cajHLcT4oA?D@B_+@ceDe`4lt%#@Z{T2i1wd#1HJX1pAwFvav{ZJ6an^txjF$=8< z@w;DU&UI; z1GWjzHgrOmWiY?@L?a<5873{}P0N)h%82+A2*Z|LP|hDsMDq$H(AG@Npo zTNYArat1qBy1vqp4~Ns=I771Mu=Mo0BxezV&rkGUGylaF@yRpC)K1u^UpooIqhiMq zDmGt`@sRea<51w^Z-_9`u{2lg=^6l$9Ed{?yNJkOlblWn0BHC~I_^^Xx&0#PZ+kU7 z$=&22X%SWO$1)wMT|FE;r$Vh`sR4Re?l_DqkumFB)LEaxLa2VoJa;v4vyS$*IjK{s z5KScgn2<{bDiVcir3})mv0{e$_`>k=+U3`{LTYFN70BK(DCJ5yo3Agl zW{%sX#pMRs-Dk0mVd9-IM;;gLJtOod>55p+vt2J!@3si}Vg+c-Zri>yj}gs3F~y@Hc)Wg7-3LyicO zmY0_|3<|~++MH7M4Gc(k&;!rc7O9Sor8%Rhrg>3Tz;RO3J1tP=yXR$%V(G|7;be79Lyl%)h0m2ObK{jVSS>iti25xE{O&2EOn3Ez5|&;997*a4PFv_> z*pPMK5&py2NiQ^%?sM?9R}pb>JpSm6B^7Oj8A9Sv@<^Mf%giNkIpMm$FUIJL-K2k~ zMYan68ViHW1LwGnX>yaw(9_fNtEc1EHl-@syI5*4g-8MNC^mwPoLhtwn;Pbvw%G`ne3)FS7lq1;GL zw{EwlBH5sHPJ3aJ@G((y@~O%Gf#pTCdY0DgFjIe0tNurXluTti9LZj7sZ)m+t10&G6&p&5c!tlJUk<1^csw z`T2D+@x2}ngSt9UNh_%0iyS}9294dbYEa-Ns3#nQii4w0Bt+f2&wyewYMNDPYV!i4 zxb1nbaPp`@o!YlSyxlC{?_^MK>sQaBm=sLg;NV~^EUf&@&KF=7wp}cQpB84-Fl^ghRbtG9oUpO>I4z zE@sm(&@~SwLc}~eteHp`=Oc!04u5_Ouxd1GCQ`77pZvQAKREyuUN6`y)e?jfenG?C z2A@KMDgWHgjsy%Rf)n+~e?ATQ4n3hN*3_x~Ymgoj>^`V)R74ce4_JWn3*%a^8q`Mv zevHw;$Dsk2|32Lc9M30po+}Ch^8~s~3_T%9pArs0y$dx^??S~cANYP!Xj_ONSTYHd z)k^`e*k5U;W5M06`Bnq}X&(CN=m=0^7Bqzt_XvJ2$n0w>bR@tJIURU*7WThep*|yC z=mnC07xIjtU}%>pE(U<10PtkO?`2$(e}|D5dJ5~uB}V%9+=Kvh=n*VmosasTAeS$o zZK3>;Q5-a6hm>gmMh|q8j|BWhY0H@qNc49Q@`6Awaci`b|1=JqkqY4K5*t`A2-@1B z1u}lTQ{MeM91YMgmR^T#_P<+Yx@w^ZWZMU))4z@NL+_uyFLDKM1*pKyR_H5^e+7O5 zrH*pkt)F>o4N&Qbx zAnd|GlKzWlEPt;!>H|4Rrre470pxfLjg$o_ttI@M#xNjaxDzg-+<$~NMg({7Kgu@v zH+laPqyU`>qMZAuRe|%MV;jT&)iLtGHt2=D|6I5OPb)WCax@20BS25w0ZK)(e+T3f z&?imas%4S?O8o}v>qXE0O!0R<61pCsZN2={77=L3Mtpkj&j84DZ38cst3cYg@xNIm zhrtCi{~@67{olr^jm@BQ`y^`tw8aNipKtsAx_<{Oj|IG)J+|2WcdH0&oFaIz*-d-_ z-QT6d10B9|wo1T3`c42|3%DSKgM&D9SdJdnZ; z=Cir_pZg=h@XCi=djIQZO%8a!J5x*hU;R7+GIDpszoz(eC14FYJuMw;U%>PbCxDv~ z-w=lXRmf#_@Fanlaz2&+3M~kYq9Xptt$ac zVfCMPK;hSc*eq6mKnB#{q=Bd1U58OYnOEdMYJ@k8ihpg%cc?M=>F(w3IAQ8><$3(ldcWrc{h(I0yjH25>KXchpW zBEHuu{FPpGxG#N)oMr&3K4xxKTzT^tCL}TB`)-*t$-0lT9@(HQ6H~etS&>h9UW^gi zB`y$Ti^&Y{SWxKLTtc` zudZeT$B}Mf=5ZRPp%?|4e>>(F-U$E)bV^ww+S>0dowR&pB3qa`=&4LwGv#RwOLv2< zti7qQ(`A(4)y6mzGBN^(z0a68y0nwv-bi%OU?0mPlZNVVbdE~UtPQ+%;&bBWpQCrF z!eCMOG82wzU7lhSsV1DFI$eMt<>Aq@P{}^8k1Cs=j)9CHC?aJkFgB*1kVP2(^OU-m zrhnOVT{J}cAzQI!;t#U>^`jsnGV+-}x^=hKf8fgG?7Mo5Bgv#ma za7qt*`{8SQyp;*rfp3E&>s$jzKjg`+0;GyaT+5V6r+lgb5lcR$x(o9ZkkDj>}bzt36{`Y4YX$ z?XW1C=PFe#h>#>sm9|nrHHw)lCT+@{7pfzerMmF=)ny$#Px5BNNp{P)1;ggj** zN+EoNFvh7)0>d;Q13QRh{wXg)S`~*)6VKw#rmL?Hm*KT6pZA7x7SbJ7_4&djOY&)Dh@iXa$_hnD1$GMon|3jMCL*&WY@A3}AG~3xuj(fc z+~nV70fp;x^gB8b|Lj|0|Lkewrmj?*?=pw-jA?d32orPp9l-)<9#+UxDs;-7P5yb= zj?kYCIOah%s`B@?bLViq3`iL6$~bIz0dg?0Dplroo^mI{8%swHct13U5|7aJc7LJN zHp%aT|CtDRbGx#XC9P8ET~xtVCuek%7k>HcC(xm32)u#ljaeFb zQFi%8=CpO!CIt9G!%Gh;CNkxU7drJ`ed)H@sr*Qn+ z>k)gsQ4Ga$oY34fK^}yqUI#0PUH|(+Ws8Q=1#Fr&Ci3e|_^c;4@Xu zBp8U3>4JqhIvy*Rar#NWgrWhP*;SyTN-W$;vQ>4PxZBzB7z zf@6lC+}>WO_4bB+aEJg5{Xk@{vI%(Z!DfkCN}As%FNPdXZ<|4J6yGq`G4dB`&GEPI zbrtp`4}AC55YDaXVEHeEL+9Ha$<3LR!VkZm8R`k5sk@cCcc<4c*D-IIZG=CMYR%X$INdcrAKV#bG3*M_#p3(N78-Wx2SGxAL3~h;KY!F_=ax zXqH}eOFA#n4JDs@f6i2@+e83KvR}=uZv~!bt})Jcuro7T1@$wB8ZCS~8aBaE7KD_~ z`0>2sD!XD^92K9b)M&&v_XP|6Xqb$yTTS!tP_ES!5}Ra43e?0nlTs0RjKlEqNqOgf zd~acE+5D9@E%~`{{N!#l;Re~};s6J0Dmy!{HDpKbUCQAvJ~!%JUqg}?p?={fZ6dES z7=dJ^pZh*T`8)vPtjQ6A&3+l_k5|~uy}RP+ ztSZIg_bk+;OT_Wx&$;XP4CeL%N$J(w7}0ZQBI|*((D}o@(uFl_QfyK{3Y>)QaH^|U z!8<^fAe>?%IDdp)?^ z*}V$-mvbyiQ%xV{5Mlf#S}s%-<8fo8$afd%w8Kkm&!C=q(}oEV?_=?Ro21+CW(JV| zfqZL1jpqtYvEJDKihduuz;1s-v#7Hha1tWUstr3T^pY5j5l_pLy~#Jj5WDi&qc&aLAfpdeR+i%K?xp|M_;nx{!8ymB)wv_t?C6y9VR zD*aogUHCWidhDnh#%6Zo&hOd=7-X)BA21q&JfgZ@D3gbzAGUM4WiES#x+aDi1ER}` zE`+6=neA$$L?+uu8}&?p2bB{z__Zfe@lyT-Al`=#%oI~$FL(4Nwhz?44S)vJbq8V_ zq0qUD5gLGKMl-9!3ZDuL zrubl{y^mj8iheFGFOatGLu)n*qm}Da0s_wWm?mIImaqDZC17)d#!GSNI zj?D4{oPsx*yO#T{m7vm!x`X!yd}`cg#BixzJ$PINk!Ya}lsEp?QeAT$8d=y*EM z%jdF4o+eP5$dse4Cs zkF4B#G2qGA6?R~uB|yu5xDgc*C*OB{SIbBC_QQ+}@csT4tABPJvLBdG$>;4!rsm;a zY1uYYV}?n;f*m5g+Yzj++18G?R&B9@RkdwNB&L`O%w^PhxNXPIQs2wYW3~$ zy3v0{napH9d;%2(fo)t0atWo|d_#c3@&ApbLNP71sMObQJcrb@Auk-VoG=1nE~v7P zM38e)JR0nc01S>c=pJX7-g%`7Lill6-T8p%=kbg%(-HRtiLP9?W}ub=h|q6)&EL>3 z_fdWm1q*pAy8SJ~G~*k=3mO#B+IN8Z)zMovuV^Ow2sDoTN8A6Gs(@qsW9mFqV68Iq z!58d}Jq0-VXQ;A5Fo@O~d<+i$fehteY#{;ug-30J3-qXzo%@lkHjc=KAoI}$&7Tuq zU=~n4XC-iKNeDm#hmA%GTQ^D2BtN2z$W!nq5Wnw}SSObep@24qwDZshRs^83{0aTL z`T?gn3GXBa56Cr)**DUa{`*Pjs*HoGG?s9yn>DOL=N=;y8i^q zfyo$%F3JuDW4wE-&^;+&UtwVjEHVCEX9KhaXY@ZkBZ2me%ExX0C%7iic=Ng~8(b+e zw%KC%av&>$3+-EIbWo*$KC{6iH~}~7@UQB0tJ6Qsel3(6!8B<9Rs^4qV*n3nsnxtk zuF&fw1Wd5L^+@$vmw~EVUhM!D0C)n}XK;}D9>Ek#xILnCiU1p1Kh)>L*HK6l2X#@H zT}2mgrS4v=;q;57dnqP(SyI6gRlZwL!iB0e}OJ&*K z^twM$eGR?g0e?XHqjTWz-@g;6Ai0u9PDf*DWNZfcUdcGN8dPTRK&xY+d>ABV5PyY` z2hM{x8*PAZ2UQlbgS`|uxIf~4gvfLyg1>2Ou>dxyCqJN9f`qnlO9jz#O$;g!Q1d!t zWHtH}w7zZ*hmb1yRgLCo{J@CaZ;yK8(SuP^P^Go`3?pBrF%w(|AnPqBO6$p@YgOs@ zUAa76-rtV}*}M5~(#M<)?PqS`7jroltXmGBc*^^IG#}cugXZLx {an1P$SM%yv@ zTv+P?DikLsB?UoAeT0Nz(DZ_Lt6N&cP~!OeP_nXa`XRL%jo27muwu9XOInkv#x@n| zB5($dr__@mxIGYFsPt{A*MeaF(eVvAau{jojoHn>3%Iqx98`(<1xnuCWXV|l92)&j zcwc<)?oN3lk2$%}IP*pFH`?iMIh>F81=`3v+1XwCZLcH)E0lA!yhS4_C8Kb<0q?#N zawFkQNff|$#xSeR?(cM;Ran!+iQEJVIj4N~j?I{G`n_y2eD6packA+!f?)_OEM3c9 z2++DFsMhgh&7eY$`2S+LUBb}y6fWpZ0|Q7mARtl&2XUkZ%Wc9F=)JSyH_B;rl5=!~ zCwt+jTWqF(iMMUeGAMFjBpz)GOJ>Q|*iGHTE93}}%DN|+%bkH5dYf{av4PcQ-gobx-&NVshEa%v2i(J`UjNyO$F&2bUUoJ2l7S2OLPbXqA}6@@?B6Rjo2;lJ_J-k z@h|S{^FOYjKNh3Q9@iykBzA2b77TQhMG0Oc|Q!)lm2I-d5&@5|aX5R&K~AAOGO?tXETQ>D&09o3K< zyhsoMNN%#Ny;S{ohD=dFB>uZ_Rbi z!vboqi>IpFaWb;UYT1Cf*EIOQ(-#s2Ah(CBT0@;qHBoib+X6&{b=ER39pv4og^yp!KOsHl zv7Y=uu@)Aw(Co0(U;W~+dtLT$2%q!yAm8b)D~^tvbHpnP)NwOYr_EuVH?~s~w+qzCDUaOZ3QHMlLw6qF2e7Jya%Q06Pl1XnnVih#jH{u(q zrp7D{+Yj}D1H7P*Ay!f2M?>p&Z?Ygm3^lD~j#g@`3b1S#+ zhD;&pa|LFZ0%g?p)+#9F^65NjHHpE_Nn4xmUdT@@iVr+E)SJTH6LAYb)xM@;*1IoCvUepD`lp1wb z5%*+FZ<@|1xPr@VSiV;JH0+6_3I3)bipt)Qcend%A~YWd3S z)~5GrMRM!vV*h2CGvV2ai}xIvrYV(blq2jse<|(vk&2N~sy{TA zh-cx>^vi>K$kTOQ?0$O1Naoeqh(vLfhF8zB#$;aG{f7%6>`Q1hniUR`!ZNt*n9Vi; zQ*EPcf-c8LKSw4mDoSeV+rr4M542>$aoK>=-F2+35hm6Pha*SMcM|rMt6NO%-p1># zJ($ir4KYS?q&B8v3tp~?8Z{b&BeSD$G;R?b^J(-nea_UzPk>#EU6IxW1j%J`=#C#z zz^Bjy_4@Orjgcb)Lk)1mV?{0W6e!(pgSaNmc&>3S`WR>b^4Z&A)AE*R=gTh?Elz8+ zVNVF-%m(hcQ3?NFJmtvF8uZ7Iglb)%_HHWb6;&2vyM$xhvFv7yMW6pVtHY`2`P?%? zx83_r_xU_==iMhnkTv6KB&evb6i)wC)6nZ9>LQU41UWKt=9WQ#16ibbZME={`JiHW zKcte-{=ES=4_K(I@L=ZsrsDD2P@(6` z`)jciOfM4MPovzls;;&DK1%lLCH9GwU%obdcSc=ZL}00?0J14QtTgSdrEInoZgO@f zp%pKw*J#K^ZOC-tgZU%uiEju3m{1g~epgIsr*~msAD(n%EfPfs%tNr5A!bw&GXg}X z!H>AdFnut6PqRqEKlyyM;&YH}-ZNyv)nsd>AN|SqCqvn-=7JZ3eHL6?b5Js14Rjr2dkZhEVrPsd@5%USU;@aJ; z++8_5#CXPR<56VlOYw?N~_Y8}1SZeYgdTc={b5Iz<)x~FHy93|Sgu0*`ALo}Es zjTh%7FS02n=h>LlvZJuOGG8n)hW^Tm|JA9w7Ix{ejl#gVu_w;L`=f&}^Cc^?4#-F5 z{u#qCZQVEtX97w#FjR#aJ`o25`6cXf1=G?NqVq=KJBl%x=GQ08fY3?GSv;ERg(X{wdnO6l_%cD2!=fHD z*!pKh;6;f-8iTf^z$yTs;`6yPCn*Qhzh|~Mxa(RD&p}<*O|BAC=G8X_hVgt(Hgagz zpQ_bmb!Xi6jk!^o^9IiWI-vJ$w-T|Q$G9Lh3go-;L%IJCUvC)}Wz@Ef3Zj%C4T6A_ zG>D|6(%n6jfOIO|DGeeek|NzhcbBAe*H9weF~nZu^Stl(?fql_66ZMJn0u{tU+ao9 zqKA6V>Q26wv;%l5>_3nTN#H8>az{_Q*lgr?ak6tj$#-EEPpS(%eO;w@93!faT(nZF z*NlV^Ovmwv(N;z8@cbFhhA_IR*JJ#NXzeuvCTh6auy>&8D_V@d9aC#}C7R1fsANze z)qQ{g#xTx*x!6)$zcC+k=8YI_gmc&DZd9++0GO(y?B&Kj`}^^&6i4Rs8UmFrnF%1} z+SdpO_H~BdS6Dqt&uP?1Q}(L}P0$(C9(!Kgg{`m0dwyn9yz+tChRDCO!Q-u5+WVGN zlB+f>EW8x1CNU3!gmD~Q>*hHe3;_3V7_NIxoR8?_paBIY$o}C3t3v~*!h|&E2Om&h# zVxCc%eS!nRn;lh#6I-!R@;qJKkEubfCElFtb+v zAIwPPO-DY_j^3r@{|;e>lS*S0Bu1&}01gZD%h?l|wo_v#-#&ivW&WZRZDUp&uuick z^LG!gjSqj<=JZ{uP8(cE*eU!qlnW>s<4T9w%TT3<_R^ZBint;H#1cgJFHh z#@1wu$i-T4jqNMfb1$zNyPw7MK3er3a|D&D&A1JsjF|t1#TRC^{#Q5y`i)IjM%L7E z+F=+TsL&D0y)ZGC?Q;8J5$<(=VWZdRt;qWiv$CU2O+tLyk_}W9NzRrWXuEm`*u4Pc zo>xn&h2zjUR4o-2L7H3D{zmOl3KNE-*1`!X35kVpFq==(G_g#Tp0z9rB&Wc;aw(WK zXcq7&J9DET>%?X)Hy@Ll;JRJX?b{$bTwP5Z!X+oPjZV<*9f?Yr{_(!^`eNZAEkz8I z`epux86qpK>p*0s_X(8}O~#b{x1ySVwf})-!tq}k$CY%iZEgZMdd1TLr(gZAY1Ggw zsF^oV;*+YnoBjgH1#C*;$i6=5A=tiv(q(6BKJ)*@GHl#lvDK?fd`wl0AXVM-E0u~%(SB}5>JKC}_62NIId`SF= zhn!3Nv-Pg>IWDiL6TVz=cbPK_F1$c7MqV^n)tP%1K64yod;9pz^jgV~l5#Lzh>~pD zz8}Aln|%wYTV+)?iKA2DvFg{5D5P-5=2-^2QB%aZsW-Vfnwpuetp8Fw7M3|0ygc-- za=&}yo>3AK5~9;b*oto%Vfc565H;XwKb%1VW4(!@8kUO_Yc`Y|4Kz?zWBxC34DY!7 zm)IVm6*>~t`$C2t`6`__o;yTt``}D#6`8nxUjz{5?v`k0 zB&51mhIp6Sfj-;D2)tJ9VU%ZAigsM<6I9M72*&+|p#Y&~GoV{GZEVCkT$0lYPf* z9^uw491jmJR{0BJ6qiPedN$Z*9Qa49&3n>|X-m%I@h_v+HT3^-_ zBL6j-l|Hl174S1^{Dy>|e|~TfuC~QQ14vvf#G>-cKHjuJG*Z!2fY7qAphsn}M0~~+ z9)_PQtJ3v7=|r>~p(fEKQ{D66-ztJD0#R)KmTx8?cj4;$!v-lJN*{)os_#sj^pg0^Zo@lH&#oF zaK3&ckq_LKy(cD(HUdIp=K?BjphOYv=lA+}f8nrPPWABk`1q@9cp{@3#U z8_wUQotV-$AFdB+D5hVHCPH#-TQ<|V?*lA z>-7uzOv~|}k5Pa)^=xZ6T?%U44S1Cw;@Q+l!@^w4JtlQo4C*EXNuZm=tmz?ujoQZ# zQ`Dj~q~x+urUV)B;W?3IYo75|w0=eOwz!?mF6%Rzo12^L2Og}O-w7l@^$Ub@(hbrt zO%8;CM~T@(d)ZaHYgk}j60u^2a8#vvm+q-}Ty7NASkl4uFwzK}*c!}n)tI3}v~%U)AZF}? z>@VLk!&=-3BA;yj#7!dn35Uu}&Uf2Pt1aS;jEOWzCO8g1jI5tXjbVVcTQ8zK=D6un zAw~3;*RJA;-e7}#Z4R>r#@2AYH@_Ama@Piw-wBkkSq&nY_ER6pyv;*YJ8347FJ~}z zP(e!pCgD9>fpolXtgFj!w^Zk!;d@QUX+D_P5eygQ2?5hT z^KSWe@M%3RI+kR6-?pcf;aOod*BF@3_sKltxZGed{WV$}ia*XRa z&My5Ug{HMNV%SzlXnnX?E7F%W6`mqmOwRFpbFPEjX-GiFD5!NTaXmwD})Qd$}^DXjq=2=Fm4 z=#2GUx2JT{NeJnOyS#mp5Ndup88L*Pr?lo%jpZRUc?vbknD&U1 zUjfed(d2L$hwoCBXCdZ$&1`C7SDhGl`+%zp*wQXwhbB5w7k#m2%G9_SB&}WYfMapl zs2gI`QWxd9bqO`{+AYMpx}{Xm5Qxhw_y5but-}$~K|2~H62Xn*xRGWCZO7*bh^P#{j0+4H>y zug^ok7jLhTsoeZ?as76}eg;igxMj178-|^%Mz53!*{b<`SVP)ARb-*k#A%9>?p}i> zn}q&_eYTs%z~lCAo}FaoUPJ8FXap``;GT4yCaaBt{=rPc24*C=kO~iV&;WEzYHiy* zUHk~va%@h`y<*?G-yXub+2{HDqi~jD#xIF(~BHyepsD+M}zTt+(DE-bc60kT-c}-Y|V`a-a6V6p& z-!w~ELgCH_`KwG-7tu)B8BY7Zz>WJ1*RefEPKyU;?Zhg2d%)gILn~f z123Ghy6DoLCbgU!y{2X_14E0n4tsXIxwe(S5V>oP zj^ojK0b&G1INmcOeBmNa+yU2hN=eM8mZI2O_8&pTRSLWUBX1yXX8>HrF9>=G0@muU^e`9c|LD&~penK`q z642m@@8|*@A@Jp>qR!~OM^wDt+GiX}U z9*huNREC{?TkBPrS`0Il=+R-I-Jf|ba3|zOz!nJvM+wE_uIvH<)14|CoDpI<0aPTp z0Nd_x!VQhbV5ktwA-rXR0wiDHcw67zSB)j3IT*s^mvT!G1k_Lepu;w@ZD30BgJ!9- z$QurXAJDC}%GxSoh-Twmr-tLh3$C7JjtO6%`QitDej=qkBN0h*%rl%Jkdk3XIH|$U zBN6q+hziu)Z&-QTUH+82uKfKQ;Qr|zG9ntER%?_fzj1ySzddu;tvLIGkE6zD^!Y@- zj(+-+l-pIo%Dy5q@%pGv^;XNumn6c*uYga_3yFE&Wj9oyjHNX$IADbU58pn5#JblH@d&~Z1!h+!M1bn_cIo}I1;#Xn;`=*MK;J z9hg7-TTK5Z6bL&zJMiu!}WqRYjlA|s>$b3S#t!ehtoZ!1_2@;{)fvfXGAi` zvq`CTBcUADK|7M#ZkpwUTCSP%d`PS0grFtL!a>@_W3YSux@D#TeXTdL0-ZR=r1F>1 z?r)&3vy-{3#4t3Qg~Lb+`bYm|s~=DQpP9;v5WW3mWZxKH(5utg9;L&Tz^6thTM!P= zN#q`?Ebc)}QVh$7{=yCq9d?(RA-Qr>K+V!SoS<)wKKh-71p|N0PT`UKxYUUi3MAIp z`Vt&; zs`bd`evCyCOmyy5enCMfzkGH*I}fbyvmSji zozL=V#7kiKAOG8coS8P0B%?m0B#f-YZ->2xk4O9aVt|t;=QjDlwzq3gn8By zg|%U8c`Ln?J{5L258@+DR#I-M_A?0btSd3Z$oXr!{df(e5(+g;|C&0MZMHu|Jz9;d zuPEkwb|X5^Q=k4|ceY3XA^7tC$NN7=AML%Gyc|pEx4MK{%UaIE<;Pj3g6cjU|5vWX zy|&DaC8`s}{PdfO#q#Q-_(S%i`|8wC;E;@a5JhUvE#j$_ZRA;I#Jnj3*fOTN_D4EN z%TiUq9wWg9#J|bhZyB)JMpt$wV(S>#(g(*o*;jYM@C1#{SLk+GAE)qZVD|$59klmv zFuVOwkXnB^oZSChz(YP)egDLYJ)TJ)19qyQtz9RWoWVU=FN1UIu=!l@NZgvsa!!1y zBrP>HQjK2hmFJY#Nm~8Oz^>*hFeLj71o8U$z9c3_hlZjR-|v1Z);SBC-7hxTUM$ME zsSg!_-R)^GPiKh+AG_Uz^$yTotA@Ce&pcLuJ^)1emDRN%cF>!*3Hf{U+K8Q)P{Nywk%v#&+Z@i z++Zwqhi|;03@UqM$Wa3t7Omz>ADVgfWp=r)_Wm=TjCC!JxYeCv$08ebAA@4$WubKtAeI`TfJ(aM-jnAqcR^@dTbtfE<(8R;l@${<TEm={D<2>^a@z6j`nils0d4dL(o{1etz#!(LYo0Qk+3 zhiQSDZN)=w>&YGv(#lsW?+rdLjXYw%aC;;s)f55jO;-oEaZ&|5CDVV~PGmEN6JK=R zwcd4Q@){-~=gE{iyM79ZD8lRzWrwM{@dYqxc8NLf(4227M7rDao$p@}c1lJ|CKOH{ z_Wg|c)o2_;DG&|_f;Sa#)GqoixpvK_SFMg~k2P5hnYwkyIZdX#s%)2W8Grra^ZMg= zBgUI)qcc&otW0!eIwZ^T4gTZCJ_k(WW473C&_LK0{nL%9UE_q?GFLA|_T2-E)OaZ% zM!8CxLq7f0<7Hp?a)h#)?1pa)WjFI;qftk;<)5kMyrztcnNeSaI_32lS%0IWp>Oq; z_uln}-@Rihf}8-K+Q^4j0TG;{iwZMy*~7bcZ7EffV; zpqikXK!UKOFe{~|P+cW_N>N3?R--yGYig{pS|g|7k6oE}m^XdRj2Ly_bqnX+*7?hN z-iy?f##GOd125tG5xC~&px}x3X8Oq>U{vEr$R<#T)*pXxTxp|nvbcB&=6I2#CLsf@ z&fZ0+iW&SS6&h&6N+P!en16Q7R|oasE5Q4SBNY&iQEm9%bHgJQpEpL4mR`-Jfc)k=Y9#2hENX5$oP)!0<}CxptN&UjAOal z*@ZznXx}IQ%U}=y3M8+G&fRh|s3dWryW(##%A{AJich1bV=Fy zY{8|%3^^HD#1W-W0GQbp!7K}KfH>O^P)|e=%aH~8x$k}waihO^xR%54cNq9mLoPRx z3{9VBq17yrB-O=n%)dl3$1&1_Jt-`XLphZL*_e;F*Z?R`o4)wPqClWU+_bdnxi`04 z2O>5eYP+Oquf2gS-k^lC<43)VL-~}*HzVZibzwcht-wp2v53A(>> zz2nWllU87X+(gOPRK3h)>L|krN@yT7>Be4tC-(W*Vj)ckRwAtIBf4Y#eI`|Cqc_WMuJ@Q3pu|HSD|JR8?jsrxeyE7mTf^XRS;{W$|Cq6k-hy}>_N(0I`;+h zgm<&bY9KWqEaWeVenRv<}NK(q9Y$Q}9NMrr9l68nJq zPtl2Qe2%XZSv(G@K9{>rrEaUXU3&FD8BF7(ESmBPdHq2)t}W2jK)bNIIq@}l0^M{eL_GB>Efg(h5XRzg#Lp-_+`>0HUxSy zsV7KiTrx9BVUX?6u$)`Ld~$h&|L0cGH|`a)&%7bqH`YhvbP-AK2lJmESokIm?i|n)`A`D%@s4-ZQRd_0P2Ws)g}k1vuX|M(Mezt?+oU~5f--25p>|ZHQYad_ za8(u}hgRF(-abZPA1Qa*_KgRCl+a(XInpXjNg!VX1su(L;jCbg{2GY2Sp)#vt*cjV zMwB*i*9ZmnmZepNQ%WuZ0E7^QPtTdk;x9BFylpyjd1|vwP)-@>EQHlpWU%9@M-q?4x%c8hDWzP}Y|nP!WPhDwZp04hU73vh&jNmPHDIor%O z5gwfHn#gV!pw$%lT&l1gnr~Hn2+0@t*``~n_pC_33)pQ$)iyYPHcpZDT&VvfWiwax zOutc3dbKp0iBO<9-gkhZ3%C+svo~Gp@jKF*h*Zv5rjAC_4G?EZM*V#)R4Glv>aykD zDbao|(yn>51*D&#&O4f+5^7WyW*3FpQ0nhIwpJ(df;nl;o)^Y|9cH0pp5LiTO^nT+ zT0myJwQ*|6sX!@j3dk5SECyct2~KMUUV2AvKOcYNH5Y#AeO_N|c!MoLYAV;L+8sT# z1fwZz2I+BWocsV=m$8e;krslD0~<8j}fK_@x0hi7B@S2Y~Z!+9!YX0%w|x>pr*{+)O7{h zeA3;D$s^0}b`oP1zx8#7su-=jpHo{f<+YC=&1E#)A%3B~=yC)%pd`^e55_BJ(wDwW z1fsjj|3vqKvI^CVp*(Wlna(YBfBM0krq}gyUhuO?Wr!94SpA<2g`GVR= z6pVHI_=%){z@rVFCebE?(;?*DnVQM2ZZI2Igid+=Og&>BZqQJrj;QoasI>3)PIOD* zY<1eEetq2+EFv&V0Ho1E&FSK6te1%n&j0#*T^;u?W*Uclt8Zf%j@uipOp&i-42s*; z19h=PUuaB3QbAOPXK6zB3GL7x4lpc{Qo)V=s-`MW9ZH=Ys@@kt%$iX9fk10wH@ecL zG>1-LuIVOg0jgDQgcRxn4zR?2!+gu$yTXr3%?vZS#5Mqg%h;_dWq>HVhgLzWUc1qy zWWk@UbZaNZ;hRy4z^hupKpqYbnJMqfLtGZaYukpcfD%rdgij`fJc&N={)69M^bM*8 zxcgmKRj>tZNUMrU>*XS=VGT0P=ct;7PR-Q!*4u*WRPy0fgPX8oB3zgD=}#NcGm*xH z)zBZO2Y+w}3N{H_EFWB7Jfl@>hg9~?ebR6@3sWCY9zNp6A0{MY&H3pXWK^^~-O(jwEvbP8ag?cHNeM>GE?ai9O-PQlYp-u9;wyc+b!tJYPJ}J!#j#D= zk5GogS2g51(Q8|^FF1aEa+T4A{3aGqUH)^)kI+~f$&>H>t8t$OEml@_(eLhEhSuQ^ z@(kU}=HuFM?tj%Ff`kI*%q0v z_U@$R1E`m7MSi)C*s)Aafv#uq`pf$PdEdDcwp7BGk8j)!O^&ls8!?5BUN;y4k0Sm0 zx6Gv{TO(`mgI3o%vP$sFpJeomrOLG92_w4tH>BG&Cm6?K?QbvI-()AUNdciYmvW|# zG`{8YD^2ztgL1+x&05c9R-WQzi@9GJlPeCjM%FS_nqJ@IQ*C6i_Q3BCaW0Gv|Jl9i z`+r?>Ea)}D!on3NKYskMSZb;lq<(i*8>ya3H51MQ0F$42Z0EjxKk2FKBB6z8zPE3`nr5)*cr%0k zgo10($tRnRUp9O>(wuefWpYapYkQ5#&(D`eHze*pdqFWG35^@^6Zs+76g@@kwY9U^ zUwzcFRS5%1X5KX&?sVe_*d#FjG-4jB=CK=NSk#GmMmA;@a&>E*bPUlK7)U#*33`=6 z?qq@ldV$oB-UDoQ4k|Et4+GMgZx+aOfFnWewtegE%W-z|CP9sILPj6fun@6jO4^ZO z{Z_j``K_XtbQOFjnr}wtbY)G=_sR)J*p3`SrHgF#p4)uNC{PIVI^We{)Q%WX5ddds z{Xpx+??<3iHko99<;m$bDs_EbkP(?dUAdst^o^j7T%&7A+I#Tg%Ct|d#t!)u}VNE>7n1g$>sVm3E13v-M(^i@U_vqkGYvIt~dPQlIAhfXif~EVo}NCc}By<&vM}u zrMg(~pXbSUkZe_hqs|dDEKJV5iJ@<*x{M1YaDhLwMU=x584}CjC>(b=771q|4#?_W zfNi>jbQyw8Mmw^j+iVrJ5N0(}Ukr8+X7g)bs4+_$ zn)QnKbN5w)XfZlA##hn4uMz_lPDTY|bR3@hPf#|8qk!n>`alYAob-2<%RiT9p2;1T zp#SrPk{@Gd`rb9M#*#xZkQ^pIn4kafrNEKLXg6u8dxUpiU3Zj4&v9ul6H`ANP2Sh)tCPScyI}#-Kqk;02vO4XOGE(e!i>jpNM+ds; zt03-1z23S@17e?76)q#RnUdv%LSVVrzjIj{hvUaD@vD^s|55>QNqYMzIl)g|zpe1f z5o!xksOTgS4@Szl6I*8?U~I>W|LQxqA*NzYgvIxyc0^ey44WJbFapqB@s%q~Eg2b> z!kfdkAi}IdKSML?KcV*PXVXVhiWwQbu$uA#4tDLA+r1hjuk*`Tikw4ARE2%-aBLPU zWPE-#c}`>RE;f?k3#T!;mh14FpRI+d{jNAWsq;Oc02xhm3a>qNlQb>>e?1HfyWp^d z^=j9wlUc@9>lZ%@Ny8B~^r&auU#JIWEiTq!G=%;?6RqAw0aDlPv)|UC> z@a#lvFel>AYzaPq5PT?f87lLYQOsihCG(4c;#pWok*3r{i_o9B`ar>?Y2Eu)ow^6( z=EGu(9%r~@p7@O}HX+(CaLy8n4so(Z(%;n%lbb>iH`?1K{qmCKOp2F2{06z|ixu4; z=f=N%Bk|&K3`b9#p`%05aI{P0OFEm_=H&C-WC3zT%J~lOu6&7E^{9g}tdoG_Tr7}n zwOH?4jrp1*`$ACg`Hvq|A5j~m2X01DDf94yg1^nx%Sq{gEmEm-;&|-i(}DxDNpBPU zc#-6OJq2Bp6b;3*lK#uy~AmZ4gk>+5E!VOE6*sOEU3TF zre@vC-df^w2wAFpDkJj?Q0x7q>znKkgq^leYxIq4_f&Rn@Fa`~3#!Jn-1e_%*s7n9Zi=VbmCh>@_!DIB@b18EZAoB+~|o90^{!4)C1r zE)AS|LQlz9Rk@x|7HLVqZo8ZWAmq?aO|)|MYImej^ARd0E0KVJrnKYq5X60nEKE*ujSByc=SyNh$sXf;`s7!3FT zCq<@#vg#S|Gl}acaqD5+S_{9wv)fPwj)fSYj!onUl{R4yGN>L=1gbjj#rdUxt8Jyu zV(|hQcxF73ssFfOve}W=)U;IW< zAdmJSiyp9?BtwZ&FpBsG=g=Sla&`|8YK%-l=P?;^R_a26{`^I1+N6&sYyeY|Jr8^60pVnLp5jQm9+kgWlL2AxW? zW3fzNApek>uJrqW8W66d>KuGlN##@dVIUzkAjgdYG}!nfDY)6jd$De>FCTnij<3cd4SSu5`8$Q+h6c6$qQT7`vjzUde?eInL=6y+Z zwORH@UlSQPjr8!nG-|pW`*fVlz7z${LOUqXfJL)G=p69}Jm4!Q!SmVY*7JwakARQn zm%N7TJbQy0C%d3P*qq*PdJQC=dlR`m*^o*CO8!_5r@lG5T#NY$oT?0{W*V5;juuqJ z24vb^gTce|XS7Bv;8;g(*q;LuUfU2#B-2d8v<DGPIg*>Tr|Y{MAeMA*PsvxFUg9 z1-9s23yK|IZJ~Vb+`lY`JX4HzxRi@$ltF64Z&;3njV%ep_;Cpd=|r4VJ>Q6yYs@G9 z?AO76L9QXP^Gp6M+V831qcceZQ0{DM06Z07zH*?=(9AHIh7+-d|NgD~obPa%<5_gJ zSvuaVj(|-RK@#5>Z*c?=l`_)naD0c{gK$;RzB982u$cwK$U235<;M`S`8I{H(*tq? z>$M-v4rQ|hHj4upC1fdJWV(e}a~=&u&d=(%#!9DqoM?o0W$x$E+`Q56USg9 zYkNvT4mN0QSyK$k1VW@JkzgR!&lS)tcgTHA*+Kd(h`a3i1=b+?5jjoAX z*f45zKCM-DwK#5UyQ-9*IXxZo!TT-QM*sTtYgS=l zgK-@x-S21^7y&UcPiH>cTA6-GiB(02)d?Y;(dl!P8n|x|?k=}dj*gBhdhVZl7vdam z$#w#hjp9YhB8mrcf5ZK7Y@}jt(dr*Qgo;?Pe|}0H6h|Mu(=Vy?S`ybrYfq^wnXEus zTH2xCUODys{55oy0Z$cuKANTX=mhfRTl|Vlz6CQnU#j0#)<%X(oTJcw_P9?VFjDPW zYW8&8=qChytX{^}Pe{^ogD-@q!b3y9=vAi@=H*~{rcLFJlB^HuT_|PLvluC<|$Zn<}*4+Dd zMe&9_mEZd@F}t4lQ6C!caau);G{&}VJr@VyPO@!+=U2|t^mQIPb$01==YXAjUMXHT zhQEfVh4oHYPESJDcaI@}bq(*V#j*P&-1ax+U-W!-#$F9z6FClp!M>!X7T+mi(RIH& zX=!OOBCGikn_w#`i$FP_p-dz>b=Tnq>;XiVBdApJgj^9Suy5pm7I(c7898RX5iD{> z3aw^jlG6Y1hOpkkGIg~(eeQ)(i^bLS9b+A?Z@*#z0sFg~QDd=YA=Czijkgd=eFn>Z~Sh^A*z0M~rD%QR|ABTMsmCJ|b zIQ1KyB@bE-RzRwHx+jDK1d^(z6PiW>(Z2NxTe~WCRnOBqov?uBj5A^lk{rX%-VK|F zp$a{CZo{;OxA#{6sL7b@F93MYX%>b!|R^1tk@$9RB^ z>DeS=n%!)-?oAII`Y$ZG6KCaF&1Xk$fkIAX!A_vR_v6iH>NZZBJ-M*m@OK@R zFuixlwr-?I>4bShCW4(j)&_x(FQkA}C)D0BUf$blOL0o-gP?96&*SFlr-aNxL4JM@ z7FvBNL!OeicPYIzf!B~%KpW2fu8fcL(69+poNRexK~LB!#2u3t_W?xU5*G1ByTT&* z*Q=aijHd}wAl=@OLfgt3S?hfI(r8g+=fj%~n?Zz`3Kxqyh94kn@_o8y*&Iv{nJn^o zJ(-s+V|Y5GI#H;PpTHy(1dvVdSNwj=Tp#e*KJ1f|J9z?uKOd;;;^!5X+a*(5av)yA zvp=MUzeWCwehDy#Pb26MihnN}L0B?NdT~IH1V`|fW5^Duk)%Kz2I};vhN2uf-5D4(KqOk+a%ooum=GU=WQ%8A%yfUak!23{SzED{5+r z0_ImtoKmL;aEkN&S%4k7y}8Yi_S`&uCN7mB6^7TXQauN3`Z$Ti9%FTaLA1(ktkpNJ z4SWJ7bsT}3gAQOxpptFDhX8V;uhGjwg0uy0BMS0CWngS#|GxJ;O>WU`L`T{I6y;y+<=DV-$BpGjFYz1@!kOTPdHqEj9lb8}0q8>e1DS`E zBpij17!vAkbw{tBQJUUzqr2(kp!wj4mUscp*3=6^;S|1Z^&|5*`poXi5u@3$4HC}3 zVsS>0Oe3UXomU?h+bFsm-y&x`+Gp%yo*ND<-e+(B`%7`}B*!Pil$XZQ_p*~Hy8{&Cnk^ru{j8?`O zv!SRFJa|t+-g0+c*SL^0T;?qqcn)y?b0IE0Q}B56Hmhqxv_=RqM3-B(+CbG z5fxYl2pjKedvyeS7CfqRYEupYIN?XM@OQu@1o3HD&c7}m6(UnYp<$*%8UjCAN%oLQ zx4j2Hsg^s>7#T~@t{@|WIurXb zsknNlD=f|}S7*n`d?x&!r!{`D0+7AG!b1m43x@UrN3Db~?K?heWc14N|5zh;L!% zm1wcHQIPX2$*pk9f){-TA(-gB;6{wtxEX}-hW?BjKDsGLw&rbUOdtJc3&D7nLa-?o zW#O$K=FhoIweraxIY!puBEk;yx1|pvNq8P3A-%~l@;vL;*j*(1038D*buv@ET{HjX zY2{I9L`)KL=~aSCxyIep?l%1>pzDH-zy(#=SIcDh*)tR>`*9o>F3I+6Rv4jzW$w4`GofaI>hU@whYvOqCL*3)ehXLia{~#Nd3Vq}W zxKG%Qk2il`p#J(~*J^n5@G~|A5;tQkpk^`zZy@?kRh@tb?F^{4)d#Nc+NXrUO3w5S zsewxY#+aU!2AsXY2`BH2tp*GE#g7U6N8`OQ6`lhhcm=Sf`Y~kQa{qhRHJ%a?(IS!K ztaRk_(1UyU`*b<37!E=F(>M|Ma}JIqh2R8z#}*$SlGhd_F8d3?bOS_LdRG;fAD6T~ z(w9`rMHrDi)6vt!C-)v!*S|+0Pf&*jRnypY(V0`3^co5#)rd75cx}_C~bAOZxAShIn zPAG@aWPMu$-h?3@QB43(M5MdKJWJxp*g!J_EQZ))JaF)daS>1Q8xZ<7>AHrJ4Bcfg z(zZs@lFa*vSTzYg^v6q<>LCG=kogl*K6TCGxt%iO-kCYwAai zy}a{sv0SvYA|T)S^6gtFAOsnA*D`aMpC@fI0lS%$H2zE=v~qZHfiR;1x#8hKqAdcV zP!HD_z@FbSvmy({Q|Z7#y#0zsC#b{p_;TXp27VG^2ILHGL zA@lC9V8;HRC|nu!h471?KKOVpIEpvcPYeV!;3DTSozniW-I6b(kB3*0-3^U=Ah{l!L_7caoVX*#edA=|xZtLwu0 zJxhyTm;AtWrePMzCLI*%+9-NdGcF!1BK^euVSyYMhl}SsJ;;MgU;Q2-Uwwj`tef~~lqej__IhGzR!5gclHFKWwM$%XDl`1fUM0`F5)dzJ7r}MQO@Q{o#nXTX%p);a@-!z@!>oxccT0&zqWq}{cvm}eNmjj*x zV7#@o|NcA%Us#qKC=5#%?q{s!`{>RWUwi(oMU9j#3!!fw4hN(b?SP zX2W0pfOl;~z;+a99o68fG>WG*Y5MABGa6lcc>ZpsrRa>)$~;90=YnGT`RN z*0?2xD%~>esnlre_Xrn;LcidmF+fKa;f|N)BhME?1@cntc67===w+q67Zr071v{qr z{2eD^n9nfNfWwpWPb^Lgt%gqYcC=9jiBVDEp80WJ=@Pvg-YYJDwisg3ySKi2^=U!% zWcK_D40vCCQ1d<;qEUIfSZ!dq3$+0qObQS6Gs&~zjM=euRpOm z_{A+<=R0l*{CBLxAbi=+4J=+^y!o`=GXkN1vDxEjOIQx}>Y2Y;wFi~`K8{|iHpk9@5w?$ETik={++mAfI$2n!7G$1olw=AvDON zEe1&0xeqXF^rR+&;fnfRgsrW9&)t95c|0Y+DhjGhy6F2vwT4%^jrpVmaVg|0H&GQP z*dqDf>uJ}zzGTxA@SEV;%Aw0MDjI^qk|%RV`K}fkGMrGYYn7%nk>uk1h;bQI>i9`T zj(Jqazd~K+)l(a)77I86iGRe6d@-x`93a>MkN2x`H$n*Ucp@%d(SHWusibg=YLyX0 zNnWyK>TdrMJY7ojKnp_iJ^CNF;P)dWE%cg%h{u^)kF-hO zArqky{K~)=A|(zed+Km3i`SyJLZFw4&tS?iPF3yD)tH>W#DVR9@Tj zk=B};Ud3hMZbgYfE@8hU*O#ol`T-Ty@`h)w{@bxpg0HZ~Tw^hmS-?`}$9!p$aAe(Q zae014q-CGxbd8M<@_*E1H!~s493iU&`{1s1I3Io`**rG8nCi!@^L{r}bhj5s(7>Gb zPWu;h+~{{cNZRKYMqNFIA7utt{OgLpv$)JovD^zX#aqxyKzf9i*7eW3iTop>BMFc^ z=-G-Y2;rNjGrftn&+bcsNGgb_F%?abM^(J~cMLV%;iz#tJOmOm1eTiwKXzBWvTmYyDF0AqC*UZ0#%3ze&jUZ0>nat|J`F&3j; zkw+Fj4Aw4w@=J@L8$(@msSOzogC+7?iWC%n`Sc!APGGWB5BhrW%W!kepH}uiG_STC zw(b;w|2NFx)FZXA;wkiqm~m+?B*Aq%-tVaw&NpTejNo{QdSho?l|Szv2usU11ad=! zdxEV)7^dd71#sc&?DNPPvLaFO@w7d{E+5xz)8Dn}?tVJDexFzsKHBlmGLBHN0L2Q&!p)RuJJlBIswIf{Z%m#fnwC=3C2SWrHSFW)awa9yJ{| z)}xb+Ozj=qpTUw=bT7o`gR;38$3CNOw3Sw(YeSidv|wNLzhb=k*&J>GX|N!VXPWknGv>xQ8OZ-tF zI7CzjV1b2^40SUIE7DCSvQTf15FFv*rbB<{jv;4wOpRnuv$D1p0srOdAi_aGipMB^`%k>a-uP1Y!2*qa;xLjri^}g zHF9nqT1}*!lfbFvH+;k!gsiS9gG?a{iir^ZXfq%k@AeW&3k=KJ#dZ9!hWA1~Zyc}0 z!s>BxzvKV1w5;^?%FeOL@i7(VUIS*jAe++tzY&VJf4Q3b7tyl=WB_ ztnX0fD#i;BN|e%8Mn~Di@GpyLm4DV3fzssvmUJw;&lRrtq;yF*@I>pU1I@nR{!)yy zCDU7wCB?j?GwX{JAkdH%4*rOHru?D~Wo%3p$CJM2F5I0S_;tL+Zhf$hPf0_&*jXSa z@M1Vw(Alz)(d>6}J%weobWAF*E0Q=tae(n73Q_-+udmOKPKMfNfNZ_&PgY!I;|$1A zlEa&Gf-Lrf?rO-Wbe-#X4!F_}+yac4ue<8Ri_CSF)BsHLNPT3~4$lD_DWk8iuL@z7 zlby|%6P%g(qF%Y5$7YR=c|I~8;S-H$f^LU9p7k@A8QtIA0%wKN-LAreNZe)aQJ`lWr`WkatM!q`-A_MEw9?vQw z$=lTGSq|~&|0}0!C5CJF@Z-AJ@bh{~7VYbqjI3l~t%Ii(9|?=NvU6Y3FkZDRC^)kp z)d-f&PX6nVE;bT_Ry#*C>Lk9hq3Zv3lM|HE_%)nqbmx@yEk6f5n^z{1N-%c+7%V;7 zz04lctnlL1E9K}wFfQe1H8UdnyC|kfZ7LlnVBIZ6w`n50cG6GY`tB@U-Eb`J7N^6u zH1!>Jm^YuxBs{fPuUppZMOr{tw&&|}nL6_;8gAFS$E>lSG3zWPLXxCSIdGHK_}8_x zG;Q}X&@qg^M_0Cf%{`}ExcbBF)9UO8WyTs6roXCyj}C|~Mf90JOdTA`1v#T_XFf}6 z);wcGh}lnoXBi`017h~5Pbs=)E6vl+7YNxIj}{0i`x!=DPQny>WMVu-?-K|D;w{8N zJBB@c%dyVVseqSGGJB1go*Q8f%dPN4oTk?6BA(|*@NqGbiP&=e{>8g;+aC>hyHXyC zi9VjP=;oCm`2&`v04YD|bnwm@Jg}_Xpi!AoQ4ZEwVjjC?36_*lQT!I6$cn}mRhh2E zVP;HCiBRRj6`4A(@kGLyoJa*+Z&XfXLZ#Lq{8m}%H$E`)Ir-y!+i%c5m3G&+f70nS zaim{#$1AP5|NpS})=^b`TfivbK|mx0L_!)7qyz~`r9mW=ZUvDJm5zg=bV^H?pn!Cj z(x74>B_-WRm*ATl^mp(5;*IzH^Tr$F-7y%lkDR^MTyxDed(COmQYkIwY{fFXTiaQ` z`TJX=SI)~hXi>zUi4uWDW|94@z^hNAVE zFLwRv9&>sYe4I%q(}{?7!x;)|MpJ7K#1Tx$-TY_8LUVLXtxt;Qc(U*S$&0`L8Au;+XCb*wSmI z`12h!$^$GZ;v@5F0gS0fv{vQN`w`4HV^L7pLS`Op#T^X>bw@1E^F)TN6{Ds;?c$eFmrv{pfK)XU{dox9( zd)#_t46zp7VkHKs5x2|HPa6c*7POP|LjHh4gH*d>f|kF?p9|p%Jg48^zBoci)rFZN zvk%A`j((D%fk*z#ez@52Xg>{Mwz|HG#dF{}`O`z^KD3NP94UQB*zQV!soX!&|!@qSjATOZw%CnRKrQ_GTkw!6m2eL?O zR?#Q`l;{!72iBuS{=@~a#NH|M|Lu4p->8h319+lG1zeHu95;e#W<-`XhO}#;m5JO$ zra@dM_u#WI`#*5YH(mwUX#U5}Lb|f>Dq?21rQI4}IR(f!c?js!0B5_Qq zm!JOWEJTNlb<|mC3~B6VfcrxExRVVfG&s_0s!F6iUIe`T2|?IN?Mr{V?r2VE)uJ@BVz%nY)t`t^DL>MT?OU)Z$%{rL~stRU~!9CVGqWV68#4ulNd0JxB` z@cwebF|9~qC99-Di{buaGkh-n%G4Jh{hhs~rF~1y=X-Lii-Mm0K@W6fJ+8))DE0^4 zGzhxev`V1^QX@WY>HW`GFK;Hji{~@1O%+@`O3r{+XM-eP2-y5wc+)Vxx4BTw3m4gK z^{+|&!E)nIKqQqHF7fdephE%rZ$%I8Q^8WVNnAEQ%SG^+->mA2Ir4WRkf0}UC)*=V z*wyc{W-Gs#u2iH|Jp=V4Bu$Z8n#VtgyQ`OhQU~v7TcO1da(VZqu~`=KXXAKD7Z;&q zk2Qrn?V`v2|Liu6d@9r)s(xe@|8{(`<2lgWlc*!71G#UqI~Vi8%ita`?TEbJlS6`}U1nx7tMJ4N{O!C{fCmL4u%TS) z&JRDjhb+CP?hl!~UPzOg_zN476+qQFym;yOVETbOaKVHyqY4>VMRKv&roWH@c=pfl zb`7pxe*Gu@9#1CBh?6?CTCvOBT_&)9NsQ*rnf+WQ0Hea)q zNvNm-A@6=1ZdutD`+oQf@C+%jh?P}uUO#ky{Z@w~M%W*zwGwerOd_Q&U|J4^ee>^~5`mR8_>3M=~)ytslh&!(g*UXffi+opIIsZS1w4VJ+^${CJ z>ZiN=d>Pscq1&#SQA_03o4rJvOcy;Bw*FT_a7|wm#NVOhm7exyRzJF@(6ky6i{Sm#@5A>l??Ki!oDrO_!`MC&ko!ldl z{r9)VJi6JR zT7B;Z%N)_>|pe-)}J+^TV+UnReKU{i6*0`-R6N_5t}Ye;4x4ivBy@f02p)kGrw|C6)iLpF8f_ zpID5HjHVSYm0#Q|T`p<(hgDo<{FJXJh(e)wxIRay+&}e)xv-%;pg+^s@reoOAuvwH ze(l<|pR22w-wQ)x^Q`&Q6~i^Qbg*~!$0FJ#qqw5*vDc>14R7|Y^2KayZ^t&QLoz?; zKm$f<6wbv2o7x?nGI?LnJNp+aiC_3ioh7y3(@k%Awp*(XzJOyhtW=<2=luKk;VVR& z6N>n+MP1jBG+Rxt{VkhsA@?n$9%Y?71tU#9><)AYa5H~(siRVwg$=_r+EX)Fi83~a zPG;aPITe*@93wWC)1gG{x|O{ z^V4`Rhma8Eanje^AK_b^5>0$hPlEI@g@#o4GyWkJEYe%*5m8Zr{B)a}#mo?@K<~6N zylmjca@=8bCN!d{jzb%5x83=@TQm3Rr)!p1X85ttGi`Nf*-mwHLYje%3B#pBp%JZM zr5-*Oj(r_~syh_Pw-NP2oO=6#E4rIEI{pYCjfu_+mo8mWUMzUjTOhQ0rK;bxO~6_t za*}qj^%c~Ws8x(*mc|;e2DameyhkUN1jtd@re6ZXTU80-JGw~Wd>~&$h!UP4{pp1z{L6!<_z`Mt zdJ78WP}L85V1Mr8OsSYV;P00rwLk9@^X>Xi?W$Vb&Z)3Bf(CC>{CZL}W<_6X^8u~H zbSGdiS!7}UhUO_^KFD-GNo@cP_WTeZ3uW!x1JG)bxP;vX`@S^RIow)pJ{0F`KP(H2 zxL<87fn_ud%wy76+!9pJ6lEM0K07rQmsCCyYzfFOvIL}ELG7HsEfrvPJPM?vz$lY* zKnpI_I2ID1(AL3ozf$Nnm}ZoSiIU-xaKL}bM_<^3x6A;KnK`SItlgWo+Dw~bQ3$W{ zvE)r}qtkX8x06Q?``+ql*UdDnTN`{9N4l-btDsk|h2p}bOc18MW4cnZ;sz^|4l_(s zhE*0Y!YVZ~2MA%(mx#rfo18JsoEj-P{KfUBWfE5VnK3^Tj_%d>y3s@0!Kh-X)ZM0C zwGvZ9*Lxd3S2D6(x`M#O6NB|UByuhXvow_s2xVgeU-vrv7D6t_1>b}%`YeaB4{cP# z$q`$Zj(KbfHTaD{>O(d`q@-7`ko9XU269@-;JO=qKZ$a zo{)~Ye@YECuYi+r12ALH6OQ%*Z|~?OQ+m zaX$oje#YCepu1HvNDwI)i9U(N_@TSaCXh*(JnrW@c4D=gQPVJDQIE-Ec@SNVWL3|;MJk{(jHUex}!n2wZlxK%kL9jcYr0%0Qb)e+$mrZJHY&cue7mSw< zwWT(bl2|aEN#lCTQ3cH`CWp^BguEbBF5>yNJVY6GO{A6m;RfAG8e;yT3uwcnDs7T!gp?DGKzhD@ z;s!F?+a%y*!t^5^^Zj&W@!w}{#Ph#rTI+*KybinY$Lc>X3)JZ+96asD38*n#&~<|L z(2^(Mnaa3`4TviZaWX~K4CpYC!bk{1*px({Ar^D-5eUa<+@_a1x-V$&hp5G~PXX0+ zE{~m%?R$>Vr!=IHVgumL#={vFbN4HcK%c<1zdnoMp9jr!=m8$uPcHa)LO#HBZlXKc z5zZe9LxepzN3f+1Ypm@lTBHCVSmBxf#~l;c*AqzY4!wEF>sIDQyfof}kA^iV7#HY| z1BTa-!+vD0j}am<(@*%Y5Vuv-5^w_h3z!8^&qN&RnUH?s0|dEk5!x_e;vfjZB-X*k z>%Ru;5=mX9AhpMW?N7pp)&K+Dg$9N=KXaLCF$>we+`9vu0EIF<-$&a10UaTk|B@de z5UGIB(Oy!WlLSIXD<^a%u^uDr6bHV=3_(rctHAGpJ&fZGB0VZ@V(D``T<|Pc2DV`i zcE{!-?Vv0cA>bwL1by)-(!wXOFek|g2yLN|qlwA>8WBZ8FoftwGyZ-h`0INA_d2@pIqSVoKB+1E8EZ43y&b28qJw5)7)3$!d|VQIPObP^l; zZCe|Tb(4T$aq$QFi`O*gb?UaQQP)p+7GAiDX|>(VwfdB;nDZXT=tJ* zz(uXaq7-u@C@4tE(XrTVfj{arA>lLV*$Y<@?*F-p&{IM+R4jDe@d>orGzC3?kRkPk zq~@YR!b1L{8UapD<+?{yihH}e9kk_u5dMDB=4k1991Yc}5(Dha-{cG&n|UCSy8{t))gpX%seTGH8a@a$Aj+lY zk+Oy`nETtDqh<5)e;gT^U9B1r+j$VByXk3$XhRoB$Ic1g^zC}3K#z|l`uu6r6VwKB zCjTdvo(dI(-W460-7s4y7Q7413mW~v*M1VuMG(lO?t8;xk{4b-A12A%6}T|^7%o)Y zg{ujBOEkdNh!}y>;|K?3!wD4%L5n#Ad<`~%^crjw==6w35h^g?si~>Ga)%h;6?RBd zB>i~@Hn_IGY7soBlI6hFK2V5{+Yqhs*=g|4RF`;d^M^(I+#Ta1AL z6K-^G-sD*%$E%Ekqs(>kBhp*`p@O86etH+-CpKtw?gN+P)8PWwmsgM~`fIg~4jRZj zQ|34q+b`XWXk{l6y$z8wfZIicS8!R^1|S;l1>fWe4wdp!rM~mCtG0B~DPkd*o+EFe zc!_A02w{=I5-QX9?PH|OFEJ_U9m{QKh!H1fmn^kt%))H^5RMI%C(1?k_d<{RX}G@{ zxKk-qYCY1tBwOKiC=*PzPLiI!m43^w+_u8+q-hFzu#$P7v*;u#&q+*3k9jY2cnF1; zl%MWkJlNk_>My#B15UTR>!2b9ucoyb-h3fU6q0;Dm`*Fd`Dfabjr-|M*1Ayp=ytv? zEm9F?ze~v*VI18TO8tRZ&>_s?NDd{+HV&M5_wy&?tcWoW6~DFbF9rr;9Qz=p8|ty# z2EGm%ej@pHAM+}mM}1rtmd-lg*!HK~8V3%5acjpB2P}RhZGy1yQDptQ` zBN%0tl0R)MemiUTXd!^_rHXptLCTD^vSjo4&4ay7wS3(xu728+YFx{OkLG@w-!;71 zIIwb!yKQD`Ir^d=;c#_B&>q40ZZdPorf+HA9&P$a`+dmP+=<{5W4{-V7bA4b;jI5{ z8~+Vkt4LL+MAPQ|3$ZgPD!aE!T*<7jFnv8BC?6*sc1E9!M1RDM!!HlCxKmFF)psH7 zetf(oh=TK;emW6cMp}6>eaCsZUyQp~Zsn35uQ^n<(p%xJI90A#%XEoGw2-L$poZmn zk>Y8`xi2y`5_h0N%S^;hqd+Um-Zlv*qFWPzOj`c&QB$GO43#L%Ko*pfqMYQjHbr;c zdQmy?swP>@>v->vOg=HHbx1D&m`@mn^o#KZ~AS0WQwzz~G z0iCr&QFla)n0^`6v(wa16NOLwT*L3aT5NgC0B-v|j*d=%v|2X56L>-~5M+UfhvlBJ z@ZBXO?)!{@8q!VM!GM~jRo83Xt#{3W+rurLD-A96Vl}j1C^&YJz)I*zM6U=%+71Gf zKpcL+BZM){xo(G1ZekkR^qv1+aj>8G4?Xmlq$70;& zlFmk%RxrH^v9*{@MOYS|JlqY3%51)CQ(fl5wxBY%K;eQAfYE z;NkNQ;_)BFEu+Rml-)OW6C=d1_1eN(gU^I_Msp|?X)fa4Quoudihi6waqyNZM5!@; z<=TY$BinAJX!ekcU(GY5JJfe95A|>CT0ee3U8+_?!TZfns;m?;y$w5C>%;IfTDK(J zS6r~lQF`kX85tSCvb@_LcKiW3)7XlrY;jcTt-${2x~!9s4mqx{g(wIA3g{$}*iZY~ zk55|MU$wUSwYAVaJNokFhvdG3TW3$4By5q2W`|5sjO~@twg@Slse*Xg@8zBQ(FReB z1gqa($9~?(orX-}CaCCOrZ{fobx87LZ&R^Pvu2C-v-c-egbi-JDT@%Xeyr?`qCB0yGeY%~$Plex$ z6l&c>czv%nJ0lxL83<)8=6+F-mkADsnqCptx_as3g!{w?E;gN4Q8z>`e!M2`%tb}# zEp+n9NuuY6f(?<8q+gRhyllnM3E_3`-YpUM8I9K-D2B(Tmx1@LsfjaNqWqz^x;m-T z%E!dVN{K;cUcLFdb>nv9#T(mshpfv*+lG4EW~D8fu2~Yj%Ox+pE%%bizvj6NddwD~ zzvJQlme83z_1H1nSmhyB?{e6q8fE@Q0Uz7p(QDm?2lhWD$*P@}Q{Bw-2b~+LgxE(u zBNcT_P4RYv>m8>q-}B}rP&&&U^(-*#>wNF)l#csTzqF@<`57)%+~1^8jAFYO=6`>n zHlX(9wIN_b`@o0duw ztTZGV+JjrJC|l&|?))-HuG#${zrr1|^fPAr56MM$d%jX$nP&2@Dok+B)=ruIW{#0; zvrBWm>D^>o?H$A4-9`;iCL}Gpzwwtrt?R_ehb|?2rzkF=irhu^7SDNXb;#{3bdM@C zi#(b;StO92r{M3pAG)OXx$Ks^j%@s>dE)lqnb-Y+DS1_WhHnL4TkFN_Wi^Z5S(*uG zRaRU0T%BDO9Bid(dp_`)4P0O_G3X8jMY$hL(ikaURBa-f4_l8#44Q8I@E@$ffqOo_ z%G7;&%&(#d@bQ~Q#A+Po#%0LDf}5K(UMrbAfT}8M!IUh-XGKo8R8^i4r{Y-fDF3!j zDLj2*2#URmjm-OheW?;ZNHQ}kV6}C+UYF-=is$9?>G_}UN?eafZ?WI&QJ{f)%Hs9) zE}62NzJ6!lLV4s&jD+a>RyJ4{Sha#;3M6yCnDKhfGkXX-vo?o9@xc_i@q_*TvIjM# zyvG$Xqy}>q3Dx)Pr`F7B2eZp87zOTbdGK58k=g1ug#M7ifvZBl!?y#x&jvL!Zmx~n z)jy6r|E0T|4k}zcUlP4tMA{ks2K@wQtE(fOI4hs`y=9I$OMk0=HMC|C?Ju_p%1a-) zOAs#Mjq7!2QKleT!SAEK@IcLc6!XdIy_teyFJ1<(Pxt6MW8TmU$G-U)PL@k8eu&~S z6yokCzj;%kb=3P8>xEoPPx|=^zc6S%V20)RTGDf975_Pw2sen9K2liyvN4Uagc6 zDEN(IP`w2`0f{oan%W$oJ^|Di(HSh+997==vA>d;$}x^lQi9aU+}U^@c4NhPb!1s& zObmjfXWK&0zlHKTlQsGGmgJ_~A1*Y!P?l4i)hHBm7T4t>4B9R(lwf8?U9swm2{Xjz$fhGSi+Y~{vhr&!xzr0~V!K;2jVHo{YV*f%&(g0Q46beEfdg^&B_G-1#Lk%lgT}$@! zue5bO#;16f$LDoN7Fwv}rL%e!Pm@6wB4hTM;O4>i%Sj^kzYoRW-jv2Yd$kf))4s-W z7h32yCEIE%Xk%vdz08k zA6q6>Bm{)-jAwR#u9e~NsCig)gFEkrVsrDIyf}<}9W(a*gL$K@`!8{`#)*iu@}G62 zbo+XT(oi02WHMaIy+K#%Y9}<}y)A2^ zPEsw~V`BBW?LjVbzny1SX0hGm$<%m(<3%j1p{4J$quaE**vo6=66wZi*Bzbb2aUWg z4{$q0P2-<>_t>>$bvH_dfz^)>F1LD1NNg+&pICKpxGZM+IlYBv?rWH`h_`eK)ZZ~$ zX49-RZTY0@mk&jx`d;_TSdCN=(uyegY)*$Pd=X$shJJzzTNfyvK*ssmy#SM|GEs=c1 zQL=o0OxO5iY;jzg#49~j>yQ;FXPGUsMbE*jG2l~kn9}g6Zs7&%trEqBOB6a!*$mXV zFjQI-b@+_KjIDx{T5phTEf#)=;KRAxYO6?Nzcf#NdU3lT_=L+`3aD-e`~DPef|x~J znu{)%9&V~kc11wD?hnhF)BBK(@ZL0FC-oKBC~Kq9!gV`iwJSAtaK+mYx~B?z)K~}1 zxiFh0Cwvq6>aqOGDa?5aXKXrN;Hr}wK4VkNPF&pw{O;_1;_uy~62o%pf%h+o%WCyv zOna75LJ^}N?wOCRJqjstd(6E`QQHq?-}a7Z%h>!f?PvjoTzs$MQ2^0mbTA75Pfphm z6!u|nYuJ0*k+CrneZHFc=?p`t1_t4KCE@CYExzE&U{QI~19J|lXR2Oe{ zK;V~F^!Bsy4>t{ppv1}7^qfcmwai&^{47O1P=2EsbBSl)zd38@b`DB+wmik3Ssf}- z(RpePeE3Ub0JmP7w~%fxCx!kCiLa!iTzb}O7!=T6+_LxGV*J-Btt!TlhwIbbcc3JS zV_&#DZ-2#ackPO0ZhqTe%;h%wXIE;6&jltiJ}sGzWxMc2oKDOUcgfI|A!%4~eiCfG zD3OOHckbsmK@F_engxxYw)e7LY~V%c`@g?VJX-8}m-Ve?P`AXdom-;Y*QsAHR+lLx zXwvmJwI$C4@1mGT1j&#>lXE;aP-t>+9MT1eXT%__2>p8G$>fReCzh3iZJ?0f?abeL^`>go1|^+3#W7biJ;ZWvC=xD)b&`p4y!BLcELI36 z4+>-a79vl5>0^+_vV_})J*&yB($_r)Il=;(rJ85(lPW94^;4nsb=tWIeui`bUzVQKTq?ve^|JnKDq zOY>p`XVOwak%ug=#;)BJ@roAJqJacstA)d0@j?)#67Pb~5Hs}j=H9|7v-}omP8mqs z(hCJV{_Z}<=#vefySUolS?=UJ<*#^2cuU;adHCwRVcO!5>U?>WNmGn5$9Q<~yDasv zUEz)CEe?Sc3GbU;lJ}r&;1rF4l77^svjgPToGo|L#gsNhTKDr>bdU|cRGinBgF+a3VU~Qi!(G5o$1axe~&sPJRz#lC34F&z-=$yT&+|a zb&7(`KM_-S3g`29(<7D#arp*WjMOot`2HCTBXr`rUN=}m?V)a3tUevDQB6B!vt8Cy z>-zc)u;HnlZD03r?oPIlDqY4`N=+zn`6mr?2^=Ao=B*;~jTyL=cdzdZF4(31Ze*x@ z#G#q}o>Qaxv~0*Ou2z9zgb}Z9b@SO&Mh!>J=cEp!NVU7=y9B1E-ZuFWnf&rqsB~m$ zEp?Y!NYCed>jWlk_Cxtz3h5HX?{R9EZmSCgRiE5&KTGGqPXhH0T;{6GC*#W=&G$6< zO~{V#o;8#maGX*$A7nq1%H&7X^}vzyRSHLXO}@d^Pzvje!;076 zbtLXvoe75;H~e-ZG}x!e&|zU=Ez@vSw2LFJ&mT3kdY+%rTy9HeV2VBT9FGd0bv^;? zq8xrXq(-*IsjWyYc4~0RaXr4bSmDq4{;WlQ%Y{2Lc23xORx66D%M`g8AHs6&Cn=2$ zLN7EvRcqrj3u$EyheDmcx(+tO)zAohIf~AT9qKN422+<|WfW=(ca^`BingEXG!vE+ zlsMJV`|JC!q^gG<*FD7V5}t=5|MxUVFNSwRmA_v}EiRe+Sc<^ zyz#EpfrWbkJuN>p0AEPJwL$S$HvPJR4#bF3$G;zMQX zMPD6<0X(+Uw#($wK9v7&>M_9?7BVF z^IpG8MdsDXdwP7LD%iZmpwnL1~k357x*5i zbQ;H(met3av|X_fXr9z-e@Sqt`Vq%1j^(%%2*Vh<)(q~}&;DvV^DbvL|md zN0chpeEVazbH?R{+v^|6a?vd$%6FV!?hd@V-blWbnVmJr*`FYy=+XbpuF-h1Gg`@u z_^@evwBzn8-~7%t{m@{Ip0)SOgnBG|0j@^SimhYkM}lMbSQ^u(`n%@V+P}ks-?~&G zNdnvU=C8rY`mg%i;hb0>6Nyh1t%0X1ZnLHIA--!T;ddx+m2O^fv(jVgG6kmrgL5#r z1PX=}td@#dvIAt^aZg_gzf&l07AI&V{?%7Dcl}R=>@_QO2d^N<0PdSFp@sQiSZ_;( z(pja5p1~}qcb^M9*#PF5}do}u&zqN85Ri|4pVtYuz634Ipq-a}8fgvEINO?-c%{F_Ol5ekJ*!-(!dJ^$SY=JA~k zf)7zwYd_=3h0@$~ewOkw^h!p5J}VdRDg3SHD4J{Z8BmP(8|#G&cOlbM$YZDQ8*8Gl zgtK%*u(}_R%;lF2E?h5bjwY-8v{I-A?X;Ql~S!j4e^g>CLZ+oGi2ZHRuQlY z<(&|htxxrcFAnq%o0PGf^{R7=`?#U;MK5TRg5@M%XI!72#JSkn4@{+yUp)4^zlMm1 zBe3-I#7aEwiT4;%giZb^rogz~oqSA#i39_tQzsj7*=3tANy4aUFMx5&jMdz<0} zF5BZsl8*RzOje$4&AZ(nY3@z;;0+rLA4qhsi#fk}=&W%tl5p$WX7ap%4B9vUVnphB zTp{MMNrE)pOwqB%CwZn*=}+-xhMUQpmM=Yhnv~yr+bFfv?je=Hdy>uBk*Wt?WubH0 zs`NI4E~zLw`NmTilx z>sCMV8@{%s9QZ28F{l2))KuSS`AA2N>w|zH=WU*a*upJ2mMh-~lJ{<;2x!D`>#@$w zS*TZj{n$GZwoK{v++%%ILHF6`CFMu&G!2Xdryrf0o}N~mNvdgQ$~gZj;*;%QY5a}k zjp#DINApoDlergU+sIEOiN^#=wAp`@-~A^Sz*Z89iCePRmXws_J4F;K!$tm+Sl_V| zX>fR*Zc2t&Z4Ygy<~$YJB(&e`!HZVauen$DaJFBeXJYExOu3$IVQalh>!Hh;@>g7M z>UNVi1O0MGy)Qt>u=m%U9ZzQ+6|&rg2=}s(C&I$QU#uDq^688!f^cL7oi_lNFQJw8@4xY{KcN$xqSBqRY*EMbVXZ8+=zy% zth#q!D>7%xe95fL6iV}5dhpvt=JprOkiL1t%MCL41I`U6@{($`^hdO&KO~hj5q_^; z9yk;KdbS{iIiXPFk>~W&*gQFfH+nUitSX1P#g|J=M-PY!z1l~sm0!@3mRtJeyQQq` zJz6kr-Jr|6l6HbfR6F6|w-%Z5;YuHGpYQwG+_(AI>ycxvF)<8iNk=SZ>*wne)~MjK z_G{06hD#B}ihFWLi)}5MaEiW?eqMdepwc+GmVZlTcZT{+?@zU`DYcc`Y6_LX!KZU` zatb5so?q~^SxQzDB)QsAI-&CG_363^TLqQw@Cc%z3*2Gu4t_$5&W%2fQyNdq!p^$~ zxGjbcl4np*N$l=0opbm-yvb_yt>vMe(Bfn0W925i8C=3F(eSjauog=HbMPJv@u~Fg z!s#m#dr-^w)U z)DM)Gq%~{2lD)Sq7DgZ54fj`J^qyTEL7SSHb(r|kvevBBi{O2iZWPAxxrzchzUFKw z8NxJ^?47nb!F(n8br{vxZ&-;`<||d}<*%M<4i`y`_~x_UVi9?B{$X9I^?+h$SC{FK zgkd-dFKPL_XxW3!FI_mg_(eK81HD6Xb#ImroJV8)ejiGbr&8nTY4po@a+gipzM`Ga zFeF(W?7Ex(JDWl@gDxPCqUbEAE`1xVcjV^nGgnqrA4HiadtD##-u7Nud{loy^?EVZ z>PMwW&aib7+-jiWt>t08z@Q+rcfNSV_dhe{v+{9&zT^0de&0)ikMDJFagXk^J)f_< z-ol3Bd)t0jl5dzuU{CJbH58o>@#y*7*1qICWc5MrVe9+ZB5kp<#SeW(5e-SsX&SN8 zBPQ-$pG2mbpR42+ajkz1o?Dw`BI%uo6_)3X;kmEWS+f z`oiw_gjh1w3$yi_8!i?uJ$>YCElLDMoMS-G&8>3PdHE9Gz4wJ)!5RA|hUpwrDHD}v zw^Z_Sa)q(pE4>fEzH$u%vjipIpFmDz`9!i4yOQCC@Wr!vGL45aOR;Af!hK>5f+Grf z6fa0NlED#aAE0CkmH`TLCXa?JR?d)or1iU=>tc><+W)?K7At{j>BY3s;4)8OI7R1bvs? z{Blc+-qc>C7O*ZnKU!lRR%bRcWHdF%vETI=d%dYy)m*O%GmVJ)oWVBomhjI5~ghYug3 z<(V0yNc0F^_sedPXwT^l+k4 z)_mZMP)X|&5$68M$&lQZ%ifQw$j+YS>usH-^{80*y=$Ch*CLc-*AjtCPppp#Jh?5V zNOSZwhbPB0%buo}aHMa(5u=QlGO4j4sW(5R)#iu7cZx=mzvcV(G)zoPrr_>WW^FCR zqaA4CV`DE^SXf*?SM<3s(8iR`C%XPy_?fGUCC{$E(@Y6wB9RY3d!AUECSoZzR(`tK z#L_yrXR&MBx8erN;U%2cb7028MQH&_eifPJeG_a_91V00s3(_WL`&LZ$Hg|&>9y*5 z^5qqNIr~ZCOTHI*M|by|+cg>N92}cgXWJs?=H_|{^*a4So@rP!?c?Tc(PBw}+`wL}&IqZX83S(0y5&9BeFH7Y^7~J#R(1MhauY>qfA< zDCxM^Px!==7(Rp8jLg<^RJbTTH1#{Y`=2k3BFP?^J}H!gr<`rxkA2V(gEAjgX)lZ?2{oQ(wXL#BynG!s_v zlh8s(H5BpBc%Zoy?BMy6nt)(qDWxW2NqR!qa0g=tHY{9UMYOL?&O7D1O>B(>CX^XB zUnmogoox1HQ^i3^Q{v2F(B(HjTCK>wV>UPwBFb4bji1L|7G=QLZ~Oi5S@ z8NDMOiWEj*#^k?wtq~KBE{v>~L~ZeX?|b?qV_4BjNrtB_`@R zv*bGg>9^UrKgfXVBs#qOHiB<|V%+m|4knf&+9BKvje&(**c2m8%;4u%UR|8su{wu;N0Irx3dt-13=-ZPeRz3I4DXSTFI$MIDsOt@_PJp zOLMH8ZV(b^$&u+nD>|2vG-ML|3ws})e;$wxSag0D@QSz!pu+!@3O;Ya7i`1B?8x-^= zR*nyIsIe{*13t0+^|5?Vs7g!)jF4Nz_K-#T3G+4=5P1C=V4OAKYCq7YfdAh&wxGbm zZDxTD;^HEd#qc4<3oj&4E3~i_0{(p3e8{3~8*2#dLU+OvjRrE!qys3h77MffpAd(! z>WaV@R_{#X1=_K@E+ZpF51^s0We0$idIQvW6%jnD6>t#T5P4O(@iXR2ow8JX*`1);)ujY< zMa(pV@iWP<&(2-mc(cU9$H^#IU!)yVz|EI&rw7Z2_!JM}GoD%gbC@Vg*v&L4dgD+S z^}(HM${=f~fl@{)Z?VJtQb6Mp;i`JEw=lr%D4 zc}yd`-AK`k7hBI`B;8{tzYEd`(ioo@=Gr*OvZzINfaYLvRUewujJU7N!q;W*kV;GywT@^Wy{nKoH2Q*5T!CpbkGklXr7~ zE@OD1q?uXPY2kt-e#>x%7QL>i+-@ya56+v?7(V@2?oRCy>xVtpJ3Be11_C%H{aRR< zt?!mNps+&mcnGh`c0Gl?!GU2th?!qevcptqrvyV}FnrkH@gW}SNGBjI-ylX^r!O@3 zdv(&!+fN+mM?`6%N+rJXK<`|I|>_4%>1oK#NOrFvwSX5lb=doT|7TewqgPj!nGKBcM9 z;?ucxo1HYEJ+n$?ZT${Tp}f zLss-!dt293-_#3*-fCL1PN~%MK6ql0#sWbd;doE>7z67(9Qsw_lynmRTQG5=F-_>dID!eVc1a+6 z%xkHqa4T7iN67>}bc8q62u2)S6^sb|P?DKmtgdOzRzj-cK`be$l6p;6T6gB2f`Y}< z8+!Veo=;mxf`X!bL5^|0*Ov(BpB3byu5=DOW-7vLub8U{v6g}3IdmsP!f7)A)Gxc; zq5>?)(W|Sfs_NXn%}h>C9$LySDA=c4nH}6;tKA|{9M;J0z_FkGss6Fzh=5%b*SWcX z3vrH)j(H91A6^J{mD_x*Ju4V&M&mr>5E&nD@pOLJdGs5h8)bf}LptG&&R6PrN%Km5 zv9B&LXnCeTFY_>(lf&W2+rZuk3trX=e)8x$3#3(?i{y!U>+(@lZM|D6a&O<*Fug0! zlV+XNhW#zfKF#u8X~SK`GA}Nchx_x=gZD}gvwR&?Q%-T@jT3*8;8%U{8E!>)D!&j= zaCNP!m!y%Ko|;n7)lE>9wdT*eLp>m899^ri5t4RD?ksv))hO`fLF42*eD0{lMQi+D zb1zeR2}xEzWh>4}7Zn&F5VoB-hA{875ijB8dSU?)UJz1^r(*_o&K~Q$51|vu16n6WN*G!;;t)YH`$-f2(uJyE_J%EB|0xT zn8xi#uDOS`C->#ekz#f^_#kjKasS$ILpaZ&=j@;~onLf4ji&Y-{w$qB!`d72b<$~; z>bls52L=~Oj&-?6FLL$QwY8##dbxD&q0*or>7S|mwbu2Tw46xdSE1FEIx#SKZu625Xza*WZ=oo= zm5 ziE(p4ML1R*(7&-OBi6i6TOe8i01`a&cW7cB84y`VUaX@r7TJKq8~VWDlu{DO7-@i8b5 z%xn>vv`5ojBcnH=ZqE6_3XAlGm;SZnDvSx&b`gvZe@3SVe4NC7^6C$I0LU1w|E}%7 z`}Y51n)H!}d#+|`Y7w_@-xg92fq4y1GUBu;lT7*3_FMWz_ zI>q6MdB8NMb;KmkwR*LVHGoT}9V(fR8sZ>Q|t=;h;U&WpXS5HaLFk@*+ayyZf$4Uo`34zhM6; z4V;{r(Rwvp79AbEhXtO10O5S^*>S@x6oxxILngPP6|S_ek)b zzT0p|bjC|{o0~bL=^dnD&eA3*5l8<2B32EyJIXJaWEbo`s?p{Cx5C60;ekhPG=G- zZgcb(Tu_c&RT&jTj)V;H&jv6Dez%2F9C14EQ25%|-&N`Y20Mc_B)=<)zD;*5OGr#a zUs4~l!~ZZ)fz2Ar0WaP-g>Yq6Oxw)U1gF1UKVs5ggtx8>6$+945l1xOY#3+bK6}h$ z=`X@-3abtX3m;1a7(Wg;njLfPAyQ*eXQc$kV;CjrV?bHezWz((SQLzanz;EfIg$jt z3~nHw(w`i|HRg@k`rx0n&=ZpZ6TcR~ymTzo(m|-v%SH=;HB67Hj5sAtX#v(5JzBCI zo3dMK1oOW5@#rT(W8-C`yp4SXH0b=K{vVt-$;{N$)Z&~Rd3JVo z8Ve&^+X87ulC*z}oc{&mEG}@8F8-3ax}2YR?OL+w6+5=b^9rT79qsLftvPFJj=6bx zH+HUWCdr@M%hSg0dX-*zLs5%NVKuR=c(Wp;On_^4RBMkU#FH7M!i}U0dk&&ursfJ? z&xHN&$@A)8{hWm{nsKV7rPyrX@&LbkIn-)yu9a@UHzDT% zLn9A!*2$uk$l#)hjRIIdW-YbMq31K4@2B=Eox;cG5VRRI<2*dka&@)o_e7zj`GPYHXtcHjTHY@F;#|B%WK0rQ z%X)7|LN|qC2e*~wPt@jqXMi|5y8e}grWaK=)46kBrgs|T7e?yx8zwsQ^|FdfZ?JcE zZk%WYcQ+bsf;EqmU@@Q*857T9AxvQQHE*E!&O6iq|GN1!3tnqyX_3I&d-9au-_|mJ z9(m`A@Igy(*k!gB?P)ybPnKI-U+4I?tozc5BJ1T#y_#4yCMUUO_VNf%)UjB$&}~rM zknJpWnw3kPj&Ks`Aqu2=_&!>|e35HliArfVTV25}j)7&pS7~6LG56Agd*;^Zo718w zV%3IRe|fiw8y&Wz(#5)hF@fXxk@0D3GGwJI9Md&L?%tGlm;F}tL&}7o zCS`uzol$tQMVo2;Rkq`PziOaY5|f^0UR0+eX?c;mpd75X2rI(hRKS9fK*T9(u{YoB zd(4N(_}B|dquxd_b^GG$ktnRQt*fG#tP5mc!K!7ZQurtZGD;nMR?ITtziWam?%Jdi zlnzG3#y(qt!?>QKi`HRI^2u%f|Wq zJ!^>BKto&Cpu+EHo2;zEr!S|G4dBEQe){ywygyT>$@kvKk<5U+y)&{Ay8HlMs zmZjlcA&|kqqytCZ>a}qF0!BQ&*tZu6K~8-l|Jf80WvfRj#>L5`e5&B8ee%~`=NJk(CyGrr|Iw5KAJhD7YCi_! zSCU;5HHsOwyOF(YQq#kmS+}k4Y$xXyr5ol3y-|4hHy7XxkEf`e`&z)4z5WL6H%0M+ zZu}jCJx`N4;MDxUT2c{{p<4N(e3@D>g3hj5rc=33WvicLL{PJ9v#)yx)Re_t+3eoU@&okX{=OISF@Vz z^pFbsSH|MQ*Db~O-g&$Xn%u*6;WA!xN$#cBa}(vc-l?dVCrAJ0@E3k}T@GTrj>W)x zF%N5gTqOx;f5j~xJ4N@aD?j}r4rVt1;UcT@7TNDQu!LvnAv(c%fT&A6w;Ly^FABCN zY*;hp-&|y!6OJ$bd2RE&*oe-;GZ8a-0A{@jKkKvYZgIZ#i%TA}4ZQ{8;^0zioLsFP z@Y+}0|ElslST@A8m)3dp;~>4W^x!iLtg=(3SNGT~s<%gq^B=zc<q}^L$QrEfoVCC22HpUv`n#CkJg~ab7U0uE$sTP_`1kFFi#nW+nL95vik-$81p_lr zqloPlQrGkS6bD|B>TI>%7$~-XqLih68fyd>@Uh}CCD~y+peS%7g^NStu$h`(5l%5m zl%jv)(A}&nFuK@fQRrf_VE4qJswmb+@K`$Z#=b_}J{|C^p!sQZ=6T_!^RFB+07Cl+ zh<=6s>a-i@a9x;ENz1cdE1C-9>DggP<`y9Me_r^gj6;i&!6?A59R#o4CT`{) ztpY&ER#AmeK^#ltyBwX>RDu6PNG0F(QadYd0v1;jee(r9AFG3x{SrjGKLp~GIY8tt zprl@(7N|fTiQ*MMJ`_*!1<@wA1i_-lV=B1$u9v{96Ny`Z@2B$CD?wzJnXT*Q&O`-b zVBNzjn=uLciPB3vA?=sQ0AC zCOvsBs?_Gd*@PClz9B}CDZ=GAW>?k~`u9Y`~G0a+Ly zk%cj=`q^b*Lm?1lu^YPhjT-ZL+XL8$4LpRNOHkUBS2)i1wCaF7__*iz2rM~z27a6e)6_|k|B~4MdnD%dABwobzZ7vpT{AgG#t8q!#L?@ldH)w_ z?-|zA()IrzuyRlkP*J2v6Qv3YNJr@)AiaYKh!Bc&2vtQ;=_S%ZK`9BL2c#oNZ&DIU zfGC}WA|>>|Z=&bi_w!uOi~o!N3$H7H*?acvnKj?FX06Yd@tnX`CYACfby`>V+D^B5 zxse(ZsxEea)J*NlgBY0{yVflbn1gMD`1ag~pnG~PZ5yp&C^xkB!ajU5$hF=68m2RA z^JpZR3S!uKJQpU;Ix|un$0`wJH<)|A%nw^>dVIb9@LD1A!S7H>^e8R}#Wt|CLE=I> zyuWx{p^niqPh7OSM@w@gKz0)M` z`N2V3h}~yfWe(l8H~#MMJ9~xyF^^NkQN3zc(nT}5Wg9`$;HH-wldNst zt)jajm$HmwR&oB#xc+`u}dd z@k&Q`x5o{=v}eeB{g+-my_(`~6Rzcsi+}wf6?4h`Z{dgX#DmBR&#@{UhP{y*bQs#j z--{f3EEA^Ef9ErLBc$!t*Y=(5fI-05=O!}cdeAbwseF7YMsGGu_lEEac)Me4+; zh<$7Z;-qzE=%d0JiKR~ovxwq`_^WrGKFd;XHcWeWg6>xaFqOF1k$>~B|7i2gTr}2b z7JJ*|4i?dq$|0`@nnL5lo&hmGAU{psyl7GYua9;5+M~N*+xz7Y?@Ok(Pt~oxPoz}Y zm1C9kSSj16@>R}FSbR4L<4@;l#qvhNv#x>F=dSOFg%1oIHfyFNVAWuL<6-i3kmMd^ za+eC5tjHV^;!4gJ6Z6!Url1gS+f-~frLUwqnWzU|%X6?WofiCbH=h;U*%Rbf$TvBG zPfy$1m&W5tyi7++2;!<52}7w>iL@Bx`@2&n5M$5$Xd}ucj=}3P3Sdf18(eY}7>NS1 zm8tM@T+F>`va=rRjIA_T>pt4Xy3T=w$MPv!gOTu1XU&vXG`k6rOv1Wimo9b2wX>}# zFWx*s(GFAwdC&d)#pgEC+Mb2n){w{HdpYVBK2s)PQ=SRTUyhIBQ{vc*>(;|2JP%ef zjdnL00_WgIB)gx}t?sQqzKR5YrR*mto+2xU*8{evByif`O&(qpD91y;Q=I9*h0|7H zxS}P0o-F58alUXi7A(Dgox1ZP7wk6w)!UzU_n}5Y(Rq(q@fLc$AhFM@M~oejinG&( z&T~gN#%t(g4Z&(f^8Tx2{TA?ups19!@u=5^fplZCm1SkR@7}$$J=|R{^IRG<75cdl zy28Vz6_K6~)rbKpYMC-Tv6m)+&kjQH-HN9FpS2(1F5N+-@DvX7MpNmt&1(mVk9cWiHdM_=Dj5y26)qMtbs*|8R^gCv zxVzaeGXI*$?BS7QeORg{jri zimnrONndUt6p7eR)jbm6$7-S7DqSWWi68Sa{k3G7_>_-ztLx+xA;`5c2x zO$~3zkq*nx1uwFv98UUZU9N9InOyOLr8P@~46|vszv%gcei;~b&XM*zee`lWBp59c ze;C9|^&&%^iF@5WCgrn{n|%q>@$r&;js2GXojIH;>fzoivxLqBnN2k<@zQdV$UNH@ zT#$(Eug7D7NfumEQf9;Zqrr_N!_~ka6p+leyj(Cop6{HcuVjxnu11=6e>#87Hc-j0 z!&J+IF5l|99H+*-OMyS-;%i(hqZPkq>fO?JN7E5Pw&N8JminAaB500{I2G1gOG}PI zo6%W-_1^XEEyL%Eii$S5eHm-B?;mplj^-G3&2{-%#(iQ1Gip`Kb2aU@g~~r4ql`KZ zPi@YWA^EJO4vP-vzQ3Z4`^l-&QOj0mv?hvvGMYS~-TCzlE0WHAlC!26eHEoRqA6Z|cA{LQ*pL-`D z{j4HexmYeKJ`JsVB-<4Tf{nsl=9icg#rd)JRslMz!TGCf2Is%b((8220mwO5MhQ#Mh=qH{{WG0! z;yC9fY2`dWe(t>VG5v2z&)ELP!@+k2@BEVbGLT;o7CJ2|(TQ%w4XNhrI`#-Q#)*5r zCHxkZ5BJTzO?n^*+m*#|*0Oo?@}NDXpbROa8m}deTJJSMkNG}S(77M;l!DYb!U}B^ z6l6!S|8Xvd^|iIb8>U^LyO|orT*sb7?Hv2=%}Ji{S#YlE^s~>fLrQQbltlSt+C9+T zc+wM7#YVz?4DTZOOx@bs+uLZVa3~9yQy=r#nfzSxp=tlc{AVL`>qF+@72`WXZe|mO z8^5!M+aWpLqwvYlC25*5H^|?=lA44y)4CA|BPN5T2*DavcMlJwWI@ISoAziJV9GNY zsAP0~GgUNIAKu^d{q-}X?4UYtYMmd*~;5+Hbz(niv%=L zdap-MGQgmH7*-NE_d3aTO=btKV`#zHP=~V88Z$=uBbzlOl7}pn6I0 zCaH?cN$>I{!O##7N|(rmx6vp|9w)tOPEi=0KGmq6mZVx{!2DID1+qYElr?y{)P1eQ zy3CP?XOdEwvABtfF%lc7eQ!{<9UmbW9~8K6tk%oe77eRaiB#pb=_>vVMhkwp6Z$!9 z+|L{b;QZiktp3Z^GWQi%IyC18qJ-p*>y{^T!Y82ZEE^bq;_*GfxhSn4FS`mXu$5B7 zKC`5qZY%A3_j3<_y-IgG+M_bBUe(i*S>mcb*v8t8M_x6RN*kWuueQ&;#n5=i#pO~2(WwpF$79^XB?Dp1Bf$cg81u`yWL)ApVCZ2A6T#iTTDZJ)4uv7dzB65^y=*zLLi2n9m5DY5{{fh+SpmHy&<8VD@sEFGA?5p)!m@ zmi!Di9+t2sF;|2l9rM(SR!1OmeouN5HokLm&it*zOJC{5%`*d6ZK5gapG7fR#bx@h zWITFVFPp1KUpbRW3iq5UD31*EODE=U9VM9y;xzZ7L!F!UIeV#cL$1yEW!nf)VaE^5 z>!@|WYaZ_uLYb99vxTQ#f7_?8^zL5C$VUJPvzKgLeEeWVsgt|$*kz?FAM#>tb|xmN zHjD-aLl~;niaFaZZOm~wDb0R=MMDp(FpyKe_Iw2;LTYEzyFBPiU&$+c&<80ti6B%> z`q@WWbO-jy7=@ivI@F|*wIKRyey%6IK*orRXRUI zZ)4F;2sTPMe0onTpA_q5q}Ghrj z%z5GihlWEnJ*^``cPSBTh-i4e?*2jt2fIg6aypqukh8b)zlW6)~jO*Eo?|@ zi`rW>xcza*_RLTugUm|^M=bP@%pK2ep^005kF;&sS}NO^(bmQ7N*3iO{3vXAmOE7n z-M^KmYUxr$Bm^ADl;SPm3z=T;iN01uEpMV?yj^!vcZ5(QzfERv1AGhL$whqjBce|Z z2Ypz`G;&$c(n-c~O)e{dW801Qqdtj&P+udtqBEj5V(|7`&e5TLr}N-9UMuv@>m*A! z+|_xFL$8)L*s5k2YU{L>*I>~lNo96mQHX;27H2CZ%Jrv2i4|20J{w4Aeov#zEO< z-S4GM(4JEDXiKk2wBdt0lGfORjvOVDRdMElYPdIE#tw^1s&(2ExhlKy!nF1+lz($E zE~ZOxvZnj+_2%3F4=Vy{>#;?(ec)nH4OD(2oBfgPWa8mc$O-N{oI~o5Wo75z!l4Dh zX0_f(n7Kh`d*Jq}0}Neq|3vlCd-jcW`(urh6JoQMmpqPMZxpW|zvnBi9aj&PC3Y~l zFWwLDs38*OuxpL5_+IWoq=wPhXRILRxZ(ICoyaOWNq34wP#+y9x=!Sm!X6(lclXc0 zb23UMORVc3?pebpg8EquorY}+b|wO8C6<3E*mb`b!1zByFA$Ek;>D+e^bmnuPN?L2 zXDMt>!i6GJ?`9%Ox5F!ucBD%69EQr{YgU=1@u=;Ej|Z#etZOx>ieb}qvs#x7R9e}B zrN2pd{-@D5Iyr^M&O&Dk+{pPfP$z`?#nn=*i($6I*KDOhpQgVYQq%bC)1mO?!TQ>* z(LkTQ`GYmP)-D)5d0tat@zkljYKJpDDVQsJc_(N}Sbd7UBV=WtMoxgW26Lc{&Y8iu zjy|rB(2QclTa@qhrgnZj!*W7CchQ9=i{Q8+4 zKaUnzQNc}l9IUwarPz0c&$OGZv7qGebg%p6)X+fEn)IEa zp)#9n7&_?S{JcY_(jhD3Pxgr5Q&fofWzM4`A3o)sbJuRHU@KAH+db)`8iO2kOX%`E zBIir1AQGyr))@WdSA&edX)c2-Nq^P<*L{_#F~gB*@91%sHd3iPGC;Pt_M?26)LATMkw@ z=s{$kHb$U}f-O8o^}T6%+74^*#X+-|)}+T)tJpM?AK7F+>!qN**M#>$2dlnUzb0oD z;rBKxCn;bOM9N$jYxzoAFh1-#&4Oo>8(Ox(NmP}W>j1%ln~cagJPhFTyZkL?+z#QL z9E5qCtAF?1u9!69{(jqhU9C2%?u2PWZnx_=@>O?GjT4FJBAVhZ!PQJ ztilC`!#-7Xr-}zp(X3(We~uI8;$;KvRu8K&T9d}LFK0+;Z?s0?v+D&s861pO-&MTv z6$t_Rt@iG2$3bo*0}ZP^CU<=DeK=wii>3tWE7z4%X6Swye%No$zco`WgE^`)$#jBD zd@B!ic8)9ci8KrjHrdK?J@#$`mDt1)Gn?ipg>ciicMozd4-YqIs*jGvSe7#=UR_!e zrLP8x=;_uozUrrIf(9dR7j#^=*B$NE18Xf-PVvF=m&G5;8)UB@Hj;YbYuT+42v!Qh zJZGE%skm|9vAV+5%I~0lr*N{{dylt(jdZqoQ3W@?hBYWI&p%4GK>aH4{`fFOtQVSB zz;XvgZPO$=qQBChqoy!tVQ6@HQ@9?@$X)BT!W$@5_vmPIy3NHou+`S!}z8z(3|$IIcK867^=p*80ejrXwVA ztx4}(5sR&6=zfD*v>&QX{iRWZgZN^a+cVx6F>rgt44(;)(kC-qe-Y5>)Sef0k8FkosX5q^NYfFw@hm z&2PbEv#f^oZDCO8_H4cmCP5f}eEpGyibPb|&A^eh}F!ddAG>A$RCQB~gfi96Gle#baA;~1u(ADKTf zoIm%;weLd7R+r|>wWRdICZ+XrN%tn9+77%^)@Jpz8G-vLgT>l%2usJGL5J;ZCQ{Zb zp^Ijq*0t6PXRyj9@xb!R&h+tR_G_Z?v{L~_OmlbRAugj0@{*3iQbzT+42lGqU!ccI6u4=~+A-9?kNW>ONvoUto0>Z|p~^Jy4C*gru97q|ZLCewG52G;EeL{Xfu* zR*AqpXRn%a3$G(uPR;}nmDJF#tSl0`Ot$t$D?bdRHQ9&Ct)^Qc(~jPj>!f!}b9l?Z0BsY_L*9*3k2oj(N|W*XpWpc}1A3%RG`Gf`Vcr zATm3i@c1CwvC&ab+h2R6eFN?wNLov7P1Zf(`4RCmRSWfb>7Ke7#j^QR%3vxerH48{ zak(!M5$gPiYns8aXOx-|jC}Kp1+uOBzM$Dw)Ni_`c;caApZY4mLLr@7wq!}vSY>nBG+sxqQ zeqw@F90Xz@;5ki zxk8;E5i`#HX-e3sQSM%xx04S|t{|NYC-=Hu zWZrP{nrei5ODpo2tgu`f=+u^a;OM4WKcinSMa;#z7ORJh$E+h+JI61_r>l-)P#>O- zD4~Y5jBDy!#3WN3lZvO5e70XRVitG77+ikcReVFU%sYCVIuNh(YP;FdVlAv($Py=| zy<(H?6E_+o7DVh7M}8wky*dM=<1uMK1>?W!=n+}9mR|ExZF8YGAa^IeLa0YfuZelRkT zx}-&H?vnvyp^!D=atzvjW43dHw1YESD=Lw@|8R8ttt46*C1t>^X3*?C2ZwF6L^_~O ze+}Y6>H#!GJ~U?aP3>CJ^73iSfvG{6F1HT)prv8gF+0CqLM3?kV9PR?aNZ$yvPpdu zZgEY8HF%4reNt-KMdDzqd=@Qkm0)ifpq1$#5NT^?Zx$nKsHRI)QvxCCBpIUc?II3;m%v@>zDzpQOx_>H>@?9G1ac-MNZivBh)#>C{&Q@==ho% zf)(qV;6mh1n0Pn}cQdG`Hmvuls&pepRZW$7=YL57vtv&$M!Ls!st&*2PV_@>yADX1 z`LlT?Zq@&wB&@&Xjf2Z>KR}G%Lb4jMkP6l^^0rHX-NLUSSOR9EHolW~%&5y9*LUk_ zWPJ1XM?c8L-vNS8r5LZ^NQWwl>EnFO02-=u41!pWMv2g!VrY`vR*djA z&c{k8;un5N$VG6f?6%|dqFP2eIU1c@dZF9qWcE6wmkVhB3N^z@ulsKcV)+f8!N%y$qt$vM8wp3h`Ubl8(H{di28^K zTbp5-D~l|j3?{qsI1%8%(o|T)nRBsxg0($RCFQM{zgG6-i6bxX9T?4KA?^sRYZs>H z-=Z?((LdjKL(1tq?FICvVhBrRU+G9viAAMTN&q;kw#>REI!5ulLUW~G`MmoY%T5P4 z^48mz%iU8k9rStG6!T6h*fd(j6pd9)`I`;WPtOVTc147v>sI%oB_4JSjL>%6$E&4LrbWqJLDM?@@|2(JhB+e{mQ zWnqP2A#3%BDGkVj=Is`+879eidG(j-?D&3h8dz9J9{3Ee?bUQLHt0O>jdte13RFJA z8|}$^Gass7y6;0=T#{q+Hb%xMVo2AD1n3;(pnEwna_?=TCDn&HQD{LcVnMI)R6|Zt zLJwygI)@`hZsjgQ)~lY{sESn6zQpC^1^6pwXg6@&;{T%shmLYBt-_!!Qi@RK58g&xmp1X`3=h};#y&c z>oj|DF|xeBEbWHctU}I0E&pQH>V3@|cdIGrSj(IWA+0KQmV8QaIz3@#aun1Fb z-7D@>xIS2xy>l>E8Pv8!J<)q*P_s>1PB|wxpU*9UDZWs?KxWLHG->G>gy)HyXa zNGpcQZ9!@jIR92$Q)VB1lc9B=!(`aUVAwQ7>L#6r&v8?HqZ-2O=v2L3Z>p#$GlSabxNwS8a09F` zLjq!GKxqt<_%*1Zv{Gigg>@DAkqWWxtMe;0_SxMTzs$YjGiqmVXHqM&#wMYAw7$`e zsYXe(VSR?Zve{Ce89l78H4?Bzv>z7i@MGCf`G;GJ1KF%XdxM1H?(em$Wk;Q#LXmK7 zUV^I`Hs)32C3957_P3engy6ufxO0a#U#+TTHg{*TgPe4*2d8Z;?xY0UTi?AZ(??7L zZb+k&lYgKdtRyNEH>xf62twh=uczJoD9a{B5(vi`8bZ4$s=j4ApF!(_zkLxD`9gg= z+Mj4Zn6Pa>teF?W*BBAkTwyx;=H@fu)~LOFBknE2kji|4SJ>BAkRBPAFY`spfn)0SLlNFrL@ie^^K5Ez~J`zb8}1?1onQGnt0mh8P?}w2uHkhpe@_YyA))+hG-HSw-DjdIs#ECV|okNoVj_{3=%?t`t_j%6$R?qZJxxujX~1~q}b~CMrf`cwx6tth-BT%hdnk}lR7vGzolzw`4nZhW8ss~->_>QcCNml z4{A`{)TD8y19-nBtZ8@cr-f^BP;*zEfX-sRrJZ+X&Rr*l8VYSsw`~Lc!S?Q zilRGQt_FlH&13SSiQG;rJ_oCHdiHxRT|2sE)yDI^SwcSN8&wc~{|VVmm|oGeEhIvk z4Nr|sU9GVr7=r(N(F6qOz|$&2S5ZmCj-Pny@bw!`D@t;(t&FW+@xej|J+Rkwg%CWl zUCL02j|*^Ac|weVz7By7mySneU*4+mAv}#j=mqV5g$kL2AU-+C0PH!wH5}9r#Di#K z?PG7SW4z~r*S~e^Rvg&3>6mP(YGjbzw-Ndx>NNVO;cy?KLk)N2dF$?oE6MbVu$ETz@*oP4 z-~Q9$`O;_N(If^Hp(tNEDSu5vPl*< z@NqpmIKMpN=#xulV4t)i6breE_FdtP=Frwl2AzIG^pypLjguq8xOd}o%x@J7W%oz* zw9#YY=ox;4;B*q9c!MxeU3MT?`vxyJ;NlXHQhpl`GBf|-qn}6sq`r(CW(R&z7&C=2`gUSp|DYb4AxC&cNwlZqQXr-?X7bFC1>@9$h zXbA7O@c=wrrApAk7Qo=a`$vlgl^EiryN~Wa)@lhen0cSt!u%bPG&?_!*+b-E1y*$Gwsg(|93 z=JTg8&0kCx^#Yaau{&`*tgucTra?8+sUNL53U{9_unD9x^Fo$`=tNO1G&UbV%uXFJ zw$KsBA4dzFrtYc#; z)Z)&^8}TIucG%iCj9?Q?Aloo_Ib+`kg)mwPlAZq5g8Y=nL@=T3)8EtsSum8_S+J09V_>k7UBBJM zXICtZw)bR7DE#opZ<`q-hD}3$i|+Zp^eW7Bk$4m#q!pg zxqP|rjkRNh93kcd9VskHA@ZdBuf4R?IWCTR??*sJSY5RIles(&YqOC zO8s$hut}}*&ZK=76evDX{F!^fq+=-;w9oO09Ay(J=Y*@91pfzbQX$ObT!e#3pOI0R zNm`5-ZB_!Of@_Uhw8Vz0gQ-o1b(r-2HwH|CHar;YE)}?=(-nHDhhwIOYoeHnr-F_H z{eJxnM+h?T{Y){Y%_s2#kt%HyRJh+RrEO@J-=?zO8^e#e1V*LNC6 z4u(_oP4|{e$=Phk;SpGQkweNUik9xumONQoe?(Z>daq8HJnc!g)_mqA7o;_c zuZ)|ya2D}bj3NzWwq?vk{IW6w3#49sG_0KGyCX<$Hvq})dYlUNe@Xy&N61(TT{3RY z>wQoiJ(Zc9vcOx(@)j{FX|3}W0K(Ku4GMZTpFD`Vpb7(3wEAl9EOKYRl-^FwKLKEd zbL5QOmt0NF&tkLH%$@+f`j-1!Be{NIicDX@;0S{teVv7ZwhK&`Gm94;>V996?*Cr0 z*%1}@xD5)0O7n=kg_QR+~%WqMsNs7qC{thS;eqahMjqX_qzd% zMgJm!KRFcXC;U;F%w7p~2JDq+Hjt4{R7lL{1cg2(ATjW^id=xRy(N7^^3W4d_5#RU z^ueusXjIh2ix>4TU%J#vwEXJJ8<&>G7pJOtle04Qnj!x4;?msQ;B^53@7MPLO^GU> zr7|ngB@Wd3*))(V-Q8zuzeR~iS~O&R677wj&H@QHZzCQIUvuE4{L1)$a+sS}+ja!) z7LQk2ZR|FDr%2-n?s^lCvD<+)g@?Ngfq(txgOE>ziY)RwU;$Mm?3?saK(){~nipXd zZYo#_vXaqtMPzW>SzmVW!h(ptZC`hb8%XCyx^D9G7fyg&y+n}6Y&rt%@9yp{r@x*^ zmo{=9VJ+nq$Mc^5{a}}KDc?7`v!SZ;DmX)p(=}}nqGt#=xjDM2I*750?QV~CCoZWZPcud7rDl^h| z4}d^B`KZbAip4=+ZJE~q$2>QaaI`)1@E3Dr_@l4}b7@0>WU-K-2PGcA9)J>$L;QN= zt97fugR3quIx_FBFh4(*oT^MPUGwAJ`{+HYtL$VcUZ~H{lz(g!?z|lGToFLtX|OvZ z#iIBF-T{zx+MqFUGpB|7K=o;m0)6GjeT`40)^woX5mTuGW{l3ZnfY|S;tf8x6gV#g zGtD@!^@AptdCBf9EE@ag(0;&^G5N6DqPbH(mO~GJCD-cSR*5 zuprY$G4{-n$9Qc2b7Ul-y4Z`L-d3h>GGF?^QW?GB?#4#_3!t@Mwu31XK_&X&x&b9f zIW~wlZ>ObvD;QZbP?=H8d~-~|3?$c{ND~3+w#Fb2+1}|{e)0)$b>`pvwh;NhK`P3p z3q#>a1-K%t1!L0{aJ07W1blu6gpl>S!4M(Q?UolO~6vN??aCPu0#L5$x$pK6nR5GmIe$V zvVqd&ZlVDuEO%8BG}*orcHy=rXqyAwM_H}EfdTp?I6`L8#500+`Y9CsU?ZEIx0gf# z{_8m~XH@nRD~1W6U58`V*UCbM%$+H`M;-O5y{}W5jpW}tOEChnt!uQjUa*oc#xAQw zwu4L{&)V_2o9bf_cs_X}@$N}bp!0_jh<3V6Wu}>bou!QidtE7^5*RO*%7XZZlU}N$ zxqb0`?2l7H3i%MngTQohXMx?GC~}RC5HPkIVdh`uz|$Tw@Hv9&r=J(W)AoJAB5#0p z?E>R%OOaPS4m=iguKNneXfM*yyFgh)9b4j+kxnT?zL-M5JMxp>1!fX0KONfy($uIP z-gE%Kxs&=}ddi>q$P(Dv+4I#egTd48@)!;S`a|oiG?qRdIfUjDB(k3Zw!Ca?cwOjQEQ0hH|(J^ zt;1+_ic?CXmSNz%_PW1yIYG6Y>UBYNNg zJf~)jH!NGiV|J%%YMc5N@%L(fBNkLgPr5R3#6^0hNO&eYSyW2fjm$qdn+(8g-@fHP z;sMnFk845Opa9_-O9Y)8#{c84kr^1DdbdjXqUexz${RwFm9pDc9Q?jzea_A|o|ip*)2@4w45RuY z6gy(0z4RQD!T|$8Vwlk#J~z3OiHl|6=Ks_;zfk}k!)#0;lNjnOf5ObF9E6~oKMc(# zgYg}uHoH$T#^UjL=<~rF+uZI!H@U9&tH{Z75OZxIf#Pa)Kl8G?24BAf1Zn;VzP zek=)t+K}6MXa7ql4UrE7vu}|NU@S3bKzshDF?bB@Y7Vub+_Sd<3%HuoL4oOG?aAS@&~L+ zyqeAb8;sl^h4QN|wQB9<{fX~3{x;c~jwrL1l;iR+Oh=>v%;F!M>2DSbz<>QsrfP+f zz`J5UC#e~I3s}5l#Z2bdAsH*lZLCVyh)Z1d7@u7)&+_3q*M*Dk0Lrt>bY8V~6Z!^< z`7!^RVAr`hq>9OHf@vfRJ>F=}AB2=0xD3v9@qKdYWipYQ;V}^os@uySzCfI-fc6%^^r-58%|7@bs6J z6Kv+3vOr=5x#zrtWzP)EVyZIhFOZqP#hCb8) zi~C)iTX>vGz{EUxPVyP85IIxvY3Gd=XIvru0X}Lm4u(ji^zVXT9fqsPTOro9cT@RRn zl$TBOnHRUIcCD@TTU%HmcQ!Y;j=#V9Y|@`OSfX&IfL|yHi7>i@2`d;HG(1UpBlbOv zdkkr&uB7(XY1b{ckTib{Nc7WS(E)8=1n$iM8IcLZ+bu9uv^r1E)Wp4f`LZiJo1-BA z`FvnVb#*nSnc42!>TMU}^Vot2=~CO$L_?Pd3-)L-_SP|crES>>J^-FW4{o`uw=aVOBd zd=vou)iN7qU}*UMQ&N(~tBP+7%%x_{bZ2+9fn!0ca6YoiPY8~qj1qYJe1ahss0bFf5Wj?v+g-Ddt_L6=O4~EF7aCINYP3Cx& z%*268?g4C&%a!&`MfAh+Czj1^9Fq+_#t1&xxWE1U+x^x1K(5CJ^k`m#FgV9Ks&L84 zHR`SuY0hc-5&tfj4aa*X(n&pZF`hImNsz8z_VFHVqdB7z`Vh3(!cxb2c!!J+a|uX# z6n4b+ANtrIBKSV+j$!1&1TB7>|LC;W=WqLQ+=O#bOXDSpf}H=*#{mAZjdpShVv0i} zeYV^x6#k1gYjuDDut?hRRxhO+*ILPW0H0EPcgi>1`Q80$X0q-D>!2~&M`$Kf`-@)cU6}hrrnkEh4uPEREIRyS-6SoT4`2NX|m@yJSG}dHD+tlz;y7X`p-^A3w?` zLqotf*vT^d54{)6cPnzay;8ESnHsQ2m;}Tr1z?fBzTrfIzmezEU7+L1qK)hyfC|Mr zu*5cB^EV|+sOyg#fEM1gNgQMX0r}7A=KS*H8$Y`3KwclgolcVh0FQ3}UM|TuCNnNJ zXyiA^{=vyeGB4WGH@$#a$|=JQln-8h9R3epfPAa}#6(`Hte|`*o2nHKjl>hFl03aVQMnBaX%9cwsr(*d|>XBbkBp>n* z)~yLbKBFM|uem>u5b|Gu@P7w~4S8_bRG5#pgRUaF{mLgp55SF2gMsDv{CPg0;Qk&Q z0CGxCR!+a4$BGPgGx!o;%rE7XAU^x|*NZ?V`~iXd?haERC3;zrZS>8}M&C9?Elo zs{~#C-6+u5{3LJ@JTVH*KXc9u@o_GiCHXJ=QOT0cQO|$B!h56Xh0Z0Za7~+kuKL6F zq_5SqEzQD`$nWP1QJ{PL74vZd=4B(%B1Sk@9lopuDW&&tp6cYlB@Eo+9H$l2ch zD+XY5$o&C+uL`cx+)w%M;}Pi}e>JRcC{49Xw}yyTOq8Br_;Jqcj5ljq-#=fGZ#{YM zHvGv#iNn8FO^^I*O(VVMr?kbN#y-DE$v-NYSX<`e=&wkngwuq4NWB%Bcq|yW2H*R>A43N&aeODM0>TXwL- zvaKpf#|`m`o4Xqy1%i{BZe;pEkS~VCW7v=RUYpnn89H?Kuk%Y@)n1dnKZv?gry7)L z{c`(IFisomsgW7(psY)6Z#(yfP;FnJ+o5;kLUqJtrM|0S|+{#9QFyB+| ztdPU^hvpQj+U*guw$lC=qduioT?pP2vE<@jZ%{n4`Bqp)$2XPq{G9yiOb;R4T$gz# zPWzn+m0_Kb@IqW1TFk8VDkUZ5;LOZSTxu#WWMf`zV|yFm{9~+B(*=w*`B_3g`?&lx zfu=gVS{}`ID}Vaoc(x->!C2>uD&26A8Dp@;mk={?muLJ^Zp&A^oyMN%eXR`4)4C$< z{^^3_+GKr12f`?h&q&bPMpj6uCqvdEVNT7`7-Agj;Ot6K4JbMY3<>!)|1I0>SsUYedZ+XQP-(zDM8hF zGuuC1Kk7fDdUy~Q{TvdrMi03@?bnfqk1S+%klFdQqw-Y}701)W=8~EDygQAtXtnxB z>K&e6Yt-*H>U#xJ$a4nIF8|WmRF{5GH*?y-^X`+r%$5YX<6%0N47aGVVTB%bSqW6> zbl}?noSO!DK7^po{%TM(DRVS~2xPGIwzRgl^JIub3=RzmtndsSs2+Y;R$y(pYiU-( zVKtk3oG;yCnDsu(fh;YMC${+WgCM)E0cYNuFE*? zN>x3dyXr%pP-{k2~sYdy~+Zw+6sYMc!d_tz#iI?HgC5my^FMhL% zeGgcF{o1+wKzn>hUs}S4t+WxRj8DjGwloV)`V}O;*&a$_Ken-@;Zrf`uZJ7HaGh!E zu=r;526by^jdQQhLOLQ!3F^pOT(QAM>(UAOr0eXLFE!1*Ehj()jdEtwU-3e+rzAsa+=gJRIWq}dsezcp|2H37GISu*=QNR0v0DR&#_PP+0vre zwH7QkEob6Aw3A}ZWB85}nqyS`C3khu@Q3^N{0@C{wOB9{W`bQKUBEg90z?{ zV)w8~`0S(YT8N6Z=V6`taS1$rk4~(jFtd>x8^x0Oeq&3`3U1(ZDlVqlQ;t9r3#Gfw42cqSmZv z;`xrixwS6X>*pFm?lQ7h->HNL551|xmn0(}Q)0+#5217}^Y=h>Cyy%{?gi(W=9kD# z30w3q3aUdqB!#=#QdW!_ds+X?0loI zPU1~juj$Z%aE|M@FGLs>hq(@9g92?59-Sg9-*(b0>Q`E3v^D8~lmD)Ml!*sHh7no$}YQ|^JD$fV>>My9R_!WbXR5XPb~TSLd7j@@ouxD z<6G6iH$I%BU=(NkGS~e&03C51$Jg+@b0uu?MBE$NTGwCZW_HSRmdPQ|v-yECc_JO$ zrorcE<>a^~8(uBSXw?Sq3`knWe4mFkrDDhq_aXCdAuy}}KI7M4oAO(KH5AA!iDMa)XsI;qO?~q=x-FvO zuK7KG!#5y_@NP(LtrVu%AZG|?%7v@;_NpyKC~@o z&Nc1bv5$n>{`mECx6WRBU2IjT*2m`S^4R|)?JdKqjJmE-ML^0Rq(iz}K)OXbq`Py| z4Fb{)f^^qLy4grbmvnbYBi#*W@jUN)zVG}#f4mIbd)@b1YsMI3&Ur;m*Qf7k^15+@?K2)cNpxjh4~;}3qu0~k}2p(6)?TNZmiwlrie65k+M0M_{P&^ueG4fU%Z84 zib=hhFm93n2h)E%JNvVolt{9}hC;Il0tF?d$w%o#_<1m4N3rU<7#XwkuHpP&pp;5c z)&qgS!X&`*H5}X>u|atG^=lQMNOGeuQ|RA&KAL1$>uT@R@@Rev<#S(P0-< zy0KT{OzqYERVz-S*-~8mdLk*8E5?CcE>37O931){@|A>XqHBUUv89v1@A!{cmvwiM zKQC8_Y{?+3m@GfOrM$?knMyF9M?|ok#F{mE^O{)1aNSuEE}8kst_rzOeJ9rwz_Pic zYNAucTK1`%vK2Z>=bd%$ zHMaASZw4Jl7KuzEgkBgp!Tv3GezwgIJpOjY%rj%Nb=EvCof6jb?fhy?4C#U-^ob1U zM#=Ou*cazrOFE4#hON&cOJ$e6a4_@baYPRCMsowR7~+3WDXOHtTBHaaj+rhCt#+bC z)u{3p)8ARndmfQ)Aia8ubAN;ETW589f$wSFjEs!@3Bj7z8;uQZ5D#W~(k-o}YdW1E zeh|Cl_VtQtb@9D=GL8{=yUQBp#K zzKXPsQ|#}by}2L}8rWe0Zqh}00>bqabG0(S5qE`mlut^KtzA4UWgdTwtA-51^+poK z0_#gSW)1lOeoRgX9DBJHW4tfMZK{ZQdlMAAW;3x!jUaGhNaNR9tKv%K?24PMMnAn` z)%;)qxAREd*^}#<$n*;xuh3$?$jdV#@EFrq<)$Z`zKcd3=mDnZ*$q2D#axtEE!))(x0z%G=q=Er<7uoC*pb? ze6i2|N8b9?#|~9%;^!wV2hm?uyo5KDb1(IJ#tYn-{7VG5D#f4P$(cLTOx_2+yHj#X zI^xk=vLn8fF4F4vpqmnT)@G~u-)`G%p+S5*duP#!rQe^M9TWTC^Dba^BZ5#@pY}PO zsQTG&*BI*e&m>(B$t*94`8*5Cj2sx!36^`{BhXj8kOc|;6IVN9tayd;+#6aIt5?)= z*uRTN)M1Ad<{h7fVpdw8n!Yj_)Tn&+3H0k2${-T7PI;>ysS}qjy;`;q4zJPo%d6Pp zON=a!^PYOlwG<9AOxfo8vLl$otZ(VJ7l9yT<~!-`gmzm(mBBoRZJDDgV`Sm-n^}b{ zePRDqrrMtoYoIv8f2e~}QH`fVRqrkz2Ashvx7jEeDON|9IMQE=t1<3hb7n95O)R5b zK%(&GUw2O)Mx^+hve;6Uz~`_K;XM*pF%9EpU`Fk}!nxC5w>L&*y5W&qo{HNuap=js z=fza8(vO?ce3TayZVr3*-R>HNnCPBp*vP25n%>Rk=@s~*!Jnv=BW6zP1&627+mvWf z4;=x+VQdE1#QbMyX``O?In~PcQxddIJkW5@Fk_mYEqeYvogE@sk3QdJ^!~>AkjaMKC8#u8VDKG;R(kq-h0Oieg)$;e zugi3reMq5xqva0hC#-SHMl~a4T|jZV#qW`27*E%m&dXI65NwpB8fsb3us<5b4%ru8 zyh>V?`EA3oqR1m?7`-Tb$IX;l#Pp_;L#EXMu3p-$ZEIg>ohFIEbvjM7FY;qQ?;3CN zw-;{}9QA8tmIZnVlo8+f@ZVJtIw-}ycx!_B9~a+;e#EfxrX^aFOyc1#M7s$-6#Y@< zuaXVcK`3%TFt~*iYpAe*r$jVM{>c-`ROs&p3=6poRd7(wY%;6A#caMo0SOMC6q(t% zqWSF~YFq)EG&xBVD-@V9v&pMWK5y+FCpus4N(U2$3|^e#L`MI#*j^{%GN;YbI0LIt zeR@2lQd3!bZ@Y8N+KT&N5;2$ZIp(1XmBiox{rPGtK7W+eW8dA7me#H5qJB}xtEceC zbF_(Op^0Gu)qV9MjD%Wel|4v! z|71Kj8?LxNy>tKC=uGbisH(Z|Z>!lYXgg{oG6h5e;`)fCqu-j$G++J=zH+~`K|5U5 zyQ}6v&>|rr0qF*@o@`Qb z>$Pq?*uRq~ikVGXt+&w^5@dhdU*tjaiuympg21kYBmKhpv8mMYA&JV_gjV{0D3Z(Z5+kBXAgcd3?1gW?FMYr=^7G%f3;Hu zm%?6k_>s#N8MjYSZxRYlDXp4IY#D zS`zd^3cKv~z~k+<7uwMwt>ZuCg|}va;0)u6c*%kbC7=N?)TRn zjDv*+giMh@g<=~W)`N!cZyAy}r0;Bb^e$4rzn!oid1lYb`jH4fY(0-6j#lmU2EB4? zZtxpt$dF70w3+i@A#}{7Z)KqH%V#Mm3^b+K*dxhAruKx}%L7s{?b@(ufta{G>bzJD zvV)d3$z(dt(k`=Op$;ypk@B#toV0qFFt8Uuhl)gDXkTZ6Y4Tj%`4 zY2dw{V*=ZG<7I4(s!>tPX%K&YxQ7Q*x?Y(g;#sM-S$vC&1z$(VeYDzz+9~Mn_oFAu z;JC>>8(?!BlC-+&g-wJ?d=d^{Zp^lOf(CCIum+-*K|iTUSh4zux|oOB<;f z2Cv{#>0F(}W45TUN!*uA!JbR2X|lV+mQk}KeJp0(JIdh+<%N1Lt-JkO4lCsgS{BG_ zvzelPSqAV63AkMfu>dHN8e4BB^nLd76H%KqgdALlAt?as4E=N8O6LMV%=9InBZzw@ zo-D$@%a~e5f{9I(n<+{eEyYWxGuS$Hg~#v4YQkpD|ipiUye74#=HnN zq*PYjDimf%$HI z+ErggN(%?QsHZq0YK0OO12)i%5+pii=XXA*rfpNmna_tRoFPBK1tEI04=Q#3r8!5B z3QLGxyG{Cb^R!-XlFGoor-M+%SI_mIkT3QLqx$b-95r|TpT__A#rrh?#eY{=vxIZQzV;C3nr)R*1=u}!g0>(2Y*#SI56 z(MP|;nNQ%W(&B+3N}D_dfLHAncgIxa;;>(-^IZ=fZ0fJ2MLENarc~6S5!^p&aCmRL zIk}=Q$sM0ZVt?SE-OdK;1x$4pz4D z1{e<-N$@)V=e@ni{lDIuucFy`)9Fy^CFRhrX9hPo9pJlfG0ty$=de$}s;ElZAGkYI z1LX{U?8yOqaQ^^~=mmg569s4Rsj?`*qyNt{zK-DeKhOB`Q~KoT5U(wG@bW|VP2ipj zGN0VfA-R=SuU}~`a&d_d@CwPIGlY|G0bn@!O9U5WrT>4=RNy^0oha$;RI}*-51m^? z;6Vi2&E!+TAtNLSKt?*rAGZ$hV3(ZXnZbyHZ^$3%0glL1yp`^{1ni;i^63CDj$lK9 z>sXeUf_+EOvcgo=cuX@WW(%(1E+TEkgB95avIHP#IbZvi8o)_C!Jm>T3yI`!!OoDo zg<1o=p;ZGJ+yxE(!=}?suh7$*3^Ra*f|CcbihF@7SRmNs)C!c_Ei|onJb|)Ryx_Rj zHljMAfsfL8(6>tZ7W;%V$5LHxAU)lq|6{Vjx>bjH51ZWeR-2l)l0k%+MGoSfua<39wh0*h4$*R595gTs8lOr@H8D4l4aU< z&dw@>m+?@+Jjk(*;XdoVB=i0jV+0$L+tL^? z!5jKnMrQqY0dk_&t!HA;7VEmt!GHmD>O5^~?xf9sMFYl=<8mkrnZX0Dt2emyzcASB zw{I@`X9r>NZZ4-(htkGZlWEQhpIi}Bk8n@^BzJ^eQl8X1{1*T#1#ha8ZFRH6KOs`T z!%b31NXX;sS3adLrI<*U|ARQ*C{`fQySlpmg65Oe6&G9h|3bjDBZG@G@Z7%s@~ghS zaPzirj6?}`#Z-BL3ohGeaP-fAPVhAd^F6yA$E!B6Zi+#dImv=3Qx8kfQFpX!5(!83 zLT7%nHr3{qdP;B&W)q(ltlLY+*Ww(0Ny)ZgJ;Xzk%j+-ehIYL^V9<4oajpHIACzgG z0+!7X&)#uLxc^gyPE+T9AiFB7otKRqOc;VR9SJ=wveVcl-PeiTVFisK{+%OQX#azx z5VU`f!>oM%zW}AWCz|FDDQ`v83}FPoEBp}%=Ud#97t*TuP2hknZz~|Isfm9mF8ga~ zZn^OTA3%ps&0f>jmTlEcA->v+{`!s%T=}olj!!SK3h()Tt9fU;_~)pIb+1q~lGN(g zecMC&n8cz2+>Yu1?-fvc0@j{kR&apBuKsBu&3U8>9fHezd~pGbQnK0^xE3hJTmeQo zD(R)25ZqT_P13rbe9Qm1l}v;GnEft)hL-=;0-z(QTycQ~;2r z6<%5T+i=*IQmYvjdXTe(#WdcuKXOhrC`2L|BQ`{38_O!S z^U2^1-1Cw>UCE4TI@OX8)4`O`=LgFz(f7BPYsYIn$*+O^I=^eqx>zR8x9MVF{2@2yHE zp915Tob@Yt93A{-w?56U7jzK(6h+A0>8{{Z=5B6IBbUxYImE@~RHlD;X(NBL86RrrEs|kCAC8gGgIYSIH#sVVqZnzQb4Pfu&okE zG8?X-CDy;mLjN>w2mQ4KMqCa9zeVfa$=|$)X9tl4bvD_{-$_H7ycZ8RE1$~<(LQ;z zFpA4Hny0{#CPQgxh%X~!=9dd&9|D5GPG7uwg>mR?da?bou_Xq5^EIL^hh@Niql>}S zOl5w`>2mTnx~JWJXH!v(4uF(*EnbMgQwOmG84QD!|q6uT&u92zCgQ}F2BX!98RHs@ESSNCltI6=GS@V2tUu~e)9g;qkhx$ zo(|SIBUyk;Loam;@%1~M<~^I~`WcTSjW1?7qNy%C9b@5$mj@CCw`D|0)hkw7sm69q zWtq;xiSoR;#-Xw80IB2`y^6OR$av)NzP%5jgTzGu)2(u#Zv+u)#on!lT9x9%&%bDN z^$(ERr|0IzGuRsXyNiHow|VDY>_%Jc+e7*SF-t9)_~Se5AW)^I(%G#doseap`{@@p zUMK;VE!kb)yRX0PvNgP73mz#baQn!kw4`#!4&P)cl2zvo^t`nS9v>9|d5KXPBD|>RAmtuLwTA&2-uRcF1Y-;g(y?feq~ae?3r|v!3C$r_#yvz0X72 z3Oc#n-MXZNU3SIj$k%Ny&xIebc@x7H~mU4boW-F(&qDpKe};(AmtjR_|3_@ zIFxsHc6*)3T^I2V+_Tl`*~`yswsQH8P9}>hx3)6(Ep&q_cQ%4U0ZF*u9m(o`<5axI z?yi?ZmpI>riw)WLTlDsK2r9jw(Q-7#hE&U`MdHDTc$|b{eEh9FFAusVi`A+H6nW2t zgx9HLQ(6ZH2UoU1+r`cpa*2Re3LOwC?9$ZxF^1NXh9~3-|GxSBS>`R?2iJo|;lkL5 zBie2Mezo!}$6=;E{GTUF6m1s+_0_-ZcMMl{n>Ol)YH2a!38jVP9nKdLx5tXlSIsRKP%&P#*H~4T=8x)#%lEufdP| znWE>YFc{h3T0!79#wkZ&UuuzH50p|XN29r9Nh(!t_V5UZWIhjfWa{G}A1F3H{n*N-3D{0wZvuh z=5yHS3v^MXxleeCEUg}XjOWV|fNW0Naji(DSWLAjS0~@ESD7lgb51n)wS|}kh_TPB zz<*bZW=3DIeOtENyZr=b0pht1*TRC1ji z646dlA5yJ;PGsy&4r7y5!px@2wnw4iNSkH%2fQ-r9MbkMDHj@qJWNc?n48tWUR*Y+ ztXQ|1-;QSJgiuRN4Ri=siH83_m15JvHm5%K9*~*bI43RJK*QE@ETuo>@_a2%HIkm8+HOyR=C(cmydA$=g&P zU7wu`0u1`=L=$)WP{!by3BNRi^|JaCGl>EMj>j=8DXU_W*k|v-J^^<2Mv&}w7SHYy z0}GWXC_5Cy4v{5u=tXoumZ?S zL5!11E(L))m18L4&!#hhVy>q1fX)Y!epMzl$mS*rtQ#?beuCcg*FcndMLcp?stExc zOnsP9$7+&pCiYa4rC6spVXqZh|3*gDUsDPdrlkL)>Rs*d1jqEy0K8VHVrB-vut`*5 zr~c!LesO#{=QMTDob>aZ>aF2i2dEU8)r`W(kIrqz-RW=!LJSD)=ahIMO&4@X=uW=# zu0pP*N|&BD3m2~ZFcmWFY+*DU*NL-=LvYO@Q}A^}A7$5m73y=d#l(-{`c|d*#&|v+R&sn*^d+TK zjMIX*dWEz0vIc}3h<_sFYPmps={#LJRkOiT91<#p$y@fW-Ox0s6~uzwW# zkv*|Wd>f62NAMitfJ^A*`Xnhsh!fJFNlZNEw{tykj z`fOGRyZ^<}^t;J^$Kj)2UtHU)quFTw7ti#vWsf!4ul!z|N*Mz0lAD#Iewm)*=glzYWuKMii-QYFn3rL^2 zN>=crd%&ePxF$G;%g$BkTVW3Hg@hr^81mOSmCAY)ql3&sY~p}F~2i`qKGz3eE z5VrQw->9CZWgbg z`uzbG<6;&o?(Ak^4py;3Qjah|S1Yvcw(I#AY;TYL!bdkavWUf0&m$-trUjL`C2z~W zUU$yPY?YVZKX?X|Xpn=k4&FF}8wbBVX>hRO48GnoNbMs6us75;c?`-ymVu=X{Wjwt z{O0&Iky#9R@Y{j%ml)` z8ER$3#HG0t65w^e`OuugKTos#IMttMHlrlDtY$SOcA#C)VyxUPqln@bizEw$FGQ=z zhP)CTesOKM81xEX50_UoI^)F-clKESi<>iaL-NY6_0*Cg1-{&p?T3A}R->!;m*@&b zaUXNlwc^xPcj?$kMVjsus;RIU^_cn~_&0>3-hp>bP8(A8o28sSeOEU&9f+)YbVf27 zD{=cWX8RU;%HH#7C*4!tw4zLE|M&ImeFu^CvhCN9-qsk!X6Wkwl<7qkMU&;#8mUz$ zmb~Eg@{Q%3A^B~FZaB=jHF7{2UnPUgh{0@0+< zE%nX@wKePa3+A)2SMho-&d%>{gFqO}zBrwvNxr^Utm%E^JM%@6PX^dgf%&HB0JkjU1D1rAQ5VOwKPS4}TzG!g*BRdkzVH$E`>+f;Sw#eRme6x$Y zP)rgbe2o88eSTWP`;o|6-~o3@SGO1PXt8sd%i5+|<-2Oq8F`_uvFLMuy5jqG z7(@;`!-GkK32Y-R|6ki;T+hJ{3CE(R8tSt6+=gUpOFBeBNoBaa^c$CbedF3Y!~G;n z&yHoub`}G{>jBktIU=I74=P>hdFwLRL^Yfeh+V2_uvWL6qngfBpiqcG%>Ok+(I4@z zf3yJGP2G>4=v>JA%R&29*^h$ZLfFy z=)I1_1Gtg)=4QiFm)-7HK*mJ`xYF@sM<9kf(x|gRLPNpu`jWr*=zSx3M5|eXOBIdh zp9!;Ozk-Zt|Kl+K{?}H}W-j2kBRCwi;wnJDc}*MvlpdDYht&4=SNki%GI+eISK~9F z)o~~#LU+mst04SZE7WC$%;1Z|o;<}|r<=rG(QpAIL>nc~p#6*e`Qzgr5_%3Dl}pjg z=NP&2*iBJ!emk>t9SMEguSxjO+)vkqK{iL4KbBnJtXoRXCLERiF)HJ}c>)RQXg1I$ zF{l-Gm^M=JWfh`?VPmCSO!^hK%H^HuU@GH7oznvYa^Bh6!PzX!@nQK?0j1xZvhG&& z2xc-0%%mUQV06J&AzRyBY$>FZOB%;$zU;9%v6h4oL&Z$y0YyL{(C%UZZy~bbGMEx z^M(is-)gS2kVbdl4f-^>{qbQqV3OZC=90wxRb$dB4XA!PfP%IeO}P99Xx{uDxcxXx z;vF~TqHNHGJo2yYYN)sDY`ig*tcVN`7oVABPhzo-r7@E+DJ)hl zir~WkfR*{egKC@SqQ_owZYIrY|3t-nCW}G#8&)zQgGdo-^r zn6SZ`LM=oG{lxsJ0Bc`M!o^}xc-9q$)z(?wjIm#XpoOxe@ct0we1Rb|KE2;%y2QAB z#jT$w`BhV3k2hRuE;eLUZ_?2GqM(59c=-l<%UKamlKZ&RJ3#B;w^6Y#Pp96mU zKKQl4O&Yf&C`_w(jV``c3NHcrs*e zt4q@N2xxZ#(s`+e_^GhxhWFAvFU2-d?++GTx4*xAzpl+N)0f?8o%HSGKf!dAzSW+m z)`4cuZk zlN>52ncX=LN>R5f!Q>l^*)G!`0tNNPA^?Ic-ywuUp!-a>Y|=ru2UA5!aV zQAc4O@pL@UFh-3hBX3T8W0+j&EH$@lo|vp#4Z&M7A9-dqRo*j^{CF>rpZKpJ^B1-J zhk-mViqO%Y!)fSf7PcwN^8~wGw%u2>Un0Ce)?OOc7Prk3f5k?HP*s zQ!X1|F+6^Z`{WyCvo(TcN`8(In6UrZE z{OH4)7H`;M9@(FCMf*EM;qe?SGBV54h=81{ImxsG7lm)~K^;hDO7y~V! z6dus1K{5dpr=X(ZN6(v@UN~}t;_x91;yHqp9elKn1#;Rc|`-}c#R!wyBj&o6{Thz-l7cYciRbz8e}CT$H03_|&v zrxZ^|qtfu9EGXE>yu}+3oGLYsmIvA&9=FLygXX%sJF^NhNs6Z2Xv<1ak=y)ymOEqN z=X*v+kA^Zyd@^{0w(>(!M}^RDP+sA{UVlzB5 z8CEV*Mivkdpi!^Ln$b4t3C}R;YxwmirC6#jy_#RR`yhD9YVO7om3jBV7y6r%ge&-#)d zI&DVxQYFSPXwY>o&7N6 zo86R}PhU1(THkgaPWw#1z`#3ahoIunw2W)3mhUt&0&z- zy}w2A^j3R)kn}M#y8SQa=|3*?Cbrh?*G3AxJO}%IV#{~LuLS%NEiMSgu3KxOhe~A1 zANn1M=4#qJ51ag*DX^?ewqoVCd*M6`B6R5{a3F&^)sgXHLj%)id`tlKjeCtWVvJ*z z*;brx4~b;v_d5QuNBR&qDb0-WnVE~O{*mpnI$sbdPD+m{>@w#7%jsOT)uxFD16ty4 zf=B}Lvn%`D9OBSYN?QDXI_@t}!Jy5P{Rmkm68 zYS%BFtF7dufIqEWN=m7>BVDpuB1~<0Bp&aM?1=KZRcJDnl*#;vKF?{3t@EQmX7wOm zIN8#|tgxauw9n=3BY5>3kyzG$Qs-GXe(dp9$~J)dt5Y zLrah4GeYWr=raKOJCy?aE^WBaMX%<^mVh&y9zNNhKnfJmr$7zmvopqHZSifXCg$Jx zOABUQW4ak7EhDo5)2SAU?nD%{&avxL^eVT?QTfP1AUsQ>gw2t0nQ*)Qn|r6mr1xq5 za(UV=aZQv`u-S6B0{W~xS9de5Si+Id^MWCYh&L!lr?{wrqRJ;U_T$$xF2w}3#~g@i z-**`~xhW)=4v!a8-#fh)cYc2%iOb!@a_HXp=3#U6D?!Ky8nJ(gYtU0=Nk}}ro^>k7 z5W|=oeGIB7sxJ7!28%{B@dqTyK#P0?j>3Bbp!#Oxbt(E6HOXZ9b5J!`F(KY63=k0%Yf6Q<>jNxq-8nO+>0J<$hB#7sFu!R2j z$&evZd}~y4wFZ`MEokE}X+*s;wAg4qwW`x42-;Z{EwdujSTIrKe=*&IMQSN-#P=ay z|LARWJaswFO%vNlZ*;YQpD*S07CY+A=2TFbjBTHgvz>ahxbM7Q{=JxwZ zoQTNdDI78jw7!q|D{S#U@}zyV?}hLY$Rv%Ijym4pu{rK|-^aF%wWyS9s%#Nz)4mA4 zpa>dzfUd0Ou^QPWUQjSAOBw2UeH?flXUC_5Y9tXRX?QFdCprUQ;A2IXK z=pjnw3cv450;*5PVd6;rM(3W_F&w2{$pjJ8m#nC;{AQD@Lzz~dr*JNZ+0Jr&vP|1x z&vSmER_rF~Lrqzkb`x$SK4-wioPJq|@wR7X^Jz38FBKh~dCQThxz3L%1`l_c$3Q}h zOp&d2;A+kqGj!E?Jnl>=X&SntaDB_td63(F=)&dp|JUl=ES|1Ki)hE~#eT%q{CSoP zBE23S1q8O8jSu@(ontLA<;zx645Cy_k>$*|1UGU24rL|R^Oc51qe-mT+@L2zSUv9_ zD5n0Q!ZyohfvVI(@RP>qO*7Rkkz_T`9J;S8r`adKxo-3Ya8(s!X?eGlnO%I|5!is!A|#=^K6Va3 z)1ut6>Th0$kD>i>`sWAr6M1?(Ech7Ws3Uz=QfS$hAcYy7{9#D{kG`ZG`H)gjDMjx? z(<2Tk-#@*$T5juhtc7Mz38ZL>-l+mjBKFOp_PO(2wi;^EO0QiQS#_LPhrj1Vcpck$ z|DO6q(f?`zP+Jzhz07qT)-^?jjeVmiy138b3d5!i17KJvMCp$z#>+?@HS)6TKQC>q z;I%MdsdW~Gj!b0~#@NT_@3t;uze}#}^)L!_7dbQcUr8D1G+;!j63rXq${ETI%RFZL zi_sd2CU&;+o5>Ak?hvL!N&An^+v`7Vkpk`VQgVPv15K{^<*?_6t+TNflkUuiGUf_t z%9zA*P2btmt?dZgLVbD@3AIvf1du6opOu@1RZUnn0@Y2b#0;?&rh>Ho#E7PrsgR%w z5-ezl0P5hu-{{f>J+iAYpO#yr^4NU4Q%g4^<`VqE8oXWM6uyQzvY%9Xx;1QeGo`rlr{;g zWfm1yqy2Sxd%Q;GsJtpk=?uk)=pOQ)JV^ChkBhY08^eJ>OA_Z@4??oY(~G4v>f%W0 zBa2Bs|6o(E89o^&j_x*>kT{0S`YB@Ss@}208PMA!alIEB=MNgv!n{{5BqWp_RxS+xBel68*~Uz!h!%S`@NXEWp>5W0 zUGu}?JdUUfrWTo_oiE19SX?u`jEmOgIgcHoo%_W4Ob*doPtg{gI88@Txdr{qVoH0v%gMe1ohL=YbB}O~85TkTyZ55JUcz7KLQ9yBMkBi)sAfgT@+-ru zj3sd?(Bs%VQQt8!z%Q*yL>qR@)$*7vNKwYrR@*_np_K&#Z0FQ-Qw5}bJYNKFaAswU zZ0;YG^f4u(Cb&Bi;EngCG4i0NCX{Vwt;2$-irSB4Fy$)lYM`KwW)+@PejL+2TxyPt zPT^qhn~KwyHYq&Ukh)a(=_F7IDy>!_dfWmv+oJmGR6sfxn{T6+j10r#%ijglO+R|w z)V#IaF>IS+11kO4vugEFGgWx4hRmVwKp21s2uH>tD`@M-(Ec~X0w{vtJpSdO5M|fyH4L}Gq1y5r>Q_qIHiN}33gfgo;iQU8rWu-;{pHL~CC}xZA9XIUf8t@GEI1=>W-PVkHmXRc40k=XKfg+e&l4RnL=|79LVG1@mE(;Va`A=oTz>Y2 z6Q||DLVcy-x#hrcUP{EpJ@CoKFHL@qXjB+yK8W|kL1tmH#%FU%6&!H}u^Rf5Bg=W! ziWYKl)^nhRt<&LxMo8?~brl9V#^O$snkY{CbpvFwNM_1lvD&3D`@+4}Y3RMlu;t62 zD%3OoO#Yc(?0=fwC|53cpCP%EBSq~K9Bk&1U!_gjzOZ6zDlF^hfBclybKaIX@?rLn zt(4qi)Gz-?j_>?=QtP1iPzj;}dD2kWm+nZ+Hx$1EU|_=QV21^e@N(X~!`i00uboK3 z{cLSbIU{A(yfo5>G6e3x8Q1;5)Xop8zv=n1m3BKy3;>)yilwVnz-ImZHs2?ir+V?b zezBJ>W27i^s-igTxoB{hR~9~kR-c3QTvL4s^T!nSefL`CqR%3p`a8IoqC|iGsMe}i za8x}Swy7pa*T)b6!K;42|P*O?749v)z`dKS0V|ib1;EZTY&Z)UzK{gV^ z9`2YQLP4AC0Arx2*+gH!lAre?s{kb6@g z5s)-~H$Lm9Cz}#9Gn0fy8FPNfMJXV)5nsqR5;RD_`t?X*PtfTZz`?L|Bz?G4Fs{1? z3EWyHgTn-S9T2p*DPz1)Z&BJ(s~n-gC4#eEqVv(rm!^~(0G~5=Yj46F6{|dS#F!ozAzyEq_)nLHlcBgmSy_VurCP*ytXZoCiH4yO1(}t z#0Xw*NcidUsnXv`Y-RpS6yrp`T1E_l+w*Fg=FCS-Ov3f0M(iH+^8EmE6y z*F{6v+elc?9h)1Qb?b(Ebl769OV=h9k#iScZVwdamhBrdX;UqG`HKkCju39BfjQ=u z-vS_aa+1dTwVlL%jQoL0h&zAAe|8;P#H!~DGHXiQdRM;4_+lVGx-2z~YPX zX#tb1QS9sMYq)%T-X6FrY6hO*azs)sqm!_vM?=2U%lmXG)t2*a0z_%D z{_8vfpqh|oCK0rUv*oghkkzU)b^Eigte#|QYkH89J{jBFLc||N>~(9&1{p+$Y}m0* ze2UU9K6?m9(31Y$bvgUgBmqWN8fy<=Gij4=)L+lzdzD@tjKB23;|61-CD#GLko3Xh zgZJ!jtsml6QTp_=7&ru}*%Vc@;Gk73f`0mGe?BK?P)C#CkTJv`a~OB9@LU#JsS#eE ztDWsG>8MH?)3q_AOVcAaD}|a`-=48UpeOx_4>$Cp*zD5zg73D&fxs7X|u~f+d+TE)}p3Y0sTgoUg~glWT1U>*<^lCT$QU& zpw6RU9F2WRAN9Sqn8j)dGFU@<`vZP%3<}qYS0F8tU^(RKh4CmB$M*pAKC-uRL;_vC zq#fu4IKj_FUxroHDN7{{G2WA(1-$*bQ=-w(Sr231BFj>K1_+9bLVaF?GdH)5{$Os@ z%`is|sB~Wi6cSCE8$|kH59@O)BZ2a3QY#TLs?y4S;7TqP_2TaFy*JqC;^?E1zfc?W zUzDaW?HtxxPP9iY@`@u?Iw?wSd>8LmEO*iQ+T#AATh?8pTj7s%nLe-OHqzPl7|}Et znV3t3%hbV9TgS)~h}7(Xw=ei8b_KT1s%W74gM6Qo&2$6Nl&xlT=r|QUw^#95mtUz$ zg~LxeD*fozf`wYuK@g@^1D)A3IzO zM#g`#*Y+!XS7;DUg9i>^U;{pkF*f*OeZ{~ zS9w}Z7Wfi1x`w0K3}$qWer=?4An2z%MfIbCP;mQoJtyw?JEUi(y3Q! zil8X9nlr0zc@nLh48+r`1#xK3`HzOrX}p7Ml%Xf@7caTpJ4fKN!N2Q^?>PQJeJtMM zjZZp<(UvgPevs)C#lAHZYJ}>tzZh;{)NKyR#Df-_ytK9`h3hkgj67NYxe6UF<)j95 zilrwmpbaiBaLkX4qJ2nE)_?-iLA~CE(R47gJUNUaU>w!Xsrf$k``bxm7|5^ChyqEc z>n7x)dLeQ?H`etO4yxNG(ViL=gT&q+tgxj3Q@t~{vFsgg$zf$U97Tl7;Z`B+=_e7{ z4yxkbpUiP6P9;iVO5?;+J%Cze?Z&ToI&*b6TlM(;IZ)4t`$$N3wT1tG%d=#uN=g0c z)Qa=TnWW9yu+NT1L%JzurmRMuZMC-t;NHtmNI%b&nXS4q-H?ijm);sJ)2@Oi;&nwF zWPSL9DTB+6AyGTjZ@FCf<0E;3SnuB#h%0x=?56Qz2>}Wi)CKD&RHbzf67nhV|1vq1 zfUo%9S}ia4De}-}08V|XT(~ucVp}0RJ~Ou^$dUpD&y0C-r*l9WikfxkOaR33GSZ9?i^{Hf8qYcn9WR zwRU?T=NNe`JGCTIY*5tup2l@*1=K^71;%8dd90PJS=Ek!boBi>oDl};J5O!K!Ii{K z=UuZ>V7a)7+`T$o)m!aROV_N8`JVJGM?5?k^n<{lmQ-kR-r^*)70U_GLxx94K!=jm z?z4Zusp@FS18UhDWMPl_vVAIPvT=T|mTmv%zi&fNd_X>yBm47$$80fHpU>z-ZIy5_ zWH;v5)ulLSzOXupUn@47zDE5hH0-VSZy|RAlTocAzH<%n{NEFqm&1+Cl$5RQYu7@f8Unlqq*Nx0UTmBav_U5t1!A;))By@`P4Gcv*Ub z$^K7Lhnotqib-s_r{b-gjed>|cxV)5{@LSjh9I+)#<+)ka*vZ>ynOyjab>@{kS2;@ z?DBcP06t2dq(&F5e5PNO8gb7^MiGsraxqn(%I<9{Til%Y9jnb!L*S{;J*BSs?#V{t zDt8(fbUNeno#b;K)o7B~LZT<}kqraI`i!5sIFPW^2SGp?Wsii>4@G$%~e!^0y-WVXuCcH}yo zIl`MW5*Ze2rwK52LcXu+#^+Lrq)#8qTg{()=9ls__+@*!_7gWJbXurYjBRdPdQYZl zx=|kgAQDUO{l8eVSv{v#Ul<4~{+MLms#gpOG{Fmg4ss&VXv!!m_C`^emSEHNF^ue15vtvL~IjpGQ3U4nD zdj?avWG`ZM5VTU9f2q$58CeD0Zz!1be)}C{x^mIZ#BPIuX=Md^ha6bFdO{Hr z%>E1Yo-b2<7W|;}i8~R~*|NM&y9=^N4crdvZymGu;*F@I43@Y~#S;qC(6sOq*&@QP zZVZ9dOcJ0rdYiI|y@$~^3vsK(t|PmccOqtbl4`?cI^x(22nX8@ zj+acFHj80HfZKXx29!aIWEylplFmW`j#ej*)s5@}7QmoCDe5hw`7zdJLw-c3aN#7s ziB*SeyT|zP1JS(c6?=p{`tAq0*$Npw#KVw&th3F0J8?FQSuIupwTCho^2kTQMaLix z6+yFD5m5e6*VJV#>rx~g2s$B+n-2D!LD-F+ThPvUZ2VJk+Mkr}dD#tT(fM5+`{a0Z z?u*XovHt`*{}1+`a_^G4&P1M>{QYc_P8;rG_xMntT3S^$K2q2z#w3BmYmI=1(?y8^LPDzr3^9)A;>iU zQGQDy!Pe30twMnU--~Pf7!oI&!Y=VzyTu*TKj_Wyky6sdrQ_{XX(iAHvwq!EPu~i- zx#6S`YmyPWjc9Ib%W((*Rr*dHNslCJYi|UxtjN2tCDC-iboQ)fP`0nsmT<#m7Rgdm zp2Lq>%2+cs-tYPUkoVS6Rd8Rss31rxUDAzG0@5k1fQSePo9+(j4v}u8Q;=?uO?QWc zAl=>FdDr&!{hj-rd+r$bj_>?&$GBtg4-Q;=ueIiyYp!R`=b6(EyS)d_z*T3x9bU$r;W0`j$=!$w{>7%1=hp2?BdU$fB3rsPv& z6ZgH~GWy9?Y4qLZSzp{4&wHkzn}*w*v=>G#@IUQF8787^-t7K?rLO@j-4RE-_b&Vo zEG-R#r76w-N3l~7c`j`HhMDOrxM1>Meb-`eTf)t<^q>Jflr^ zmC~$hzfjWPHF8g;tL)IxTi5eaomsvgrt_M}RUr7@`aE?;&WHQKBXQ36-eXs-Kb21@ zUV=8u^=y}sJs_(isdJ*iy>3liOOc#N?>32gqWARMGf4j>Q2t01>#K*(&CR9TO0uX| zQ#2B+sGAa)ul9RS1Cavlc(6V<`aHyN5ClnB4Kl?9-}G_wu>oKcYasAMOTg%og)rXo zn9U_n{T6a?m=HHK4J9`P#yj1k+@9_Nye*;vQv@@EiG0&2)Ter~ z`X8*3_ukL~5kFn053!49NDbI0?aBoij9P~SD5Hk-R!8b9n1DV;@@8N* zdliXXyZ7P{P;{iyT0VywUh;9%0?DS*CopcEe*yI=;7e0G%TPj!Vsr{3ob$K*5Ftu6 zZTX#mv8QyHILnI$HKbl9j`wQA1e7uz^$x%1;(+&y>b+w5hxe-tqp&lItg(+o8w!GS11Sq^3 zb9(=;2&Us{ms6{K3fXoh>Y)K5far5@a)N7AMR0i90TR+|E=%Gh!p>3NfR?Q-24l5R zn#Vj@UE1GIOO1%2xK@8dj<}r}u$zws5CB{A zKs5+dpfb;^#NI`ecQ^)Cc2Tr&r8|pBJ)5wpRA`ccXwS62|R zlcYCLqEvO=T|8tQFYZV*uKLEaGOX3 zrUC)*sM8SLLHC7SSQm0oC5o zK%Ep~&kHF1|6k*oQ=-8%0m@;T00vKVY(IzrO#r23R2}61zU~Iz84y``Zikwr?+Elh z%^V3f2!WsY?`i@Vz%&7RNm|!({eVZz@5F1x{9pKa;BEgOiXy;Fr}g;`(5nEHVXmG% zm;~$|%McqV^ZW1aRqqub$j0#c{#1Aj2*^sIjJ}lrJA^!h!L)~-nMci{fa_*fBV7*| z>3?4%1-4hV$Vr(`!Cn_sRM zb7uglym$dabdM=0^ERpBH~;@ivnn6LnePQ6GA@s3TDYuK$p!eFNDtTdsF`V%G$hM8 z!8!gYPN6bfe_)~TgcsFi;eV(VNw^=%$u?sl=kmUI`ZAsTNU1R3+V$RlVnoL&GIU?#ueO7Qmby=IcbT;GO$oB!v()kralzZPvY@l(KU4Ozvg>8;fXWxL&E>J|Y z20R2OCzlL>5Hcu~)2PqRlp1wC33)2;Q6V*^K&dU@a2X~$`@?KbeYlZ%GlavO`I}*b zt8^*zi6&-!K7LDu|7)k4?Z*P1{i?!a)B}L}KaF)z3?TuJT`X3enR)!M^?RBrOKY+~ zlnHN`450^krMUOj@5rMCII^AT@SJe6NpDPyfAki}y+uo!!fq-}DL5(Ns<&zZ@dzPfGh-*c!BKxzq`BRs5J38c6b{>G%ItSg6PG>tro#;e9nN4?zcy@f}&tpgn zzrF$o7WcKm6=e&T7M>QaOAh)cr}fr04V4I7tj{L|o4x4G4X}8D0Nyf{_g%FCqSJ*d zCCdp58F^#iXmyT5*%u@OcqkQ2z3%QQ=ewOYjD=KT;XTV+tV5MzD#4g=iqhW|Ez7VW zwBRiPWktNsp&Mr*T&nA?`Sb1dp#axdqvYX+Y;!N{E;MMK5&Ux(io)(fOm(ihP{e8T zwRegm3P4N_oAz}f=~M|hRk0?gfsfKX3z%jQ)~BxSCqB$JY8B2L`D3}>9k%Pbr{xB! zuX1cl0OkdJNPlIJ{YoM~QjmQv!eF|ObUpU%`-wm~g+kB00I;^xINd6l45%*|P*faM z#4TzA+8M*WUwUA*ouw{dS-ci0@>bAY*jn`VVo9Ucy8PsHbUyD?dQXum=wU7+Ab|hp z>slh9j^>57TGhj;I6BVUobd~wU?6GMmnI1cyuc|%1QtEv!yeuO)7W?c)4u69iY49G zZsFp0`Q4uU6(nnRrmU(gCGvh{m1&PL6>2r8;mg&Q{D2(Fw=sOrV#Il5{RybI^yO&uX zByj6LO%pl?)!?}w^WHy-{*FFBb-ESUKL^M=LB|oB0<)l|N@wl+>xPeD!F!%`ipJdQZ=nmSeIvIW9$N2aF2vP2@sM;=R`j z3QGczyfi?^NJc|zQ^BD_{uWp4XVn0sR(<<;xRgB zc$fDE&t}i&%^TFWWc+k)uc!nrwZ~e&FsOe=Zhf07ev&E0u(eL_y8#qumw*JjtdLRc zOK=~{y{FadSy{(^Vj^(V#u3kpwU&Uw55Gz^Pm@7&)#VrVX{2rx^?cXexAsI*j zRcg6D24d#zE5n%_q+;Y=WrbQ|=|2X;DrwrFr6nbpB~s{w>6?w4b^E%lC!0WMslyj& zXDqCzg8zM(oNdx@-dvQ6)M3JM3! z%vltnOxW1iFGcGLkp@B}L1_GliJ05IZ#@jY6n$})%(4_(AFIDqt5JFkfkw5A>~XguI;u%*rkM~bp+UpQ>pmTn{qw!7Ln>Oe^L z@|t>>x#B~jsmX9Nmc%f6V87t}Je8h~VzX0@X1+1hh>cC!^^Bzc7hg+TucAKu_q6lOCx!A5@ zN~P|X1@3krw%eopva84r{Jc49GQa;GDSvOd-CtQ&1vPH{L){ctX_}dTbXn=zhXwf^ zO%bM3AXU0{)}`6*tERtSIQC#yulLf5j|qp7;dyex2T=zu>t`0B>4o#1!W1H3^#<~_lQ@jth7fbfeia#O1T@Mo zSOkm;~r4cMYUq37CFm*c7mz;USr- zk{_#x`3-g`Ny%rdF0Gd{Y9hKSpS9i;7mvurL|!p6HIb$K_}8W|i6k`jVYLyRHXPU; z6_8$gz_MxG7mWkd!y^dELaRs4+tCP^#?&6fSlN7p55pwPsvHya^jIlTeF(Z_ID1Jc zSy)`ih@vomllC9N`cR7;q*=TW9-4s*$4aHKDd)oaO=VLY;VTu_JMV(@0IJ**s$URf z2|ff-F9eXONwr~5=t)jUPT-Bc95|j?pOZP8blr7KNoX+iG%8A2&db3}q{rCn>XT78 zKUlbHBgnk4{5mh>^D-F$K2_wMH1ffM5GF~;$z=Ir%WPeBjaw zA0H6LA;dQELa-^|jOOQm%QP#5pg-X=Q8Yb0C5`(k>$?ZkNRP|E_Q<_1jR{eJEdElB zEv0+j`$Q?NSffmDTiHLOwCMU}i$fRG;t8UKYgWK)Pic&~zN?V*rn#D#Yo!C#M=6<9#t-!P!Kd_<<;F)&=c}wn@d#3vG-HGq-KzgnZp03G0zr!{+q+#f05)(TX?$xGGgWdxvN;vExd6BuC>J+cKxFzfL{>L+XZbXg) z^Wv?cbxfZN)2JZXSnzkHZ28|}kGhFIt%;Al&x)wjN6~-&0duph4eKk5#?!+`Ij`Vp zFmn;Gt!7(Of(ft)+@F?t-UUt@4KB`w5;J`!$;A+VFqmZX`T>8MB0U`Ti^p)CwAnUa zHqlXn0s@>UT4i;0Go(V$(9k}AceX`ecWP)cbt;RB$H57$J9032&dS`!3HeAUi9uG# zuA8E$4-LH|5pu$GueEC_qn1h*G_<_cU^lnY@6UZBowR!0J4^n4?tP=si#nPP~i#A(0tTjOlcH% z&mJ|~-IG1woLtMw9KKA6sArxCzkUsgit+elsMk^L>-xYYO|zKX23l^Ku zn8qJXG2vI`M`VnGtcpYAbI1OvksBC-U&)|0Ut*d{*4524&TH=I zpP9(0q%wxJxIbzbe2`Y)|D7;y!(I2Ja@jU3Ji37G^PT3bmM~$Q_3hAg@}X^U+*h-v z$0z4occ4Rf{Jrf!b^C12=$*UC=Jj(1m11=anmVpZ;dW9={6jG^k+8)Z%9BS0lvo`v z?q`U^*v$*qPMp6tw%6Wm{+X-rpEyf7Wke(W3h)o83N+8SiPoHw+B0fh^t?>Y3vSg z<^kgpQhw}QN}nap$!+apL8bIwRjHzzo?KPPotNu;^)@`a|6`7Ls+;ubO|)r@gQZI@1M{C<(wICRoksb%^h8~w zUpYm_2)+FkRM`DS819z&=b1Vi%i`6y^G(j_ih^;=X@_Kgk57Lrbi=A=y;nkcad9zE zM*f#D86?ryOTlQubR_TkY8%#x=4frOq&Fy4$oYL>2$d5)(+BCmn(g~*E%fbi`P-y` z^xvkV%|H$p6z40?gawNQ{>nNuPGGOLJIug#=f1tj+?rEraTsk6%ttubRLm*08YGjh zSqrmjO3@V_6ucLZ3?cRxxI9{HFVo{G^%VB`?DKB3hyHidq#=f@S}C(yJx?}p%RrKs zV(r9aXSNb8>IrK`dB6laJ*0)pY^>0{`{-B1WrStsda@h*l+%pLHH>8I=Z6|>9BfS2Wj{VK`_7e~t$Fd> zZDBhG)20imR@;?#qM68%RI&r^_wLfqw0A!#l`<=UzEehhN`<*^fCydLL*}PkvI?a! zWi-K1+Y-$PTW1b~-tX)KtXj3ckGIEkmNtf8zYzqB_j@Ojz1e`w6`gYP*J9`C_Q%sn zBL)p9Q}4Z%CDf-VS%;DKds3x&Ah-qdD|jS!)S*sn_&?M3PliVsC!TH!Zx-l`WN%!} zxkj*0pq%gNY-ULCT&$;Uj8@R2;xpy0u?$8aj~`WKp%LWQIEj|Vpigr+?(-R}{(N*p zxhgkB5{w}21^W>Y^8&4cs>@aWvu@)s$CyI2|L;0lVWn$tGykG{+O>fW!I2Bij_{gB zh}YTX;+vEHcl9IS;VeUr4*&fx*e}q)rDS-Bu>1F4yjKtyCLT>FE`m7xL0k7`_A7XB zpMHM3`t_f0A>E9CP|aovPd|k4pYI{zWrITg@2@Xd;ZUJ#r=eX;dVWP+L*;tHbj|1x zVFxlfa0UMP5FDI^&fLHhv5~(cQh*l9EGRGhZEOFr5Dy72pCYXq#?wyrHm+0jNwF!K zX7uSFn<@iAf0x2d&Wkv+@$5m@ze8dVfgu(v{xL8S_%&LQma+QA!+3-K(o;e;haI3g zuCv`Wkh%G<4eG+r5OS8;8b3vecmVrBAOy<*w`Tn|?$1Xwmmt3b5?YQ~a~};SvQsHt zrIWx2NnE$Rs*!*GKEkU6#aeH4oNVFZ?~o$!Pr(pw`2Q|bJy^%Yac;7T5F#j+H{ zOrpUEBiUNKjDJ`DfD`QH)zm|hw7)}2i+~|~2jTxtDn9N3BINk0Q!kdSZA{O2vWy%@ z+pmb6KRi47?<4|YlV~6KX7YCunA!*+28?gx)%fQlnyA1+mdwPs=q2bRx%ll+T3~DY zSxlWU8cF;$s7AWxPz5blujRi(K0q-BLma67YhcIN>Dp$R^G^Njh7&I6%=~A1z@AR^ z)`#u>PT~a{m_*_P@5|7?lYkF-upITkmM2H%&qpk%fQ7t@se5n5#9^*D7$Nvw4rY-_ z9;=1_F7-ID$SpGrYq!5cQow~iSjHAY`**W7;c?A>ZWD*AcA`VVzZrCS$a)b$J$3{V z-~OEhfDu9!aQOYR|8A~`7YKi`wV$lpz5a9bZi2u5`>{#ip554?53FH^>Au{m&i^(j1KEg{2cDPmc-ZYef*$axDMR0);xGb(>DyaUR zD=pZ$DiLfx{5zxp31=Bwk9^vJT@~)J##7e-Bh{IgaFP8M04bE`ls_fX9?_Ya~ z2a}N7AxV_{I|(>RFPqn1yvZZ9e?H=X5iI0wuSOnsEDBX6YOkjF(dS0px6d zZ`OFazDDP^JhPb!oc-n_Zliy!K?Ht|3hb3t^>Z^irh9iLs;8wNY;4ecRFMmk!r zEWC2#u_9}PH1PGz>(2>ZpGzflkxO-k5ZPRxS(pQ2v20jKJBXy+mb9ckul-CT7rZ)? z2u+36UqM%D9q*05TiG-ni@44cOVmw-?8fE$YC%7xiTvp%I3!6l(T4?~> ze>#k`OmCViN3@3Vc52`oBu&V8Dg#mIa)Y`*USLvBJ>ie7#Q%FRU^ez}>NZ*6-~9># zX0BNCx%2N1i(tdQ0(xc`mUH!azQpqCIyyRUnwJR&HeEg|`JoeGMn!lHEoiSl+BBxr zoq||QQ7EqUSG%mD>SkodRIB7lW9g%ziOm#2j4zgg^XWY?&Cw*p7ve&RV`giB*iKm# zZ6v*w=1fRv$EeLREG*-UTTk^QqwWk98vt>d(KySE{ha_AtI88BiD2FBSmuqX#)hpn z^tgbbXdr2u$8KPKyQM@T?1BrTPw#%EH7F=XfyF-w`6vZ|zbSsw6Wv?#$rJP`z#_r+ z;Ve+r5gAO)FXHzpO7-A0WUW8Jp4%LIY(VZw0=q|Bl6lGS%xT-s{Ob;ppFH6Lg4lJ! z-|G)GmipL4(Y{drFm}-IP9oZD6UF*EaJ$d39Y-K=>by#L)f1&OrE7nGCOFgJM(n6- zNwK$~L^IbIXYSJodg{tgJIf5T@lqE_P?R5aoeJ1SQgy%2;1NAu6}#G*#QM6o*ypjQ zeq%WIWuB0IMihk4d_}>{;X}zq`*JtYg$DpDFnxoFO2arQ;IQ?f{%Xo>qCpQyjmxrd zjc2D}DX+l*2`%QBcn>bkxw?u)uT)Ah6BGQt?u_#K061XluTB%qx zX;Ef3*Ao*{IxACcESb5bTn*jF)(VL%)8_J38VHyD(uSGLODbBfFJkS7iSPyCAqLL1 zGw`?ZzRjPnF%A|qsj#i+!O?@?(+HK?X+*0&UC*LvEn;ny5%3N;9+Kz8RJ|N=Nqt5I z&zqJX#3VtD8O6&XT5c#|?H7XlHjV6}E-1{ys)81FHsbxgkfGq^B%%`8(T4WAtFeD74R)%&tlG9rRui0 zyv&l72s*D`r~97=PW!Z;zVi;&ic>K%`^rGbg6yXCc`Ne_uOkl1`2NDHR(Am}qp{La z0mb?_1o#B6c4EqeU(~nM2@%hz)KLV__h}Y7_l~R2`b+?TmwDiHUFUmf*(*UY- zYXhN79l>xdE!CdaT*c=UJb*3$;qvl`7d=!`e0E7-F$Iz#l6wkC{ziicwRSIi6d_TwbnCTT##7 zvm4M>Tpwl0Z0-CG%#`AlMJqy8FOz&c+e6mz0)Kn6F`iSUH$Fud-~Yaf zdnp`pXv!`8iezV@S`dRcF3US-tiv2D zio-PxfojKjJysHD2j!g&(FDuokqoVRZ%uI@KJ%|H;=Wa=F^tOqm6fjdBzJY( z70s4Sc-J8LxO=iz2A|~za={*u=<~4Lt9Pc<-7IVKhux$f@|5Ka_L;(hT2D}L-v1bh z)Shm%HL}|oe%KX8@+w+IvkWm4(2z~RmvuF3=@<~yN&i@L+}yx z!Hi<2E?4RgHVxl=7@AixXQZF5iE@J{vl4mpuzVY15NDgc}!%(dqkzP+ncHT=Zj-=HBb|iy<{{L zWY{y~2`u()765K5zKg)H%-5$#RbY{pKcu%5&xS*4Aer!24hEOUeFMw3gcFX<8ED`5 zW&;=QL$T0jq)dtJF&?*#2yF4yPg13FX+jOy966!nR%JO7Nn8;X4y+pW0U&%?2sfNO z;s3W5K+u(B%9L@UH{nN=#En`sU3UaqX7BS`?K5-xM$=5gpW3XDQK|`e!l6tgkNI*5 z0%D`kDTkc^Wl}zdHKenB6I7tw6xsd_qoYvETV%kZj)WEN3udCbaF*)cTC~CZDtv>05TIPD!dh29K z;rbJfBmhA`ghKDG&}k*+y)=0&TwIf|H!**L!8Tm~&M$q0{(822gKiFao8iO6P*$y0rA?4?R?_4YM?SWdl6kUB;6pqjuB z3TS2}=2jaB612T~DFlF*K!z!!Zp`}MwVcW&YG1q?Txf~plY;fj&bCH-bRY4cK+&m@o{Vz3 z8c`M6WyD}Pj479EZjToibr$`X7nU#-ODETwCin2KxQQUhz5-* zQ0@Ta!{3u-Q?%-z*-jc7Nrq z_~J@|1_iJDT^xg*+b!7!u9%3tj}Ge7B%dc{nUYMIbj~E<8>unX7|?6(N_c*)qIV>G zsl)O-s@)G+?50^jgg2ZcWFD@;DUW6H2C-;!B5PDw3xVBw2qlQR2*Y;1z@D4}uYifs=U%C#fmeT@mfuI1pCiNuX|Pm} zJ>Fy?dsG~$aAnoBXBx%GQ1HTQmpR>f=3NN_vRF%cAZkmnJ=Osl?M0(Nkx^TL%3n-+ zo(3#45dIGC}82*f; z_fthHt5-|#>Qt=HVK)NsIj5^Em0Bw;RCNU(BKL8yvBh)iNk(0o5kWtlS%LC^(a9!n zrU{Up9voR|;CfSPp+%G+v(_H7FHhmXI#_Z_<{l;vpGq4+sinM93_&F#>j@b-c3e0M zG($#3J=#eJF_xQj^C)rVY%Rsku#}C*uBVMf*ISy-uImU~e>xZzvX6rdeDjw%;}G;3 z+vV;b=Qi6L3Z1lbjt`|ysK5oS>HG8BpDS7dn3+04?4u+_7>X)q@&=fhDg0_gx3mE0 zm;oBpVDwlEdaMLsBL?HLhN;(lTAZphgFV1|X;cuV{p6BF+s9xpiT7P>!@~>;wJ%X| znF1CTv_TS=tLu%-wKkg{Dn6?I*DE4F)mqB<~1O)zh%bj@@YKpb$SmvD9`t=QU z4vRn@`ga}C!q$dIJ zMl&}8dyqD0q0PSbO?#Ud!}^02j<))e#S%$4%n(n&FBxe{Y8J0sxQbl3zBm&BI>zH+ zsGd}SmumVuO8xGLSGN@b%vH-vrDoR-c23*Or&howe>E!kKXIyacU>8XmYQYN%?v0$ zvN{_movktoH$DE;;L@GQoW!@S#BL)T&w*5+Qf#+nqJjX~EZo~J$<#aF1BEpK*pXK1 zO~suFTp$yYQ2+KZTlFgtVh)3TwgQ@s0b-lJMCuNcF>BI-4d10J2y`)-eCvp>zNRtwjl|x?~2{ z66kwB>4}il*@QO~6jr6hb5_~9WIPr*(@9nrg!b<%D_naG!ZMJ-uzwLVV6d!=$ zo__mA3IIM_dVXp+MF4@BJ$D=;WW@xSAOVFfGAzKcjs^hIEJD}xO)Q9Dn(Rp*1IP^d z0kBZ`<{n)0O??PFNQg$gK)LW~?ngvB_*nDlZ$L-;n+|}DzmXsB0vPif&m<8_JPZ$Bje{ zR|3H3ZKWBK{{NE0uoeM8yxU8702)V$9P_LLq;WwWHhOfGfF2_vWYC(^qNKl+v&hUi z{ts;1^`w+2)u*WD=9QUrvoyd&L%;Vl-oV!3wngSgB!V=>JAkXdd?!d=eQcj~Nr3wcHjN9p9dplf<|1;P#2LiKp!6g{j6S~lG8wKk5(b6p=zM9@oDwTkzo|!B-umr%T-W zPsPm%VL2V%-aAAPoPeyFmpeZ1><{^7wNgQxN;Jo}vjEdMCkp1XX~=1EG;j+0c7ME% z%2-jnUOom|p5smSe%0|S@)(C9o+3}FwHw%6c5V}@-EVl7u}Os-3`j?ZQ)cN%#DsZO zKC-b4561k1bWQ`0Q7ttSV?We@RbQ=zO-8mylr=V+a4Zy#vj8%cQvGl@5f27SIpap0 z{Qh$)fu7Sp{;0Z+ZELfpM-7qzA@Gf1mT4IqDV-Dsj^703ppa*z*3Zv50NgDY-Ud}L zcdh*Z+-8qNPL5f8KoYM8N#mub^XWzCc6VP!{!8O5rBI~SVrsAt+;_aF`GiJo;4?M9|AXoYw1$HOk zSgz2h!$3pCkLGV+2%;v;sQQ}act{W-ID8!=bRY>j;tQT5Aca}9Uat%_R~^k$lzMCp zsvQfpn#e#>;F^A0ZFqtELF!9K13!D zi&9KlcmCvGXXwG_xjUGwzD0$abVT#5FM_-+VqaXQTSpKfuQ6sLz{FDU`K^>obi~j@ zL)rmmI1F{RUFR-EM46xjIr2e4{PIBc0%hj!GI4KHkZ9Kvt!8WSrlA&!>q*mf;0_xg z-$_6Kxo@8$SeCCrt{Fm{xmQ@}%`hRPSoAbIj68fIiThA=wpP=b#EmU`w>_3wJs@bc zPwyZA>*8p;q=DV)i75OX?7F*Kpq(P<&Y(*UH>qXelN_ zYo0!+rPeBs7p3R)f7P)ia%mn1&LUHPy1weD9ly;6aJ7j~QPL+<#kiFtM4 zK|x5Y{zntryB*a+%^K`|`9%Fo$oO0XEI!v0Tkh>rF!EreSSW$x zHonJHDO@xa_2GDpt)$NDU*RArs^xKM04n>`CTom`snnZ1W~pt@?Q+I^inwBt%ek%Q z+N*#pPKD7R9Y;$V;`CY3^f!}CZcK&T7ouWfzi0O58iJ1r?pnFcnp*muD{QvMnC11x zXFc!SE{ChuU2`vYnj)xOf9?BcF~$Op$G6(+H)xMNKUR=sz41*s2hvK9s=;&A^ zXXdl(JDfTELxH-EOz3`GYh$t`?TQ!?0_f9F-XvBl%^hLu2XbmZnv1G={L>P9@t$jU zetpIOph&L!GvYb(*{Qy?7kd7EAgkhs@znReKnV@B%{tAkzP;W0&7hRwn-ahLVhzx1 z$K0-q%A##Exywo%t1O+0B_AUb*A#2i`IU?nw)o~LD!Osa5Dw5+fzXA1f;Sff6sf@N zbfAI6RzO%_%M6B4a}aCeL4f~zMz7xU!@AumO0laG{Ogsf^uiHHl~otez_nSKVC$O~ z0?ifVRZ1+?TE_U+N*}Q_f-9k;5hz!UW=LFI#%bAIXS(LR-IypQ4NDW)v~N*{jOz`g zN{nkZlmZQ1e}}%rtH~%@r+RbMRSv5L@m%8XNW@oSH`I4TeA*8*3pI!*D~wcLuGm6# zmL)?HUZSiIq@5E|cG8lGZF7?a25%l+v4QNfH>uC)$=zpwVsd?mu6iX8Sn04T~g zwRMFmW|Rp?{n9M%RVtv8Z*;qGKQ^?pnAg1Q+UNttCqOe+pf`@SB)isOSB-@CQ~QRA zYnJe&IM_1iss!BhtMmQ&@HEdm)xgB5)o`Dp05=?J`t?FZ$PKw+zLab$*$k zBa$$KE2to>-5<}KAA<7>T?Z1-+Kk8Z)tmG)L3LjQYL3(O53zea%eeK}ERPVFF7@-i zDds6v;6JJ#$1u7-@2|goOPu2#PR@(ZnN|?k;JG6)v&%#KLs%&*-{sZ9v65E$V7kAL zuPQ4jR6a%DJ;H^vDqPK_7{SfaDV*AAGr_d>&R#AB!UJ!UO#clLZ~06wNtzDUx^LURzwQB^jTe zO$RWj6WUZ+xe5@gaxqb(;@&_2qsJ6FNk|8 zba`VdnHh{I6)G+!x_*-W`mt>GyEdL5_yCyBwi*&)kt zmjrjqQMh(N2il^J&K6>#4P2gmj z_TaQs%h+*<9Jh}GI91nY9n-th%K%5jmypnzyM7jod`B^{#`=yTVT12~N@CxrRwy$A zarZ}2H7?t0axt?s-ciG=si96zj{t`%n^{eJx}=E@kDs&UELdKsWvJ1exvlROly0a{ zji%2vlx=pA&tjXOo)P1cgq+jA{Sl(|?URA5)4lsjcLI){-{ZFYK_L!!xhSFjc%AE$ z5qVHbpISaqqul}@6SHL%S0ShWEShO>%*Y#GH(Sj$#jW|`-SnMrf=?Xj<3t>wX^

S8bWGZOlT{EX|jZ=?3N^&1rX5GVplY}YVMPxn!|o{Vfpy> zxC)VebjpoK+>=gp@?r$9@Hp106P5elDr~0RnC)F%1%;=~P4||$p>um7#F=w+1BW1_ zvFQ=^DYB@4;l3n3>bZ({Q))v!Wxr=$UGSb5!Ud}I=*s;?} zZj73`rJ*4*A>TLC+(E`izNyBd5*YCBROd%}IdWoa{Rz8+n@HY8OZ^)c7dhzXSKTw52$|Nvnq%(KT^xi_zi|bkH)|?!K>DA!a4AYo=KeUzsr-aM>Fofy#RA+oJlNwio6c@YBRCm|M zNq$&9yBxn$JAa^HbhtT|S3gb)2@7MG*z#(pGYRtI9fjO+KY5Z08Sx*N07AW1de_2dD9a=t;bPJqg(huHPB3Q{6VEbWnaelj*#i_EsnBTAmC8#55c<|jIL$mf%he?8t%DR!AtA#}fudQU@`uiT;v75^t zKNAX8p~s{_XauYoB8_g(gQI7yD=3$oem_^TYr0q);OMMwCp9(MCIfMO zUs|o99)Q91^xU@OcExj|_05R}rygZxkK5vqpgrT{OcCS+!_-sy$bIe!JA+8w(Ty%GiEaLyL zWXAN}d27cv)1STE7%m}KgPQrfI_@tO3<`GvLCu-xhypsD==JI)WMf6D%cCmKKyDl7 znVf*!Dh*Q>LTgCEE7f_d8U}PMZgZxj_9qQUh*9ycg zYkr$qgABpUdGthUWXXxS@{}dr8zRk~IUc)<7n+s4_sV?~KVvv@uz#kyUzyk!8^_Hx zFw+?)<@kq_y#C~wwl_Qc%>v?93eB`bV-6_0bm<+EAWiPIh?6|^FchEx8EKref3!%v}dQX+a7&wVQ#XXHpOo=IHzh@ zj<06q-Ro?3Z!-14pe0)-Zi!k|{NGxDC!ZQq`fU%(4PLM1S#$?B`4%M$;zzNh$Pk;& zVN;WaW?qWuK3Qa0$KEn{CiKhgwk1QN*Ha=Gw?&J9h2c=+`16{~uDOv)g?@*_Gc+FK z3+pC^rubjy{M?d)l~-k271-cW4Z7HxqP>4)znPP!yOFDaPw?j1C6pPG@o_jKf2O4H z)q6UjPp!T*X5};5Rt-@EJ~Y(wjh_wVKX@>j!Kd6L?NszQ-p>i&HM>4UqT}@+yW)NG zx-><=p)h}-)Vc>->6a>t6zit(@iT?`YBj}LWC%O?oPRcsGR_$yd9PE z)wr^oioqAg?Z^hT_06X)4K7YJDlDh>tQw6WG4pPjZo50b#!gwAu28LBn&;|DxyG>L z52O@)d_8Fqn6|=$3;{v?jNZPiUfFPM`zO<7q#oS2q4DP73Ea!%Wm+sfqE(IN%d$p| zzwe3>rh8)^|J1J{O|l8pwE8{^RJuost#$|cL2{i|%Omhl<H;Knvg@(h_*}|0!%U8+=iu(K+-^=Cz>;;f9IX z8TvF3%w0Mi*Ba-*YqFvy4yBU3Pd!FhvK4ya?q^YeZc$gO8`X8*(F7 zt?S;0gNwGSC})N~I^%^`Q?*tC`J-w1(ommdB)@i7E7 z?Is*Ib^nrU?fdAd2^VnqHLQb{CQ7v5C2o;-oUaOVFTIw*f9O8$*{>7VC6{Azg)Zp6 zBzSz?K&#GnIiRTZm9QU7*!ZYaUUr|@o(30@F7one%;>z+$`mnUXrpZo4#Mnu!cM!= zuj}LvpG_J`{`t|y>-Zj}rNyxc>0w==2VaKNRm8`4z&<6t2 ze3eHRk%m_M^=BSnY6dedZy`?ky~>77Mi3KFgLD-DDI(K^jdFu$vA(Z77>^2Bw_bgnk2_sQsd^}>o66%CwMdKI&(phQdR?B%+qW#3ktzeqj9RQUF#_mR3) zr5j*5j4Cp8S+KhX(f)NiTCMJ-LzBA#hJK3F%CGM%?+Y{Y+0dWRfQLO=n3vsK3 zMy2Ce#>N)3L2eLz5X&mNG?<#-WS&q$a`sIU8>Kqd{@_Fj8$%wL2uY~Rt@j4^OMcNc z+Dr%=Iif0RLa5N?CxHz346+rOIdnFTr!S{DELV07v!}nt(q8IBNwa2R55eIvu%rE)Id0(%jIL;QmGqqv_@xr$d07JRM(!?hQ zQgH*A`nt)|vG&MZTri*fg>Ghd$_Hy!Za^UVi8MwmA0rEh2(u6$l--8be=R!Ce)OJD ztc0V{E!u-$7PfXBP^7c&G9)^7_oB?dJR zy%qBQrTb_`heL1a6SJ&}etzJ4X0p6UjX(N49EW{r>-$aYUq;DXiZ>FK6!Gh<=kLBH zq^ZKm291X#??c}UZSM*UwhtDvSOa^P;O?8yY?(MGK-jZ87gl&} z&ozB)%06W|8jpEI&98Y6j0z6P6o5&hdKHLBSvmVQuqqk6f!8dPXp&t9!#ysG0o`D?gMk~?_ z_~%ez9Z}sFi2gZc$bWp_GClmgpy{Dtzy9md!4qWBrGGKu!0+bd*no6EAd9>Z8hE1* zf93MElO-~9e~jwOu4-CHBX?UkNNch>>yW}+&Bp?5su%i7Pp@A&mR;^sGpeYh2obnS zyf1*kpO=YRs;1`gC)KLA@fFC)JCT}p1+QJ`?L~L&x)T+%)7GB-rzo%Q&X!8RJ6D=72P*4g7GIBvSygFU`~n(`kXmTCk!zr;PU`n=XIBx zgsbH%GV(f$mMcX`|RST-wBSq>yeyq>CSihJ2I6H2Q4v;M~yr))R1nqX}QjN&QmR`V3B@mnIz zjxqObGxp=HYK0K3R7Srw3qL%PpL&(nO~T!c*NPKtw#N3t_8Dzk|B(UOWTpVN*s<5N;r2f zV@B47v9Ef?5x0Ndj9v~eOeSmi11B|L%?ezsgMGG0cE?%=#fvBWGBulv+|5~|0WIFE z;d#TApzSiWiblV-bD(XA#`@C#KXrP}u(^`NA&=wthm zHVaV?41KXny}GzzJyvXuy#eOES?;#1bCKP8EebtCx@tfcjaA-eRF+o4>^fI#N6GKF z5cvu|bS|S{u3T~HJu>-o;<^RmK(aU1I0w&Aulqp6tXt%ZeWGzGL;_MtM~TARrr-M_ z9@@S#kFV6`Feri~&l>vZINWqux6_o_AIZ-U}ZYy9je@Q%{{eYmzv&e%f$oE zIleysNS8#H_latTa3V%+(sxrwJ~fOg;@4QLfz=8T6pFvU&h*T;+7HktEIur6K8z=E z%$qYQxxT>OJ^C3)0Ep?155|@!7yad$M$;3&FCo`B$dg1pcI`C%Ufs9$W7rK5B!T1hj%gO()wLsS(Cp`XN;@;>A^-c^Fmh1Nq|u znf_%MrkpQ&3_GCwHjLF%!l~**6$!OEo?$w6oKv>0v9)vjeA=+DzvU@3(y<5+$aN21n_+)*hOt<^0>zXo11W0F2vF5SL&}9nxHm-U(1?MsS z9y6|xJTmpoldZU%tR5>~Q>|)|2~FlGt8sFE@rcti&ebUx^u_pt5XdMt`R(et4x2Fs zCg%6$)uDIIx#ltD+qy}5Za3xDk`!r?JfR8Mj>y8eaBb;twPj}C`!kOfzlDF|NR%{> zx>z2Q(6|__quib9y{*2p07W?*Q=_V?RE8~7sM#AG`Xe8{S0}Q+!$BM)y?yq&t!VvA zc|+m8FD}(H()if-dWYOLAgrwL$~fD%tC^miojq~>rOViRC7Mo^qrG2wAFcX@#YhX* zk;4q5d~&&ccrrvPbrknrvoG?D&diA5b$!`WwZ+iiOAS3$XZ(?D?BCNg-`GHIEWDh3 znGPZ-b(=aG%-Nbv{kMF4pqX}}(Tzo?zCwfe>kN+an_6-ePOENo3N+BheH_!`^SROH zi}?Za%@U^T4-)`Czuge}Q}1sH$eI{)EKNL0HJQ_uExeI!%67UJ*$eudnl;c2s-CTm zl(MOc1>0$t7rXkm)v?XyuQ?}0Y7HQLOO&a#mOOjn8AI>!O3xSLBL0Pm+gM!Te8d{q zyuItfG;;@dEZ%1mXO5t^wwSE8`3~LFri8_$gJ?0gQ>hSm!H=DFzatp^P)sDXfWx<0 z$F?40|4U4v>XPT@gCM7)m@>x&nC+ttMLr*H=T84n-+?M32N_dxgYjh`LaCbF2E+=h z9Ga|3X+j#7T5LvskPTv3ZK<-H_*VuZ{Y7@FQX0KFsnjHR++!uEl7fYt)wjyzc8tyK#Iop;GVc81o~>vhUDEmG0c9g zG_jO|R#xR+#A>GB(s~SH_EMw5jhe>sPy^j^`c7>fGU+FhQ5kT0j4D-&N$gZJDt(oO zr|~f7ov*<32O@QjMg)HHS;u;xNoOSvPXG`mTZbn9M6Tw-r_VWB$8Qbjs}Q!I(UqzB zYs}|tspIJ}X2U}fs|2+KjI-6U@5&nbzIvHO^EcNZcry^|8)YDD8bqXiqBl@NZU^;5 z0O!M8@IzOJ)Z0(LMg-pZx@@O^-mqp+9$Kj-&#P6D2_So*KblGX5cXc?cjCyVrDNMR zvM!_~2;Sm)ewaqUzAR0~X3lEL(i@J$wN#V9_v()8SMAh>vI@;sF746yBMX8Kpb#>4 z>-1}$TS1h5oJ2Ob&YRiwrhhgSb+lG9nJkdvqDAmJ_cTBR_Bg67ExsR%MD| zmaKt`AMM7&jS-8dGnb2S0IKq~=bk+pOZ+W!wyzlihrcg|NBudlZ}@kO5io^)`t&0u zujtWl6L;2y4!$O3LT7%z12iB(jTHJX;AbSC3;`nHml8;6zi8i30$t{8=S`sE|CVvAVvh_uIY;P<^?BG9sWwKI1hI#N8fW{Un6gV zI|0`<4p9-5T!m2;6YS|$*uvXi6>fs2%%rU4a}5%h#TU7 zRwNa1SZbZa%m~gzzcp2oYxWPb{d0{^+0*`?>a1wVe-E5iS5;E_3hQ0oD815jn+I9u z2sYhP0W(L4YY@BDN4>=h=mEvg#inv$4OK<9WELoTT$e1Xh{yK4{p2*gr6M3}d7c>M zMC@c=E^|PUC3|$YxaL-%E_YJpDs81Cmbl!~GAO#PL%fdX#m~?6=WVW9t7&RN)zHys@{YPa zyYi1O2jY{IXA}4z(uAc`a`k^`n(X*+{tL!CeJA1B9ibepQIFadFjrs4D0IZjMo~kIL@OWlXd8?K znDz%fC>TYdroQeiFMrCT{Hwc7S|k8-hU9Lr37M(xAq|2jI4A9YX;{%|jbqRfnn~yu z@bRx6fx!-~4AgY8>BVyJKh1&m!AjwiGzKN>y3C8X;9EtFW$f5(8g<9I8D z&w3&22}wt__1@BZz);v(ZPgbVcvCCCFlR{X^F(9j*SS;@LA#I8nE|RQ{I!wS=EeEP z@m2k_T*lGQQuy@iQ=e2M9@I&viF^Mf!aCZq7upo8J#cfE;DeHpGgGx^V(9Z+95Av!&r?q{w<^<99fVf6y<{p4b%-*y%T=l{d?=!ru5DKisXD*^ zdJxa3)hSGvS$8yXB!!`XB(L1C=|d@`YFls=V;0J}AbV}(oA`@;sVKAyKbfO*N?}<` z+k1#0Q`C*5{84H02b-A|?HH5I=%@uiEp~C~c}n7zQSonW1;&n%`87!Oic0_q;y;iM zNGB!7WYv20^Oxx(uT3~4CIqMYaj|yaI63>L8s`_aUVLD7M8B@}KGxMF!1+uUWJ0MM z_1uftgW&E+(BnTDpD2y+m7RRG7cAT~s&-uDb`Ay@)6Xbixq$3^0PeK>-7O^blXbPAK0LOSj{cJE9SC=cxUH^p#j9nJ*lNNr7q|vi6wS z64|G%h}M?LY4MZ|_0uH_7t|CgYYnDPoyQqtF6e3p=uwj@(_t7~_M zFS6;En;=Oy_}KsObge%bBq-;M>fGTOtaryjhiHgN&1@JPWEREaPaB+3JBViPs|B(7^@0Wb`BjKw7rhdPNb8PoZvKOVSWee%4WX$^xy?;q5@! z@CUEtbaAKXb%Sgv$>5l zXQX;cO*EHPko}%n&))YfmL5gF-wGj>p`H4E*AwG;3}^;}m$D;iZ#T3`OxMFL?h`W} z0dr7T!VmmI)yy#Ga|0tdq{@j#)P<#0@3MAH{A0@3gAd)Evef8sZFTxiVWcb71( zRm5#@X`r97U9v8UXVhBP9msWiDRY}TL}1ZV%0hHdDTdX;bz}aG>&py-wc9jbdlLy_twg zHh(*iBAwYvqP%WwImsA=xVuS>-q#nS4wHRFyiU`nl{AW>zezIAIwIv0_M|F&#ywu} zi%)8z?5~MgYysJ$c(bOOr=ZOrOzbGejl3s%CmxNRF|OR82}=k|vdR=bmgT<=Frk*+ zIOao1BlJ_ZcV;Q!3*PvB(KH&XA=|!IGrc$Uj>{5e$)9)*FtgIyEz4IV)*j^m*0kd1 zXvSci<|+#|s1ObP9)8dBf)~xZJL}1B)oROPm(Xo0L>VZnXEHGQ*EuX^EcG$v@xd6A z?*3lz@hnoIF=%}yq;Tt-Z3x^=6qGrg8Id~@PVMwJh87t|iJ#0u4?&3N=xFHpYop}O zPDmu>UQCYQ zmkhWbM+V48Cq6nhX7+wtecE{D(aTsyqU5v9I+ZV$DV!chOoiZ;4^z*32;n7Bg_h)x zR>j?#1T&sk)GFlnmOw>-a%JRK2zP5C%tfZceyWC58kRWX#p-sClqQNKPbo*TBZ$o@ zUcCXq7{^%Hf9Gzv;Vj}i3b`*jvro=W&&8#Z?$2gboBuLT_NDSjOEioGvC6L1S+loX zd0LQ}b~d4Q^ZyRyG#LbMzVQ&W9%pU7cEKDUN+!bqs`$a^If1pR8#01)w_JDHwy>;>3yK$Ll$mTtfg&+NVBr@4S~Dg-#pr! ztXQoxj$@F!J)9wd?Q=C%f-!t|BC}({ZnDDd9NIk}tzq>&3G~{5`u9^X81$YC1+f|i zl(m4v5!#y;^<*!*N3GeK$4&KXHsM;`^*8PhEM#!ouBu$_PZBtF^&6|CoU#%L2e zL*?4SoM9X%kyPS$m8sj%iUKZ&l9a8FRAwRkwo5rq|5U4(rlfXe)iwAsrN1y$IuxeuqEjKy%;JB&ktBijhth6573Ml%H@1|`&P z?|1o3Y?Oa0x%QFG`lUll_J@xsH6fsmUv^&Cj&+KO95%tEySo4!(q1q+Fj1ayu@;$( zXkgil3q_P)?s`NpB`8u^u%>cYWk=l+fu;waJNcG}6fO6aP$sTy>23}!{3v0Pwj52s z#U`YMF86EYI+-$JsiyH082ep5R!n617)|H}YUFM|)}sxZzIu79$M1oP_8v%5ln|&i zsIyPmGU7&%vj)-fJ7~gch8FIbYj}dHmF;|zr#!#x>(@aEq32GV*EBSZFDom)+*t*U zRTh~Tm;-wCq}3piFW1owt>aqSo$CO7RZd_o7g>L@s{J!1R_jgWof?*@#z9_2W4l(8 zIQ>_2&5St)S9RNrojU-g?|jvXxiwukwj)q#{!z)YTEZ9*DuFS=?jE4!Jetw%_dAw{P_^^tXc{0}BZ) zpB6o~o}b56Ijjw57^bsxCEJUBs*@wEv72C<_O=|W166Jt_Qh#+8tG&8n)s&UVzy_I zk1Ws$CG_Xq_<-`~F%ne(vza@q4eEg>u0FBpTa0Ow)ehb3TAYEx@OOSl3bnBt_ zMVGA}A{lW!^gfl}F$8DQ%ViCU=vQ)fNvim5HJq!Uph(=rFs0W>J@q^Kebu13l zkACvzDSp>{`AE-SU><68opTOsNih)EA#w+U4|iI9r#~wP*oSA+Wp{z+mtVknO~Y zsNSC_2#um|9Bi8w>2hDp5Gx)TI@)+(hk$LAY7cZ@nvC8vw93l=qj(zA*DSk0UwXFI z`LSp7E3Y@fZ%al9i3g>>8MJ!xtQhES@7J1?q|0%nAfn4&0R2~K#2(WE>fL}CM!m9+ zMib!H-hOEHk*ZfR~h9`b1)6#d7Ex{Prf1zr`M&zuF zG0HfU%%-NnHIPrk@5E9pcA7vkv*LPs@IzTq)PCQ483L4BGd=olTgGMb8IRY}3hv9@ zSyC|SOKUYEuiFXkFA-A#Gu`0hvO>!Ar9pKI)w!lWYaLAcfArmSXStU4s%noo z?nNZ~<-#gjQ9X~KMg7UZ6604YabAG|PvSV|jYu1|u1Q_sa!qDA_(t9rCRu+vZo0Ly z_uE=`e_wSXvpB@a5X_5g*x!)L5hYFLGVW}oMZP$E!*ie5u7|%R2wvmX)0+T5m?c)p zJJw&S9(Q(iPI&cyu~g~12&RR&rkk?>8l>k@>5Q%vt9-<#F`1$td24gF=9Uj{uB~E$ z9Ph2PuG6%C(UFE9ingE|qL9wP9chjIZD|N0}S2LkR_Xo!|Ee(0# zwE4=*mM6fFRpF2MqxoYQBM?@TWre@GNuhS97Paelg-oATMScUlz&Xl8No-7U97aN4 zRI4Ia<2fMHk$#{#gxq*QwmNhg>6+kfqgJ8C^A?{&W4~5(*#-H%EyMTN^qJQNnfKwg zop$WR#fJyJ-ftIks^W?g3lC3|;i*`lB~IC?dBhR8_CP<>x@TV?$cbgE4Ax%#8ryw% zdPM`~_Cfe#7u)yuCjp3EZQp=pA|r~50F z=jh341l-(A12fFr7D9tHDEj6~OXZYoq>Wc#iN*Qx9eyV|qjF=3u&8mB9|xex#a1~H z<6g>1cAk>fmKvSEUmd3Yx<1lYw_3(CF}a_DTQ}&lKXcfWALvXBs=i9yvg(g;jh|-W zc9@0|p-2{%?i4+9;T4|QQS$n5Z97p~bnJRHtskZ)XDUy%nZPCYG}nB$^$UXY2d7S~ zG{hY;)ktz8ukST&0&)t4I%R2!2~!O|b$KhbYJ0Eaj6G3wyvwxf?0JG;y!}2HLo8ih zD%^88C&^cf1WZpdMXQBUF&gkc{ufBx00Ce>Q$k8>$zbo|zl;*R z+iy|6DkE9Bt-l}zK&=ueaIQpac3v;Q%bMNlt3gJ%BW+kEaM9jG)6>hnWmU zAT=@wzOA7^xD7W69%cr?(TFaK@Bv-nyE^L<0Tg#) zYE62KOb1ek0YQi6kK+3@7L#k5X9QSbj{&bW@c|aE95n`WJOY_um(>clzS}jMUs$DE9%U%NW(KOw3-wy(+_tQk( z@NT{(>;ssG6L{RcbPV+OD1u7&t3?e$6pyzPP_grCc#Yv4930PR#z%P4-W_0-+@j*8 zgFHa{*wHacV1`eELx&!3dfqkfiGhus`s3dafPmm+`!^Xc1%6lFQJ=HxF6LZ}Doz%2 zyar=njS|2Dwp{F?LAvKU;rexV02Z*}A1t8jKUhHVnG$T?WVT?}lF4r~(dqTHwB@u< z@7k~i*@H%y{xnunchGz6_ZquI`I!+w#RWcT_kM9Wd_m}R@|CrhQP^O2P`EHhq)AyY z#LuOy!VCcI?et(mxyBOB(DM6LZ{IQ)HolDYeEw#3r0pu4kb<*wRLp05sYZyI&N@N{m=wf>w>R4(pH6lETOiYx%lIrnwjd_|?3t$HSI;GqJwSOa z6yn;rV8YmnlXwjTtU+puJ_|=aWLsde?EU`=v?=LJA~Y>Y2T-ONVKc!Z1rFb?F3%%n z(ghd4EH?3q_IeHomnJL#%xr{umH4zn1d^ZC(8t_1v+z0yaaSXS07|Mg)yKNQyhYe^4sGz0WwKZ;ppyaly zT2KwZtQyiVqAV10ovTj+yo!W10qz|IfOd>~G@UGgA~KNh4C4oYPYgCdmVi~fcGF`4 zP!~*|qzM6)atiDpPg{(r{R2#WRZ@P_Yk=7Qs9_yHhEf)5T=HgMd9J6gk+A`BKu6tG zc;|b16Wr$Pb+R=BK+tB9eCxH&@)mbm8>xpl`HrOkKHK-1KsOwm_kW=PO#qKf-yMyC zDStw5e!LF>3Q>3h;ZE(Pw zKPr13@?XB?|Jls{zinnH)08D=BAAvf7&tY*<}4xJVIVtx7m$F|;g}C6lY4C>%QmK^ zIC)>)o)dQ_0K5SXM?IG>-BDjca}-IepWH?f!d=PstAdq8u64z(f(rKA<%x`0#aC~LM!BV zab4{}`%O)2eYtN@Q(gX}_KTk;Ijm-eLuDlr?ED;sg*uWj6UVF|bT)o6%-Lc)UBjj_ zb_!(eM>?4&80(C2cgKeyr`L;J3-8}RT&;Ll7gBab$HbeIM(2D+*ThnMTo#1Z`X9*M zdl2(1osG8j+`*H*Yu*k+$8@uFGz)iDWo?(6)2A-(0<)pY?#i-=gUtiVSVVx1^P4et zyd|+lTv*>sgVg*WA|lUxo{LHLGJZwbf!Jxk+xoar=~<`yTC-Qx^6YN6#`B*P(2cMg z=r|bCSr)rS<9lzG8Mzo`pb}zA;Q-uiKtiO;wWJ9=I+dtfM^A5{VMyOe{)8_-C96wo z5^Vqb=G9h7`5@X&tbVb&MXuepBj|5-X@bZb?6C9+;zy>l$8R#?{Uotj7xg$qT6NgT zMRbmqOIg&YF)m2^1?wYnk9JL3-^86GU5b9U^ta*fabXzHe_ILrJX(;>2FJP;JI<+Z zKE&*r3!CLnE>u^>Ad;keh;C0PVZe(`NTzD~vDE*_jdf@McR08K5B)YdP{W_vpM$x# zl9H%(5`cA@qSop8TBVb}`6_BYog6V59>E0ra_q=$e?23$#HZJfJb}vZ6{o8k>TZ{Y zt5ahT{ZgRgVlI_c`Z%juYyCd$Mw|#nS@7>RTq& zB#>nuoLKG~%FB^cdTM5tuK06IMd(=Pz>!ASE#A3qj$ZDbZ%wY1`Fr^LL*dL*Rjqr2JIeVg%mh@Fyw_3`M5n4u4lJOrjQEJH_NLY)Mm zHbtmoO8q;Fke26ZS=%bbyF$ZkLDFX9}{nX}P2bMV>_q?Fdpm z^sIQfGo#h|L1Ys0!qwGf*b5=%eH4#vH5_Z?dp@`;Bvj>e^=i*klnJfbZHS^_BVGyJ z*ttxHp&d_u%?-=YBGuW1*~a6kV^NYVtIkE!3U`0p;M376H=~+DV)O+}b?@4w$k&bX zF7Ej&*Y&yx-zr5>uhOz3E;-yfd_gZW&CFW(+uMm;1?lwkJXNk8=+k@iqI+ay_37zn z3;{RLmGN?qw(Sr!&(<^S#ZO$se?MmfbkGEWp_G8vXYWCNAP(KPr{F+w-O`IKe%8q^ zU!l^%!4A7go3gbtzZzGN5wBv{*x#j*-*3m=V(t(h|ACD!!xwr+co(AjER$?q;% zq!%IWx74t<(*GhlZny1JwybrF_ucR+xiFa7N|0X5?J=%}fJcueMLwY!k#^a06v;JF zD@$->HS;kyrelqeyo33YdL=>Jp7Ao^IDU#tOOc%*zrYwE1#85ZlpUvavqR;+Q#~FGB3w_ev-VRLX&5` zEIZ(}dy`eKDQTkiK{#3+ZaIiCex12`fODCJ0D^EP<%@>;_RQehPi18axa8^@o^MuJ z@Gc#G*)+KLK<${IR963V!Do}RVKYB?RckLI~7bT?;f5wQ*EuSbmm1A`ZkM|KzOjYDiPTcJYb2&rvL3 z$WwZnid3(+OVWE7E)fZ&z7Y}29&g2ZAveSYP5(IOmU*p_kud0i)A#NXt?@i+uWmB;zMLWy= zvPo9?xJERqC6{o^8v0W!(JOaG!ydY(wdwy}*4^Pok*+3QcXzkqGgzejv)b-FCV4lR zL^94ruBIQ3{KoZkx_}j(-j;ehBuvd0$z*A%_#-QD8~|Lws~8n49x17js~gsyN2t9L zV6$y{NFdjKgwEsaOh2JTUs)L+o5VD+x>{wo&O3cIQm5YRCpMrrDfb@hHy|19rsN!? z2WKJ>CHtOV1YAnVsuk{SAQrS78XM=O3=UtEFX8) zVgbvZ{3*hWbvA)ph8>}#>+sQYe`p$O+Fxs7T^&u}S)^V~qnL}?CUU$=o7-l(`Yps` zn;w^niiDJQSKYTb3fRFdib4*y_$s)5p64YNs}ACsBLAAajGy={-IpiXDqw`b*WffP zhJb*Z;KK<%WVv0W{tOC*x|y1O)PzE@@)XzC*RzM38{T>>Jl9d)LTXq#7;vwiZL1rh z5!bH_vac39FRvtn5k$4Zh>zq5f3bB)iqoR6y3TXD<=)7+OiJ$C^7HkfzG#M~sf*dc zU@nyKkAuNQiQK1qx+J4M)=NuG+zEyu}uNWn3!jwuBA>-j)_UYWSg@`Wzohw!5Nn5D^#G%!)1EA z-C=k2)Kps$gS~VM9|S`qgGM$5Vs_gT-ec;;u7tA zPZuDA0){7&wLN+D((89z3;HC6j40JcIQssGydJACjh&DB zg8XZ%3GR;y2+oXVOpS?3KIu-M@?!4c7>WXBRL?238N*&m_Bx3%FXY*M*K@HV2LkD0QcHTKH=1rbx0(w*TArfL`d%1)$@ z;43!gZDoN0nPfxDg=+KfPY33kb3y^7Nb9Zc*86a^Ey;ySH7z{gxbh zjJcJZYkX>*7#H`sc~t?Bc{J_cexv&A)#o70$NH?a#|07tT9d}yE$2t?R#wapWZu%u)(wd` zHlsXZ#ZG>~k9^vzw`S>)TCMu~GlnEx z$Q%0`WQH%pM2-iOrW;a$Pn7*$ZQ>IS*c;{5)sGD+BTc{FCMdInKlpQlZzgCNYqxLT z){+9Z2cG93%2(5Ex8VXe4+tp1ke_N~GYBj~8E;UOqgM(bN5qk<>b*uiJRm>=L>6|54k=P{$1EN17Q6|qm-Z9_TtTERk(b{Ap$-s21Xpyzy4nmjY*c~4jIZX z1HUVofCn6=@%AsUKQF3{6IL(q!tbZ3NC?61}hK>2U z_+MMN3Jg_t^UY7M{@hFsA3XY{XOM;vcywQ4Nuxe^<(+8STDdL}?^pak zD+&Awa>OLQJOw>}?!7}yXS$i8gPEHTOdJjaWtb!ybP5dhwITVtLAQxa%)X*M$-?`) z5<1lMo=?PoJ}r?`*$rI%wO%Ic$1j5IKUp_aM4+tx(l<4?zb|=@qrJQE^=qk#zn6#d zf-kQ|;q)N_wSnK*z;>76X&!l!9Jb5j9*t&h~fNot*96*7XeSmw&D%l57W2=Tl?U zZ-T!!phIBk)Tvn$k>rRcIjfyq6ehv&h}Uuxe=l~bxIvop|0J9v7|3h?e&@C8R?Q0sO|1Yb%!xa2g^BG~?bpy8=G%6juIE0+BIG&pr& z+25mYoctA;8)!-(w)RE)E4piVK)xJcK~O#*Ur|Z;O*&xJT(|FQ{Y$<&Q1T@xs7dfw zzF1K5Wr0@E@Mj@qB;ZRGJ3VfzDy^_@eV`rs3?*Nd1~%k>m;D_q`_UZnx2u2T3*^{7 za{rGf^3$Ia`Ps#k5+8UdJsmk4|Jo8A)Um*RTl_DHu|ORQj&F}B|9mMe@TCmN%YJAl zkt0R~R`B9j+wo@mBiZ4ocp2!8Ik4;y5%f9Qzi)}b0i^Q~^REb`u>%olsKnJ90q5|M z9@mx`SaqYIrzXwci?Q*+Y5w-@`QyKrXFmg{IRP{62g<9$saFJFs-$z`Vz8J;ZZt-s5DqaP6V*-0+o{Lk43I*AeRzPJ9-Z2zTq7*!EY$KK00j5f7BDk`z1$g}&x7>^wc;OtK3dQk$C9^o^$ zveKp`BMa?YuAJ~R#E8w@3pq)t6GBPEeG^PHO5T~ClkX?E*QL~*@NvEooJ?A(32!6|O#`cNai z+y0Sw&P5a{^msMR61=b97R#TE4mes0CKl<(rAKvcGtuw)?PoMM2eUUeZ2il>teihO z{m2gc>!;dq#2-qORvg_YQj|^%D68<5aD1C1UVd>Y#YUFN__0-PL)<=Zg4jpNtcfg4 zIXZctQ${^Wg9UVnsBag=+v1M$aTNRET63VIk$u{eHE;=n)F>ydl-_#xvxx0L{wmvG z;N12#@WhAbpI+*Ade*JekrJM_VYKQrta@emwO@^2y?+5IlJa?1$~iKU7$23IE6S}} zEOtMm=C}!)kyx_b6rHECk|a5eLt%SH!S=)f#2qNtRK)K+w|?7ucJd~79;=I|sCe>Vc|iagpSeTu{O{YiQSlG(a@{KoHuML%lBMt$6EokY6^b8!UYAbaF&0&qz68J|Ip`izoJDnXE)IHhp?tQ4R zGp8Fa087|j^kZhE=9jmyDH1XcqXasaNCBN^Z!bPJgDd4Vw!)A0E6drFxtJ>pk~)HP zJ8A{{0#2Mll%+)j*M7SPbmC}Ou!il^P9$p_j+z)yWc1b!%fdh%3UiyEMV%ZM9LCjL z(Tp4yiCj0SC{Awk>eC$n4SRyyUHdFyxa&AR$#*8aAnTdSq7IWqD*oIgk!@r^47y6j zoe3-Z$?DMr=xgkh2@8Gka|4jte8j zy!w+_8H^{XQ`c}rJ&`$Zh08GaV7(xPysm-P7vxW^65*-=WbS!j)3igP6d3{}$xx}Z zAi7y=dR%>K`8drtz{ry+&ydK2UBgo6dpJ2LDylSo+nT#EedAcjE|;Sqz&`e-)Q}bt zPHMoFc%3*R6=G$fXrmGcyEaeMgfR<|Ap)G1V{yRBYUX+5luDl5WMtx3aS=b0SLAmv zqh5(U#B&I`fv!UI$sR`}!>JkMH`Kb#r<Fp^pOXRn;+vn#t&E^{r)`PG|k3s!uaKEoo0 zfeSgu{mEtVIG!iB`jl68bW>@h;cGKds5x4JO5{d0|K`O31a551df^rfJKxn-k4vT; z_?Tr63}5?w^pu-tN~v9h$?xlRbk8pqhp86+{AMp>+&#mYkQ?X@ARn=GjKkk{1p)5S z&ti69?X|vVS3N*^hB%e>bAxF`9s`mJJ4viw#*PU=GO$$J*HQF1^-t-F>>6uMl{~^6 z(;=xD#*jQakB008O%gPJOpq^|SuW-oud*VXKI@sApM5|{c|QAW;VsHitJ8t`KkKh% zibyh3SW7ZJ)x)81cMFliM82GGf}Axq!G+{>*?eGFZB>RYhfGgJp28xSb>tL8|E@iy1WKAbOGc-;0T6@VYsmY|4w%= ziysF=J>ZQ!-Q$KNYE)n-l~Bk4^mhrk`RBW*KkWsU<9|kpaRNto4J1>X{UU=5rAQDR z6z)?;AWW?Ycuv!Y1B8_4<3nIpS?4|(pw<6;)v`MAOsroOmRx4v04P&-ElB1r0NX&O+I(F4Iz6tZ8=v56{K+HuQ9=uh1290ua% zt-J9R1c-{8>a}<(11;vA}!I6ESXt-a!A% z2I9OLS#j@KP>=V1p*jRynp2cPq0KRwjD2HY5lrLm3+x;Ron{{oD%g6)@=Qkl{|Ms$ zz97E%_fY0U@!vz4$Cdi3DGkmo3EJ9T{}Idl&$-ntAL~wjpF<*>&zy#c5naw;C4{_I z5p%dVL|KN;1=E%pR@ZhI;mJ>-pr%IrLXG)Y&z)8rg=N@}75A&k)Q+cDgQf!;zj1;o$IMG@9MlV> zgBNf+{PO}Nh~s5t1#m(Q0%u5bQmrJ|$u}oKWJT;?obj5UYtn@HKl#;f^gtcce+hWq zmrYVXe<+#F)YxdiOYDvak4>8Y2`}cK>&&N2C|j<=%!1)3PS5E<(@?OzgGJtd4=_4f z--^FGZhTdddkE_Rw&mO~w;_)Exrk|#&GA!K{bX(}Ev-nImN(*4nN8k4JEqqsW0dR# z;$ug;vj;OJjBrQbjLi^=fk1(-6T?2NJj7x!~ z^~i&uEUhh2+gD-d`}YoaZ$C)m9_a7KQOQRF?0IVzK1f@B3Tp_&#}w>B>ONV%^&i?1 z)Ykr3gn%~EoDPRnaXTLaKIr)Q5d%;%uriQ7iYEV7D%cki5{{_=LXKFI1`gD-P`vSI zk}ppg%|OObG)NqJ9ozQH_hpyS?HUwtRqlSZ~jnXm}Q-v@2FrMy-o}B0^bt0$&SK;6p#3(f_ea8ljb&FJb z)t=3QdaxOI@B=K5Z`(kZJY?x8BVh;Xb@*tW1sJ<;GH~NIKbJY@z7*<}A3p}ugj`XX zS>*+wkA5w6Boc#64el%|dGJ<`j*K+tO59FiDx^`sNdl-~fbyQ|BS#UVn8 z3zJa+$DcBt$P-Tkzde?QrSYLW`&2~yxlfsaZn(l8Sh zhpG8z)P84tN}Y;Jw7v_tcy`>EwZ^K)>h9}uC2K|U~bKU4-= zCoI}gbPsIZ@}Sl{=YMPOJ;R#bws+Ab!cuTq7KjK)QJR8)Ql(=>I#NOj5b4sTcM!z_ zNDaMOC{jWT2^|zEB0^{hHK4Qrp-6{7$eD5Nz0X=}m;Zh4-uK+|VSmX(N#>lHzcI!f z?S1Fh7G_Xy-iU=CNXP9o9~1plVpeAwZYpQtD5=a;@$~7_wbgd6&e^W??FWYMn9%vz zVjBF~)rPuydg&4eq&nB>u{eU9$cg+6-wKUdqPgme7#74^QdjV|;aB`lScfs}U?+V$ zhbYIW&lP&Vp!tTTowZ}EeyzFD9t^fm^EA^02^oIgnb0{FMk&JVr_q%Lo|B3sohz;@ zgDA;ou8sS(i=(bEzoo8_Pntesi-TT)K}_^eSnI_V?@%3i3^@pQ$E4YNBu7L0(^5n+6^NKt)G*4kqMhB{J!WPG&EcsSd8XKau)Pbv zCC!uufIx4Z9<+O(`1X#f<&7KgZ@%PgN<#W_HP68LV>@IvHqrTs)w;Fy8Dx#eOn1OC z{RpyDCQ1fSAJ3pcCHc*pH)Z@zhyzA07J<_JDK7UtypQy7agj)q>4qO06T6T$fLF+G z3|VzqJnRZ!CpGj1qn-D>cc+mU>$OUIixoS3ofn)~TB{ZEHLF`+1@IER(gAJ#?n6B{bIac8 zKuV3Rinqpv)JG~^c$!K~&$F0I^|@(%D2`1mBfIt9Fs=(m{)Iq1n5>hiTAszgZ#n z0{T%d7SSXW5r++rzza%+7)Ce4Te#nps{pc1*+NjzWX!y;Y_ghUgWLsL<9`nn8 zc~)`k<$4;tOkq|#Bp%upliVdEBeoVHqk^gI+NDAk8pjehPu$VIB!)y<99;VdMDOU$fc=e`s-QvI`!vUOI-}#0b^f!%L8uM zpqW?VuI@)i*TzdRin}?3>P^=ilNPb4BGqw2U-`ZoD;3tErY65^ekU)n{v}c1v~gZv zSSbRAO`$bfZp%n!86>BcLtr;>m~T%`%IhRuHZ!r4e~qb;o(LW_Tzi$gy@|xD4Vg^w zkteHyLm#XZUltcwn{aK6J9Z~(t!O;dH|xkGTd=|SY&viv21{U|;>~I`dyCC~p5=r2 z-sr^iBk~q}Eh55}&nYMh*)>axNSUd$c-vh>wmx%qVA+ne=eavnen@*nt6|$*X20jA z&B(_5Y^RTAgXfr>Uo&k-Cq}x7D4T_^f+@}SBGPvskL*BQkMF7h2m3lPzNF>~J#;Wk z@F6qE$bY?DqdR@{n%h&viPIwW-*2dDYfJZF6!(ga6Bp3QRjSr_eq%Ta5a|19>dFq# zkCO6m5u>-2guSODMo61MTOGq|`8)@_;&w`WCl#a==FFx)-!uGFT|U^6=H+O!SY2c@ zQ#kQBSUZ2>z1k2?J23hhA+W|~Uo$TzrfKue?qp}pAxAY2QbDllxAG%giCfO2sY;(g z6mj{o>CsSyznp4RdCG&l53>rGd^m;-R;jGxt1uXZq^8>TEp(PPB}JCjSA3XoGE4lv z2nXZ@RyS@u-Y>f!Iw9nwtu%8wRl?%&Ws{1Q6~~>uRga05@HOz6&+4U(CLZ*7@6~a+ zm4v=NU8I=Y*-;UPX0%7XR)CY9LeS^aGD|sd>krLO-Enj*JEO%vPvpZlK5EJ28Z))| zjCsOe)_7~LZh?dlTC5K88< z3om$Xg(SttU#QZ~n3EjF##(b{5kjkGQsN_WR7#AhY(>*Z;?u0@6(474n#RFykA#*;nOc8PWoUDsa!4$wjpvZrYkWp9Y3z%g z^{3Dy;U!0L*l7^M^}*k%sQcy zGjadQViRQBBDgC!%-JeiE{ae8@TLrQXfx*8hE8t|B6!&G%jRIZ!KF}tP{tTcyE};O zc`bWHR%gj|PFCaP&w9y@at7d-?~e<|g&_(bR1jZ%ctX~?{PTrjwik}H>pqwTEDqcJg>_uJ6VnQp4ebx(vu?=<5QEga2rL8(t(X`CaKy4#MbT)tmJ-G?lm zW8asWpg!|TY_d~ad;wvCR;|y9OZVgNTYVnoo~;O%xO$HVkEa;XkjGA|7_>vu@Z0Me>n9aj3Wb>e!XAX0*PiB(bq}7`ggZN}*hBG+O!5{r=_6}6} z=^r@TLr2kD#&tl_(|?hhk+2`lLtLtG-jnjkE5vp9+gGe^=soWMn#X(dXRZg`68Ku@ zB2%CKYrtcw3JBAz`o$yoQD41-G&-%`4h3iCPh`d~~XmY_x1>Onr_nVsc%;+Aj znE7;M$0&{z>-V@NxP04co}ic$(!2#qFLO0~0A#eH`TG-;jw2LOvZ=>Zl-EN3cF@#J za@VbyCdJ)bT1uM(3XEv~#wAIswv=!f(a8u;+TPn;pJ_b884Iq1O?8y=OmZYUA6AKB z<0G8pGWSR-j4rRt3<;P?lwGRi_mebt*fUf};!zwgrPoCyXUz~-1bJMu*`oNI5NGG2 z#TQDGPw_eI?uoZt0wPbyJSa)lbKs^#(}jY{{aI-KgYbOknWau zQ#WtXJpuW+95*9ZdMJ4x=e$l_dEcY+rdO?^VdJyVtlzs)gbN_s`0$NYl;FKo=UuPMuSM%H+^!f81%VAxxm7M~Wn9vOoro(ud_R=H+W2BH9-TS>n(Gu7H7ivnw8%Z+nFOUDL1iz7$RKHzr#h#3-eC zXd@{UNZ)b9X$1oxVl`1@xY`~r!?pAN`jf4*F+=4jCcCA>QzeZip3hHlRGE1E;)pAe zR5@$ZI8u^F$`PG9)SR;m^NX1iDtLv{LSi*hoK%irNI1>s~%g+MbxY?7-nl zBGHL!R;I5Gy<}Y*Kw|tI9h5`5t9f5#l+>REmGoy_6g7|y3y~XV9j4JTvv4f1v$5$Y zv-o&H?kL4EQ%k}@%-@_SsXJ0Ta!<$!5$5csTE6(D6CRMS!Kf*+(5cpvhthzrubA`TIv*V-rEeQU2_~aB z?+1hCvt5*NUZ|YUBCkTgMuMu|ia4R2(`ON8{r&y*S+dC;cq7iZ?xc3mT`jqJ{ox9) z$o=nAG6`|pc&D1-ZLGKpDKM0>+n(6a?yHA)*O|vB2D#G z`EVIGc%$SM*XjL;4bL!Zy*Y(h<)e9;P~+-3mEi=WamCi>_(PzGn1T=?ge{y;-CNQ#KBTsX6^&#hZOCg<6+Ic6aSOlHO_6 z+D{TIzkPJ<9`&CM7nl}pKgTobvv_5cKbX|YGP^`t@fRu7@-5j}k{16^y*JFo%KhC<&W6WFs|RWL&|&S?K^Cg(O*Z$N}%lDXq1ke#0<^-EP^w zp;-7}!%0t*8z$qRpBaWgTdcK&_vPvdAZZLc?MIKCJog~0BaM5orAq4!-jlpJy9f!2 zDN*jVcFa}mSEQIK?k2rbY&aJr!ZqICeI55J}ua^@{$wV`<+?dLMeY>zY+JA-j`&Qt@IC=>JA) zDVdQ#zxa{Gy3#M{N)sD4L?=R9_jnOrQNd?!!1krI72oGOlZ?YuWZzHVJE}M=p`c z7SNQ*^jU3{R6;jyk^VjJL;Fx3cH(z>MHv=`{6;>W9Cb)*o32M< zq^v|agv|W9Bo8TB4MK09P4;Dq*w2QSMeUzm>AeAZX)Jo|D+~__l$N0cON;Eb@IJ8K zjyfCyn*PCtw^2|~@JmD&1-)-DiPYstE!))hpN+^A3{*{ao+t zKU$rXzaWtL@XbDX(@+BnOlr{=h%NI16Eds#Qjy&TXTZQ!NfF#hMSo&Y$G9AnU!xXE zjlp{Zjw{T4l`TnHT4dGkJb&}qXJGdEt2FC*zBb8jGNIYDHNV5$zulcj`$+HZE5SbT zy;bShacoO9=q-Yjj_~*u3&BL${R;Ncq^h)Q63pzds#|ErB{Nx{5>>)59jAT;E^0U8im4{TfE7*(@eEnz7sWHUzZrIk7V!P`So82^|Yz zBdP)!_Zw$IK;mPt-mJ;2RMk*3u<`p^=UO+hRDI8T$$_yhO*v@o+w-mxw%S@R+&ZT7 zW{d)Vt=RT%s<`H3NL3{^{8Hw9r$IELe*MD{vE?MFx6&TP=ML`Gp~DMK^mfiF?}}U; zwXY}?Zpt6{?(QiaSfFEy8k(&JQm#resj*}Pl%zhy8VKPEEkYR4wIo7@I7R{<71A$W zpQl+=-b*|#|Me&MMQ3~=mJ_%FH6_0k;?0Y?(ySH1b=b1wQO+U0%f@yc&eG!#+W4!+ zybLpGUrUx}z;txrI_Q$OFiQs~Av@P5Qd&yJYR}C+VL7OSz>|gs%wYDQ_RvBQs=@9A zJHId^lOyADqltsxQdKq(y8sQ&J!Iw^F9ql9=v|5HrDTlB`6b7?Oh{Jvz5Lr@Bx-uQ zBWp5LYiI#iNNUX`jn0~c_XA7dL$w4T=&vme{?&1*)@xSXob;5Fd|?<+_-VRhOycH= z;_nKUUS_Au=#5k6-ljPcug%R6vf$*cVHI12y<++Ab8q?2Mwz{ReKn(WineGet))nz zq4KKW;>)6jdZfm#0G$Wzt|iWg@`29d zPaQe4F=MKLIB0%)Y=#Kp@MspUuS3Fd9#zwyRqe7IgvyPTQXTmCz1VMQ;tsacl^{W5 z0R+7JhZ-J@K94bB=}%7yX53ZLO~z}-)--jI<%#g)d`?~l3lt8YdU;CUG53{$4ln;_ zSq1*@gZDa@d?xIdZTObP0}0u)jg9pZy>brI7m@KsRgMQc{UPazWwPZY!rPd{BmCNu zP~VvPHC<#gxS3sP$|==%)U0AIztw&D)4C%g`go1e3CF=wgsOFxf8Qms`H}$Zsl2G! z2?^GsZNW>zh+)neZ@F$Z@4T^~c3LDyuUr1Un@FXovvXmwjZxD}t+S3VU2BL^@cSV| zth5a!Xls<`5@MyFccreh$r-|FuWQ_Nsz=``P<3blC25Z+ipt&{^$=V7hVSqI_0)w! zrbj}*GwkdY;{(1V{#wIVA$iDHPO!EMpYGb!5DEzsPZxt3e#A(iZ)4bRb*@)8VCJn0hx96X)Vfz&DZE7A zmzZdn1It$QLJLb^;0dSwC|%NBA<$9Dk<9wS2EK|$L-?24is~)3{t@VYL2}9Ef`(?C z!xKf25&eQC87ro5qy{b&w7n_sFxJe-^4(vxohlLuUC9m7W15zATZ+k*?0^NVjXFFjg_B5%X7=Ox zKCZ|H%k4!cq@_xXzOOs3IM$Wv>`Nn1@cqT0gmsC=g)5ns$6{|*Ze?**qny!hGi0{Y z=>GPEC;SWUGc~chJDF0I>@_hmv#|ofFEnl?y+4qD5~vV@evNHxEu-$aEQmC^sFVZF5?mX5l z(_UPLdwR9jrphH5q3S|jgDt(i8z}ibUw(=)WZ(i(f!B#gC<|@!kpT+TI2|DtI^JWe_t2yV}l^`5(! z-9;WN=0`C`j6}DY3mKC67w*^0`5`yq-yj!|H}|$Ah0-Nugd z`Ae+{Qz{(iC=lQkY36vLZ0k&j9;g31+uTwY!(tH#dlH3Ilo34ccU&IsBhclT-8(Wg zU5tva+A{V>i5gLUks!*}MxjbZzR%=dtp}GbAtUq+rIii_^w8tx0d$3%Kg-#DG=bhU zfo{zQY)0CoWuUt;>+O9S`pZpC8ucrRyX{a{tUXnGjvq1-O82U3B@v`YXgrM013bZ* zQ-w^w{!kcMi=vK!yvAF46uZWkblwzA0<0MaswfQYtA;S=?%XQx)gB^g{TBy8iy}GI zxj2Sem8J4@u=TKZdQD?VZ~g0J*k_WJv}1-H$N9MAY*(OV%R;19 z(V%W{^pdPbjqs>(*>;`12hk&5C6pN{qU`a_j%SLG*oZNjQB|9=N&U~F*t^_VNPT9( z8k)~mc%6%Kdz>Jb$dUbMa5+ND zY?|y0&CRJ5{5m-M_-M89*Y`>DVgjzu)6>5W)k<%+r)j;IC)TYr!gtpR>EUugG71)s z2nIw{@JH0t%vz*M>e5MRf>Y9%a8o)qn@rk(bK(Pb63b8}A^Wfc!MAtJ9U!(2G)9;f z4!MK0H0NlL4P04>~;*+~HhZfYn z1(B9`+{)b~Hxb2!2{uiai&kCUo%d$SKHzs^kBGvDA#92|HuB898T*5MqD@?_)u)v& zx*w-qpdK-N76H1)a}r;X2b(C)-6H*11`xBqLn2C0q#F~Sn>(vwUVXfmC=^2B0{WxB zEh3Afh<-v`Tdu44MkRkYn;Iij+U2rEolT^oT(ZR4;#km`WUZe0u>7pvLP8xb1YGO+ znccO)1|m8HPKT!Et#rTjFVhRcQ*EhB=e%Z~Wr^pFwi?^bOW~e91of1eXLx!k%^{*+ zU9Ip|M50hv#7P)L?_DY?DvSBBnOU)0Z;qdps2tPB1C2Q;W=EL7CVSDIW5{0mFPv9i z+1en}mEfsoy*xJF)#=fVDT>hFX$EGyG%AQ6noag@qZv68NOp34U{J*Gywb3))t|du zzYP*sMM{`gZSe?_O*VUJoz{jtP8eF1_BI{oI(Cs`1O$YXOKzf-L=d$&@v2v=O7+9I`KJOBcX-+uI-J-EkDmJn4Ui5!|)*Dp|XQ|YMl@! z^Y}wwL^{bzSU^DKfV>jY3982nmCerdqa)B^Ex!k8GLBgP`K^ynjvRM^G~;TMve*OK zyQ}`z>I#m_JhqmzwfSt^H zxt!0PEb9xx=20PH(#z8NgTgUS@^LZ3y7tThyLah>ir{5u^=VME`%K9Uc7Gq@xXACc zFbywzj!6qXVjzZHtyb?Ioa6PEKevL#0^g$>yRd-n*_GQFZv~on|SW zc;MeCQ4MZ<8JWjI?p;WTUm(eIeKAcY06hn3Z7MN3Z)f)KdS*#pxUmA)#!6|E$VcD{ zWPHpc_${Ez2cubeR)RL-&INxu4-(eGl11u4z?0f)+Sbgt=;!Ab;1q7!gbCTfgro^O zutS4P>gw?wMF0?sW3V>!Tkiq|X;`#Oo^7O3g9@2mrfzh9zQzy7TGutqXw3BdBqqfI zP1y7jx`Uu7_>9}5#r7A{U9A_Z-4tElF0R`4;kcE-feblE% z&|s-GL3Q4?b;OfO2SbE|$rS<|=y~bY4JjN_Zq~Wb4AKmthqCw-h8abCXSG;zGKoGhXUCPr%ui|f3SomZU;DD7z_g;;E+ z2cbI=+zg-l!M|46LT>u~`L&%VF)7FfhivsCA*+?9fQp>l+`YuIt`VWmo#KhI#C$b3GRHAMz0QUZqt?iexio013^C(kd%MH7e9l&)AnhBJZLV(EBm!G4+E~J? z{3Vv|N>g9JfOOJjP>^=XbPhqRL!WbcmQe%pFMjVsgNHST#{EBb*`hXFLFyX&p_Z?5 zvzD6GuZTCpg4&8u;m*LCo-%b$LMi4&S4Zn2`o-c#GpRg0AA5~&RFYN5= zX?OHIIT246c_!849#^`IM-1})m+Ai8fe@s&| zQ&RT@{TSCdl4jVnV~5zNi`TL53CrJUb_c#cl5rv@)${#W5+OGdrYT zDzZLqW)rgO_ezG{Yqq?}IC8CxopeeWA|&crn_goy(_?Uqw#BJ%dZ*02i3N#B>~0^7 z4Ac#?-8NZV*Yc80Mi(-F?&Hp?SDTo$nNQ~KaH)`C+S?1B#dD62C!iq?iv({b^bcpC z^x#a-!N9}_r#4m#dWgeNW+~`hH$yiZqBVTmI56A7(xu%F*p$VY=;q5OUFho-fhPH%y|3M_j|wTPAxrD+(II_zNNM8^X!-@{5`b6Rx|T~5&S91 zv^QtT{^RpOUNtWo!zxV?kxOxPD@_v_Pm4rhjA)Z_wHNclE}e$OSGIcx#{-sZ;y-|x z;)P5yL_pTd;70a%Lsx44u`?nG3^6KVef>5Q!Q|;k@QhTofOe{XLuE! zzXpnys6}L#RN}C8KdcYQVOYNyVPqcwLrykX*h(C!!Z{D!56)=V9;cS^ zW_RMLwLQ?F_28B9jbH`-J2$nukH1xZzcj_@N8MzVF<*qTP&3E>~V6lx1SPg(r-fAtAOX%_?D>=*`^x{3FwTlz0S#ALeslS z2M-oK=}LoBVeND%!yzdt{vO`Bk9zrP*DYS}@8&4AQ8UnwQ_E0{F|x4LIk@&`IMQx# zA1$3wwz;`GJ|u36d5#tRIDg_w?aj`5x?{I6se@B8q^)J(IXM@t=St`EIWc!6pY>-a z&a16bo3^}&gPoJvAyQ4rJf+odK4_bB6mbSk$Ju7o3Ms)DC#P(hg0`+sWopXE*fIw# zi5`14IRzThFD7ILodliN(b_r=RWJv2)rhFX3AG45{);|e-yE%0dF2)O_*`P#CCtG= zyWsWhfpHE=tP(C-ZuuIVH(lH=x)@s3?bwP>DdUixzF#wyH)@^TxR>JLbd2HHG&x2w zcCmqK$Bs~yRoJzZD*)j+Kh|ohM@bnjb9++%eVe5V(vB+vq2NKWUb~iiXLb5?%G>Cq zjY?1P-2%d}eY}BTn#tgINsA)roVojlR`Mnv`;R_Rmu8$vZ-q7x%0(#!WZ~;%e%m9*&vLuglhI?odrOkHJst5NJE0N` zZK&0{FgO^7Fn_qiYWFFZ#r&c|txxIt;(&0tS8F7SQQz=|xw!4iUs&ahHg?}&6f$%A zW#!3Z9=1d|s*V;7_AocpYQ9Ak4mtQ*30?GLUfMK-36r-+OL5|Ub%ATcc4B@bl?o7A zm=D&#z2hlMS{SlqGH5zn;ESMD5dPs3>P-h0?L3m=rebWIs%ksv@-}H59DPbz5IhqT zBOCc{L4&SfY_=RY9Q?Imm(wFqTdVDyfjZRwJn>64ws_f^<-Bw@4T$4JAL7I2_Vsps zQpFg|ch_b;H}tOW)vIju_i~PFG5zI0Y*?wCIU_Sw+5bgc-RIZ-u$X1R*DHu1bY2sP za@%Mc1JOjUbkN`>^mOwWMD|&=!`QX#tn2>dXITV~rhVPz+D(Ye&ili;w zE8|3OEtn=ozx66ni|O#4eaiABS@Z_k(v;D`jew5wWJ_j-5FwF_u?<~ z*QDKYlxd?o?`2Z;RHWkJa z@=N+C4fp`F=jxtU;!;oLFUF=VHJKtOcnr4nxFtojw$wD@m$Dd)@98cQ41A$wfK%aT z^(5kjQ^5d=@-60&q_Q&I2DQ!E1y+Wx=r<4pk;EYmIskN020)jKN5wQf!HsT=hGF5L zeO@^hAYEu#hv$&FQcMGvO;JV~2z{(Z|_mYeTELH?IrnE&z+Xw{P8 z(HQ_#3y-Oo4jsRmYoHAhw3X+*;RbM?GSD@6^h8NlUR)W9p1Gqn-pVT1PB#L;sPAS^ z>wBP`EevuiUqnfcwl1id90SPiWT%3QG1D-|!K$b* z1o7tG!>1nTKME7hJbcIwplE94PUL6#zR3t`V+F1UFX*C%HG)g;?nJR7+jk4QU$CK+ ze+pFwpmDYb_e!3FhX-6F>citcWek42Ae41b$nJ+axiR(E*wi5n3ctm^f6)M6un)zL38UCP8 zbaL3}^uX1dyn*}%vqrik<}JrSM)&WLDgo7ZL35oS3|$GdH>PC}fM;#qaUvG}vw`mlS1^{T^oI_c)1? zBVFxnZ4BGr$A`<-T&xrSMr)H{1sctRFJBA?9B!Z$)2F`PR8X2ZU3BZ}8E4se`L~PP zp2dsCSFbu?!gaxh4bz|m?nq;TA%eJ4J5x)Z>3_ZgRm{i_c(ow}5}|nZ$!bJoqL$)Yw~8(2_SXnA>o z&mXMC#}%w)9*HKP4Ao608t;Lud)Ap;plrHye}p)c`Qb*CNw8n3OBX38+`0r198T0$ z{8s5VStwRk)(;&6B)iVK-}o1{*az9bLUcWh4mYrUx)N#>>gK z-yZ^Yg5wlz;iE?{cHQ-39NX0Vn*f_tt_lDd4p1RlsMq=5P5{b=Nh+F+_SDfxpe$u& zatnFjbId0Mf6%790)xySIeH85eT;sJ5*GGI21tYD2o}`spF+O^@n<_{SQ7E56o_&l z^ILf!0&l<|cV8B|Is+(SI!o>kZj2k;02oL6X^bZH3Uzf%@>REAWr1-#>A{kf!@}?R zAEN1|QntRlrgID|M8@U@;yk9|gAU z*-xoZ?o<50xL7#81^~r{x{oq|BZ2l37bpAFIx3XVu>PGe09&d6gZQ=D-GDZbN`qK*b_P61Mqrw5 zS?UKl0t~=J{Y5Ij756C`F#UPu*)vDOQ~@F}dX&j2^9D)eH;KO1cr)ZhnmcaP{D4@q7Hy?3 zWj+K0v+oGr@dE;R3k(={)?i}fRx?go6hN23O2U-E^haZB=x6|}$%38V*CkR}0gN*b z2&NwaoZkH5qt|YOJ=ME#T>;2_1`v&p1uHKD;ALKS&b_1iv8lpTJAH)q0-!8$o^DG@ zs!<2Hz`yVeJ_KLtc(jn=?e~UY_Qr^NoB)V*543ym-oaK$#g%P#MfUypHs?=)>1nK8 zLX}gf&xk&2^n#8y7^jvN%mE;cB!G7YDCWt8yE-Ro!peB3(f zpx+t2h`oajLf>IHGoxluaD)eZ@1H`cK>IyCfAv73_3#zP(1hX+cuGpj(Fd%W%J0o+ zNX1KjT}GQu1^cj60E!Z`pws$onDMv`euAHAqi|z00ajqjw;RYwu2z(GhN{ z;+lSPGzUN(S5>06fn?P0iRYQIVv0uR5?@bn@HEud*H~IwDofEE&;qgf2J- z0QP4+zL7!I_IHdAhU=0&<-hrctElDN~Fb18!)m zD!qD=;3}NN0V__7;3y`&hI5~yr(r$fLxuN$NxtGfVIsoZ#B%!v^1)%65~dzIXF|VL zBINMTcjuFYD`wy_x@hNg;>h)qED-N)Oxt9gUslxDg#ZKK##+x>wU|gcmQ9?JzT?1{In=cMAz7Ur7PjaPoa;1-$sA!5(|JW zvH-bqyI1zu$bb=jy=CS%WjQ!DC+#GDVv%=AYfc!eD@+#|lDtnRqig)h7=2K*rbXK< z5ZhOTvOYI(J02;{M``b>Sb`f&c362i?_6lk{Pk3?oip+E&D>7={1xUqP>xJt)+e%Q;nR~7-giH|F}*aQ+p_iPUjMNN??(R>=cQM` z!-9}oN9P=pPPCJ6o1A2Q6Jv78^q^=lqe)pUgp#=w$8(`s0{DFn$L74B%}g4 z-SeY$E8X5s*KdcOMwoRjnA8FmTI$L2h+78`{2ZlHBgNjUo4o@Ff|vvaBY>&6m9K1S z@}^Q&UR~_DccP#+U}lBZo`-#wVt!#~SgJU9K4E^iG~ zNcGd*_%Nvs-Fol*#T}<8sv&V8<7a@RM4x&A0I%LETzt+k*GzMod6;iM1#inta2n#C z0oe@$zo*}Gyl%aF2khC-`Bzi%J4prc1C38|wieC{o1l`yq!76ev4S1s!FJtB2b8{{ z{*If?IAD4B0KN(%D6|6??=RYY4M{D%v9dV)5YX>Rhwx`q;R?bhABfH$mP=#yH?ZL> z*wRnO`e8|2d2#ciN3W@I^YcS2Ev;@@7V?QmUI#QPIS+Qdsk|e*&ESS1m8X%Px$mRz zXn~HnFV_#}Vq?#Pr8Vd$E+oGZ%&B$QW_i2ga+>P#j|l>15&>N^K1OySdV70aGjox; zBoX-1M4(VBaS&eY<#@lqr-e$DHq_I1h4xer`7mp8&&f1k+|{>#aB4k#`sg1sNP68S z7x2>D3 z>Fe3p@a(l2ANvSy$D`6U8d=!D-Uq9a66J~|+=_&@Hk$Yp+vKhGgK~3nQnr&567D9J za5FSV1`MgR3N{xP7UotI>lUgjOkR3$?OrFLgq&jaG%@JV9v?f=Q1&|8L`7~3AD^nm zjrzMUDX{2CBtBUFZ@ww2&o$ma)y6(mKQZC%?d#W{gqvicw)U7IM#C&+uy_Db7E&B7 z|BWwDP#^MAeNlZ>i1pso|HdfGZ<(xEQ3J{Fs3_*;ZyYCtR_;LP|H?7=IS5i~pzC4Y zGS?fdgg3 zr_Tl=BY;iQM3s~vN=ncaEiSdT)>hCK4bBL*|8LD2$Qz85Qt8+Jfg$_--$LJ=esSJ{ zJ<%<{_n!*MU;gp+ClIgwm7V9$#_W7BH+o!?mHUu{uMhe=yD8-m0T~znJI` zF34EgJAk{*`en79g}a)rSJX<$G8G%m(D><={yVQOCJhrSQ|r4L6D!h`nW*WC%l%WU zDS=aLQCL)O>it$hmQQg1f9KT;<4|v2I<+!^YImD%s*ej)%%)H*i0p$8ic6xpX@wv) z%2@;d&TCORq_bjwRyQ4UUiI&u*59@f{1BQ%^YH_EW?bR_+@k}c@}BYK?-%hWX;OZq ztbORnXjZ_s!@m?2hNIVp&KN!Z^&g7lU&o)j^!5Iz$BMb;zuE@nLts7{^(!=gx02rr zv;y5Zr+{UA5&b_>fxpgo5yU*u`}BAImG~;Z%76648PgCT`7h_Aqdn(z?DB`Be^9l* z&hyvtH%>n+TdMIX<^S_Pe!s|9kHCDPd}l*{|8@R6Y-kqHPlfGe?4SSfhee(~^{`C1 zjF#v3!~fmZ{-3u8|3RU8>17tawHD=Q4jH^-_n5iJlv{h@-+9Gq z7H#hZ0d=3>BhLcGH%+qfm*)hw>uvde$aXCoM-39a_Q`cy*P{26rQ8JyxgkKbZ3W;G_GmJvjPbdjO6D9p(Qkg(|eXgjnu8 zTDh{P-Ihx5W3$p|bnEI|7@5;3vrIfTt=jPKyw=)p1~ijg?yNCk_~poG zQo#0u|N002^$-3Z#S8ye+Jpa~(|HBwr2tBVTS1hLYwPmbRxdlGOZ<$@*fZ%N#qOc< w1&05|>tjPp*`I#;iC*>Ab$!F_;)6rUI;Xjm`fs~|KmMe8TkBTIjr))P7kb*kwg3PC literal 0 HcmV?d00001 From e9ddffd761392cb4baea8f6b711d2e99712d57db Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 22 Dec 2025 16:45:39 -0500 Subject: [PATCH 110/152] Add LOAD Charts & Diagrams to README Added LOAD Charts & Diagrams section with links to files. --- README.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/README.md b/README.md index 1aa865b6cf37..3c6d483ecd98 100644 --- a/README.md +++ b/README.md @@ -5,6 +5,15 @@ This repository contains LOAD Robotics' robot code for the 2025-2026 FTC season This repository contains the public FTC SDK for the DECODE (2025-2026) competition season. + +## LOAD Charts & Diagrams +### Our Filestructure +[File Structure Flowchart](File_Structure.png) +### Robot Control Scheme (Pre December 6th) +[Robot Gamepad 1 & 2 Control Charts](Robot_Controls.png) +### Robot Wiring Diagram +[Wiring Paths and Labels](Robot_Wiring.png) + ## Welcome! This GitHub repository contains the source code that is used to build an Android app to control a *FIRST* Tech Challenge competition robot. To use this SDK, download/clone the entire project to your local computer. From ae16d8364d3e9213d21fb042a11a39be2d901da7 Mon Sep 17 00:00:00 2001 From: NotABitcoinScam <152728412+NotABitcoinScam@users.noreply.github.com> Date: Mon, 22 Dec 2025 16:46:41 -0500 Subject: [PATCH 111/152] Update README to include image syntax for charts --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 3c6d483ecd98..ee9040542400 100644 --- a/README.md +++ b/README.md @@ -8,11 +8,11 @@ This repository contains the public FTC SDK for the DECODE (2025-2026) competiti ## LOAD Charts & Diagrams ### Our Filestructure -[File Structure Flowchart](File_Structure.png) +![File Structure Flowchart](File_Structure.png) ### Robot Control Scheme (Pre December 6th) -[Robot Gamepad 1 & 2 Control Charts](Robot_Controls.png) +![Robot Gamepad 1 & 2 Control Charts](Robot_Controls.png) ### Robot Wiring Diagram -[Wiring Paths and Labels](Robot_Wiring.png) +![Wiring Paths and Labels](Robot_Wiring.png) ## Welcome! This GitHub repository contains the source code that is used to build an Android app to control a *FIRST* Tech Challenge competition robot. To use this SDK, download/clone the entire project to your local computer. From cf708cde19442cf79bdb81d58a3310d627422464 Mon Sep 17 00:00:00 2001 From: Professor348 Date: Mon, 22 Dec 2025 17:46:59 -0500 Subject: [PATCH 112/152] Added a few new static variables for Panels tuning --- .../Main_/Hardware_/Actuators_/Turret.java | 4 +++- .../Main_/Teleop_/Teleop_Outreach_.java | 21 ++++--------------- 2 files changed, 7 insertions(+), 18 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 4529d7032eda..888e111241c4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -46,6 +46,8 @@ public enum flywheelstate { public static double flywheelSpeed = 4500; + public static double upperHoodLimit = 260; + public void init(OpMode opmode){ rotation.init(opmode, "turret", 145.1 * ((double) 131 /24)); //Previously 103.8 flywheel.init(opmode, "flywheel", 28); @@ -99,7 +101,7 @@ public void setGateState(gatestate state){ * @param angle An angle in degrees that is constrained to between 0 and 320 degrees */ public void setHood(double angle){ - hood.setAngle(Math.min(Math.max(angle, 0), 260)/(360*5)); + hood.setAngle(Math.min(Math.max(angle, 0), upperHoodLimit)/(360*5)); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index 50167883006f..c793e9ce39c8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -64,8 +64,6 @@ public void runOpMode() { Robot.turret.rotation.resetEncoder(); } - double hoodAngle = 0; - // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); @@ -91,24 +89,13 @@ public void runOpMode() { telemetry.addData("Turret Motor Power", Robot.turret.rotation.getPower()); telemetry.addLine(); - double increment = 2; - if (gamepad1.dpad_up && hoodAngle < 320){ - hoodAngle += increment; - }else if (gamepad1.dpad_down && hoodAngle > 0){ - hoodAngle -= increment; + if (gamepad1.dpad_up){ + Robot.turret.setHood(Robot.turret.getHood() + 2); + }else if (gamepad1.dpad_down){ + Robot.turret.setHood(Robot.turret.getHood() + 2); } - Robot.turret.setHood(hoodAngle); telemetry.addData("Hood Angle", Robot.turret.getHood()); - telemetry.addLine(); - telemetry.addData("Gain", Robot.intake.color1.getGain()); - telemetry.addData("Distance", Robot.intake.color1.getDistance(DistanceUnit.INCH)); - telemetry.addData("Color", Robot.intake.color1.getNormalizedColors().toColor()); - NormalizedRGBA colors = Robot.intake.color1.getNormalizedColors(); - telemetry.addData("R", colors.red); - telemetry.addData("G", colors.green); - telemetry.addData("B", colors.blue); - telemetry.addLine(); telemetry.addData("Robot Pose X", Math.round(Robot.drivetrain.follower.getPose().getX())); telemetry.addData("Robot Pose Y", Math.round(Robot.drivetrain.follower.getPose().getY())); From f7f2012cc8021300318574078ae87bf7c510d088 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 23 Dec 2025 14:01:46 -0500 Subject: [PATCH 113/152] Added a RetryCommand example to Auto_Main_.java for later reference --- .../teamcode/LOADCode/Main_/Auto_/Auto_Main_.java | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 03b75b9437e4..8990861102b2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -6,6 +6,7 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.skeletonarmy.marrow.TimerEx; +import com.skeletonarmy.marrow.nextftc.RetryCommand; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -17,7 +18,6 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import dev.nextftc.core.commands.Command; -import dev.nextftc.core.commands.conditionals.IfElseCommand; import dev.nextftc.core.commands.delays.Delay; import dev.nextftc.core.commands.delays.WaitUntil; import dev.nextftc.core.commands.groups.ParallelGroup; @@ -192,14 +192,17 @@ private Command Leave_Near_Launch() { } private Command test_Auto(){ - return new IfElseCommand( - () -> time.isLessThan(5), + /* + This RetryCommand allows for a command/set of commands + to be run as many times as you want unless the time is + less than a given amount + */ + return new RetryCommand( new SequentialGroup( ), - new SequentialGroup( - - ) + () -> time.isLessThan(5), + 10 ); } } From 8cbe5f3d0e7f22187a5c63715b1e66c0f69fcfa9 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Fri, 26 Dec 2025 19:56:48 -0500 Subject: [PATCH 114/152] Integrated Auto-transfer into shooting state machine, and made preliminary auto-zeroing system for turret rotation. --- .../Main_/Hardware_/Actuators_/Devices.java | 13 ++ .../Main_/Hardware_/Actuators_/Intake.java | 3 +- .../Main_/Hardware_/Actuators_/Turret.java | 19 ++- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 15 ++ .../Main_/Teleop_/Teleop_Outreach_.java | 8 +- .../Main_/Teleop_/Teleop_Tuning_.java | 134 ++++++++++++++++++ 6 files changed, 184 insertions(+), 8 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Tuning_.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java index 0162b89399f8..194b17122755 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Devices.java @@ -7,6 +7,7 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.DigitalChannel; import com.qualcomm.robotcore.hardware.DistanceSensor; import com.qualcomm.robotcore.hardware.NormalizedColorSensor; import com.qualcomm.robotcore.hardware.NormalizedRGBA; @@ -318,4 +319,16 @@ public double[] getDistances(){ return new double[]{sensor1.getDistance(units), sensor2.getDistance(units)}; } } + + public static class REVHallEffectSensorClass { + private DigitalChannel sensor; + + public void init(@NonNull OpMode opMode, String sensorName){ + sensor = opMode.hardwareMap.get(DigitalChannel.class, sensorName); + } + + public Boolean getTriggered(){ + return sensor.getState(); + } + } } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 3ed7dbf88de4..f56721bef0cf 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -1,12 +1,13 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; +import com.bylazar.configurables.annotations.Configurable; import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; - +@Configurable public class Intake { // RESET THESE TO PRIVATE AFTER DECEMBER 6TH! private final Devices.DcMotorExClass intake = new Devices.DcMotorExClass(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 888e111241c4..5f728aaf38e8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -23,6 +23,7 @@ public class Turret { private final Devices.DcMotorExClass flywheel2 = new Devices.DcMotorExClass(); private final Devices.ServoClass hood = new Devices.ServoClass(); private final Devices.ServoClass gate = new Devices.ServoClass(); + private final Devices.REVHallEffectSensorClass hall = new Devices.REVHallEffectSensorClass(); // Turret PID coefficients public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.06, 0, 0); // 223RPM @@ -44,16 +45,24 @@ public enum flywheelstate { } public flywheelstate flywheelState = flywheelstate.OFF; + /** Controls the target speed of the flywheel when it is on */ public static double flywheelSpeed = 4500; - + /** Controls the upper software limit of the hood */ public static double upperHoodLimit = 260; + /** Controls the speed at which the turret will zero itself */ + public static double zeroSpeed = 0.2; + + // Stores the opmode object for later access + OpMode opMode = null; public void init(OpMode opmode){ + opMode = opmode; rotation.init(opmode, "turret", 145.1 * ((double) 131 /24)); //Previously 103.8 flywheel.init(opmode, "flywheel", 28); flywheel2.init(opmode, "flywheel2", 28); hood.init(opmode, "hood"); gate.init(opmode, "gate"); + hall.init(opmode, "hall"); rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); rotation.setDirection(DcMotorSimple.Direction.REVERSE); @@ -159,6 +168,14 @@ public void setFlywheelState(flywheelstate state){ flywheelState = state; } + public void zeroTurret(boolean stopIsCalled){ + while (!(hall.getTriggered() || stopIsCalled)){ + rotation.setPower(zeroSpeed); + } + rotation.setPower(0); + rotation.resetEncoder(); + } + /** * Updates the flywheel PID. Must be called every loop. */ diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index fff9cfefe75f..c92f591fa3a3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -74,6 +74,9 @@ public class Teleop_Main_ extends LinearOpMode { // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); + // Timer for the shooting state machine + TimerEx stateTimer = new TimerEx(1); + @Override public void runOpMode() { telemetry.addData("Status", "Initialized"); @@ -136,6 +139,11 @@ public void runOpMode() { telemetry.addLine(); telemetry.addData("Intake Mode", Robot.intake.getMode()); + // Color Sensor Telemetry + telemetry.addLine(); + telemetry.addData("Upper Sensor", Robot.intake.getTopSensorState()); + telemetry.addData("Lower Sensor", Robot.intake.getBottomSensorState()); + // System-related Telemetry telemetry.addLine(); telemetry.addData("Status", "Run Time: " + runtime.toString()); @@ -299,9 +307,16 @@ public void Gamepad2() { telemetry.addData("Shooting State", "OFF"); return; case 1: + if (Robot.intake.getMode() == intakeMode.OFF){ + stateTimer.restart(); + stateTimer.start(); + } Robot.intake.setMode(intakeMode.INTAKING); Robot.turret.setGateState(gatestate.OPEN); telemetry.addData("Shooting State", "STARTED"); + if (stateTimer.isDone() && Robot.intake.getTopSensorState() && !Robot.intake.getBottomSensorState()){ + shootingState++; + } return; case 2: Robot.intake.setMode(Intake.intakeMode.SHOOTING); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index c793e9ce39c8..06350c35c2c9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -34,10 +34,8 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.NormalizedRGBA; import com.qualcomm.robotcore.util.ElapsedTime; -import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @TeleOp(name="Teleop_Outreach_", group="TeleOp") @@ -59,14 +57,12 @@ public void runOpMode() { LoadHardwareClass Robot = new LoadHardwareClass(this); // Initialize all hardware of the robot Robot.init(startPose); - - if (gamepad1.guide){ - Robot.turret.rotation.resetEncoder(); - } + Robot.turret.zeroTurret(isStopRequested()); // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); + Robot.drivetrain.startTeleOpDrive(); // run until the end of the match (driver presses STOP) while (opModeIsActive()) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Tuning_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Tuning_.java new file mode 100644 index 000000000000..61d79094d429 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Tuning_.java @@ -0,0 +1,134 @@ +/* Copyright (c) 2017 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; + +import com.bylazar.telemetry.PanelsTelemetry; +import com.bylazar.telemetry.TelemetryManager; +import com.pedropathing.geometry.Pose; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.util.ElapsedTime; + +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; + +@TeleOp(name="Teleop_Tuning_", group="TeleOp") +public class Teleop_Tuning_ extends LinearOpMode { + + // Declare OpMode members. + private ElapsedTime runtime = new ElapsedTime(); + private TelemetryManager panelsTelemetry = PanelsTelemetry.INSTANCE.getTelemetry(); + + // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. + private final Pose startPose = new Pose(88.5,7.8, Math.toRadians(90)); + + @Override + public void runOpMode() { + telemetry.addData("Status", "Initialized"); + telemetry.update(); + + // Create a new instance of our Robot class + LoadHardwareClass Robot = new LoadHardwareClass(this); + // Initialize all hardware of the robot + Robot.init(startPose); + + if (gamepad1.guide){ + Robot.turret.rotation.resetEncoder(); + } + + // Wait for the game to start (driver presses START) + waitForStart(); + runtime.reset(); + + // Begin TeleOp driving + Robot.drivetrain.startTeleOpDrive(); + + // run until the end of the match (driver presses STOP) + while (opModeIsActive()) { + + // Pass the joystick positions to our mecanum drive controller + Robot.drivetrain.pedroMecanumDrive( + gamepad1.left_stick_y/2, + gamepad1.left_stick_x/2, + gamepad1.right_stick_x/2, + true + ); + + // Color sensor telemetry + telemetry.addLine("COLOR SENSOR DATA"); + telemetry.addData("Color Sensor Threshold", Intake.proximitySensorThreshold); + telemetry.addData("Upper Sensor Array Triggered", Robot.intake.getTopSensorState()); + telemetry.addData("Lower Sensor Array Triggered", Robot.intake.getBottomSensorState()); + + // Controls for turret rotation testing + if (!gamepad1.x){ + Robot.turret.rotation.setAngle(0); + }else{ + Robot.turret.rotation.setAngle(180); + } + + // Controls for hood testing + if (gamepad1.dpad_up){ + Robot.turret.setHood(Robot.turret.getHood() + 2); + }else if (gamepad1.dpad_down){ + Robot.turret.setHood(Robot.turret.getHood() - 2); + } + telemetry.addLine(); + telemetry.addLine("HOOD DATA"); + telemetry.addData("Hood Angle", Robot.turret.getHood()); + + // Controls for flywheel testing + if (gamepad1.yWasPressed()){ + if (Robot.turret.flywheelState == Turret.flywheelstate.OFF){ + Robot.turret.setFlywheelState(Turret.flywheelstate.ON); + }else{ + Robot.turret.setFlywheelState(Turret.flywheelstate.OFF); + } + } + Robot.turret.updateFlywheel(); + telemetry.addLine(); + telemetry.addLine("FLYWHEEL DATA"); + telemetry.addData("Flywheel Target Velocity", Robot.turret.flywheel.target); + telemetry.addData("Flywheel Actual Velocity", Robot.turret.getFlywheelRPM()); + panelsTelemetry.addData("Flywheel Target Velocity", Robot.turret.flywheel.target); + panelsTelemetry.addData("Flywheel Actual Velocity", Robot.turret.getFlywheelRPM()); + + + // System-related Telemetry + telemetry.addLine(); + telemetry.addLine("SYSTEM DATA"); + telemetry.addData("Status", "Run Time: " + runtime.toString()); + telemetry.addData("Version: ", "12/26/25"); + telemetry.update(); + panelsTelemetry.update(); + } + } +} From 1cbec0a8d8b97ff318c9607c4fdc8d4dc1f4a9e6 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Sat, 27 Dec 2025 20:39:21 -0500 Subject: [PATCH 115/152] Adjusted aimbot update function to pull the alliance directly from LoadHardwareClass.java --- .../teamcode/LOADCode/Main_/Auto_/Auto_Main_.java | 14 ++------------ .../Main_/Hardware_/Actuators_/Intake.java | 2 ++ .../Main_/Hardware_/Actuators_/Turret.java | 11 +++++------ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 7 +------ .../LOADCode/Main_/Teleop_/Teleop_Outreach_.java | 10 ---------- 5 files changed, 10 insertions(+), 34 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 8990861102b2..263851d0d12f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -113,21 +113,11 @@ public void onStartButtonPressed() { @Override public void onUpdate() { if (turretOn){ - switch (selectedAlliance) { - case RED: - telemetry.addData("Aimbot Target", "RED"); - Robot.turret.updateAimbot(Robot, true); - break; - case BLUE: - telemetry.addData("Aimbot Target", "BLUE"); - Robot.turret.updateAimbot(Robot, false); - break; - } + Robot.turret.updateAimbot(Robot); + telemetry.addData("Aimbot Target", selectedAlliance); } - Robot.turret.updateFlywheel(); - telemetry.addData("Path", paths.farStart_to_farLeave.endPose()); telemetry.addLine(); telemetry.addData("selectedAuto", selectedAuto); telemetry.addData("currentPose", Robot.drivetrain.follower.getPose()); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index f56721bef0cf..ef3a5338ea8e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -111,9 +111,11 @@ public void setTransfer(transferState state) { } public boolean getTopSensorState(){ + topSensor.threshold = proximitySensorThreshold; return topSensor.objectDetected(); } public boolean getBottomSensorState(){ + bottomSensor.threshold = proximitySensorThreshold; return bottomSensor.objectDetected(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 5f728aaf38e8..0cd31300a4ff 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -90,11 +90,10 @@ public void updatePIDs(){ } /** - * @param robot The pose of the robot, gotten from PedroPathing's localization - * @param targetRedGoal Set this to true to target the red goal, otherwise targets the blue goal. + * @param robot The robot object in that opmode */ - public void updateAimbot(@NonNull LoadHardwareClass robot, boolean targetRedGoal){ - rotation.setAngle(calcLocalizer(robot.drivetrain.follower.getPose(), targetRedGoal)); + public void updateAimbot(@NonNull LoadHardwareClass robot){ + rotation.setAngle(calcLocalizer(robot.drivetrain.follower.getPose(), LoadHardwareClass.selectedAlliance)); } public void setGateState(gatestate state){ @@ -136,9 +135,9 @@ public gatestate getGate(){ } } - public double calcLocalizer (Pose robotPose, boolean targetRedGoal){ + public double calcLocalizer (Pose robotPose, LoadHardwareClass.Alliance alliance){ Pose goalPose = new Pose(4,140,0); - if (targetRedGoal) {goalPose = new Pose(140, 140, 0);} + if (alliance == LoadHardwareClass.Alliance.RED) {goalPose = new Pose(140, 140, 0);} return Math.toDegrees(Math.atan2( goalPose.getY()-robotPose.getY(), diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index c92f591fa3a3..cb838d472fac 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -48,7 +48,6 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.flywheelstate; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.gatestate; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.Alliance; @Configurable @@ -260,11 +259,7 @@ public void Gamepad1() { public void Gamepad2() { // Turret Aimbot - if (selectedAlliance == Alliance.RED) { - Robot.turret.updateAimbot(Robot, true); - } else if (selectedAlliance == Alliance.BLUE) { - Robot.turret.updateAimbot(Robot, false); - } + Robot.turret.updateAimbot(Robot); //Intake Controls (Left Stick Y) if (shootingState == 0) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java index 06350c35c2c9..c136b904818d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Outreach_.java @@ -75,16 +75,6 @@ public void runOpMode() { true ); - if (gamepad1.x){ - //Robot.turret.rotation.setAngle(180); - }else{ - //Robot.turret.rotation.setAngle(Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true)); - } - telemetry.addData("Target Angle", Robot.turret.calcLocalizer(Robot.drivetrain.follower.getPose(), true)); - telemetry.addData("Turret Angle", Robot.turret.rotation.getAngleAbsolute()); - telemetry.addData("Turret Motor Power", Robot.turret.rotation.getPower()); - telemetry.addLine(); - if (gamepad1.dpad_up){ Robot.turret.setHood(Robot.turret.getHood() + 2); }else if (gamepad1.dpad_down){ From 07ea660e18cdcd71503196add474ae4a1fdd1201 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 29 Dec 2025 11:26:35 -0500 Subject: [PATCH 116/152] Wrote wrapper in Commands.java to autoshoot all 3 balls using the proximity sensors, and swapped old shooting sequence in auto for that command. --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 38 +--------------- .../LOADCode/Main_/Hardware_/Commands.java | 44 ++++++++++++++++++- 2 files changed, 44 insertions(+), 38 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 263851d0d12f..d05c0b60b9d1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -10,17 +10,12 @@ import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; -import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import dev.nextftc.core.commands.Command; -import dev.nextftc.core.commands.delays.Delay; -import dev.nextftc.core.commands.delays.WaitUntil; -import dev.nextftc.core.commands.groups.ParallelGroup; import dev.nextftc.core.commands.groups.SequentialGroup; import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; @@ -133,21 +128,7 @@ private Command Leave_Far_HP() { turretOn = true; startPose = paths.farStart; return new SequentialGroup( - new ParallelGroup( - // Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), - new Delay(5) - ), - Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), - new Delay(2), - Commands.setIntakeMode(Robot, Intake.intakeMode.INTAKING), - new Delay(1), - Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), - new Delay(2), - Commands.setTransferState(Robot, Intake.transferState.UP), - new Delay(1), - Commands.setTransferState(Robot, Intake.transferState.DOWN), - Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), - Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), + Commands.shootBalls(Robot), Commands.runPath(paths.farStart_to_farLeave, true, 0.6) ); } @@ -161,22 +142,7 @@ private Command Leave_Near_Launch() { turretOn = true; startPose = paths.nearStart; return new SequentialGroup( - Commands.setFlywheelState(Robot, Turret.flywheelstate.ON), - new ParallelGroup( - new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.flywheelSpeed), - new Delay(5) - ), - Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), - new Delay(2), - Commands.setIntakeMode(Robot, Intake.intakeMode.INTAKING), - new Delay(1), - Commands.setIntakeMode(Robot, Intake.intakeMode.SHOOTING), - new Delay(2), - Commands.setTransferState(Robot, Intake.transferState.UP), - new Delay(1), - Commands.setTransferState(Robot, Intake.transferState.DOWN), - Commands.setIntakeMode(Robot, Intake.intakeMode.OFF), - Commands.setFlywheelState(Robot, Turret.flywheelstate.OFF), + Commands.shootBalls(Robot), Commands.runPath(paths.nearShoot_to_nearLeave, true, 0.6) ); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 3b05f53fd8ae..c79e73a9c9b2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -1,19 +1,28 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; import com.pedropathing.paths.PathChain; +import com.skeletonarmy.marrow.TimerEx; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import dev.nextftc.core.commands.Command; +import dev.nextftc.core.commands.delays.WaitUntil; +import dev.nextftc.core.commands.groups.SequentialGroup; import dev.nextftc.core.commands.utility.InstantCommand; import dev.nextftc.core.commands.utility.LambdaCommand; import dev.nextftc.extensions.pedro.FollowPath; public class Commands { + private static final TimerEx shootingTimer = new TimerEx(1); + + private static Command resetShootingTimer() { + return new LambdaCommand("resetShootingTimer"); + } + public static Command runPath(PathChain path, boolean holdEnd) { - return new FollowPath(path, holdEnd); + return runPath(path, holdEnd, 1); } public static Command runPath(PathChain path, boolean holdEnd, double maxPower) { return new FollowPath(path, holdEnd, maxPower); @@ -25,7 +34,7 @@ public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheels .setStart(() -> Robot.turret.setFlywheelState(state)) .setIsDone(() -> { if (state == Turret.flywheelstate.ON){ - return Robot.turret.getFlywheelRPM() > Turret.flywheelSpeed; + return Robot.turret.getFlywheelRPM() > Turret.flywheelSpeed-100; }else{ return Robot.turret.getFlywheelRPM() < 100; } @@ -33,6 +42,12 @@ public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheels ; } + private static Command setGateState(LoadHardwareClass Robot, Turret.gatestate state){ + return new InstantCommand(new LambdaCommand("setGateState") + .setStart(() -> Robot.turret.setGateState(state)) + ); + } + public static Command setIntakeMode(LoadHardwareClass Robot, Intake.intakeMode state) { return new InstantCommand(new LambdaCommand("setIntakeMode()") .setStart(() -> Robot.intake.setMode(state)) @@ -47,4 +62,29 @@ public static Command setTransferState(LoadHardwareClass Robot, Intake.transferS ); } + public static Command shootBalls(LoadHardwareClass Robot){ + return new SequentialGroup( + // Ensure the flywheel is up to speed, if not, spin up first + setFlywheelState(Robot, Turret.flywheelstate.ON), + new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.flywheelSpeed-100), + + // Shoot the first two balls + setIntakeMode(Robot, Intake.intakeMode.INTAKING), + setGateState(Robot, Turret.gatestate.OPEN), + resetShootingTimer(), + new WaitUntil(() -> Robot.intake.getTopSensorState() && !Robot.intake.getBottomSensorState() && shootingTimer.isDone()), + + // Shoot the last ball + setIntakeMode(Robot, Intake.intakeMode.SHOOTING), + setTransferState(Robot, Intake.transferState.UP), + resetShootingTimer(), + new WaitUntil(shootingTimer::isDone), + + // Reset the systems + setIntakeMode(Robot, Intake.intakeMode.OFF), + setGateState(Robot, Turret.gatestate.CLOSED), + setTransferState(Robot, Intake.transferState.DOWN) + ); + } + } From 44528d11016b0e2862af99aee58c9d275a1f75c8 Mon Sep 17 00:00:00 2001 From: Ari Date: Mon, 29 Dec 2025 18:03:43 -0500 Subject: [PATCH 117/152] Added odometry telemetry to teleop because i was having issues with odometry wires earlier and also added a new test path. --- .../ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java | 7 ++++++- .../ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java | 4 ++++ .../firstinspires/ftc/teamcode/LOADCode/Notes and TODOs | 4 ++-- 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index d05c0b60b9d1..4bdc2e6915ab 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -155,7 +155,12 @@ private Command test_Auto(){ */ return new RetryCommand( new SequentialGroup( - + Commands.runPath(paths.farStart_to_farPreload,true,0.6), + Commands.runPath(paths.farPreload_to_farShoot,true,0.6), + Commands.runPath(paths.farShoot_to_midPreload, true, 0.6), + Commands.runPath(paths.midPreload_to_midShoot, true, 0.6), + Commands.runPath(paths.midShoot_to_nearPreload, true, 0.6), + Commands.runPath(paths.nearPreload_to_nearShoot, true, 0.6) ), () -> time.isLessThan(5), 10 diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index cb838d472fac..3add9219b3b5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -119,6 +119,10 @@ public void runOpMode() { telemetry.addData("SpeedMult", Robot.drivetrain.speedMultiplier); telemetry.addLine(); + //positional telemetry + telemetry.addData("X Position: ", Robot.drivetrain.follower.getPose().getX()); + telemetry.addData("Y Position: ", Robot.drivetrain.follower.getPose().getY()); + telemetry.addLine(); // Turret-related Telemetry panelsTelemetry.addData("Turret Target Angle", Robot.turret.rotation.target); panelsTelemetry.addData("Turret Actual Angle", Robot.turret.rotation.getAngleAbsolute()); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs index 39976888d7a7..9e19264603b7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Notes and TODOs @@ -22,10 +22,10 @@ -//1. TODO, test the auto paths used in the generic autos +//1. TODO, test the auto paths used in the generic autos - ARI WORKING ON IT! //2. TODO, create two generic autos for testing and competition //3. TODO, test the turret rotation autoaim with shooting //4. TODO, establish static (non-changing) flywheel speeds for near/far zones //5. TODO, make hood autoaim using InterpLUT //6. TODO, test turret hood and rotation autoaim together -//7. TODO, test turret autoaim with the generic autos \ No newline at end of file +//7. TODO, test turret autoaim with the generic autos - ADD THE TURRET CONTROL FUNCTIONALITY TO COMMANDS \ No newline at end of file From 264d8fc7b0dd9ff11129efd51b0d747d81d4563e Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 29 Dec 2025 18:59:56 -0500 Subject: [PATCH 118/152] More tweaks for auto testing --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 19 ++++------ .../Hardware_/Drivetrain_/Pedro_Paths.java | 36 +++++++++---------- 2 files changed, 24 insertions(+), 31 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 4bdc2e6915ab..d5b9fc0ebd54 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -6,7 +6,6 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.skeletonarmy.marrow.TimerEx; -import com.skeletonarmy.marrow.nextftc.RetryCommand; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -153,17 +152,13 @@ private Command test_Auto(){ to be run as many times as you want unless the time is less than a given amount */ - return new RetryCommand( - new SequentialGroup( - Commands.runPath(paths.farStart_to_farPreload,true,0.6), - Commands.runPath(paths.farPreload_to_farShoot,true,0.6), - Commands.runPath(paths.farShoot_to_midPreload, true, 0.6), - Commands.runPath(paths.midPreload_to_midShoot, true, 0.6), - Commands.runPath(paths.midShoot_to_nearPreload, true, 0.6), - Commands.runPath(paths.nearPreload_to_nearShoot, true, 0.6) - ), - () -> time.isLessThan(5), - 10 + return new SequentialGroup( + Commands.runPath(paths.farStart_to_farPreload,true,0.6), + Commands.runPath(paths.farPreload_to_farShoot,true,0.6), + Commands.runPath(paths.farShoot_to_midPreload, true, 0.6), + Commands.runPath(paths.midPreload_to_midShoot, true, 0.6), + Commands.runPath(paths.midShoot_to_nearPreload, true, 0.6), + Commands.runPath(paths.nearPreload_to_nearShoot, true, 0.6) ); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index 713559941a20..a459ceaf6efe 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -19,9 +19,9 @@ public class Pedro_Paths { public Pose nearStart = new Pose(112, 136.6, Math.toRadians(270)); public Pose farStart = new Pose(88, 7.4, Math.toRadians(90)); // Preload Poses - public Pose nearPreload = new Pose(128.000, 83.500, Math.toRadians(90)); - public Pose midPreload = new Pose(132.000, 59.500, Math.toRadians(90)); - public Pose farPreload = new Pose(132.000, 35.500, Math.toRadians(90)); + public Pose nearPreload = new Pose(128.000, 83.500, Math.toRadians(0)); + public Pose midPreload = new Pose(132.000, 59.500, Math.toRadians(0)); + public Pose farPreload = new Pose(132.000, 35.500, Math.toRadians(0)); // Shooting Poses public Pose nearShoot = new Pose(115, 120, Math.toRadians(-35)); public Pose midShoot = new Pose(85, 85, Math.toRadians(-15)); @@ -65,7 +65,7 @@ public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ } public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { - nearStart_to_nearPreload = follower.pathBuilder() + nearStart_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(nearStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), @@ -78,9 +78,9 @@ public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { autoMirror(new Pose(110.000, 83.500), alliance), autoMirror(nearPreload, alliance) )) - .setTangentHeadingInterpolation() + .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); - nearStart_to_midPreload = follower.pathBuilder() + nearStart_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(nearStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), @@ -93,9 +93,9 @@ public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { autoMirror(new Pose(110.000, 59.500), alliance), autoMirror(midPreload, alliance) )) - .setTangentHeadingInterpolation() + .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); - nearStart_to_farPreload = follower.pathBuilder() + nearStart_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(nearStart, alliance), autoMirror(new Pose(89.000, 136.600), alliance), @@ -108,14 +108,14 @@ public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { autoMirror(new Pose(110.000, 35.500), alliance), autoMirror(farPreload, alliance) )) - .setTangentHeadingInterpolation() + .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); } public void buildStart2ToPreloads(LoadHardwareClass.Alliance alliance){ - farStart_to_nearPreload = follower.pathBuilder() + farStart_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(farStart, alliance), - autoMirror(new Pose(89.000, 89.000), alliance), + autoMirror(new Pose(89.000, 79.000), alliance), autoMirror(new Pose(95.000, 83.500), alliance), autoMirror(new Pose(110.000, 83.500), alliance) )) @@ -124,13 +124,12 @@ public void buildStart2ToPreloads(LoadHardwareClass.Alliance alliance){ autoMirror(new Pose(110.000, 83.500), alliance), autoMirror(nearPreload, alliance) )) - .setTangentHeadingInterpolation() + .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); - farStart_to_midPreload = follower.pathBuilder() + farStart_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(farStart, alliance), - autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 65.000), alliance), + autoMirror(new Pose(89.000, 55.000), alliance), autoMirror(new Pose(95.000, 59.500), alliance), autoMirror(new Pose(110.000, 59.500), alliance) )) @@ -139,13 +138,12 @@ public void buildStart2ToPreloads(LoadHardwareClass.Alliance alliance){ autoMirror(new Pose(110.000, 59.500), alliance), autoMirror(midPreload, alliance) )) - .setTangentHeadingInterpolation() + .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); farStart_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( autoMirror(farStart, alliance), - autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 41.000), alliance), + autoMirror(new Pose(89.000, 25), alliance), autoMirror(new Pose(95.000, 35.500), alliance), autoMirror(new Pose(110.000, 35.500), alliance) )) @@ -154,7 +152,7 @@ public void buildStart2ToPreloads(LoadHardwareClass.Alliance alliance){ autoMirror(new Pose(110.000, 35.500), alliance), autoMirror(farPreload, alliance) )) - .setTangentHeadingInterpolation() + .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); } public void buildPreload1ToShootings(LoadHardwareClass.Alliance alliance){ From e920ee09728456895f31f6735eabbaa40c66ec0c Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 29 Dec 2025 21:26:47 -0500 Subject: [PATCH 119/152] Improved some formatting for auto Commands by passing Robot object in a constructor --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 8 ++-- .../LOADCode/Main_/Hardware_/Commands.java | 43 +++++++++++-------- 2 files changed, 28 insertions(+), 23 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index d5b9fc0ebd54..d38959977763 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -5,7 +5,6 @@ import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.skeletonarmy.marrow.TimerEx; import com.skeletonarmy.marrow.prompts.OptionPrompt; import com.skeletonarmy.marrow.prompts.Prompter; @@ -37,13 +36,12 @@ private enum Auto { // Create the prompter object for selecting Alliance and Auto Prompter prompter = null; - // Create a TimerEx object for time tracking - TimerEx time = new TimerEx(30); - // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); // Create a Paths object for accessing modular auto paths Pedro_Paths paths = new Pedro_Paths(); + // Create a Commands object for auto creation + Commands Commands = new Commands(Robot); public Auto_Main_() { addComponents( @@ -152,6 +150,8 @@ private Command test_Auto(){ to be run as many times as you want unless the time is less than a given amount */ + turretOn = false; + startPose = paths.farStart; return new SequentialGroup( Commands.runPath(paths.farStart_to_farPreload,true,0.6), Commands.runPath(paths.farPreload_to_farShoot,true,0.6), diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index c79e73a9c9b2..04914cc0b7c3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -1,5 +1,7 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_; +import androidx.annotation.NonNull; + import com.pedropathing.paths.PathChain; import com.skeletonarmy.marrow.TimerEx; @@ -15,20 +17,23 @@ public class Commands { - private static final TimerEx shootingTimer = new TimerEx(1); + // Robot Object for command access + public LoadHardwareClass Robot; + public Commands(@NonNull LoadHardwareClass robot){ + Robot = robot; + } + // Delay timer for shooting sequence + private static final TimerEx shootingTimer = new TimerEx(1); private static Command resetShootingTimer() { - return new LambdaCommand("resetShootingTimer"); + return new LambdaCommand("resetShootingTimer").setStart(shootingTimer::restart); } - public static Command runPath(PathChain path, boolean holdEnd) { - return runPath(path, holdEnd, 1); - } - public static Command runPath(PathChain path, boolean holdEnd, double maxPower) { + public Command runPath(PathChain path, boolean holdEnd, double maxPower) { return new FollowPath(path, holdEnd, maxPower); } - public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheelstate state) { + public Command setFlywheelState(Turret.flywheelstate state) { return new LambdaCommand("setFlywheelState()") .setInterruptible(false) .setStart(() -> Robot.turret.setFlywheelState(state)) @@ -42,48 +47,48 @@ public static Command setFlywheelState(LoadHardwareClass Robot, Turret.flywheels ; } - private static Command setGateState(LoadHardwareClass Robot, Turret.gatestate state){ + private Command setGateState(Turret.gatestate state){ return new InstantCommand(new LambdaCommand("setGateState") .setStart(() -> Robot.turret.setGateState(state)) ); } - public static Command setIntakeMode(LoadHardwareClass Robot, Intake.intakeMode state) { + public Command setIntakeMode(Intake.intakeMode state) { return new InstantCommand(new LambdaCommand("setIntakeMode()") .setStart(() -> Robot.intake.setMode(state)) .setIsDone(() -> true) ); } - public static Command setTransferState(LoadHardwareClass Robot, Intake.transferState state) { + public Command setTransferState(Intake.transferState state) { return new InstantCommand(new LambdaCommand("setIntakeMode()") .setStart(() -> Robot.intake.setTransfer(state)) .setIsDone(() -> true) ); } - public static Command shootBalls(LoadHardwareClass Robot){ + public Command shootBalls(LoadHardwareClass Robot){ return new SequentialGroup( // Ensure the flywheel is up to speed, if not, spin up first - setFlywheelState(Robot, Turret.flywheelstate.ON), + setFlywheelState(Turret.flywheelstate.ON), new WaitUntil(() -> Robot.turret.getFlywheelRPM() > Turret.flywheelSpeed-100), // Shoot the first two balls - setIntakeMode(Robot, Intake.intakeMode.INTAKING), - setGateState(Robot, Turret.gatestate.OPEN), + setIntakeMode(Intake.intakeMode.INTAKING), + setGateState(Turret.gatestate.OPEN), resetShootingTimer(), new WaitUntil(() -> Robot.intake.getTopSensorState() && !Robot.intake.getBottomSensorState() && shootingTimer.isDone()), // Shoot the last ball - setIntakeMode(Robot, Intake.intakeMode.SHOOTING), - setTransferState(Robot, Intake.transferState.UP), + setIntakeMode(Intake.intakeMode.SHOOTING), + setTransferState(Intake.transferState.UP), resetShootingTimer(), new WaitUntil(shootingTimer::isDone), // Reset the systems - setIntakeMode(Robot, Intake.intakeMode.OFF), - setGateState(Robot, Turret.gatestate.CLOSED), - setTransferState(Robot, Intake.transferState.DOWN) + setIntakeMode(Intake.intakeMode.OFF), + setGateState(Turret.gatestate.CLOSED), + setTransferState(Intake.transferState.DOWN) ); } From f3aa71b151990bec7ab5337facd13bd97ccd84c4 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 29 Dec 2025 21:38:43 -0500 Subject: [PATCH 120/152] Improved some formatting for auto Commands by passing Robot object in a constructor --- .../ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java | 4 ++-- .../ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index d38959977763..4d8eb773428f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -125,7 +125,7 @@ private Command Leave_Far_HP() { turretOn = true; startPose = paths.farStart; return new SequentialGroup( - Commands.shootBalls(Robot), + Commands.shootBalls(), Commands.runPath(paths.farStart_to_farLeave, true, 0.6) ); } @@ -139,7 +139,7 @@ private Command Leave_Near_Launch() { turretOn = true; startPose = paths.nearStart; return new SequentialGroup( - Commands.shootBalls(Robot), + Commands.shootBalls(), Commands.runPath(paths.nearShoot_to_nearLeave, true, 0.6) ); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 04914cc0b7c3..5c84305559b9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -67,7 +67,7 @@ public Command setTransferState(Intake.transferState state) { ); } - public Command shootBalls(LoadHardwareClass Robot){ + public Command shootBalls(){ return new SequentialGroup( // Ensure the flywheel is up to speed, if not, spin up first setFlywheelState(Turret.flywheelstate.ON), From 7ea0b890bbbf82b5402cc3d31f62835292d926a5 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Mon, 29 Dec 2025 21:58:39 -0500 Subject: [PATCH 121/152] Significantly overhauled the way new auto programs are created --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 144 ++++++++++-------- 1 file changed, 79 insertions(+), 65 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 4d8eb773428f..3b70ff5e8d58 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -13,7 +13,6 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; -import dev.nextftc.core.commands.Command; import dev.nextftc.core.commands.groups.SequentialGroup; import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; @@ -21,21 +20,10 @@ @Autonomous(name = "Auto_Main_", group = "Main", preselectTeleOp="Teleop_Main_") public class Auto_Main_ extends NextFTCOpMode { - // Define other PedroPathing constants - private Pose startPose = new Pose(87, 8.8, Math.toRadians(90)); // Start Pose of our robot. - - private enum Auto { - LEAVE_NEAR_LAUNCH, - LEAVE_FAR_HP, - TEST_AUTO - } - + // Variable to store the selected auto program private Auto selectedAuto = null; - private boolean turretOn = true; - // Create the prompter object for selecting Alliance and Auto Prompter prompter = null; - // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); // Create a Paths object for accessing modular auto paths @@ -43,6 +31,10 @@ private enum Auto { // Create a Commands object for auto creation Commands Commands = new Commands(Robot); + // Auto parameter variables + private boolean turretOn = true; + private Pose startPose = paths.farStart; // Start Pose of our robot. + public Auto_Main_() { addComponents( new PedroComponent(Constants::createFollower) @@ -59,15 +51,15 @@ public void onInit() { )); prompter.prompt("auto", new OptionPrompt<>("Select Auto", - Auto.LEAVE_NEAR_LAUNCH, - Auto.LEAVE_FAR_HP, - Auto.TEST_AUTO + new Leave_Far_HP(), + new Leave_Near_Launch(), + new test_Auto() )); prompter.onComplete(() -> { selectedAlliance = prompter.get("alliance"); selectedAuto = prompter.get("auto"); telemetry.addData("Selection", "Complete"); - telemetry.addData("Alliance", selectedAlliance); + telemetry.addData("Alliance", selectedAlliance.toString()); telemetry.addData("Auto", selectedAuto); telemetry.update(); } @@ -83,22 +75,13 @@ public void onWaitForStart() { public void onStartButtonPressed() { // Build paths paths.buildPaths(selectedAlliance, follower()); - // Schedule the proper auto - switch (selectedAuto) { - case LEAVE_NEAR_LAUNCH: - Leave_Near_Launch().schedule(); - break; - case LEAVE_FAR_HP: - Leave_Far_HP().schedule(); - break; - case TEST_AUTO: - test_Auto().schedule(); - break; - } // Initialize all hardware of the robot Robot.init(startPose, follower()); + // Schedule the proper auto + selectedAuto.runAuto(); - telemetry.addData("Initialized", ""); + // Indicate that initialization is done + telemetry.addLine("Initialized"); telemetry.update(); } @@ -117,48 +100,79 @@ public void onUpdate() { } /** - * This auto starts at the far zone, - * shoots it's preloads after 5 seconds, - * and goes to the leave zone next to the human player zone. + * This class serves as a template for all auto programs.
+ * The methods runAuto() and ToString() must be overridden for each auto. */ - private Command Leave_Far_HP() { - turretOn = true; - startPose = paths.farStart; - return new SequentialGroup( - Commands.shootBalls(), - Commands.runPath(paths.farStart_to_farLeave, true, 0.6) - ); + private static class Auto{ + /** Override this to schedule the auto command*/ + public void runAuto(){} + /** Override this to return the name of the auto*/ + @SuppressWarnings("unused") + public String ToString(){return "";} } /** - * This auto starts at the near zone, - * shoots it's preloads after 5 seconds, + * This auto starts at the far zone, shoots it's preloads,
+ * and goes to the leave zone next to the human player zone. + */ + private class Leave_Far_HP extends Auto{ + Leave_Far_HP(){ + turretOn = true; + startPose = paths.farStart; + } + + @Override + public void runAuto(){ + new SequentialGroup( + Commands.shootBalls(), + Commands.runPath(paths.farStart_to_farLeave, true, 0.6) + ).schedule(); + } + + @Override + public String ToString(){return "Shoot Far Preloads";} + } + /** + * This auto starts at the near zone, shoots it's preloads,
* and goes to the leave pose that is in the launch zone. */ - private Command Leave_Near_Launch() { - turretOn = true; - startPose = paths.nearStart; - return new SequentialGroup( - Commands.shootBalls(), - Commands.runPath(paths.nearShoot_to_nearLeave, true, 0.6) - ); + private class Leave_Near_Launch extends Auto{ + Leave_Near_Launch(){ + turretOn = true; + startPose = paths.nearStart; + } + + @Override + public void runAuto(){ + new SequentialGroup( + Commands.shootBalls(), + Commands.runPath(paths.nearStart_to_nearLeave, true, 0.6) + ).schedule(); + } + + @Override + public String ToString(){return "Shoot Near Preloads";} } - private Command test_Auto(){ - /* - This RetryCommand allows for a command/set of commands - to be run as many times as you want unless the time is - less than a given amount - */ - turretOn = false; - startPose = paths.farStart; - return new SequentialGroup( - Commands.runPath(paths.farStart_to_farPreload,true,0.6), - Commands.runPath(paths.farPreload_to_farShoot,true,0.6), - Commands.runPath(paths.farShoot_to_midPreload, true, 0.6), - Commands.runPath(paths.midPreload_to_midShoot, true, 0.6), - Commands.runPath(paths.midShoot_to_nearPreload, true, 0.6), - Commands.runPath(paths.nearPreload_to_nearShoot, true, 0.6) - ); + private class test_Auto extends Auto{ + test_Auto(){ + turretOn = false; + startPose = paths.farStart; + } + + @Override + public void runAuto(){ + new SequentialGroup( + Commands.runPath(paths.farStart_to_farPreload,true,0.6), + Commands.runPath(paths.farPreload_to_farShoot,true,0.6), + Commands.runPath(paths.farShoot_to_midPreload, true, 0.6), + Commands.runPath(paths.midPreload_to_midShoot, true, 0.6), + Commands.runPath(paths.midShoot_to_nearPreload, true, 0.6), + Commands.runPath(paths.nearPreload_to_nearShoot, true, 0.6) + ).schedule(); + } + + @Override + public String ToString(){return "Test Auto";} } } From 0dd63445a6f2697a4f3c05ee46ab2f098207d818 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 30 Dec 2025 08:37:04 -0500 Subject: [PATCH 122/152] Adjusted the implementation of Auto template class to make it easier to define some additional parameters for the autos --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 40 ++++++++++++------- 1 file changed, 26 insertions(+), 14 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 3b70ff5e8d58..364115c481cd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -21,7 +21,7 @@ public class Auto_Main_ extends NextFTCOpMode { // Variable to store the selected auto program - private Auto selectedAuto = null; + Auto selectedAuto = null; // Create the prompter object for selecting Alliance and Auto Prompter prompter = null; // Create a new instance of our Robot class @@ -35,6 +35,7 @@ public class Auto_Main_ extends NextFTCOpMode { private boolean turretOn = true; private Pose startPose = paths.farStart; // Start Pose of our robot. + @SuppressWarnings("unused") public Auto_Main_() { addComponents( new PedroComponent(Constants::createFollower) @@ -87,6 +88,8 @@ public void onStartButtonPressed() { @Override public void onUpdate() { + telemetry.addData("Running Auto", selectedAuto.toString()); + telemetry.addLine(); if (turretOn){ Robot.turret.updateAimbot(Robot); telemetry.addData("Aimbot Target", selectedAlliance); @@ -94,8 +97,7 @@ public void onUpdate() { Robot.turret.updateFlywheel(); telemetry.addLine(); - telemetry.addData("selectedAuto", selectedAuto); - telemetry.addData("currentPose", Robot.drivetrain.follower.getPose()); + telemetry.addData("Current Robot Pose", Robot.drivetrain.follower.getPose()); telemetry.update(); } @@ -103,22 +105,34 @@ public void onUpdate() { * This class serves as a template for all auto programs.
* The methods runAuto() and ToString() must be overridden for each auto. */ - private static class Auto{ + abstract class Auto{ + /** + * This constructor must be called from the child class using super() + * @param startingPose Indicates the starting pose of the robot + * @param runTurret Indicates whether to run the turret auto aim functions + */ + Auto(Pose startingPose, Boolean runTurret){ + turretOn = runTurret; + startPose = startingPose; + } + Auto(Pose startingPose){ + turretOn = true; + startPose = startingPose; + } + /** Override this to schedule the auto command*/ - public void runAuto(){} - /** Override this to return the name of the auto*/ + abstract void runAuto(); + /** Override this to rename the auto*/ @SuppressWarnings("unused") - public String ToString(){return "";} + abstract String ToString(); } - /** * This auto starts at the far zone, shoots it's preloads,
* and goes to the leave zone next to the human player zone. */ private class Leave_Far_HP extends Auto{ Leave_Far_HP(){ - turretOn = true; - startPose = paths.farStart; + super(paths.farStart); } @Override @@ -138,8 +152,7 @@ public void runAuto(){ */ private class Leave_Near_Launch extends Auto{ Leave_Near_Launch(){ - turretOn = true; - startPose = paths.nearStart; + super(paths.nearStart, true); } @Override @@ -156,8 +169,7 @@ public void runAuto(){ private class test_Auto extends Auto{ test_Auto(){ - turretOn = false; - startPose = paths.farStart; + super(paths.farStart, false); } @Override From 040ac93f559ae0e3b68059946f75c9c6d146adf7 Mon Sep 17 00:00:00 2001 From: Ari Date: Tue, 30 Dec 2025 17:43:37 -0500 Subject: [PATCH 123/152] Added a temp speed value to Auto_Main for David's viewing pleasure --- .../teamcode/LOADCode/Main_/Auto_/Auto_Main_.java | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 364115c481cd..2425e351afc0 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -174,13 +174,14 @@ private class test_Auto extends Auto{ @Override public void runAuto(){ + double tempSpeed = 1; new SequentialGroup( - Commands.runPath(paths.farStart_to_farPreload,true,0.6), - Commands.runPath(paths.farPreload_to_farShoot,true,0.6), - Commands.runPath(paths.farShoot_to_midPreload, true, 0.6), - Commands.runPath(paths.midPreload_to_midShoot, true, 0.6), - Commands.runPath(paths.midShoot_to_nearPreload, true, 0.6), - Commands.runPath(paths.nearPreload_to_nearShoot, true, 0.6) + Commands.runPath(paths.farStart_to_farPreload,true,tempSpeed), + Commands.runPath(paths.farPreload_to_farShoot,true,tempSpeed), + Commands.runPath(paths.farShoot_to_midPreload, true, tempSpeed), + Commands.runPath(paths.midPreload_to_midShoot, true, tempSpeed), + Commands.runPath(paths.midShoot_to_nearPreload, true, tempSpeed), + Commands.runPath(paths.nearPreload_to_nearShoot, true, tempSpeed) ).schedule(); } From fdc2d0d8eb6508bab3df5c2476c037fafdcbaea1 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 30 Dec 2025 17:47:17 -0500 Subject: [PATCH 124/152] Fixed bug with the toString() method in the auto programs --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 2425e351afc0..ac7fd057f612 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -3,6 +3,8 @@ import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; import static dev.nextftc.extensions.pedro.PedroComponent.follower; +import androidx.annotation.NonNull; + import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.skeletonarmy.marrow.prompts.OptionPrompt; @@ -123,8 +125,9 @@ abstract class Auto{ /** Override this to schedule the auto command*/ abstract void runAuto(); /** Override this to rename the auto*/ - @SuppressWarnings("unused") - abstract String ToString(); + @NonNull + @Override + public abstract String toString(); } /** * This auto starts at the far zone, shoots it's preloads,
@@ -143,8 +146,9 @@ public void runAuto(){ ).schedule(); } + @NonNull @Override - public String ToString(){return "Shoot Far Preloads";} + public String toString(){return "Shoot Far Preloads";} } /** * This auto starts at the near zone, shoots it's preloads,
@@ -163,8 +167,9 @@ public void runAuto(){ ).schedule(); } + @NonNull @Override - public String ToString(){return "Shoot Near Preloads";} + public String toString(){return "Shoot Near Preloads";} } private class test_Auto extends Auto{ @@ -185,7 +190,8 @@ public void runAuto(){ ).schedule(); } + @NonNull @Override - public String ToString(){return "Test Auto";} + public String toString(){return "Test Auto";} } } From 6baa577b149aed2e0f8bf21e3d0589dfaf463ed9 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 30 Dec 2025 17:51:30 -0500 Subject: [PATCH 125/152] Fixed incorrect start position for some of the auto paths --- .../LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index a459ceaf6efe..2d9da6839ca2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -208,7 +208,7 @@ public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ public void buildPreload3ToShootings(LoadHardwareClass.Alliance alliance){ farPreload_to_nearShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midPreload, alliance), + autoMirror(farPreload, alliance), autoMirror(new Pose(75,30), alliance), autoMirror(new Pose(80,100), alliance), autoMirror(nearShoot, alliance) @@ -217,7 +217,7 @@ public void buildPreload3ToShootings(LoadHardwareClass.Alliance alliance){ .build(); farPreload_to_midShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midPreload, alliance), + autoMirror(farPreload, alliance), autoMirror(new Pose(85,32), alliance), autoMirror(midShoot, alliance) )) @@ -225,7 +225,7 @@ public void buildPreload3ToShootings(LoadHardwareClass.Alliance alliance){ .build(); farPreload_to_farShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midPreload, alliance), + autoMirror(farPreload, alliance), autoMirror(farShoot, alliance) )) .setLinearHeadingInterpolation(midPreload.getHeading(), farShoot.getHeading()) From 8f17186adb0d23e51a246bc53096caa83c3d997f Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Tue, 30 Dec 2025 21:25:05 -0500 Subject: [PATCH 126/152] Implemented (But did not finish/enable) the InterpLUT within Turret.java for the hood autoaim. --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 2 +- .../Main_/Hardware_/Actuators_/Turret.java | 96 +++++++++++++------ .../Main_/Hardware_/LoadHardwareClass.java | 4 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 6 +- .../ftc/teamcode/LOADCode/Main_/Utils_.java | 3 +- 5 files changed, 77 insertions(+), 34 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index ac7fd057f612..cee21c316753 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -93,7 +93,7 @@ public void onUpdate() { telemetry.addData("Running Auto", selectedAuto.toString()); telemetry.addLine(); if (turretOn){ - Robot.turret.updateAimbot(Robot); + Robot.turret.updateAimbot(); telemetry.addData("Aimbot Target", selectedAlliance); } Robot.turret.updateFlywheel(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 0cd31300a4ff..e5f1484462b5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -1,7 +1,5 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_; -import androidx.annotation.NonNull; - import com.bylazar.configurables.annotations.Configurable; import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.OpMode; @@ -10,6 +8,7 @@ import com.qualcomm.robotcore.hardware.Servo; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Utils_; import dev.nextftc.control.feedback.PIDCoefficients; import dev.nextftc.control.feedforward.BasicFeedforwardParameters; @@ -26,37 +25,47 @@ public class Turret { private final Devices.REVHallEffectSensorClass hall = new Devices.REVHallEffectSensorClass(); // Turret PID coefficients - public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.06, 0, 0); // 223RPM - //public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.3, 0, 0.007); // 1150RPM + public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.06, 0, 0); // 223RPM Motor + //public static PIDCoefficients turretCoefficients = new PIDCoefficients(0.3, 0, 0.007); // 1150RPM Motor // Flywheel PID coefficients // 4500RPM public static PIDCoefficients flywheelCoefficients = new PIDCoefficients(0.0002, 0, 0); public static BasicFeedforwardParameters flywheelFFCoefficients = new BasicFeedforwardParameters(0.000026,0,0); + // Define any Enums here public enum gatestate { OPEN, CLOSED, } - public enum flywheelstate { ON, OFF } - public flywheelstate flywheelState = flywheelstate.OFF; - /** Controls the target speed of the flywheel when it is on */ + // Define any state variables or important parameters here + /** Stores the current state of the flywheel.*/ + public flywheelstate flywheelState = flywheelstate.OFF; + /** Controls the target speed of the flywheel when it is on.*/ public static double flywheelSpeed = 4500; - /** Controls the upper software limit of the hood */ + /** Controls the upper software limit of the hood.*/ public static double upperHoodLimit = 260; - /** Controls the speed at which the turret will zero itself */ + /** Controls the speed at which the turret will move to zero itself.*/ public static double zeroSpeed = 0.2; - // Stores the opmode object for later access + // Stores important objects for later access OpMode opMode = null; + LoadHardwareClass Robot = null; + + // The variable to store the InterpLUT table for turret hood aimbot + Utils_.InterpLUT hoodLUT = new Utils_.InterpLUT(); - public void init(OpMode opmode){ + public void init(OpMode opmode, LoadHardwareClass robot){ + // Store important objects in their respective variables opMode = opmode; + Robot = robot; + + // Initialize hardware objects rotation.init(opmode, "turret", 145.1 * ((double) 131 /24)); //Previously 103.8 flywheel.init(opmode, "flywheel", 28); flywheel2.init(opmode, "flywheel2", 28); @@ -64,13 +73,17 @@ public void init(OpMode opmode){ gate.init(opmode, "gate"); hall.init(opmode, "hall"); - rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); - rotation.setDirection(DcMotorSimple.Direction.REVERSE); + // Set servos to initial positions + setGateState(gatestate.CLOSED); + setHood(0); - gate.setAngle(0.5); + // Set servo directions hood.setDirection(Servo.Direction.REVERSE); + // Set motor directions and zero power behaviour flywheel2.setDirection(DcMotorSimple.Direction.REVERSE); + rotation.setZeroPowerBehaviour(DcMotor.ZeroPowerBehavior.BRAKE); + rotation.setDirection(DcMotorSimple.Direction.REVERSE); // Pass PID pidCoefficients to motor classes rotation.setPidCoefficients(turretCoefficients); @@ -78,8 +91,13 @@ public void init(OpMode opmode){ flywheel.setFFCoefficients(flywheelFFCoefficients); flywheel2.setPidCoefficients(flywheelCoefficients); flywheel2.setFFCoefficients(flywheelFFCoefficients); + + // TODO Build hood InterpLUT for autoaim +// hoodLUT.add(0,0); +// hoodLUT.add(1,1); } + /** Sets the value of the internal motor PID coefficients */ public void updatePIDs(){ // Pass PID pidCoefficients to motor classes rotation.setPidCoefficients(turretCoefficients); @@ -90,12 +108,21 @@ public void updatePIDs(){ } /** - * @param robot The robot object in that opmode + * Runs the aimbot program to control the turret rotation and hood angle.
+ * Must be called every loop to function properly. */ - public void updateAimbot(@NonNull LoadHardwareClass robot){ - rotation.setAngle(calcLocalizer(robot.drivetrain.follower.getPose(), LoadHardwareClass.selectedAlliance)); + public void updateAimbot(){ + // Set the turret rotation + rotation.setAngle(calcLocalizer()); + // Set the hood angle + Pose goalPose = new Pose(4,140,0); + if (LoadHardwareClass.selectedAlliance == LoadHardwareClass.Alliance.RED) {goalPose = new Pose(140, 140, 0);} + //setHood(hoodLUT.get(Robot.drivetrain.follower.getPose().distanceFrom(goalPose))); } + /** + * Sets the state of the turret gate. + */ public void setGateState(gatestate state){ if (state == gatestate.OPEN){ gate.setAngle(0.5); @@ -106,22 +133,23 @@ public void setGateState(gatestate state){ /** * Sets the angle of the hood. - * @param angle An angle in degrees that is constrained to between 0 and 320 degrees + * @param angle An angle in degrees that is constrained to between 0 and the upper hood limit. */ public void setHood(double angle){ hood.setAngle(Math.min(Math.max(angle, 0), upperHoodLimit)/(360*5)); } /** - * Gets the angle of the hood - * @return A value between 0 and 45 degrees + * Gets the last set position of the turret hood. + * @return The angle of the hood in degrees. */ public double getHood(){ return hood.getAngle() * 360 * 5; } /** - * Outputs one of the following modes + * Gets the current state of the turret gate. + * Outputs one of the following modes. *

*/ public gatestate getGate(){ - if (gate.getAngle() == 0.5){ + if (gate.getAngle() == 0.47){ return gatestate.OPEN; } else { return gatestate.CLOSED; @@ -265,18 +281,13 @@ public void setFlywheelState(flywheelState state){ } public double getFlywheelCurrentMaxSpeed(){ - return flywheel.target; + return targetRPM; } - /** - * Resets the zero position of the turret using the hall effect switch
- * Must be called within the INIT loop in the opmode to work. - * - */ - public static double zeroSpeed = 1; + public boolean zeroTurret(){ if (!zeroed){ - rotation.setPower(zeroSpeed); + rotation.setPower(1); if (hall.getTriggered()){ rotation.setPower(0); rotation.resetEncoder(); @@ -299,16 +310,17 @@ public void updateFlywheel(){ opMode.telemetry.addData("In Far Zone", robotZone.isInside(LoadHardwareClass.FarLaunchZone)); opMode.telemetry.addData("In Near Zone", robotZone.isInside(LoadHardwareClass.NearLaunchZone)); + if (robotZone.isInside(LoadHardwareClass.FarLaunchZone)){ + targetRPM = flywheelFarSpeed; + actualFlywheelCoefficients = flywheelCoefficients4200; + actualFlywheelFFCoefficients = flywheelFFCoefficients4200; + }else{ + targetRPM = flywheelNearSpeed; + actualFlywheelCoefficients = flywheelCoefficients3500; + actualFlywheelFFCoefficients = flywheelFFCoefficients3500; + } + if (flywheelMode == flywheelState.ON){ - if (robotZone.isInside(LoadHardwareClass.FarLaunchZone)){ - targetRPM = flywheelFarSpeed; - actualFlywheelCoefficients = flywheelCoefficients4200; - actualFlywheelFFCoefficients = flywheelFFCoefficients4200; - }else{ - targetRPM = flywheelNearSpeed; - actualFlywheelCoefficients = flywheelCoefficients3500; - actualFlywheelFFCoefficients = flywheelFFCoefficients3500; - } setFlywheelRPM(targetRPM); }else if (flywheelMode == flywheelState.OFF){ setFlywheelRPM(0); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index 910a01ac2f38..d17b84a13742 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -57,7 +57,7 @@ public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ if (alliance == LoadHardwareClass.Alliance.BLUE){ return new Pose( 144 - pose.getX(), - 144 - pose.getY(), + pose.getY(), Math.atan2(Math.sin(pose.getHeading()), -Math.cos(pose.getHeading())) ); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index c042b35be100..ce3842afbd6c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -57,6 +57,7 @@ public class LoadHardwareClass { // Declare various enums & other variables that are useful across files public static Alliance selectedAlliance = null; + public Pose goalPose = new Pose(144, 144); public enum Alliance { RED, BLUE diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 8e78912e2c92..63ee37efd8d8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -83,9 +83,6 @@ public class Teleop_Main_ extends LinearOpMode { @Override public void runOpMode() { - // Initialize all hardware of the robot - Robot.init(startPose); - // Create a new prompter for selecting alliance prompter = new Prompter(this); @@ -98,11 +95,16 @@ public void runOpMode() { } ); + // Initialize all hardware of the robot + Robot.init(Paths.autoMirror(startPose, selectedAlliance)); + // Runs repeatedly while in init while (opModeInInit()) { // If an auto was not run, run the prompter to select the correct alliance if (selectedAlliance == null) { prompter.run(); + }else{ + prompter.run(); } } @@ -283,11 +285,7 @@ public void Gamepad2() { if (gamepad2.aWasPressed()){ turretOn = !turretOn; } - if (turretOn){ - Robot.turret.updateAimbot(); - }else{ - Robot.turret.rotation.setAngle(90); - } + Robot.turret.updateAimbot(turretOn, true); //Intake Controls (Left Stick Y) if (shootingState == 0) { @@ -316,6 +314,7 @@ public void Gamepad2() { } Robot.turret.updateFlywheel(); + /* Uncomment all this if reenableing manual hood controls // Hood Controls if (gamepad2.dpad_up){ Robot.turret.setHood(Robot.turret.getHood() + hoodSpeed); @@ -323,14 +322,9 @@ public void Gamepad2() { Robot.turret.setHood(Robot.turret.getHood() - hoodSpeed); }else if (gamepad2.dpadLeftWasPressed()){ Robot.turret.setHood(152); - }else if (gamepad1.x){ - // Set the hood angle - Pose goalPose = new Pose(0,144,0); - if (LoadHardwareClass.selectedAlliance == LoadHardwareClass.Alliance.RED) {goalPose = new Pose(144, 144, 0);} - - Robot.turret.setHood(Robot.turret.hoodLUT.get(Robot.drivetrain.follower.getPose().distanceFrom(goalPose))); } Robot.turret.setHood(Math.max(Math.min(Robot.turret.getHood(), Turret.upperHoodLimit), 0)); + */ //Shoot (B Button Press) // Increment the shooting state From 3f57e05aa2ae1e7cd8b5d73e31277ebf8cc3c282 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+Professor348@users.noreply.github.com> Date: Fri, 16 Jan 2026 08:50:10 -0500 Subject: [PATCH 149/152] Changed teleop code to use the ending position of auto as it's start position. --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 9 +++++++ .../Drivetrain_/MecanumDrivetrainClass.java | 2 ++ .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 25 +++++++++++-------- 3 files changed, 26 insertions(+), 10 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 0c5ee695103e..7e88fee59df4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -12,6 +12,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; import org.firstinspires.ftc.teamcode.pedroPathing.Constants; @@ -104,11 +105,19 @@ public void onUpdate() { } Robot.turret.updateFlywheel(); + MecanumDrivetrainClass.robotPose = Robot.drivetrain.follower.getPose(); + telemetry.addLine(); telemetry.addData("Current Robot Pose", Robot.drivetrain.follower.getPose()); telemetry.update(); } + @Override + public void onStop(){ + Robot.drivetrain.follower.holdPoint(Robot.drivetrain.follower.getPose()); + MecanumDrivetrainClass.robotPose = Robot.drivetrain.follower.getPose(); + } + /** * This class serves as a template for all auto programs.
* The methods runAuto() and ToString() must be overridden for each auto. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java index b8fe95f4d0f1..6f40ac67922b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/MecanumDrivetrainClass.java @@ -17,6 +17,8 @@ public class MecanumDrivetrainClass { // Misc Constants public Follower follower = null; + public static Pose robotPose = null; + /** * Initializes the PedroPathing follower. * Needs to be run once after all hardware is initialized. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 346e08c9d8b4..40490966f4e3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -29,6 +29,7 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; +import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass.robotPose; import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; import com.bylazar.configurables.annotations.Configurable; @@ -48,6 +49,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.flywheelState; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.gatestate; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @@ -76,22 +78,19 @@ public class Teleop_Main_ extends LinearOpMode { // Create a new Paths instance Pedro_Paths Paths = new Pedro_Paths(); // Create a new instance of Prompter for selecting the alliance - Prompter prompter = null; + Prompter prompterAlliance = null; // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. - private final Pose startPose = Paths.farStart; + private Pose startPose = Paths.farStart; @Override public void runOpMode() { - // Initialize all hardware of the robot - Robot.init(startPose); - // Create a new prompter for selecting alliance - prompter = new Prompter(this); - prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", LoadHardwareClass.Alliance.RED, LoadHardwareClass.Alliance.BLUE)); - prompter.onComplete(() -> { - selectedAlliance = prompter.get("alliance"); + prompterAlliance = new Prompter(this); + prompterAlliance.prompt("alliance", new OptionPrompt<>("Select Alliance", LoadHardwareClass.Alliance.RED, LoadHardwareClass.Alliance.BLUE)); + prompterAlliance.onComplete(() -> { + selectedAlliance = prompterAlliance.get("alliance"); telemetry.addData("Selection", "Complete"); telemetry.addData("Alliance", selectedAlliance); telemetry.update(); @@ -102,9 +101,15 @@ public void runOpMode() { while (opModeInInit()) { // If an auto was not run, run the prompter to select the correct alliance if (selectedAlliance == null) { - prompter.run(); + prompterAlliance.run(); } } + if (robotPose != null){ + startPose = robotPose; + } + + // Initialize all hardware of the robot + Robot.init(Paths.autoMirror(startPose, selectedAlliance)); telemetry.addData("Status", "Initialized"); telemetry.update(); From 00dae44aaf471654483fa024dc1b474a8869ee96 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+professor348@users.noreply.github.com> Date: Fri, 16 Jan 2026 21:20:34 -0500 Subject: [PATCH 150/152] Auto work --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 153 ++++--- .../Main_/Hardware_/Actuators_/Intake.java | 4 +- .../Main_/Hardware_/Actuators_/Turret.java | 21 +- .../LOADCode/Main_/Hardware_/Commands.java | 7 +- .../Hardware_/Drivetrain_/Pedro_Paths.java | 407 ++++++++++++------ .../Main_/Hardware_/LoadHardwareClass.java | 2 +- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 101 +++-- 7 files changed, 451 insertions(+), 244 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 7baf0f46a474..82501e12efbd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -11,6 +11,7 @@ import com.skeletonarmy.marrow.prompts.Prompter; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Intake; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Commands; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; @@ -19,6 +20,7 @@ import dev.nextftc.core.commands.delays.Delay; import dev.nextftc.core.commands.groups.SequentialGroup; +import dev.nextftc.core.commands.utility.InstantCommand; import dev.nextftc.extensions.pedro.PedroComponent; import dev.nextftc.ftc.NextFTCOpMode; @@ -38,7 +40,6 @@ public class Auto_Main_ extends NextFTCOpMode { // Auto parameter variables private boolean turretOn = true; - private Pose startPose = paths.farStart; // Start Pose of our robot. @SuppressWarnings("unused") public Auto_Main_() { @@ -49,9 +50,6 @@ public Auto_Main_() { @Override public void onInit() { - while (opModeInInit() && Robot.turret.zeroTurret()){ - sleep(0); - } prompter = new Prompter(this); prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", @@ -60,10 +58,10 @@ public void onInit() { )); prompter.prompt("auto", new OptionPrompt<>("Select Auto", - new Leave_Far_HP(), - new Leave_Near_Launch(), - new test_Auto(), - new Complex_Test_Auto() + new Leave_Far_Generic(), + new Leave_Far_Generic() + //new test_Auto(), + //new Complex_Test_Auto() )); prompter.onComplete(() -> { selectedAlliance = prompter.get("alliance"); @@ -72,8 +70,14 @@ public void onInit() { telemetry.addData("Alliance", selectedAlliance.toString()); telemetry.addData("Auto", selectedAuto); telemetry.update(); - } - ); + // Build paths + paths.buildPaths(selectedAlliance, follower()); + // Initialize all hardware of the robot + Robot.init(paths.autoMirror(selectedAuto.getStartPose(), selectedAlliance), follower()); + while (opModeInInit() && Robot.turret.zeroTurret()){ + sleep(0); + } + }); } @Override @@ -83,12 +87,9 @@ public void onWaitForStart() { @Override public void onStartButtonPressed() { - // Build paths - paths.buildPaths(selectedAlliance, follower()); - // Initialize all hardware of the robot - Robot.init(startPose, follower()); // Schedule the proper auto selectedAuto.runAuto(); + turretOn = selectedAuto.getTurretEnabled(); // Indicate that initialization is done telemetry.addLine("Initialized"); @@ -100,15 +101,18 @@ public void onUpdate() { telemetry.addData("Running Auto", selectedAuto.toString()); telemetry.addLine(); if (turretOn){ - Robot.turret.updateAimbot(turretOn, true); telemetry.addData("Aimbot Target", selectedAlliance); + }else{ + telemetry.addLine("Aimbot Off"); } + Robot.turret.updateAimbot(turretOn, true, 0); Robot.turret.updateFlywheel(); MecanumDrivetrainClass.robotPose = Robot.drivetrain.follower.getPose(); telemetry.addLine(); - telemetry.addData("Current Robot Pose", Robot.drivetrain.follower.getPose()); + telemetry.addData("FarStart", paths.farStart); + telemetry.addData("FarShoot", paths.noTurretFarShoot); telemetry.update(); } @@ -122,20 +126,23 @@ public void onStop(){ * This class serves as a template for all auto programs.
* The methods runAuto() and ToString() must be overridden for each auto. */ - abstract class Auto{ - /** - * This constructor must be called from the child class using super() - * @param startingPose Indicates the starting pose of the robot - * @param runTurret Indicates whether to run the turret auto aim functions - */ - Auto(Pose startingPose, Boolean runTurret){ - turretOn = runTurret; - startPose = startingPose; - } - Auto(Pose startingPose){ - turretOn = true; - startPose = startingPose; - } + abstract static class Auto{ +// /** +// * This constructor must be called from the child class using super() +// * @param startingPose Indicates the starting pose of the robot +// * @param runTurret Indicates whether to run the turret auto aim functions +// */ +// Auto(Pose startingPose, Boolean runTurret){ +// turretOn = runTurret; +// startPose = startingPose; +// } +// Auto(Pose startingPose){ +// turretOn = true; +// startPose = startingPose; +// } + + abstract Pose getStartPose(); + abstract boolean getTurretEnabled(); /** Override this to schedule the auto command*/ abstract void runAuto(); @@ -144,55 +151,89 @@ abstract class Auto{ @Override public abstract String toString(); } - /** - * This auto starts at the far zone, shoots it's preloads,
- * and goes to the leave zone next to the human player zone. - */ - private class Leave_Far_HP extends Auto{ - Leave_Far_HP(){ - super(paths.farStart); + + private class Leave_Far_Generic extends Auto{ + public Pose startPose = paths.farStart; + public boolean turretEnabled = false; + + @Override + public Pose getStartPose(){ + return startPose; + } + @Override + public boolean getTurretEnabled(){ + return turretEnabled; } @Override public void runAuto(){ new SequentialGroup( + Commands.runPath(paths.farStart_to_NoTurret_FarShoot, true, 1), Commands.shootBalls(), - Commands.runPath(paths.farStart_to_farLeave, true, 0.6) + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + Commands.runPath(paths.farShoot_noTurret_to_farPreload, true, 1), + Commands.setIntakeMode(Intake.intakeMode.OFF) ).schedule(); } @NonNull @Override - public String toString(){return "Shoot Far Preloads";} + public String toString(){return "Far Zone No Turret Generic";} } - /** - * This auto starts at the near zone, shoots it's preloads,
- * and goes to the leave pose that is in the launch zone. - */ - private class Leave_Near_Launch extends Auto{ - Leave_Near_Launch(){ - super(paths.nearStart, true); + + private class Near_Generic extends Auto{ + public Pose startPose = paths.nearStart; + public boolean turretEnabled = true; + + @Override + public Pose getStartPose(){ + return startPose; + } + @Override + public boolean getTurretEnabled(){ + return turretEnabled; } @Override public void runAuto(){ new SequentialGroup( + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + new InstantCommand(Commands.setFlywheelState(Turret.flywheelState.ON)), + Commands.runPath(paths.nearStart_to_midShoot, true, 1), + Commands.shootBalls(), + Commands.setFlywheelState(Turret.flywheelState.ON), + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + Commands.runPath(paths.midShoot_to_nearPreload, true, 1), + Commands.runPath(paths.nearPreload_to_midShoot, true, 1), + Commands.shootBalls(), + Commands.setFlywheelState(Turret.flywheelState.ON), + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + Commands.runPath(paths.midShoot_to_midPreload, true, 1), + Commands.runPath(paths.midPreload_to_midShoot, true, 1), Commands.shootBalls(), - Commands.runPath(paths.nearStart_to_nearLeave, true, 0.6) + Commands.runPath(paths.midShoot_to_nearLeave, true, 1) ).schedule(); } @NonNull @Override - public String toString(){return "Shoot Near Preloads";} + public String toString(){return "Near Zone No Turret Generic";} } /** * This auto starts at the far zone */ private class Complex_Test_Auto extends Auto{ - Complex_Test_Auto() { - super(paths.farStart, true); + public Pose startPose = paths.farStart; + public boolean turretEnabled = true; + + @Override + public Pose getStartPose(){ + return startPose; + } + @Override + public boolean getTurretEnabled(){ + return turretEnabled; } @Override @@ -222,8 +263,16 @@ public String toString() { } private class test_Auto extends Auto{ - test_Auto(){ - super(paths.farStart, false); + public Pose startPose = paths.farStart; + public boolean turretEnabled = false; + + @Override + public Pose getStartPose(){ + return startPose; + } + @Override + public boolean getTurretEnabled(){ + return turretEnabled; } @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java index 809d5af7393a..5d02127bde55 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Intake.java @@ -64,8 +64,10 @@ public void init(OpMode opmode){ */ public void setMode(intakeMode direction){ if (direction == intakeMode.INTAKING){ + //if (!(getTopSensorState() && getBottomSensorState())){ + belt.setPower(1); + //} intake.setPower(1); - belt.setPower(1); }else if (direction == intakeMode.SHOOTING){ intake.setPower(0); belt.setPower(1); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index e57b6fbd361a..96908ebc72cd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -66,7 +66,7 @@ public enum flywheelState { /** * Stores the offset of the turret's rotation */ - private double turretOffset = 114; + public static double turretOffset = 116; /** * Stores the zeroing state of the turret */ @@ -118,14 +118,16 @@ public void init(OpMode opmode, LoadHardwareClass robot){ flywheel2.setFFCoefficients(actualFlywheelFFCoefficients); // TODO Build hood InterpLUT for autoaim + // Near zone measurements hoodLUT.add(0, 0); hoodLUT.add(53.5,108); hoodLUT.add(71,168); - hoodLUT.add(77, 184); - hoodLUT.add(88,194); - hoodLUT.add(94.5,188); - hoodLUT.add(103, 188); - hoodLUT.add(204, 188); + hoodLUT.add(77, 181); + hoodLUT.add(88,190); + hoodLUT.add(94.5,190); + // Far zone measurements + hoodLUT.add(103, 200); + hoodLUT.add(204, 100); // Generate Lookup Table & Initialize servo position hoodLUT.createLUT(); @@ -143,6 +145,7 @@ public void updatePIDs(){ flywheel.setFFCoefficients(actualFlywheelFFCoefficients); flywheel2.setPidCoefficients(actualFlywheelCoefficients); flywheel2.setFFCoefficients(actualFlywheelFFCoefficients); + rotation.setOffsetDegrees(turretOffset); } double redOffset = -2; @@ -157,7 +160,7 @@ public void updatePIDs(){ * @param hood If TRUE, enables the hood autoaim. * Otherwise, sets the hood to the highest launch angle. */ - public void updateAimbot(boolean turret, boolean hood){ + public void updateAimbot(boolean turret, boolean hood, double hoodOffset){ if (turret){ // Set the turret rotation if (LoadHardwareClass.selectedAlliance == LoadHardwareClass.Alliance.RED){ @@ -172,7 +175,7 @@ public void updateAimbot(boolean turret, boolean hood){ // Set the hood angle Pose goalPose = new Pose(0,144,0); if (LoadHardwareClass.selectedAlliance == LoadHardwareClass.Alliance.RED) {goalPose = new Pose(144, 144, 0);} - setHood(hoodLUT.get(Robot.drivetrain.follower.getPose().distanceFrom(goalPose))); + setHood(hoodLUT.get(Robot.drivetrain.follower.getPose().distanceFrom(goalPose)) + hoodOffset); }else{ setHood(0); } @@ -308,7 +311,7 @@ public void updateFlywheel(){ robotZone.setRotation(Robot.drivetrain.follower.getPose().getHeading()); opMode.telemetry.addData("In Far Zone", robotZone.isInside(LoadHardwareClass.FarLaunchZone)); - opMode.telemetry.addData("In Near Zone", robotZone.isInside(LoadHardwareClass.NearLaunchZone)); + opMode.telemetry.addData("In Near Zone", robotZone.isInside(LoadHardwareClass.ReallyNearLaunchZoneRed)); if (robotZone.isInside(LoadHardwareClass.FarLaunchZone)){ targetRPM = flywheelFarSpeed; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java index 5116ece8fcde..248a3e8939e8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Commands.java @@ -39,9 +39,9 @@ public Command setFlywheelState(Turret.flywheelState state) { .setStart(() -> Robot.turret.setFlywheelState(state)) .setIsDone(() -> { if (state == Turret.flywheelState.ON){ - return Robot.turret.getFlywheelRPM() > Robot.turret.getFlywheelCurrentMaxSpeed(); + return Robot.turret.getFlywheelRPM() > Robot.turret.getFlywheelCurrentMaxSpeed() - 100; }else{ - return Robot.turret.getFlywheelRPM() < 100; + return true; } }) ; @@ -87,7 +87,8 @@ public Command shootBalls(){ // Reset the systems setIntakeMode(Intake.intakeMode.OFF), setGateState(Turret.gatestate.CLOSED), - setTransferState(Intake.transferState.DOWN) + setTransferState(Intake.transferState.DOWN), + setFlywheelState(Turret.flywheelState.OFF) ); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java index d17b84a13742..5a18905eb4d1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Drivetrain_/Pedro_Paths.java @@ -10,22 +10,24 @@ public class Pedro_Paths { // The variable to store PedroPathing's follower object for path building - public Follower follower; + private Follower follower; /** * Define primary poses to be used in paths */ // Start Poses - public Pose nearStart = new Pose(112, 136.6, Math.toRadians(270)); + public Pose nearStart = new Pose(118, 132, Math.toRadians(306)); public Pose farStart = new Pose(88, 7.4, Math.toRadians(90)); // Preload Poses - public Pose nearPreload = new Pose(128.000, 83.500, Math.toRadians(0)); + public Pose nearPreload = new Pose(127.000, 83.500, Math.toRadians(0)); public Pose midPreload = new Pose(132.000, 59.500, Math.toRadians(0)); public Pose farPreload = new Pose(132.000, 35.500, Math.toRadians(0)); // Shooting Poses public Pose nearShoot = new Pose(115, 120, Math.toRadians(-35)); public Pose midShoot = new Pose(85, 85, Math.toRadians(-15)); public Pose farShoot = new Pose(85, 15, Math.toRadians(60)); + public Pose noTurretMidShoot = new Pose(85, 85, Math.toRadians(45)); + public Pose noTurretFarShoot = new Pose(85, 15, Math.toRadians(67.3)); // Leave Poses public Pose nearLeave = new Pose(90,120, Math.toRadians(90)); public Pose midLeave = new Pose(95,55, Math.toRadians(90)); @@ -37,6 +39,10 @@ public class Pedro_Paths { // Start Poses to Preloads public PathChain nearStart_to_nearPreload, nearStart_to_midPreload, nearStart_to_farPreload; public PathChain farStart_to_nearPreload, farStart_to_midPreload, farStart_to_farPreload; + // Start Poses to Shooting Poses + public PathChain nearStart_to_midShoot; + //public PathChain nearStart_to_nearShoot, nearStart_to_midShoot, nearStart_to_farShoot; + //public PathChain farStart_to_nearShoot, farStart_to_midShoot, farStart_to_farShoot; // Preloads to Shooting Positions public PathChain nearPreload_to_nearShoot, nearPreload_to_midShoot, nearPreload_to_farShoot; public PathChain midPreload_to_nearShoot, midPreload_to_midShoot, midPreload_to_farShoot; @@ -45,6 +51,9 @@ public class Pedro_Paths { public PathChain nearShoot_to_nearPreload, nearShoot_to_midPreload, nearShoot_to_farPreload; public PathChain midShoot_to_nearPreload, midShoot_to_midPreload, midShoot_to_farPreload; public PathChain farShoot_to_nearPreload, farShoot_to_midPreload, farShoot_to_farPreload; + // No-turret Shooting Positions to Preloads + public PathChain midShoot_noTurret_to_nearPreload, midShoot_noTurret_to_midPreload, midShoot_noTurret_to_farPreload; + public PathChain farShoot_noTurret_to_nearPreload, farShoot_noTurret_to_midPreload, farShoot_noTurret_to_farPreload; // Shooting Positions to Leave Positions public PathChain nearShoot_to_nearLeave, nearShoot_to_midLeave; public PathChain midShoot_to_nearLeave, midShoot_to_midLeave; @@ -52,367 +61,481 @@ public class Pedro_Paths { // Start Positions to Leave Positions public PathChain nearStart_to_nearLeave, nearStart_to_midLeave; public PathChain farStart_to_midLeave, farStart_to_farLeave; + // Start Positions to No-Turret shoot Positions + public PathChain nearStart_to_NoTurret_MidShoot, farStart_to_NoTurret_FarShoot; public Pose autoMirror(Pose pose, LoadHardwareClass.Alliance alliance){ if (alliance == LoadHardwareClass.Alliance.BLUE){ return new Pose( 144 - pose.getX(), pose.getY(), - Math.atan2(Math.sin(pose.getHeading()), -Math.cos(pose.getHeading())) + mirrorHeading(pose.getHeading(), alliance) ); + }else{ + return pose; + } + } + private double mirrorHeading(double heading, LoadHardwareClass.Alliance alliance){ + if (alliance == LoadHardwareClass.Alliance.BLUE){ + final double v = Math.toDegrees(Math.atan2(Math.sin(heading), Math.cos(heading))); + if (Math.cos(heading) >= 0){ + return Math.toRadians((180 - v)); + }else{ + return Math.toRadians((360 - v)%360); + } + }else{ + return heading; } - return pose; } - public void buildStart1ToPreloads(LoadHardwareClass.Alliance alliance) { + public void buildStart1ToPreloads(){ nearStart_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(nearStart, alliance), - autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 78.000), alliance), - autoMirror(new Pose(95.000, 83.500), alliance), - autoMirror(new Pose(110.000, 83.500), alliance) + nearStart, + new Pose(89.000, 136.600), + new Pose(89.000, 78.000), + new Pose(95.000, 83.500), + new Pose(110.000, 83.500) )) .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(nearPreload, alliance) + new Pose(110.000, 83.500), + nearPreload )) .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); nearStart_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(nearStart, alliance), - autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 54.000), alliance), - autoMirror(new Pose(95.000, 59.500), alliance), - autoMirror(new Pose(110.000, 59.500), alliance) + nearStart, + new Pose(89.000, 136.600), + new Pose(89.000, 54.000), + new Pose(95.000, 59.500), + new Pose(110.000, 59.500) )) .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 59.500), alliance), - autoMirror(midPreload, alliance) + new Pose(110.000, 59.500), + midPreload )) .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); nearStart_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(nearStart, alliance), - autoMirror(new Pose(89.000, 136.600), alliance), - autoMirror(new Pose(89.000, 30.000), alliance), - autoMirror(new Pose(95.000, 35.500), alliance), - autoMirror(new Pose(110.000, 35.500), alliance) + nearStart, + new Pose(89.000, 136.600), + new Pose(89.000, 30.000), + new Pose(95.000, 35.500), + new Pose(110.000, 35.500) )) .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(farPreload, alliance) + new Pose(110.000, 35.500), + farPreload )) .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); } - public void buildStart2ToPreloads(LoadHardwareClass.Alliance alliance){ + public void buildStart2ToPreloads(){ farStart_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farStart, alliance), - autoMirror(new Pose(89.000, 79.000), alliance), - autoMirror(new Pose(95.000, 83.500), alliance), - autoMirror(new Pose(110.000, 83.500), alliance) + farStart, + new Pose(89.000, 79.000), + new Pose(95.000, 83.500), + new Pose(110.000, 83.500) )) .setLinearHeadingInterpolation(farStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 83.500), alliance), - autoMirror(nearPreload, alliance) + new Pose(110.000, 83.500), + nearPreload )) .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); farStart_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farStart, alliance), - autoMirror(new Pose(89.000, 55.000), alliance), - autoMirror(new Pose(95.000, 59.500), alliance), - autoMirror(new Pose(110.000, 59.500), alliance) + farStart, + new Pose(89.000, 55.000), + new Pose(95.000, 59.500), + new Pose(110.000, 59.500) )) .setLinearHeadingInterpolation(nearStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 59.500), alliance), - autoMirror(midPreload, alliance) + new Pose(110.000, 59.500), + midPreload )) .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); farStart_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farStart, alliance), - autoMirror(new Pose(89.000, 25), alliance), - autoMirror(new Pose(95.000, 35.500), alliance), - autoMirror(new Pose(110.000, 35.500), alliance) + farStart, + new Pose(89.000, 25), + new Pose(95.000, 35.500), + new Pose(110.000, 35.500) )) .setLinearHeadingInterpolation(farStart.getHeading(), Math.toRadians(0)) .addPath(new BezierLine( - autoMirror(new Pose(110.000, 35.500), alliance), - autoMirror(farPreload, alliance) + new Pose(110.000, 35.500), + farPreload )) .setConstantHeadingInterpolation(Math.toRadians(0)) .build(); } - public void buildPreload1ToShootings(LoadHardwareClass.Alliance alliance){ + public void buildStart1ToShootings(){ + nearStart_to_midShoot = follower.pathBuilder() + .addPath(new BezierLine( + nearStart, + midShoot + )) + .setLinearHeadingInterpolation(nearStart.getHeading(), midShoot.getHeading()) + .build(); + } + public void buildPreload1ToShootings(){ nearPreload_to_nearShoot = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(nearPreload, alliance), - autoMirror(nearShoot, alliance) + nearPreload, + nearShoot )) .setLinearHeadingInterpolation(nearPreload.getHeading(), nearShoot.getHeading()) .build(); nearPreload_to_midShoot = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(nearPreload, alliance), - autoMirror(midShoot, alliance) + nearPreload, + midShoot )) .setLinearHeadingInterpolation(nearPreload.getHeading(), midShoot.getHeading()) .build(); nearPreload_to_farShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(nearPreload, alliance), - autoMirror(new Pose(80.000, 83.500), alliance), - autoMirror(farShoot, alliance) + nearPreload, + new Pose(80.000, 83.500), + farShoot )) .setLinearHeadingInterpolation(nearPreload.getHeading(), farShoot.getHeading()) .build(); } - public void buildPreload2ToShootings(LoadHardwareClass.Alliance alliance){ + public void buildPreload2ToShootings(){ midPreload_to_nearShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midPreload, alliance), - autoMirror(new Pose(65,59.5), alliance), - autoMirror(nearShoot, alliance) + midPreload, + new Pose(65,59.5), + nearShoot )) .setLinearHeadingInterpolation(midPreload.getHeading(), nearShoot.getHeading()) .build(); midPreload_to_midShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midPreload, alliance), - autoMirror(new Pose(65,59.5), alliance), - autoMirror(midShoot, alliance) + midPreload, + new Pose(65,59.5), + midShoot )) .setLinearHeadingInterpolation(midPreload.getHeading(), midShoot.getHeading()) .build(); midPreload_to_farShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midPreload, alliance), - autoMirror(new Pose(90.000, 59.500), alliance), - autoMirror(farShoot, alliance) + midPreload, + new Pose(90.000, 59.500), + farShoot )) .setLinearHeadingInterpolation(midPreload.getHeading(), farShoot.getHeading()) .build(); } - public void buildPreload3ToShootings(LoadHardwareClass.Alliance alliance){ + public void buildPreload3ToShootings(){ farPreload_to_nearShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farPreload, alliance), - autoMirror(new Pose(75,30), alliance), - autoMirror(new Pose(80,100), alliance), - autoMirror(nearShoot, alliance) + farPreload, + new Pose(75,30), + new Pose(80,100), + nearShoot )) .setLinearHeadingInterpolation(midPreload.getHeading(), nearShoot.getHeading()) .build(); farPreload_to_midShoot = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farPreload, alliance), - autoMirror(new Pose(85,32), alliance), - autoMirror(midShoot, alliance) + farPreload, + new Pose(85,32), + midShoot )) .setLinearHeadingInterpolation(midPreload.getHeading(), midShoot.getHeading()) .build(); farPreload_to_farShoot = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(farPreload, alliance), - autoMirror(farShoot, alliance) + farPreload, + farShoot )) .setLinearHeadingInterpolation(midPreload.getHeading(), farShoot.getHeading()) .build(); } - public void buildShooting1ToPreloads(LoadHardwareClass.Alliance alliance){ + public void buildShooting1ToPreloads(){ nearShoot_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(nearShoot, alliance), - autoMirror(new Pose(60, 80), alliance), - autoMirror(nearPreload, alliance) + nearShoot, + new Pose(60, 80), + nearPreload )) .setLinearHeadingInterpolation(nearShoot.getHeading(), nearPreload.getHeading()) .build(); nearShoot_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(nearShoot, alliance), - autoMirror(new Pose(60, 55), alliance), - autoMirror(midPreload, alliance) + nearShoot, + new Pose(60, 55), + midPreload )) .setLinearHeadingInterpolation(nearShoot.getHeading(), midPreload.getHeading()) .build(); nearShoot_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(nearShoot, alliance), - autoMirror(new Pose(60, 27), alliance), - autoMirror(farPreload, alliance) + nearShoot, + new Pose(60, 27), + farPreload )) .setLinearHeadingInterpolation(nearShoot.getHeading(), farPreload.getHeading()) .build(); } - public void buildShooting2ToPreloads(LoadHardwareClass.Alliance alliance){ + public void buildShooting2ToPreloads(){ midShoot_to_nearPreload = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(midShoot, alliance), - autoMirror(nearPreload, alliance) + midShoot, + nearPreload )) .setLinearHeadingInterpolation(midShoot.getHeading(), nearPreload.getHeading()) .build(); midShoot_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midShoot, alliance), - autoMirror(new Pose(75, 56), alliance), - autoMirror(midPreload, alliance) + midShoot, + new Pose(75, 56), + midPreload )) .setLinearHeadingInterpolation(midShoot.getHeading(), midPreload.getHeading()) .build(); midShoot_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(midShoot, alliance), - autoMirror(new Pose(68, 30), alliance), - autoMirror(farPreload, alliance) + midShoot, + new Pose(68, 30), + farPreload )) .setLinearHeadingInterpolation(midShoot.getHeading(), farPreload.getHeading()) .build(); } - public void buildShooting3ToPreloads(LoadHardwareClass.Alliance alliance){ + public void buildShooting3ToPreloads(){ farShoot_to_nearPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farShoot, alliance), - autoMirror(new Pose(73, 88), alliance), - autoMirror(nearPreload, alliance) + farShoot, + new Pose(73, 88), + nearPreload )) .setLinearHeadingInterpolation(farShoot.getHeading(), nearPreload.getHeading()) .build(); farShoot_to_midPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farShoot, alliance), - autoMirror(new Pose(78, 62), alliance), - autoMirror(midPreload, alliance) + farShoot, + new Pose(78, 62), + midPreload )) .setLinearHeadingInterpolation(farShoot.getHeading(), midPreload.getHeading()) .build(); farShoot_to_farPreload = follower.pathBuilder() .addPath(new BezierCurve( - autoMirror(farShoot, alliance), - autoMirror(new Pose(82.5, 35), alliance), - autoMirror(farPreload, alliance) + farShoot, + new Pose(82.5, 35), + farPreload )) .setLinearHeadingInterpolation(farShoot.getHeading(), farPreload.getHeading()) .build(); } - public void buildShooting1ToLeaves(LoadHardwareClass.Alliance alliance){ + public void buildShooting2NoTurretToPreloads(){ + midShoot_noTurret_to_nearPreload = follower.pathBuilder() + .addPath(new BezierLine( + noTurretMidShoot, + nearPreload + )) + .setLinearHeadingInterpolation(noTurretMidShoot.getHeading(), nearPreload.getHeading()) + .build(); + midShoot_noTurret_to_midPreload = follower.pathBuilder() + .addPath(new BezierCurve( + noTurretMidShoot, + new Pose(75, 56), + midPreload + )) + .setLinearHeadingInterpolation(noTurretMidShoot.getHeading(), midPreload.getHeading()) + .build(); + midShoot_noTurret_to_farPreload = follower.pathBuilder() + .addPath(new BezierCurve( + noTurretMidShoot, + new Pose(68, 30), + farPreload + )) + .setLinearHeadingInterpolation(noTurretMidShoot.getHeading(), farPreload.getHeading()) + .build(); + } + public void buildShooting3NoTurretToPreloads(){ + farShoot_noTurret_to_nearPreload = follower.pathBuilder() + .addPath(new BezierCurve( + noTurretFarShoot, + new Pose(73, 88), + nearPreload + )) + .setLinearHeadingInterpolation(noTurretFarShoot.getHeading(), nearPreload.getHeading()) + .build(); + farShoot_noTurret_to_midPreload = follower.pathBuilder() + .addPath(new BezierCurve( + noTurretFarShoot, + new Pose(78, 62), + midPreload + )) + .setLinearHeadingInterpolation(noTurretFarShoot.getHeading(), midPreload.getHeading()) + .build(); + farShoot_noTurret_to_farPreload = follower.pathBuilder() + .addPath(new BezierCurve( + noTurretFarShoot, + new Pose(82.5, 35), + farPreload + )) + .setLinearHeadingInterpolation(noTurretFarShoot.getHeading(), farPreload.getHeading()) + .build(); + } + public void buildShooting1ToLeaves(){ nearShoot_to_nearLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(nearShoot, alliance), - autoMirror(nearLeave, alliance) + nearShoot, + nearLeave )) .setConstantHeadingInterpolation(nearShoot.getHeading()) .build(); nearShoot_to_midLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(nearShoot, alliance), - autoMirror(midLeave, alliance) + nearShoot, + midLeave )) .setConstantHeadingInterpolation(nearShoot.getHeading()) .build(); } - public void buildShooting2ToLeaves(LoadHardwareClass.Alliance alliance){ + public void buildShooting2ToLeaves(){ midShoot_to_nearLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(midShoot, alliance), - autoMirror(nearLeave, alliance) + midShoot, + nearLeave )) .setConstantHeadingInterpolation(midShoot.getHeading()) .build(); midShoot_to_midLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(midShoot, alliance), - autoMirror(midLeave, alliance) + midShoot, + midLeave )) .setConstantHeadingInterpolation(midShoot.getHeading()) .build(); } - public void buildShooting3ToLeaves(LoadHardwareClass.Alliance alliance){ + public void buildShooting3ToLeaves(){ farShoot_to_midLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(farShoot, alliance), - autoMirror(midLeave, alliance) + farShoot, + midLeave )) .setConstantHeadingInterpolation(farShoot.getHeading()) .build(); farShoot_to_farLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(farShoot, alliance), - autoMirror(farLeave, alliance) + farShoot, + farLeave )) .setConstantHeadingInterpolation(farShoot.getHeading()) .build(); } - public void buildStart1ToLeaves(LoadHardwareClass.Alliance alliance){ + public void buildStart1ToLeaves(){ nearStart_to_nearLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(nearStart, alliance), - autoMirror(nearLeave, alliance) + nearStart, + nearLeave )) .setConstantHeadingInterpolation(nearStart.getHeading()) .build(); nearStart_to_midLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(nearStart, alliance), - autoMirror(farLeave, alliance) + nearStart, + farLeave )) .setConstantHeadingInterpolation(nearStart.getHeading()) .build(); } - public void buildStart2ToLeaves(LoadHardwareClass.Alliance alliance){ + public void buildStart2ToLeaves(){ farStart_to_midLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(farStart, alliance), - autoMirror(nearLeave, alliance) + farStart, + nearLeave )) .setConstantHeadingInterpolation(farStart.getHeading()) .build(); farStart_to_farLeave = follower.pathBuilder() .addPath(new BezierLine( - autoMirror(farStart, alliance), - autoMirror(farLeave, alliance) + farStart, + farLeave )) .setConstantHeadingInterpolation(farStart.getHeading()) .build(); } + public void buildStartsToNoTurretShoots(){ + nearStart_to_NoTurret_MidShoot = follower.pathBuilder() + .addPath(new BezierLine( + nearStart, + noTurretMidShoot + )) + .setLinearHeadingInterpolation(nearStart.getHeading(), noTurretMidShoot.getHeading()) + .build(); + farStart_to_NoTurret_FarShoot = follower.pathBuilder() + .addPath(new BezierLine( + farStart, + noTurretFarShoot + )) + .setLinearHeadingInterpolation(farStart.getHeading(), noTurretFarShoot.getHeading()) + .build(); + } + /** * Builds all the paths, mirroring them to the other side of the field if necessary */ - public void buildPaths(LoadHardwareClass.Alliance alliance, Follower follow){ + public void buildPaths(LoadHardwareClass.Alliance Alliance, Follower follow){ follower = follow; + nearStart = autoMirror(nearStart, Alliance); + farStart = autoMirror(farStart, Alliance); + nearPreload = autoMirror(nearPreload, Alliance); + midPreload = autoMirror(midPreload, Alliance); + farPreload = autoMirror(farPreload, Alliance); + nearShoot = autoMirror(nearShoot, Alliance); + midShoot = autoMirror(midShoot, Alliance); + farShoot = autoMirror(farShoot, Alliance); + noTurretMidShoot = autoMirror(noTurretMidShoot, Alliance); + noTurretFarShoot = autoMirror(noTurretFarShoot, Alliance); + nearLeave = autoMirror(nearLeave, Alliance); + midLeave = autoMirror(midLeave, Alliance); + farLeave = autoMirror(farLeave, Alliance); + + /// All paths are for the RED side of the field. they will be mirrored if necessary. // Paths going from each start position to each of the preloads. - buildStart1ToPreloads(alliance); - buildStart2ToPreloads(alliance); + buildStart1ToPreloads(); + buildStart2ToPreloads(); + // Paths going from each start position to each of the shooting positions. + buildStart1ToShootings(); // Paths going from each preload to each shooting position - buildPreload1ToShootings(alliance); - buildPreload2ToShootings(alliance); - buildPreload3ToShootings(alliance); + buildPreload1ToShootings(); + buildPreload2ToShootings(); + buildPreload3ToShootings(); // Paths going from each shooting position to each preload - buildShooting1ToPreloads(alliance); - buildShooting2ToPreloads(alliance); - buildShooting3ToPreloads(alliance); + buildShooting1ToPreloads(); + buildShooting2ToPreloads(); + buildShooting3ToPreloads(); + // Paths going from each no-turret shooting position to each preload + buildShooting2NoTurretToPreloads(); + buildShooting3NoTurretToPreloads(); // Paths going from each shooting position to the leave positions. - buildShooting1ToLeaves(alliance); - buildShooting2ToLeaves(alliance); - buildShooting3ToLeaves(alliance); + buildShooting1ToLeaves(); + buildShooting2ToLeaves(); + buildShooting3ToLeaves(); // Paths going from the start positions to the leave positions - buildStart1ToLeaves(alliance); - buildStart2ToLeaves(alliance); + buildStart1ToLeaves(); + buildStart2ToLeaves(); + // Paths going from the start positions to the no-turret shooting positions + buildStartsToNoTurretShoots(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java index ce3842afbd6c..2e023e363459 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/LoadHardwareClass.java @@ -69,7 +69,7 @@ public enum Alliance { new Point(48, 0), new Point(72, 24) ); - public static PolygonZone NearLaunchZone = new PolygonZone( + public static PolygonZone ReallyNearLaunchZoneRed = new PolygonZone( new Point(72, 72), new Point(144, 144), new Point(0, 144) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 3bcfb2fee56a..40003293eb05 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -29,7 +29,6 @@ package org.firstinspires.ftc.teamcode.LOADCode.Main_.Teleop_; -import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass.robotPose; import static org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass.selectedAlliance; import com.bylazar.configurables.annotations.Configurable; @@ -49,6 +48,7 @@ import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.flywheelState; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Actuators_.Turret.gatestate; +import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.MecanumDrivetrainClass; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.Drivetrain_.Pedro_Paths; import org.firstinspires.ftc.teamcode.LOADCode.Main_.Hardware_.LoadHardwareClass; @@ -68,9 +68,9 @@ public class Teleop_Main_ extends LinearOpMode { public static double DylanStickDeadzones = 0.2; public int shootingState = 0; - public boolean turretOn = true; + public boolean turretOn = false; public TimerEx stateTimer = new TimerEx(1); - public static double hoodSpeed = 4; + public double hoodOffset = 0; // Create a new instance of our Robot class LoadHardwareClass Robot = new LoadHardwareClass(this); @@ -78,6 +78,10 @@ public class Teleop_Main_ extends LinearOpMode { Pedro_Paths Paths = new Pedro_Paths(); // Create a new instance of Prompter for selecting the alliance Prompter prompter = null; + enum startPoses { + FAR, + NEAR + } // Contains the start Pose of our robot. This can be changed or saved from the autonomous period. private Pose startPose = Paths.farStart; @@ -87,36 +91,55 @@ public void runOpMode() { // Create a new prompter for selecting alliance prompter = new Prompter(this); - prompter.prompt("alliance", new OptionPrompt<>("Select Alliance", LoadHardwareClass.Alliance.RED, LoadHardwareClass.Alliance.BLUE)); + prompter.prompt("alliance", () -> { + if (selectedAlliance == null){ + return new OptionPrompt<>("Select Alliance", LoadHardwareClass.Alliance.RED, LoadHardwareClass.Alliance.BLUE); + }else{ + return null; + } + }); + prompter.prompt("startPose", () -> { + if (MecanumDrivetrainClass.robotPose == null){ + return new OptionPrompt<>("Select Start Pose", + startPoses.FAR, + startPoses.NEAR + ); + }else{ + startPose = MecanumDrivetrainClass.robotPose; + return null; + } + }); prompter.onComplete(() -> { - selectedAlliance = prompter.get("alliance"); - telemetry.addData("Selection", "Complete"); - telemetry.addData("Alliance", selectedAlliance); - telemetry.update(); + if (selectedAlliance == null){ + selectedAlliance = prompter.get("alliance"); + } + telemetry.addData("Selection", "Complete"); + telemetry.addData("Alliance", selectedAlliance); + if (MecanumDrivetrainClass.robotPose == null){ + startPoses pose = prompter.get("startPose"); + if (pose.equals(startPoses.FAR)) { + startPose = Paths.autoMirror(Paths.farStart, selectedAlliance); + telemetry.addData("Start Pose", "Far Start Pose"); + } else if (pose.equals(startPoses.NEAR)) { + startPose = Paths.autoMirror(Paths.nearStart, selectedAlliance); + telemetry.addData("Start Pose", "Near Start Pose"); } - ); + }else{ + startPose = MecanumDrivetrainClass.robotPose; + telemetry.addData("Start Pose", "Ending Pose of Auto"); + } + telemetry.update(); + }); // Runs repeatedly while in init while (opModeInInit()) { - // If an auto was not run, run the prompter to select the correct alliance - if (selectedAlliance == null) { - prompter.run(); - }else{ - prompter.run(); - } + prompter.run(); } - if (robotPose != null){ - startPose = robotPose; - } - - // Initialize all hardware of the robot - Robot.init(Paths.autoMirror(startPose, selectedAlliance)); - - telemetry.addData("Status", "Initialized"); - telemetry.update(); // Wait for the game to start (driver presses START) waitForStart(); + // Initialize all hardware of the robot + Robot.init(startPose); runtime.reset(); Paths.buildPaths(selectedAlliance, Robot.drivetrain.follower); Robot.drivetrain.startTeleOpDrive(); @@ -141,8 +164,9 @@ public void runOpMode() { telemetry.addData("SpeedMult", Robot.drivetrain.speedMultiplier); telemetry.addLine(); //positional telemetry - telemetry.addData("X Position: ", Robot.drivetrain.follower.getPose().getX()); - telemetry.addData("Y Position: ", Robot.drivetrain.follower.getPose().getY()); + telemetry.addData("X Position", Robot.drivetrain.follower.getPose().getX()); + telemetry.addData("Y Position", Robot.drivetrain.follower.getPose().getY()); + telemetry.addData("Heading", Math.toDegrees(Robot.drivetrain.follower.getPose().getHeading())); telemetry.addData("Distance From Goal", Robot.drivetrain.distanceFromGoal()); telemetry.addLine(); @@ -292,7 +316,7 @@ public void Gamepad2() { if (gamepad2.aWasPressed()){ turretOn = !turretOn; } - Robot.turret.updateAimbot(turretOn, true); + Robot.turret.updateAimbot(turretOn, true, hoodOffset); //Intake Controls (Left Stick Y) if (shootingState == 0) { @@ -310,6 +334,15 @@ public void Gamepad2() { }else{ // OFF Robot.intake.setMode(intakeMode.OFF); } + + /* TODO Uncomment once autobelt control is finished + if (Math.abs(gamepad2.left_stick_y) >= DylanStickDeadzones) { + Robot.intake.setMode(intakeMode.INTAKING); + }else{ // OFF + Robot.intake.setMode(intakeMode.OFF); + } + */ + //Flywheel Toggle Control (Y Button) if (gamepad2.yWasPressed()) { if (Robot.turret.flywheelMode == flywheelState.OFF) { @@ -321,17 +354,13 @@ public void Gamepad2() { } Robot.turret.updateFlywheel(); - /* Uncomment all this if reenableing manual hood controls // Hood Controls - if (gamepad2.dpad_up){ - Robot.turret.setHood(Robot.turret.getHood() + hoodSpeed); - }else if (gamepad2.dpad_down){ - Robot.turret.setHood(Robot.turret.getHood() - hoodSpeed); - }else if (gamepad2.dpadLeftWasPressed()){ - Robot.turret.setHood(152); + if (gamepad2.dpadUpWasPressed()){ + hoodOffset += 10; + }else if (gamepad2.dpadDownWasPressed()){ + hoodOffset -= 10; } - Robot.turret.setHood(Math.max(Math.min(Robot.turret.getHood(), Turret.upperHoodLimit), 0)); - */ + //Shoot (B Button Press) // Increment the shooting state From bca8d0c32f5fc682e0adf28a9de0acfe8ad7bcce Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+professor348@users.noreply.github.com> Date: Sat, 17 Jan 2026 09:42:04 -0500 Subject: [PATCH 151/152] Quick bugfix with one of the InterpLUT points for hood autoaim --- .../teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java index 96908ebc72cd..e2682fb4795e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Hardware_/Actuators_/Turret.java @@ -127,7 +127,7 @@ public void init(OpMode opmode, LoadHardwareClass robot){ hoodLUT.add(94.5,190); // Far zone measurements hoodLUT.add(103, 200); - hoodLUT.add(204, 100); + hoodLUT.add(204, 200); // Generate Lookup Table & Initialize servo position hoodLUT.createLUT(); From 007b91dc8ffbef07553dd84406ff124e4014d142 Mon Sep 17 00:00:00 2001 From: Professor348 <141444315+professor348@users.noreply.github.com> Date: Sat, 17 Jan 2026 15:44:47 -0500 Subject: [PATCH 152/152] Auto & teleop work during scrimmage --- .../LOADCode/Main_/Auto_/Auto_Main_.java | 51 +++++++++++++++++-- .../LOADCode/Main_/Teleop_/Teleop_Main_.java | 12 ++++- 2 files changed, 58 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java index 82501e12efbd..978d0c6fa1e8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Auto_/Auto_Main_.java @@ -58,7 +58,8 @@ public void onInit() { )); prompter.prompt("auto", new OptionPrompt<>("Select Auto", - new Leave_Far_Generic(), + new Near_12Ball(), + new Near_9Ball(), new Leave_Far_Generic() //new test_Auto(), //new Complex_Test_Auto() @@ -181,7 +182,7 @@ public void runAuto(){ public String toString(){return "Far Zone No Turret Generic";} } - private class Near_Generic extends Auto{ + private class Near_9Ball extends Auto{ public Pose startPose = paths.nearStart; public boolean turretEnabled = true; @@ -217,7 +218,51 @@ public void runAuto(){ @NonNull @Override - public String toString(){return "Near Zone No Turret Generic";} + public String toString(){return "Near Zone 9 Ball Auto";} + } + + private class Near_12Ball extends Auto{ + public Pose startPose = paths.nearStart; + public boolean turretEnabled = true; + + @Override + public Pose getStartPose(){ + return startPose; + } + @Override + public boolean getTurretEnabled(){ + return turretEnabled; + } + + @Override + public void runAuto(){ + new SequentialGroup( + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + new InstantCommand(Commands.setFlywheelState(Turret.flywheelState.ON)), + Commands.runPath(paths.nearStart_to_midShoot, true, 1), + Commands.shootBalls(), + Commands.setFlywheelState(Turret.flywheelState.ON), + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + Commands.runPath(paths.midShoot_to_nearPreload, true, 1), + Commands.runPath(paths.nearPreload_to_midShoot, true, 1), + Commands.shootBalls(), + Commands.setFlywheelState(Turret.flywheelState.ON), + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + Commands.runPath(paths.midShoot_to_midPreload, true, 1), + Commands.runPath(paths.midPreload_to_midShoot, true, 1), + Commands.shootBalls(), + Commands.setFlywheelState(Turret.flywheelState.ON), + Commands.setIntakeMode(Intake.intakeMode.INTAKING), + Commands.runPath(paths.midShoot_to_farPreload, true, 1), + Commands.runPath(paths.farPreload_to_midShoot, true, 1), + Commands.shootBalls(), + Commands.runPath(paths.midShoot_to_nearLeave, true, 1) + ).schedule(); + } + + @NonNull + @Override + public String toString(){return "Near Zone 12 Ball Auto";} } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java index 40003293eb05..7f80337d4b8f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LOADCode/Main_/Teleop_/Teleop_Main_.java @@ -68,7 +68,7 @@ public class Teleop_Main_ extends LinearOpMode { public static double DylanStickDeadzones = 0.2; public int shootingState = 0; - public boolean turretOn = false; + public boolean turretOn = true; public TimerEx stateTimer = new TimerEx(1); public double hoodOffset = 0; @@ -255,6 +255,14 @@ public void Gamepad1() { Robot.drivetrain.speedMultiplier = 0.66; } + if (gamepad1.bWasPressed()){ + if (selectedAlliance == LoadHardwareClass.Alliance.RED){ + Robot.drivetrain.follower.setPose(new Pose(8, 8, Math.toRadians(90))); + }else if (selectedAlliance == LoadHardwareClass.Alliance.BLUE){ + Robot.drivetrain.follower.setPose(new Pose(136, 8, Math.toRadians(90))); + } + } + double turnMult = 2; // if (gamepad1.left_stick_y == 0 && gamepad1.left_stick_x == 0){ // turnMult = 1; @@ -364,7 +372,7 @@ public void Gamepad2() { //Shoot (B Button Press) // Increment the shooting state - if (gamepad2.bWasPressed() && shootingState < 2 && Robot.turret.getFlywheelRPM() > Robot.turret.getFlywheelCurrentMaxSpeed()-200) { + if (gamepad2.bWasPressed() && shootingState < 1 && Robot.turret.getFlywheelRPM() > Robot.turret.getFlywheelCurrentMaxSpeed()-100) { shootingState++; } switch (shootingState) {

Mc4Cti@@e>~2l&QHnwGOO$~l@{#(mbA9k zgB<(}B@P?wgwGFf}IE{E}#6QPAib#vTsn2 ztlM}N!ZjRn2NdAMH2Fq7A=j#4k2=sux!$-b;KFzzo1zy5$9-7zqk9ufrBM?l3Pd|9 zI`K8>rfa~5%SgoUtK)wyb#4fE7~1`MM3{XS?)zvQm!W%jCI^N}+;X`;KMM@w6d*-+ zbA3Lkd8pvJQHwVLH}^MEFNW{%?x}Wo9WR3pJt|`+L}??zz}YAuFM@t{ZtjIDa8|{k zu9;XThMq`k=P&sQ%J(pj_+}3d{gn18*>|2PyBHwOuAdt^)M9+$9dNTpO!4y?Ubsd-vJCQZ0f){@pU$qqUcDW)21kobl~!f=#BAZ#KC><&{gFNKZp$UMyXxo9nS zjt?wz(!~rz*lA&{*;;|VAB2DQVevjXwP3vJZaGo{Dp=)XhT;9+CJKlkic@-$IhQ}l z+{EeS`lbdwSe)&l7rSGzf9xlL9n8{VW~3!XZiGQUg9Iog-s{C2aQFl9vrT18Y2}e$ z7J-(O8ck7#ZBStQ1{e!kmEaU?hQE{?=QK2z^zTRO3Q7_(*{L#a3X3P>#84lr2l#=_ z>sX?vzP=d(+(^)|e@9F(s0>A}eVcVt{Y;s*s)?JD9Istj0QY4~Cnw|;Sl`}>0FO7w z$?MjXAc8nJoz7Y#zBuDNspeJS)(}q;ABW}R5q!efpuczUdH+C3>YZdm3<1-0Q-nii z;f7a=AIiH$X=C?)7|NqL=wJwgiYSg`AA8|O!@!7rLS0=A5#^)Xe~jU#`Yg*_{D z))&`wSg+k&GGE!1a|Yq%0W&jaD8c$-gWxRuNA>GWk^vW8CV1h|AxTMRxV-HxE^r+X zNPmwQ8Nr$OW>}7?%qc5mt+GkEoh_uxwc2=sp!m)}{ucLLW4Nf2dR(Zt2hI%o^#bQT zU+{s%BO9ZyWb5F-p$b3BBNg1=mk=p=aCK|4BE+q_u-0{~WOn;5?9!*W zgvPVuDbpo5In*?ygM~|9Ctq?a|6w8jSnuVJwXdB)dZ8gLXRBvwe=pTe1B^~|ko3t< zfrwS+ynvIY)wNRi!J>bz2td<2dOGiPcowd4qJU3~Uy8kc@}06lOsY94pIg{qZwi7l z$2`1^z^6rRPx9oj{~vYLD)@iQ^8Y2QU9c&Qxo?+NDC{5ay)pMs;qgz9bw=uJu(;h5 zWGzKS;5-)mR65O?I7py%A+7q1E0Qg5JL#0w#w=V;XaPC{U&h8- zsOxPrf41)A!b;BEy%Lixq8*MIhw29M{))bbMECFp2PYb(X}0r=K^Aq^kpq;ZdfG~_ z>bD6B#xYg_v^A3s4HenQi@vXc$OMqG; zAb3~7jJPBe+MD;xj7GXT*u38tThd50%-NH+feKBppfmCmCb~_sfD0)b!$~n_N$ZWw z^GKm>LmJ2E#d^+p@+YEH1%lmuBAPT}djtW$bVz-H9t2Kvz=3?EQ}t+t{Gm1tJV(*O zrjLi*&YTu%{y97Ak%#==Qhe#&6-EZSU3&Cj%Qb3&Gzf5s3G{Dov(BB*bokPcahP;X zY~pRg);9@vH;IURFH;A&UUAbAjD19a+BwGK#4xm>B}ZZhn)ScqShF3=d+LKfd$dh- z_9TmjH8mmeR0$j*)s0THvl$knzH6vF7bw`8RMjG1?*}2A>>{R^E?Qwi2fd|7ka?4h z36T3~=GZu$=@n+V3Cuc~Rwp`#hF*L#xn`g>L7Hn>j!*fFoxY-Qk4^LDOhfj=Zp?2E z_p0z-R|Z)G2?tsQhOG)}3z|Yo#+WcdegR?M{TZEUraZ~3YqawR8}M2?$Z48J+Bpy# z<(;YM#~Yr4(1-R0M#0e4*H_==oE39g!a$Ye5fn9u3TwIf+;6eSxPqJBx@|5>lDpa4 zE6xU266MSpOM@gngyFlZyfk^8vP#Tpu94u1YOAVt8!$rIN87z{ecW+nQRqlMk%nvP0UNhUg;iP4CRGS)Xd!24A^5;Z(RVvd&pRmOqzLKh{`&bq$o+sj zxP7gwPh{da_-METDscwI3#A?B;u?RjD>T)5;=iFS8s?s!+Q$0^&m$rU;dghbPxce> zf2oqs>9_wizk$J-;%9$g*?C?>4ab6r%@@m;}yF<+tx(M0~hF4 z7?52^O6r@2OA2VH)_+-XVMww9j+vOdTM}*(ZT9cyY@Tc%3qd>Q^v!Uar|HA?} zJy^$kp!v{NK}9{1M`uw7pL@EhJ08-rSKGQQw_PaHZgD*)J}jJav9h|NtTYb9VI7`B z-ddU0mtS#%mO4FL;HDcM`IiX?}T`G!m@@GsfD@XhrZZP zQ+fs9bTY-{dZxa?f#U0tk)9tM+E&-p#CbbP)7}~`^aSMj661k$(|qZeR~%lY7H0uq z?po;jY+J6n1WM@%;aFaDwRSjJT1{(fQifVvRNWPSi7j57$ivg z8WYl}?8bZjt+Eo<9T^YvudlC*C)Nipc)2@$%(SEhO|EsP z=DB;Q9FjG2UGyjBvnIge__436sLo9#O53Q_$UNLfLS~O-Zpy4#i?dilzuW%DiVx79hwIQy0FD=(CnuP+rO0*L|d>;H=T16IUEfPkg(=XA2&@e$T0B-=ne z?*jPC)T$mZv-_Qn-j2uPHK{soL}Z(5DGUp30ouIwMK@ z(U25l~`^~6k7`jnwei$avX3_cak=+xc`#T{5dtW#JLzHp}_>f2A zf(M||1Kj-l7~>1=XQ|eak`qM=UuvP@yb%$B7|Dj$X8nD_V_17?l1oBTMmY0KNZD_a zsvEATb1@v2tn}|gHwU;2wRW<2T?em!U)4+yP=CzsIa;O$5_Hv*(A#&qTALE@Ghw0;%jXM!nZ-E{fh+0IA!H>cT} zop<&3c8sy)>c-Znc)dz1YfsE6t=cl}L*Id+f%EH4CW0Eb*QGXh4xN6n64z&gNOB5alx%UcUHWQB4@NMskUy1PHuvg&uvq1$^LIdvi7 zf~pKSGSn+{G%B?5eOgNNBgG`TAW0&*hlf{`!p9}-!~}HMN`!?8KBS5GWi;Y@hd~Ed z0%yO=t3DIoHhOP^NOw8c2l5}8SN|fNb|3r(%?iw>Fk*Z}p54@6RN1{^#te`ppBHa` zYwq8DMZjo_J9K;24Od-Pd%PUu=I0I{P;Dnt#GF3FX}ybO;u05*d-L*jsz>7B_Pydq zT6865J^AM)``GTcm-a}IYnmP4cxx;X(-!r#pei9zAsf9#JO!6rS$sGw!1Rd!oc+!y zHy{$f@uZqLs&RVFe;>m$5cDo++9{trO>d;iJ^wBe{-}b>J=LhN4?k9pzQx z^D(x>+ro{jJ$y=*%z(9N^rmg&<&G$R=W^4efIzn9Wuf7h&$)>&ZA^~Yw>;^=4pnWhJ$Yg<*UQeJ<|y|LxCQjEU*uV zmM)I&7Le$f{7?=E%$=14HW1SC|8;``Zvh1o7@Gp-dbn4&D?*cwbhi%yf1AhxDuK;) zYMtXL7fqnmYq9_Fqar{9fDZs6lS+03TERVrqT{Dlu;J^|`(m;H62#2@3`)K!Vz<|8%F=y2pW+Uw=s5R@uh?cCcV2Z5UWk{stqf#N3i8`1k!vWzP^ zD{2q4B-s49JWyg0OjB)wrUXPxw$2FBes-^xvJv7}lOx_a@bA*QU@`*9KBEWAYR!`D z#nquVT|$%b-AE@>(8lhm8&Uj%+(>f3EQS0zGB9rTRE*WXj&Sk`U_{K=fn#MNiehA-?@ zFAJRW6mupj@=~13SNeDQQ7bu&2exngocLNAg*#%(u~;)Rb9$zya|BByf`1ovF3-H7 zP+W!%=%?tv>Lc7kHNzYRdHXbbezT=Rz_WiBN7RfMVD)2>ouY82?$x&{*MbG7Hwjuu zE(wub^uK6+W`w_A0UzT&dQ*xpi_}PpTPbaP(d^pWV`l6h-~!6V*jNk-f!KY~jEnTo z3YfxzKK_qX_EG5e>q-tbN1bBo57i_q+Z`N!d9Q(IN8ITj^~W;l4L^wU3(`ntntZ4Ori{u~ zF#4>GzLCCcGlf-AAo`0C+^Sa5WY@q=YW_Ba(`!8Ogi9FSx|-=&O{%tr{V#=@h-??q zBHKU+O?E{JJ;ikL19!*fV&?{4-ZR$*@%gLiO04knVN1~S-QvNR^^5I*(PALY#@Nib z_vg>=jlZ-c!Y*!?5$IJ3fN#MGYMJ(78oC$-)pKBVJ@dV>6L-{9+1}f+ay;WPxGnU zd&;c=65dWY+)q|CfTE~v%CPEbs}V5X0Z4LV<8z>RUH+5!T~EvbL2z?#;L9OE`_?M4 zWneGqJXdbWC+M~?wuGTuce+$d?zfAz{7MzwPXnw(N=D~_NUjD-V zL2<8jhUes@kfD&Aii)VykfoUjoddnj7PLvY^_)5gU@(yujnM2B6|SKE8{?34%9tz| z7xdS2IjI46=pG%%{_!lTu3oyE^CJ(3iD-1+A(rHFBpLD9B=P1_ zK2w!~)LflhKI^*Dey~Ka(RTDw{E+^c&>@Y5MFT^_?p9thI}#+k!vC>?@!fM$fkPn9 z^Ck;-H$s+mn}x>jl7L!NFgl)WbaSIvsnPqG(y)T#duD-8Xu)FV<)sw0uqSnNa!%*b zvW3hx%f=7Mk0fVd>eS8qfdHLk0zvAo$xG0HQN`q$RbE4hk-0wb#f7EZW`mL4+}H<_ zV60eJTwQ(M?T@#I8#JSHREel>OG@3g1}%Q6sKu@#=VLW{lOfJ#JLmX6@Kv%IlchY~ z-phVtH|hW7OJc?Fs`V6YH8KA_HotRd0GzRju6nU(K|VA-+yr35QYc8vl@(R7@i$m& z0R)`+{wP@Stc{*m!lW4=GqXhKWzl~x55#T`pcH|frxUeAd;{6eDg}q`2)-wroHg~* zZ}KXl$6df_NHa2kWT2SCIWpt|TM;1h<0Yn)SdcE`ZXln|PmD*Z>iNcTfCtEYbAqyR zETql0CrK+NU%T?I$+GmFvXj<*= zSgtUEL5h!`3o={YH&73|NT`Ce33?s8a;mpP+&2>oLR2J$tq-h5x)&$uw#3VWgOTNN z!QJ|WNzeDYfj$Y!B+Q*IV2EKF^njBi5kixlo&CL%TFigCd1CHGzve`e;VqD1Xg73i zW0ADVhW7bI$|#-W<+xjW->hRcP{UMl{HV^9yr6r$ zAt+K!3CmUHK^92oZ_s97T-_V^tG-?oeXX=G&Qd($9Ka`a|~(T8%QSWr3}c{CxUd9ETeus@h!cTIh`>um0FM zu?sS~08(|-k5PZ|u<;df!yZ{ETBrA-sP_lrDkojvw$k~}cpQ9E9A@E_}KMMoU&K(dPRq=P^eefq+iG`UJ4M`wF zv#`ANt2XRCb9L?4$23+wxAToYwcqZ3mD-XlZeYy8L9&7<+tLyn$Imc-xjp3qt*-v_{@p~(9-#tJCn0Vvjw_qAZ8g)n(N#4L%7n~OG@2cD4jIeCS8 zHQ=)v&43pGZ+7}33V5NZ_7b=%mGSkh?+ZijmttOA zj8_nYW~@{4a>m(vtkE31c_OihJXR&qRluNYOZA46TSkeDas z8kQkK`G*}rw{wsVzZ@aLfT&ejpADLcC^XHRpgbg%oLjA@OUf<48yRVIVK>7c$=*UJ zsRioAMu{{gy?IUN`8k;zSp`8%XsA@v{_@Y&#aL~VC}t!_RN@yi`&)(QD6QaYZ2j!? zE_1uu8Ob``zMnsNN-E84%RW@L{P^*U_IiGvJSrLuqv@^Bm1Rvt-OQ_Rm1F=-0TYoq zHjEjV+B-NIfQHL+i9_&XwMpwYKOLi|kRbDG`N%MS7zl5F2E9ZUkAIE&+VyoZ#k&_| z4swxg?D7W+bA!bn<)Z3vR=y5p&IKh-FE*jV#1w;Z^nc!w3$| zSnBUO-(t<%b-NZ#e6{A1nCjfVD9$!i~r)T1>W?xPzFk}ST9d5xvL_er14 z(m5zC{<%8!)UA|9^eVXVOuDQbj~i?^Du_KPQoY3foQ(*R`dby7c{OLU*<*2jPec1T z$#Wv@L0RdhA9PZ;qpRZE2Aa?%7FsEP3TjR0m?@%vJH1^LCe_6GPPVJ1pWjWbYo-%a z8%Cfm>4FT%&maHH;Y0+WfwjIX0%=0;bbzPlb=AWzbLHPJqmMV~{{AJe1}MrJ%>~-N z0_VlvSa+xO%w@rSb&>=CP^XFh)QxZTS zD$n0lte9aA-Z%ZqKfQ`c2Lwv|_4go6#4nu>EVNH=8_dc593Uw^F9JtHk@w*Pg5J|u zO$6p-0w8i!2QRe0cdn1p_d_AqYI`SCQcEa-eW9ey6YqKJRS~#^obHh8FqyM+W-&60 z#*nk%a5yiyQqdvl^=Ks=nQO|CxyI8+{uccQ8OP*O(j>?U1r(OC(6k&We{%U1b7~yc z4AN0DYzK6===DF!vJhKPIh+p-*ylP!P?y_ z9OCSN*<_6S@e_So97CG&Yb_E02}GQ(BB^QDeO)-aRnII(ZL)%tDe8-CMTC|*N(w{6 zbox#_j;)bkE-wq347a!)Of@A-y4>1mMH&5$^eQpZtt=_0EOHc7pWMzElhv;JoUocL zzRTAAm$8wNEjfSM8*{e;JgXk*y`kL&pXw z(C@mHL%KPkqZV{SZg#OK2m$npTAEQh>5?OSIZr<6k_O%~K>R}lEcirpn0Z#!es$_*j1(Qnx30QhXozZv*b!&N>mdJnRLJ8L>^I=v}%X&!)5aIgGRV zM~sHcv{@C3HOZ--^<4J~uI2A2)2D8oGmenIg%33?Z!&5?(Ld&cRn)QUR=!Wlz1J9CeYMObSMu7LQ~|sk#u|u@I)~*i%uuz9iQ8 z>d^ewog{wv)wB`fyW}7$)*;&(^^5gBO?>wIYX(D~mmJLP^z8H_pA&H}50Zta-m7ZR zfeZ=iY46ah@yeKyNuadyesOw+347v8+@|I6ujz|5Q`gAKsv|=8*~z0&WG8y5G3UG} zjV5C-Nq!iq?D3t%#lP`;7PSMbdQ8jjpWA(tFp1#S6G|ieJ`rW;>LvXT!C{_ znx$HRn6@;7GjJViIn%u2G}40n$%#{*zH99e!g8_upUU`Di`|=A zDgb4aY~8~-CC21wGUTX?3@GkST#y0!2ouN;+7^Ip--`ZTL8=zRfjUSEuz45RrsT1$ zQRH2|wzcFslG2I77-S>H+&ey$WqfZje@%(gv^EW><#RbwsGI@4He^dU*I$ViJQ^5CrT7*W=WJWM^6eL;&Gp5ETYNW6}bWp zC8b>XLignr#gnT@PEH<168{M>J58&4;Gig}+I>FFSmdAEIP>0ASx%@(NDq4l9JE== z=mV$g7DZF`?T={SoIVNQ3|m+C1|dzzJ;WQs%*Y68vG=XqChNXw!Oqeif}u3*ST^&~ zEr@VfQg|vdwFW6OGZ4EiC|rF6`Qw%`xEUhPgL$2y!{|r;gV8P<_6NO)%$zNk41M4h z|Hlf(q^s2MCnFJn6?y(?!HH)u*vf@wL>DXFzCeA@($gHF=iy=SE${dcok^`a%iP&x z)5Vbjm=}qS{nuw*Lm9Q%h)?!|Z>I$PFPY`!#92oGV2*JyYQtB!L8hXGi$R)ed>~;77L76cb=>H#4L`FZtL$})ZiRvw!W(B zz+UkUc7KCq{44a47KmH1is>V)eun0}WTEE)Feq)tV=p+5@x#bwu)IlW@gbb%F1Hjt zzqcgSQg|!|KlZDxR&JgNP5Zcume$Z;XPH9|4uAe8B;zc&&dkh&)lYn@!DdO4tYUC8 z#as7>JX_&fM`qEDd(nC|YR^Fk`@z!aw)3n=rGP14TFq605trJW>>3G;k;~7GFxJ=j zmx?SgH!KYMD@cdvxHLdxTkp2nw0r~a5w-@~)(Z(`)e@*SfOA34n4A4kC!7|I2Vvt| zh+8}_8@;h&Gh_9C_3rGTrt8i@&VOR_^E( z;M+2sI-X>3>n%^7$g2bG~?w5yjPAOIfO?{g^VclevNI! z;L1+o%SQ~5+V(4ceV}E&%eZOcTAB&;shBhJio< zN&kN&E3TT^RmDuJ@*VEK73^PHmUNlC`hNHExCW?+PUnB-i3I{h)J>1T+wXmN9slYT z1H|HN9s{eAQ=Iaj8qSV?Rat9F*hBX>ZDsWmrvHbrw~UIqQTs-jVd(B|rMo+&l$4b2 z?(S}+M7l##O1eu*8bm-qQo0$s-aq%=`#k$SXRWiIFSF(g3=5cRu3ug>KxY_7JlUnB z1H|i;1cdm_zL`v06ZQEx;R*M7X!ThZ5f|mmjX=*(DnA2tTLw7TfLo(nJ-Kyy)PE@q zAAl4<+kE)vj{(%}nld-a5dcY4C>Y+n9O(K{BOi2LWjK2J5f-oR$x#4)3R{OrSUeD_ zqI9QD@6Wk+={ch> zM*|1W#bjtxWLVR7zPB8-)Q%By?s4~@L3$ih-@L%s{1nr80y1ObX zNk~Y{flup)*LU{_rzm32D2HQ@$9tZ@IfamO3!=6X$`plD_mPZNohnoNs<0UuxJw-r z6~$s#5!6`6?KgKOK%x2nBMnVc3$+<}`SNUl>|PgFF#OWK6Ln zeoRjys+XL7K?6aS^|RXIzs%vWeog#1#J(^e3tL39d$eaxsi(^Fxl+;3X&tN?`&yf} z*2|WdWR#DvSozh)vKC`Y;z)5Te{fI$j{{C)*0KDVbo>THP8R)g+yb^y2Px$(7MhTF zJsG=I_Qa*>`I@RY2M4F{$0FJIo}WAmRq$o86&tQ+FfrsVRW*D%sBl`9JRO&z6h^=i z6QGi)e_^2|sF5r|!Y9U6P+9yK*BTTGP0A9s9)#g*OreflZeVCCqDG*SW6QS#%_N(O zG=|;D<$G;yD_;Eg+lNU_zWW+7vzpyKGEYH9Hn0_pl-|}C4=qlU2*(a95Se6HX)r?Q z@o5dwGVqmZ5UO>)>TJf;(swgg+dU$CV;CrQeoIQ=ProG%Lfq#Y$6(|YcV~r^vT_$W zbF}71OgKMp>pE`kUkd1DWDfbXM%RrL?H-Xt9C_`Yko0VQhkPr4C0rWk#u=|Y2DGJu zt0%{d_kmNc^Ri;j1HpK@$aaSgv9Ei+HNFLC8kXX4cJa;pMPtoxXO*&KSD9lYvdP zVq;nol?Fjv#sI8z7`q!E6dP>uOpn7j5?Ug_4-AJf?m@MOm4?deV1MXX{w_yoP zURW|3VA|C%0lM)<3bHx9j+Y2lJMLWWJKMUUi%gS9Wa_U~H7?G`jEUmXOdDr}*wMJ{ zGxgupbweb4D5^Kl1mBtJ*Ju_%&}Zavvc5=vMDyGXe4q$G%L_dFP^O})!&dmd+^$MD zulSP)UQvGIok9FxbAVc+WL5ua)dT7SUYj^GS&Of5y438SyN-iDH{hOhevX$ym- zxm2rvo<3@=ig&8Yie~i;T%4HNo1;tluk0S|$#5nGSrem*4s9ZlBka@o)86O=?SkVi z5VLv?Yfr(w_bBg1wY3*}7Gu?{7J5eLa-~>TLw%}(>(;SIvk7Gxu`F}2qaj1Hml;HQ zt-RqjRY>zF?CkteQjzE`q?m7%l`h;c6!DzL5XGz|570u_3x~mYoKeV3Q}V?bQD}7r ziAn{kZQ5!c%o3z0q)U2prj^48RkGA_H%wiY4e~N`-02a)7M0P*cX$t51-vFl0%HdE zAXxivhtKPOGW&?W3 zdwGu%Eq9+)EKHG=NMy~^d)2j~#WE_VCAmSgpOpv0Urb-zutX1Yc@Ow)F4kXbSY0^~ zbVhgGadF&~vDgZCW4vl^r=^0R4Kn`crq1d=u_(<%6D-13Yh$ z%X>mK0G1v@Q`wv6g>Fh5w>X=5$98st6DI=;#C3@QzyG6wW|zSWQ6BeircAT1ZJJQqc&?4O_T~tf>_e;z%knK5yO9RG<{o zUveLI|7|YU{;f5hDQ$9N5X$30$>)w2Q9xy(+CC%qIvI5rds+TeME_)MOCsXQ_x_$x zCt7?8$nk8<%^O-ayMYcF`8^H^+kAZ&$iCSx?e6W%2&QaMgCXrIfefNFvKB6dbm>p~ zb4-WyN(chxJLldHKb0SG2W4b|;&h{3c$-V&?d@%#d$+$kn{dZE0a)%~riq zgIxAb%6N6^6*{>;euf_gDidhvHKj&)p>;kLviR>il@u6tOK~lv;(22$_&^rz1^X%W z(|!t%z4)#nBYQ;l1ISk!V%{IGfdSa}d!MnJHAkVKy9NURgG|!V5o1?)(wUu0C={s0 z=Rj1JM%dojCi-|hK7=_dO@-JdnxoAA6&w6hXbC6o9mH+ca>-dh#^ek&<_qz@BE}{{ zJiuW0t6bqIlgb)85|FloR*UXc4sT9HTr~M$^ku82`!cvJ&w5)g2uUbjRhSgHBcQWKqu8JA=dj&y1dICByHP9W(_1XG@Zjcv#0r+4+973-5Ozqr3E(d z!>?By94WJYIT>{zWa1lHSm2D8^!jgm6Jo*~U+7`hwmG$W3TM_AviDbo!?Cs*SrNyR z3B(r!Q_%-UdQ=9ha}HKRx#_SEn-s6%l%7vffnT;NeKF9g7k5FRR8*PRr=kpUez$Y* zejNHd!+B3P;nt-EIft7GeT4;=Tlv_+gSd4VC5^A>vb+*#^udj;hrt* zgDVB=FE_{>Z!8S})~faMMuz3|tjM=@Wd{J`iPXeLYeVXUM^aJK=j7g_n(xI3&Jp*) zurUJ8dXoziBH=}p!u*BLPDPHR^brY9%@nsEAIO+zT|d{rh=x*e59RjR*&y1pp@`5U zCW`J8)a31J8e@ZJt&gbXa$-ShO_mDkc7km8W z_?QZiWIiFubVob@;nqDb^QK9b5eBfiukDrQSui;K>4^4R_1F4A{X)2X`uEs-S8&t{-OwoRQ$68vcK$ra{sR#P?oZDEN}E>>-*>7UM~n(1f@9uJc|(rFS^Yk z4-o&Ima>bR30lDX<>V{|`~IUP_?lAdHU#4Rn`WD4`Crp)O$rAGTkj2)LKMW5daRPg zA!RcH5X;kNaB9Q@o7shf4Pt>y!8a+6cEvuUV~ z*rW>VOs!y?o{Uj*qEp&=kC2~aL!Cl$6m6rkUubHxa^f;P&HeDIH-oz*U}*g#DZN7W zkRmkJq~;NSeciab1meEyu>6;b+RiBDW~8(N_Cw6yP0y-;BIS7kWN#=GYU1TYxK;g? zNU$As>4=wGe+an0cpBQgD#Mwv6{wpUO_%3`4EUAIDO1+&3koDWUe~BsXzS{l@0h#9 z6;HacfQ6UrNoHr~7t7Pp!2u%~_X7lmZ+Mf}sX<$Rl&%Xdtc3~i@tsUP@B!A(*aVzo zP0EylT*y&s`1NB#7YQa2AgRNXi#iU66E8Mp-&_tq0ov6N)d^5 zO0B!Z^4B3Zn?^oQ-jJC{_Rb0$t0t24Zk~kOTY+OX>*@LVSYRH@N58Jflt%%|Dk}8V)M}1Vq~lC5X(oP~9 z)TmRtcdnd7t^}EoG&jgvM~`xSssKs5B%;SN{}Y`Tj7PhNK4_*gBDy?-2r&HVlGd{Y ztV^e-25-nDElEy^v`)998(HBGy{}(fD@2Q^&hO}oDR^=ae*B4~pnzIbNf)X9R@S<| zH}7$P>1J)&{W}gEeddH|+S~n`4T8J@oCFF{DH zpU`uC_X&RtypDkGxkI01Y_V6;{-m{F=t@fj{7iWY;03D`;4oTA+Q*^06pQ)aHMkX@ z>@q0jHl)2QT?WKxi}>X|O)pLLsDnd8wflyQ4QK-JQ`5!fbOKN-a`VMjAN*=Bld|e5AKj3RSzb68wj#!)f zO&$O%Q*17%0vTzUAmHjw?#hUxXRWR~q8PRviT}8YKx=*d{qYe7Xcu|N;!ZFGWzRM; zSejr_0i9%y79fJ3d>>Yy_c2uM1$W5^Et(yqsiK5wm)8ouk%&AdtZ9JXimaN-`nVLG zoSewArkO5$UQ+|FoovfZqAwp7GgpWwleEA{MK8S~{G`__{lzX$|BzvC=NuuayrjHP zwZ_PM59m1-jEoBx=uw|u$pOF&a934@wfAr4VEjzDBuGjM7Ih}8ZQ%GEDpAV?%78Sk zX6FsHmnuu~p%F%m7@h1c(8~sQx>$JW6+RpBmv(Y*IdAO(< zCy~ebA)}d5GYPPIMwIlq`+MMA4@3327Rl}rPC7y}7D@OoH+Gx>C6bw$weY9`Q~A45 zb2(-h=!TJ*E4atgxH&6|PC=bf8uj|G)BYlz)5CYHS89^OO|W_${Gn;x&-fKQ7!gU5 zb?V!q0cT$(*GK4NTE=%Ka(Y`)xU8Cbst<*gY3Q@XEg3Nj4r-5hhe!rgm+AyWBfH%RiO+%cbXV05=#PPjbczUz?S`VyQ181oeDlXG*}+CZjk*7d778^^ zf{XYT-ur+q>(ho^#Z-tWR~ipZBI%rh7bcL$sIQBe_977rU=F=Hyf&_R#+;;3ruL=; z5t`pvkW?G@tGLmdDc4wuFGW;w=bPaY>R{7*>kWVB!?T)NYZfkJ9neK}a%`f=mh8Op;}V`r%CctBAT)sQ6vurMtley-Zblv==AR3Oi8*24cpw zh(WA=)^<5;sYWERSClSsMb>Lv7lwx)Y|kuym+wlAtjX0GpYmgFv3NDVJ8Ao^dz^f1 zKwsVayz8G9iy0<3H4lAE@Lhe3TfIT^KrIPj@N{X}+oh7teT8>}iwBIIQu?Nj6!kS6 zdU5Fn#Nq-=9l;M$kheYB;o0R|=-fMxyo)Klg^14T0b zmL&WQ0Id7p`o}+-Y#QMwpyo%_KCnY31bS~uDzrZku!QIYWQkw;Kice9X$Z57%;3|B z2Co)1y4u@?!hVVEGx%9D?CAhZKYiM$3OK*U5oVUpVZ$@v+HjN2&>P2xInJ#bWljet z!nm%VPaqtpusp(G0FwGU{zV$yg7}~&pwc8y)Z%dTS5>cqkIkdiZk2fSrfE=w_SEl&&suXS9Z4>i?Q zR2fQ6y36dx3L@}QTX$VSVQKP4w;pt z;WOjlS+m6=k0r@v$%Q^1`=N`5LO}|%YhLi&-*Jc<>eGgPy z_~I~F!m`C@5T0ACRpkvjS&&H$xrjGo2$ki3S&Z7_NVfr>;^i+!R0*;BZUp7Rq*kb3 z!mzuy*kb^SR|JKWe9>7LSmWbZeEMaC0n!OV8{b`O9t>s`f8)8@V3$(L@R` z?^dQY3|yl(57AmcSax$yMk2j-US$)f7j z%_cDTIzOV8_x#ZS^xNy>h2hjAihq-NKHR`c_rDr?%ZR5y&-X=>e}eekuyb0FUC8}# zK{n|c(oJVtXwde#Oa|yuQVZjc-#z!!p4hX9!Z<5s@=3VEAW;mD8%`T5j00F9{9PS* z=yHlS(!70q%Fk1a4?Yr}i2W6TtIGqPxSiZ^WTMSaO^+kAm4aJe#-uC|_>NLLS-%zO z;nzST;V1V3?6Dumm!EHJOT_Up59P2(;RA!u@{(jge*rqrFk_V%a9;;Xwf`3$Vo$O+75Xky@BS@6kmUG zXMUEd$1A142keU`wfdr|`s0@>b;9V+s+QYvswgA0h9tAL+VL`fGBURIMgq0hTa7;x{q0dw^ql~z2uhcZgU$8Le~CgyZwWX2uYhfu#QS2!pdYC&Z?#+ezh z|6{1vM)c6)QODxfq+!;|;{SL7hD6Hp-eUH62-7nPtk^Cre_j7O-<6h*tFhaQ9cSReVR_<<6D8>1HWLKgx9uK8fJ=71IE5e;Sq|9diC;_L4*x$0KxOabpQq6duW;( zHLA6Ky^xW)T-%BkcJVE?zK``7vh!XS5pr^LAm!;fpBl>(+|)&2mqXDiB73xiG=n1R zGZ-lq#UCOSp6s>-KgK!$5~#!}J}I25Slbx5=HT*&>zbAHbR=jy|FCYhY}e<|yy!2I zHB!(W7zA=$@31dgv~f9CnFr<@T1X#K+dMaXV2z^U`Z(X}8`?DUAv{dM#PapVCBA}}n42ng&)B?f~uB^*JeAKt6uH1tVo03oRuaX%e z_AD(efliFE`TV@300>3R*P4R4^L!#_RMfc5srBSt3gYmRp*2o<5<%a3CjTuJmgT=_ z;5{DjC|*Q^*uEe|qX76|(L58L-R%o)Vy;_$A*!0%d~H+Pk3{!^M1UlsM^{jw#7c0@ z+KlE;82Yh~9AkU1u&^NBsUuVQVY3jX$|706yA{p2&@e2}g4g6JskeAnC z9Sz~`ffQ{HErgtjiHTIrc7Pgtj~kUW*Qf`hj53JsQwvqTQV&=E#n;du&eGCYs8ZkQ z8>8>|125n$N^6P|M>j{3>97*8PEV-u`PSRe!QcmbjFObC`xL&n+S=*;`@gAw{B>t$ zS>BLD&-#0=={I{Pxv5~E&%e4S-t|{O$%#juRRt^dHIS%?>guI}R77+=1pubskR66` ztxG{Iq$PxixB3WfAvJu{cvYk{6LNXqZ@vrqcea-Vca!6hSMaMPeV> z56LBJ}7K~!P8(@kLYMWeC=mU-{WNm z_w-vxr9m21fp*G0pCs2X{B4bW!+MjB9^_42`RP}f;L;vj)p9s8a=cC_jr2NZW|q(& z@9`@6VpKATg)0eIDlyV3<+B++EU*u){f&2)z-WQY;GA}KA_YNX#eF=AcieS>Yj+&@ z9!{kkPyDCZYqw-daBi&D`3&n`Zw|B(4`cs|M|EhpQIWRf93TuREj6h!;@5p^i;<~E z*U-YO-vD%km`2D?T4EtF@g;}C6$i=E4RqG3N>+lHT3s~grQ5pJ^VQ@AiQz4E&A1!j z^y-n)^xN0ZNC2o5 zq4>X1>3^iwAGiO#uK^4kDZs$3{lmb`zBiC(tkr#yS{)deYMAga@5Ky#_Fi{9Kizj| zJ*o;0qb6N#;>HfJaJ9&mKV!Tz1WdigL=1~cFL>DCU!p{J+5#ZU{@*~gs0k~mz+OM- z5VcAdU#b*x8JCc-N+72^v9HOD&Zct4_IybJSTe`+D03MoQ^!m?)g^d!jo7n|e_$5B z3QA^Iw|Q4NXCf!u?{ESu_eJeg4+MA6)|>AG`Ll{%jNu;-N~u+HQH{@ctySyTY+*+W zm5^U`#bh7eFI=%He9y9RzxteTnnQcOB7h3L#B`6=X#}rQoxTU&UB>h0fIF{vmIx9Y zN!z&OPJ}rpHRQX(-9&k1#yP@z3YpQZBQ!Z9yiODMDO4z*Jd`5^w{nXD`_Y;?e3AxF zSYJ5$A-YmduouhTPDCTI$=iH`5a zr#`}^HNvJd&Wke=79qj-e2SyEeg#n-oQzbAA+dp3Qd&^#%z=wmQsIx7Z>cQ^S)^g- z1@FP7cc76c!wR+L@ntFgvR(hhLjG*V8T=F+Kq}~k8Sa<++#_i!cjU0d!f&6YzsJY> zR#-Dm2IojK*4R)HXU$fcj7*;S6Sy($_A`4^^{mSR=Zc2>3r`EeuHMC^< z7W7#hx3Jb8Azsn`UD0&I*%N{#hpQN_e_-l;ZH?^TfEO1UrFu7(D0=NLks%DeIkz>FnucG+26s9J>edpLTKs z(OVUWt5+hd_nfS&#U(0_dNAD5HBmDQ^XF`gI$J)bq`Z#E)E&nsR%A32clBNh&XsVB z>O-O?FHh{f!d4WcN$e^uMTl|8pPG#gE}+`F@HYEK)R3ikQ=Q&^rcHWq@H)HO3-4fn zb0Zq{{T_F2z&>RE5;+vwM!WHO8|E@$TOAS*NLr>?Cu#Z?)l*#~4}~?%0s1olevoE3 zYf}zp$K+287-b_bX|ye9N~*~HDI2oTQ(3rPlFy-7-r9!kzpVh{$zW`|>4c%Y$In z?#KhT=cfaO1j$=*r+m6`idTQx+&?S@L-pQ=>0=ZY!h?93@K`s#sj^bR;59{2C1Hk> zzd3`<!F7Ju`lz8J!lXgty!^ia{icipON={^5N3)>^@$m;qg~prMXAq=3Q8+t>l{5$kzKf^$eu>(xPrnvd5ridkc ziphb3JUrp9I}`F%|D>qY|Ajw~xxzdi{{jnH^*d%qNSoU$kK0NEz-GE5P^6nDg{8+pEH3oCP429MJ(0Q8^5to#3eG5fqZlz^~h zGlt&Q?v!}IAz^V&?n&U;+*pXP?ihH#^b#h=$H(`uA4B?F#6c(L#kUc2ch*?rk2aJ* zfuO$0{k2TLPVlcNs_`Bq8{3XoZrJeyaMl&U7Jq&*%jgG_M!$%S_A@dYPz0?VJ|et zeuFphT*_$qvzGgdav6}Hv&A(+)XN>gyLj=xl5DwKD{;~l^KZ-5N)w~#rpo4<2NNk3 z@1lCt+u%EMNe|1(zPtxW?Bz9^K*&WV2TlcfzNVwGYkjcAl5AHcMr49$@cMKpyQ#d_ zm>3hHmGHtBk|{UvG~R}{aV<(4eQFOJjwFHGv7Xl(%15PZ+dC}()tK1*r{Z}i)Loqk z?-jPQo2RF#i65zHQ4wmG8VHtHOJ8lVAUo(@vmG>VABrrf&WJ~j170t3&UY@niO;vO zp=hK6S1FDMNlN%zNFzyAk0VgS3CVE?5?nP?W_k za6d(J^YYnFjhyB5+JgPYs|a7oo~v_$+VzLFEwEN^w$sk~E|e)PLC6ww>K`TGCiFXk z`2tT_yB;wa%ck0A5{t1?1O7#@N0B2pwkQ3=+EH>dME?$49pv z_4Z8CsB_{>O1u*$i6@?nky#?L+IE=Wo7Zz>XKk*b;nS!haPwbTP^_t@tcf7fA3Ks0fD+h|~u zkdPGE*+csWUb*qdqfI(5a%68WHrmd%@bbVep(T!NbFi}qO;3Zkv)o(aM{N;8PeHwZ zz%B`thgPCda1u!RyRh)5@;ENhmb(E6>dJ<)&JA3t-ueaJwX+R=2u73f$IGsnI2%lD z2;(G-8{&21*DgFbEOX+&m)>+W29XD1<&n%f`~8&kz9rR6Wi>XTPU!7L{pp9QGOUrq zylV}f!K6PWg|iurG_e)u>iKPhR>=hDoWwsVV_Oy@d5TYabzrq@h>2H{<+joLF3wS* zOcnGKRLF`^x5EcEHv){WD3MX4Zs{7n6vBb@zz2>OgIFW=^|kP!XVYkoMXM9@bqAfw zX9V%(CC(qQzIU}XeUzyL#T1!w!i~l_;+^JSLsmVft$wcivc8jf)?6!?v&&zp*sNp| zNqD|;d?t-27y7|L)~L819H)bYj1ynFyRRgBw-gGUzQYfOP75m4$<@7c?!2H(d^%jL z2T%qg%GlvV{jP&pno8c5hyxdc==RdR1XIjjP2l5!9%^JBi^tw|*<*f6Hbu@PTKU|u zmGtB<$n5M1gWK4|gbUuO61o6_kg9w(O`}gkLm^P=2AoFj#|XTU`k>k!T99^81e?^S zM*dmTg+_cQbCl}~ur5Zb1tTRRnW~!r7!7w{w2gCqEw_ z;)a^{K*CE{)Fr@;y!(A6LJi<&9$og>QGMOGug(M{@y#eZ^_GO23ve zz5{N~Igah(7ANG}0mGG&1N<{GBI1~+nC=L%n9c2aQ|xiz8gMt?G#mShGbe=?W>_t4 z{m8*&=Lh{d1hY~qg578m|8Se86XuB*s2B}vwoKtb+K;FMbQ5!pG+Y!c6H|hW^9r;h z_K8Zg@+%>RyjTez%H|nQS9skNd;c;K0KYkbGAH1uZ;T#qoXwXp*1@p1v^Yp+?}>n` z#2m%twt`Y!kbGHo0jW}|j(0u0y}#n^xyCwcTY|IC7eM4 zy0|=6@6GiB;{?thaY`K{J>v4zvmRKq>)!=WA)1Y+$K~&8lf-wpgl?l zelQfKL;`(}w*n|4JsYPOs#m6v(m_yX#muLg0`giYUe}S9r+p}sMcv(zptZE_>ooqr zW74NsM}Lw8;C}k^!^;6_k!-&QA}Gdpqop396Tcv!864$7t6&2i5*ynpBaK;j+b{3v za&u)x>gRU7#qRHqJYQP9d6NVj+T0)%p10U>7;2nuB5MI<@oKT~H(I2b=6$6bR58Il^F}rED($WD zGcI@@x>Af>Azi&RQ)2-NijHel8F+fX-PYU^BuRuJI0E!6C=QrCsvT8>GSY7gCx7x~ z&Q9}VDzK%Rg&e`zObCV%+c}>Z2MX-JnS%pviQ-VdS5VJbi#-((YAgtxecZ!@lm0HC z2N}F>r5v6)r~Z+GMvlYif?dC{{#)t*gFoI&q}Z#l?=_?UxzUm$Yu71s8usSo`8Y5R zXnPZ`puxOi1Mhi$dRlU&M=oj?m;qw8)A0#iCs)_ktN6vG?jIc1I`3UK9K;Nd+6`Si z>JsNm8?k~0v*TBCDS%}yFL3%HQAZ?OXZl1JGE0YzblfwZ#pk>|MiemFF-x^$WVy+* zBfBGbL{PQse+o2~WB>6z5dk(<_6HZ1J@Mkx&j?>qUU2mGxxx#|T~}X|u!nf592{HT zDkzeG%AC0Ite1~gb11Gt)*GY4JXJ|TU${h^xrE%;u1h&g%@hqW=Q~_nTmX5zJSS4lX}I*k?kKYR{xGfM zx4~f~FjG7EbE;kyT9xQ|o>Zp-$q~*(gTc8KQ%1o}3G3GvJ2|$jlb->qkzDCTU-n%# zd+N9#1d0PD8h?8V+(k!68`0HXjuf}tFDBJjbqrb7;E5n6hu#B++kxBCZE$-lo#uIm zA6Lj-_lLB)&hfH^z0c$0q3v)pI9}6D`ex@VHw4|+_czTzm}VhbGzhfv7U1u{o5*_@ z{c&N`$`G=oY#UJe#rx?D7YLdrjs6XQ0J8Bn#~ryz*2_0?Gl7uzzNpAJuf|}Qdbh}1 ziEtnXMIUM;HT*u09`Ji!p~l$85|Zu@OsR+o;nh?#*PVDUTTrDa6g0OJbc*;N_9z_D z4u>80N`ttA!($1wvq4jAy!y$%ALSLnm)~Tf(uI++{qDk4ta}|KlcsJYs?3yh3r)OI}3`Sz(hN1{!Q%? zkMQ$DGXG`Y?C@*#U8nUH5bjEkMOEDM%}!u%pqKC21sio}d}C3w?~; zVKs5{f+&mKLMCxm@;P9oMt|&$sY{E|VKdP0ig?V$Fekm#?)G@Mdg$X8v4&dZzfOU7 ztEsUw+@c-1KP)UE1x2WBGhsaKIMG81HF^P#Kg3X$^%Co6$C02iF{aZ|pEKehU7~^b z&uL4=S)%M6Q=Nsj-f?RkSGOpV%*- zB2NNNBE4+)@qf1ln8}h$jgIx4Z_4>_G_2t3&Hb&8E{TltMXbHJ?&|}qa=;jzNH*V< z(JirFB`HXDv#?#C`bbuk9ro}lJ=anCBknrJ8EXg8_$XJ+*=Xw+^yoOp&0l*__fmFh zhthASumC0k78MSdpuw~lT1=zWK_k)l?u*gxpuC&tn%-~R_*6EGl-nm)XU>$5jQf|r z?J1Ct;awmeF0<(0g;$dlK#WaH#oGs#;>I#2;;^aAR+idDt^K|UzX&wOm2<*i`LXPnN&d)Je zvYu}P(##d&OT5mY)aqI1vvR2jc{9_C5}hNKavW(n{dnFU{IXv*-(l zk`=#iSe^Ha=OX*Z#L||B2vtDEQ*to$-gu0n=~^N~?8Hy;ljU2$b%;?4s5)ID4#1%H zMjd_d-q8`Un-uk2>M#5lAAek2BAS7Hei->S*ovkn9EE`J&RaWSlDL>oW!c%kL2vEk zG4y2Z5o3ZT=|{mI7p!;1>)ztRxnTz_V=CBw6He7T{j}-Rujxg^d6S34pJDn*-Kw2Z z@qvB|kSr2!lG&0+0KTCbXRf$0XcC8Xtb3PzfD!vWBu%#j)UFY^$&Gb`Uai*}WUIwW zo$+yfcRjS$1Ri$appr@MyXmm`x8WV+-ID_#5?a^ayy<-^98xesl;O89vbeNaL$oo+ z6A_6t{Ke1-Nj>oBaz0VXk`O;3yAFxEBvitu=}*`FjMPXGB7}Avv6zle-euZ~PuEZE zu5~mX+Lx16t$bY^8X&WSIi(<&%rt&@$n5YZGxCU=Xt&YCIl}eb7e)077AVHY_0#F0 z={X*lGTMG&X-C1FR!X{+d?Omm$yPi${4jqG&@X||nX3}iE;&+n)U ze*2|QMMPq@A%mSfp`V*&VVswce0f z$5e6{dR9&4KE9uHuVKK6Mz)YA2)MWe&h^_sdW9|6?GVrf%`gJ5Iq7Bi?2nBT^Rt9p>)+7qty+6QtTd8{dG_U9J^vp ztZ2h;-jWiFx;9No*5n;qO?x@R?hV_MLcJ=8(TtO8ZQE338a!kGw&D}%nkv+B2o^Gzsk zE{_S~^ZMT`ifV^$PT_bjbVamOQkye5J@ESF{Nmd0=Y7-N+4m{FFmM`K+JDDAZF7V` zZ1qfp7$qjqAh16KoFw{H@zTFb%NZ#Yg=4`Yv*J3gsWB#tPdzWSm=&)|cZmQUtI z1MhbeX9L;YP?NmD&)cK~TFxRj!3Yr5ItWETXIS3jp5rD#;MvafQq~d<<)hF^NB`t2 zq17GoUpqL9$Fj1)yB|JN>M`okVEnT(ss!aG=lNfKU^T-h1FRZ5lCGYvrGflD^tudq zH*PP2jp(9Gkg}!vmc9q$i?!M-@kNhr2V>aK^aM;r1LIK0Gaf~Dw3}tc`;9eC50H0i z!Tj{oM(j=ZVSlJPz-3aP{@(>toPp$je*y&Oz5HJT;Rjs%F zXnp?j8szA}e)zCXNVoW-v*us6YJ-ILF9j|%ua@Wl)^)k&W$abuzf4ZWeWr^DE+(?dQZ=1#7K~BRu8jTt;l8}b%4N#Gua+c$zk^Sl{7ZCPdVu5g&WSttBD1>p zk`#WPrQe9o1uRNq>9v3G@F4uhYZGl<&QUrZD$3ozwu>7N9jp6ug{hB;*|Daj5wVF> z44jz86`Gm1ZLC5wT&n(E`2N*n7J3`Jzx@Y%LzMJpH!X7uTaK|NK$TA(oxyEXZf+v9*h&7&ID1|%F?I7wel$aZ&Cml@QCPxr^ z&=PP&{44eVXoWlh(aE}(Jc_0WDot?x5Ws>UVp8@Pi{1aWHKg-!?&~thnslD`&N=h3 zufehP4MewPn?I}$T;ZeBZ?&5w8=Rpw zm6>t8U*Vd2q3N#Cz4I&ze!z)0Y;Xdlvg$Ji;(S|ecBH^Q3UXd|yWo zM+8Cl(6_F1$n-L~PxiW*mUUYEl2+7Nh11GRw#2f?RuqQWwj;pqE`^MmxIQP0mRe4e zLM*{)yz!UK7fZ8hH>{js-J94h&8{K*PnT)Sre~lytJe1jv@~k$=y$y_EA3Z>?K|wm zB$)&50YISUEHez(X>9=;YDwb#P#fpw$Cj%7H3W+t{q{Z{T1_E4g7`HmeEfPjG97Qg zoP-Te)<@CRNE-Ex_8W1&)2(EoI?of(VzagMca5&{I#6sH^Y@9IC28e&jNZzUZCdW1 z^P8vZ2GK~O6mim62?HFd#DL`!-|F2g>h}$vg;rOB-%C14@}-Gy;|d$U5Dl1ss;cZa zgq0Wk=Z{4e?iNgkw=X#3Q3zNhT}_j571p%R))FsJOj)DcuM(y%-)K<@;M6f;_}u*=Su8z_0=0$s$f#raUgED6PGl9P z{^mPA9pI56x+7&DN>e!(TKe7U#1YJ%#tPh!TvGY$)94_aR6dNX_7kEFrJRk|8L48k z!iLH^w=|QKtLqGk630=QNW)cJ$I30Z=nX3i&@Ie}>LUljEC%;`ja;w|wg0(9XVw*E zv(t8B&E1t_qrtDBK7d|NcF=TYBC`J<&b~S->c`s_hVB%Q4k>A+V`xD_KoL+n6r{Vm zJ0zt$q`Nx?q#LAj2BnA2_u>1y_r1G*@7_P&bGc@*^q&s{bI#fO?0t3!r;MqZ<}-Qm z2-FWwU&dIwKn50bW!>S=*nW9c4rF+bVH609ni88?S@rKE1MyQ8ZP2o>YD9=LGQQ@U zCQS1`tkZvnA-pc>_?`4#g4LG)Wi}HiGA29~UDYcP_>WnOg1K}L%;LM|Us^M!VG}!r-*tA!eX8X6iF_Z7$7A7YiURv4l`S%%c z(;iy(E!jNuy@Bw*9!7;(ugB@*!<~tG8r6{+?fpI(LUTCK z*m)~PzZ*JW4rDp!r16-wU<`-%ps&AOp%um0#&X*}6*3Esc4hag7`xuYte|M|Z3=`U zQEM0&AnFu>_Qa%m=tOA*r_g{>+&wi*My(J;snh5ifOcUpoP?&PO#}f9bH49cW7<8O z^VHe18<;SL>6h31E225=z+BH1zNlv4&If<-^Q1p$1`u3>fkJ*j9-J^YN1qQy*iYsS68=Ou4Kv z>ekKj+EvF47=h?$4*&M%^ongFsH|9+o1^rMnP8GVAIfg%K>0hb?{8v7gh10*0Dp}Z ziaYM8AaI6|FAhX>bBVYUnHN|aig>d8NIT9b|CB8uu^>+jj5!|8M}&jo;vB!75f(Ny8HqJ9gk@V!vxL0zs;`|+CF7;baD#o@RGYh{>7}Mc$^f3)MQ0sO)IlD zH5KW}83S~nzoyfylQPp{z`}TD=0&wZwk$*0clkn3+-USwr|Nk~V)SL-U$>n1C!( zt-x;sGL0TbEB>RG;*mGO8Wa1g-0UVbpJrYVHl0mH6!>;C;E6{X2QW-1DGo&2Hhm+= z7Kj_#Rb@~5HFgG?Qmn?ni^QOL?`$B0-A81%>@Y7DDr?kq8a{lVONyG&C6*EwO6E%h0 zx%`lj&OpNPIS`QEb-!Y;-J|D1;k;ukGddKBt%U`#j)(9-o?VM#83+ch^AR~CXgg4? z>53i4;5~dz4^eeqTm<|6D(I5^fs5w@Z|wFFypSB0Dimcw-z3$@mi1V*Q{%-ZUZGd8 z#^sro)p7At!tC!xOc=N^Sd=z<3(9aJ`Mk+jEbx6$1cmbXUWoO88oRk5e=2Z9f&Ns3 zQbQ4qa8x&RzOnl?(cn^UG_jLyI7&(?)@wpJy>N`H7L)>op4Eigk8a*Zlb}x3FlH1A zZ0XCb@Nu*}eCqibA<@UHj}mwMfg-W~c+ada?JF+O6upD>wXPw|RJ-?51aaB6Lt5r! z?Oq`~yn@K{b~}`cDVZl4(E-_A$m3q`i6t9keb=Pz@@f8Ratw&9T|4V|p12<$C+)r! zk&f-4{M2n4t1saf0op5VS$@wp3PjJ#i=&}_ay*ZODu z1?Dl>xHlN*^w-1$KDFC6L9-oT#D4|LlWh~$9^Yc{c<2eB#<;s8X-?`#%Q z0MyTR4fE0FBH#a}ZUVJ*yxl@#cI(GS3BR+~rA5C1%cK%Z_9@g<%Bg<5R?Tm3mvIp- zQC#yHK20?|9X0(SLtMYjl?VKIJsyFbb=AiV@MC_{9AW!Mj(%rHt`HI1QNDS~c{y_( z7UGHd`H;28hs!G_>59`3Tyi}($O464STa7xJE#1yhDK{ej zJfUb>gt`9pfGg5j7ZP45gP3jt1}9dmve>Wav(%$vFMmd47Yt+~dFD+;mV_!6$(x%N zcazsYUJ3pY;k+GNMlQvuIXzOvYIl;Pn`mjWM! zGu-FOvKh!)^sOw14}4*7=CJQ+8SpY=cFbqy7I`LbBjPAAj~@e3V<)ciIno18=c^k0 zZuw2lu3Lj#s!{$OgaFvHWmQ}n&EB3R+giRLAvz9;MM4ZPdBu8z|NE=>wZIDBCqdt> zUT30TP%=DR?6*9DNl8qsk+JV$Fl^UmClSZ(kV$X}w&eT#apW*1MC;+KmLB#L{CYJQ z%1)z$J6Pb6!$gA=VWr*>C$V{=u8ss3e4adRN1PKDx<^q_ffz+j-H6#z(jh^@GF)@4 z^$j^^LpV|l$Xz|X?^7{d#@p@*U7hB=_vx+HJi(}PClC=Dna66i=dUj!ybMJwLk?HG z5reWV{hC%kaJk{%Nv9b`=dyZr^9D${>8$5`RDf{CrB&)_jRr-Vf%{XW8ziXfvt~Wstj3)7NK? zK4u50vJ=}~4=CoiaX#E0wyJ7sM>tu`zcus=F8pc&7ZSai=v}Dw;WGbgUInCy*VQ-D zWwFtkzmYXQjE|657FEdid8k$mhTYrz*-lyK+2%fU#H#3px?0{G^DgZNz}a29j0cn8 zgpW*BR0gZuj!0pyQN%{;-aR2*=b-J|Y`3OBE20$bi|uT!U*R1mChZ8Ddm}9AQiwxl z$acN{NiMMzBABh*2t|UCmb>WT&7y>HFX)-Lh251T+*f`g(${kv;e^ic(XCEk$3u-% zxOuT!Ov5iCv0i@#5sY%ZSV!Uf+tY{^rXm!jpO23M=6?w{)hiVbkWi*H zop=f~-eV$T#FBO#2LXK$4HXS7kx2oupvyrW(L0!^5X$G$#Nu)Tg&F+(npFodMGwW@h*j-m7hH-vv#Ks_oqXay061WvAZDkTu(09Of0M z_)ZjN{^N%kk?YHM0`FALWqjk0!rY61Ni>@{6w4-u9bYx4h{~ky3oM1lzqU(T%-K8N`QT)^(sFM3jijRe;&a>e zs11q4gU8w}b&nKEPKSwp5{Gs$3Kq#=+s%?qC)L{3fWTPlMQLz4)xYM~ETtDe@2-c6 z`9)UqByJXYqCcKXDI;G^GlQyf)m&Tz_8;xkA7ISlAw`+15w5wovP;tRi?o~@z@42s zXmmIZ$RzDyr?_R9Q2ks*+jX@!x7pXPVl_{o@r#>?5exgO3kwFF9hspHSA1Hfb;x9jQZ6?fTPN$LR zibts&Pnn8aZB#5IDdUyZkWjd8yI03r+XXoXM92ft; z+a`FFf4Vn%S6GN0KtF5n&d-$xNi8Y&DBgTU&1p zZhb{7P6b1v6+qtWlI zl)1&)6_+S0=nuR%mbx1-a?CI6^^hEhswDWSQZR7W14`wz70Z~e{n6Is&ul?>ENY&X ztXk{XOQYROth&U@@x0NJ4vX!p;ry!ZLX8s^=c4WN->D)fH@jNRnNjkAvUs8?3Fv`; zIEd{TXJ%(|V!6e1TeZ}wQ?_pq1;;(JExJtwa zAf2Mn_jcITp&{qc^1hpMsL|g!FIUIm=~oTx{$1XuR~uIe`LX^VQ1_&(Rxu>q=Vf!5 z=&aW|A6IB5RJFOH&jLe;>-k|uHKW0H`q zD}NTw=s_XXVX?}7O=lBGLH>tFSeOX~zokW3mf>OSEm_OAb=x(9NvEM66tm*e-qn@X z*in;iE+Qp1`slMgOOi`52{HGH)z$DXY)LuIC2HZcGkq2)fyu^ta6b$G1HbY%ebsEE zoOhz{?j3Nj1j%e&qirdLG>SD#)DsqREWCy|uVvA$gsDcosCCA^fWBJy5M5A?JlYklT-nSNFVKhq`*7pUnu$MwBw(o=$s0*hquf{T)| z1kpFC7siQ7px3cM&+j%tqVqzhlzclU%u85f-$ajUsu0E<*#C4nFkuCAH~dnpvU`+M z<@FEH;JjG(i6iF(E!Luk%Sq@b!_!&{83-Z-TdTioKbL) zK-~F{@%0^RmkD-ds~Z(5XB($!O@M6tOfGTCD5g4-RLUH59xnr7=4X8po1IGlnSMr06c?Xn$iDDldiGC6{rInn znv(IqE9wUS)E@8Z!$o6OLVgiN{$oFvx8Kt}Y)E~g#J$HVoSLU@y{#6{3npz8?#jK62^jNgpgwu4$C!`6XD((wED?c``lF?im zeVyktSlWs)7_Xqxs<&rN;`|hvci#>Zs>2(S(dn9y5sls%PR`5AqYCm=TV9oB(YQ+; z@;VjwzXtvKQ&m>nl@`di=efw7Az`b0Ka_p{~&}Rg`={H2qUv3uC;5DMYMKeL*3NYnjxkLM+jS`bB_wK?+ae#M<;E4mmVl!@?H-r@0)EJQq$61&fI==WuU%K-Rtn5@ zxPojR5x9eKmR1NmI-1Uc^^mPQKM#5J6{LN;&Pm#k711@u9xkEFOTuPrm~7d3?Az35 zvDr2{fH7zRgMpW$ZULbDcf1oH4&_QXVUl1+p~%M!JW3yRCOGDJrckUrrw~cBd9GC@ zak=j5_QE1BWqvWJKoPw_ZgRT!;Ye=iB3oOHRY#&pgs^^n0VOgTm)_``R=fE#%B8-F zqDw^zj49Fx$JL~pXHyz`-)z^fWtr}@=v7A_7%jf%c30Xof9$%7O4g(ITJKOADBFE2 z`sI~SLO3pcT*_HUYOMjHlM&?(mRnfk&5b*;A|vbPt`nsf@qUcTqn9f&4|(@m4W2(lwZ3u1|LS^`d#Xnw zY48Ol>m#$&J8e50MiQOl>+@ImV|I;Ja$UC4@V?PDEyph_{>q_Xv?UJAaO+fprUuk` z9;+x$!ft<}RE*YqMGxf< z0oI^~;T}vTQ3_jyhO*J7B-B=N-k9nk2b`^FSxy~R14AOqMl5boic|u>H&n>k0tU4i zj%jEyE>wC$eup>EmzlMeD?vmOJInEV-?%9U=o@idll*dbe>EjPK$(^dPq0I@nUwSc zbw}Q+p=Hp5vHV~yFi=$LUt2M%U~5U}H6wX49K(2E$}xp{-HelRR2*&ST2vH|`Vw(B zi{beP!g0{-ZIIN9{QF6nmtx_otG#5;sgn+>e^Zagv*&kjrKar)#jSVx1UgXMrB|yN z@3BPUZ1|r;*Ts&!MaDk0%7Bru1IEq`jeFKv(bSp~<)Y6R;@@V$j2k_vQ?Htb`JEjd z<*_w6k9;0)Pu2tQHh}>b;x(3Gi}nYlpzBkvFKBQ4yPxW)D&|Nw=x&)&X;rB$kISXW^yi~C@ONN@A{!8dGHaKa8)rQ*`DZDiyVoYKQY*R1ljK8GpP0dLh`oAi&*1sxpGiWa+2H}+i zZ}>W8UDo}+>1K^LKf5V|ywCZp=GGJL7bJx_WZk9@5(`hMXcVu*vmQmq#2-C9;c07q zN8XpMwUQdM!L>5~JP|w|Ll$TN&u70vJOGwOWT5(|-bh0j0yNWuQ}1Rf8EgTBFynG5 zNE>8G=zsVS?;B!Iq+PgsoxDE2McXba%bna+faKm6Ki_eF@z^KseSd4aS8Pd0%z+`Q zWDt+fkYmpYo`Lm_l=&u%e(h&%tF@p`OKu6X*I*>P0D76D0YA)0T#L=S$5 zIU=`LgstE^jP2}ct~d15-Q7qYp_%kq%2CFn= zcqLTp`QWZeR9aVFl4tTivISg3xNWgj#M`mtVlHT)Fu_IIpm!&Um0?JA z2tCIcS-L6)Uc<7tnT8l(JTcp%2yGf>O@QJd{$-g4@1PaFJ zW{!8Pnya#ypBA(=5VyY;6&4nmm|6D!ez3XF#d32KTxB#X%&uRJ+F&XnU|dD7wh$d4 z&$}5=F+-0qhB1mMKQ7md+~dmqF}g@!sVii5QJ_T&4;$Cu@=$D3lqO2c%)+Wab+)wH zwi|>v5rN`=7Fg+po+>WQA`pq!iQg?)cZAlY8T^Z}qVKcL#P94uM9F>pzDqhibE}EZ zVBd+iU*Mg_5L8=BP<}^8t{P#UE51oCsnW6Mtbx(ZLNDI$khPsaOvDux7n(((lkuUqUkb{F@&4$a+G<9AA<@S++w}f}K2Ba1@Fq>c}{7Nh9bRLhVUr zTtYlop^fH!A}QcTBWkKdwAp|dRaNJ6=x~+6q3l581&RzX%%8kzrsI0l$^v9|9anaJ|6Ui%hCTxw8P)HA3A;y zkBUh|J7Hg$_lL8p_)xla6b{=_4^*mzM+k_}lQs5XF+sgDs~nRh_Q8_s`7CEaS5}3Dg$3Ia1a^b(QZ-h0192Dt zgwA$vzW5OF-XMwP*b+m7wdw29LW>idySux;#Roi1U8iRamW%!ja<0n4wZrxEdJ&Cn zI~+CQ8qi%AkpA5!>CWoO0EJE8?r55+bI9~UDrm2WZVtObctucb79b<5EX+Ru9EI=u z_56RR*e@Swz0T?KnLz55iJu(~Spk04`%vk>A9XQ+Q8(df)MaIybq4Bt))RSf5fx@W zS@O}K#qDjwuDbu(atBatfAjcoT6?wFx&MSi0qs*FE?oSo8}C@t=Ug*eTLg+X?Hcj! z@N(H9W>BT;_H>xbXFxTOmJdqPd0=IOlw*y=gn;8rXL!0>^WBpjK1x>+$K@T$b@w85`UK|``!}w^n>53q4A(V`|ZlnK&F_- zF+f{1E~`kbBM;DcUm2>KI|85R&BRL2f{}<4D#GBu7ordKR zjzHm$cjJ$d!NI|&HvkSfawko(C@n94#$h(*03Q|D0{k1juZ?1P9-%%DP(nB_cg~o( zP(47bTsL*R^wIMwE4gz!|2*2j2kb?c-Z+LoJhiE0UFYX|_kT3S|Dq>tY#1o(ji_Sj zv0Qh337tYSC}dtJl&G)J_TNfGzN1nsQq`WP#U0eYEjn7CTU$ngy={)&>^q&fPAOxc zGZ0oJq9qZqPJRcG-F9#TatTM$IuUSiM!&>@1G9P?G=xcN7nwnOULjUeP(*nZ+(aMr zHk)2vUVz;84WVhl1M;tMNGn3Nh$mgH@aM|)qOD?V`n$S(ed*g`zv#dEQC622efAKP zi}xl(BEL>;UXA5h|9N^W6KT&xi8}ep$_g1Z^>?iPlB5y|_eU?uIK-d%1QSu=WA*h; zTCHEBe9wU6lJC*G<_BF2FC&;1YB+tMTB-~*9YIPxl_e!{Cqj-e+7^!%*|lq|T?X<9 z27MN~v|79434)n9KI4OybNM;G9%nu>rVQ98`7Yx1gg8R~GdfXD&SgVM)J5ax4xGc1 zTEehgnBu`3$Uv3Lnx5Y*j;^$#1Cd6#PM9nfsTu|`7K#?ATzYw>KS(cf(2HV^JNPQT zdQjGgi-mSw`Zn+$2Qh5#oo;mN1Y;V4^+eOeM&|7niue|AoOWZ?LxACvcEB)Kr&Kug zL{Nq-GWz?Fu`_lv+AYHrGjq$X!Q)WkH1tw+vcllsE#yL|ZVtZ$-!Xl+ubuim2Phz% zhbP-+XxViRA_Pl6p4#74wU`fzM3;k4(HM3HKb@!@ukowAFM5V!AE& zO(_DESlW%2-3`nQhQNYEtHw3%EY7MyNio})HIh!E#>dhjvRD(GC0C*<^@5P2_ui6u zjmCV(#$p*qjMB9sO;u!NWU*$}D| z&AIEF^P{-5MA|}8#N7N(+^=VL+Y7XBYK6=k1Gos-$8#zGs;x0jo`j$pyGd4MAYw~` z*^Mo?`<3x=I!pR{L0oqedgb7Igs`&CBt!GC!d=pk>4;7m=IztR12nSfeHzNzP#CZ!!AfbWU_~p`EWID zoJcE%cOXR<(!tO!XrE8o@Ii{6TJ8mTym0~~6L0Dkg__C#tPpkkgK?-VU)u$jewc;c z`TG~SGZR5$g1PV5i4nw;21q+65Fw4HaI>Edp03oJ!W&1Y&BMlwT44B(@xf%3Uvb_q z8D}j_^MH~rP9Y~-|CW`z7PATgyK`hWASkmbpF0yJz^S-aumR0zuFB_be~WL4 zAx4ybsNn;~lxEA+>%B$b`bC%|lUgt4jH!YPKpsEe0Y-QwVR&mWRP4yDsBFFWhnm!X z%<@;5#bF3ralk;Y?xPNT`G2Gn;=BLs(Ejbk;YdOC+_jKcmG)kVwWJ{r*dRVry@uDi zSgH?y)p%L~0(1xCLWi!<)VL)v_;#)kKo7z`;AisVN0dT7DFckW+=ffv^50H(t9bqS zu+Z+&xZOTit{uWw(ImACTl0Cmr|${C1GB&*Ff`&x>0?J+8SqD&AJd^KSGNFtU0(+L zGC-X%xE(mppV(}C4QS1`X(rEgB%0W3gJp2HTk0u?euqwjO2}D>lEzQOJ?3c>quU;* z!Fp9Z|24z4#j(zZznufadKa%YJk1=tgC>L!kFxHznXeu$JGsVBY=rA8b(-I2Uqh%p zl*q9Ck9k#EcapSC4*LKClC}*Wx@rqXnZLgt_W`rYt3&~<>=FY@<~SV%u~-BP-xe2d zY3O=whIL<#&sg{Q3Y$h*m#O&er*90(i&CR1`8INLXdQPuT#6#aJ0DcU7_&v(UPaU8 zxQ&@^3RdW~x9EuaZM`$dI{EmCeI1a*#b18tTmyJ15ZnPH%e2kws+T6|X!HrEDUR?& zXL+8!{e}eb=Q%64@lsr+8KC7e@_4v{i2F;lzuI@ZaQLlMmU9Z-difJ*ECdCo&{+$< zr8#xldrOK*)|=N$OrYc3L%_&<@HUE;?N#+lLO-xnF<7Bek|;$jIm;1ce5VE!@P1H#v!==w z{oB!Ht;6eS)$@})IZWa!Onw}S5kxpu*IsngbYz=}FRyvW; zOrC4E_(qfpBN}xcARjM!TPM>BZk#_nFo5{+Vj=-in(>2w0c=k!xLTbWxJf{;%cbRS z>36s$tklw@$b-0slO`du@o_Tj@N@(I1%(N14@HsDwj60v3wu%Lo%QLBy9bJvm9=@_ z>6hVZlM^GYLOR;^Z&#d?nOg~J_X+~;Zlmx!Dclyl=yv=HDBKf2-{qy`O_!Zs_$y@m zS~KQ@EoVxtugDF$-zlcCyTeK=lXy0?=4W1@NHq2jt+;@o)wO0DQaX+sD4_DAwMLbf z1+#NZl5+wX)Hurh!cLJ^;Hm$C?sU9z)TuHFL1kHLB>|+s#?+je5{FwNvNtnc&oDzO@uJ; zSruO@-UzoW;qt6vWuehU{0{{=a(-obsWg9lJih`+8-Pz|iTx5F0ecLghpnrJztIf0 zHHw_!)&$Ze#vr&zMYImJd{ndTK8yMH^5RNhk-}Z=I_arX^*~uy52>~oCp&C*VY|7R z4wd6rXqMc5ZTyNqGfhgjJtFu9dEur1YEnTjx2{=IROs`7oc;}Al%{uYHs1;u`$DBp zL{X(vymJ}a)5r5^AR@Cd(ia=e6Z0u{(8|$T+jSYP7v3*+RmBe2nZE6e9d06t7n!19GOqDu zxc7n`97uw*q+hW?>0agP8xdNO6RVt;qPTIbsUIw$dr6wIHtTN$ zX6V<{iH?vVHQxI{D;A+^OFuirewQ0kt$SV2C4N6GjuBZPaTBkm-VRlInJsbiB%y13 zzkc?zi>pIAyQ4;xEQ0W4*p7sNf}C8qJ?gzj8XPlljUw=}EAg^7aXhHMovDJfVmyn3 zgX7dog0KI3kH0)%9hKJ9oM%Nz=>2)q_HMgf{HPs$(gs*FMn;R5YQa+*R9O-tWHTmF zN8>W!B7S3IV?VbNs()>BkFP1Qyhbb|`4`Wh_7DD%`=E?m46d2|FGRnm=g5B${cXAU z?f+GpGTx3QJ-ZdJ0SHokmZ6n)rS$dKj?f%ZM+b$GhZU6_ie zRD&)Cpt8jOG%od1n+V9v4(EJfUt)^tdflOJ=wH7|(46fNX|9#2@SscW7MK z{a!7DKeaL+itCu>GI$jeKnd00|6s_`pb0R9&C)^8c{bXqsk*V_yxeuvLN9>k;W*@K zPsQi+Dn!PsWCsvSM*pp7eV2XTdf0;Xc#QW*+yAVh^TB<8sZoU&mv1w;qIs7bz^69d ztL+{rQ%|Ug?yr5@wH~ME{l`l8L^2}6U7vA}RR;LdbIqss>7+L6Ug?JBFeDr7cVmky z>W~o0LlWwG5kxOalTR9ZqNf z%x|gMCRsUU)rB)!hCP4a4Zflb@ORQ>n}vk^b7b5k_QPhqjlU_clz@e2cFR5xvaL^4 zQONe1w56430LRZ=Pli*cj;va%X1@hI8JBs4m9=#QKw9c<`6ycvL-jSk1*o!^8A#gW zIGymY9m;v;c+}fZS`KNeaHbTlqd}6pUH|P?$IG`FuAF8&)K9AD(NCqL1N@*25KHb+ zuehz(11qM>)5e>lm6X2DzSP@Z^MuFjNTu6a@;yslJhTAh!27%8~= z@7&OJSQkO}L>G((od5%N(pJjVYh(SG;aiie@BIAFA9I3g$9;GARzXOX z!qr69s15L&gPp{oZv#Wmxw|`6rY8Lv8$`hKxKO#iAaM> zZ+PD^AagP{b0toC7F3wlfz^KSi@zAx(DRUuu>Kfeb=9-uN-H{kxh$d&`126^pM9Nh z0Yf^lYC?utZ@auTb|s{(IKJ~a3A$S%-{M^$ zx)YaMaa3WW;ozJPn%K)1+z^Cq6GR{k6$iEa7Fy32>+{26)+HJTD{uGzm_~vNK ze-plOaNCzJs#>#)E42!oUiN!mM*W-tS0pKrNRi$g78>0DY(QED6DzPt41@4mX~W@R z;nxSt){@?HN^I=2yw+R%_a!`91d3zdCgqik((Se(1tN#Q<+n4({L6hp`#r-l-CArL zx9NJp$MnR(ukVjVwJ~#TJ3AQeUGZ-ju|(?{U1&e`j#un)-R1gmb|gY6QKo=PBInVy z(ue>?q1wv+oI@;_fq5((dnpDCkrLY4OLnchP>RyW({AJ-;ulX8oIj`yceh=Bhk@OZ zWA|wA$h4=9%TZWc`!=F{S+<{9{}S;2#>OIlaXB=Mp|>CcvYC!T$sPF$eGu(?9s9 zxVRyQ*wy-pq8l$i5vI^CJ%vtFJWCYM%G5JI*m@>7dkqK3jq(M2r( z-zKlG1cZV+@0U6=?5$<$X@QP1O2?M5+50BYKq%_@eYcZb9{hALB!xT1! z8qF9#HsY5d@>3T*Z2O*8-?oD9f^I}_c4aB)He@4`yK0QURV)=Fh?Z1>%<*XDsQH(4 zA1X>QLSCj}Q10R244MqsLTP+rbiQJ1TK^8!n&~@S5#iw%4V{6}3jbcJ+6!m1?G7Tv z?DB-I)7kCqlInux4-%FjL#O)@>POS(r|xBfvasgHM$*Rx5ha`Lt*XtW;nasJBIa zlGaEM{;hV%-oPCfH5barf;YfM6PI1LgYw`Y zW1;1oN5_3{$Mx=n`J^v?$&gHq?5m8#y3vqij_P;g7vvFi)Dc^@`U3oGK3sDZpCb4y z=FwrCV=$ROr17e&@+~+3cHaGQ=%OpqpBArlLTYjHehU9+YA; zDGCZBZT^fM{0$BRgaL-*neAj$RK5N|Sk;b;ubO{wk|=TmlBsJqyL?kW1OeY&p>R5# zF-?qv+N%Ht2%;0qvjF<%!6AO#*l*u=Fy2CNE0DCcTbe25*xxTwxGF}$GJt2efr+kIQ<%z5*Fi-e~G1e+%zfF zfV|>lFjE^h!#g8LJ;ETy?Qy{%^gD!8ECQ<~wYrTHRZL&P+k{wXG$2W-YcMhP&z>Ap zR*>~`&@DV?ey%qfVmA|+4Vj+!n>skxkgGKxZdrrzt_Ja19#ptNXY>vg929-FC3kKD zKno|c)QF8ZI?6v_gqAjVvy7;p881`C8S)-u;kM`3TNDxWsSn~L{rH+U1a-VhC&7eTu4 zj^Im+JMd0U2(@s5uRTm*+(MoSVUOFpkQC@Ndj!SSk9QB@Jim_cQrbS!dO5X})F*%x z{GibwbNa3;ttZtcr2M~X;bUU{2O|+VU?jqL67Lhe{AtC4lG*xH-W*)^9}fSi=RSDjW2y4|^s!qtVPeZx^ z&JC;rIZ=qsT(gSf+tA7Ixu5sx=V)BEPaoOn5Q>4y40~O!Xj;#k{8dMqB5GrbRR+@| zH>zyQt2Es{nU3sGlXQ~Dc9}m9qAWX3E5i;Cll(!g&Ij&q41L3n%1QF^_-@7@?^OIC z%$$Y<0f0ha3s_goCm0JXYB_kMd-Pt~)1=GkH3#0#1Mg6+l}r&V29SJl;&QE? zUi*t~5F96bS&qv@V3u?TwKZrHL-gb0ck=8+Th1{&AF%X;4jALuZpPNq<+(TyGnwPJ zn~x(vesR*FV1#LueEmAIV1gf@d>R+}q@<5cF%i>E$ESg2kcFUF9p z1qj11?-Zam-aHc7Ej9RECWg5pDrDaMkjB7x1yiXql!5TU7CW_e)J1g$x z#ip50r=aht-I9$p1PKp}zG_geRgEcrwb8jzKi`4NkoRpFzLu7=mjwIUL~a>!BE7I2 z%kzqZ=yKJCtEL&-H6THW3At}qtv}@?LaymyQ6e+BHt=pZ&DuHu1p$UVPFnKq+VxVD z`|F+tP0w1cP(7Z3on5{FHnBo~Hdz3k*!0_U;pr0Z+vp5JEM%x#MT)pjM_W;w{;SC; zChCA^(Pxg_q+{u^!k6C^eY6mAwO+^{^>Dh8QM@%a6U2h?$Pcu&=ySg>6JI9hv0Fksc_NgmecQIWXO+#~V2>)-Pt;K=G}FyMaAsz;%&g_J3pxG1 zfAHUOLzF*~aKNf^tvGY+gvqJOm@M0^9wqzi%k$xg$M$CBzJ$C8+zEg?lN}-I&}63c z7?D0)-5l}gPz9IfAW(cFo`fafQ#=p8JaeA8a5Daw5$3RDp=N4oSP-J7@WoJ&d|3;G z!WJyw5$M{1EaSM{MtJ&zJ^eif<1}%IM`O$Nuq!Q^|#z&5rW)>Ua_m3Bm^;U zR7aw^XB1s$+4TH1JMQ`cR+S`_`#zW5UPj&b?De|5zH<$040AT+9&|z$#{TywAO~9X zWkjw$|4%Kz&qEfJckdBNl5<47uGYmi`hw=C(*xf%-b_xaxm{ffnhQ;19%u3+Z%GS! z|LkmjDABvR?zuvz@mA|N>16Z4!*W-?fXj?WkzStux(wFU)qP*m@_E8%JX6g6aUgI7 zSnI!I%@+NHa`Hh8b-dv|xosO*Q+Ty{y1c&@8?9|uX@4jJe5lc+I<|hx@tU>!tL+qk zN(!0Z>bK*st-92UVke+U0A>QEf7DNGfP__@M)&^afg)92w z(`miYnct?`4|l-M9tQ_!^F;@+z2-TkH8f~WNHar8KN;ETNg}KDdgrGm}pTM%_boBhJvIT_sc35sil^gu4 z-w892{UYPy=$$MVn+bP?d5X{4^ZT7W5ltxOMf^aRxLC#FENoani8SA5SbNnU5W3c1 z4XJq3!!IjZ4}}*|jl;RYP|%7Ugz5@dH#`lhtvWKke{HR4A>ZK$%$)4Ywo6uxZqv9LXOc?SX8kIet`?q9XQ8FY=_qa~mqC zk)-pkMyY(dIv>^_vn$*X?Pb?W(ufZG>&aPw*c#9u5fB>wYp!Jq^eHZ#7gaVed3~nb z=0{A;o2q`Gp@8FyvF>2CMPSg|v6kBj@bc}NOKyEVL9(tpK{VAtZ-uUi0jd3Q`uC;~ zcy9E8jkR^sN>pTI=WVwX4~DkfD*SxLXPzxGGC5B?S^z%N!I9h-T7Nkfipmyfr% z3e5J%Iv6uk=jqXBn+TPN?I9l3k6qp-ub%@lA4g|LgY%ys&8*G+tw=Y79N%1CvZ6eL z1#@^-q3S|Ayyh>sSEEDzNK^m#HHDaN%V8Y!b;Xbeq%7giDj^|oX(Y+JOGb<-`zcG7 z=wg2fOG8KG@eW>KpF~Ccr7Hi?G9aXSk^lhsE9+-_HOjb9WNL!Wq(7}Q3BM8ojZgg{g9|;0I{P3}L8OL2}w2t=PPh?j1w;T|WYjXwC=?dopin#SraT zJvRtiFeGk384O|zZg^|>KS)@N5YBQ`)WsZ`8LvfT=_h9aR~9ax@o)_i{Z zhCY{K&<%GWTsB{fDnOQ0j*{xSh2)HnKfAR8*V#g3e@+7yN8S}K4zJT>azvupZD0+0KVRINTT>F3(6Qh zifhKgwj<09cW_bC9$S|Md;+6miqSjQ*z-!jC%DS9e%-ac zeDj{E`_h~yzWcPzMr=iq4?|~I5%RIsdu4%lz|GKY zy|gg+2i@b1{g2A^N>9|!=s(m?UMV1BWzYqd4ti|$yUQN{!9E1?KUfQJ0KHYB_L)LHeV!+`lJ~z`} zSiAw121wLF&mMT2EBwZ`Dm_;IR(W3A-|Y%?c0aNDr?)A_dDBeR8O z95VaS#IGdx*E(sQG{Z4$GF?_7#(>SsQ4bH|Q{#^iFElkR<995MMdEpuN8|OzAxnAf z7>5!H#PR;RBJ{1)xpKP#LYRokA79&K-LE!SQAm|9a0!paf5YI*W7YBUYHu2>l^A?7 zL9nWK1yyqBwy1aA95?Toi{9tyv>UhlL-iOvQ9WnH|E6sEhw8zfz$pb`sIzm6(cRz| zl2X{vI65nWMCNDa@`@^HXs!o~Y#q6y%#_(I$B7p{(w-t*y)aR30(WVnnBy|f!m;RE ztX-T(^E#an*nqjZC>m zBV_>*t#cY-(BzPCp1?=^T|#rYB|Ueyca+R6=1-4v8UWn%7&$O&0aiAYIIK$98w=Hl zfXSSKO1AISa#qvS;6VMBo-Ns`0TIxdd&JFi#xN>^8WN5VpXpi6HZMX@E z!^lsA==Z;KKxnblu(7d?pwq3kXA3+tGc!ilr_T&z#Xx(0tWABOM)_i4Q5O_O0?@=V z*Z<<|EyLnyw53tp-JJmvAUMH&a1uN~AUGiecXtgEJOr1)f`s6~-GjTkGq?YP4@7MRQVTSH`c&4k@s;X5BsonAOdT=WPVz>_aRuxVRHF;o!VAjGJFA9(8SSgwn zMcUZXTxd}icq*!6iXC=IBUh;jmZYhzFOnZ(rjHPW6~WJjgOY5%k%|2F$E}hM8=JSu zUm&r=M6~ zQ8hQNbRDub9LY!`;%=_igoO3=!gdPqt1-B6j%1I|H#547#C()m5SLo=CALqTZAw^94g6N7)WoI2U zGmc(YN^Mw$t@3+bLf{NP%PiOm%_%9dQoPlt{iY$lM_KgyTVxoFs&m{_e%r@9HHqlf zxDx%DYR{iWK@z!f!W(Jd;1v#j4ZXu#^8CJ-by?14g4yS3%J}dP%p}!S)Xy$GA5n7{ zd<9Wx78X=#^37|+X!;T{+iX0x;^hI3B&C360s^-5{1ysoM02@^%L;lqdU}ho1?w`5bp1-ZwEmjH^yIBppl)v(x_>YCmWMn-!`}K|23sEViR#jjk`Jc| zgO{^Lv2727ZQZ4HD=fw?^?0z)tx;v?gpyv3841{+U&9T0z=}AL*0X5)KYF*r~J?AX1HG7N{hvrqhr8#?+4b3PR4 z128{E2|D@{&h9=5*vx@A4ySnZ=OEh68^nLJX-cA+Wf@V`uupZN!oTJ>uKPZ z<^Oa6Ax!`y9JW0k*%x9@w4L~#bU_~HA?u5P?T81?80!nVUT@4+m8 z2c=QwsRNwIvDU!Ta=I_^|HSuag@9J%pP@NSkIh)<}^#X9AzoOd1|A$FBPZQ4N2+UkMzkFvQ%rPjS)6L;IWHUTdYi?Q$SgDk@HBzC&WXh{E$@PI=G zpPNxJ#QfxXirK-0uW%+g2%K-pPTq1U3}7T@urUa3SCd?c#$Xk`Y+X++CgsQabG zz+PmE!g_I0DPwPCiR7!tE^yey;D;mI&(2Sy5JU$9tW(3k>%R~q{49z?NmErDnQ@fM zl-w7nM4~Fk2m3A1ewc<@Voh^+C;O+n@x{uGFy%Q>5}J2m{?<7+*^%in#~ zMH^NdbM=bat*|klUO|;v62!)+;37)E`lU}Pek0K4 zQSP?x%G=>(c&`$2cq>po-Z1hhHWj7WGrC9oti#&nY0Guk#m{MZV9UQoSjoL5g5zuy zrSHPE)trM}2hLmJj{W-b<)x~G`AOWEC4+w<2CKHt{V%*0b!s z8ts3Z>>qzgtl-}`8oGI}aeLv&uKCn_C#ZRQv0syBYt0hpR~x-Y^azBu_4b&^KE75^ z1=ZM)j~MyJslh32?3ZD)QhYf=cs{xI3-@ojHP@-K!Ja_I=J>U_JS!b%IQtlBw2DOj z??m-azV(GospS7n-YX+c|e0w*k;&%+aF5I`XcupSH-& zeLGm0h8;{Tm3>}67Ut`PMj<^;da3*tS(G^-5yNJ zX<>(h_R!HFoJaCBN~+DdXW}N0k!L#M^~MSQPz?M6$H70>nms11<^o=79OPJsf5SO! z77yo7yM%MCoP2G;7Sl)TPX*ADg73?9qZRpWz`Rx{BQU>AxY3u*Cj*r-DOpD^i#Xsa zQP>QdW$cR33U|+is01CVgGr@-K2_EGOcIAPp_P%ErMqY)>#)tAi;$8~;gurB^>WSAwK2ns zXv;MX{uMKX@rbz4!1u<(6|6xDir^bZO=c3arU)5=TOW8)furR%+P)a<>>mwUV6WQ5 zM_fs-(RD{*oD@|gsHY4!Ke`rF81qvFC@`|nohHPLf{bFnXC=60Psaympx1BGWiffYh-ro_8>!Z{9L?YHQGH_z3viQcCi6dQ_QaAT`3*wgsZ}L_ zHB_Rm0&Mn3w#w>5=@PV<$z^g?WhAm9xYE`5JmjXr`q5)40OiQ}#JNoXC+UcA+k`b4 zX03t*4Mt?^Zj;qj-cX_!79|OOtf&XLdW&%70O<};CV1288wZxv;jkIWK%$apxW=ib?)zts3thu>Qx3<(FJjw^A#V_vA)|- zQ7NyFf23$iV6+n6$@86myS4Z}S7PPW7b2fHab{h7<~7B$Ly#Et4leDn6FfiKq z`8zd~DF`O6G`jia3w^#m7F(Aj2Tv5SV$*4oKnuw(q>1E<4@!(OGXxSyr*?8MqACIp z{onxlz%yNZ8&VF8yybt=uoqS&2F&{(gt>lx05s1O1U3>a^qH`>Q5S(Nil-NJ_jqZz zfu4+~s$Vc4G<|nm{chGCS^Udgg3BMgH>`8=?v$*B(`yB|J6Nt`%2*?48CMwfrexsw z@Yh^u5&wpMi2+B~M*pOXsbMH-f|ZfTv}J&T`{@SA-ugNFwp8ev2$&c+n`9zM6va&vFWViO&4CKhmnS*3~kx!h`*y}8=Z#e?W$CTc(5{` ztb@XLuS74WG;YRY{a$cD3ID>k52pm_>Q!xB;4O8n(GdEDC$Oe!6R`c09|Io#bB@0g zh3>5vnF#Y2z9#;54cjCS54#e{muMmW=LwMRhTSaIMS8^ZbzFascX3$<5cd_&D*qrT z8%ewE)#YVG3?QL#4&Gnx2E9?g+`lc58T-b>jd;l;zM?-4lQ%OX$#x2W3MM4Hl z0{Vfzpw|Ox`=?PW|GRt5Cm(%j;QuV11z@^Y>F32X;8AbOAS~A}tj6VVvzZlR^x|rEp*#w!T zB6K-4H5a4VbCLNMm;vUO!OE^#wBu8h(dx(AFqIWQIy90N(2K3Aj|eEJVa81yz|2Cp z4_z#fsfR1b&lRvM@r>*wI;j;G;;%)92Z*iA0T(GxY*b#fuTY^|5DEcj}=oC9LGD=wJ_{t22)_Cq&y~T?jm1uPdH96FttJ zYe-5<+c#q+zC1Tx_)#6R=GNHGKaZ}Yqr6G_Z02=h;2Z6`n!LorYF$`t_p`(cQCT1y zg<=ejp8zrH1yZQR5ZNSI7biCg0wu+ZNvziiet&kZ_riD?dEdEDVz+3yer8YAYB29@ zEvIQ+F>o7kFK;q`&yl6)`l-8NdK`bdmC#c zBP}$3VDo;r+}P9?w}twV*>DV!bwU%)PXscnNE2a!X{?s4K?jF)$unn( zkb8Q+V~Ixsyjurq(ohrrh6yI_Y>$vVS~8-z)-QE5^V@5zAkbq+Y-N-h(TzF_*gvx7 zT(&3Rv9-AEWY6B}nPD{@^I=$msqC!Z^xijW^zKqU@DebnmkB6j(-RO6Dm;5Xd4q}8 zqXkxg^-axPvi)7Z)wvTJ-8JAZ{e~ZL5*TUwbZGfiAy-lXv8F>#IO<>`JmllT05&9x zA_h!&T?lIxUbbuLr_rv$fT>YR?&Q0MsnH*P9GA|;5XDFR{oQvG5ppt`x ze09PCPEntXP&zeYNejFOM+_aArk3N)?n6EJj)}XK$rq~_B4H`3C$iGDQ#>`QH>q{y z)rc{65Bp1U!>+G4W1nwg?VZ2+H<~Bq(V`&d0~foH?+30Y@zn}-lMi8nHcGIT7vlrk zsRJf_ks1{eMj16ZbyuRb0APsOhJbk{$Y?UJ-#6@r6Hh#1+|}2aDR;Z`HZ(`x$n-1e5}j zG02NWh6D?RZ|cy`VGcc{RYIX$ zXUaPe2J?ym3FQh1O{_M0VlFP~9a8ye$7SJ}9%E#?V4{)XNIiWJlCjD#hcz7tJ5bf( zl#O|ym+`v5x`}gM^^eO2b)lUk`=v1c$IDfN2xpB z6%#o%=r0F;i%H)SFrek*1Cbf<#g46ciL*>oxJ-h@S9>eHFqh7vUlrl#{nMuMt@`GYu4gUtkp$X&m1G|U7tKjf25K(&xu8yJxK~~ zzrKQDJn&=B$GgoTdTw0^eFB0_k44wC*NLqiFgboDvK&rRWc&Ql$R#Gxi(Pgr+*o94f4NIzLNK{1R){ zhZU((5nxR(B#au`zy!a{x*zDDKXaVW%_z_D%JplllAuTVKXK!>y8Sbxe6#I#d9|;-oviU*P7TxLCc;}x5*E7R5EYYojYhz@-0ynlCVwY+ z18*?e;yXB7=XQ^4aQC?x$PGm;M$xyk*8S{L;|NxQPM`u z$QhNE*KP*4m$I8P`$7wVreDqpSj%J2E%zVeS`C`cqbjvQ5fYf0SH36s7m*K z-CAz~J}0{r$u9R6ny|NzXLwwe^m3}(&2=GEP}S8b=mGX3kW03Mx(yw1ds@UaOZY;2 zU-h=0a8KDSB1H+Lkvk;753hydZQZGioWe4x*4Y<7{}HuR0A~xsuOUqnHg9^1ml?Et z{m}yiaYb<{txissI<>vu)bG#NIOI~Dm3+2%BkPK=1Fhe`p|E~CO30YMVLUu7D@I+vMXcPj+2 zX~Eo&$qz&r$V+LdJr55EZ?|8|$@e+zPg&aWg6%GOIZ!&K8$BIF5NR+QewTQ^$vB~~ zJfKVOH})<>njKf0bLDb&MiwwHL-0a3H+m9fc_Nak#%+l4vpHUBzX^#odgu{2i=aK} zcpx~vYCzVcMl4pMNjw);p*rY1fb4gaTDQBeG)Cc;mFHAY8hh77aWtWnx)7iETtA~^ z*lszA3EnO-Iqn}iE7Z-OTD>HTA2lYefwySA_U%s1q6p+A`gI@|8&Bzr#^C1}1ex^F z=$qneAG3^63r7A5!AUqCrs5eO#-$ToJHJ2mzoGVV%cfkI#*KSLdX{R++4;*$0U6w1 z^bym$qHlrwd_a9q%m8eH>urZlEEZsNW^%_beC?7yD^_m@hbzo4P^ZpJ6n_N$VoG-N zv_jI_(t@x$%{?Izy0$%A=?z0Bn}X59LkS7*>feMm)~zhZXKj|LSECqvdg8N|usT3n zODzu-Aa8p>V$!$3x{olq3mPt7+*yCiX)ewDEI zK*@n?yJxlr+}a=vDnaBT$NAG!F1zK%9)J1Ts(vZB4`^d=vqbxSY4}ym=-LxBjbdJ6 zgd^Om!vimbe+__@nim0;jsffZ#px^1<%Qgk9z67ipGpm^$^PG%Vrh#t9J^?}`R^Z3 zo?0s#8wXJEh8K+9hB%F^**RKISPdGwuyF9VST;q#p zWFlFQ&1iws5s{Ms@lEOiWh$sY@3`NbXyV;%ETf9kd!S~z`3KIVt&1UbS?=#7>`z+(+e z7w#$>K-Uq%V9FNk>ITA(!ckFBxVX5&LCvJh#bwoIaZfZcF!inV2VDPvhIvY?3G)e* zU|5-+Y|T44y)x{~%*?|(We|7ZY>jRr{9A;g!R?8b>In2FBn&&jHl`66tn>a^$!w%;GFhAZZ zgiF7@F@nc0w0tnN)oHr7%taJ86pcQ&ywW+M09nv$uC*ju!$;^nP``Mnf#8=QWuPS zR*61S7)ogZCoKTvI-o%N);b(TcUV7RVuNv}i^jC}h6*W3x$ z#%DDS>mn_&DXaFOQY{mCh7-#AaX@nR+3j|DC+;Rvf5xVq+uoDR2#fpQ=C z_at-7NX#NyF^awX<4IL&tXkae*7&sgAKKsd1cdS*mTAYK*O`1TUz@ls?_w>Ln$!?< z+R$pg*&p27>+f(Ma*azP!0mDixr#aLZBcE#8SofNC)We{vJpNg1%5mXK~J znrzPTxLD7_L+Q9Q2^eTNfj@bKli;3;*a+L@PPFeT(U8Y4JIQ6`T7z;}6+}*1kiI5t zL2HI)Om^8sPRTE}eZlbEdug-nwSjh^m z^}&T{OCatxsGeo)7NEIQK4f+D=Q>5~!dfJ~lnX_tDw>-^wi90p5*gbC>AlK@!; z9=L-AK^TAj)-TuIEQ3-3k2G`*;=pe`^pQW&fu$t@#PQ+UX?tj{+ z|L&+BPJJo9<4d3;Bjx)Ounchjb7DN?EUka_L62EY?<7`F@V_1WEsFZIz<(Ps|L;`a z?r!sn+_(%GfMzk=R535^3!FPJmsychK;=h>@jlXE2R)8)ZCa&p4*Rao|GKTG?)m9H zB~3gczS2@K2R&K21l@|44DaP!GFOF%`M?puid)5fyEe6y@c|2z2oR90xpOoJ*+5Dblo3) z{p3rI=&uFhM%;`&J`r@~X)q^QIXt4ZATm^FSfUsdHy{MV(nh!r<-uN7zuHgj4sTTU z87o|aM&&Vno5!s*iYTnkE{5gF#~6d)p}_%t#Pm_=2*AZYsw`*>@e2r4*4GD2ClcG( z+2&R>4LZJ@%Yb)UkbuFXl%f-8->K0MMyaeS4}OC4b8sL7Qn@n9sWS}@->JrVB2D}Z zbzvOlYT6aVTAobNPS$ofy5qC4wXMc{oZ5O3Ln|_33K~n^P_er}TG7bEXr!5_dS6PP z+25VDZ-wKy3D+oRpl$4nS0q&Mg^N9C%{7Knb`e*Kt^AkqXEz*L!^Y0oXjP?;UUz7R zni$h>u_duO38M^4H9Ze&Z3RG{%BFuHWzi$@JW;!RVl+)W@465c3da?5$JN`$^>S6F zN`#y!VWsW9d^pht&{qYunNm3wVX3J?z|yUp9l?~ejIv-@&qr<)=&%Ub%Wih;`xd_A z#G#HM8?g!5DhFub-W?aYM8{I137k&|T#lE{rbP2aBxeuPZ3ua4#fhRl z>bQxp+Y(m#ZteX?$CGG=2+&O zbiFan0ooF`=r9~N5UhlY0k^=c>#WP;GcVt!!tu+u94k|Gy)7Re3mEcMFdVJF&V@hm zA2!2J^cjmyJ;t9il^#^&q4k{jVKx9e!>a~6dxtRvfjDcz<(56C02*z?Kd$0V_^xJn zE}zv{h0s{xCo+X!8%!w$>GSbgEaD8=(zcp_DwOKAPz{G=zxQVskb8(Qucv!k>#Vxw zEWVm6_k+JvgnUr}`5r2$TFKzAR&E#~?ECp#U!$hoPYFt!hG!XjSp`Uy|H-db_%XSZ zl0!aF=&et7x1=9P1?5`?m;R0{i^1Zb-K}V84PU)I@(+DJO!k8(*{+kvmg|mh{ek?_TE!~Ei&-Y1c8D$c%fT=+gM1I>UjRhR z?At3*9}I=ZX8a3b1#? z3~Q3fZDQ+|I=;FlP;(%Z_C`lu}D9jJfE@8#tlt- zj4`ktef6!xq$m2j!=ocJ_rpd8U!`cqrvcaS?{wy0zOf{4_mXnYA>p%PC4!U~?@YrD z#Yj-ZIShSplf^w~%}1%^#jV#DrX$CAX@6`0tKw{Jj}A{uGlm&7OA;Fu1sdE1nk-5V z)}CYOl%3wiXmG+CZCbzJahrJI_{H9i6pu2ji+89VKLDYF_)qDYWl(hkcR&)TvvSa7 zlm0uRC!tHa5<*Zal*~oRiU>UR+Mv3T20=}^l|wk}q!G(4VNzIfuO=-_sQ~--io?YX zH{0I=Yx`@M0?+ueNPwnro@hJt63MmCZWgJS3Ebk;Vqb4O%e~7;YIhfJs7NW)eZfaA zEYd$ZG*XcuYCs5oh?INn;(j62FPq8x`p?TuFMgQ-OC4Tex6D-?qppV~tesuE+=}Xm z<1(BKabE;eQwCs&lRHiYuVplv#Aj5S<2a36#3bRODR6sROTW>HSZ@*eca6J=&pC51 zQ^EN7e6Wi!rZg^|hZb35kEcR3{a%_yD_KF%C3?P5hSA!I2_C)eqJsH5g&%C6UX#0( zGKGto6$-DLC!DRdOnPKE#21fGtQ%qdEz6A3tb}q1MlRBO5 zt1BG2yD(!)3cHnhq{*vO9-~{TkygylSgmIk1@iupEWL0pYkaG z*n)gF*<%8nSJK-rKCg+}W#t@)xi{F4iG{jU@(KD8uRmY2XVkxrtj&U>Eo+N~98z~O zU*zbXpIT zMggHg2orT#%Kw{D)*AY6GWnls2zQl9lKd>;9RQR}Kk}*M{|#gxH2*1gR!=-xFE9RA zdG&9GnC?Fe@dB{cGxzNeC(1e4i?F28UGkW3&Z0Wgg{8#4cu%R2TXOv-H*7^kMOF5l z2K}<*m}RUXF`dAft8B-IE!C$NhMwERKDUELt-Fx~g8Yu_1){&%wu44aIk2{mhht#M zz~g~Pm8;P5+kr!X|IM-cnbGseNzOZlJ)tljb0fK8igrvQ_<@nFEskH-7z#MjZu9T4 zI3yS8nsf-6mzF1kS60MBOt4t^JI;AiMAmP&Di?utCJNV}mrxi+E)$VProPzQwX?** zWQV6ET!*_Yd>7Yz@_YfZd`>QygrH#lQhmSH(#4t}ABq>c;PxE1;xD+VPi$B&39K$Y zkNcj;^B3Ys@l1HU5*{LQkoH@oiOF97Y;JHlRUWkQ0L~w4Vs?H1#X>%G88mt0iDJn| zEHQdPu2XO}E?2gX^lnm%Pytd!oT1OIz2-$144e01YP<`b`_iiEXrf~YthVi{ddJft=T}juh`UkzZG5MfQ5l@@>WM?P{wR-e^abyz!!1w6 zsT9Vm{0LO&Gt3DYzQne%x6jdJ$<}4h+n>_(VN(o*es5V)k`zkR5PvsBC(9_5gq*eM-1V zDCl)aw)>{^{pKv*7VWsc{ld3UiYbpEKgMjmStteeO;)HbU;9QU#ft9dSUaR9D_hJwE-H6$Y7=@l3n%s4BX9(R>-G!l=IBo`G2v~)a!QNjN z_a4#Re&D05pDj@T%Gg!t;j<;UpXGFaM!6gD8vKfd?$Y0naum{p>@V2u{*&}f@hJG_ zt0F{O3h4u4yjiYN}YFpU@!x>(zMKrda>3z>l_MfGGVe@ zqYp3RT6=}_c`WDLboru+f?+>jp$jlaNTsCp_u)RWoRbs&=%gq!^2C*R-iGu_Jajot`-R=8Fy2G_{;eh(+(nU0lig!{qB7))Cy?+<=6gUUL-T z)yXG)`rZ1~re%4E2-;b;{&O+p?$uJgBVtKO$+sq4g}`7u=hWRW`z*zwmpkVTTPs4~ zlVJPSTgDNH#OO(InC1NjVErA7ft`!bd4-C;Dh1lVgS5e{zc6USa+*(qAXJwgYv+~Hl6AEj{I1V4#X|Ivj}RcJff!_+4<9_O{GHz#*3h_*zx{1x5IA%Fy_uj? zS3CPs3|Gn!c-K1kE*S5^{HVGJP~qB``v3g_|I%Pf`F<;2IEs(WuBABo(NBPRBJvOP z%91?|R1}{rDAX66aA;|r$c9w!_b5z4N(#{(f?Rb*A>~Ur?_gQrUp(>;SR-8Tc_U0D zV7j@xGmkUUH}Ct*KRV-ZdmiR- zUwX1}GyVqVV&=HHAS;uDSomIYPo9j7EIh}kF$oQ)!RrX&0F?9IJgG%39i}E{375Ze)PSR;4MU3Ij)rg|;kriNzOojqoH4Hn-xK2lwB|+YP z)mZEU+2Cu{S#rN|C%*OeD1%(PlT6xmtuSe*iybvVa;c)mPJD5?8^coH4LwDj+T`zh}5 zP*1<20@A66;1f=KzGklV8Twyr_G>NI65ad5FMm_};+q@!A~tEYkJRP06jEX;Ry$-O zG>TO39sgP1DrOM$^ujoxv<}BIwsC=@)z|M>^}q1eFc~epybWbjYADh*8;`N}VL5pboT!o@QXUXcP{9OuqOWC+=8aKXmRrlqsyRinTI( zLi8YQ0Qp42KP*3(t0TzO`XmPPKQY*QY`-0N`QYNs>DO^At5yP5Bp;i6g*^o;gY)hnyv2VHI)*4obF;jg_my|lFFMDg(snJ)axy>I5#ps7Tfyu zic})DwhV~eZbwIqdloU-AH#0-*Py8sy`J;P>W+cA#u*|`K%=Y(x|H8<6mXm^p)**e z5IA*VN%NSHi%-;sW=10~)dP8;v8tP#PY>|2L@Edk4CkfVo>`)^P8KxXkhNbBg;`- zA$jY{WRKqk8cv+?%~r~s{UtLl-Zne!{zU1<(TI|;k>+_^7z2N^O6hA`ImHj~4*x#rvTuguv9QDKx3~a~w@60+L4qHF|-tVKp)8z;$=o zt&7VuIWSLOD98)>bTY}}gFvAjy&@D3$%lzsQKkG!3oOCVqfXT1LHWzyNo?y%dCr|b zQ_fp23$UYA4h7UC4xG=9{dwVa7gpJ#C)e6S==&Ia+FVZ;{AOgll0i)JJ`_h^0_MGU>xvHbQiAsx=w!>1} zle>Rdx&Orp7f)S?R58lrNS?njRaagD8FjjpUauUHSDna2wTQO@Tg60BW})kiVLD9Leq`2${C|Yow7C%G7DLc{H($KTk%n`3VeE@#Fw_J_V(DS)kv|vP90Bk_reurIE#i z=P+z$ey*L8lADx*v$ANYtz~@1nGG^THSrU*hO8fxCKXcS{+k8-X<7f@{w#JMO*_xz z!bfry@snCAjFmIXKI#44dsZ4+`Jrtp0>IR;DuJ4H<*U83_LLS3hzWvmhCA{HxA*zK zzukHMPu=?eEejV`X%}v8ZhU=IX;sMPz5Q9^*pP03ok?VOp6>-HPy=D3Kwb?nW2X7= zLxP#8{ilhIOVs+=d$896bSibXqDlL+&g%&cLBDf0DRyAZC7D+EOBJV>=iiHdgV(B2QS$wcg{dO6iGz>3G6n<5&vNSPp&@ zvqCqPWNm8ham+=_lAQ*lD?HD?MV6dJ$14u_BwNI|cA44E-So1W(*2NegyS-LmYLEC zVVl^dJcju7QYqL=EB^^i!N}evd(5I|i&dx9&Yq?z_=47V3kVl=ol8x`Kydpsy6rT_ zN=&XZY+n7)qBbW@M1Cj^8Tf5tVMAabhKM!c?s}b5SchAaHVFD{MuG7ZV*&-*o4%ii zn({ARz#(us!L3|(Oq8);o#0Me7W;4U3WU-eX{=i zcqia+oO$i}km@7g1qbN`sAfF8(U z6;4TGm^>&G%01FF$JctSFe;S21bss}k(>>C5vxDCE&53(IR?L|*%Exj(x+)1F!x40 z1~V8oR*#R^Qs5Uu23J7!=IJa)s4l^D@~j>zo#9P17@FYwZ7@C!@v>QaQZ9P5NPt5j z%~$QG8e-tPhM~;V{=}>_T`X+u&6_hqg&#J4*wO=zgh<4_9#3O}rt)5P9wu?U-%q}? zP33pA@5sR?a~SkZQ}T=*@n(5LUH2MH4&O^_=HeZRdHU>MCZC=U24gvJ4gp%szU$EF z2wn1^vDHTc`N9Hjal5rH#h1#s?Y`0+jQCmI8lbb3Y}h}o8#!@nC!;|Y_|(00Ho z8OW$9Wd~lbzgOhyPZiI->51?NvwlF7i1X==7msnE&amg@un=4k2=LAXc~S1Aq)K1v ztx5_nbnNsJHybb9$ak4m4D#i7;boPX_LX*^@xiu4j0@O^N{Btmy3YRmP}1>28g*S4 z#-U#hN*w9J<|F#b2TBM{dShCq+u2h?y!7)p2l(1}JWaNiv-~?S>ccCUwgykyR|p$NFKVg z*N!yFBnbNT4)9Zgx=*&yr-4bS0QXhjWNWAut-PG#nj{|FBMKgm-96SA;Hab1l7 zbfg1`tV@R~{D5fsFXe&@@MHi0b#m>K47j#p6R zPua3C@l7EMO!zd}qVu6uCb+$yJ|C%qX&L>63ssopTv-_h07Z0(BjPj) z_PrIR%khTr+ZZ%6WJAmI^PTQbPbX_aW+>1){$%x6Cm=IDW>VI@!$VCj{(ziyIv00W zQ#02uq#7RzdceHFu&u*kmGg*IZ^ZYd?#WS-CdgE*?vA-(#BCXH7uc=(o{IwDHRg9* z{s_IZ27l7W>|M*ck@dA_`^qf?1~9(IZ0HcGQB~v#bd3K#8PAh<+}cyurz4%eiyX+_kKSEXNF>54ggd9@q?B3_i^xWi+9S*gRh}S%Q^>qg{l1a83^nN_6yf*D_L5 zA$?6JM(s5RJag>t_=^6seg2A9RLo zmko{qJ6BiFu^*Zk8^bZFW^CPPRKo{dXa(aO6J+{yqa z3&p9^4b6PLF6*~xIN{>2MrYaEd*bBHB=42xjZGkNe3Wy{_a-tS0#>&q2a;>m1H$KOIxB}dWK5)2l{>?_XJ<&czz(?hipo5}o~ zXGb?-OH@MRcJ*_NhrB*5wBaNCtb1+6mUfP-D}&Evby3D6dOO$p7diwBv{z-kMlQk9 ziqUjB5&05QY={u{)_HRGAXr+A5+nAa%7u@bb6I@X(gPh!Xdu^{X*h{*tW$#>IKk|CIQ&;7i&g!{=yDg|0Qt6_Ras8KXCwz`Y-b*RreP- zSb=+aG@N*let&-|=n84CX*fR1&_^IVizYT=%K!T0$^F6odBZ5Xx)66dEw*%-U_|s9 zcIUDxKkTQG?ePpDE~Vx2HV#SU%OlC+U8L(0_zTYv1ir+O}kdYsD z?WxgLk$-i>x%EM%>I*x#X8 zvd8VFJE7=O4g)Xa^1UTUq^K2Ao0S~~5W!mt7*VystGN6b8zZCy4|eDms4O-L>mjnV zyi&&s6^rl}rJ>sEg*LSFSG4`2US)*CDqE`G$qnf?&DX}u;fvE$G#PPi%PP&?-SOsy zns<)&`hF(SC5~+GZBym6yx~7fg{$KB@6lCw zdTY>hFr%|9@_MTjyWsCt1lE;_1rE(*@C$x>Gt3*TZ$^Qw>bM`A(Q@s~>$STK3WIS+ zx~vJPcm$CTHdV|${xH)^R*+MSyM_|+^ySE6!@qNvR&e6#F$${rxlMjf`_!6Ei@a(hNlBC6Fezt1@0zCv5 zuugr)TtWIep&{^z8RE(KeLzA6q-H|S000hA2WCRsMfa!w0+$M+wO4=VVE$X2CvQ^; z=3JvI1gsb;uM`C0{;`AB6ayieLjShqGi`u_{m*Vx{`m>sjylqVLr5$fS_MU^>(b!&()fi2#8bC)Sb zhrYPcSC(D}o|iaW+JLDrXfr=E4vRth^fh(vV{{2(^=a ze65vgJNkIvsPIJ2K%r<5M^g4r8BvoI0aX;?9Wn4VnzOhL`tHxICRX(lP156EZ)*m$ zj3yEWw`Sk_SL%jl4pi$me;!`%uhtkHLcLe*8|^1R?K0cGbsgC1MMVw8Zm8V7=ju9d z0_PFi&w6C1xwazH==4#9zY8wL$HSldoRw81Oo_0)x@tPCB}li)w#gMT)6`*}=VE7H z!6o0$?m=oZ=pz4y(p!-0-N@ImiMcRET9lcKl{>8Q5@znM7{fX0u*Adw|* z8cX^U%X75YRC3`RRnW2)H6)*GLb_FYVxxJzX;cZ8L8!;;m3hvrs&JCmQookjGLVfy zDxh24Ik6ngbPhMmO_N=i2LdmX3BV`BZ9F62SMgBj51x2@3CUL_9-~nSfz(5YrUY(QwKkRO||36BieJA>!sy z(iH@UfC%3a?yP`=iDO0VJs%-SCgzuguk+6X(UwD`$$%{YeQNs>o?BBG$tMiV0jQx0-Wo+R*ai`=Dpv z4|xNwZju7eFB(p5i1YzbhRng+Xo5O4G5)e&qM;Syd)Is&gCO0*qdCaLKQR$*nnIrj z`qKJhJSc4J(&(+w?^TM>Bf-%S%&&M77+Toq*3N1dzLUY2qC766u9MuPOdmv;y+x5z zNv4rpvs1#HF0p5KvIB`B3!_w%XkoiZ1w{*d?`S?{-%m?l)qZt)|LOI&)lkzvy5%9~ z=np^VrlavY#G#i>R%#U}@&PK18Q!q;=mrz z{e{RTEI_V`n5#&P0Mg^X@l3U35g`Q*BBU0;+EDLjR=CQ)#7VOVxgm`1!bQvB^KIid zhY8yMxWK}XCURr0)t+-WYMMzie?b{wh{yTYG&=adGL7;_pn%%0d)Ss-_K{o_dqjd& zuyf+ulDI1D7GVq8yX5b&D_de3KX}C`E9R_u>gvyT{N!SzoDqmo=Ly{QVMnVm(%m|9 zjQwozhbL^jWcC$%`(ER_!FqsB5HuPHb&aB)y$BpMsb-WVf?#8NDq?g)E5VB9^eHg5 zT^naK6n>dG+eu7v?i1XOXTNb)?sxx5MMuh-80jS#Ppq{O%8ieLs z%$K2M#v8VoU)eF{aKQ{KFF`0L8d{oQTet6kG$lj;dtc$Of1o1}>J0A16<5?JNMLeC z9iKMb!i6ZVuRIY5$ElWTo2EcYuzmNB_mC)#{_MxZa{69VjfM5Jo!@xmjv#5#=O`pe}7C0UjJuoR$O&+O~}m+oUNV12?229mYq{LW~oio zUqqthNA-G*rFcjJ`#kvX_PnLmXMuOZ*S5M5s*Rj~z%cDkMGKlN_$@9(nTYb_9TroQ9Vh zI*OF#v3~NA74KVI-vK_5{StP66>pMgZ~cXvM_zSXh2lc?koznDUh$rA_KwducTg`h zmWJPIY9SJXyf4QI6|TROeiSJ^ox6CZbPG>`I!q{_$R#Xjpz-bNxWqsp-87Yrk+h(_ zYLz1J9;PFqJva-gqR6-1>5NueM>}z7>p4IJBt4z(chl&vuv4;*NKg1RT~H|UdMT<= zd~mS1Njt8n`0WFo=YllcRTmiZbkQCC?6K|qq*4UEhj&xKzMQJs=5jxwY0 zj7Y#3^ROU7+5H@>5MtP+d#kFNn_>!ybyo0Za&Lr2^Elzdew$dj#wf*``ub*UzuCD7 zBp2u7zTWR!vaMf&_Dt=oR`D;x($hK_e7uu$xu1Lh#FpQ0Mb$;=->0R$d`HAQKq(ej zC?ubX9&_}BDQC};M@?+z=L3JxEaU5J0!b`1?PKa<72285sG4BV6v4+WlI4VsyXpEq z(W;U-b|Ru@PH^uiFn@lf%ZOL4fZ3WUQ`k&?P-HC5&-o!%5y3b3c(+YuJvP4MN`c6k zpyWvD&DXUuaqp&?>!3c0hu&TyKA{|V%sB&Ad(8ahE%}irM7$6n`_Q&Wl|GH-`I32P zQG5l*>(Jh=Vm08A?+LH{(xx4LnXW4PP^r41x_@u)%A-JK$pc&GRyyETl$)CdFfv`C z-JHy6112jgA%EwKe<)D=bI=Z$f#Q=TRGy}QNod!G*$R+jg2>AO(8|ee2SPL3d4M(b z-_VT96sFGq=}iE9>@NTxJHzvQrT%Kb>0cka%)gLS|G$GITNKa>ie%)cNbCnG7Kll( zaAztPom#opsF-j}+Pb;FDek%k-Kdy1iH`;O2Cu`sHYo}nlrN|Q7n7WW|F8j_aTEFb z9CMhQ?AX#$4?DL+9z>2dM=)r7e@Cgx3l)#4&-ym1L)H0ve9(zyg3)SmsIfKb-MET= z`kv>}z5eW+QIMUCqm54$OH%IXQkD@=x_hz~(b_5^Dr%T*4H36ogGBIU#O|725Ufmo zJMJ$h(nD<`J`RCt7HS6eD<3kI`-U&8UpH5rHRx&wTStnR(if4nKg}I+A}yBfRI$iN)Dm9nQn;UT>xuGBiU}lNp;n;u(W8mBxMJC(t*~wfuB?N zbQ|5^l$}WJ<}eRPX@3jZZ3xv6WD<2jp)d`0!Q>M0^zNcmi&pgaM#MG*u%|!yr-U^Y z$v)nBek4{XBSvG=q)vpC6?uID=+1juX0zK^qF;50hB^*;>-Pvi@5BBj;$`QH-}uuU zqcb0TeefEiq9>J+On16|ut?Xzg%c@XW93o2^?NUB%|Pru5LP5NTaM>s<3UVp8dzS( z%B&|qFhQ3nbU|f3=e|$K+jaexl{|d}_S5{nY-PcF_x#Fwg^hcok_hkh`~D12J>H4k=v)IO zDl7%+sSQZ4NDA>JZY>=jhp!faTkoJ<{o5b3LLw;0i1JU&(h3#8(DIi{{rxk)dP@nN z7$~Q6GXRpm1)n~xKWohXTEL{lO+^hD;omU+w-H{=<9!L%zgge^2t1XQZr-ZY-X+=O zZ6ja8-MWFgfa(6h27tmntI8jF${bow;Fr9%Ny{oK$Qaf7QBTHSK5IQW|66msaJOV2 z0a1(VDp1{k?~fN|k&|CaY+A7TJNC^vTAcZxZYFwduzTWH^n>b1XVfgFdJ8Zap&6>w zQl$ZF4HsX>-r}MkJ1UdAA}vM6=qqrW68r@Av4+GsGLdo{;wK={cAoC++)i3Rx4ni~ z`-+g<|CrU%!AKTUGpGta$skt*qtO<<)vpzGgo~eq(J`emAN@}fN<%Mn*&kwL7ZS+Fs_0#VOGDScYyPgmUY|U4FrJ9VsaRnS8k>26+FK~V3 z)fx{*rtze^(S^wO@>2S8Y`t{xx#czZO{u-m6-4JoVS^bU7DrJmc&q2aKR;5Jv$G6p91LfNuW(F|z8B(3cQmSe?+4JRbahB2 zR?IEDuuxq1svD~zMS9R{dGa_V70GzXeLQ5u-~^Xwac?mi9lPM_)D}xQ@9~Ub3BcKt zDdQtY$EZa;Tic|XKPw zRi#3)Kb;Iy!hWi{ie!K4Y5n7i)!fqDX6=~U?;Si)f+YhHi&$v}Z8;241G^-Qc*@Uq zU4TKvY-{?3w+~&y5O5XaK&q{VIQ3GP8->Jy6c4okru7hgJn8Gu*_%Zj^Kfr_EJ=={J4x7Y z?Pvv7;)a`?J;7@|0}1I-vav9z1R&K3o8xh^-phf0L!kNdLZ2XWr{k=IB!k>Y+|Gqm zd&B&DE2()ZN$_aT@DlpBPY96Ga3aOU;P<~5nDg*t=xeEA{f9%Lo~7Jv`GFE7 zDEyP%nP1nBomTp|2NCgG3e~vtsd3&f+YS^Kvhwrr)7oE-&x~)7AAz%+0&ye)?mlbC z^2_7f%yYZPKn~_%HL^BF^B>4z4H%Qg0w6~_KQfKxXPX9qGyBa6{cz8kFShnG>Hum` z+r`HJT}zHlyK7zgA9WcRcwPYmPt3ET9HaNW@*l-VLPMNr3`M?u*+uVvrT72?SKJ2} z_x%N*bS`Hw9+Se;>BtlKsVn=5;TGX8!NDQi^ml{nCcO7;pX0`Pe6FsV^6LH%vaa+2 z4t+RAD?uj?MQsuH}1oseZZ$}YLVP;_INkOpJw zZPcimwC5K)lB`g4bLA@<-w`CS;rs@eSsY!!!S=gpbD2xjMV_!5f-2(9jhbuQJ46i1 zKd_|9!$1R@FMx14yO2G75=g+udMWizlK0ZQH&o%Z{ia-;K6kZsPmP!G%bK`YcH^O=za$!Bg|p*3(nr`$7k}a}obqoHY->_3 z^m2a65#ZwzivDl|7dN-DffJ{wa<))5WsT^0s3wI1_mi&5AFPl4fm9m#wy3Ly$q&-2Rklsn1rt|;>j~bLB`;9%QNZc7!vO2QK^YkT>9Yjy zRFM2t)ekRNe>;pD1Ngq8J`Ud5Xef)RpC72_6#W*VnL|J%(pH}=3m-bFNWqN>Po$_3 z{=RqgX>qA>Ckt0-gsH&*E%cDXmCc00sL1cUNl2tG#O+u^X(@!WJg)DY(^ zBKaM_6cmSV)~wg#-H6C$k>}!yC^Oi3abRa_*&KLc4(;b=%nTWb6m2_t$?gXpr#s-A zO%zRiu_3AQ)I-tgTpq8=j91lE7reM=Cykh(V0E4KIu`Gb63!ub+(j}}H01olB2O9X zlBC?QEUkr^pB-F?RM&Nl*qw_naJ$iFq3NS28cadH|7-I4w?$IVsl0HCeopDXx7$HJ zjDOEN{@G;D*}wmZnr?29atderT4jl79h}28D7HKoWVBAuE5X zLlf=z$C%{2*Q}7}wb@xD&Ic0GR+b<=G|6X(UvsAw;4*h`uoO7X0kE*--G?G8ho;h`bXy$jq0y@=2s&GpsbNt(@rS`zH?d6W+ ze)>~8yO_jgNWJ ziHQ*4zS8;CMGft~w0#=tcq!NoagZuP-%2%=2ygVFoO#IH&JF7|3f~+@ORGrqdf!(L z0fC=_?31>7>@3K^7?}y~@SSJ`X}75`PSz2Q>(eYP0jn>f3K^9%M5B|9{m>RgU>z4= zcDMz2QA?IuHN*`+Hrz(DDndUn3(X^;I8Sdpmzl z(2Y(_^vrY#6zL=0M@ZZ%3c`h?(JatG6uKb8eV)tk@+#{ZN|Jw+AlFOyeKc7fsKaM| zAI%C5&0Qrn)8yXU(S4p%ePvoyT~!w z#Mvk3(>Gl)u9b)s+5OBq)N05dhdNP8S9~I~a)UZrSzei^IvZsAu7Ar}xbH@kn9oX{ zh@0kWnjM**GKW%}H{aac4zxE|L$H4!&TD7tVoqAtKOMAI?g`4f;<$D5 zGdysqWO+|EaW7h&M!rKpLLyC@)Ob*6{P0KT1Tg%Vnwv|Ji0I$a&xt$fN8{Z@}nO>o>qYH9WW5(0r#}`2$}zjhW%ye(Xm1QD};B~ z3j5b8>#rsH>fI-LYJY-f1&E;bt?@s&7xML=71;lNAX>!-`>t*3R5kENmry75Z=Mx5 zk#+Sf`sMSVou<=kQ-|pTkf6(@I_d?U=6oawGE7tm0GlJVjMUef`*^bK z4YIYyWM4~@o~Z$icgp(qzw4q2b{4K70tpVb_7tCAISI>#g^$h6A&p!$BEiIRfa=jQ(`Zz2P(8^6?1nmo-WfJ=!!fn;AwD}p(OsSu z_t6)MBNGV&tXacXK%re%KXTr-&D-zUBZvdT6z686MvJmwa9c=%#BD_2tut;WsUiE& zQ+6vK#z*Gn;k&k9$!u2x-+ukR`eWw}Ut@*Uq zBpzSnr5Fx@JN6r5LRX7rWm$jz z>}Ty}9ezu~=F!T$Ic@c6_c8!yXt#g)SeFO`q0cWGrU@cH_2f8L>Ca z=}-O~GBu$J6fL!Oub8-5!f#(UeT@RaeBe>dK|^zuJ}bH?K@;s)@g%y8hgbQA~|oAiDhlyuHf?^ zYCoF&9JO+D8yi?+Vw+huycJn$Ac)D)qx_aNWhM~t3V#{Nqh)a_Fn-hWq5J|aBb7v! zldR`(nD&d#^zq))J>RkMeP*^qM$+7{k{HY`?CfLQdY>eG2azqx0KI%bpW_SynK>Lz zK|l+<)(R=Y7_4ZJJ;W0V-rLmzX|0Ipi1UF-P=kWc7sK=I zAv;D)BB$pJIX5mt**1>`XWMCFGxv>KBRl~WH)j)9WU4;*hm1KC56z`TSxUI7aGJm) zPSnMpzb{~tTKjA}{uc55-SexNjDJ03Sq1g|>op*GEi6z^VS7DuK7)N0LD*nxt@v2**b(e2Nkfn@u zWNk{vsC#+~nW*+fo?7R(t#7GWWQr;(=713}(v#%G)4;@V?{fGOGjH1gyaJJr{vdqo zeb*h^R@ELaO%<7&h~-oO#4YdJF{Ar>K4+otOzA24W0&DrU01>O&DPeNnxWtlr!>7x z5O9DDP3+>F-iX*9*{*ky-?EE7o*Z>74abR>gs#u=2LHU!BhA_-q{!a>N?gx2S$5uY z-PUS3I#lLY8H=~7$<0Q}&l6v8 z3b%)SQ7KM#c2Pu=R_WW5=8Rkr7yD{8yi#J7)sb4Wz1pC*pUilC|HWX$#?w(!>6|9N z_=`Jxz!~SaO}m1RaSdiVj69x7_~z@|9PEOz-dx~H!r&RyC^5)&3sQ(U3!x8eSiOXI zq??WDPi>M8r`&PxkiJ;V2lZ?VY96TuZ`O~ zHOA!bT~QqCS7qO`$?kqqk**>dFvvS0T!es;w^r-%r4xQ*Fe7!W3r67`ze|ml!x67C z2EzgNn<3h~A1f+!VJ)#jSN4qEXz_8^hi z(J)`@4_+XOM&RcwugH>H=Mn~EUl@4^z6Z`_k+I5;S)2NqOZ8qU^SKoq z{W(Y>a|Pq5COkq=^V}u=L5jA2P^c|rn^HuL4=hZRd%^h(Pgx8(#31wnorJbK_Q_b7 zMVmsoEKxXa0CfJvp^wMtF=TQ6q@(|ZMyzT+zHG<<=CN7tRs)a80ld{pxEK1~ zJ+nzGb`WtSa6A{WjLqa7ihQ9DB+u_`T>pCgY5S?iza(^bmn%X#A8?dWq$sb2F7C>+ zQIx;iiU#gg@W~*;&`H+&82?Zx{5U%|Cs}CFAt!oj+H!n<20rz$rmLzrsx|et)~KA> z4DUfkq&zx0%2#v9Ih=Aln?`fWubloPPvg_gB9uhhJ=%|>o=QUdb%ZiYJ`zPpD^|vQ zO>%Lg0rR^hIkUV2>5mYJPr4K@U)Ko{;G@hF``E#bb7}vnB?4qLNP(3^@S_1bHa0c^ z0SRP1EdH#w8dHP{eIX*myBwMBg%tA_=@Lze@A~0GO+qWvy@5$D|8Tdg4j1oG9}Lf7Oxtg+@tq zSykT}Y-S2ut0!^0l=PD#t3Q`dC`R`id0|w17zTqbW@J@_IQyA>$POW1jKUH#4ohHT z0~CQ{7zSx!R>*u}m=dLcyp^4(c(JLQ+%0Af(PV9@?!#H&%=ykARwBK^JcRKQobPia@L^$N$;5%gucMH&j=CIpG2`WEhLNVi zsnJPhKHsc&BFT;vJ7_P#WMbS(w$9q;>rceh3Fv-Z4zhHP6ZaSfiPDZF3T*Y4SQsLO zkD`XJ3W+bEbTII!Muw`smc?8XoVBLJJ5`%omT)u0i|z4h@X_zT;ZgiR#g83Fg=f0L zi$yCKAjykluq;n>3%l;Vb<`@zC+Z9;>nO1Z`BJeNF`HV8mfX)!~2I! zHaz@fulf0(1&zU(`$BvKH&bqs9&R|Bv5;_(TxK*2NELaATV^t?u4#1eLH$~ z(A5O?QFt7l;Vry^dN&a2IZ(>UnO6ZjgS5I8Tk836p;O)32B~a%y`hycoPUzSpBo<& zYxedn!B5Qrev)t`%RWrE{C79-$D7M1o~X65xYfGAY0n7aM0c#LEPdT>@_X_pvd`AA z+klEtsK*E6K+ilOfTAJF$?Z3HW^v*^NJc`n;r7gwX9sZhLY0xW`+YeV%$GPTp%h_xADWgi`Zz zogLEUZxV9U%gx?9VGRxro(lH@VlxfkxJYXwhk^D^rLXWrBaCjQbI9h+#=aP!b^Jw3 z7}%^MbH*TasvAVPCe+nzmXY%zYcJb~+z=*pk>(_MM6E@yONk|FMl z>qhDOsF%Mv$U~^F)E?&D8sl9~<)=ie;kd|8G3qD{fiZnGnbmUD&P!F!&5a#IzNLZ*Py5_)4WU&-elbG5l-nlx+Hxv_Xfu&H zYL#7AMBn4o#ClCySA+K0Dg8yoXg<&t=OR?@Qj@s75tZJ0nQd;rk6@npfe2i+wA$hV zF-iW7R4~?+AW49pTo8sKMiPvVl;1;zTTW{be7&z!7$fVCKb2`WdD{H$5O0%+TBiyXpIo zvCWUvJ&@UGM*?N~P(UrWwY4>IaL}2)%2LF*_4ZK`#w0angv%j45Sy?M$gh>qwxZI^-=8p28oB+n^a;HD^dJ`as+P(|qGm3Ef3>CV#A613 zc^;iUdGMeU=Q4NsI(8Wf9DE@K^0;;LK9$>3>smoqk|4O~ki&TIyDxKp$-0$BpEKN+z?+8-cck~5} zJl?MV>W>$|^~9eaEB80D$%)wW1UweUC)B9`uP#M`fuAVL+8Sw&rya`nsGL#|QU@k4 z-n_o^?E*W<^#+|-WTpQ_=@n0K=$F!|?;v4AorO9ign@9lk*;6Aa2_u)9x%7IEyw2P zL&g%--g^5avhA-=?=x@V>o^^jT;&J6B^vq?9d?wXUS#fpva5)E;f|ZZHtiv>DUQnx^bO;tRDQ*?4gFLDPGXoq+ z=V39lSuqATf28od;%#!(tXjXboI9C$M>k^JC6XEO59#-717vE|2HuDodwK9 zs^yx33q@!dOpZ-%6!^}(wzmioLf*8Q-G9cxuX=?2PnpEx&a6hv4yTn0)ES)IS@-c( z&k!5J;84Hb37Q^D3nTHpknyh%d{q+lmNW7}5-XXtJ@{smcnvRB73btFUP%_1Cs`f)+nz!0>sz8+9l0Q5e-pGHca%+Z>MEE@f2G^y)817hESyi{Sv3g@* zpqbh}&z~aixDg4k-xZbeWHzFODq&^@3Oy-RWdTzgKULWP@kozu-kAUjGG-pn@J1VS zU|)fm2$vv(z2+f@#9}qHn8}Z~%0nY#^o?UD4om_gq8*=|LR~%J@sFTc17Z!&wP`n+5b#bK3g5ZRLgGnR~U|`L#Tavd^9;>}F?(Rd_ zTlQpM;#nAk*z|wH#=)$LJ8|DHm<{iKFF!n(N3@Cu$)lTfs2sX^4P3Bj-Rtg#TXdLQ zg(B#Y2@4L%nIE@&6+dPEffd^e7@j?~oFe0UNSsu+y-j{NL-O#gJQ=)AKrWZRI`iC8!%A3xSsFsC9 z{73>vo$GxR!#5LTN=Uu9N~$|E_vm?5Z7t;q&{a+|-C$HS@qTQn&1jaRriYw=nwe~! z&w59pM~%U5y?07yHO%@NdWO%DFbM4Sa0g%8%>G{Js=WW*4&81)rl!|=HBMIfCV34+ z-IXs-J8^Z<^tykbLgf+yDDpGMc-$>`rMY@d-deXWUtjl$#g*z*zFL*kha9Qdl-9`s zkf9mmqZPRPf#YWAB6j&=el6q5J1fb#1(2rvY5p6W$YcJIr2uI1Xaj~VVfsK;FQb2C zt0JIC!OD+k9fsQX3YOKO39Co=UR*Tu*6bE%JoJcL$cuL@c{6H5D-WZeu!` z(|;aJNl)*q)ptn|yyK=F5sswIqt_O`W`R|Z&BF>B$hYqgJP#d_ih~XoP$P*S9UdaX z2nuje+FvQdjA4I&dE8%6kn&?9GljjbA&7WZI|I5KIusJ`TwulbVZ)yCg%hNL#+Jc; zQ;8e}CAz`uLdmvrNxIg6J&>6+bxfLe0w_iXvQY~W(VCnuRe9#gqk9uy6>PM)@~M1H z0>~hJDusyJDB!_nX02TDcsh83uf*+4QV|JxP{&njO5~&TtN6kMUYpN`GBz#Bbyjw_ zAUR?mzbspxPwG7FBtiBOx*kyRCBz@j>{+|dfaXJL&hFqom1;SqTpGHW>V#u&%pf?!$yyExfp-OYt+g@s~rJXZK`B z@LV|%e>lKweelpfq8_ndy%Ngb=>v*+N~w0Z`hrvi0yJJF0 z0b-3iF`qYjJn7ziKz%Lhc`fyOV+8Bk0m_6d7m?(lU^sSLHF%**OZi_0^%Nra@E?)z z?{3@{njQsT*lUR2t_Jz<+u8vgMWlmFd)FTVj+a+T#V#hs1KKx%+rgHD*a@Pa{|Ibl z_GXf+Cp@;jouCuR0~DR72=o}<=V|3xNzSE*&UDaa`>HQl`Cm0J`_a$%;;?p(%!}P5 ziA9RtcZmsWLjS0}ORrn48|jv)uHVk`QEqcF?LhEfF5>(9a~}-8_fLT1b698ydU$xy zFrJm+1G|z>HDTrWl%Mxc6anfGM(+ZU@BLftrXIb&nHRHJ-o=&tj{>f;EF^z$asa%! zN{-yWRdvTS+`r@~@{8+wiq@?W@{7drOMw4DALw&#&bq$6e{8vNJsC!SLuaA zjglXM$)SBntVG+U>qM+Dmc)76A|Uw@Jggl{xP9INqQH`Fo~~Tp2)i7eb!O$O%bRo^ zr<+;_^Y$v1iouH4Mep#i9ohN00~1#%feMQ#Y>^;q(4WPI^NO+ z&I{mx(%$r*!%KMo`$4g=X#8QI*a$exyk`V^*FzPx`NEU7E;?Ga#u0P~mCud$9S^mW(i^%D}0 z$Mls}=v5%hqN`jy!f1sw_d3^3x*La8dQY_oJsyP~WFj7pBF-gc+Z6mAq3Xdj{Gcm% z8GU?y+qvbCn^(BEq09ri6_#he+yu947X;3VhSo7yn?#|cq(@So&2&5=s-w)Z_TVX= zfHmGh8}eOZ-bkC8I$`lu7$^5-H+W)cBqcdgVXe>l|BBs^hcuV;Y)-6#%oeb z$3fflv-ZtOFdV<)D*Tywl+mnzRdx(+rNr@K!xRel2;;r8Fb(S)M9CKOE{nH40(~;3-#2x!fdweacgy2ihUCH8 z{Gfv$CmuNRBJ`>XoIqX+@Fpq*{*Tp_*~;4or&u=zvk&p0EF>q!qxE(tx$qUX67 ztMQLJ@ni!$UVU1-vTwvWX+|^3%Qy_T0|UeHTnO+P2j(9!xKQZu_t8o;y-%#{dw!_ zNwVc=;QcK}>v@;`rEGtLDro$@Xd^Mx1B9h6`uD`o8$5p;0If`?xC55_Z~(;dDOdiT z2#88QutdI!0UN(#*+9K=#_MA7a*7rrnMQT22;a+Tmiu!Rzt0gO!hAfV;V@rsrm4#MJ=@V=>ricpODRyVMzvUXU3k6erC z-Zs}Xh9w){Guf80QD-j)t%qVd&FYhvxROZ0KCI9>2{sgIFgQ`rioX^YPEq)HZQN_TmvMvNIQ;-(F)pPOp{KT(0=@@UK`|(hFJAO)~`( z-8wr54}2ZqDiLrz;W{_rUV4G%7NKu6nN(6RscYpJSjNGlG7v-S*B~t7+!D9Y#5;nB ztaUk)xrQnP_BOY@t&mXLxe-iN=Fe4iO<{$bFF{Fty|NslqO9h!DVc(iHMKB5;g|4d zJRalt!A&(!p<753*ib-f$1kc~Tr>n_)y#?B@C8{&UiuCnE|CGftun^2OOh~Ncr3F^ zOIY$V;Cp6i=;hlQ0YVSS=~`>89Mig?xYVHj^cP)ra@R0n4k0JBO|Tl5LQ)9RC9M-f z3&YXFFAx1Cyoaynv*%OqkL;-foo;zoxTB3R3-|(s-Kv#W@Z##xx74XA0KBT$?`Yxa z-KVuL(3PPHuB~-5Xmlq0Y>mss#RaybNn-E>50ICWW7+kpZ>Ldm{Om*pkvQ~4n!nUT zI2$AB3MM)P1_K?lUq5fDX3&r}So}7Hk)w2GZ5&-9W6PBjmVUitB`jFd2ba`9;UrGv zWA@&_URYvjRR%WobrQI`BbeFaq`G3{B^E<3S}HZaQ1&5logX-t5U~V`j#>a_VYl;#^6Z5DGcFIYZ@q4iy>tiFJ|*G~i! zR$n&-v65wkz7YW93{I=fWCdAKVDLE+`9Fe9ks+vUdn5TLQ1|qr{%FGSZed$A9N<7e z4&~+bFApN`hwIBRyhxv?yJfbj-OkQn-`Ut4>u_1D|XUg_3{Q=(DanAD~ z!;|4X`fBgyNC%)p%azWz!q1TS3HZv*yqw%KIV$@<$q~8(go1+ka4gtq0&NkC-rd(1 zr~S_15$&<)>7*Vr_W2-(IO`0X|`g4vgwSZPn^DXD*}{<0p3C*} zXxzlny^u~zPAwA`_m9()p)#-uS#jqi7@+T6u8l`B6>K4m=`+=BO)-`C*YRs>J#>zH zTWFv@;sr!fu}WsPe52A1Ifx_n&hCL+MF1pq z2?W}?Ly%jMO*%$uZYJTQuE1eHTti8Z`%c>6N$zZmkumV*ZBTxFO>4*|aNflZ z*!{@AIsprQtzPVvSqj`;*dHSA+;cXn?%_=kC0|}%#@Ed{`J`L~S=jU=!M2tT_a1&~ zYZGm(tTO(z2J0Kcp<=by)@J0C!G?ouN9P0nG5JxIo6@&!?i0p@G6cQj1}czsV0y36 z9GnjKqnx;b@F?V3)O~leI3}4hkNl+OPMVM5ymrk zY&ytbVWuSV2*q`ncpch#0#1$IyOTIg2>>=;ozw8jbfHRC40v)4?gwc&G6Y0KK={$B zAP2PF2b`QWn&||=?kg>Ry)95?!RhTsQ|roS=G^GcsO?Xg-M0a8fENVwk>V4hJT`=SCKc zxE$>YQws~MT3JFRvCzx|@E1J3>KZNChR@QBqA+xyBwGh={&XTWzDSNMi4IaNX6TVa zoYcp^?Xo|Y=m7oL@S2R&O9O*!Sy#O@Y@zqO(AHQ!jU;F{|BRuv$r^x1UlTyvv58gX z(Njea2BPsU^GVyYXO3}|4rNI44%;tLOdOZahzCj=cYEf^zm*_>(b*L4<3b?XRUrDQ&asX900VE7a{P7NUnz>eH(4h8h zjQwgPgh2?o{dCyJNU<=@K_zn^_n&59-+_#Z0f@{Z{>Z0nLO zRbmZaTT<#q!Nalk!$0E?R}Pppw(XEyql%_r?FG;1Zu{6a<5^BJzBu* zv2~k>)dITbW45{P0Wv#G5Wyoxgq(UQZs)-^$5ap!2?%1hEug5Q)+_e2_dKLD6msvx z)h`1Io2gv6nP^3Yg(GC?p92-|A}~uhRp{eKwpQ%g4|dyS4C3)h67!#2i}Sfhp+XR8 zhnr_oz37-kzl6e@adtO&EFFvnfP(bExfgU?G=%Jbqw4ao=_dWIT{^)fecks?UD9}&Q;lm@G#Tf0%5*+;tuE;;c2=GR z@Pb!a92R<;wguaAu$2*me$S@H3vDAVI8fK9?0i}jb=$f#8**e@5J6S+LsPCza~mYW z^kR8?S!psSJy>RL!4rk+v;QHO-YuA_xr^fRMk6=4)WN8ytchZqW(2S#F>{T90yV~a zZeCMgXQGflBe5=84dp?rd*_H3)Kee2eL8X;0*PYw86fw9`vX(CNHp&{kM;w!y4Y?^ zf+Wiy-g+%VBJ7ta=D&R@O2j{6kW|vjS33FA`rx4`1fET4)V}W`BnG3yc^X$}abU`h z(hzr;u3?V66`gJ^XaC}OTJ*N*Yd&5p3a zlBBY}J;LO^&M#K=am)(vSq=#W>yuKGOTCu5(L5VbZvis{IAUh@FP7$sULEqSecY2uZsbalX+=t_hBpLt$&RNNlIoeE;`kSQj6y)7F z<_1=#7R#Gx1sy;tqgkpN|N1XMUJMYZ9*%3LUoJgOtPar9ncfrh*#^vxFwxHuPZE{R ze@RpdfH`OxP4d!6x;J(&QijXyNb5yN{F<5fJ_Akv@}WTgfIJruU$iVeM~+3Ie$V{8 z2(gZKRgH;MvpbyCXdABMw(LqUg=+5j8FC(DE$bNH(xL&KaEDNfC|%Rx%{=*wB%T|W zdq`Z8$|V}oVKYj?fonknJHRD5y)Am#=Jbj35b}n&-L@6<>pYECb$Z9_&brj@k*h-%gZe;ZvKGycy30`4;mE^0-Bh<_=5w& z26t+b7=i+Kp#7$@wl#X?y3H?)sT-w$^X<4bUV#HGbySb7$Ha8=Ox#5+l03f;9O;|yi+Jz1A!x60Al$7osdRYFl=Vg-aWqo8By0YaKJzT zOuevkp^`cDne0|=kSHqd9J9+CZIg40Q3{+okinqA)pfVWq5zIqsbuKWO=J6k*Er=B zgMx8;JG*E&Fg+bgq&K+XJZM={jZ>)`xz}9H@srYF#zYuvLV*f52_mrRU@Y~mG6vJ? zuidI!(vMh$g%R%l?v8-Ns43Fq`j5!~iQjru$&`(?Vn7O)eCR+N#J0<45g=22!i!Wr zEuH~FPdpX5UCKXHiHw$iMVPnhT^Fve8b*~5AU=sWnbKr#XL}tAd&AOKdZ(wq0_dmr z3f#caC-lCnD>aqu+BX>P1t|R(R=@l=9YjgAYP%1VLKQd;PfQR1tN766=B_+vPca32 z^XGR@l#VudedmdkK{Z#2GyXSK47^_2#a^pa;QddNkd)152OUW%a18q2=nVdC=RV@} zU6XuwemOut)12e~%^fd2A)gZrz%*@-?|R($Un`f(ydVOe0OS5IWy?iZ`N6dEo-9>& z`)1o)MaD!@GV*SKM5g1jd8VWiZEkIir#>UsHZEDE)pgU4qCG88*Af=XO z5A0T!1-`;1hWz}Lj0|}bftTqqrFA0CP4H($UTPI@<9?onGr02+_w@G@Kde69T{(|6z$M39$-}u?nH09-ss%-Hw`)ymM%svD~;lcrJbB zBq{rfC(HB3M_1oCVGEC?Fke@~1aHQT7?<`eZDpbFd~e1H@G*XQ^L+BLa(qyE9XL*n zQE?h%{FfIX;wLXDCAkz&YQSDUKE@>dLT6XIwIs_|wU(1y2mY8zF$a{;O%qDQ?piZ4 zv{#I%+PlPo$v!a%SqlT{2osZlS-WZS+ZXFCuPmWOezA*8Wc|}w&3)BztZxZawbwNvEWDPsUKO? zIJ7>hH+Z?`pTZ^^jXp89BiMahK(0P=HFXgEX3%lnz^Omgw;Y{S#1e9+7!SY89wTwL z9%~+JG9Odg7@Z~Fao+-sP_R>cW-2yxk;>WDXb(W&;m)&I>wy8%0Ti2Jb8)Gyk|Dx? zNtsPC{Fx*OSq2S4o=bF^^7`e4MVXm*&1ye@_wvR`N3uKoE1}f>vlCX6)-O@bYpH|} zxa~j38V+>cY8-YF)vk6J6me$uVR|@^Ai9v(JXFH<#LpwiJ+oLs?|;<~`j|0Cmd$o2 zW#v+#C&{SaW$%llX;pKzJ&@hie~4i0d*GmEyAN%$%I=+WNhBS#j8|dAvk%3`RtV5V zTlgdHWYyt(O>XRYO|WUHvpQp*lI2Yf)V1jvyy%fbxo?9y%DlS5{@RK51|E$WlDAgl z7z{szn*&2!U0k-RtAvT8rCh-FovJO7rAF_e!TD15`V{MjkZAnARw zN>WI%I)#S)^EV>X)7rpstcAp6j6|x^ucoq>MGOI#?0YXik_asg3{)=d(9qEMc2os$ ztnflV4RNrknEP`3MP0>OVX|?;)im~M@iz7j`u6w0GiFn~I?R7Iq@zfL)9dO#-F;Cc z$U+^?8yNP>tq}(Y2kskpM}4oZ$h>T9FjU3QzYvvyHW;^g*A zJaD_ zz8U<_`S$NYHd1Hu?=h#kaw~ao((=S_9c6t5GySu54j2GC9cUTquCHGK+>G!{%&Wd# zwRlp*yeJf&09NvU&opvDgjw7|BusWmm58szBz>uwoyA*(`&gK*`j+5HN=*sV8{@ zls^PexEdggmzV#@(S2d&VXZ4*GntgtNmrpD*?>Ll9&7tsXq*su{rOE8#q1$DLC}k( z)DUzV{iZ>98evJ&j{~zpy(bBX&?*!(>ATq_uz@Il6&6Y$elpZG{=0= z2O~$Ypt!saT~yFHsPvyh8L>Qpvo9||Y(xIKcix;4#wBj1jX52;r=Nl|k8+n>|0)#@ zF^RCg5T$4|bVOqHk0)d9I-Z`j@YgYcY^x|?-MCpX{xJ@ruBGpP7PvYRp{+jcK8y8B z#9Wo1Y5b@rmt|=0?eKiIV4`cwBYR=On{?XATeGB+8L;UgqY813Z(16QMd?1H=JKB773N_?FH}tCZ(d1sTM$kPq%a!E~VH;6VWx)SzW@UvdXg>leE1fxh!1cy^JSKU>XDTXU6!0ER#$NQ! z6gix}ZnphwZs^!^c|d#ba6jz;*nT3H!?Fs>Unu$|$ZOu_{jG%`s}OCob@z?3Z;fUr zA7P`x5lHwg!oByEx7v6|9FUfto=6{k+9be&cd1f4vDMyy!KHnD9pUtARD;s$!7d7? zy`gNf^e+dIqb|I!&R|~nT~>-5=ql~kk;jIpu3H|6@#~WZ=wkbS&`yHLv!0W8O+PRH zvRbEsj#w0FTG^~000dEcDF=LzUgl|90hUF|x&e2MC-jB=Z}bIBB$t@rfhPtE#KBN_ zpat+=z|9)$5DEY~fK><#J77UkaJz={j?n+&&?LB$hH0pyh zQ*P9AdU}dT;Ue8e>4M;bOJ6?wS=H}m@@o0$-q`!R)I?l+RwbvxC2_91TkKB0hq1Xk zw$Y0)RORw)HD<;bI4eU1adHe2n&*>}ZjOO^Pdp4)2=#on+Zy6@V61)yz6-6*9q zP?)whAzcCRN~22V9v(#Fy3&*f6zAkT;vdEVb84;{3*^%G@lxH+!{a7(3t6KW(dR`f z0W%C-7OLMyN9)mMoJfWK6Uk^UQN!Qgw6w83OnP>13BS?9)dTGftVUN)zn26kFZ5WM zJn9)4;kdZCP-E3WT6Ci~BRWN9Nt{1}QNW@SQ; zgUMMtc9yQ;ALQpE!JL2|u&EapGyyqj#XcKU8S*Btx{t%aRH$;rtWj`j89hC(lC@qf}2yv{Q|!T;19-k;B7(lml+-*DXQ7AsigL>qU# zuxRyl2{F!?kA!9AWBEHVM{PALVZWN^mt^7XKMPlW`KT3(0n(uD%je*jma^S28W1|PtLZ!lbQRR-1Vx#ip62^>M1a6-HsqF--R@a#4*WWL z6Z<(}q;9GGX#dVzS~68`f5yh!f-IBfe2BSfIYdL_Gq&|2LD zwS^`fwd@%*-0A1hJE7(1QB-xtfR)kN**fIWW}Vy?hI8_zo!)${mw&!{Avc3gr3RkO z;FQ1hj@j5F@assN$rC-_m#S#Ng^KeFA{e%T-*y=6(t9`IubyuFPWTK~YZ4WJN^J?B zlN(`u8lV%QUfKcXTM$ywznL`Khs8~2em{T>X^ zDHMltlyZ zYz^_?v1_SeyFHKXhXm09VAXBO20ngd{PHidE#mh$2rx{rHxq+OINxs{_b5vM-)hvk zpy^-sPyL(CjW*&X+a9aSO@*)C0cuq`Reezk6V7{6~_yY zH-1un<+$by3>t367>H=mhTWUf0@Dow>MY5<0TN5R!SN?B#e$lWX@lc5W!b#(dKq_8 zOY?H%W_+Ou!hW{o*VRrDj&$&Ssj0jWKBd8>kK{)=6?SOIv1h)L=P2@HcBoF6VuWey z!yoTZC^1`5%K6X1h~p(uvSKgP+{^U4A$M#XMqnzJ8bP&%(V%*0JgHH=j5RpxBTtdc z-Pkc2Q!#MU`;(T~Wi41{@aW*3si~UeGU%q`k#xb!Q|xvT69}tRsM8P9aR97bK`P5K zJv}T$J70~ZCNGiJnap0(8h+OnWwVzoJ`%~RVhO!*(M@R!nM)Tu{&w_eoYCPZW%_O} zZ3KF8@u{k{HX6`d_YV)dF4^KnU&FbYe$L@c?>RfeVk#P8SO8(n#4r#!uU;!X2&2T| zaMLL^PK&%X82GTas?2Qj!VB&l4G{2KkjIZ!4OiVYvNK_yHEPgH=San!-q2%qEjX~e zJfNI-CkQOGr0w`W_{FBku_IQxAKHnCXiJ9o9HSF{26vVlYF(!75KmD2U5{I^mE3y^SqV%{J-u3qq_?jcGW~dH>_X2;FAK~CL#g2> z8;a$N-`rNcIb5LHc`qASPd3{V-QY%jBxb}$p45%SHr09ZnlVwaSR=d-n%6O7JqWJq z=->qX$tekkAC=i2wM5?DbP+DUa~xiQ7#<0geEH48R1cvUu(b7}uq`bu5fq#1i(jr) zoM*ec>(a$PZV)Ve?}b%x92E35I#rJX%irN$f*&m7qGuK;vL=&3+~+l(rPyqF{A(m$rqbU8QPdT z)|BS=3?7Hyw#F!aLr#D3-<@xej9Xua%Ni9-h;JX!NcO&hBpn%do80ZVSGMR4s9jLr zcv;3dhmEiBhFF)NCgpJ+xS3lj3(&TW1J4oDH5`UeH~mT%@i8C{7pNiX+IYWQ{mUPI z3w;<}fkUz25@E;ag%I$?iiW-$=#;}&a1 znI?_P7TN9A-!(Gt_JhM%s!&(*1$E!-F)hcC5_D+j3z4i@0FLoqo#1lsuNxF!sNdDm z$v0I$a)AH!9wt3RDCn5nyA+(lHJiNX znMdoqoN5){zRsQ5e(?hd1vrE#JtW$GV2SzHglmg@i8(=2x7K_+O+)!}v>N!sfp0Qr zw(ssNK;}!T3!>RDDjbOEOCKc&@X9hS-g&IX@(8K)0UY6aL(2as3|m_k|EQY41Usbqv+x-_=7oB2iS_x`sxEN?HyzaBwnwb3 ztxdh1rFC!rtwqn1p#5_Eh_Hpi*6T~G=Oy@?_V>4!7_NTn>Q2A}&Oe_Nz8ZmizqN9A zXB+^)Du6qWYaz4;PthC3XcD&5k1RJ0Bd0pY; zE=L0Z()`=GQD0&pdhKf?MaKe#oE{%x5@xdeW_WXakL6aHPL7f`hbUAv*_4pQ}2&R;yXlc8FV9W$#F+mc8Rf>~QfV zBo?f6q5?LKBGP~(Obg{OFmdMg?~9*eQF3GpY?N!MG%G&X)Hz^bDx#mB(4;6>65(5 zL?+t5>7P9I{s=O`B%LuN^iZjv!c0=L{y~>%N1MtDok()X@nebR^xJ?bGUlhGw>;Mu zvd(3Wm+Zx5IAC%#yP+qDr#3Wdk9}!7qxM0I(Gnl$_q@0mU#vE7ppJ2KAm~=r50OOg z>^U>{lsgW?95W!PT5Dk`QRAe$jcbj8_7z7@1fUL((kA~1I@-A5hOjZwLsyV}Kp$V6=Rp`fxKg}*nRVVKU zg7z+d-BHXMHidrGQ4ql&*j|MjQC2mx1Y`L4v>_}z*gHUn8#sV3>*dvk$^BdJlQ$;P z{BS$hi%y%=m(9PiJr)ZVJo6due{*(3mzA;S?*t@uiT}WH2c1cEaGGJBk-O8N zdiA~$gq1RWznzzt1J->STl*Ffmz<*?RU;d1?N+BaZdZ>)?^{*$H1fJ=>1^Qe}k z1-_Zfh|8QAFX7G0v7r{~@Ar+RvImI&0+1TeUDpqNF>pXyaHwy?R9_`925l?aLIIxe zp1K^f&6Ryex?nXfF(>KC8E*jFVgeQXZ7f^-ftk5-^3TFO1DM;7@P^}=*L?CW@^96j z-q-(N_)YsroBH6>bGM}fiTZzi%G1V1aKq-k7g-B%d*j8{nhYKHu~@!WJQ!HwuU07e zXD$}>C)xaILs+8v2JGLi5cR)?UgCw3ytR$Zu8_l&m!|w@--2hA6!6;*ueZ0H+Nx-l z{LfG&*B88gVU+l`aY%AxZtt8b3GSSnpnI=e`fvhC9(}p)7S?z`=u5z}HyaqQUE@~f z`uZ=3Py57dvT%bZw})fs1i2zA(6Y@wre*W?;q^&YhuLUV(e>KE5g5c*VA7c3rj?=T?!88R$u>#TY@`eZH-&(cK?YimjIOBXwWt8BYs8ug9zB=9tDG0@yHXRGRpm? zP!q^Mir+ct>xKk&=BqS@yuc(Ox;)uY^#K(XkFIXU0BP@YUGwu8(}L6LEbGW(Onl@x zgz~sO4txQ+1TqXjPeHr?c-5=3i}T+px5@}5Y&fQoRA^eNmD+~$dR(2|wQPEl4Lfj# zU!NsjQu&{u@Ck6S-%5(3e<29mx^EqYD`L{KAO$0i{O&+x_Kd7nLu#X5Kv= z6Pl4-_2=Cj(g40>`pM63L@_}l0uQ!aTajFYVlYBOs*=1fnlH>VnvPl_CF}5vc)i%S zNEsy^ghYsnKZmj*nsal3`O~iQ4nSapZ3;8tLi7+(c<^mQW4Hk`(BR~X3Q6-Ezux$A zzwl7cp_+*duVk2-?aC7(OHW5D&R+~2KRk@}KSV0YSJ$B)wE)YxJPhlunwNe3JmD*a z@j>lUzKx?&%v>j9NRKh+4*_1LlUC`>hQx?LRuD2hc@~ZTS^qO}u0n^;WZAZK?!P7< z2wvuF$e8t$noq)=5*JvZX_|Mhq7X4V+E0HD8piJ*e<&fK;UR*bva5Rs{lU;ieJd>hB*tMqIy-pd|qP;OUb;8^> zh|3C*5)c%qY^@G#TQZV0=RiSmwwo!;r~J8Zn@z-RT@hh6W&4(Gv_0}}niBY)CWV_> zbo!r7PHGOmzb#lXSXgKTLs5)rGU7B*$se&ej)qR`fTc_>|`Ij|lQFx0ne$ zkX&_tK2zve>)YVk`ml(03|v0@_i?-}4WlUq_bEI{4>ZxA|Gm{NJOjKTmJTtSqsnxy zPsr_V+*h!;%!`Pq@*4J1r(Cg0^l$UY|Ndm(J9~8gA_9TntG|dqfbX1;KTCPYsE>gg zz-I5LeLnO;DBGfA`+=hC_?T_hvngB14+~59;U2ACh}WwLOl~u9Bay6gkhnITctzVra$9EbY(cmzHGc<9mUe zkfNd@q-OCEpa!*VBc5GpCG;!$N0etUQ7Lfuh3nv^`8oJ4Wz4nEEwc*jq;WBRRT>O*ZzW<0$_TpD!=BD#p?>BOGiwWioh&wbdjzy94@o2c zLq{P5W=eSd{%2Vs$bfKJBoN>pU>V|Lfva_vJLtT{x6oo{pnaG};vks$1DN+`UG zF3w9A&VD&VC(BM-!%4125#S;|>ObvzZfO`yh1aunA_f|W@fQm?(0cKFhPG0lg{WW_ z&JT9oD)D)5uaFl!Z%D$UyQ~z<)jv^N&)WJ2WgwsOj3X z{odcMpJHM71X9%>Z!CEn>ub=sRAoK`KTh*8cHP7AKp-a^mZksFodfj=1*1MOOt+hHg>0xjpyWmQwMV7!wHL5Ah3o7^;ldkL(| zW|*eBIv&fTbwOL}DGtUNG?5b$8~x~#F6)w=#vR7<0kr2_bD#{ z3P1MypWEdBo+xmxfRoh>$ewDRd3|t%)AKJcz-KWZ;G+1>bm-rH`iz&|2YBK~lXur$ z#z@22Z@&D6fQpZl^DnM+pKNe&>VF>*{o4)qmxlz1K=1;5XUq4b*8g>y^OX03Dsc?& z4UEc;Jv5$g3Y94xJBJGk3sG7xSS1TQYEW0{yWS)G9F>4!L8@4Q;Fq}H7eLs%^%Qd6 z)+mth<{uhzD$#9Egv}YKCKR%`iUbCuVw-aK3mB#EnA%BxfGz9RB942ffL zaWUayJSK})d<_O1y#;0#yhI%2S!G|qb0;rsBhMnUgw!gFPV80@I=O0fTtUAy=D&N11%=D7N#meFpFAm&1#n7OzbqfO^5q zArS#1;lSYQsHuywsbe}mzM2(U1R@f&K6ftH>C5?>&BUOcH8s^mw0RrffQ0zM0SOfg z_X0?NMfN+fGEvAkmYYO94Y{W^vvn=d6#b^*6yy*xp7_)3-7cl&h(tg@u9NH{-yJdh zyI2x#SJkts5FCAFL?#2KS-7>}4fIABr}?N#iUb>NTflx!c2r?6xufR z?q1c^R(7YE6Uu-fQNvYS_$!5>Rh5z@|M|^p;-L$1ldShg4aM8UMWEFw+>CzF3f3Od zGu22lS^Dti@@SfYND*Sp+d-1kY5}}7pp_kgzIcLFHX~ee)U|{&`3;NC3yl(g+9om= zvNf65W3h@KWbkK0TQG;_<@7uhwv5$${RlWz0XFpw^!=kWi&1w6Y9fg*gOsEp|k~@^b7}3}jJ0jk0 ze}?#Ech4_G)#t|Rc&NszsQ#<9dwyk0$oPZ0nCAuSRHX8{;0r}u#_`tz z$C*0D-M)p<@m1=2su!PNfC3&aH#s}U0o{9CF){ZWP%v>O&!1!F=D(3Bpbs*|4sxvI zFu4DLf=W*PCAM)XHR}W~lmSn4MwRR*Z9V#gAUQR87Bk10hGU>P;gC(L+FipCY-B-- zl4rW4aLdbjY7eL+>ViP>8pjnD(NIuPWSJ#`T(WGNjYvqDDJe#9Mg7v*2Jr)Xq0`eM z)5*($CQGt>`?UB`kqq}Cyu2w{Y0@0YNtJVROFgIaFO0$0&y+G#yFd@jk4QAv+XDp- zg&JgHTTAwo4)tN=ycd%@wRf(~<1osOvo{^V4t}=_z|>Jz^SO)Hd~&(lE7nT=Cw%$m zy<#SFSa>&ZP=VvtnBu7cHdk$x#df_7EBM`DAQ~*U8Px$4m&1;I9 zrts;eh~)qI&wuaqs(2#VX%PR*%=(nK0+=_gP5_qZB38U!^85WTBKjqMXrT*usxEec zZl5F)fyxh7@qp2BH~PSO>eV8|%O3$;OL(v`arC$rFt@hVBqy(gXy7Xg9g9`R;}?LP zw|`?Z#2?DNq>LZH6EJ0`zMBPF}l>EU!(59;R^_NDy$<`D& zhLcg^)V&LEXO|MCWJ$+Y24&}c#? zeB!wTnL_D~ncI6Z;NG(P&&%Yhre=gIe%eLJS^j%^+Qn0Gr`J~L=)~EgUO1YQlTSQq z5i>(E$Fn#6dTn#ks`VzO_RS@PO3U-}cw6>?SHWS>h~UO?k|@{H<#+)$j-gzwMFqet z7bMHJ=0^9L^&?WQBGxwx6rVYGC6z3x$4<1H+b}%UB76)5N#7)}Kq0ArUqp}-8bQx= zQu~1{O=AG2$jT>FD`_r9HGWLo6l`Kw4qQw$NmIOu z0Iv-!Njn%zM1$F#K1B_<jypTYYN|z?71B- zVg)17qI6-Dg<6$Z|^p;JHr1YiSbl% zM{i~I4vo2NyD+bLvC+Sq7LFA<$0vAj#A`6xxfTilSX-n`kNkiP84Nu~O5N>lqLx+I z;2g~J)V;F(m$ySm?^32!yc0ei$ioPY38;vYruz)^bNnc)_~m)yB5c8PA1({A4nUR} z60v;P)O8l$ybA8rKt;OnsX&>5-#y3J+ype&7A(|fveJ_D#64q@I95ePT)g5T@ws$* zQKZm@O-m;rDF36q9aQjfqoWrHZINs0?+2RGHhvkIxQpUe_I;F>m$xw5ZM}zZKF}L` zpU5HasE&J$Cr-Qt-uR_x1NsM|{O51fR>)7NDF4ajI`jH(Bm|73gc`tU@$bdzucN}^ zqnMnFE2F1z=dS!(JpRS;W6h;~Rl@sA&y@z-m0e$9w?m)Q!_+LYNJ<=5l*l_;R#z4c z$^?SvWb|mW>d~~$j9rdH>vYv-q}sGB+C)FUQ12I$q7iJd#=3;TGf0{$MxquFy=L5! z@DaZ>SgP>SIas}|X#4)%tJy1Za+1k&q$8ByO(oOFtKz)uQGd&E`oZTZW$(XH-uF&a zZOO~gO&_R43EYhlyVo57LcYq^xBcPv2J-1P%$o*u^5lCFW@1wI*|X=~y}?QGv=ncL;=_4V3_)**Rhlh?qn@Q#U{ z=c2S9(P#grr$9LtN0>w^G$M1idBN4Dnuu(gU@Aat;W?*($pSO1x3{A}$|wr(FGyoX zu*OAIipx$R+Gima4-0Nks0y$Vr)j65PyQYC5bXKQB;PaAat|wL4X%7ISHCP*qjZ>7 z$2f?~oiBDh17~374dG;=4Ys@3n`7g#@$SBfR0RoY+ja1ZBbzj+fZ%i=z zq0lr&iW+GLdAsOU7m-C7yZYP5+B(L(P88GgS183-YT? z!H$@vdrb@V0qt{7v4#iMA7PxPFZTFj5I)8zj#|1%;A;|;i!yx*Fdr@OBqKBzrXk0VLdpd$VHCZclOTRT_KvR zvFL}x4~A?5sf6GZdU?pPJE}=4o#FEFO7+VG?3da@7ToQj(+4eAfMrVNZjtjL&=9(POuA(J zIL<42FK)YMeR9bm1tu?MlOQVSkn{`As(JFLji6|?Pm-lg>S9NScLq;4U1@B2qA@Vl|<2`++pz!F?$n%>}-JP+Hn3$5f9$pCO#QjR4XA>n49}hEG*~%$#OB$xd@}!t6+&ibwd5;c)$1X4Bf05 zX<5gRe6fjaJL+l0R|ti!;Y(5m@WYuIN878j`6w%oHk|c5IOrBx5nf$?{kTo^z38D; zg6<@Go58W%+97e~8{L}C3@MzFGDR6N0z>=Y&V77MF23ebj=D!d!Ncr4_haghwGfdeLN_FTT&;hF^rc6CG(DCE zOST(?Rv~WLjJ%24H0OhV=F5H9eZ*0b%JY+q(cUWsuGHn};#Z}`bpG%=!uI_i=@J+{ zTnqz+BDsMhF$R7M2ZWTu;bNI?;m67_;n>7ExXbB5XuIqUnWBTzn^{n-9v^j-SyzE$ zu>B!>s}qc(WV-rlarBOn5(^KdbN)5*xM}dT9wu_?3_p@txP1jC=dl{w*0^mQ9&Q-g zDKe!1xwUKBaW%ZnpJzgvs8&`!uFc%We)q(m4yovNLrXTwA^rUwL1o=hl8{LJuphM5 zD5P*k?a5!@5r15aco zYHY-`b~uByS`gfikLOzJyhv87n8Ck#u2h`W3DZ<_uJZl&2VkBQ( z_aJEz6~vDbJ?63W;aqn<^*Y>5dXwzJuKrq6^t&n`(QF7NrcG|e*5^q{BtHa!YX0`DDMeYK{!Tas;98_;v+{# zQ>x7Vd@|cPoN!7>!NO-3nnH-w#{(E7s_Hy};??9TeG`RtwSXfl?o>vEFR;ZaV}e0V z#iV<)T~~VaC8iJa5(nqR9aj2$UNTD`-?@`sCCHAr;CnE844)Kcy`zOo`ob#igY_z^`%N#@7>RH z6{(wBO$be<;v;S2{c81l{zXV6CdS!I==U9R`~4jXdgh;J)Djpk#@F~&FYS>Z?we1rH$8Dz5`1ZNuqEMeTPj~+f ziZlrLIibAuxIJiT^mHM~gtGp6c)mD$M^qmLLKxuQN`GsWMmc)&rHP64>}5I$3Z-${=dIt_?Up#}@Ot*ZWc7z|%v0|A1E@*~8Uq5g`kHC1w)-xH*G>$vZ9< zyN17SDcxoz=|?!MR4`f4uy8~M8o_pzE^GZn>cR4?I=r8c#2UJOMJg(K>3BIpwSRDs zH}{b?Rz4g$$jDGU<{0@E!xZE;Vd3=3nyJM>kp9(Ikpit@Ta57TOUAe2>BG6Y-yy&1 ztg7mpW6xuhzeGL*{59h&#BiW2C1fymAQv(W`{S=Y-jgi1-a2Ditm_e7UOjp(rL#e}!Y8eY??$%=O|M1+2A^&` z>Xfc@P_^mC9lsoSCQ!A!%eIGM_OMSa(q(%UCHP3X5&1d$zG*a1>tgkNQA)p3zC)fd z&`ji$UZXWHy>^o?alqR7hn`otm+Kv#ob{(PAqi39!Hj-#Xnc^pd*F<5OGLv;bC?uE zP#uJSarTC&{xywMKRR9&A`dw%on`{g^BYOP;&ayJsq7R4e^@fDkMl}%*L7bLAo5$n zGsP_bI6<*bmJ)pYT9r&q`)cU!E5ACH$`CnzAO6UQilf6;){oMuHe(a1Lj8DtVY7KL z?^n6mA}F1Lmc+3`KP`6sQ_q68xnovE@Y7-t7h7&|z?r-j8R$F+6D=&8Fx}D_$Lk4! za^vRU^SZZsP=y|Rlzh7O+odBQ7Jj9R^C77t5J)#L>DegNc~)QoF#Gu&{=h^q@t2zB z`2Jtg^Iuf!UFXXjK?F9CEbxkb3WQ{nr~+UgSQ7r%Lx+bS&S?T*1m2J6WlFWf#L;P+})jGg|=vM zcSv!!;*dgVaVZqa#!GRB5}>#gm*7wwg4?^;XP^H)XWxB4y2EP``*(@4^EPT-x$*Zmx*y`z(i0ug(SpR3eHwq1n=u*1K^Mo3( zPbc79l6rpi0+uaR@1)!smC!`^CF%}1WZPw_HH^F0+yVmr#Pvp|!AORLXGSDs(+~Nb z;h_gnV-3~@Sup9>*KlvZ4-)qTGmG0Sb4oLLaz+zmu9ItwWC7~NasZbL>}`hK522&C z6Cj&ptC_m+Qwobue_~n(R&c{;{QDkFTLiwTaZ2b3EQmf~h)vS#5*2N-Mq?zc)~scP z?(lX32B4fu; z(1?$7#__G`Gl{mkt0VF7=UB?mDVvyJI!ba}8R2fatu~rpv4mzYe;Sr?Fgcv&ZyWA@_o|bC#qSOZPvD7bM!VQN`VEbejDRj0nd(s?(l$w&T%-0C!%?2$AX)> zP-VTU9f1Z~mr$uaAc(XT%n%k6OFsF?Mmq5taE5*?Q15!LBDg8UnHTiAn_3XZzbF^@ z0Y>ARi*wFJ+HH4ZvQblJZ0x%tLlT`xCH*_9i%h6>{R##iO$~`8vpb*GLB1?F=FRP4 zY7HQKC=Dk5c*P?_kr>G<71x&qZs*7C%IGpVywc-&fc@cejlAZCE9q@0}2gniruwQj#P zHb38jg05aDUOC*Q%lExu<12q%kpOt2!cmA$HsIye-vMCr6$xLH(^5ssvTsIt1WUl7k zE`Ts42i^=b{Gf9aD{@5*a^TSwSpq^PD;A6PgN#2dmF&rMV7`qo=F+ifC} zZD-;ot`z22MfrrQode3Jx;g-T66KR5NKM5EEqbH4w4C5)2b_uAw6xuy1FGf#>_{b+ zty2tw9PjOU!FQm9%$}jAlS6s(+p zvxG5vn)H8cXHc-W0KVZr=zu%t^b1g1~&91Tl z!2wq+Q(D9Sz-|6nHd6fOWD)vLlLZja#;T(HeQIafCg|+>R*m7;iU}=FQYaoWNVaE{ zr?G`*Hj6WTue@LsY$+JM5pJfg3R$`6B?ZL4x-Ux0JLr`Uhzriq+{sdn$KuD|nj@J} zV1`Rj;-QT&2LmEvCcLH@M-}a}6t-db*q8ppH2KGxc$S%kgNCWua&4IShJ^lSf$1@h z<0IrUwjqIOQS8!Qif|vG{cO zOPtTh>`0&#^*P#>)LN%rG9hA+#s8<^D4R^XZ|D}P2@A9SZ16W(h9bhI5NW3?aTBcP z;KDlYI_c7I1D{1ehz6VRkwu-C_~YMNfKz{~KSY)te=FnR2}=nvREnO2np@M+mGM9b zFZk6Rgo2wv)_Z=AY&v~2p5V+qOk9qq8&9LS4&P#9p41D+JlRgSut&sLbMt#3{B<@< zkMi>w-!?v0`OKBlZw`m{Z+^)^jmmdJRWiNu>1>*qmc1R^Bco}hC zl~iCkBmTuN<*T%yl=O7N26P4DjNj2d3eh!0Y@p;6ubf=k&!$j1Ma_hPpd3Ul;B9pY z3TSrUX7y}JBM)HN>}t%~INDwQ&UKm6^yCNpzG1 z9dFiqZK9^Q;_Rf@yud5Z%?={_BCD{G_?T9wPLR(SUDmRQ8u@3ePY6#Le6}m+1y?y+ zEL{svMQY5Mc`CI01p!&H{-;5s&u8YXGAJo_3^2wXmY#3c#9s+yX-`u`W4g`%Xc2ay zTOKdhUE4(aEEJ7!6dqo;0a#C=A%A#9cd&RomyvPo zR{`ZxZs9lNm~ZyL0hk6-#)SJTuOM=%+nF5La^3^oFsumB4L9nyX~X{L6>WEoH!Xz( z|2!Z_lU~$SJP?!38-IftuUr0_H2xenxKc;{8at%0YI-!k0>_RfYi^*?|DqlKBq1&c zNk(o@))gjzml{zQC4d-RR73z-YE+>8HlpB4HnUfqpHP{+JUtIjr0%UQoYC1*cz=Fj z_(s2Mr`vw!To?H|gRVuTfTdbEfe|!^rI_TBrN(zyt*{o$rl&ur2d+8-I(ilJ*S|L)!p6 zYux%7NLA`tHeuH7Ldn}$li=njAJQnkdZGUUJ7)8aPV-4iB}cMU0m-LYSUo3pi8iug zIsS1yjJQ`4aSUew9H+on{H)CRNk~*rid%4&?zQA><(>U4cJNM$y z6yL`Y+ArR&Z5EBnU$Nf$)4eyQGjF|5t=S3yZ|m4*Y?_u0N?-k8VrX8H`@Ia(TKL}g z-7ASADsz@7c=%nO?Sie~h-0QoqcC`DYHAA2oS9#}Jy4vIAx#Z_4WkILJMESw3WTdH zAKe-WvYm2i)rhNqZW!>X4G~Clza=aEB&vKpAWFCzuHa;s4NaF!g}9gTK!xUDGDV7z z!#ShirRto{cm4j%%2MwIqI*t^N~tEPL;P0DT_&-LbH3vhI!z?(dP{q*d9*MP<1yve|$@ zeQnhqOiP~5SEV3_F6{?q0P#KJ?m=tpLY5bik_2k&DSIi(h(}qM_R@QLK29qk1Yy*I1EHejQ{c^h}g^9v&oOr z(eG+WDM{LH=i1_f?uPGK)~e}$0(iAS3&}3@b2zo%EvT^tH2a2m?3{->1J4TOE7*Rm zkHU`z*_dp{aJU@@r?*~TrC`|7U*%E|F4AGp`He7Y_QbKXQU%QHtqN_L+gkw|sk1c5 z+1Nbh>)lXFN*u;ESrgFwH{_DyA1k%%$mXa84p~<}4ZlI6a1eFMU3n={D`z@GlCaL^ zLQ#1DUgI|vm(kYF5MP|v>$sz;pF*g>&q$gD`UVIIUnVtTWi|m~dsNk1%&223V@>H( z6^7vsSAK^)=`yu3jpV6hCiT=$JA|e-hU(gar>i~#=je_pFCi*`!-%g#N5wOzW-b^O z3+J9=gC2HXpZWPDK2BEl9!T1n!B8n=VdCnWU_Q!p6)0?ufF+d#aIyL!-QFo9o>+1a-i7=6 zy5pTS{c>KuSVP?t9G`mp^4Y72*Y)AUb~jhHBZARkGa`hf5RI(qV{ge4U6M0y;Z=y{$JoBuQgn!2@YBqPH>z_dNO z<6*_#Ajxf&%}g#noGaBHrLx7XNc6=V)ZiFpB*|5bm;_{3!#PT$dgTh$Sd&fO%mpeZ z<|NDSZLQc+@u)C4EHdN zfBJ59)Zc&1r`>Hed2_ua?f!hKEp4hi7*Tv>9S_eWPevNotqvT)?VRA7!lcwAEXYAE zVl|=6otf)!aJhYCUn0_sh~CsBlovE5-E3bsIG1Poxh(RpsL^kU7|x^wUZwuh7tL~d zF-!G?`5O(Dva$4K@n{yoN$XQFnqe15hFgCL-kcf%jg~lijHv=9fhi=>Ec~1R z+m|J;ChT9Wxr>at*23H`*Jjy@5uOsO7Tjt zOq|N}EC|YQ%Cm=)M;5cEph z^8Nd6|5pLdU+*}-BR^n^t_pz7s7RslIRd}|#A2xIFM_i%XedBqK}skCHg5>f8xXNL zaqoKt`-zH&&w*u!!2}IgK7cp+zZUfTozwVh>e1BwliD!(8?}*h;>ph$EA4UD>5mXp7SzFF9@Cvoii#I$sz`I| zs^Fjyj}&YW={XnM6U4{Ix2oPBI}aX~aVrUuBB z>DFoJ4N88c@xmkdLssE)!}gcj-yVBElI;bu(kn$k_Rg7U4n)SEZuvfEZY!Y1vDk_} zfji{Ris(7SA)#94urtSHFxh5&cOJHbzs!$U8OY{+DHb7wCqCeifp^!S9!xEQa*I{Y ziB#3cFCd#Lmm52BvoclN>nQa@j}GnhlJ9JWQEQ*747HHFE1V)(g*_k+W}yOM`My9q z26!)$%0v{OLY)N|-f9x2EMdq*`AbF`aVB!F`JpbR`O*yO^n<_kfJ0)?-f1NNev)St zN3*fLa+98LwOVCI}dNfQL)oS!CUyHTfYRR1Mtn_i` zX}BNSe!^#xuYqrwZ~bz83?&FceshSoVg7u6RM=EoopVC%$>Ie%PB~H;B(!{7sfeRJ zRc<@t$UkB)xa`aMY@K&!b&ED8scMUwmleZ@m&;JLKh%eASoF7Z^f1#2c0F}r* zbaI7#EzJ2p^zxEMfDFUmN5TVmDI1!54^&yy5e29P4b8RMpZDVlEjg%Nf~jp?Y;o7f>`u4mBp;j%fX0 z>k8)Etw$cyd`z%DD|-Be)Dq`aJxzx?tuyu*xH|KP#d632#x|aJFUIm4L1sgU8s^pQxIa1 z3|@)-_~4}vBo6c&uaq6>4mUj~3{kkp{KCK#&M#qzP`Q>L-0ceejNDXYK%qPvd{WNz zlWICu1wn0s+R;_R$L+3HDin&jmZqq2f6)6*Sm7^K&oPE)Ku?88d*#!)faD#VIFo>E+P9ZJZ>Yx#l4Ck3cie%3I$%JHwK* zUvY^cDK^}|^%C^QQ5X20OZ2B3OQvzdAh2$*E?p z5PjU2Y-{1>`S0-6cDLc!23fLfT1;vuOb3jvzX3Ua18_jIoQMuRlA~5U8Xel-cSBYQp>%CXXB7YG*KF9NB%{FAwf>m zt3DeWkfYyC1X(C%FxzElRozj8e>}Uv2!R zoy@agRObM-(`q3Qfk=zemk)8y76NPRK}1H8R=!0rG&f*-u$ zK|-o*X^A)D^jc~xk4BvLVR#k+`~w7vvTY9RpL(iVTK8@94GiI#rf}WgZ7UGoPD#iou^u0v`b* z3^~n=MW-&*sd8>P694d=6_*Y5$>c~g^CU?B8Cwnfdv%mU#-+|ooxGI+! zl!ssX$|91KrI?|r+9}*_>8hHCKolyuv7UUMky3FZI#(}_a*i9;xL>buxk`aeOvQ7$ zU*hCKYoEPwmre>=0AjkyuL=3)^|Mz-t?s0NVx83Wm1IU?FSwEEu&Yu)tqVQJ ztg)OL+8BwCPgYIG_bz6&=h#h1-!=^Vh4I15cv>!!4#dmkiS*LXpf&3CEcFrsP$35% z+}lU|ZI}pR+mD_&_Swik&g0#&vznfkW*$#KMi$$O5YS^I%l9Cj|bWZ7jN;QHmq)xWI}q&!*^Q*I?(mc#Wp`j@+CC z5khqq3I%i|W;HQBM!2wwdOh#Hc@mWJ$;itPsDosV5~r>#r>-J>j#8B#Nv|aCH`f47 zdvoy^RA^DCp!%Hb+8DVCR0zVDpw1wX$f7oUKFv}aa!@n(I5RW*^V}XbYExrljA}7% z;uTeTfS{;0?bCYau4P(DnLV2g_zir+Br&B2Mbf?>9GREEstvq@WKK$)d;`hX-Zd0<_zaSxiGgJ2Z*Q9C+!$c z!W6N!#ntv)MNHy)y5e5d6;dfz22~~kg15Wi(@}+rx#TN~cw9B9ErNpLTFz1$MH6K) zVX|)RM_-6{a-)p0wE}3$$%EHK<4HcJ3b=e^?S$*_=%#WLyqR?dZFL)LP8qT6`I=5@ zCR=m$jIPnkF@hT627JzPYV0Smb-FfqG{1csO;=mKu(0fu+~04BHtOq$Pc()(xCEiN zw4QMI?}CR{(;Pl=r^WG5pAmL5dWVD=NkXSoWW$1^ZN<0L2$|3!Az?3acK*nrlo(-cpGeWC8i+@NjkKp~O|N;6 zY9>w52k>8|S)hIdQpVp1(SXJ@SCp^X(^obrf%_gXh;PqCX9ihWp`H4^G4;H=`zFw? zTg%~AND^R8$8d0TCBKF>CZ-b?`6iR*U}e{mb~G1-+-Qd-sz;6~f#pycg#1+`SJc%$K_0M)y(h#^7u5ep{4xLZ&rNK>e^aC<5gfi2KY=mj8zBHk{sbL2 zG&Fy$XMv?GqkUqV(8E%85iyqkkLT3OkfJ<*S>dYqPAUg}OR+dS{B4*}{yy|Ko?%}lQLwpO{~!N6nT4;dEV%ScEr0=bTb*ktx4x$z&)R31@$cf$NdR5biiOXpAAAjG0!VXMooY3`%u^d7UPh(%aJEZJ@OollvzLW0Ux(hrR% z19HDbk~=;?_Ia2B?0dLNq#O!Ndu{?HgFv~O$#l5VQWzJTl{|(Wv+g!9OrULn$~7}! zr8%kyt8sxQeehi=mRh=riJ?M+(Z^vAF(*E$H%hQnW@`Q^I(BDuQZ)(TG2J1dz=KQ9 zRK?-D22QiPxXj2A|BAU35pl}XD#!sDEI(wxDiq=WMIU|YQFcGGx0Joed6@KX`i#N; zR50M(D`C~O?_H1iI{7I~VQG7*(X(zPhV-^Nkf_0lV4wAl@&ph>S zmJvyzMR+PCi^NGs4!hML49zb&UgZy#R7qKqbJVX=_VZ|=Aj#w7SJc__u>149ps-D6 zqwfBki_~^R{t?ox8AjI&0&v{>BjV8y5n#GR_xhOj;bqr*!ll4Hyxp8kI^5S}YX$&?USDHO1J$uq)%I)xpl!R4X7s-0k;imv!w#;4 z9<-?2KDZ80yhr)tqFqNFZ@yFY^s4n>Zi(>56U8gBt64T9wFV6b_Y*HG6ciqv*tkqUi z^M&pf?JDD>+3OW>3rlv+O8wKmC4?6JPnnmJ%Kwsi{Y~ace&7P69Y>Y`ya#Q0wy)qn zeH+l56UGY2#QIABK-2HwvG~wg(;UBLaRpg)Mtz8l4dDtriUo*|4tX4eKIVtM`fw5~ zT0ZqmLXHj#W|#XhK>g{tztD9y`7Rjoh~>R*;766wuspQw$SpkBR$}U+di(p4FCdRg zWlUmlL1d!2725i5(N6zI<)0!pBVEx7hUwA<#%I-`b?TdfCg2Z`<8gxr0||dS)fr6B z&2??-qjYPd4NLl==vEjDFoWchiK)ZY1_bR^1)rqtt?L=(r? z^&w(q!P89qj^JXfMb+!^u--IYJR`c*X+VwihlI}3_=%xXkZhG;-(mqLxHJ3bQ4*Qc z__EWtmiCNrRUKE!h*fn_?{w`}sJ4r#Z?d2h$frYVyef<8(ZI4^M&*Dy1SQU0E!Ds! z*i34*7o4g(>)tliJu~xELlb}0Hq&fm$CMh6Y1^L|oRGkyZmxz^taRgRF1(JW98~CH z4)+Rtr_~rSE-?i@!I+Go{rG-R_ep#<*4QsqykC?#Y^*8Ide<>mu8=Q?p|pvxC2s#ORgWp{r`~<%**gbzHA>&G;%lT338Hpt)5j2IwR~Gi8_6^^@ zV8@La_`_x(iJD77PS;8G0U7a@O?!aqd~tKiO`BNCOWTMM+uD)6 zTA~Zd$*HLqCi+C&*$~bI7_wuvOM_9Aqagn~(9@UBxjxzb%}NUwm?-Iw!(n=I!~+%~ zU$Ay_sA*Rb2$B{JFpJVTp%My@4h3E$h0^=riOH=Frko;d4yGVO4n1;S-6vR*gt^%} zGQ}?yTD4%4XI3u@m|wpiChd41ZGjS@^Tkd4quZJQE$aE+ET1NI-3A$76DrDB#&L?L zDj@cClC+W>4so|<(&U*9F2xwNjWg<#^K%UsTD;|RH0D@6k-Gjgy1Tm?bT4&>rlCP_ zxC@y&yuleZb811KVqvBM?W2x)B&;*Vb~UNbw+ybG^5L#x+3)Opea*SNP={aTwS)U< zXLwmD+YjrDBU*Vz#LfmGq)f5#HA|s02SP$6UffpId`dc5Ra0*faPg-&Qdv5wrdqpP z^{-Sv6G=qcwyWe$lLzKaVR7*v9UUPBZJ$)17&X4d>Nc0LPi_2ZU~7a^F#L`41q5fz zus*xZFNq?7Pl11b8DUAwf+0q6mX65_-TbhD#Up@#9{Kb5_o9JRfsV*3R+ISv88b$=Hqrershdde{Y&zZ1A=vmG;r}zl)j;!O_e^l72@Hi060hJGDu4zw2&yPI_g6Ubf6F#pU;JyAbSu8*Rk)g` z%`tb#>NaZr5k*)BVb>@{O9$pHJ&-&y6wZRD%vEu$iLMhljMQLG8sYwU#{ZE_Z4}*r z$}avcTTB8?kqz5 zLcwTh#JmwHGy~}?6GsMw+wG0%F8{4Q-5r|pxRECj`;aMbmRu$JXHB7J9D_Nn0M&() zn^ib6$8VKAvxsRLVt{jiqwHd9CZec4D?yN*Oc$-Vb=m|dy=*hH;JXOaJx_30pf3C} zPVVp{I?nqo?li@X*(6^l?H-P=Qf)*XNcU>KMHG zTu+Zsi*$dN08;M)&X{guBQEHP^0NSW+gYSpbX>t0cO%|MniH!vm?Ns85qLjV!G}Tpi%Drpr22>g^tHV-%+Z<2Ov>fbJ6W0wjg_m` zezX0S!FyN)o>p+gZ{`1**bXZvQ*dPG{EJrRfxSt|n|WS;|8V zrDS>gSj@Eug#86+Z<&YLncQXJj?8@>xAkH@N3k5fy5&s(wEJt<(UEfxQ z!TLbVt2Ez?(Vcm_-|`CX2u&HJhtzW(o7qZV8K60ocuYJaozVSlKGL4PxUi&D^6R5+ z=UvqfFfO9bv<1gR#Y&u^EKND*^5xam1wdOql979C&+XsNd zn>726f|3wg>wf_p&Hn^A)O!|HoG0Qa)_<^OGc0GHdJ`yKWP8mSOq{*nsuzIyS0 z;2b&ahvhN(-(~E7E|0f?Kv0w0-?~yGn2Swb1YyRS?IQrR2ZT>Izbo#ZUA53mzSh<1 zwdoi!!QsMI*1QPhSInVnX@*6SOZy@xB`K@X&G(rmc_+!|aJ&Yd>8ORn8`!Q!CVCLA z)i1?E5b1fOgN^HDSJtQ9s5*WveMDgAzDnU{3*p&U!a&7Q;=)WL9U|@YzeKJOb_OSqG|ltuCNM$x?Uc(^T8aAe8V} z?%AwtSr%EZB++6iRoD9fm&$Vi+@=+&AZ7FKpyDT|#_gWW^fstl{797z%wo_x;k_>) zbMiUy$PZYE49Ro|@dxXxS{@2Iq~=s*&BxO$_NhM@5wk_e!w0mxt7}_?SKA0}2!_sJQ%Jgd8+>b+%xza}55KX6(|3UrW)V8xhxj%&(Jq{DpiETu}@r0eHT%E>9A7bU;m_kSX^hI}pyDa6|yno89Qz!u|c$?iO& z=)7(wGwFH3&WvFUe@=xtmXjsGz2*77-wIIUGjmJSFoX{rCG)6`_o#EUkk_wYk}m7FWcM9YJE-UnyGmxvYV0wgRtmz~c!W&LRDU<}JH%)d#ao|{h@I~*FD{4)i;BwE z%@Ns3hEeECAv4SUc-qT(!Y*K6sj^f%NuFnE*t4ghi;I6@DK?$`H2>!lt}MG19TFVU z(sC#B>oK7J^o@*@)vMn_ZW6c!*=m>12MvSgH3qH+cy^IoIdX|G@Mz5W$T9`DDS0y3 zUP`MmP^Ym0=V1er;v=1Um8fQ2m@o~4r!QuV4u9kI#ePN*wooQ~>Gp{BVS-|v6#C8j z5n}5_Ss!rzW_N!HEgrOAD1@ZXjQoozx8zQVCDWYUkc{c3IRv#QU?C+ zkqWCh7DV3zWn%R_Z4Y;N2WC`-X|pHs=A?URq420c^8^?rN}lrFC}M{0Z5voHanrSM zc$~f8NfCHlxsxnX78ckR+tq~v+NO$sSGoigpeLaYV>qnc4JY{tp)(=hR1bbz6t!+y zr+i*b{G(TxCq3SRdUr{t$qm_-h(5_Y0)v>@pv57#yxl}t)c&-kZS)y{U z(hf?1^B~A%eJb|t=e`9147csfXfhQ(LpJmMJl8BvQfvWNZ^7rs`tk3D;HV|j$+2aleBI_0}7mP?Hr6lFR+ba)8li81! zzM*4D-unf)wLm4x2K7Z8jIk?dXlzl3*eCCuHMa|P46&&|UqAW{Y5RigsJrtC-T(`A?kr8- zX4}wL6f_{CHM6y66>P-$fzGy2MM(49&D|BFM=8>_#*hN{%G{KY`~5tGhmwE?sP_@9 z`0)H|1vh;&bGx9S@Drx1403-4^$ZeD zTIs7t*FL*JdNdWexk+gKTu*jy$`-2G5J`XZQx?)UZNr*ZZjq!QwX`CKQ#_mgpTZ-j_#bjsHgzQT|AjB zMtWQE_%HavE`YN(fRSlfNj$onFof<~gIgz`HNMUe3i%8j&hTIq=ib@V1bi>I%^|V+ z%l$dqI;wBw+-2FOtvkXL2r=XZ$c;W&jbXD|kDWdPPvLnvpSE9iv0Q6U&DSZa+$pM` zH#RG`%cG##J!WFH_hxy85DR{W-E5gEz3$mr!E&QO^r>=**sCjM^By^V6>iENb5^); zcBzDT5J^1L&F-D48b2y@Q_84%4AP@xkw7nJ(+2gCqQ!GqG>a1)Yv^zE^0#cEUQr2W z0(bSvE6-!znxR}r*15VjCeq{KFEGwG zL4t*r>LW6Q4$OE@T~B}FH6PyeW40hC^~zAI7u+KEXolEQnu$N6;v?`WbeJ4)4cjRx zV>3(*pL7a%@^l(Mjh5ZG^Y9zZm~>a+To1TdMD~2f=(Xg$eQjk^9UBarzaM_V7oB}5 zx&t_XQl)-PuxFi5dH(62y(6Tx3E$!LdY38XFaq$(;Zx)@x#;X2~0@P9Fxehs_3 zdvg7LiD)2*u;Bh`s;!*vHtA~HOiJ%z>k}qGGfVkT=p!WdU&j6VoxdM8_X=nf&AxKFy%(}_L{L?akM z(HLEz&$gj2_&dVwV0KAWOj*xG`SNry*61aqV(AR!Q!D7$U#{<{LCFbUK&SZ47G#TJ zpH84l3ngNJn=Z3=tN`W21Ht87#Adn%l!4nA0Pd zGZ*eH`UK1@8|Yw!p5dGBvokWmNg>qKco@;U{1B!b@E9}yVECbtWMun!_f7EALuw^^ zrQkqeirx#NeH#3CV|;;uEeB+B= zjzd$~Fzqx-Zw&j^2?2v8hbwHDln25T6enV)M8n%iW#Yp#wW94}L zAqo~UUGMwY8QS$Wy~C73C0)W}g)v4cmDz|dZZt9&!N2AzPRDbb@)8jlZ-zZKhw#v! zs)zN7#Mz;o_DAURWOLi?RY@OryOWJu2CpW++1*=$xlX`H!Ux}k>(gfUq$mB-`dvEr z==1nKV*;;h5}}M1>`U2B{r3PoXXXzE>*MA9Fw`GRjXmJnplo5T9Wu=Y zoYY~C@;djyh$S>4a+Y*nOC$Mwo`Wq}xHWhDwQV*H{1DEG-hvL5S5E3hgn@%0#NoFh zwOF0)a-10o#ae{W*4HJuFWGaAIEN=g0Rg&3U8G`lbaFEI2Ig|}_-20io}tt6uGN$C z+Ge7o1N60P1$ekv{Tg2l9C?tKU^vNtm-t5y4*83JX;-HHL%VY6Kk%37CX>qlKbc=Z z?#2L&L&Xo{P;uy$&p#bV0PWjH`XH|t_-A>&si+DQ{l#oe$;DvMA;DqA-LE$Jveycd zpCU4N+F6$0fVT6Mi9chF5h%&UuA99VCq!DK;LD}f()N(4? z`^n%wYC?6c#efy^i(rv!O9(eD{wSFB$y)zg$Iy;zjB8<0@uU-@R(~{L?ffy^0lA2; zUSu!Xh-KB3xF@lcOtxruirOfL)}A;MYb-5y<(g7uVYrYmpW5T?Z9w40`08|J{NiZ+3gU@cw zu|PqxvQaV#4SfvbTD1tMe`-p%s(F4@79MQ#IxTBxN#A5#llz=1Z-by)i!uS}_gYs0U%8;9iGk*D}mghfP1 zQUgWPfVS>2zLYuX189Q4!q@?JVP=cYbg7S<7V4t3*~ubAp`sAvm;>4USJ zO>h}`HR$#@NZG!Ym#?N#ahY3OV?X=#Dy|2x8W0h89`ny4;XPIyGjXuyeqNy2GZBZe znV@G*u_lhTK2sFUG+DHh9-tl@`|3%6W>4x4?$k7$>v~$B+OlP#ZLP-o%#H_Yt947i z!G;>#(!5w{Y522&ez&T};|8Ng4UYPYR0yT0)#y~6D8_fGyp>g`3y;;hVV1@j8*Dg3 zhOPm3w>Nr)vnT%1snmyz<`hXo;EvsHy@=bq4SunxQRh18s7yefLT$l3Y8aL6`}5#E zNrBL2CJG{!PC|F@2k8z@^}8OTdCM5Hijd^4H~dr>QTca_GQR0{TCwdc%Cw(Thw}|M z^9-Km>9O}7;3Yi1=Ap(P-8*&j^n91UYH@Q_aWC3>{Hra-{fp<)L7~-soHjI2{|llX z*!TeRh8e{Zr~H4+3iHu@u>1#x|7YrlBrPNq@t?=SpTo?bsX$z^Kq}BPK>U*Y>}!th z|CY)Z3`@#%oLT8-si7>YDGM0KAkj# zD_)FKLOOG)A)&dNtCYJvHd5F6Hxrt-B&}D!Dq7nr2}D9~6Jb2>Zb6(T4dM4UQrDDs zTZwl9z#y*0P68)JF#WiuQ zEE6qTFr%cf3v5nkKPqcV^Jny9_s-aP0ZaSf>T2}DQk871P_9odU_{Uh}eka6UY$nl`gb|rWtMf?@==u(RxSV^fVHLkJO zS1mKUAou{aCWR8{`Hj2!sfztsL*52?1Msq>s6I-uS1^4gJDW7b@$}%mbctGs&9P6; z2{UsP)z1s!=_g;8?CVAy`B6Ug;DJF-#>Gfvk30;ytSa_=^MuMKqqy;P1Ui^UcugK!i%Z&7c=6jrvl=B zs|xe=M?@s5ui_M&ADIr6dRV-Kx;k+qH4bEW1-mPS;p` zRCW34&!j^shgkNL{5F&6Z_Q0%MjekTPJpZlihivL&?O{u>LTamgtzO zM7Tz%6pcu+81PYmzac)DDTxz6gHyIc{CK;@yMIhjF4b*NodW?2HQh|(&yW3iv*Pg_ zvY07HQw8K1L*?ybOioI(G;jck)%4PmX7bj_^z<~LX;!7gHEc6q?YZR_Bjtk4J;U+1 zusHTNSiCB6Oq6*G!ayqj8$_dxG%t|hBK*c0kR>T472>G92g0;xMwIA3$u;zz7KfYD zC)(FASkp{s+B1U{A_L*{)b2!{HH1NI@_n^|5znB*MJj|5z4U^mSZY{%7=QSiqQk$R;q^=X!d35Uu&g zxX(;a)%E5<>vj1&ZN4A4QRv8QApV3`>O1X{p+IKjy>;)sl1K9nfB^in%ROCN+Zw$!l`T* zs1|9v6$Codvu9JK_Ne$I*`a~_6j;*!mp`p;;@ggBS2LEpNgW(YzJ7?o?9zfOCJRcX zv5XO=DOpMYbrIIWTEK|0(0y<{bTG5Ije2$1SJ`oCqkW%%kX zrIoGxn`e2coq#DVJ9?0%hh=(6N;-e^$HpWxFsxK^jBqE{VT~uC$+A@b7Is{+pn2-i z8vMDx138yBLNvmTHchz=$|Q+{p?Q6kT6v)#Mib6|FfNOzDMk<+bnSZMj0_v6rDoAF zd|=CMQ!m{R8Pp?O#7n)~<398WA5R8yC;Y(I*IqnZb;}|;sO3CV@FPIWGB;=V^_7D; zt#su_EyS1SbI4kJ>zSuNW=~Nxf$KeR@=?gPaEumv3KXxJHv#ZEx9?y28^hu)b}?F0 z=?PmO<1y~;?=F|RF(1ASnkLV^I$Xo_!@xl9!!RQo{}Gvt^`g9VIjuyv@aK9E;q;w6qX!Kq2yXlIKo^ozf&^tjTRp-QDKyaiqmW=G zvzQQwZ+kK()p%y9Mkc+W&(KnqgCTj9`vgU5kkW$cT|T`*8ChdXcASf(Zu_ZCc^@@h zvqYBsn64}WwXUoZT4BGNYAmsZ^td z&Qg;zhcHE}R1R-KU|+3AQZf___dXU(RTm1^0{cj%o}&7I9Zr1w1XMDD6Et}&EyFkD z(7TyU$x!X$gi-I%4p+zDfRh0$ugHP&g)eA(u$eL3DQU{CQ+gbwa3(|EZ>V_L)>1K0 za4B9O;?jg6J=RAamYkmcqqGXMRWoW4Fl8p4jD8Q^{NR8kKb+3=J%_n1_7UpN$M%*_ zg(I4TsI67Ht^+rMxIsxnF61hm{Ff6-LFl6yHR^Fxw(RfAJx{c&Yck6p1%FRON6tLp z{{t1>U->%usR73rQ{AS5QHItV&;5R~HK%a?-Dj-(CNn zzs<=kvRylM*-=DF5TVuV&-|It0GusYshvmt=YKgdsxdGQSx=m3)Gqs|YkJ98 zQ~tLDOMBwdP%oAr*#KQ zjq8ctvlc^v{u_&r2KN801>no+D3ZF}W>GDmJ&QzcB=)@93A+7sv~UneCBXcS{1}-V zY#`XTzyo^^qQM|5NMt#tc{78>fuqc|-NRhG!1S3)Z=vtP^)?fj*>U3RNv$1J(7(2Ng_jVY=`IlH4=Xd+9N$)KDk*V0wGq{C<)=1k^{1FM2Y& zi$RNSE*Oc8pMlJqEFb7-CjzF1sJr^ej$6D@4jK&P z!Hino2%tL2T^bux44rIu2q@g1uiU&fr!%MI(K_KC_<0^CL)*2i zZ0aL<@kn+D)j6$m!P#@fQGf?nH{)O1dS%#p8VHMsb+lypA-AKO5n-h=(fV7A-3^n*lNl14M-JR#*-T%F=wbps}xz30EZ7x3WW#+k``~IaZ z2Mvex#Z_mUoS$h{`Y}P^_i<<3wf$PDuT{52N5mFwhvHT|=STe3U{H z!b!9}hEFP^buBtpr0g$u_o=z0q}W+0w$~cjHabO44E*jlWaLWQv+J%&E~E&Q%6B`(IdwPJRXA6RDzabM$Z=3`PfDU|*4Kyk8lrq=8D zBgsxd;cVwU3eX0ir`lH?36!v#yc(t}eQ9iF^{CJvpC2*BkxD;?j+mySL)(10r@M&f`l|lv>QLVw>SR9*tG0u z%KSs{P?>S<9mj}2m>(ZEmzll^__L_=y_B_-+BtLbeuT*$RB#U_Q3lYjHkV};R#_mU zH;ug!xgwM}eXR9hQHv)9$jex)PY~0k1)A<+0C!>jh+_U=GNY60bVKy^RsZo$huLXo zr{mRz?5$q#YVbiWYxF`RPwFnEy2O5I*3mYV=;JbheK%vm68bVT0Ko1zba8dv7CO%` zwDLZxc?qm^3p3KJYB8OgB{QrEIx8pcz_3a;L5>{{)o7R4=$Ri$ivVMEj3zZuBM#X6 zydX9+`*+%J_CBEH=y2wP4ZYVi;SSIR_Tp+v`omHqPIvh1i`}=Hy;B_h zsLvC%E;ZtN)o;@>=D(gUUjGi5_agP6%I!k5Z)OT@#&x)lu#ce3vyU(}^%)moQs97R0X zm)*FvJlw6?UJy?XI|z{rXsr}+5{+xlsavC z@F_U%@|14OKhMgZkZE7W1WE<$uox=Wt5DaanDOBubNH+teu(n z_uZ*DbLTXT^NCn03vd@=cBCx!9jfrnn5I|HP*GNokZYI#yw8@DfUxJIx-x9V3uwvU z0stHuITTE6ATu-LQc~(sd&`^*W|vTlYOV!?=d|hc^b-LB+sBTDR($t?RJ$}r9Xg8T zWrxDi94ml@!}ktm{zR>26ulAP979XNzpP(Z8fwwZ2b2EzRV_AI0O)Qqta3rjbGqea zO=iBOaW{XyKhFIc24Q&~9#**GBOLUKERU!)G5zrOs+YB?@aQN;JY?%b#F&jH-L5)3t9aoek2;seb#gvh;oeLCGF_BZ8ki7|SfJ)cY1<`b= zK8(tRUYfE3n#;cFx@g9cG7E24BQ!iZ4o2}a-Fad1l@=*p5cOn!W#HZOfzK%T<3tqP z&&MZfSxd*<4>|o=KkU8?dY&}0hvUbO>d)I!oadg~(}4}=)Bap9i|9#xGh@O#UQYTQ zJu$8iBKiD``Kf|9bJVH|YG8K?Dj<%(${cMl_U+V(X-18b*kvQ-bo7H1@K@``cU55( z%HAGzzx_cOk#llyX!GpD#4Y6U;(hTC-Hr3)LfO%>RrhI$_atJ-o|i$j_1i_<)8K6t zDeJG_5!YnV?EfTo3Mk0_Dbf6O%0b7 zcl@CR*N*g|#f&fa2z!&*WkLZb(vR9N9&un#)$%07N9r+l1*a#}nY3OxDi?R)ZZ|PA zljH!f3ame3^CLj5-(h`@JV;}gb_Ep-f2G12yX%LAKwhn^y?l_oYkR%Lx0`HsZOe%{ z-Y9#ws?qy8?|P0rn5+4zI;}?9W^rB0gPkrd^c8Jm;Q0?|`fs&=a!lO7P(i!IJ4%SG z%MIJT?V&SQRqT2nBW}>e0;_6;>Yp{bn+CP~zZ=vN$mRY1HBbJho5WNJD8bb@CKq>} z(#c2kWHkdAmG*|Z*gpf}K#EPr!)#!1h>TpEZWx+;m!`>Uwqy5G4+cUt0a`7p6JIdT z|7836s=0M~i|p5D(7;_KnJhY=7l_IBnm)$Fpu1?!kMEVO>U{D+BE%k95(E1WUbDZe zxs6S9$2*aimpfCaeWOr8EX&1aR^0ZNFSYo`M65u8dg>`XGm#og{F0D z+}0u~dF!Od1c%S$_AzCACvZ3Fn;Os}3~($uTZWf80K+=v6RWWV-aT4}<4c^zAiZo8 zQ+NKgPqG^pj@~5XtS-+g2xiJGnW*UbtO73?8cu$dS=t{yn9StdG!KZhXfL4RA0v-_ zD9!vA(Ov4<wIop`A$i>h z2j0Ddv?H#xx<9cb+CGRKF{`j`_l?u^y2?xLpZp_sKp#5$8(%z)H(vE|x<&W;l$Cir z9!VRNN%f_GNDpi4peI20&xcFG0PlK}jg8HDUW>EWx1OfAxj}OUnnU`UPZHcV&ngM` ztnX7PxO{Z0MjWKAhnX0iIJNj;!l7c>hF%3iZkODN)8do$AP4F%wz3PU?iQqdLQl9` zcU7h3Sd_+Orhfz|88GuXp1sA*^yfz>a>sp#GO;mATe>G&z~ z;7@{N+|Mp!XN#J5`+6=?q0dq`Bj1M{RIcXv z2a4VhWR(KyFrNV;s+BsOVE z=+jLttXY#;)c8We*Bf)hOMxk~f1W@mi!{H1X^`%472s9EJB|XfHosF!=gX#CD&Z)^ z(t-nbTJUgTr{1;3t*lpb*YQBOXxw2H4QV7E9LzaHe-F%R7266h&lI_C+&BWr);T+F z1ji>O-#m=ks6x6rG4fR|mpuJvE;V7378$q|WQk9xC@*=8%G)(XK2zKNjqR0Dz z3RB<)-&piF4>>k0VxwY+jodb@A_m;?jPM5)?4_$u-_@oGMG)F$HGOm-L^a;; zUGeTm4QfzXFzyjwD^Jg0Csy3f_k}3!^Oq zdoLRb_BrfX?cEA{5(`Z{o!Fd&D|6U>X#9cMC10?6 zPF8WQ&d&8;4APg4T|PGbarQXZ=QGzbLvOFTKWobRyrBWc%Y7Cm=k$Lh*gk6k1Y2rg z0YI>gRSih}-z?2X|o z`6i>Ms3~>4Ri5X54GD0Z>Oa}55o#)#o2%a?0slPB$_Kf-$e}-fUJ5VYo*ytN83y;> zYO6TNx_qejfEt|%eJHQv@uF6?HO@3}my>r;RaKP>N;s6h{2SS%&rOJsk=00Sx;tX!Pvo&5 z2q3NmMJCmQ$qSuYchj+<=7L^B2&)!%idI?`zft9MH#1ngHZIC~BS&*`m1qd>hNc&P zCzjzH#+H-?UX8KiHthrkNb8?2Y@EHRRroS<(Q>nR#diBQyM8HGDA z7y5`VDs5Y(H6cJjZnxO7R+bR@k%h(4+Y0mZUpY8K^A)g5iDX)^Pw%{P<|4!Ed12HY zOWY_@oGlMY&=&2RC*6GAxw<0Bt+ffzNb_s`Z29?A-kE5*omiqikF z`~(FkyzYe!knfkn8f#IP6Rl2=}7E|`{a z-rnBW_;qm*$a-jKg88Z|1i5!Np5AEekx)sj3A=_rD#&%ukj&;Sf^e=N#>J7fWSQ4* zQ!%zpMjLl^!KnxN-Ruq7;-u59Kxkecfy}RP&{rTAaw!LK;PDlEOjssCtmxq%ct5?R z^;Yl|UGP2FrLt$PZIQQkq1N`>Z3s|tadmr81LXox?!k4P%0~JB)WqW^0R_VCY*=jp zLzGvEM_*Sy@JRpXt`R&02AZ7z9twm&+U3onq471FrR<;nT{f{)Eih8DOcZ;v`bz&i znb46xixJJi9$*Cl;}7n3Qhe=p^R-M4zXF>Xh1-Sy%(<0RfDdcY!>)O8jhe*YFt#c9 z<9t_{6&2Pu86q>}iVMG)sHfwI2J#uc+uwKZ&mG_dO?(>Vh0K5tEO;EFLw>`j8Q+8nwldRo%CS^Kt+7R9%-LiFcM3s(sMG~ zwolkwpIS7cRr2TY!`3eFEQ5|metwbA;UZ+^U9SR;2RtFS0^Ju@7qrz$ zaLBfyrspY|ik87Osmpa|iflvG^bQ_o!bi8`_~S_fy4`O@1ja_-J>I2X;A-F6V);?+ z4O!-aK6AU2;4YDgG3skXEdB8WpHgAKd&=zcnYY?AVc2g7Bp#ppIfwDXL^w3sbSTN? zK#~F0lF?y=KSBQCVh*5|a*9){W0} z2>j2_?W&CkL!>b9yI4abBkG?(PBQUO-!rlX4vRB&R|J?B-y*~zkdiN8i$>~v5<7R! z!J)4bMj@KCr2Y8r(^-F%otQy&-p>vz96w16=#x$`Nu5#Dv|oYkx|%4TL`@-N{?u@C zCD&xOotPFW69F>IfQT^pHz5Tr7%JnPW z2^0zED)TCskQ|+^IYcHlW9Uth1wU73tzmeiU?e;$fd*%06r*; zDD!GC&`nr$gX1-M%bv{Q?KcXDv|KN{UMVrJ^7U{3ju`@)2>Ax=9L)alD{YpmQX?`Fyc=`ESl8zk+{SK7iUUqWd?vMEKBu z;S#(HaX7YrRqVO}U%MuH9PpD}tY%#h0g+tg{2KW{h0SJdCi0gC-f9v!mr{Nlto7~{ zOqzLBh(3v;9vdAajMNPooVucLk9)$+Q4@iD8k?FpiYSNHfDvt9=5WV_|pGRB0LhdShpOYfkGLwSa-yW@l z_ZwAZKxmeU;eo0q%D78pAu4gB;b3UtdYW!#FWaqm;HPgvN_tgl>sV3efybnChIOzYfM z;QN?T@ll<~^^vTWy#YbvK03l?eXd{UvEd4A=y^*;VrosjAE65d+#kv-8`rE9IGY%xIQo}v<)x%+^dLZ zw-ZG5@ZrOP5o{hJI@%YnhtX{sN$1wK*$t7C?^V8zj;c-WU#gq0)|+(`uc$7`8dYvW=fWmC$*S~R! zpFn}%zvC2tUlUJx(-hACbyv8&zP|ZrL39$|ahKp2HK*M|x6`b*GE@JUQpj+C8Dbko zk@}9ot#txuO9FIB?Qg|j=7VJWZdT(W3t#)EZ*X>`!uS`sXq7!^$!AZc`{>-pLvk7- z#2ZPTud9Rvf{tx*q#2!!H+0}SV$PR47#Ed}bJ8$6ebEVLPz0*e&8AbJsMC^gp7$g2 zAV&+ohN_7}-{|N0K%eO`;qi7ePytn4nP7aIJ(B+L8ALUPgp00g$AtAzNs$FSRcK%M zqTSd^eez>r60UWjEd;e5t>n^6Bc6OaU4f_xy&L95^qZRO3tpf&v32am)esUUM8f#f z*O>hCYh0j+l&MRCWdkoEiJqC^BuJbo+VKav7Zuvp7U<;cY$<%(B9m5&n{Vz{GGk59 zzC>}US?D?)sW4CPhKHEO?4mY<1|RmBR6QAUi5e^6yr7anszp}mfutlosj^`HhYuh4 z#l$#w+vqE3y2f~;-H~}&IC&{D8RAKmwxx?hNw=xCwhzy>!J&!1Ru(Kk43dX6B_47S zqS6bqy}yH8tL+;RDAyqbK7$pRW2Jz5()n;9iz9gz1bzR^vqzsz;_fnC0@EQ zVJ@E9PCoJxFoTY`0~RPvu0@E`asbyNiJkYOZ!-O#QNJ&=iXeT*5L7;|hng)L(xpC5 zoaqgTZ!9=tV#24UDjX~!9)t^@pX;D&jw%|-YHOWO7k^hRDb1ivYdwphH#dGBdeF&# zxghVy5bXY?+hj_-iZSYHG4z~abQ-$tcGu&}^B&gwcUx{C&W+GJ#tq&a<- ziS?;b5*(?rLj;vYAN7+x0iLJi6Qt zHj_Vd52{{O)+oCX>^EBF^88~NUyaoN+AOO6eY3FX{?D5uE0xXe3P3tjwmCl?oe{1bZJLKeayd8Hme2 z#UF#>Pyh==ju>yZjpQGT3sSMORotrhe*AO}l?(}PlC(36YJ2};&yZyyHcPw#Ti*3F zQ}FW+=kfepu^8sO(XpVYdT&=N$92{6(R|(Y+U*V|H4_`b^K() znCw)+6t>>hruZp%mAhx396y&dk3gx70yyJWC0owjq}qp<6@?ShquxoqmS;Y!g&5cG za=T0humC(_8$1j?4^tO6(?=kG3o{qTu{WmdFB-ty`)Ee9+{1q#Eo1NvOUQ^ja-bG4 z1iQHQU__{$*w<|jm`0b2ZsZEtWS$#Bu-*BWP;W`^FT zh|wIJM#)9`GZ5g`kJ;imoXafWt$2{_UNuVkTsKOJPtJr;ds5WMH4dYbs~qPQWNyb> zI~$l8CH+W#2DzVyo+oPHSP1Fh1oXk>f(sFDf+h?%dzhl&ZJK>vZb)kswYw;Op5+M*lp($8yf?W8%8~f2Sz-xN`WsNXppNj=d&_L z8Om;xI6o;#%{nXln!*^xWC=QV-F{0c2*>B~hs0VzW8|n9xy$(vXQiZFoqE1!;jhN+ zCEy&y$0az)rd3La-)Elc@$)iPZlk3TzzQ_fN?+UeNr*?oBgB3m!#@#-ezfZJY=PoM z-;39`d*vF;+Oy2&*C?9f6B|I0ZCGRphd*Uu5^`wYj*9h7*%fpw^R+1RHddMSKuj}< zLHaZrl|ZLg(HQB2x=1^b>VEreOQ|)`s{V&3LC2$aAb^yq=S=TD9gx1A`K^GkIaoh0 zbjCHnruds&Tk!eJrRqhD>s36|vs}P##BaaR>J3lk#q`ptIGu#@m+BEy|672EFF2vG zv2n1OQ)YZ1+rJ3Z%ztAF2!C2ar~S_o{@xcipry1pKwthRXsKr5>GH2Vqx65s5TLV1 zL*b?fkcj4x=^srZoaVW;h)ujw{l(&M-kiMo`)BQGe$yIFEdFR5j6bMZI+q<0;Js z&M-uz;<&!CEQ}5Bpc%sIx&2n3rCS4?75GpDH`X`^n zH7n`ym?wz_20y0%_U*Oq?)WkVH9`bUM=7X0O2}Mi143m;;ZU_V6y<6|35@bDT5E?= zTo&eEZ;6AxKMH%vOsB>4OCLlu5QcVqpnf3Sz;cWIeysUqMIl{hP59*{^MSI&V=gqw zn;O4O4%3s1hp9&TO7x$jv|;L0tJEfcAQl`jNyxxpiBT&bqyM8kS0}0VtCmmQg`bzK zk*i%xZ(=_|;S^%KgOeE9vpd}&a86NssDz9>F@`mUj7c~Hly#0us8zy?JB?@;#HK{w z!W*be#hvqauw`mfld7CSWhj1HVOLjha++*2a&3+;DT!3cmAUYUa=4$6yyVH<&DZ9R zCoZ9fcvZ?C+f%D#GE5OqM?(DK*UK~^C*}9C_e=?CDpMgJdks{O6;D%9os}g43FkY3 z6J8j|#9ysMpsM`nVm*18L<0FOo62xEDW$>}%YvNl2>1H_ROS6yoKP>45?yNf7Uc@< z_USp9>H2G2e2Z9x!ib^!v&$uPyYs4M3ZKX2>Zg+L+zR_-O@;wa^)T5ma=;pG&)i6B zgMFM5QCcp1(?L_d(8mGCRC`<%G&F#i# zJ6HFSMw5c`XqWJ#i?WBLxOieMG(KWypJf^Am|E2L^b@FbhT9x%Nt)^CHQAkR2MaX% z*Jp_C)(7|3m^Cq-=*wq2z9~A$(`}apOusMIvBMBO4-`ZM*{??NNprU{)_xs zLvf5TVEvA8wqU9rcLuzKLAS2=ny*>Q%gbTzak~IeV^@Mu>(#~z^yZK1;7!XI2m}hW$ zsB`YLqq}OE0_vJ=GYUajTBxH&9l0}mtoH(GPYDC}jvCOJ?x^z7$;KO63f)IBvU9O>c5$qv}@#YzI{hq)Pe=wP~04UJ1!To<6(Sx24uh9pRoJsBpjw4P6wp1c_i_G0hwRTAzJKS^ z46Gb`e`4XJ<-PW7C8KxvGDt&i4rt;DXo77m#hQR`hgj(I66Has_uZ!*O z(On6A&@F{MN5GwM%pEcf>}?^qgoA_O)8bxTqc)o?q-TJI1wFlmg1YD%8n*u0d(-|) zSjE)}R%GS2d?LH{;A(CP2(a2g+1tcCq+sEkR6R*6D;&GHkaBQ$7tE4qCjH|y|2}>@ zvkmwz6HsuQuOcu)srPR@61V4i>s{v$M}lM9LYbla5{vEvw95|q2DNwGq)6zwxw&&p zi*lwMJ{jM)a4F@0YjQ#1o8z7yB6$SV0InKUkEDoC&B!J$q@SPf z=o4Csqs>P{8Ec{j2#;B%(9=QGL7zh0HfGlju{*!$f^Kyc>GiY5_OFw3^saFW%H2}a zB2%_(Z9TAQta3~VAFZ_e>q~*}NKLnu_Vcy?yUh6>AHvbzz`PoH{9lq*A2@&J@cC#RZ0>n|UEZK(@i znY!LRmg7P}^cMZu1zbcXPs9%AIc9j~om>y}&CF6HBpUCl1TPB~uu3i6pcL=P6Gi_y zfnS^JX1vIB-%J|ARaA-waDM#fgbBL1Ec?H(j{v#*!_m`q5*o5*wXY$(CO@R$F(>l z;Lw=eq{KKR-Qjjaq8cABQeS&|KJ^ z^+Sop&<31(@E0No_18WEq+F`U+=qQ@tnkKHPx~)}r$mXS=^x(ym{)LR>g@NemB4-VaOn+{%v>NWV44m;Ra01AYaQ16W7ieF)r$!?q-~E8Zm(|GBtd zpC(`<0CA`K5sf3-GJT`78VZY_15XlFx}(7j*tguJ6bbh}h-Vf1i(6%BihB}E(S@Ts zTBd1(&IX%1+X%LCi9Y^j2RFqy>Xo(b2l$lojTGuW6s(qzrKO|OdO-8UTMTPy?Rl%; zC$_DPouShbpL_5r%GtagIKkFQNd(=d;a38>5_~;=R?80;Lc(dpkHNxp%075P`+mk& zw6t_?K5llC{n8popE)jKvCaO+CU{ovES`_JX!k+;GeE_+#e0wh>(bht(wP$}Q=i?K zf?-qI@GMLWI|V0PyCMs<;*<1LhQ_62R^{@r&q9#b&9>CH2= zgncJ6TO13=Uo#>!G53pS9WldDBYorTf5a2!p&-dp3>0R@TSDF*7?Kg+A9|QHc+wX^ z8{p(*2+bX)92aapkw(`Vp)Udy-zawX^gNvzO(3G@bMM2iH1Lm)iA;5zh~smnBr@7i zl(9YkGECwgYw$4tcws%0+CplLO-+IHjK|4kQn76CF_}OE6AACDb#vNn?JyX1hz1JU zYCeZY`*Qa#sz#dDx(L zFN6ubmt&n~RZyvDX*KuIL>BDPMqjQtTPZ5@Bus{f9PYluLx&|o=lllEZxr1So z(MOCVHuh=zvE2bfanm)96Pv=nQDRS0m(v1E+Nv)zHWx7=IN$)H3@VIB?^+f4eFAc)Br8z6>(* zREsd6TZ|U`j-$W~(1--t!Vv*%{BCZ;bhtBktZ>~|$n$cBSfaI75Z*>xVjz*?Dr=wh zxwA;M6|F$8B?iHlC_LwPl#%$F_GL~b&j<59#hwDXEFOd;6KO}4F>E@M-Kx5|F+3;(|#7=W~fI)#JQ#j_+bn9VsT5Z!hksVWcSyaVti@(pM?KR@E@zx3N1dUax zKtfg3A|9d6`8Vv_r=$U;|>?Z=kWG*4WtP+w0R_SL8GXP;xI8cjU>rAf~f5ByD# z1rqrzG8b~0*iK4KF0t~ULrBBUe9CWq{Z6gw1TR-az--%7j9};U=kn&km|QFYhmy{M zQtydH3)$@UFvahi2PN z_0D=8wKe9&!XZR zVTSw-z4C9u3_uVreyN0zy&RNnxjxUjV#PIjxJ0GYhMeS{^(_^T9Q3`CN<{G&g|9-g zyN&zqjq%EfeM|$i*YxSL8+5@-Bfps?=;Pf9Lmq@EK;ZM}PeKjKivqL+Zn&wZS-*d! zo$s~3y&8>1jXWaik|oQl{=MMw^LbVqPJ;*U7ZQoN(HCd-xW`jdCadIg=B;($jS{N{ zX-+oX)?(0@jrwMQ&BTTTC&I}g^G~go4oW9;QHTyqVnYRuNXj<;A{4;lShTKh(ioy$ z@c_F-Plyu_fVEn7Ov4?GlXd#_D(<`>@`CqL2anEujz5m<&R&_cFEq&wEm;EJ+OyBV z4O4ZN2?eeR=wa<`;57*zu+4&GdNYv{;Mt2Evp-i?8y83#h!UI)&!E2`AU;LQ+) z4a!fh{j>y!trE0-VgibV`VqgYUCq5DuZE?^r*~TSnOInexw`wDT0)QJa199vR>JSU zmM7|37wdQ%DgwW++^CYKW*F?h= zDjz=V8qlaq%(z2YOeK#qiN@GE4_BQR_Zd8g-TTP{lllhN0LOBu^o5Yb3dPS{wC2=c z7;UECh7fB>DL@$$Q70A9FWHom%rhqBO*Q@g^oJ8Q`$ri*>sVQ(=8?w&eRn`ax8oql zRo`2nkqy2>XW`p>$1N=_cb89_Ojrri+)ew5P}|f)%QHW?AXX9R*Hwnez8xb&&xt8s z%{DZ~*MuDtXum>csr707KxS3Sf|q>*f4s#mRIQ3ORn`N!EeUSo?|p2u$jOi40K8ev zdgtdzd4m^8U+`6ozF{M>#V%Gom~g~1QFS4jUHXty#WmXr^O)?Z)A)jT=3r(Fx1hpQ zr}n~~EIvjGnb0{-(M=||Xc8S>OF!qt(LS_)v}FDA*dagOrUZtXLe`=<4aBuk4Xvan z`@Q=873#I=sAohV;ht|=br`mgjWx60YqOH#k{i}|aED}%=!GoJZ@{F)Ir6x^tT=9g z=L^&WJ{+)RgZ{fV=kK?_6y$FbggoTm zNf6-i5rtC#m$Mm=Rwv@C z2eDE4ePI`_#+v$2p6-F_@IV;IBFW3UK-&HB>f`Oav^KY86<`pm3eITeCH2enz^`&c z4)T#Fufw~gQRdui4k6z#n-ZLt-_&=(!KdY=yWkg)rtZnb5~V>oF%4I_?r!Ht?yr|? ziM;pHX`gY<{t~6a-}0KU^G!=i({mT9O3-l z{bO(`z5Kz1+Q+?c&@+$;^^OSH!eC;trxz_+hLlro$3q_1fi|AdG9z`~=Q(2PE)A!@ z1163_dhRugYv&i;A~qH>xAOX!+-bt6ya}gEjy}t^DL{Of+G31IziKH%=lmUYJqLyU zFZ`fS>maEF-sL0d>_O)k_RFi5CiGlaSC_tlf&3@U_q#9#o^qaqXDkE*Sy)|Hen*8S zd^=HIhM_jZfm+y{{=6*!)SLU!Rz|VoonkhOy5}K)(bm^p#@aEot;u)Cgl{hbQPftxm&XB?sm?<`-MrS^&-*Y)XNnOA(k;D3a z{H1|=(@|B~+|lNQw$zjVPYc!!1X=r^54bFO-v4;I{@&vquO?~#*VFy6KpJHNuoku> z&yHXGGYulc19(AX>c8E*#fxHoZp2Wf%TdYNF+e7h~FkL z*En9;m-DL|qUQb%tcMS84Lz+H!okijf82lGVbe#AgMw|Zorx5i_>=XBeyos&J`+Lj zF4FVOR>4J8vV_RSX-&T?1_{2E{dgdI>w7gKAJ}B)Uba?XaK;hSlg0H75R=m@;R}Zr z&DN2jaEgcLfusW&t$4#dW1vH+uWiA55cPsKLgs= z+s1ry6`E89O@>P|DD>J>OLONRT}K}$O~OL{w-#XY)*f=PZ!{PV=_4j9PvFK!Uq*W1 zv&IRHxG0}ldsZx1kg(~mq>rTH$9*nGs@h5P% z6Z3}Ec0mk$?UQJ8#Co+%0zlJ6zOH&J-(IoOshs{8^n7C7-y`ohq+3QR9E;_rKWKj& zitA*;zi<*Zoao($13N3>j9tXllj`ai7}mG>9a zN>YFp=&~NRcn0di_DHDIPdPspD>*;vZE!4PV_BbOe{?D+D(muOyQ0!lWB%?A66RL% z!|P>y?!tL;kshR-g$$qTgT6-#dQXb2$|g3x^=+&qE0ac$&HNC~SlG&Gw#)))e0BWB zkAzssQZ}Ygm;8(>37YaL+WKnK5Iv0k>^P(=jc3t#CqvMklodg zl;b9=LQs7eC|k_y-|+riW>`C}2d3!(oZPNa;ZtEvf#p@E-`k@OYzb?RlWDNyuJ9MBtaBp;&Suv$&W>9`lxkFC(oBH9$Z^bygNZe-_C=B_Gwy z4|EiRE#|Sf-JM8E%p49Q`F701z~1O3N%m;=Xda!2`G7>!<>E0D^J?fUeIE8K*%ld! z7VDr`G>$G7$mIvzBVw-8(7;WbPE1%++PYUHtheLVgCz=YLjG2fQP;1Ke67BEUnhOXsWs$Ti2KP=l6oNfpaI5}cPF`dBao}_FlnSBC@1XJ z>IY+2?%Dmaiw8&K=Y*YP#GfA-H^ba`KP?)^Yx4C8E~)UDzjB#>d@bI2Y9Q}Ng3*wa zuO#rW6y-0%{jq6-d`a?joRNt8z-7+QNZ)+?U{u`8?KU;KaMLBm4T!2lD_7}bG($c33l1XroNZ{I7nD&?L z1hkmw@)3m=??iH`7hU(>KeL86@+Ch2^`|_f@$C`FQLOhQsZK2U6TQ&m6*K77OEW9R z3eI6)_=zsXe4L_XoUN?+QIC(XZlKtR%T>YAU3+qCPu?^ezNI0D%6>>f_gt|)tU_%g zzWwb)JcETF?H$6`a?OL7qbo|K=$O~eM0#1ixYa;+$|2^R99HTYoTp)BUxMxhyP1G~ zBhgJx9uz)=ZET{|q7_wD_nl4j_0i*NUu*I+;KKWF%D-nft&WxMzn&J7_s6qi)blf1 zMD9K_ufNv;s`=yS$z4{QZCq-}^ohXAN4tQUI3t*j$xwTW9`_6}&dEXj%FpC%v${%A@eaoRm%aF2oNe}#QP~f7ooLXutWc~oT|g2@>)4Mu>17Qh z2d`T9q!0MlmHqvGPf7V+1bi4kj=22egD&;*f9>s&|MgnG^}k>1E>xBOq8WougP0u> zWaDoLMy5Xp^#5e|1oBIhUfvLl>xKVCFaq-H{29WX52W*uAdjG>g855#66Px1;w zGnEsC!!`7cRpUqXqWkP@(eLsQ9e^fTUJ zqRvZrE*UoA1>DGl*QFQp$KyB3&Iqn7SFj2)J?q+C z!h*+$V)yCeB|B?O%dGtUjpCOMPZ&l}E&w0M;8S`;dHzK6{~_%y1EOrWwQU%NZb3Q* zQ9_Uqq`PKR!nkh%X%JCCV5GaHOH_J>6cuUd8jw(l5s>a2h8kjEfFZsM@BMuH+53Io zU+-UkP|mfkwa#^}<5beCoeW)9dH`7pi_GMRcZ<4@I*x%R$=gp^P#@n0yyx?OhOxDD;;o`h(ytHA#92rsDB+Kpn#CL#F zt|Cn?#^LB0U!hB;Z$k$?b}?VKfIpCYcju-sCndm%1k#-fZEvrzuph#|rx_M7Q6i~} zAIbxByGK`l&+}1c+PchDRp8C;CY3qIQWwM}TkD9yA8nXFtso`E2y;ELR(+t8FL>C` zRPyMdhOg3)Tfu@iouos|Uj-GSu?nE@`~->?!$)ORx2ir~ywN-F56S(<2i;uuA36T7|Mf=i zExtQ)?>fB$IkIZ>#O&XcIKxFU=oV4IhcS5tZ6E+38~{}=Wx~!4JvZ8NaO;993IG$0 zZ~y1P9jF4SITyE->=ys)mU4ib)UcI#ZgST5vikABdE~2lSyH;lun>jaOJ7f}0yf3$ z=0HY8c~n`@KGMzs2?>aKWp4w#^oM*J{2SYQF&(C3mpL9@lF(|oRDkALtCCiy|5!Wk zI^i(#_tDj<=Pb(Z!)(E~{KlSe%p24C)5N9A1nsHRd?ZN}h`U38uiN(T8HN!O!#|I8 z@+-fcl%qb(XzN^fL=Q#He*;dZ&*uU}rOI0Zf#7X)kDV+H`SFub2}7#X!TRjdY0mJw zH{8Pgcoh(dzSU7S=Tx|sJte-WAj;<|;kXaqi4yPGR><4;PeV0+G|43vqx*7Au2a?B zse21Z{{CyXg&o?PM+CC$ZbY!0Xw1zR)(QrTTU2xlB-)!jP)zjjTB-Pr2*41-^FB%1 zb#qj6qu%3~LkpD^Ltbn-@|KRX`DFjnok@1XH>idrf3ixtJK)S`9R>+lLP_@7Y_3&# zpShLgRMfqGrcZ^$sp&C<2;Ka z3~OTx3$JlLOi*w0J!mwN_nr-&;b!E|dr(5-Z#1o7=_E7n$4waF%yzpyx3$A@+NRNO z&%0UAXcyLPa)_uXud9m!G}ZA`T^_38szj&Jtuq8qYjZt0@JCJ~3^?<*!7p`)0-;f1 zXCj>nI~BgmY%SY`K{3nKVxU2nHPxa(@~yXaRn1k=jb5|5 zd#fbFcgQ81Pb$BTCQuSJau5|i&%vMBqg0X!K1H2qS6|&wG^>)n zwa#EL+;@vALs4YBVJ7d*wZG?UsIRmhm#BAe zm$fDUx8QHL_Z74_62KCy?3V50q551JaFqlmd$hZLO?h#^ioiGnZWn0$`XzNx{K4N(OW3VY2&ZuWV*8IgEa48GsID*k7_ zFL3ZPdNfo!s=%qouT&fSxqDRY#>PfGg+oL^goF`ss=b6wwwma=K^4l+%e&A_z)_Vq zHdH25SBr@(_2e~@;0H_~<_%s$q5%`hGtaQ?J?!_cd#`#hxMDU(D|Y4>vSf7xT<=i< z;c2=&rLmnc!M_S^IVAuzjTH^=wx&ipiKM2-+U+@n;g~z0Fr8y|MQ3``w<$}Y03O4oS9 zzq~r}kxRJwz0RM<2EgEY?aLRdNDM_@di3*#L8z<7uW?p-*J+ZL)JW=9*3xc8HoKr8 zM&Lk5rjsmG!+Hzwp25Y6GH=PZuVs;)sHbPzIvb+KSt;j&Zr=Y;lY-lE*>Z_tWb*X{ z&lCxsK2u;#^#U#K?a_kRpv=_=1?41~?%mOfw4FQV!Tup_Zi6eRJ!Wr3o?8SsF&;U0 z+UU}D8%lMeW1BB+9Jzj(39K7UtHwd*sRkGCS*|?klg4zl+UvhzEqwKSA+SFneu!|- zHo9WyMfE+=)OfdJZ*kT-esGHPwcvgZ0Jx@r2!nS8P@V=-WLGgkr9yTUp8_a`;~!(m zM;j#buHgXSMTKDi2Y5Qgx8?xUmE7ZOfxNH5o$nm$_D^~)&NvDb*`bk8Sb@dUjU#?q z>NU6IUCtIb0)7D}bC81L{d;4TvF&2& zUz*<*cpb>^<3%NpouB_k1Y&FTSR-Hy(xBOtTale0g&FayC{h4-M{c5Da*0twrGJqJ z17|43WPmQY=P~++tkQ;KX+uP_1l$H$g>0nbI(D`x&wI{aO9mbF+(i5EnO3P79XR+Y zN^W{};R#z46B!+A|8uRr7g?&da7_c8_Ivk`~ zBMr8sj$8!PLxa}W*Flt*3eFE4XWKJfngoDZ-ljn<5uo>)05d?{HJDMIiH0v+qF=*2 zG>cOOrjWrfKQ%iS$yOjge6p#>zLDCpeeLaa`i+g6`vNe2Ws&#ApsRZ#vobkK(<$_G zh~y-9Hj24rl_R_??CdJj`Ry=#)7hfNQFp+ZLedOs-aTF}_|~o5Ezn>s;G!pbk&{@M zT6~*W`4IvAs8X9(5c!Wb%3#S>_oRe%y;ou0R@awL0gzROETTRHl&!iC#!xs*n zZ6k@%+VazV)E{2k{pv$-hdgVXUGiWxnrbZBtGTgcZBet_VAlXk1WWKI=;iSe#EuzW zpUTMrkV`^0Xi&0b8dZX^?D#oB?_KI*Yi{jJJIL)td=4ZtN@SOQB5!l29el{xuMUqu zYa9=VyghU6uQ<=*0TG`u4cjvTT%6r(3XCD@F~jh z+koqX-mrBVVwWu~z^7XX<*H!xm$IzW+mSg)Tu=1yuSF?#CrGykc=LXSl)Lr6gV!MU z(v{qL>-ptrryugaK&{J2v=30-X0?@FBV(ZT29HgQ>sIL|sU;p2ig_O#8M`iyW9I9C zSZ%?Mc@w&R`;EF0=3fVKEUFgsN7jvpfjo%=000kouE{@Q)EtYA%Nr_R9HVQFpO$=h zs)-=iS12uV8F@LQfM&@kvQy=qsuxP%-@dwfCa|rlyx&cRHFC>E21*X;#%QM*Ec_iK z$KmA_eXig5ynLob-a@0Ji$vWnH~du~o$!mrQ(%PfE*EABc%$>cKP}AE^ zy}w)JK4|y~Q=)BppFo<|W6sR0mK5Czg#R-7g~-^=j9M4%z7`UBe#CfY><@szlhYRJ zfw0nktRcQO!f7MpYeU0zUC0M{0CYg-aXKez49ICk{=r{;{-eJpRqNt?eqb{K&<+5N zy~!UC*QQv13R{r(V zfBXjQk1lp^YG41CJdf4|=;7S6hh6EaHT_fI(=XZ*RxBnKW@frv!c-u}vH;AjlaoIA z`^-hF!0kZMLl=ElGoDpDrodWAGfBj!kPrMG1x8HFIZKg4&iL>(qhLI+KfU&wyJu{A zJ;yv7%GxOM_WHuf-NOMl8JJpiLOXaZJw)EMdHq+#%vD1*2L1ErvsBiT?jt1GeuBZ+ zxA0NJH@DBf*ePe1;HFz?<$>hn))r4-G=g)a+EOH=s(~XgO}@@(!Bcek&fIiwvRb6p zT(0Fc7>+*-uN#V2dxbEf^+@V=5U&WJxN;y(qfPphddw}~ZtvNXtTDGz(jfY)V!UrN zMV;CxxMjB!PhGoUu2q3JF4BhjM00Mqjib0lkHH9&D z=&^IHu*T-eNt432Du^aWLZPI;RoB}R%nq9r8)P!;oKlR6emiRm!M}ss*<}T*%;v|cVkqpQj%lnB^?@=J-V6xz7JAWV z%d$+Kba$Mh>(XMP;m(7<1Y+)e$1o4p2P(W>XE-K{qX_7@9|ia}-DCU(5+gH}pVb^w z*;xU@?x6bK2CZwDNkp$mU)vp-LW5p20l5~u||4+Zcl#pPEa;X(0t9}m zt?C#>A#l_>I1*>JNb}6sHZkW|t8>yr^-2z}-;<>VPBK=R3p9y=xSI&Yl|MaqHha@W z^SwzK>a1k>X;wCvkaa z!m(@~U@eB+iN1gh&^!5W2pPfvo7?rRRba6aMLwrOUy%62H1qlojKbh-oe%BZV&jV1 zS?!7`rX)lH{=UjXfD{3=1H=|F=M^H6qM*o5sT--GY=Na-*K_AYuLxSyUt4)4E|uK(u6I0(NlDc2 zq0=14C*)^s>1eN-Sihuh;U`nhUIl&NLw0uH+N{V-S@Za62y0i4n=)_H!;Y@LEGAEi zL++%RchKT`b$9_(Nuy035|D2hx&AH*oeIvw#OvnyPz;zUAf&A=mK7QanFVXj5+)At0QKPaiOS}^W_-1Qwdg_$R_LAHfLTFcNZ>c<8vKk;5EN*BX%F8deYK{Yz1Q#>LMXzP01m=7$c0Q7hFWuHclX8&Vf zX`;(UQSm01q|vCi|3t~rmo98kNi5<5I~aIGvq~6nvb*S&Kd=x6|NTw7R4n_CbNU8y4;W<@Z&dZXj`vQ zc`BH`-Wq$0PjU?i`w3b)>&Kli%=ln+wmN|QakuqcL4ZNJS zeqPlk@8XRBT}Dt2nx#Godx>x_Fsi6*NpKuRcDC8@Yvv{>>;p$X{R{433OXl!>qjV< zG3>itl3Kt`=&=z|FSz^ko(~TU4OgNsD5~>344HoE)r$0{qwO1lc8lzM~xN=e;Qgm)d$&pl4g$Nh#NKPvZB zaLs?X=k7O}aWWj%Qg%s9f=>oWbb=vlmvVG2g^Q+ZDlYNMZMuH1WX;pj%)9oOK~YQV zur^4f-A4C2!*L|%(|aGZgLTA2Xx6PMWTuCRGsD%GmZ{FbRyU*Nl8w)6Uot+eZT*z= zdv#rGZ)#I@R+aEH0CQy7j#;3Z#!`K>5@!X2Yx~ju$jPET8UCpRkIxv#c09O&bJA2@ ztMy^`!X5e^ZUcP2_z5fh@xQzPD+$PMv9ji5eem|LbuM9#7vEo|{JISF9o3XenFS59 zynkvF0?-{vu~<5^oqZdP8ucSLs{#(ts33_mS3zyU0+}(qXL(!_^G%)nYNEH{;AsXV zz;CDzP*F(FUU*z;>0ThK0Awajk#5#-3v8<_4CgCRnJ!+*$zT5x5N5X-J_r@NPJ?!j zDuKj^%#_#;@)^Q%UA?4uAc~;y8f*jUb`BvvsuGQ0J}hTa4SG!Qty%URM~Vl})w#3F z+i~V%LRn9#?3KlZP$o7`!2jE4jNgXK0k>TkN>+2_X>l~*`&~~_+wx$>n?B18p$drJ z=@bU+MZz##k;ZXPCL~~tRi!L>3Y zw-kvrF|VbJ&MQ>nSC}J6nKB(C6kWt&IJyu#(4%G6_4OQW+?jgClSdmMfYg>iPJ#wy z-un#R5lH{lX?3>W8Y&rpy?Y5Qw=(4GEPo(l$QA!Oj$Vawa}jwq6cpn%<3kCUC@vLI z!qKRgy!e1|!!O*)^;|x|Z)H5Hk-C1K&>osqy7wdn^{!bGk!Q5AhdBSg>en%N|}vW%3YJwTiq^*egS*|KwnULem1o< z|6d*gMw)>?HUdG*+bKNN<_2=~EU(YAx)p`xQeE~AvXt8i_7aa?-Kcb9+L$G)RT`{% zw}OVQr%s#k;=QUdM_xdv5E8HSSMdOA_0b-;yz|^ZK9uqxdrxBN%G4I;}Y4REuPg`-P%UI=V$&z@4)0TOg=IM>R@<%57Rpf zpHap5jm;ABI;$qOJeqt*j%$eKwbBhQE}-@ep!`~u?{y3NZ;#wo^mdxd0s7}275KQd(7|_Fy{ZNdx;|%H0tY}TUZ_~Zy0%vEV&BYF*F0WhAXQdZ(5rcsdTamA!>UZa@Nfa%Ua*$v-H7vU}_dgJCo*-Yq1}${~2uS=~aN zq8*+)g*10MZ@wDm@mG59;PzlOI47`Zk~t@Pu8d@j+T@NDB3P!?e4>L-y(&q@E|PfN zwP6uxI=EFrr#k#Mp9BQzm8T_%)wV4b3H=^X(BY2Cz_Gl=z+;qsV3>V`Qzi}`Krx3C zSS2L)=ukBnh?hD=i3OW{(7%XPZEjyh~LY614h{ie0mKVmd$TH=r@E z9+-!mJ`pA}qx9ueCmH{MPhW(o?=aGj)FW_JXmJ>N_GJaQW*H8j_J2%Y7f6fTQyq{` zu(!I-!eU}-8G@9Sz&%}fXn_h0?4qtK>8L>HYATF$+VD>svPgq|F`u>N>wdXZz$lZ3 zP>rBXRllBqx0H+Bucp^Iea2Fds=mz_f(NhB!*Bwb`xP}Up@iAi(C*m8d*bh1ciQds zjryYaKxhY9`)Hz21FW@JM3 zKvzvz*~eDX9EhT$H$sNZ+k9x5qd0N4dw+d2j-^>&f@*o{&2_QH5WF)T|Cta>5|fE( z$9SjhkQV^aOF3fAq)Qg?CXCTKj9-WEY%pk-`*1h4RXl?8U>AaVioV}Cb&(QJiX9yt zWyCWMQwCVQT592WM*79!^?{86*m`3Z{)=UbP)X0HTozQ;e82^;xPWACUQ+ra3tSGQ z+rcwR?%svh(3+dvyX>2~GrF&Deq+397wR6W-6TKrX}ddCVQZ_%jghEun4LV^+MlH; zNJu{Ezh6AOlvVf-^2pWN$YVvh!Vid=54eozbSjuss4ZPNZz7%!|B zM+e4_F6>tR#P7d&PM;C-p!TI9eL#qj&%+o{!qDs|z)$7-#qloS#_(Z$!0Yf}}yh@7Mh55#7^Nx7V@WV$Sz9PQP4;SgzmNks+`C2;yJ@y;NQyM;iFqanl8YiD4);*RN&FI@5`%bq&h$UhsL3q z0=|-JrS!NDEH1vShnY1v#dL+<| zwnhLS$e8Fmra6NmAr;EJpf9E&EadK6l%cmSslBXKzUo6xQCnUK$H_^If&;Kx%`7mq zoyaAv<1ua%GhF+AY*dnV={>#LQQce<4IWN*N7})mWXs_D=%ifdjrQpHJt=-HcZdxn zuu%@}b|sjk4D9OV<3u@FrP!KN{g|EgR#gBe9Vj;lIC@6Y+F zy*j!Q6G4|z4R`~CTyaWF9?9s2Ii27K0+JH=LICv83SOn=ba3+tL51ZAW9})<+}?cb znrgV8g@2~$8M+Pro0^VW-goh_OBN##=3w4dX{>F zWsRQ#OTDmrJ4tOlVwJ!J8YlxUQjOcAWm4hTccan)8wyN~plma!Z|Kp3*TD=UAOa@2 zZ>gg&!?g^Wq()QzR$*{2R+bQ*b3^zAvoHH5FJ*uz7&YWDSLwVcaLPyYRZg<(7af>3 z3c-`0jSb%~DXmI4ARd0l&^*uy$ryTv&}AF*y6;3Iv3>g>t>=DY3FMT~l{j))L3*)0 z6weZsCw~2%sG^!^IfUsZsVj6LBZASp^i_brl;OBT&Br*84@E8hiSh)t0*r$SgW((d zAh_weuTgNz?7D!JNL0%Qjqvnec5MtbFKZuz2(;Gxoj}@CY9N3uHZiqG22sS7SQZHb z%EFj-t)qr-f)9aDrTuY9Jmja1@4;1xrd{c*Mpw=RBy*A)gDvEyGk!7zuVSp9)sWZs z^XH{f%K-KsvAby>_2=3ndIr^RTD}(7NKOf*<1z9{*f@|vDR?mSDXcaKwOs0UcT@jX z(TRxtrcP;yH;a|oupF~1H=*eLyEL+L=Pc0q*n0ypTBU-;et# z6WE_-rL>E&Mp$fC?uH*7vBGdlmok5=t~(TLYsz)!@rPqo$p#yrHuFIJ1h)6Bh#vm? z#a8dsrhtVZ+qMl|QEIN>DWUZ|;1iR)2t;Z^wa@Y~(Em{rbZe!36M4viupcA{~)obwft2f_RZ9OTs(ZIDcqNu#*?R z8*Ax(Ki)~gWY8nAKw-telR6bsp6De0*kTy7Je$2TMEK}*i%|7`kw6<*E2x78_x?x` zUM6zdJ#BSHaT%i@1Z*E^KJQdefiH9B;IW(JvbjEl6hG=h2P^4dtH6?FjWWa3c9*HLoFoiPW2Y}*2{x7({-!9?m zMd?xrX#IS&cON6ILgXVzwH9Mfw+{CsFIGz}wI4@EF23az5rCx0Sj!Gn!3M-}?I@<~ zGH&{r1WGYDYjG!^{}i_3^RGXICMnzbVKnlPT6CdHWyjLwwFB?${W_qHJ27omIRq5% zd`FMpXCs&_MYk2}v$Y0!gX(<&5o=)(ldk}NuTo8oF6pc-jB@p>nTbhS_w3nZYsC8K z47B=zwDU^%!+fT`M|V-rK@}yBpw_YyVRJBU^RbA)p z3sUSG+v~ifcCce)-8@1*1+sN;PqNH;N{StiH44jHX?{7C_V6VmSHbM&hbM2NNuIlA zmECv-WKvQx;(mmChT<_mI0+)aP8hs@Y(e_d^cPBh4p7N~1J9OwS|N~tfXkz$E%8LJ zvbJbHkte)QR4EI!80yUdm!Yo4vHok6JHxoYrG^FQi@VFypvHxX4eE_M9Ao}`QF{uc zzG_qrmvnHR4WQEZckDxG50_KAb%K2xZK<%KWGCh*pV?XWG+|exXA?^Odv0BpWp_=c zHYjWDa-BlQ5JTF(URqbrXf|I)^%%p~rl79#gV6iw3PN*=>pZ`9l&FqDYj=91vDL9o zLM}1-94Dp;>M>;EH&ok7%xdGv8eBAd9~tDyF_=)bOG8RDiYN+dt(&5uWO}r@t@NurGZ_K)!TjY0IhC{maV(YV76u{spjA#HH&(zI8Fe$ zU(uomJ;p6E@M0GwUZtA=rY@mkDs6rimLZA)^ztR9^n{(?y{yu6(sw&Qay+Xx+dhr^ z>R4;GtCl!a7uOAX?y7iTBY{liSn;cwU5)yFnDdZnF=F!Vju6$-Ekao9p8s4}&t3os zGWBV=`qn_kPF+(|sO_gGG!JAmpUHEtdSpfm28cvlVM~2fh|=P~NXae?&Uqss^Gbi#=2xDz#8Z>KulyD31c%v zAd%hEjb6)$gxTAca^8W$m%S7F+FdV_<8ekRU8n7Me*Nbb$6+F_zZdag&+>adgFd5r za)T`sJ#oT@;5o1)Tf&H6<8<|cPB8z;93>?X=I|=Zpds}$svl@;{Bz;~BU;E_nESu1 zseg2IVIcwW38V_p1J$tw?PboswH*PPrpD1!1JX?OBC)x;rQ};dXO+62w#tA;&FO*$ zu0B<#u;z2S&)C0iXIEuZkEO&Y=y>QbMg53nstyh;IAWa5{*>GRQH`1KMGjM*74=(2 zDoOW&$`bkZPyh3=8psCtxW6jVozFsAV+ej$!fcOo*3<1|OI zf5m;DKA&S+V!9<>P}K(-l0poRqd)nHWJ|hw)hI24rKHc#yd${C|9iwl?n5`eqJB%A z3fXu)F`d;XfTpJLIV8ovFY%WhNN?~RVlMv+bOS}1fX`evWEg5M#1e+&soiJO`bCV)4dUXMdG&6pLNUBEqx3qjWo#V8+ zE~9GiiR3-b*7~GE-M!DO9Dc8!vwd`CrGm*{sL83#1AE?KlPT|5BSjK)>GO)wmLOR; zlRW^S22Q^AA=lo@XI=bsJ*L!4q?{hDNZX7XrO^5%x+RcpuMrwn`@Rxg_E*2eO z{}~*?71tIpRqu8;=H8N<;@dl&29a>?Zz_f@GjZ4_&2i7#q9X4!juC47-v^(Lcw{2) z<1EW0i3S)C(BvPKziBy2L0~saU}*-oPhXo|m&WpRQ;B zBlX?%VBKSQ#Thl(gu&dGFruOBUwjgDN$-6n2p+elGn_@3GD6rT2v1frY>aqJBfQu| zYMmd}SO-T7JnRTo7H7cUkNc_98K?N;_+>JM-^{i!aYAWW#!{h0I?&{qwO#%NgHyjt zw~K6zTkPZT=ru&MK3iR27g^H7b{!PMtIr%{%X4OWZ}HGa{Z4- zWOvE-u<#XAtM?R0#wkp#gk({;kIA7bdE4aajJXi~cc?VT@@k#`1NU#{0*A6Yc3G>~ zI;NXZa{_wJHLqV(Q>njL=#Q^`@=B^({(zI%9+y%vAf=e9BRGoMl^gMXU-30^y?$k4 zq25}Wp{tq{W01>m*6$XA8%VZ{Y44DpXlAlH>THcF3)pl_%gme{;sxS`{NCK%xO_~0k94*y9^9$2h6!Fq(k)Gp2Y@3rvgVixzti;gE(bh}eBkU5c0wH=tB zJs7O>J_EIdQ4&zDN{8<|0;J&k>jM@EP+^c$Hr209FYI`JolMR zPvwQH{D2~%^#wdiE%sV7TuM#?58{cWctPL(9aSl6k_9;va!(J&>-buzM?Q3r$oot2 z^;5A+Nor;yGrab37hAN4p**5X#subBu^EWJ*vSJF&f zFz%on(i~yt1;Q@hdjLuw1#gwO?Ex#{{x=S><@7M5{3%|+0i!Wfc0cQ3TP8#T;@#PJ|A-il8q z7mjfJ5Cx9CQvNYqG^2dH>^8rQ+!&^23>@TevORXg#AU=q!_$l|tXmKl5yxn?khEEl z1fo@X(&sCa&XW-@*N`ozBLA9&P|CP7xGbyQNt`|RmbC$In2qp9( zG|Jd>2b^NgDofHN*5c@)IZiC=;u>v-D~hNE5HsIQYa*evDN-;0_4qh>mU7U2Sx!Db zPp;V4-RbUebYXZowaD&wc$^<4wl-njjL;n@H`Ue9&uG5F$wNw80prQc6OYpF@V`{x zrQgO>KcXPf4tdQT;mVwAY1a9qno9WN{K0-Lz%LfJ%Me|$>4G^wcN2H0Q(iGQSpO+A z;-;_6_P2G=&dFt0%NU)sKv_rt8|N9~FOT`_lg%Wp+rzDZcZFkGc`etu?BWUJ*((W? zIiD+F{Bx6H=?So<8p1D7dlzS<^0dm$8{O_>M6~0#OqZ7Er&ZC8qoub6%JNSXJl5VS z47Hx05kbGz*Ofc(k1W_L)xcwiQa`!4TLDBq>mZud{nh8w7iFQM0H_e7cgzwlQik~P zivI)~svyw!we8P8PXadiH_w4;vFNq<5!#dwTBHEBf96IMz)z>};zFYd zBdpdfU%O?s(`L8gQ!)=I#Hj{D@s|95oH$JzH2Q{y3u0DBF&yF1ZJ*RSq&A`I$H{4O zYbQ0+WI%lCqF=iROkFRa>`(Wx8X3T&EEhI=X4V>ECSRIwE>5GMznYPP$`9ug;*q>3 zHysk4q(?DvP3QV{lSTveU;G^9Y7nY)k_B5eaU-%_E@PKV32KIjmf+nE@dj0P(wp0E z5gnq+uaP@oHbWp=@+2)7Kb45@e94gp%qPwn*8pS@Ex7FpCHO9JBUS3{S*~CJ5A&m2NorI{fPJ6&1EHb` zcuSofQks}HB{uQrr|l)76~424?q9k0$uRe(^tB{u9%NiGNjvynXL@GoZgiuZjeU!e zypJ=I_s&a$0dlg=qIs+JwLbeN0k^Z5G=#4jF=f0wxA5(BY=)LyoyO;6z5MEAqmtj1zy<8nt0RW&zAR#w zj3h#K<5({-)jFbe^G&<68@*f!XBPF$%U5X+=wlhE4)xtFdAbeQw+XT^q$gvole4sDd%gp zr1f&P=o}`@v>&etKA9$o;IY7tOPaFAUIrB9$}|652z)=$BgZyq7h@4gj;$}T%?)-g6NYymF3Ig4 z0bx7M&Xk5cIkS#79`?)tm~-5p!C5GlGFI&4E#kJ@<*dd-E=!+%`oDw|a|bqZEL|We z0!^ym!H4Sbbg$$-rZ)}(R5i3ab2F;u^}Bo-B|Y zs4`ixt;L!*Zt`tOhg8#nzP9Wf)^C5HzL+q2h3&2sL^allgYsw-h~8E^lqKiuRRq?O zaHP?31Ub)_yUhxNnS+;C@!F)=pk?DgT^{U9p2SyTg$ellj|DF+*~q)73osS^X!IhW zCWr(A)ZTM@?3HPwKLrEv2_<>bE;)ChT`oA~&+@CeRoe}q9u27nov8qNZD?U(;f>Cn zggmMyhqE8ZliNoLeRsM}5(*R9%|hUDL+p)EcN{Pq&3(J4Q3f?C{sjpb{cJd3kH4wErKsh0_pQP^cP?2+Ql6m5myKA zz5AlY_8gd1QlGT$n4dS#5>=%QentMtB!Oy%Adf#G-_!@GpY0@iFhGF1$QSx}597zQ z9(4;q@=#*%>&z&V1U_%^mA#MZ*J zr92!V{Fe()2(=4~#+L9s@muWQ);n%bYDIR$V4VUNe*5U__vf>FFTij|iXj5jFNiJh zjf*m2y&)u}7Tp8xt%cTP3kEdw&ABPra!UYtsmrg2cJ$WJuhPC zqxhgJUy&-0s)!g~uJ&iknfVyPqVy46?}mZzE{Q(5X$lVipv@*1MF|PufW%N22>}I$ z>X37351hC6%<0SAnxA@m^Ca$Dbb|={&8~N9sk#y=n)MGlJC*qvg#=HOIqb|YG~y|gCi zHv-Cl8v zJ(jWj6?p!sdWbW*ttW5DC+bnZ7BSEL^>xQOAEFSSnlFH;gYRTp6V-IYcsDw#iQfH6gC^_y;#VPnF(WnFhaUf`0Rhd&YVC2u>F;$>%&vmmmB_RMx;TO>`J5Oj2TnFBZf!gPWh32Jq!;f8&oWdL^?^ zKT;fkoF94GU|7g&2jEWj3EOoJKH`RnP0$D0SUPr2&eO`)NuA(%bj_y*Bx;W>593M3 zW{{M}PzrD^&Z*i3$p@=ep-*CJ6yQ-GXSExvL)LUiv%4;BSq4$=>#2%P%%$aV{aDqD zvP|%zOq%iH{Vpn|dt(sN%qVoK$Uv=+tosc}?TEc_Y@=p4^8BYH4NP5Gx$&j?MnPF9 zJ|Bvx@!z@30jv}4=-S$rm+eUn_j4~!-BI`N2a{_h@G8H?1>pSF?zDCrE_)&VQ}<iGi<$#qz3(c$39 z5n@T{LHy+c^#{}S#I{wP;1U*6rDlc?MMc|QH(=`bnK_ans@W+-o1|cTMTm>G((T5~ z1bm5S52}D!0Jf;0PXKJ5W=RN?gn%#E1oubt41h^R+l|h-sh9})2|0L0U0_h<3o87e z${T5r_eM&B7u%;qwK37{*^htDboM;yw??v=#?wX@P_ef4_%t6nLlyz#ZwIlgrfQUX zJgg0_PDb;T9Vsrskiq+G`obF1&hkJGDFKwF;z8qp&SGKrCL827J~jY0CKu5Ubs;Q} zeSgx7yPYbbmbA4lmYw^>xSYwyP*I#9hBU&TO+Or9bm|-OYv-D<$-jEo8_Z>z3MV_< zvq?0tJ^-K0ZV=KUxF~X(J*bO%n#hgEN0j=_eodgpx|Xx7Wk)rol%S}`G^%+0FHB&g z_rmx1@nl$Njg^@dwB*rUTVd4kG0n&ei?_v9b%$%23T|h&SY!TnCsru@q+R7D2kwc1 zf@b5YHN>DYyOE;MFW50S2uM&K+EY|m1|wk)rD_&bVU^r)F0JC?d;L<r27z3s8@Mc=S~>MIAglP{fCN#!K6<*~;vpWK-X zU>9M1txriA;$>)adYwzu!BkjJ4Ao znKP&=4K=Ebj5=1ayS(47+jF4Ls6R#%-)N_H3W zeis6tR+SxgS{gRF5;i(1n*?<1QhYS}1_mKPbf@3cPrkKzh3qKc z8U5cjoddfX^=Kd&_lKML)VQ#aP(dACEajK7GT>%6L=bCjECm#S^3Q7%z??Csd(k+Me;NcL^g0+s93Hep5(Uk<5h@Gy(R#8@U z?fKz2L-k7ecRX@vJ`3I#@RT`pc-Y?Em*FXU|J)#SrsE`f&vlANshJ5(q`vJ!j#X7y z_-yEnfQx)oIEhP?+K6R2?K6|_NJq%Js9hM&Qb*^7V7OQ}<cUnWa9L~=Ih zx`h5Sm;lY0EL>LM+yoq!urcMCd#|H?3f_yBgrxjPU!bvZiZMsE|LnRvvk^u*L5-1- zxXDS`>`YecY~HqC?2`Ytm97L?T~x;=g4o+mKlJdSh_O&F{F+An#-m*+4cWxex*9Wi z0tE7l5vy&M)P_K_1!5cy-1x*uFN?ATR5Z(KM>x9El#Q+ro^KjLC!{4BvJ+U7 zp2+O$l*qOOTl{vq(|yLs>DyUZO%y9K9cHcqGH(F1C^9fBOo zIr$CJ%(w%+`5ed7vHF~?fD26KV*sky3`K$1dK1R4yjla(q-Y$0b{lCN(T7G z3#Uoy*5cVF;VRqJghJTet9GG(X>pi8SsHEg_}1aTRUn^$Pr&O6EmA8WcVxEx7w-Vs zCF9*HsmiBJR%a1qK;#&aYh`8S0B;WjnRTzecB5nPn9?}5Ixe(oS3k#`o0qB||1qS@ zeH1|vv#p5LR^M=^GdNM$MT_9YLWFt+3fB_${LK6Aj%G>kU8saWpnKcTpFa^>5mpUh zsvu<*phkcj3>h_nH#g#9TT(-FAw#I!|KEkmKdzDOi|GPbiv)T_`F8mIZ9Sy{xRG(U zw7xc97*^;mHY(@MvZWV$kPY>xi0(H{Rz$a;E%bc0*9Xm7yJPoBb<^wMT(&xg%=NHDN zs9AfeK!BkG0gx;f%mpH)VCG!_ZIY@WlJv{wH_L6WFidS=*X@gM=xXs?>J~j=3nP0Z z1+abc88w2~ZmwDb*edSzTlz*uizi31X<1n}w?C150FDPcnW-`dnJ0rkl(OFZzFY~C za|ocUj=xNbW#^xH%}pTxP$Z~2JsKNvN)dZOkp;2D~1MCEwOj&*J-3)(z0zAMXXXk zs-h1Wdz>%8uwQD0!d3zPj$!$G*_ImW;09H)R9X?XBrZN5{IWxrKF`rPoISB8%7R)xg>>bywSf0PLbJ` zK>&j??g!Dc9$!D|B-i;4QPH7hcT&YW$@D~iojVwRa5CrT)P03E+mpKmnVd%#C(ZUe zM^JUv@fP;_EVOJ0*c>Dn7Kv62ZSI$Utqd8C7ou5y4(Jceq}ZYl?7y)10VmG_?My_(okb2lO>4mTIJ_?hL-?9F%t z;03j(gInZ>gXkdg*5l&Vn4_a3RSPcGg4q=Fi9>Q@>ny<70#(7BkE;_MB)!X4|G5_` z_aYBmln*33U$8o%txx19sOKeqMx2%&rK9~RX3x(EZGKH~U;lYptE9CJn!(nwX0x!vA(%ro?|;?-%+<&LKbz|hnQzF8>`y&7oaS9)#z8~iAYi0u zK~fFaUyL617hxcNxKD8Og~ouB-fMbq{UvbiA(E@dhYx+%ZMqcrc034>)yV?;&Q>FC z&0oTLhzA3>NR;?@IR!o*?R`^*T7A7C3Omo+|4zE~Pn%$!-x5+^Z+hZ2d+1l^w!R_+ z$lFIG*_OuTj!Jh3#}vN|!tj<|?BD;+Avzmb?u`TZoEwK+Oa;Q?=?V|sByB+>_v6w{ zL-F00pvPHt1uV9`?0Zzls`cLWpaB+%>bXxGWVBBl`5Q^`PJ6P?a95ecgvsdKIfK{S zVe*jegT#>7LuY|ZiYL?!GbSr zn0E(Q3O9pG7rh5v!V3$_NlDj5SWVt_b9Vzfe>uTcOeLSvCdEt;4qE4hQCi3W?61;D zQu~}nMT-`(;oIJU6zNWe*7jR0iQNaPgw+3!wYQFnI{f-YVHjGvrI8S6P`bNYN>Y?g z=@=T320=o)LsFzWN2E)-bLbel?ib(p-19r@{&mi|YgjDSngufpc=ogRXMf_ptF7MD zaZbWe+`DT(+@+=C=ZBhgd5Voj(V#LvjBLh9v*{5x%Nl)aCH_FyGHxJJ$t~Bi zT&H_{93P;L?+nzP%VO5b5?rs*vm1J2k(gYQMr>L;=N+9(1^>cKSyBTW_52I10)h>B zSr7yzd`3L-InWfB8(lCD+?CRyFpR9BtgpD-(Ym&Am}6&b0&g!5oA>8|+0-oayUT2>P4T_Z$oevje5?Q7uJ-6)o zN>#d!bb7jpF=qs+QX1+8il9la?M9~mHu^#1qs<-g{qut1e=|h&f4JrHAL zXZzxpg5Ww~fQZ5FZ_gN~yc)!agg75iF11(C+#@bk!b(kik%3V2lUw;q^?w7p2H|Kp zLSFH&+GtfUC(Zro>1hRW$3;aM`-#~rPM{E&*_7-(4g4fph(cT{m2!f3rW|;s1c(>8 zNp+Nb|E31#AYd(7-@Aj_^e=eusRjTmih~8(G!p6!=*0Ea!RemGn%q|&fMJ?6&&nn( z=HQVbck2lZ|8w_0Fs)AvT>-AsR`h^u=cmax7-RhLu+|5N`aIg^>h#$xXG|=p$d$1{Sa>JNk}MCcc_T zNlBNh;6!KAB9!y?_HelkiAU%0#_oK#&O3;T=&{ad7sG_re*_M9*w)KpZADL-`#7Yg zC2m@eN~>C@&|Q)SO%FI_#7P2eBoM`%8b9x<_qW5n{OIfygWHR^TPv6;tdD=MmL(b) zNx~6+%TL+KS8G8%3K3Q`_0~^XBa=H)?vrCrMqEQsioA3__%nZ+0Qlmp=W4QdxKVug zsh`g8jDLm+MJ}v|*hSFOha#dy7g6*;Mw0z3$uVyte0)j&9LY){t)IO?JXdC9sqVi- zS3P5ruo2CN{J!U#ufa)6|3$+U=+pN;Z%I6F7D#A&Zcv`|+OmbcvLcUKkl*EyTlAt& z&D8zjb=Qns(LC@$@G^t7n#D<|o@t7@2lyu&BwHp4$fy#D#07{fSko0o-#-4?{Myjv z!)`upb`4@y>`Wo)NEbtfyY(C_iLVxlq3wGJx+>!&JoNujlRTRY8WZ@iHC5JCLpI3{;scm8yKtTvd+e=|2p08 z#yW389di~JIyR*7%C}Go3mL(rBP1C7&Uf^TjEoz4=;QSU_K4SBhLg?HJecfO5I25PmQ6W$k!R-B0!k7n7^fuLxNc2GxLBf4W+tG zTjKjT-V9zHoutv?>5o=s?UmEdt=w;RWY{gX)mG2>#KLQ~*#lYqT9+hAHJNrlW;+U8 zuF@Y1M}n)4!M7w%BB+ZF+r~dGSB0yz{zcWt^C%yY+-ly6tFuLUz-Xi5=-H>w)DP#_RJ3v z#^5`ohiuG8=aM;ND@#hd@3BD^W^e3Pb-IK7H|da^#OEF7i@+_uH}VxkcV^2q>sU%O zo-u*PsA@Q5f+M$uXh4>)f(CfmWfP*6-zkSHbTylGOXqi;?61G(#4%isLoJ%fuPoMf zJ>GICm-6kGKsE+LpNJ}s ziSuIa)2&_y66CVaZg^@UZvNLM0w@(zU4)7LHzoh!^vQQ7_$1o_mKBzhFP5IXecwm| zEd;R9eEu{{9NqID{u?GlEHbC@fxuLbO}8hWgA*y>@m+a+cHff<6qCHUF+EuTQW%SU zK^Y3X^6#FAn?*kot%SFCdCT`kE%(9HrhX2pD+ZGLz8878tu(l3?tF2g&!UC+v;M|s zR!on8U@&3Bmv1#PQ;6c0hLTnq$N;*fE=r2WYO`x5Q-Cf0MaT{oV7zbaIE51#Xy2=f+q5uf2-=0V=UNhE{z@#>6 z<5pGWM3KyHED7ihE2+^|2HemH(*ociRlv>(|- zpwpV@t6mC5##bO=f|$&-EU2`bX5DIIW=wo=Z62;k!A$3pr!3j20xl#M8`{Zcd>ciP8eyIoR6_rx^EaYPr!T2_p zMUB@6CPTWY3l)=UX5gMhK7u5!EGRxQt(AWc(3b4WF;~S&&}PZZ06}R(whcFj^Lp>} zrTZe0Z7Ng=H8%V}FNp?#^*UkcR4JUz%U{5q7*8HUvnl`~Hf&v5G;7f{f@xv6q1qhn z5-K=y_D0N-RgbbkhMYD2#1FzSf0#5MFX$bi^dMXR<)jnlM&lEIgU2aemWrUMf4cv zY#2dCBA)ja+6pXkZ~w9ZDIS9(BMP(;%5^lzMC0bkY_GX|xyac;+|LH*XJ&zH2XnKV zZ6J%<)zDyOftW-g%V$e{$kX2JX2{Hz{EKnl8z#y9pI4vV^7%Mh*;HxFb-3XtbNCE2 z5W+g#FrzZorQW{NZb&d3$Q>5=6GXH%!|zc2DEvWK?Y%^%Pyis;i5>A@Rl4dmxsw?j z9*&{gwjkG;bgb9MH9e-0e|#c&OWcSsmqeR@pSlA)Z;8t%5I{Q+ry>AAXsR#c3bPLPIP-m!3)o zK$wq?niX*Cms3b`KbR)yeMPefrYeK;9s7y?+4j$O`v(G9>+VK_OJPLR{9`_MNCXT zUJ_xN28M*&5V^RV{r>O?#O&e)8m}9~-LlF6x6= zku29tPG^dTp5rZ*7fo{v4vkKVQkyPQ_yzBep<Gj4Zp|-Q)B?UVcZcs9vMnu7@}w79kr*s+}k?OH&)DMo;&D= z1DJHh_kZ|!O#oF}=?NzouPg)!(R!1;Ub!Xnie2$3T9jqnQxfXK$nkQBZ0BJ|o78>v zjSb=$=(XE_Vb}eUl)#r;R=V=#S2|Qpny&Lv*mL=%U8VrP_Soq2HvkxJX7Bd){darb zU6r!3Dcl|^3li0Jc%zc0RgPw=Wb-0{3fZ5i_`nzUI&sFO6*cW&on77R$?6>!d)C(F zeny9edI7*~*IA94z_=ryUnWPGV&AJixCM0x^2OC`y=5&G5W-DDugW zljD8mj_5y!5Mbg5F4?6w6X6IL<3}Pk*#6?{REBaqp zMnKb!>NR^X4E~R?{<>pFihCig5TGFe-TT#|)GnUmTX6~RXtaN9hM3R56U#ngF+Rqc zXGA`+soS+7LGTeJum76nKmYS0@D+0|1a9SG_t!}paSvATb$L1GNk)+G-8wZYhqsW( zPK+I`<(|9pP9i6)rw6>!^Lx|fD#Oti>G2RC8VzCuP`-!)x%wFOfOF9&E|HMNF~tGe zf8E~sElAWr&buq{^x2C*Ev(~KA$he?K9h9WYGEX?5y&ZWe*GANvZH#7Etmy8~ME7imiB z7Psdm)&Ml`JH8>w4dK853y^dvD{9j5#2oNl<^S0zoXa^T#tnJZ@ryr>U;!ZA=#xmi zm!n7xHYWcu5b5dqNUW1791w<}(asigPB0Y_aO8@Xm7d-OAEdwloO!#Ve*Cf(jvWOZ zgS4ORG~=7falN`4%Ygm@slQEGV36i0k=g*_Rmj!cKP{O<((DDz}QP;majNlOr1pmQpWL>4r3<3WS zF2E->1lO)vyXif*P2r8x-cK6vg^<N9Sw_^_gHtM`~wM zdcY)UW_#u<`-R#1QeS4YSs#C8GX>9tjN!wa$*t|xgxI~7TRt_6U6s65{wdss?)>v% zB+zXagKl-jnLztSLK$d4kG_<*b(~Ck$uHvD>lXRcCC^~&^!y53!x)dHf&kOJYx%Fu ztAB}k^^q?UrIfcb?$=%NXyTd6sONR@u-0UPeypY5mtq4HbFf z0JJ`F03;=DwhLPR?f$W)o-TI)|KkU;!u_;`o)5f~_kVrkoS(-ZL4eo>FW@-v+y~3C zEjWnlsI7Frul}+QjZIJryL?3Ibj^RPf81I&Ej4&UwdEY;(9SZv5V8hSbPO;-8js`= z$(ioxnEe|s3gl~s{4zZs2JETYhUs+EB^$XT?W!Y4=Y!!tYZgQoTY6Pe!tS3ab0$l~ z+4aN2+;{PW-MKR$n{GIAH_7eVk&qp9N*`5Xj@8|=YW=J=|M3{q0)nH*&_Qac#KV)+v{YQPJxz%>SYYfZCjq#+96r#UtXG zVva)kZzZVBG<~~>iE%Bj_<3(X%|37f!JH4tt_fw`YH@In2z^sUCf`Vk;0swC94J()!cdXs5(lhjuR9c zkJ}VYGH)^&66-2~(uX+Do2C*jMJ`pBf)vZ1HV|GTB6G=;I&_wL4EZseNJq<}q=pNI zcr6}L!lT)!$g<9E6E+H!af?^0Nb>Fd3qP!8qfx&{t*sJ*o`YC6XiH0Zu|lV*q_1Z7(`%NP|S8 zKHS}w^58=7yRFjBn`tq_xTUkW6Oj))vX9T=+Ncr5?n_2iw*3ybIRyk7(Z|oO$eLmN zswN%+s_d++zolE?QW7`u4$HsBF#lcgrbRpK|8>RV{JY|1{`anU;0CvFQ2Z}q;I+k* z)Ao~KQVx(qW;_v$W0za=s7@}PhUobJVjGRA|HJH||AE=7$31v4SI)l$h68|s`1EZ@ zOvA7J+o-2v`nWO1siXZUU@v3lqyqp6DMVM!8w9b|bp;iND4_cea|~jB$>_hjqV~IN zhf+W8Ip!IZpz$mJ{ubxhJTD=JhG*9_;D|F$PCCc`6_bJmdneu*aT(Ai#avde)9R-5 zZA?0EC?Hq24&6urFw5K9>!@ntigr~}A)jWmeClu$$6qoqwc(8K?A|;Wd7@W^0=#16+GGUKiSwrHBG*r5 zYqq)g_#7js=wnv8ff4JBM;8IWI49$2S_uFxr>)hLZg2d<>is+@>^3u)b0cIs_eSp`NwX38JHX2wX=JU-ARd8ubs$eJx%zHTNfQFpa`v65JiP-t*@0&@!q?7BcYr=F}^>u0)QA-;0 zz`z9cpIb`u zHfJopC4badYU6Hcffu(uqM6^n%jT#{^Con{;jc@l6s|?G2AGiXa)$t-eI0WU?Eurg z{W?_8>kRTPk(N@|cc{9zY39t+J_ot3NS00r6Jz7-Cw4_bbw?0^YlMlBG55M*I|tX8 zo!jUk_+=s!XS36DOr{aDhbuC|2m&h)feNxqud#Pm4t?Q)JB?ysSOIRxUbuzt(aCyP zgWDboF$s0`dvIYP6BmzEhT@kGtibk=I9DzB+}&=*`A%^d$>)L8Dvd~X(5sz1D(hh% zR?T)GIAXMYB+RF*fh0ss#^&iqKTdD{w~nS2hO2ecgM}xA_&x|u5p1O@1|H|3;>#1< z%~`h2p4E%DY_5x_nwa5}&vGW4-sdCkGc`$_W{r}F%bcbn)}QTf0eK_!`UqXSK%XvO?>M)EtPM=yBvo3j$^XXXnJ^G=cOT`# zq!Ex|msD@U+It$HuvM0dcL3ieuvJb>YUx!IyAe-Y@Ae!am<5s&K+YC3!KA}40|2B41tt1od{?>pd#4IijwIK#I`Mr@ zfW*1kw?TzxHV76jx~=7p>6U5Z4~Cf+slQYUH+Rn(UDcv#P39jb@5rctchiUjo09&l zJ1X#ZXmhUYUZb63C-$uLr;UZJ+rua8Zl` z2M0FkA_~wqKFMhRA<|}KRA*1tc=e5UG09#SchbTHpN{C#E$C$7Y({+2Iv~aQ&pplS zVY#``Oap__InXw7RdNtsKtt_Be}gO@I@fad0>Xov=zWf+NafMOuEK!J=}IhxHJN{@k97*8FogtS2~vsy$kb} zqE6Z$sUMjhk{{3grK-8Z2P*xZ9jH=EEYthUq5>35VX=hT>R&+tOU}>9X#1A`Z!S{UAl?vX8-Ga$ArXtHPI61gB_y6ZEi~t?T6?_wEe#XS*e@aoR<>GWF>@89%vF(a9LC|m*20`4#`qE02zkO>q z3ZNnL^^Q5l%W)v2goL-w1x)hPida|^M;8?GLgVjneVUzZXIhttD>%g)5aD8I@{S`M z&0-fg8Sc$G+iau$pfM#v?B>y;#hvRLX5j1+Fjvw%^2?^IQ56bi;z(#POcq(bs zw(P}WEzr#0f?-Bl`5!Um)#SXzn7_n*Dzr2M8xxQv0HzWBfFa}KzNHw;dM2ByIi~Qj z$Ger_lVSdktf%LxJeD6)|Np-68>7AZ?f+8_P`~iZ>Or_a=eBLI7f=gaEwb$5#TEhp zLLMx?{9kSH9D7n0F8Nq3oPGUXIpZ@ZT*&~Sg2sRL+@DZCPD1r365wq(4{-O()#g=4 z1;OR=sO1DBoYT-c)){)B`FyKwhV1pQ=l(Zv>jp4b1m|&ruRYxV{P7O&)9kY~&JaNE zqkaHyO2a+_XO&;pil3O#cL=R|IzK0|v|d+LsmeUSx_Uma2M90%TUK+`)BCEgCtfB3 za4V7oseF((L8AK|82e3jODHv#vS`5e1a7N+J;O=XuQx|{v#+aewMM`z%E9|;s40k< zUWRo>bD=XqW!;=DcC&(ffD1@-ZS{Puzuk-ikTKv8B?69_HIFMYN*lI#;Ka-ZE`2(#Ao)h^-X#K9BJTPZAMyy;) zz|4ww<;b^F5_j#86?+%S(mQC$P_Fr71Uk@-n3z3;K>3BVlD*rj%~3mICpl+j29Jp$T(A=cgJIp*W^+abK&!i{GFD*&b^HLET(k`M_iw- zDgG4TzxsxL1)6vlAQ}w=AW>wH@Um1M*4+i)1K`bZi@|R6fOdm8Z6dvYRVXfLHEgb> zPCJV(39n$fm;U1w)JuS&KWS_0dAGt_VRBDPOubB0eoCR+Ln|8GzZ=3|13-B9YN{$` zrGgB%N(Tnz#Jka-dkm^mk{|Z*T-73&^sL&J`LLJBc4Fw8& z5*Mx02N8Wy-&BhteMKYPi-3T>V2heSfCQT}Vebffg>EANgYpIMa6Pzhf=5cu`&+F2=k3)cXxIbsZZU z^bx)IH;C&VK62gyJVsi=W=y(X%v7r>4fSfxhTas)l`jtL+S7oLTP8Yz3OMgLKp1S_ zZ~BZGlwzu8xWiEOHGVqhMQhyI7xQ;1y-`SY9kQfh<5{0rHK?W$a!<#6~;pRAu5>LkUxB(VE%xfT55Q zAH+qdd527#ui_+_HKHW(WyWo6_hQt( z9v2yM-3V;vfGF&pOYh$#Xg`|tD!InyrNusJlnk$Iz-sutc3BG<0Zy{grwvvdQ!e;W zmUCjF7R?Gd`sA?rN5ix9oy+gPw?!6OoQcHl9z2d4#U3ZFeEcsR0Tt=65*&lOeYRGZ zwoY)IgI!d%d3MfgL6OEf^TlM}>d2SFV|KK4O{5-_!TJ*$qDP(VFH>sYHqD(O})c9xJ<4d9smvB~`M+mj= zk=n_|2~t^Q`R~(4*2qud>1{ljk$|gLz=x(vU8X{Hb~T!0HkxkF{*QPeA`NWU zDgN&H_Z=zD@5l&xhGuzxCB0_zNhglmD@toGiP|kvxREtb_7wco1cn`(#)@IwQF^Dq}F#Y!)kT3H51OG2_pO%A>2K{{OOEt21qGzci zE4Ry!qEupjEtlU~dX#{Albm$QAP>w?+QN~ zD+2r#wntmiYW z!!yime7B*iKDUfegqg&ZSIf5N-oK%MJT}BWZshTVpkq;eL+R$(CFg~o#|Q45hvDn!@?tHn7=QWRaW!!6 z5sj|gW!)t_l06<#KMDbA9t^tnpqT-H5}d8VDX`Ox$Dbj?BHYlEoCkQON&m#2F5-PM z6$oRBrCvM9yS4f|jTdUs6+&$A~s}lsJ%OWA>yvE&mcp% zzjq+2CUsG_=q{FZzI1`ekFbT>{|NVi71Ra75@PFF5WZ3k&@oAqqN2;IMZdr%`m%RuVxB^afi<}=*k>(#Pv7w8>d%Lv zHtwVyy5VjH`ZkSsPy>6)MODmb1FQ`9cQh7?eQVf57N`df)MgvB2|uz0dBPg6wfF%W z=x=}MKQ#vNYeb^EgVNvCHe!!lO3T@FnE$r$ofVa^7u0Q5CGo#uTJAedkh|J6xq0Px zCiXbubls(Z7zi63c5_UXr(>;~1zkP@LV7F~G0$g>OK0Yy&G)2a%bm?)ZNcr2LhX?y zsmPw8%&tfzsjNAxqz5`$YtfJihuZj|EvzpbfX~4*T141pdN>1nQZljg*Cxu>?^r8FrR%5hNWVi!W%2&#_P22B4NO*Wd~yn-GDj_(?8lv)_mT_l^+IwcVf^pSQ|>w$Gnxos z#ArDij;(5Ido`bjJM*tdQ;&SY(Dz6q3c4#G~f#5e<%X#lfi{0@E1RRLp zzd=2!UwEU(YbCQnIBw-i6T?I(2(bE+S3TOG(X2>18p9cyc+v0}Jd{M0SO znI1Cv={;Gm#H*G-ChwI9fBLABrz7c1kLO?6H z&r(#!F9>V^{9SJ}W2J$?pbr=f(5fyUrvJCd1pgSo|F4u#SmfmWm9c5_e-VKI$bkpY z2UGx%!*kkya{~nyz$0$E^rN_J$=_nRpaPtX(18H3MUJnpi7ZKvW8J3HVsVgl65L zh$Y)4tI7={KY3Xys6M7ejq|VIT*7VvOCvvoAfgbdZZFSP;$~LM$_-trImn%Sl#)i? zad8iQK#+47otq-j=OK;KFePNZiQ(q z{=}}|jVl%UHMZHiM$2AAm?K8KD~}2Iy`QGo7&MS<(%W^14hz$XM0mA0ssAj{jnF!xg_A(wPB5AV?t}k+26{TZOzK5e>EIv1W}nZEmZl970-tXQd)1_koWz`DB&3ay ziHWqu#f~tEPPV;Ge*B=JYG?`w+HcA(i@@N{P7hw;>`ot?<(bgU@S42zS^8c4r=sGp zVz(qSPY8dYq9kH4%5y#XcbV_{qbLZ~=Nq?TFXA%{<#sHo;Q7^N8T#_lVqOB?Em_Y6 zTJbDJ%z*F1`SC*^Hq$Q8OaBKKKxFmIl`&YE@x@B%5uPx%#EmC~b5~i25%Qjnea=1l za!ri(twl3@xid%f`0Xnq4fdoSU6_fh$jCWYB1ewlNxZUK-VaOOi&PQnnl09jD6(6c zZ-1DlV0yl!(rPKX%#AGmIV$MG@0=y;w9Eglco4O|n_j7wqw2^FJv$D(GzzX6@n-&M z{i;!J=E4f)RDH6gP`=$d0bwuCTenzIw2X_pui{K*2sT*s#BUp*Lx1~2M zXYI!aLJTlY&lVL_1nO1%s~pixfr&b({}<8}4E3ho{H$+V=9?e%LZvwIR9^3`MnV0W z@=M$=i{m9x^zJn2YRjfyLuXws<4?*HcM{CTk>$2fQq{zXj>T^zI(K6xzlo~9`WC0i z@K*BktASf?9HL0%{h4Z{`}=!3YPBgZ&^b}^dZ6M-+g$rvuJ%Q|yhU99MYc~LtLsR5 zu;H|FKF?wmWdSFL;wBjO$8@?W?C~z z8aLGyCFVdrH(XheC7j^{0`H*G&{r?%?ee*Wp8FZZ`1>&GADO1ox4Jdgj#2$8TZ`UQ zvGMw6o1Q8_F7!6n2}=;1i?N6leO$LQ1T}|F1a$Qgc^v1^lj@tI0)E@?#^-%{>$T$e zZdPAJmGw;D?KX8Kw`DRTd*8eVp$pNT;kCQaqodIRosy~ld^r8^V-cp)Zb{J}ir)1- zTjb@v#-`bsHxY1iuZ(L4$C>~{*kv6R&-oi5Vv3X4$^o$kHybj-iHZ13ez|RW|3;*+ zIqT3nGL7dsCMo8=4Q5KHwOb^4T$|ew4<@2PJ>U_1&uY51&FDv^f?e_cC8M9i+O}EL zY|n_w-9pbucSB2fR@&7yyjkuwo5KhQCEszxxbRnX0PyI@v_T{gb8NRP^f4UoVVS#3 zU91g5gn1-y4tYf*M@D`iDJRefNq0= z+Z8G7?zMYt@o|MbI*c>0pEVQRx?;TXZuZpRtlU1&bTUc*?W)4GFH&tEn`f*wcuCzd6g98qFza=d6Qm zycCgz3Gx|xhVwDMebT>+#eMS@DpL7Hk%8k;N7(*Z?F$lSxT=`YBJq*e_W({>e~C8>6CGRiO8Il|=J7^isO zCO-s%el|W!61^gAJFWGX^6vB9XtL}+0})0t6qc*^BL$TPEWsHhcmJT)#=iPw!cbov z!F?tEh;29f6LH>~@4c0&P|GK(x9vgNi)P%9msA8Oq@}aBq2!y0ZGGfgfHi#dmuclbh!sv;t z*qnTb()b*EPB+!^Djn1EL$aTX%ny3;Z00kRAV6gZLmbJnaY)#zMZK4F+>0%tj^Hgh zq@BFm*KT>}L2%HtZHMSrZF<3E7-~^8O)EXCDR)#Ui%WtbDyZZA&yY`e_w#?>JKcIW zfMIwy7ML{moGDb`y^lSSSYB-Ak|-jmT;b2|6SJK6e;f($X@vLaC{SvWwLIiTI*%(b zg{uMP0}@#K12dSFY;ZM^r0Z5h*t@2;JfRo(n51!j9I%&KD&~m5BhZ=Elo<5uh|Yo* zIR5jO-;LU#u9p)=j?ON!Pfr`!Bi3-1I{+M&`a_5Xt@vIYH$zbtvhvf3cDv(vzD~;a zS=5itn?Q{3#O1#~Rfblp+!;EQDc||tESji7iOJ*q1TUJbYo1QJ_OF2Otor326C&)^ zYeWaPgNJhfo4$GAbgQKg)CX$r0ty3=DIb278lI)rW20rBH4`sKrO!r)K|3>lEsKZy zA$u&{+;?8JuH2L04q#tCA4ukao{fl!Swk|1EDA;? zR&9D0UXIpVjnN_Mp1Z^5mm+FybkK~ z0v2A~(3*+>^F`tF{7d9q-A=q9xME2rf(K0moQT6133kSywxR$UDwEQV&qVm~a!j|o zJ@2I;U$7ih^Mivn#6qhNNo6Vs)M;sp0bdV<3ySAIjANHGkK-(JJZr>5iPlAabpc^y zrP){YOnKCa6aCh-J(w8=Az|y=*LRUoNOcl^3$ykSbK1-PC13I*1T|NY`ht!2=9N(X zpNEQUb<&l!~{M{n9%cWtOY$G;(xtMI?N>MimcI5t>1o6Kgoy z!CRtpY9fs0PDUrR1}XMt&1ky1XcNgwRcp#1@v646jxC#KQrC1Cy%_J4f)6uicT%~? zjf`%yn|-MBCj{sd$h-vlU)zOox=`jO^Mrz?U!jMvaI$q8EV~p?`I@}is1 zGj_eHZrIImgnrG74KSD3H;1mjItlJL6Sip3lV*B_hPtq&fCMADs(2t!BTf-D$&c{C zn6JlL*`j_xJ#2Mk-eTuRSX|`c5%MjdC)DufOraD=iM1SWM%0>5|xnQ z2Qv}&^Sn9jl_bHC)|W&m;!{VZN9cVcU~o)^I?bmpiLW-N+8+V=V+r9rrQAM4xL`^E zZ8By8c`-dI-0|kkebD*(!b*f7L<7Nlx?Dc%8gV;TTr^LynU$xaC#i$C2qWiHVA%~&bw|1%&_-m9#|-Km0{aSZ|UNy31QtEL_>tI zRPcLJdB^#2sE#nB3o%4H7=AY}vgw_Yjl&c-?7sSyuN9do-6_a${f&HOpzmUvJ0XnP z|IQg`dZh4!i*3!f>-*a{%%X<`436qcOj&MjSd33F%Jiy1X}tE|f3^*{e=;=oTn%lw z-b#CS^g(M}uLF3Pa#V}2O9qrUMStJF#c#!3DXSUo>c$aco$iGFQu#m|aPs4?NWNCx z_d`q_gZc($YgSX%s(J%cy6HR%`-90Ap(IMCTM94?5IDD|St_yd^N@gq@8J_Ob@uc5 zy@z_y{V^`zU4D(u#?uvw8Pp_)XW^j2fQoV*9iF9RI{M%Jgvy;TH`Dj4MxdIwI~FLZ zTpV@w`w=_LjT!szU0whA#!~IPE(}YqReb=l76{Bn@~Tv~KH4TxBA#>wl1p z#V>ONjqi#3nd|r-*q0Z-krSzLn@OaBh~)Y4SZOn{k3wUUG;naNkiMDH+~_Wy6@0lY z{8*YRuSRMt0nc4yFFjDq$<)F0ofG*CFsR-?_M*PuiqfYcKe)w+xj-AYT@bX3@GH(q zY(w(=#_c;zfc)t~sz7q;k~Xj)QVK%)e3vAp(cm0hR)GTE`ytO*%@%d`RWa#VeG5ZfN%0IGWPlg zAzO6QZ?v>w=wn4%0{LI9k;mR)ukn7I`qtGnqj)31?89P$1^yC?`HZ@Q(UsbBrs*T5 zPNhM3ql@NM@&HFCi-{L;Qw>><%ygy#Vi!be#elNC%^GrPgg9<1HqI&X*b0Fn=#(4B zRzA$DkiNRwIZQ={Ds-Rmx3MDjVD{3nzGEJ-edEobTp3{5^z1ezoItofBqvbx8McF* zpA{;~ZCxZcq?+?f06JP}AU#cXE}xO|d26&ZH*@KJy5-gQ88T93$p^)3|6#FkApBQ0 zafjtw)e#c?8doCAM}->==YiAH1x5a(_b(G8YV*lK<39Uo{OKPsRJkJ;1{>uIU4Cyg z#Sgnin&{Ob2}vxQLQ-dFKQ}NKv#iU`v6UVZzkhqf>(h!c5Yd0lXJ^QSd*9K4&9A^1 z`(?n8tRDY;vo?3I_A9m$w3&-OWO)q)W0qmQwCUVUS*7RPe_M*S2dgW7pWl;{Aidr% zFuOr1_EQEdcqZQfQ3A?{XT{@%Zwut98_+sz(Ijq2Ss#9+ki@n5&kKS@0pCKenp8Rn zIF}l6T#gWioU~2xQAXT*Ubag^f!gjQu;JzSnL&>LtAoD0Wz+G9WAig8g-g`J^a+0p z$|0-#^7OPN@o|iQniVl!z3B_154sDH`1x7;p$K-U_5F&fz2<;3A<##xx)v5cbppoL zfqkI}%|1&9iFiyklt6QFi;2isBbIw9+I*I2rgmn8H11IVK3z`iV9%{oOK^VHV9#~}<@QFy>uoEDJ9nMUkPf4tsNmDo@Fz_9 zF5UTF-1y%_^6yi$!cLfx{lB^71vc00i2>#I!o2?vm2d7=aSx5#ncbhU$Qj*Kb`O1t zfgz^+zK^@$-@7ozOu6#9g;+jKIij=G;i`+bq;YNcC-xUlBh!oz>nL;FQqRb{qqCCZ z1?bZkN6aL7V#ggwKc0EZyw#fLfzA}5>pJsnlP;Gg*t1+zx5)$T?Z?Ukm%89xOF3$Y z>wE+pE;XmmGOiVvE`IiI3C>t%)QsV>Jt%9kjGg~gLF04b^VV$^8K+m{TIH#6EIFEz zXB9stH_;dIW9SV{a=v@2W98@q0FJ7Tghle7F>OJnGCO7&Ao|ymqf5P5zEZ+FQ=YKR zJZJ)wLh0Af3be|Q_Vae~sg&C3Xav=gbShnQo+g=XM64R#OT$u20@e!ud9J)BAs5|7PmVh%-WG)i)=Wt8dhybL+VQGJNHV><_CJP^|aq2CT zRk30NJyt^548q#)Zy-^;qmNrNMh#9mGc_>cKSe*l=yL*7GbNs)ypD506`7FZA12FT z%lE4zJ4YO*fA_DQ7D*!*NVGp%{sd(y;L*1R%z?9UteB9;U-Z$FzCFQ`Jlh<{6|Vo% zr7m`g1Oe*aixx$NuQ+-+CK@@$i5(@U2kIw_l7bmYjf};my-XpyF0&N8b_)T@jKOxi zsPjLkD6}i&vnDtov2BHYI5{?d^%?G0oJ)6(r~_o)UZ-G9fAnJ9lFuo!MBz5#i66Y^ zQ1}Rr*fIg#y3?T#ID>O_pl{6$jXL&dL}IO>8BY5sRr~y>*Al|_gWST8cLv8_9hr(P zs1q)F)`h9&|Ab(ZomA?GU+akbobbIt&$ui5pESp}I0+8SfKjB{rLhGe=K!H2dtY;?fDY zqf4ibh_J?vFm&85uQ1BKJ&BZ!;89^nz%(kOQgI;s>)i`>(X%=w4(L|~CC=Bc>7i!1 zIEQ%$UA(;H&1c&qBw4Wz(}ph5FHY0 zGqyh=9zT!f-3U~K40iT8vH#&F6+tThvqS-nhv)h0r=iO6AjakcvkS*u(`I2%InceF zKk)v0HQ@C={3}SU=4;yr!EmkBB}+%&He2zV3uygp_fxBOR4ooTP5`YM_sQAc`@cX% zs-If&JmN9flNNV9S?f)ZVym^((()$J6Ay+DB(V|fSUN7g2F#o^g5gE2XLMZD`BBzV(^kH6Whg={q9eJc0^j4SAq1n!I_JNycP zrI8Gvn!t|HkVO5Y&Egn#gpbOI+qvwAEXSEgS|#}bmDjnk$hTC*gs{kpjs!`e2z*F! z(U5;w1pIkE(~c6SX5dN)Q@8F_D#-7}vdo`Tp%MeMoIi5`C^T=ovxdyH|5i%aw;=LI zmvWz7b+2lI+S>%B6UrvfN5Hi>h>pk;k!&&=nU9qT0mo7%`%2j}9_VBQq_v~dd^Ap{ z8gi_i3yo(hI>NKb3eV8sHU2V0OVu)gi)Tg+4l=uPdID&|+NoDG>aV%9$gV0PKUIfB zypt9c3+N1_%vC+o!6+lc*HPA9Ko=!w+x7#$l?hKfkAQ+d6Kx))1brjAqfGE;A@UZ} zMkzYwOOw+xfE+gYs^Pg|hJSdTT0ynpZ9z9Jg4FLyOq{bLjjs^4yJdZyhFkT0lpWk* z>5d@KF0*OPNQwqt(_Qc&QeX;HY($s`HMv*|pUmXxHNF=xh8+HI>TNd+dJ)Ty8zVmb z${E4r>nN>uqpsfZv5JWuufxI@NzvugnW>0<5fKsK4@ZTM9<-oR_dTLTuS`e$E0`u` z$$q}d*@eSmXr9F6{-*w9Cr@p4RLTTRtg5<|Blg29wsl>m=V&EfJ!pbJYMG+i$Nz_| zw+xFi;MRp<=#cJ438e+;?o?{%ZjtUDS_C8nDe3N#?gphpxjFc(}l1=>lgL25f|{4*m2>~Zzj2DQKo!v0`@h&)ta6tAlWY7 zQ=C1JOMj!99&fOKVOPSh`zp2YhVJxubI5-t)Eei7z8dx7e5$Tw2|7<4Cd7*Ok$Xv( z01ljOFy{=ltsp;cJTu_CSqql_mhl_U^(S`wY&ht`Ey*mY^61EZIF%Rs_tps=3F2-N zn*q}`T~s8;)r=2;`thy_ydOL4VoEtOZV|kUDJQDoGgCVRe5A$nvYcoGs)uigl8*wM z3p@KxS?v@Kz9Kz~vtJK~+n-ewpD?81%c2!!ebkd)eC2@f+>x66>W3r@cq+dORrwHe z+d7Z0Zt6n@RsbQg+VCW1fKhtG#q%q9-zn>v7iR%wqZgz$N%8lDqMJmU31XjwQh~R39t)5C|r} zO#iTMRMALLnxPjC=A`9&8Q85-Mh*@uBjgj&pmX@RpRT@V=5OJE(|{5YP+Y9WCy9eiScbW5`(EZp=M}-N~lZ`%g`<{ zZc4uQ=urO++w&yLORBfV6lQr<|DuS8>dV-K13}(k9Jp$XCgsDc)P0HOQu1Ajnp`Ur zL3uv;pox$oN_YcGLE6D>Zl8eI8ib*r>)vd@xrxpya8^AlMhY0O&y=d^YjA}vdW~@I#Q~WJ!AMte6lN6x6E1H9qS+HU2y<{;i+O zzsz@ESE4PiN+2s$7 zIF%rIx{v34(xYhBdWf}@bhZr6a)UnkDxyM8vaZn)qdFtomHmFQiN(Pena& zxJ%w}R3LrLjJC_E851FQ@L62s@VT;8CEb4LgXJA>uf7Nx=L!PXN{UAL)93-{hlan6oW9#Wf)=OHWt95LDl28fw=Szvz-j{oC_fM6dE|eSZ z&xZOS)K5199*XHB@*XSyr8awh`!BVb8o1&T1+gtARJWt;R5XIA>AOxyv(~j$t3Y1I z1O~zroJ$WIabV9HT+848UC+-UIpjl|J8d*yC8ldA`IAu$em`vwPxprAK%G>#I0S=^ z9eos?Mr&_;Zxu27FMY{&c8S0@bD6xCb;j zASLceB1f%}7W1w#MORpLE*)hTO}?~`5GI=_a(I(zEe!+WFsM@)`cx3=(A_Yg-kAtW z#6+$40dfRt4Ekdt=8|Z=>Rx_b_qV_hLU?PoZ5vp89vTPt3%qGL1G=){+@)F92FXM& zG#aT6Zi-C*l}xZ!kvA-^_A!(;-t{$s3+<+1`ulQ80XIR7%03@c`OjgoLS=w;LJ@qG zU5PjsDdJVZ%*`%()C^SMX+620hmP(Fjky6caaUKTj+te37{MgP?_d-r zXJ526;2aowXnwsJW)Kep+LkYt6^zvK*0w!8zx&o{DMx zvC#th(W4GVNT7SQ1O}lYS?s%F3>$XRQPlE2^x$V@a){td&gGDO_#zU2Bmo#}V1YzVGv}{Do7ex>FpDe&iVY)P2b6Ez4+eXYsVXyb&f62tXv9h#LC$-F!GJqwUL(;a#u`h*X<%LF* zK)d`XQ7U=L? zaKPrFTZ3bql&b%sk@2>;zH`*@T+l)uIZzZf5u?!Eg+lGC0&#h~84z806Kg2BS+*%F za`w#$VW_+|AOF%^P+8>G-1junsJBd~hAvq+;pmlKb?zH8mMm7|3RyQJ4uJY?cC#RU zT-Geux~KuHt=YT(J>&j;*E*jL{P>^oEeROkv(Lu&tm()Q@DsTfKuxmp9ir&d&eC|s zQW=Cv?@rG(g*{*iHoTAz81ISXRu3NYbz+v>7wz!zM(5*w8d_S&jULaEsy$ClmmqhC zE%|=&Xp@<)lk%Pq`$jR6*un(!wwg0{@w~Ljqi(U+z%di5d0~AcSo?LGa&ICqV`beZ z^1y=u7l49=I{?taaBaI!2W9|CoQPqq1OAqxRO_k!_pg%%oh5m#u59lIl>LJi9a;$6 zwZyyYw@?tKn-b(WOgyPG#4gawh~?BIPZ1A=jk4^J{xC0p%qJHK;?to>`mYeg->*Oj%k)3=D*QL}3%-9z0u5zc;yGA{yQDjThj28gu| zh`ZJ)GHYOj%n@)pnlZD*W%K)iAn0XG6>ODA9A?SUhP=!DolH|Aj)vJ- zXSVlXF|-bcc16caF{OO(_^lMvikhqLCt|<&rACPf_@L*)%~iz^z)@=8JioEe>BKoOBgg zjEE1ODWKqw7sd=;A{47MZwU0eUeEbUBeBPew6`p;4 zmKHUCm@G@bIT{-LH2w#&#J^uaew-;pz^uzg_td4=s>1s+Ph^_7SLlg4rMQ7``XYfO zV4QlaG>)(6yw{7WWNrX{0E=UMHB6&ab7;eNww&gh5~|}!2<~(VyNI|^qMtUeY8%vR z&;5{3iaPK-*F|^pPV=DxH#+8s*YGFKvQ={w8QKk{5EVWmq(>eOHKoIpZazAqYZ*CIJH6+pKs9z)&Wzko__?ZWghtO9xI{jpzQ9? zl;hKzkG@B2xY^s=>z+~;Wj!H+Mt`t9WC|YzNZqWVPx){laC_{sQNtK6GU7Un(w)Tp zV2*Zh^nU1$ifVtw=eV!q>8@kQ3AH`beZl%>P^&%YS^r%!i_ro=-lonkUk8@)B@kfD z>!No02wswlJ)C#}TK5)Vo5K`Q8Zi8z#>Sh2%#~99{!gd@Nm&$73*;7&tLhjx#3MTo zTN1}=gGjf6`;6_vmh&I0A62`zDt(ssPtG%+TFnA)f5Yv{mO{Ot>0uabjd1#WPSA9Z z=sgb1QQ!<}W?~2g(9T{oQpfOX9K90cQX5tU0NOLBTm;6~^7)8Fz>J-R!Uxf3`Kj%h zDDufE4<-Mf4Dvz1WCN-n1}IZg$MzGojf6n(pq-F8%BcSzvGiqsOaB##VHWgH@jCQQ z4%e!+sUH0ftZy2v`9LK1)J@#3(u;G^?16rm?mYPBCz0dG5AHf-c7tXDY~c$PE6nk( z+*-0qd-p+?QGQv|8GSv;^@wX=%2Db;=RV;xV&rvfL@+x(-a?0TUsfC&HaX{m!{rf( zShQ)5pKrvwBwc)Hyz$RWynJi-_K)WDtL8dzES3^U{!&in#k7xDXq0 zkddQu+@re%oL13&`Ksg+M9yqsU1F&ol}7Whfq>PMhID7fVI(t8FQtPLI6Xn2R!OjC zCIJMOG~Xl)`O_*@W-ElQgvDCC`p7<@3MAhNi?En?mE^p`Xw>>^!s=)P}v zC0>+i?QMbPv<8bBEj%-rk5g&`mwWb@vwrxA|Me_cW=1-Z>c%D9ab;o+5E9pvxJ-=y zoNoFuAn)}k^X!-KJps{3Jum~~eOW>;+SF{!`wnIz#Uiji{1ClPh-`pJbO_;q2vc1TPNs0c=34#P2aAlq%_-&PH8tzRlI}VOfjG_cosh~>=u}?xAkFhGo zub~Xqp644#)221pb3OPvX{hM?(Ag`sI7dW^I}zJR5t8V@&!_ac3#OR^NS_&LlsoeG ze3?=RKMKET&yHgn_qP?y#-nhgqWL(IBsO)x-hB$rEA$`#mV81(F~wQY%cWt8EPsJR zqseM~yPDaxz`bwGi1*99<`)#>wbr0qejI9vA!1&GN%+gQSFxhc>4Ngtlf2ARd{)xg zr#l|GBX)IO&IHg%238UqdvbQCFYO<`qD1sF0usPcS=pULfU8qWn+Z%30=Gz7V=iSry9?)6q-n$Ik1 zE%<4_qQ!nVtT!F<#ZC<7F4Xm%o2W<+z;`6=IAVIAXPZo`Ute3dwYBx=TmA%Ws;@4u z%&DVfB(hLfF`QxyTxbtcKtsl z+W!y6ksl-ei#!zq)k^DADHdZf7yz5LMAQ$Pphv!mD|dVgM60%)A4ZV;8D;O@A*Bw$?9eaDiZc^wTK-fbcRY2 zd^^+79%}TkrxmZg_$}<{f=ntSF#N=eI%y1gdRggD=?|=C3rkP_jW2SMjU8S!&JH<^ zY|F_U*dsugJXT9euZ<^tb|4uy^q=uv>H8=@Ks)4yRp)Cahr+pW+0C~i1qVx>7+^P5 zq`_4j`>b;BELKydxGDr_TjDWLlm^&^=3^)+?<9OW&;G$1!(`l0Xsj)9Vy=u-@}i`N zVE0yddLX~GGRr4l&Yxs^*ocLuO*3y+g<0IYJ4%C9RJqQ9wlHDg>SI;0y`B2B)r+mL z&>vkFwl$AweV>y6-6R)2zuEWv*e}q|A`}68g>;xmqWT<`yf!^yCLEd>~*Rk>NuZ+bj|+0fvh4; z&U(&A;hcd4I@Y(;@IqjOl2kbv~>cEo=WY|BZ^lV+bUfIhfbi*48*I zrk*E+%r^+=JZs+KS`R>A>AS(zR1#;jb()NaeN7aIUy1{6#Muq+y zD>?kg1+viTL_kXV2Rq`ItL+kvQaW`$|C(Ry1oBKIaxzZH2)uR+e@;h5&wjl+J&p0# zKN9aa31we!p^Q%udc4`hi(NDzEeA$Ww1HdBw21V(&+wW+;6%SAU-wJ$~6rz(nE6fQNS1I)Q{O~2PV_ZKZ9*zVHog)EpEoCMB)0pt0 z7X$!9>8G?V1ZIKhb^kTkM9lwduq{Sq?yp*~d;L~quuBiKpLYe`wE!~vcTw)_?+_Bh z(~hiY1b}G?p4B;lso$(r`BT>_fHyk;6@Bt@b#n`pu#UoMtC*=CpklUTI6kS4@xvSw zxwDPrUOA5-jfITu$A|v`w9n^J*75fLNmUPj)G^I%Y9W!Nz0D<0(szE#W49FWP8{Y; zTI{Mj=ow-XnnEw9tgQ(@jR>tPX@Q%_R%r7jejVy*dFRf zOdT|jxQjv9XixL2;&TwvEdeSInbvec&48&-YE3KZo$qMuvH3*~WaS9b zTC2u35a3kOnClsP!UBk~ajN{Xb!!Ph)wF&u1T$iRtPio=0=oE42^}a)S^aIgvB>n; ztz>^Sz9XI!=GAd${|g((Ia-vp_erf-j8y(~wvkM`B4v#+3QeesgT{_oU)$R$t8C-u z1DH=dC^81<;L8d%T?<{9$Uo_gW_G~sDi!2=l~#{8yX~)OD&&+bQ{-u_RT5fBgy3D!(}5`5cYJME+mT{Kujn)@^yyvj#zvOQL(Uk5kv-WY9@IpcahWDd z^RV8>`~F!F@cm!|7Nu645ZU93icDKj%S+lKkidwNvj#d9tEeOUQp9ntuhL4%#l5S6 zB8;DyG>o-Wm1NEZ!fq0UkI)LNe#mhx z5Ctn0N>(WtwVBA{1@IeHwxlrnkGBAUG!=uPjf7YhF5CS>WhnjLs9w_=TIm~OU{vLj_<}JO8OkUr&1kHx=@CM`tvA5oS&GQGZQcjUXgh(+BHP|kiOh2t?cKArUm;PHOU%RTBh2& zy!=LTbqORe0T)8+>w--E=GhSY02*UjfUPF|D^tN|2onjjL+cyTCnM306SO~ z7}Y#GikJ-nI;b3v5^yU$XO9{19hdvF$9SZLkcp!=RGw?_r0h#hn(Gsr8t@b`)ihk6-37Lso z|H|rVw8x*l4>N1Z{;>GY!vP>&%<(OA0)WRAgpDWN7#3}#W--E_u^}hHW&$jS1ALUT z9?k|6AMbYa5VlHOH||eiVT{oW(T9a?KHlD)m#H4Be!LYOkKULsUWD7p+(qxdy-fU2 z=rnJU6nM(H5VxWb7<+G4s?pJ&zd^Dv%Dae&GqAFklyyXE+RqFm1fPPKuimPJ) zn^{J*{tr6v(%TojAm_=_XTq3Mh_zVnMryp-h^+FOl5zd(e1h7gW+HNegu}3chm=>@2wzg| zS+tpb7DcjLy0wA!$xZ+il<%9lTzy4$7^w1v>v}<)5 z2p5TAa7RRZVfjUSEgG%!j3_uwYvH_Zvx*}gd&ewh*twkG& z1>MX9P-758a*g}I2Q)sNj9s~h?)qL2uep$#5wV~i7e(A!Vlw2+F0=|I0E)M*g@!5j z9wY1hCK5cwfJ{DL2;op>KS0}~m@DszTTf1Ii@qbwxf7z1laMXIGn(|syPGV|h}f=H zw{4r*W^K~tAA$q4^j_alWhgUGj-~Tr?_TtZ!J^1{bM)CtUWKiBCtK(6bXuDYMPQU= z{I*<6v@T^LI&Kg}eKEi?c}``_tmiV^mm)=j?R#`?)K@U#cY=U1O|tG7?Xye(GpC_x z`#Qvz?FC~}7d%mMC7QNeJ*T5ZfyQ;7cblURhV9^&k^3i~hh@WEX(W&YRVsv5RSOg% zPr6NFUXdnr&v&@L1p6>%jfS9c%Br}Dlx2N=^ZSD4L}*Nr@5gv8orUoRN;Gx-TMB=& zZL2#x9>3QW_XQh+cYSxGU2d7aDCl0)*Gn$!kc(WslZ&aLY2R)-kP@oNdq65 z9~|{R!3={hCObHZJ~}W>)?f}`KsUtjNIAmAJCB1%e5vIY-XbR8)!XSr-FI5joV;}D zATv`yqg9H)qt3_@gYm;i$6lS2K?z|IKa37M^8D2zYQDsKb~jiPbem_5%QJI7wnJl$GNQsJA=+9qOhUG8@_-{Yci1| zeMTdcITrbIue@Ppf#6FFRnp)%;DxVl#mZ7Rh5Y&3PwqfbO^tx~e2`fjNs9rs5#ZT^ zQ`XzB`$6i%fU??og8}cFbiOd)!?V)jwDLnq+B+luoH*DJh0-+^t}cwi85IJkp@V7l zg1mr>bgk{*3djx%%7R`a&I<8LIL^f#l&jn6_Q9)Tr~5Asy*H9;-* zu_~Vo>5j$tjlr=uu^~X}G1A65*&E`OMM$|Uhed*l*Q`ncP4;T=kmm8jcAJC7b zu>=pQ7TT0+GxX|hzd1o}*29MUk}LfE{Y8%&H?c4=G5@3;x@6u_d~{ivdRrV;j~kE4 zja+j*bN6eR>*uh}wIxRKzG~a`bFqODkV*dAgg^KGPrT0Qlp*k6e6y z-Yizn>{$Hs=mj_BpI<2ahW`i}X8#-aKmBF*|JHlx!z{PTQcy9A%X9Z(;A@Iw#;Juf zN=Qx;i_XhqZko}&i}K!5a-S$0>=f+`oOa|Mw3&{_%Svk8$l2=ai5cdjxoWdHn4G~i zaN2V%#VVsKf{>Z6f2=M*ALI9?6h0<5!mfv9d1sjDy-DC^6Vo!8f`JGvkeWO<0)Co4P|!rG;>}NgF=B+vr%pF|y{ZkQD|n zL)X@$H)TJ-HzNJ6=4EY%fV_A6w1B&%RBEp4e^<}`M;HJwBbSxH{rODq&~%t2jvH1X zo`8ZJ0?qKjS{~*EYbcE0XNb|QdtIv02xWVM!g4-*kamL4Cj3|o9t{5Rl3(;y@6f|V z`g$qI66 z!NU=U8lCx%U(unUm$Ed&CdUJ3B|9Ry-%C*@WrD8I6|}O7JGW@_L|9VY5VDNIcF{Oo zsEI>;sZzj1hJBJv+A={UiznaY7mJWB%8VM&0k&rCdF)f!?=-+BPHPk^k`>2$*T~F^ zU^8Re$$s2S?ti-<@0iB&vnl1ZkH&Yjw1Ev!jHVeAE@*n#5AV*NG`bJ+V$0>KDd5Q@ zb2`iXib&jh^5!L9IV?TPrQBZ<>4@wdb%A+Xk^qut5xbB+(&rW>j5u!V@g?*yMJQTTBRTHYR%mAskGWAHldO;K(dD7xHC3 zMnT%}0M5cDMWC1W&r(+&g#bKCJZ7({5*+U6TQyQF{mUeX3JZ~hTCkrqcTAdv$U}X1tc6z6$4E8pI@4_p^B}Iz%p4r9F+@7Mqk{auVrohc$5(x_rw9{rat7X&^cbxO~X!wBUkG84i!GAS70L?hOaZ_K#f1q-fAHDuSfczcV(HP0n3_HOe5+#0h)AN)Jb zd{DcSMXA&yAK)Y&HvfZ@Kx-uatHbNiiU+7gc`E=xIV91I0u*JyX2HGC| z!UY>HV;_VR3m3{D$N*_cKjnT_i6)*m0L1pr_~`1ZT?47l)ap{!ar^tUJ5_?u8}H)V zMkQCrmH^Wcq{VB0$TS&4q;8ewReS7e3oA&q$1@>sQ_X$^f@qZWB95(|Zd{du=fhkU zel+nTE(R}oC14>{q+>DtPi_Zo)0Yutg7F8u75IPTkBUn~h~zqIY>+%5{V>tH`LPWk z*g@ekt{M>RZu}EepN=D9H}yL1bh;9vF{5^tT&q+1kZULF|FjM4K7AJ3>tMBK2EZy4 zi2R4IHZd1u=nL`t%5NGkIuWq{h`}`XKU(Gs4*+k`=Vr2J?*E+?1AxRyC|rWGJUG`n z$?JUk_sAIa;|U5p3hScUiPMX(Skus+&`m^2LZSE5-re8bVhu~jTxcN#70{QnujQ1B zy(LCNf5y-cWCE+NiZ=jH@N{OT&gHtO=WB z!#~-ChDP{U4zjqOOFz5AXMQ_-Q9}y4o^WaW@ZIi;$l5-SA(T{W8K};%VG-hbVt!;q z%<&ik;!F>Ycp7QGXHGYTv#n%+eL%W1_*Wu!MYdc1%S)g9ja=s0V7o<>)5X;XG;B6M z#9&DaKA;L8PEeBbXrC?j*Rdf8EI?n$r;*ESfuyKTm;uSgC&ej9M8s&X&Ftiwo=AYT zBIg$Wq117uzRCrKn*Hp!F>16HYXsz^R{}4X?J=Yr=F#%K+5Hqkt*J6;z69kl6B6e; zOM|??LDx&1YVs)Vtr3T9dTnTj{m|dyNSVWqOZa8OQnBwfn^*Ju2%w)~8?Y zer2F~Laj$c(6v%4(EIor8t}v*G}epM49^q}KQ!}$0Ca)=U2|OcP)zi9!A}wr5`uhB zhQrt26;J5+Q4_XG9f#;y(nQJgyWwUkb;9SlT24x8#=0Xvh$3;daFOh-qR*ChI;qJO zaNgXV5dt|V`<}|<2i9j+SL#FkU7y;WDb$=HGGafMEV65TPMiXb!RwVuQ7Ou+_uIU)V8h#6DKT$9A(7-3fVFq|P%$8_N#0W5uc6eP1Nb>+y5F+?_O~+R zrH%{C|_HBY18EY?tU11RKCFsj^folE_dPH;65P=CB5rjLi5u>BX3J=-R3Z{xx z6^yXb6A5zDL%orxXHV+BvtQXkB}?fBK71^i_tJykbyG=8*?L-iy7TYB%HTOCfBk--nX+Nr&9aeTk8FtpyoS zKOS%`XjM9R0xYMGec_UpYv6zs2qw2Z&scomne$RJl?>=uLOxxXDV75+%V%~(M`nxf ziu82q@~YV#o6&-&>HbgAucr&SNE->e7ifPed=Um?5;>}gc_U2#NQdy9e34qQTB+Zk z4vpK_a>p&e`ba|2&t}SeNSaKMYV@5d)u18gHE%a<&JsCgnuJE%1oU07F?PZ^xJuzc zPke-|*FI#&8YQtbc**87LlxjG|$LB({`O!maZ9`}ndjeu^#cO!?}U z4v{lNDlb=39=rKyDbC<7Uo;JEx%?Wrf||)pgy7&4gOX2$1X9d!Z6NC&FiMWf2SO_d zI}|;h>5DUejNFcq@yBUm?k@tEGRz&OI^}fb(~TOF2uw@(Uy0o8OUlFiDzNelm3qaf zH#~~Xb-xdxB~3xor7){YB7s3GZGHb8Kc+{t^~{3rEHsQZ3G1Bc57LTc-DR@^Z^sX3 z8b5O)3trn@*0q>x(U8@r(=qMydxkt0VL7@f5Wf|df#a@2d*Pp<()L#6IUcoLx`@!6 zpj=4}V3Q2u-n72>YEc$b+#an8B~w?V1A-hK_$4-XL1_*a8`BPF65OuqhsV9!kiSI= z6>)ER`#cEVIm~|F=~G5Dv`Rso+-2c$SP2U3f*(#7#h%xfS-CSL6>efV3l>yi!!n(? zpZAAbSjThoe=vr>zr3HWqAug|MlrX5P|0E0ie`Rh-cGD`bxFiXW9 zw}!CnSgTZyPTjFA$5a#hN2n#}Y-LLmw@#xl<&6bs6J`k7Tb4^>YqEbp2|E2R$rBMbqbnzmVh_} zh2tTdZ)r5PQfSk=tn5eN+#v3--NKkpCL-h!mcbf_sPq6TM0y^d{xAH>_VHg`^4}sF2X}g)b$~BA z3jtDS|C~*t_mO(f0*7Apq zuVqX#QX^FxkW|;jW(sm)JvO&XN8TM1JQjKvS-j8ZvgyH??iz=B;P|lgaq++0j$gBf zK^Fp_-={*>5U68s+E!{~$AH4<{(^3Q^$a!7%H3`=yHUHZ6sJ#yS#2FW(4SYb^V=G& zAiUXP6b)DZz@J|{LVj2b+&XwXjmhB|^ATo1OcwO0_!FjZxzNtL>dOVWs>#ewf1Ied zsh_DyIL@IFp8W~=ISP`Qf-8y>clpaAIF(@IZFGCAq zm%FyI6O2?iLpUM}zgzdRxvCW1SVQ-kHj+|f-~OWX<2-{%p=|9nuKyh!$(&0E?57N_MGMsmMkiuT4xUZ(XB!ngp4P5)q^iHX8jR^Q z=cGSj%hq_&lgK={l46ThpWb~&Sn7B!{1iEmc~9QlY(<-X7zhOhDgAe5DqBI?teV$y zkscq{bl!Dq#32OQ`0e^%g&xIpUQ6I)?5)-RtS{Jc%RxRRmzc|o;-*t1JZlWHEaq|$ ztg>Y)4HGUX+8SRf*+iY0?EkBvljZOzM!PeDaFalLV^6i*#PUJlkuU8WyR!4~?l9Ps z@Pvs;JlKM{Nb@fEN`@+ZRS7NDkc?QM`CgUhqLpbw6H}Z*8+NklH0!?_Y^7D6{f7_l z1DPa}^1+z&L7a+2oCMfpo(K=|`)1-WDMfG~^{+;#k&$oEZ(?7X0zBsvmqTXsBFzC+ zk-V~smc+j|s%*2Y{?qz-cx)f*ysiXOX~n!yCzaXp)RGxS!yiXoIN1lX<2iW-W^1E@|ZI2V2;uQpFx2O>Ylm*hezNXx*RSzVs z--+Jf+P6Jm4X1SAxO0X+W`ic@+33`*zYh}TsawzRAnv}xY11sK?79#LmvVhn``gsv zKD{ zYz)q3yZ=qt88oWTdI8UkqX1n6Vjdg=fA5d4<@En)+hi z49N2I@p1yu0TVE6Ojv{G2EOtx498DQHs15sHfHc|iq#5fThr|qd z{OLCHsW{#CU2KN21sDA+;9l)Ws`;G&3E9i)TjK~c5bW;G277!FSgvc6D-u>e0{Gcg zPmgz-#f2GhVbB)6rY5co(`Zu`4lklL2{`0WbhH|W*MGLs9h8MQp_rBd1ut~xGyJY} zgl@Ou`8L0Do&0(gqof;BGOjj!`dk+T;t9DDD4(^RuT#Z3T4!G!q~?U{12TE*Q@L) zSLD1Rxi=5T{xN`Q+FX3N2)|2e4moOq{-6pw?*lpktgG*(zCCthu=nb%oDn@23Gj+y z?5F;UI4^aXpeyP9laTkHLvdk&|07Jo<>Yj8_n$sjk8$CD*G7Tmexg9fVHKFs4y%?U zSIKN+!XDc?&Gmqy>d_A!R{e@Z#`-J}aPtBq2{y-Z8Zl!x{X6au_NEUbkyVf3bo;kH zw2S8hGN3EV-+zQ_MXqbGUycB5#n$5aro`JBJ%@zj1*Bclo`N_b(wvEUz}EXi@Rt!Z zSyS1_kmY1Ume|X`R^Qg4!N=*A+`td6_0rAR1!c zy_6Illf{k*7@!4cI5<(HaMlNTI_G|AzCkr>J4S4ufNIXbG)02 zu@#`FdAPDmb($G6{JJl4i#vRCm}+y%bsaSdUjaYYS&8f8jbNv80d#c3wxO+5r7@pM|FciQ{Yg42+-ko;|A#DNH~Yf<|RP~12JG1z8#HxN;3`4KSa;b?`! zU79#!!5{WqBksh@%ib!!$RkD<2{{2UU|N+889r-~IYwF7ha%ecULgE}yQZ~yf+O3m z-J7OUW4!qG!hZSdkv`d*f&TM-&1}Y`{@;vLVO(Q;FYb;TaP0HHbUjj5ZHV!tO0w9S z$oh8(p{|{x{j%aD&EwR$KRh0Cnr^A+-*X!?TW^p2>r03&XZ7=SqJg}AH@p_GL7%Cu zq%h<7&nkyk$PI)~uiE#fDI=Zi+GaP1??d)NE5WGpWig9VVm7qg@dG*Xa#+y$Cy}Dk zDVL;xO=U6fggKx}8V5WP@fm7R#l0CYt2RaOPMPW*Rs-IXYv%4H#L}6GM!fVJ;W6P1 zZBDPNW!#;6%ZU);}rdhaaOKd8ACR}cAX*mU~ zAsqsJav+z-EjPAG23FawQww$|54ynQGjN;MFlJb~ZiNcxk{K>;0}>}yvc=UOb>#%i zZs01Ra73S}mB292hcZUj1#-b3?P%frlXix;o?Bn5Z$g$BnL7v9`V+Ja!&g=eeNTd^ zzZ?I+n!&x#=j8T}Jd7S;L7b!1T;+PGO`&(+{!tm@0Z7Tg;dH3uvd6(#0y{KKh3kGh zo&X{i1$4##Bw`d7(`V4-Dgm>Of&94VM|zb(Y(@vK7yE$iCH39hfY@u%=J!c=zv>0Y z4mj*sfZo?-1rN~svUdO$C)zWsI|CK9-m!hZ3c~+`tWOVjiWTZ+c0Ws?H%+=Vxii-x zR4*ZFdIkiL$`HAi^7{ZK-+hq?(AGp9(cp(_Bxq>-{tjKTz&U z1w?0L1Ox;#0hJaS;XdkUz716Pkrd1hCqW>S*yVW#C?bBiS07RGtnjdB()XQzOs7Ld z_KI>p2kuAN;CQ%~cV>rCMF0tpDNu($AUMal^DIUSUug$UHYLhQp0WH>4`A+#^>)A< zrUXhYPmz_rf0><=-C>0W+J>_=^N?qewTqh=@$QWP&hpAlKkvqf1B46U7ED(Th0&Jo z3og%@YHy?G1_s3X|JA_g35Cly6&Dj%b%^e>aN15?J+l<5vrXyD;11ApSLfgj^n};{ z+s0UO+ME`ok?^wZ^FkBj)3VaHj5M#lOI(jhzSFHKRmaj_NkZQTsf02)+zoK`#cpwm zD(hZ?MipNm>1*vl5npLIDj*cGsD`QjHR_2Lr7*U$(Ef@s8HQ6;5(e6lRQyzLSe-`} z$0$ywT8!sas)_l5Gdx01oM$$QzXmGbR)6`|X_fl%tIzSnt9tuGNzQ2` znn1PR!2<%{n5Y;KE5)>5Oh!6P|H+)E1~!iW44Wxuns!9OuyNY+R{QLkR`TT%QaYas zA@acKEkYl4QQOo-Vnq9WF8ARj+qg*l3pzZd8yw@0j$(r&DO?x>6kZ&oe3yI_ke%#b zdFrS_#DAC?(E6EV)!8XYVqVBzUb{=fnll=HrY^W%@aUteIN|ngR8b~yA00E#Yy_et zZA=Vgb|)SpX@{5HBi2vHxfGky!9Y*1y>`tHzMeD=P|AWA+Rr;9b|Q^a`=SlQxM zB`^d1`~W3APm)n>+$_x{8t?*ZJI85pST_ZSRl07&M{wP|munq8ad}To#hB7%^7RSi zR;o8o29Xf$(OfJq*Qm$52&08II1adSF$C-F63hvf4RlWPO{+2416~hLWg3jd*H;+= z_`g^Q>-zD^1GwO5-Z@yQoX4(89VOecIr2(Ro5X<9QJ`EC;o$!ILt9y z#`TdDZEatCW>AU8JH?X2@12*7os5l2C3UtbwGQ2QksNy@x+f)281tqRhXE{qb1eEc z3*+kAp}!xhMe7)uqh{o?cmm7!Q(W`Bx&szmU&#VRXC`yRVwZ}UPjexQf-%WUhE-NG5zs}h)H|81hzH?`_KEqKKLmGJq0 zxSG7n86W(Q*5RTR!1cdr7I!L5oh_JV)!7zT4Lqya$V@!o17bY!RlA!JVD1g9pETdF z0ci&_gAni_LlfS80vD3ld7Q-ls8PjLMQOCweePycUayOT-c>Nsn*vM3oc0@y9bk{S zxIjWWmD731q}t29`Vf1bAnxSoD25PW*NyIF@>QFluf-a3H6fPS1DlTEk44tN2IlZ^@WYd4C#$xAhZE6S`>IfwiAHVg=nf+5wb(_YY-(S8rB?a4L|> zl|FfV{D9^1_h#>BLkk)Ru^GN5-=75a{JZoYtc(nRU}wR`)DO%JSkCRS%%vmtIC zU7yPorIB!!+F%7;N&M%$BJPhOOgpC^*BszyOLH(RE?HTA(j~x=4HJp1u*Hx{O%V(2 zt@+xhmr0sP(}#HUN?GpKxo2 zCUg@MvJ<$cD;Js8>jtYUm|B<@!V)^3#-plZ-yd+;I)2Dhe{FGb)p}mFGCkgBXbFk7=>m=JlNSBH%)=K3V#sSt2(Rby($w{;T(^u#g^H;HDsF0?Crwo}Y3x@7G zSb-SKFky=0Oe26LbkCZc>C8qf={(L5NpNg4ZcmSh>c}|aq+Iy)VZye~rA_6y>g{_~QNAirh?wK_&mXA7LKpZtB4ni?SM-cPPM|`R6yyrPlLZdad#QEn&1299R5gFR`LHE7rJNamupU8C| zHXo+{>=@^Xr`&8LYrOJ*c&^5LvwtiElN`_VRiCJKqmcZuOW%)&B~OeaKMBRo+yAOM*5SElM>8$eGZg;r-CH1uC!Wop zZpo@8&6?djg8WIVSFdbqV+LAs`u_~gN?GE5)QH+-!D@de!87U=0_i7(Hr-RGda@%l zR~3@48TY)x8N#<1yi1GlHA^mkDT5K+%8c5v^tlIc5;bSec-uknjUy`S7iW>uVmWEb z3tM<4c+0mg!Sz>me#31$mK5ua1)`ppDfYgOdx4+*{;9a;?W8DFirO8lODqb8yp`!f zDR)Ld7frIvmCERKOHh0$pU}zmCdR!}Jf^y@ncWxf1-z;M`aQt(_M+^|zH6rQg(K9c z)T_^9s4KFt8UO5C+{@{w-6ez(s%xmqp4<+U%8`UzEl!v2k!JiKgP<$4{}2tP(n{dF zw{LRoe)@N^f30B)PKfGvF)+tgV}Aa=0yl|(>Un~cjy`QP<^HO0%!1vD$_D>)5h`n-p2$$XU&N$<9^`E#GNa~z44Xk zscl{YraJ8g1+$X#xb)ZdBT?9pMr`d*wz|4{R@S<^Rn4>ykQwKWT?2ztU{@Kb`QcNF zQ`4g4No$12Nq`hPSI0>E^3Oa@$LXJ;Aup4Ax6ICYZs;Q{=Vb)Z^Of36m4f)8^>{em zCb_;nZNoO3wz63|0vYszj3E>ge=IJ>p)js_)7E*41v{2GtzEwjt>Lx*BmBW*NmA)~ zqjy2mGPqoof-szTn()`~Xu?{0!Bhux-~RFyaxMo#0lJ}nn0ZaKXW%O3XdH`AV&6Kq zLG=J~=Nxy5bBv3I zp!6KyYVhegUgRyJ7m8Y+sQ68TXW#4d>j-8rbt^oopkrtw9&`=JtkxvXLF0OCr+Fo` z;N+3!B9j*>OZj`hJpGs{4|Rcz!r|(cUX`Ry7l_H_e1TT^a(%v!Z_y}azCpMJ2+N+^ z>PAE#7I>JO(^)Lx7bUAuR-Pmb@e?Y++ct%~PMNRw!DLb-*q$G% zvG}Ck6jGk_D);lCuFHuwWBag)R#o6bIj86lxt;I1UFxp7*=XyRRWni(TCEf$G@&*& zrJ;XTHzMMe54~SH*UTkkBJ&1)AGSHG?*qPYgM!487W1JpDG~Cy2n>x+8134VAT`sE zlsx*FbL)Xg?qYW|l|lRhjZJ+0Ta%#8Gb;to8Mr0ftw#<{y+I+k zOYz=9hOa3Fjx|kwQ4D8@bB-wbZTtUyp49hmBqYb_qYvv4_2ZPmYaUFbaEa;kdSLxpAwUQZUn%-K=`QbMmIVSN&Q|;bs$N zs5iBij?UQgQzXRG0U>qF*vp%;1ElU}hVLq#O{oW4n_Z(POPG2|%e`;4Ua_jd!wCPX zwTV@g*dQ2i+*sTD!!RzkgU$HNWv4vOYCp3`Cf+GE9J;G}Uo&%m54ciXe9gY}kt+y} z-uiObZ^vhbUzyOo;iKUq7OpNg_B)?eRFkg zwIA|$ek}<@*3O52l$`^vZ=$nOGu}{+sdebjuJB_p)RlgPPtsqg1y(#Zm|J278&UZY z@vt2&qP&da!k^l%UcCEYfK*yexwZ&#g2Q03&GmE)#Ij$j)Q$;C5~1&C~qBv zqzV3r-`y?Q!1bCj$tDfVp{z8i$qP~4k&A|P_~U?9x4W;ejFB71w^=o!rd$Yb@-myx zO@(Zuw|KKzF8|6Y6~cBKK4<0IUHQ4cREOsf^65hX6)5fGuJgJzN4Hzg=2{Q@^Xj&n zhosfaARaPwI6fK#H*ok32cs*{`S`6dR^Q6u;3cz^AKgvk@G6FBa^yvF!-SYv=J$og zQ_pk5pbABMrnGet*(;J?)AX_}6MTXTYqqk7JEvEoxk_>C*OgY!c&%@v2EqcYAcjau$*z5xUC>ki97 zK8)<;`w5mUVXL>E+Oz7)qR4faK;XS=T|CeHM6^txni%Fs$e^0WGMHcVR0Ql})gPek zaB>RiTkKa%O z9wuEgO&c@G7(BY94?6k%DRx#u3jb*&C5?jlMFg@sE8ewA^8LMCu5y%Cz`p0o{?6Iq ziHo$H-tl|(9$u4tf@L3jwPLPaWF$7@A1prp;g?1Mq>etrx9Zn=Gs6c+w`oWGE&Q2q z{!-v>?(KZ~>p+l&gX4AGjXxXvN~kP$#>yCxi}CR;cQpC_&}~|ISK*Zw& z(E|VXbbS*3>W$e|fjB=1JM3$o7|mz(BI*8ihpl46DI)XgbCY`CeV?Uaj_Bu<+uaYg z_r(pi49H~P-a_wxXi++G>lpIn4Vz!FeUpPCPFg_k6nJSi+{YeYN@9a~Peb?{lw^ z?#FrY@7(=pBNk8@w-+%x-jXCHZU~A!iqLO6wDOv6gAr(#X0@-7kZd%NRad*^Wy$d* z24^X;r49UqIWM>@r}zW zr1@jY>WVyF&go0OZ#y-N2wvCZ+ey|^ya7%IQ$KoKb~Y0m`mR!t8s3gPMuSPwK3%+f z18$Vmn30T*{`5akz+ZFs!wl;elvCBKDCWxcK&ncvDm;_BmlR_JwA0>S)6=z6~o{)9; ztX7#&tQKet&{f5HZZoohHb6e?1sW>7>YWLk1-%b!a!OuF(U=C^Jj!?ruh`UcbK?hA z7cWlReryw){JpgRDP}5;NXr+17_uy7){^Rs#of^Nw+OKK}Je%RQ_5 zL!MxivYJWyQz;f5Wm-&nMKRJNXLx1FUF514H`n8xLs6%m{P(A0yr{1vNZQ zv^xI7JGagb{T`d!vU%GzS-`B*^!beOBf%D`hl1IaI0%9)F?DhR(v_kX*9|T}zYTfq zl$b^CSh6eqVidQ{dUjfF-#fN~cX7V*lID5h^D&K;3r1>H76vtZLvtS*46b_#0}u@< zZ|ueEtndR=m1S~zBMVGrGnqv)$cADt_%&^iCLx5*{niwN=u|XsLxVWI%|!|eUyx5v zg|jce{2pirCs0&!_`*SC&ZJ}ube6i{e7{` zP+((ycY>~>XLP20%UZ~aK@AhHNmS_`1>K!H54$;LrZ#yLL|P{FoVLGxHPX<~xQ%+f zb{OhD4T8c8puyY$=7!4IQh$?Jpi&xd=elbhu<$!D#65PYl;&Qq5HdK`<@OFQkM_0# zzf^xJ#aITsxw{__#A7L@(*kMm+&?4SQt><-IL6B43ZG{lI1Kl-k`=z~6dbAqb|?>DDds%WeIIFZE6x_u1URD=rmMp0$PKj?I3Zhwkd*SbVAcaaP4EH|08 zVz|#g$jbNU)iw%sZ2tOH9)qhMD?JuP3}mcACre&-I9-wmuJO`QDqP@lXmLg0>aaRF zC8M{mkM3I-g^JWF$8NTx8=0g5cDvAlBk|uM2tQW;Y{M}2+8Bg&bdRTIzvSJ!?6psr zTEc!`Mf(RB?uLlpp(K9|0s~+6sA3P#?i~k`$)7P3`Sp2E?LCM$T_>Ws<`R9Y>J}xy zn&FmUl-^UEs9|AY{gq$IiI4&8Q@(a#WzjIfNv4IBgrIa%x}`q2{dHEHoheQsTy=g+D9rlk;4sUqNILz%MM#7(6c@BiHG z>3rH!cu(nWzsff^Q4`a99>_ZAo+dbA6HhTs@BwQfvF8m>d>IU^ZIn9CT<$X>CUfBe zM|T>@mb9tu_q<|$9fQ0J#c7qRi;H8Re=vM59BPQ(-0CZ%6P@>j1B5^|1fzy}+xW3x zoASwftW%|oJgH`Ukt38A)8voR(P zLO4Keb0agYEe=JZ8#I(1cvGV-*fQAuw^FMmEf`gjd##Y(-PoL%b$Vl40VD^0?2b<> ziV5uv0VskWFaDz#fQHW2drK;?>*#O)l{y3XSEIKo@D@YIXYhB)ALY~6xVPW?s0PZf zspNV%z3k)uQ!=;vRQsuut+*Nt{yD^3cLJ*+zh=W$qZ_s<;#*hL;o@xg8mHoo;?DBI zEPQ)m{Oh6QL^1@v$IR_Ncq?S^nQ3ik|9DzxQh6nD7Kw~0ZbU8VcDm@bk5LZ~Qb+lR z*;R}38{$L%YF|aGGh8;6v%~DKRhsS_-+5!m$K=z>=n~t zDg5Xl&CYVgUK`p+u^RW#@u+jq?!G-(A?|@^^d2M@?*C3GbiU}~9=y+ouSDGYR5`up zg-D>jYq#@^^QMu*4+o-R{oMhvu|z8C^V_PpDo0&1OqeEX$bE#$4u+)U8{>e>8n1&L zfsRk%$HC2YKVr)gnlZb1A2oAcXQnns{QOCfAj44JQWPl5uq$jqbF!(x%4~kJJFgx8 z^30m?&(<>)o8feF{WBlSN!j{~Vb_@|aWOF-*stN9Ep-ie`;h_FkFK^incR97ZA937 zt94vBRCIWF{B07zsQIc1k|H$6*w}@oaj_&4D+Pm`NT1@XOS{q}(iY-mYuNaV%q|M_ z4i5dAUkF#V@r5V)uce!B5G^F(^yX_|^LyS>f=3bG!&8L^61)ZFl-qq2;K#>`8H_``#kHTfG zx;*M*@gTI;E0CL0vqer`%B(#ykuzb4y3%!$DP7c;gt_Tlda1sJz?6G>C7oOvn*~!TS zqoV4@3q5xW!+RK1c~1UKeXiYq^J9m-Pe2Uw9Rz1Nx) zHM7D&tr_2{{N>4O;mbMKkkHA2uMi_m(B6UmZM<^aPrf9oZ1}2d9X@0v>YiuDcqF{e zce7f25T)NNJ5k~XB%iNsVep>0VpCn}DZ2kcjfBGg1!{mbwW2L04b6BKW@+N@Mqf1J zvre|B+2gbGe4^yZuD-wJw@8z|MoK4T#SnS_d8d}RloRxVK>Lo39oE^5@a>)#GX{{^ zt#DS>i_Pc}dnHZ;#X8Nmz%9!~tMJO}cIv(`k^&oAGVFVQhBmsuM5W~p^(m2Wd5%B9_@jtgX*}?#Amw+obeceL)!{uc zn&pPMioodxqWWdD-M*_+0KMtq3hkG8IA%WC`N^)CW3HoPFDr&!*>_%+8U$4DH#}O% zrB#!R)4J1;7RLvev%F0ardtnsxs+2kDZ=;5drsqSya1K6vkz{Z1lqw5d4(5GdYe;p zP~cTn@<4R72Gx^3I#J2Zk(p8kGw|Vbp9IXpp4$ z)bIS5(M5VdSiEPd)^K*Z+Ga~^thcuu$A8D0zsQ8BmUpo4m zmZzzlyyZ&*scfaB?EmE)EqL-Z&)c zv!caLKauRwBKVmX9^?R1vRi);&1*or-w#XC4^Usg2@t zGc21gUJZN=M#+$|t@%Ed@u7K<%`O=o21J=6<#E>sq-LF27e6Jv&{Gdk_Vn_tA7y`9 zJiw&fqd}VjvvG#afpQcLp|IYOHFw-4)1?vN=igWe-g{5JhR5%?iC3h_)KeAI9cWYM z#U-EL>7`{H=17O)%F^;ExqP=kMr{$n;+4vMw0z5_(oNg@I`NfQbQ32EbRfkpqW8Xql4#Frd^+-BrcGc~YdNEc1H^7YQMO1kVq*1Vpf`D*L zSenO;6^b-OWX=}?yZ|R(kw6BpJ30FY&yX7*Jb(X(;9=sGsJOun&&2_G2WLvqO)Q2g zZGDdh`bu@#Ei0WM5?#ROlzH0MZQOfoHtI8I|C=0mm3=%cGdTe>_%4l$E{&zW1on>V zc&olgjvUH;$2ue94`&zgQ@;JA=P%Lkd9wGjU# z`eTBLAdsSscFX1zaboB`%Mh#)8M8s|C*Iy}x?u6xo{0{CT)qbt{YN^N5`3ut8l&o5>xYGwjozXqWoSF=r}dny`uPNUCKU(L0% zA7DSUX}YiE#DIv|rQtc5Ba^YfEPvi5zHsoQd2PrE%CTnYVU5e)**Vo5yew-RMae;P1aYBk0HvEhpH(CC4E3a-#|lmu+QnhK3_Yt9Iy^Za)}a zn)`)GQ{9gEwXy#vfnCJq4;Q$=acKpNslxX&7t|X1o{~{%a*_S!yx3JXeqf6K{^Zre z&7G~zrKM~UvAEdx=6k!0bejYCoAZl{aXKGJ{uX3R#Q48Ck-sxb7Bx2|pbodNwI#Gj z*xizt2)yk6;B3h$*T#@%^92j8VQzo!5j4JHB;<&i%NpJ%BC0Vd+lrZQ@jZ#+RS>7g zyh@pVfmJ%`d{2Pt5JFikfStqt?k0&~2~9pSj1epTP%!g8?dA1T80*&EdMF*nbK3R& z`8^o(B6=eCCfzQcH1Ld1u&rbiEkR1qE+9vPEE8uTlq?c*|$wef)%{Ja%cDB zlGr`$FbNvk4XXnM4UVv#Sw%sK@3)AEs;AnVNXr}0FGSonU5H6Ze_ly&TKb|paJ*te zbj0pwyOGhfzr@@QXzUc)_1IZ>zI$na`iP1C8jHH8r1jx>p?c?$P<32?ctjwofPOQb39I$YRi~?+hDPw5fQ|o>Bld8dFp%z>zw&4}wX=3+ zF1?~=O%(c5eHD&Q4(HPb4E)u5Xro7M-Hbb($?Pozcd$k%D}>=JlkF(uBDwelf&^A2 zW`6UFL1*K1hHxXk-*^aiMIR#;c9JpQ&}|3jWF?5~?t9*pEtU8jM!u2uOP`05hjUE` zQQ_tJJ%3>|UbvvRu$jJuQD5NXTEpqwYO*!?`!&~hU>d!uc`}s_4sDw^dacX}R-$9X zc<0WCN!|1i{NFc8eW%+t(nM0{?$2>_FmzEh$kp{C(7dgW zD~c-E>#W-lCiFONpyr^ssX281d(8o=25rBoS8b01n9}gN5=?LE44WUf{*@Dr>@EM= z5Lg9MP51asGllF51Nh;Mmfe%1o{A!Tebszqx^>)~x6W%Aml7i;D}#>FZmrpJQELJ2 zRXv-VMNrgs-PxJ0f5A?=9&p#>nHY|Vc4Fdb_4aG5=6h)q6QYCV(j4^cg$AWcwMn6t8F z?+ijmIB3X2u-%Uw%THQdWs&@G))!$=-rGhGuENbuO>_TX)UA*j#+@cnJ2m_+G@#&Mn|L5`>+OewCdMn1AqjvB9Xd)v|KD|6dszy8;hFj-E_p*gGdwx+Eu`4{LdEKXzS)K zB+|Xtsir*7k9WJ<+cj^+XMPurrl?Hy?_Qf-SO#qj&`iY>QU|VQ-y%XlVJ3AF;ry?qb}r zu*K?7AZwv=6_liwkLlVwW)#O>sY|1Z#DB_-p#_i0JdcZuo5VqQlhh{p@G&;b0;*HfZDFX~B2Ow~{Pg z4a=vvK~mIIjQ`vg0JC4;LQZuR6&mQY zZtlad=8H@u^=dRQ5Na6^kY*t_H|muoy?F2g!dzuwki#g0HpcALNDo|XH28S-IA-4W z7d6JBO$=?S#9f0fz}or~J0b8aw0UR>SD2oM}P zL013jil?%)5ODwd{4TvFpJyuEs;D>By5T>JFin#6w2WoY>$w`VkVh4tcBf(BP|xx8 z{l4(-{QVpn#`mK+-+eX&gHj7A|IZ@EI+w~^i5-H#h^XAgj;82iS$zP{r341R}U za^}g)>mlFSwgBn(LIO)ZSA>#N~V}xMgHfHEJ9~Sp!L{+EVrw58l1xT9nMHGWfXV$V?xN zxpRzL5@mXp&u%@LoSD%*hQtoLWH*Eo&%l>ABbna}XcP689t_B0}Ov1vz8H8Cr>b>c)BRk1O`%lEtVhbU>iZ zcs=+v#%IzP4`}hLs7HM6Wf%nl#$92>(Ql1O5pD|EXKDdi&~+qHwDw@gFcSMO0@Whe z#-iTHSKeM$SVu}A&3z&Zy9|vhDQ_Um&1DDmm)d&eA=gHWVl`y-&jsj#GBQ3@$+f>Q z_lC=ZhR%H9*n}+wT2P1w{Do-wO}jwtG?+l~mja7~P)26O%y=M|T5fdvIk%i9gs=h1 zfMA4wY8ckwNEpt`e`a{Y>nz}{b5NkC>~1&4VrHc9SzS>3vt?2tr~5d6*UHu4 z-Rnh$*QQLCLr~Nw4}q}V`$_`T4|53I8thuU6{b=~X!NR(?Cg0Fno&W?!Nd;>UdEyx zR*3V@;pcg3K{=F%s*@!G?$B}!LuAT1lmu!R40!I2P0(mov9w5>e5T?T^r8IBsg|W) zxYj^RMYy@MlW;Itf4Z+I6`TZ2&FQ3tgHps|QODjt4c1(fdS@NrnUcDUh&EvDn4Ci~ zy`9=@y>v8*c8@g8U3W7*BFz|KPA3)N0D(5#&Jt!NCtCDn)U!WpTb6G*wVPe7nbl5= zHrDZEgV~7@G-!DO8;X!2105KS$&4GCQZ))6;fj)UL=ZM zH{B|qwCQ^ipdPMPPVno(+wL;gw*+!iOT74pH?$$Mb&fBq(eq%%z&rq@ zWZ8?XilYuAh<`#a1W{i6(AYgn{QIQ(z83ySiEwWJD>K&VY+9~7X!@} zxkbqnHTNyw#|70bkGnnq&4fHx&}?abvF?nGSmTvrWoBt{z&{sggGj=#l2Zn93=Wsh zl>ZO~>DbqOY8+sJO%u=7(_k-y^S8c@ql(x3ggRNh)fH`oZD;hJ%l*8h7A`9i z+QoMxvI;(MZ_m{DuH7e6((p=cq>!t?$n@Cg?#4-{m)6IfIr9zIEb-HF#rk-#(Di86 zIUY`nEyu`6-?=oRIXK@8sWD3OaSrAP8K7fT+iJik!cl_{F0FJ&Ln_9cGc}#(MAIh8 zJ<&yNU6&b95004S1aj0XHboyqR1~jl7rp*y2iJoKqLIZvxzCy~og|<81qm}?HaN#G zcs%sA2h{F2uGntY{@ux#Lec4vN}TAD-!m(g!bw6SZ|81x#{T3G&|ip&MF|Q08k?}< zKxw4}_Pvqd`+TiV>(sMobuJLS9{(Y*PgR)S=-BsSkEDQu_2m9GGFVbX*s>>n+=N<8!tdS)BUSmvPFt6gZ9M(DIV8+?o#u;!tHkQCT_8@EHRj2Y=XCN z0+c_CG7vp@`r=}_@EUS`X-68tF1hiF=Ap&h8G-Co>s(e)1#cL%AKF5!bRM7(^i8zo zqVq3P)|=0Y$~CRgk77u8C-EcKpL7oD8#>Tv6Fg*2Ll3rjUyqGGjOAhPVN#FJOjX21 zjWW)*y@8hzPAY?U9B8?W4uFRx7 zJa=Yv#}hJHBsbb>cv?GsO|~ZQ`NT|Euc~jx9RW_itiJ5%w8;Gype>>u03o1>Q=17H zpoQ3@nwty>%dNx#SFuHeIq^-}esJ^g=a#2{vh8MbY}$Du0SpyQ^!F`l)+r?80RGsU z;^-0O?S*dO(LyTUK8k)+e&oARW-6FYgqi8JLV$^w{I-8)xFIU~@aWDET;r>*t06ej zkTJWfxmWTxf|l)nf|d{5;}@cj0vzpzdZT_0xRIy423^WuBGRF(k^^m_3MFyw0Dsh` zmIPR>vTNkf1#%9#PrJD{lVhmwO+({8|8G!RGyJS{!j2jITFi?+p*N4mc=LE*!h(b? z5M)__zj=1GThDMAgoUSKY&=z}YGgSSOqN!?I#F|w)E{X zBmAYzHY+wJaLFG)t-o<64XfeW$A~>%>fu4TE5VkClgERlH@_iia@7Wouh8mvZvF&s zW7%A$btIXKuron2Esa0GwtpNUr; zWRdJxDWbp9R?ORJNME|?;I~s@8~E&;{!~+&5xvKSedEn+HB7c5`Zw`(%H($Ux*you zVV34kBJ6|)!f0TEWGyMGwhnV3Sk~5Q;K5aYW_q1^mVZJ27lkZl(19>tj5w`cbm8Rr z`ot?)#}84*BX+{mlq?+`nYc00&zA95m6(S@vJ;!QPtCpDUDb&~h(cRS39k<6AA~{P z=SJKQW^*kqHnt$7`bhL%hX!+M8OoJ0Sp|Cq7uewWW*#-_(V!Z6nS!j}Z0i`6;xYY^ zL*AW(`n2Jzu(Eo$@AK`Une~Xk)GBQpgo_59QggNe6u-}3UuUxW8?*1 zA$#(%$GB5AX$H-m!`!f)zULoPgGQR!CDk@O^YsCD8H|W_=3bZzH(2n9^Zp1>spV>%CSDqV$x3j*NKj0qAw&ItC%Rw z+0X(F$4~)O9G+|IunEqw4En~q89l8{Dbqjc#P|B=%j#p-Q4SJ2?RFE5urr%TaCo>LH4Z*2J z)&A$ywy*2m@R%n+lVya55MQo=>s=7PkOBDubxdDwiW?IlQ5kmtAUmT6ht$+H-Omt;I;__V5iWcBuU zqe!)6f|V;no}%*HMzjTH@hgZ7Yq-u>$ew6&vIyRy=fT*lQ)k6hzwZN)%4fzE1XnIW zc)U$9@83rxx`-RuvB1^{spDH)w#H&o)CF-F9ElH-WL{t-LB^1&fQaTLRDaYMK8%5& zS5&eCMeAK{e#9}uk|C5{K6XB<}p)ea~pS4r88Ic0RAT;<|m-7(hay~)ptf!-t^fmh|O z7HddUE^NBdw0sEp4gTJ@nfI-<%-Qw|+i;fH`-?%Lee8%6oCO=_pjVIZ`j2wGe$XmFSPle&eY2T6rjH}BgG@x@4(@5xKQ3x@R#TH9kMaS%1_ zw=d)UY^=yj)d)+5R2yeP3G>_#wZGhXc(MEYnG9Ne=Y>NOKz{?A&jQ$*R(E(ub^;G= zgQ8xU zz|@qqO9ECVivr3^SUQ57z9MiaOZuRTQhU4nxiFyjZQ-^}fC6mi$p!_m<(FCHht!JK zlGacD;sa5Eig!ync>295mH4b9=RKy$2Cxx!kSgP8Sh^^Xb(hQDk2xEBIg4KsYu^Hj#h}>0kO4Be; z7i__t-uca1ZAQ!>+*U!w_=4ZmJ>I{#sU<~Rzi~9}o+gP3$%fmil$mpCg_iO>KQ5PW z$i}UKlH$+s=-NQS^Ef!ua9p!3M`D8L!Q9X5$mz({6`rhp%EMCbuzRNjW`x9DH3kG@ z&+8~8ddU^3r7Vr%)LdEn%@VHA3`Q_6S4sHrl5R!ce@!1auePWxfsxScomd}DJf3V8 z7@o)1C(5A8YSaeWl@XshAn={w{aaW5jmf!~(9Jj9^sB#5^G&(pe?$1@$K8yI4!!~b z+oa0Lw$y(_XfD42>-!fQ=-7s`da*3oWqcO?aXA2QcYVtW?l1h)Z9hgU?`eZi(g{+y zd1Vu1d9N4#H#r>~gm^Am#DIX}NJ`HAzxr)=z=*tip~V-6C-12sWAiV>`})%l zn4D_L$qBKj3&#MOjg@cDoe3aoQS^NMlel+w88KIJf zu(fj@rv#7YhDv;^gQAZQ-MN)4NB{@qd%lT#?l6OsUiy*FP0Xq^N9n~lSU-6Y@CIC7LoFvnZD+4$yQfar>cF0cR^_EK^w@^m!p_OL z?!2JGu3H^ab6EF4Q^)_iCT#lgOnV`=gw~@)f-%Yuq#+EoM<**QVakJW_{ygWFHs;x z^C#D5YG$D2gtKO-6TDV=oeb-UaYV7RvpdXx=f?(ngIS_>H;0!4W~@#;cKc5kl3XES^E)}>d zCU0)uBTc9bc=PHgZNRmrSTii5AcG#>>@6_-LWF5(h7V$_{4m>);%y;6e=4Jnj|tT@ zHjtHlp~bv?!atO^WS!copF*5fpFuVo;RKgBpB_^j)rJJpy47fJCruV-lz0yb* zai^KZRa_Dwh^IfHP!=JXAB73UbrZguT4BTW5_Zj>-%fwIbfPe;t$&{Ho7OfSjL7d( zeiYDcakUnU8fWp#oU9Urxg|tQC!NLb)Pzw@New%vmr%9}xXy0>R!)~Z!~QlckGXN? z+p*ueMQ|5>{gXxpwRRp2^$9*{t)t4@cuX*g;{^YCeemA>-+z4sg@i)H zck8hhfgQ-m;vy+W!{*e$o|`TQ5Ok?{KUISor*8(yY6@PmDQvl=lj5KYcqJ`HGrv4w zXgoChsKQTpMn)pR$H({WH|%$ov!V}?yF%d~(ax8*1*yHXuY?vGx-oy*VtzAaX;C6e zD04osYJ~qX6FV$Q!WGNUIg2t!Yjd|Z98}XW-tL$M*HtqJ5oq6EVp-oPNKo+sME}?$ zNY+LFnv3>65SXTv-%H$kLgco0HKB3@8F4+M1wZ83yQK&oW^fdO`vj)6Sf?Se$@AB4F4MdtINCA{H7m^ zGs{uGJ93%sVXZVZXW6nyGF0*hZ8Yq|G>o@RFgFP%&mm)+2)``#f#$bIv|KtjA4~)G2?_$;H8zRh`UcUKaO`u}>culZ8jN%OT z`n8hr;Fbe69l_8wy5d?)>ZAew^D1=d7vg(htjuWr*I9v81qRWwq`*o#{xe^?P%g3@ zPBk;^o@3+K%OtZ%7OpQ~ubG5qonY)&LUK`l&|vhTB<@&JeRfbRisOyZLQa5@;z}b+ z%iH2AOMQHDtV3Q}gIaybS(}dhceFJTuW?L2nSG|$;d}R%L2Ojj9V2KnM3yAXj|McQ ziIf{}&w&;;{CaY+i&~$dV-SUN*N-&+C5!rCq+ACTCqAU1O^xHZhlb-L!BS-PW#*9e z195SB#Qevynr+px+q8VOBg0RmrAhs#rR-=>>osUJx~sSm1iCQO(9+IA5Oof-dbl%X z{zD5uB)6Z=l>0xl0N<%3i)y-i%O&f=F7fd2^5OIj1LvR5HJ&|FmWkFw)to$h_>e8z zxx``ZijtCYZ8f#wiDe3ss-nfRH`Ybs2~RBfWT;P-CPcV)df4n@xNUs49=^Z7|G_u* zM7hP%dk;*;iyDYzynz2Qk>}n_G#--|T^q70ZgqdTQ1D?R7Ev_L-4BwgGCr6;TVBtY zVg5ry>e(NiU2mUa9 zMjjcaYMF>c7W)BI(f2HKKVhG8-!F5Z{ugClz*>oEnAvHVS$xOc<2Mf^C1=N`K3OXS zN}KGQsl_;$UY8S=7J@TUQ8?psA6)2Q8mxZPQ8d+ol(O2`e43Q9PU z?Nzh)O>a9S`Sejhs}3g+r`d%)3g8a{a!cKuH6>^`tKs4A`%SVW)@zuYaLyYT)IFiYqJ(KXyZqkz8)nYiaJReSutODojo zOf!8Mry!||gmo|{XwHPzg6^Zq7D4h@ex@dG0Br3RJS=IG9Que@bw$MtAOB1t(&ztS z?LB~+V7qQns&oPAMS2kt5Rfh%=|xdNq)8E^HxVH~=%92E0jW|&r1##W3WTC`=>nmb zKp>QyCw}KY=Y9Ws@60`S?o0+|GA6;vexAMd+H0@Pdu=rNv$hgKg^{e;$i)HSrQ9en zzwN!eE;?v)lzsNTIAW<%N-oV5jK~H=-UwnNpXB36HVxRrX_(_s4JSCbLZU_H4^Cth zPUJ~(@)GYCRGutpbJD?%UK87jJ-=0CFTt&1IIa6Md~)Wi}=_@FdfRbw!St1 zWn!9*nV)a1UEbWDu3EfcUI2f+-cr083mBjhcyOE@{RG5!^b_;45)A3zzR3p)z2}qq z|3^Tic?^(}$y|DmgF*P}^m8>>4`oTz6)1tg@1{onPo>2C#oJNYr-8@%;Pa04pO^h@ zGPKY9C2Ed${+nvbtgILVoIn4~H7>lvfToGD&u|0QqZy;IIyFGRQC&+B0HHeJj)P#l zILEWDs<8?}GP`wV^Z6UG*H=oryAyy`^7fdMX?vfg1{+GL73)mK*W`Sg6?g7~LKYr8 zIGeC>f{yc6+Y{oB&GETY8RxY$PukLj9WupT9y%Pt5eADbtzn~~iH0Ke57$y_-^;O! zz^Q}S!hHovCIvXMjDdS@1_G?on+x=sKl7Msf`nJM-P)b$`P?v5z~;B23zBPv>JQ|@ zxOwXI`X_N_>9dbMh%knEdAT7r+(7Y z{WwwsvJm-@ZEAzm)|SqTejY*AhX<~`;+$>m>b89<1)MP2M=(@ zWCU-tTAf6vZ^G5HH1ofwW=^gl`-}MQBMZ{@1I;h709X?8D7~Mo$-O<*stj(zLUP%h z{~wBGe!qEAby$lSl!c}nK-exKp!F3{VI{xOq^d|VDs)r&?{v_8j%o_OF15(razOIL z`6s@Kn*Rte$`>2~OxV!kM^1z#&}9oR=Elkqe6J zCJozij8;Gu*k|>!p(Gy)B|E9)PBcm6oN*IaJfqkc_tbi3lA>Hh&6aTp#=gSWapVtj zz#nnd6YhHa)bRbp>xTuL)rP&ljTKQn*vgHk29>Z?1(2k+_&T;aGRNUeX6?Are1FxDX5_VvF61s>A9vGxNCJ(iVq+1BDidkTeBHn0X?ohp<%5@ zlrZcYKz#gOB+K2udiOA91%O;Xa-0PaORxrO5u!;ei0NW@&bj zbp_xPU55O}n+!13^NR)?P#DYdG|CDUoxPv1vdN7Bp_Th#a_cL&|9oy`vjLgs>^o6V zLgzlWWd@tzZ4p+FOE8dG0FO;lT>@26AuJUKNV?}HCMwd2l!fMvi05iPjkQ`e8yj8; zYwji?76I85gz9>C<>S>~yl^EYDD@F{$A94_%n$q%EG^%V;zVAgqD5X5EG8#NacaAK z8C4BCBvV8^|F~;V@I^A9e$)_mlPLf(5!&$F^)Q{~m_%8FI4qQzIP{J_A9+z;_;x3A zSok$pWUoI{nQ!+GyhYMrU?}pTWXD`|4e(R5B{paH?OgCv zRbRYVe=yDI?hq?8HoMTj&haI82x%zr`q)HXJ24mvOgBs$Ct71M< z)vM*}-%F>s1PmA$8&>~6H5G_K^SwDk63B7>DdHstFmgr-O9|1sM-nG_|9%u^w<2a^ zYU@c&nT4w>MP`;lh5F=bP9XnHMgBjwEAz%7>kT-phb9-gadL_MFD5g8+^t-}s>Ek& zN>Ofon4RjnYUs!eU%LAe9D*~n=bJop{pp4QrGQ3e|Nf1K4jz5EVcgV4ceAN;p50+f zbzSo2wyrwb(BM4~ErSa9ALH)z_U&g=)9$wrUQbGVF0qkh2vXI-Ye1)4MSt7_RMPW6 zM9iSmx1xicJzw&+qtV!vD*_f(mj!VIIjNP8Gj?cpgti`QQ2DK+Z^_y!zpXx>5;Ltr}P2kZ*zTXeZUgw$bK59r}r3kM%}oKVzGh?n54<_UCYPGbLl* zRl%^FiHbtPwQmz8!=fw+lVLfB$ppRZ+Iy*XRG;r2`_@txAgNlthdbhJe}mP@Fc1V-?4oCS_X9v0^jf2D5taz_|jxb)M{ig#7fD3h!wN{Q#|uG zN^BD%&`*Uhw@JQ7L=b{_td|pLx;J4{Ntin#nIH5}cOibDL*RpvnI5CG_n!Ubb?q@7 zg5&y)|1Y3M!Q`zU>$D?nOG}G-;dnjR5pe)%LqbwAGZhO8c|~}|cYDRXmFrud9(0XeAq`vL94u4X@odNu8bs2w(DGHXO-?-C+<7iv#1~)qsrlx6S^yXWQ_;we&B z?v=J#qm3Uxqf}Ev&46xc%lr}a+$^i_P4WP zx%u{hVDWto|Hss#A*z`H13AF;^77+<5>qoKF(ICK0J+SWehGlG1B1oqUvZdn0lH<% zZ32Ubn6}cdzm0qTnW6s(g@u^B@vM@hl7Q_bsVyw?cc1a7!+#Who5U1(=qqGfY*A5> z$avi*-82U;5GWtr#I*ElHmhZ6^7g7(O2%3K>*9GG$6K#cXx2CeN-Yv~j4LVSJ8NRs zl#6@ATNBvzfR~K}PFO;#@v!wrw?D@Hcqx2WGQy!0a((THB`7EME+PI4(x8VgAeAwA zH{qRv8lvH)$cgw&KGCXYO_ZdK_fxCy-y^Lx7kZJ?_O$4$keA}Ksvf>PQiY0E&K73l z+w7!9)@*w6)_97v67#MC{s(mP?c#@IW+cBuWJIG!+yr0xbGrD9(shobj}y2iAT= zY}G5GS0)vAW!X_3fuzG(ti9uEnM!f6P7f{hLMoiGCZPQAnWW+MA$XndH6%J9(1E=9 zw$)|LH93>7Cpr_>Gzl*8da%!^+!n?%I5b4W{Jl(xq8)i32!p6(Wm`(ff$@Rw%0H^E zj1qxK)xa13bkL0n~BYpNR>+EHUe|z0dO871^JM=vg%;(m5HGvp)Dci{S8>4)f z7}eYa;mN7>4@LX`%7Tco3-8B?p?|M7+y~%l>*~Q|$1;f`aDf%^8G7mCi$4i;20KBZ zt)G_)=nO%eis^$QZ-;31KXFP21ntyT$C%agqq%Aah;coapH3T|pkJmy^Nb3=Pks)H zzU-8Hea@%=YC={^a4i1WYKNbMVlC4$kFEn3@Wr%dINT1b%6;MQZ^rBmq;{cgz?ZtW z>}saW0yur%=;!LZOT8f*uRd^g<}&FK&l|FLPS{C&ixuxdl+!|tt*NK1;P4;HkG^ig z*NNxC6};me4=Ru^J2g$Gky zS0pfCig2oh64{Fz3kc@3{!uBh2@gy)JC671Pk z6i+LGd}9dzOx>~Q<=or`2GvxDXLQUPn?b`mvpDr+`oIo*3zy(}HJQ=AGD&T(nMCP> z7K8GgWYafBTV(inU*)_HS8tFt+ z?iYLc5t7SZ+(Hptiw6p@b!Gvx9J33|MmXwUv2u?Ns zh|p<8?L>4RI3o;BI>?1jD^Sq}Ovz0*0iZ#<7-~JV7j%Hu;m) zEnHddpY_^46mN=nEgc-%jn8!vavxVT^`xg1+#714yA__)8$5BD9%vHtQzc(y(?WOA z@yi_An=7?Vr$qxo==j)5TU-{l8Y zLB*ww#Co#F)Hb%ZVm9J#g|qnlzv&Cp>WvW-m>MF9dSrc6pWPG42?F!~-O_veQ)1u{ z5PvmNfdA-W`Q`}D>+=aI=$7%q%$L~_Onm}y?*TUMal$)!dpS1DI+I zd42qEMqG_<>a# zuD)OnPl%4BaGJ4-xr@*m-FijJP^T7`LV%o1)`Lnfrt3F-Xi;@!7H{Ojl@!$8;I7XM zb$)&Qr7jKIos80cc2$+lx`gu`@z(gRSQnPwg>i-J4!4l z8_vAl9?px8gclVZ_2p54t<3({_O9}?dSiBSH#7=YeXr%j#>Cz$r>kqbR5{+d^ zc@#J=^sIE+!xqTM$ShvJt}ZbO6ju0>v2Kwy5h<{1)#0(L71x@y)w7qiFGnKxy{7zK zmrq5<*3qY^**CQZ2X5~mnc+^^Cs9zD(#?h=u_}t}iK&;Aq(O*d#LKMb5t-+dq;&xj z=6C9<+=dsuy-QV@_I{gX^#Tdo7jEFy`Rp==SxSH6t@mh;Ti_G8Lkx!&`$RW1x_+OVc^qi)*n#$ zf;w~rgrAMzN3;;sMRi;CsPbmhkK)ZL)&M)A3Gcqtz6)+`mBY@SDl3Eh-r7H@YcrkOFro;9v5Crm zl1f2VTlHQ?oJ@G-#m1WU#CX=&f-G+YrtPK2B&ft1VKz^)XBB*uf_<<1f{og9QNKSU zG3tr03dY1Ek21=1HUvSd+u_Ec7zdsH{^ik9SNNaHR}zk3S40bS`Z6S6bx)&7F?MLa z$2od@XkN$%3c}hIbU=?@6@>v7;4Eb<6l=&KAMz#(RO;Z2Bw(7H4efRPp`fHsGI|8G zV!uG*3dX3w${6lrkQVKj-_yY8$C$rsD9gp<8$1c4*x13$LY&XMalrJ+cR-(<*-n1N zd;TahTnKvhgUOA=N9R9WzY4ayGyyrwcZt>mGE-bakl=>GQ~$4r35#8>b`}R=z|tr{ zl~7jKZJJHg?GDYfMPFTl@pZ}h<5I7sQ8iYYXBBN_KJ{!?UZEid#R~aN@_y{|8*AX zi23w1+ELnqSbwenCdE$^rm2t{dA#M*gx0ZL+uMe<$-CQNvxL(S@wYGX!ouu+-^)}d z*B`vq*@f`MfJI?KCiQHSRnk+Iq{obvjBK*Aj*1RuX%sd1lPlfq9~THrOPHj_CK;P( z^U5a0w^U&ew(KFua!Yh{bU(ebZ7!$m-n;cu3GuhiB!{!mqi*k9EBoK$pa)^(|41*| zd)H@X;FTM*oflYZ5gGGc(Z~2<$c(Vr8S=TYa)A7&`|m9X>jSpN8Gd6OM@~OTzwgOd znvBIvj{J=@KQM%P3V}Tu@0Q|)xo+5*q+~uQfHIj#e^V<(6!b;l!=)Uay!TBxkLp59 zIJb_H*8hAbSD7zS_@0qf$ZXV68!R534aMGuc*iv0b3ML3R>Z~A16%xgQ20`iTRqlN zL1PILGB2RMhbN*0qQt^yZ2sJn8TAy z3vk}Og)~vaeXyX46)4XUs=vej&M-a+eEM_|tX2)BhsQl05eon#*EdYSnS4+(JYxu? zC!4Uw5_nH27A=m+)x%Y#0GsrDBI>cC$atdpJvJG7ckk-@Uq%G1N3?KslqnF> zpbws%?7QVAo)QGk8B`Q5yz1s2R4L7`=2nwal+##EKE!EC5|Vfi z4(YD+n!n}u-i1p?GtEEPBM)?Jiw&L|h{_PV9VCL!$Bv7aYG zf_7kdGvVRkv!7@-I&CdRRE0X1%P;eT5GLRC;xe-Z%9seux5PruV}Jyi(^H0NRx@Qd z2m!o-LQA%=yI$8gES^_vcQ%>?;P=Apf7|&|!kwsqMS5D&qvyD*rv^STi-!jn5 z&EBLIP=`^?c>g#&w4se&(_H!Hyq2fR)*|IxwB@_~<&|JeZ^NaR=!1Kk$6CI^0U2p{ zd3vX=={P1rA2_&3s;VU4AT$Q`%oU`Q0%AFQ-Aa+xS3KH!5oUm&s*8NmsrESz*e|7I zGs$MzVs2hgmNygJaqp1&N$Xg?GBZyQ`RJbL8>i0+^|ZdhjdKl&F$i+`i}E1E4(StF z8)X`R>E>zQHiE6Sd2u~pwZSpjFEgQ1Ov-7uzvVjXRA&JyhJ@fv)rHI)-1BWDo9SqUD-vjbw>Ku@bqAByvj=~;em_p4wnJ+j@r3w-lN^xP| zb({%P&5L2AeaV9M5`VbG%-!Gzm5*!}x9Ce3pu--SoTS>ak87eE)&8oHzu=VIYWEz1 zAa}dlE`GFaFt)2pVoD{&|6VH9hGHF?boBQ2zFhK^ol16bB+5OE#_7=SoJ)LV|6f`F zWjqhKy36l2`ICy+rP!;D*zVEf$gi@o6uCm#eC#N;J2@0#eQO&WbCE3&p{|h;`ZYRt z9I+dC6X}uR4c%FV0{sH5B+lPYI)Yx!XD@7NEGzMB*MbOEWZ>RV;`&n&{ov{`Zz7wH!-ezGb$;|%zNnKCakvU%5 zL^-JU_T!}Es-Wps=9EECi|1Qgh!cd-vY-LNPEcY&fvf z=W8hN1Ot+W2g^7Y$b88$Rw;KCHXrAoDIOGipXYm?v272Y)K&?HZQQY2SGaOq`E}w| zawPso-DQ$(`hY)CjcD5B`ucE|8ru$Oxzj9#Zl=#Q=sp27;(Yg9NS){L#;kZ$`D#Z} zCyvrmFt^O9=@s3j?i8wT%j}BM)JjYNb?ly32iCGiQ22G~wY%ZA^JViUD!sdW4a_9d z{jR+W3IDLi(P2vwNm@@6XLgS=+=n1@Pcx883E^AoHqSwgDD`R~xll;I90UjCoC1zF zAYpz%Q8J(Y2)Hbs_H1u&CsY*2Aaq19OZUW>jCo)7*@ zSUd4yY(EXn#>?+U2+;nTc-MHrCP#8MzxbZNl;S2itK6NkV`--qheiIf<{KCjV5GY5 z<+s_1N7=^9ueT5p^F`oos*6E>vFFG1Ut<5AU;b0j{B6|n|8-P8W&z3Nn|-B&BxA{+ zh+d;yzhq@ZEmku)KMW;}Ww*;uh+k7-Y&>gXd0T=oEJqnYc;+`-nz%8&m|yRbqwkYU zV$HjDky&;kf0g-ra=JYDpN(m5K84&L#?B4+80Y>F636dCreoc;BOTzBv{qqM{014d zg`hn=k?T1#?nHuphs~6XP~L4>MS0|t{)|A_j5oyLiB>3o}Q$ z@C(Sz$1ia|Ow4c4o4as+c>!qQ41?Xjl)n@;)Xgwkkj z>~tLlr{V5^VYV9M>=qVvm&BslPqQNCzOTIpGv$AU#MPQY@r3>rA*lJ(Wbey zMX0vQOer}|#FV&!yru!z+|2sBfze98mt{^Fom<_+H&>0QgYZdaroXWM?kY;l*m86W zP>n%=ZA5^Zl%^sFg3to-fN74tj87TeM;`WTPo>ZqYMR75zB7#&tYx@Hg9BhlVFzf+l@ z20TvSO_Jw>eCcv-q=dMjzyZptOa;WKAF+a7+d$iHn#n^N(4w$bBziNEu&pm5~b|sL=77aJMrw%gQ}J zKX=<0Vb@^G0`kH6yi>)57UB z9v+_8WG}RJF!|>B|6RUm{7BNwB=zwqI7sqIpNepX&tJr5oT|>7eJX@LEIW-}I3@E1 z`=ux;gh>g93HB2;+|pocBmpZ{Z>*{QIoS={iCn z2OH!gb=*>u&iFpJ&7A4kos?87Kmh;K_$v)WD}}4*(@?_j9`?IRG(aFEU}sMSX%p{?ev)(ps6^pIhqI~qTW-C-l`tdCYc{x#h1$IxYEW#trza1>?tk?!({ z+V=&CDYv#8&%UM*q#D_qcfcGW>wGvS(QH$Zyp?eGF!wi`7+y= zcAy*mx+mYtBj6HP$5Hjtdl+n@NScj;@#`bIsL|!?5w4dTwwaQj!a2)ZN9jL4{xv=6 zX8P6{uT_oLiqzYLkj>oD84HH(BWgDYGy7h_30!C2Fs8n~Q4~TR>#0UK9C@8a!uv{w zP*Sa4#D+l&2AMzFudQn#!+6jC>AGudo%>wolN%@j{X5m7icSk+5YZf}=vE_|4e_{n zZPS82sJOc;?s$T1-JBRrH zjp}FSz~ukur+JJNujQY!8JL50q!kSv$}-0PtEvB!tMPY&Qmo4!!^S0}5WiL=!f}3I z1INqP<9o(@C?@4$oaAQ5OQv(B`7nve1_D-$+YYUkHg4X=ev}2quSXEkq#+pZCNNrL zfZr!OLV^6`P)a$!RME?lSo5RtnyXzb#$kbQ;;+NPOeWAgJdd5Q(*shyw;d#A0a;h@ zEa$1<37Q#csUvpHl-P&9vXidHo>l^B;k-UcI)fg{8&M zxRTIaW-tYfKq5QbG;f7HAaxdf(I8dUVfY84LFo5^8P}uVyhv?S5^ukoBBO*zWOBxF zwq%V~ju)#v^k~AUW#YiiX+?L*SJ(z-H1umaQ>c}^Y{=n;LX7gYV^l9KS2>YwD?Qih zP|BK{TVa5`)1upjB}Cx$0-=9wR=Cqz%{Ki~jT7rLx>KKu>DgK1U&lUY!nBsLTiyOn z_uiDe`8nPyS-{g=`l~*^^~CIplb&9zuR^<(q*r;{rqc=I&t$Ys;I+&`kxYjtfe~-Y zFMn)NC|Ed7SrR#_$pYKXzNr=uGY({or7*>d-^cd{hhgkM+lVnzQ3}xSSG=9kGdOtXY8HA9Jt#!_UQ>(B3fn7; zQ|DUpCX%eKs~g@*PtM8VJYYx|R}~FaBlTs`F{V^87c{z2aq4_=QA|4a*m#rTx01Ji zZmC?afT9l|>$pjsw}RI{xUTl|3j3c_Oa4UWC4$8ypXj)U@xMyA%06Y&hWT?7o_ok6 zJr>ijI+db!RPk--9}iLImRlt!za$mmk-A22c(A?;d|8R^gROv@>gHamqw>zG_>Gi# z$%fv-DgM^hco?cHQx?q%aiQg!beo6x*PL9xSL^H;oe@bCM1Pj>;l&uWQ``rIv1;zr z){#@)XOt2=J(=}OgmR~Vzc`rnqo5HLmgrfkul=Lr<*W9wjP^Z8euecTE)`-f>ahchF4KS3SC~!~KcBewli1W?4UwXgo|Gy!exB^dlL)XKXtm5fWyxCp+sV zIL&*5E%5Y4`#GE6UQqTk!iV{L@H2eW#jwl?v{_B%g`)3?;!pRB7?`NVg3O?c-lw*- zYkFNR!JGNuo%&e2(A_6|0eeq?y=_!sgQUzx zH(R&X6{6>=F3Vy59SebD&{7$~%XKpmd=$*q{PBi-A-Z`~Ch9J`>?N?Ho{!?()yDaK zD-S#?>Xg*N6X?vNfIjOS@=w1=Kp5Uh|9!_=>q<00a<;;0Ry^?uf$e=))ttl|Ja@Px zY9HWmmA}Qy?(guf1{MIHR?XE5x>Tf(*MqM-ATs&rxy+|?_B^#N3uZmoqXsST!0hX3 z)U$*V83t9IObc}8zK`V2R;fA^4-JN-zJE>eAY6MsdadVRy9)Lx${i+;_PzB?(w=>J zJnE2wREd<8C+v9P8GarGD~H1#nB0qcMonme_V0*%l{iJNy=@%M~3b zXLw5kijMonY{cKy#h+)Q`$JohH&lO^YK)V~Z#222h17!YJK}*k9a~O#+?>Z^G21*A%*kUy-Nw z9w>_2H__wbD9^R}&F&*@T_=UknQCHBo-k7;iSByC$GAn;%JrMxB;PU8H*I>fLsv^6 zEd8CLUVOvnCq8*~>{+0WVhFAxdw?1%r)QTvA$LJ)=HIXxvf3##snHKhCNrepx>~l| ztw5VL`Wjtrx?GuEt+}8dm72Hl^{Z&2Py{-z(KmL}w9_84d@<%PDC=4I5^^?jH57L5 zA+~H#%0^Yy^xCmrAH;k#7jj-MwD?XQ;@4FZd9#Y6ugq~Hv#&+}D*^UxO_csL$rBvN zclKKA8+6L*LL&F?-STUZbziz*kn%jNr}h{hn@tq6^cl3Ocz8GG!g`G4UXUL{?L8?e zi?vhot3~ove)BWUr+CHK;z5o(14;ZnnO*NEGwZ_2CAu=pW9%nKKyApu>VNuquHLO{ z8(Q)f7SLLY@*|ohtcqxW^;*c4hsz@8JlwaZgpWQ==+qW>m?3y==p2~$$QWBxEq8Jk z#W=Pv?d~~zDj5>r?ynK$S0Q=OaX#LTq~cf;3w`raV(<3=@j02C$KvJP_x{%iQFkc9 zC%<(2nCG0!%vUXYgdpd|7|xCo7rq{Q#9c#HR-L}8v7a4*1-zo#v%192$@%SFE50+3 zX;N%tAt%-z=5J#+p}Q6BEbKU$S?Q+}6Z~zPXlgRgbh=_}?{NPn%REyt;g4PW^XDb= zUUbWTMAvbAf&TNtx!-cejbah#J=P$b24}kn85~rI08iebAF)vl0Y3^BxpwZ2g2_Un zHVM)lx)E7h>#v5|)zA&U<-(sMvLLn=j5H|NakDmeKK|u8B5T$~$kU-`>1a{Ocg>pV zB&^`d!&)S?Jn+f`1=}g%t+%N|NhJ|qu8Z4wOrbSIva$b=td6)lK_ejtz%!?Bm z7|ZX=%#1^yM7#8Xg+f=6>9UXs>-=yairz`e@8Y+HkI{@xN^o`S>pL$ra5i+_b3Y~y zNmx^^>aTV_98MEU6r#S(_hHMnOgAqm+HN$Fk(w!5Ja}ill0lH!HyLU*Fzs9xd!?Yf| zs9apB?=BLaGu^!D$;hliOY#2G3w*gi$El%*tXp)Qw#hgLtu|`acC*kF=-J^PRqZ|f z5uWQ-DAAbWa;{ewUqnSjEZ4^K7um3aXztw}$bRE&;o>k^T0&fyQyc9^?vmrQZh$1Y zm@BtXUVVW-)0W7qXMj&H?sUFRH|=jqyoLZH7;E~>wV`qNR=s*q)qNkNY6cLFCff`V z(6~BF*3Dlxr0i8*H2uI;IhL$7CO;xnY*O2HH+$nV^pL!}Y1*9M>s}x!#eVJ+5vXvjS-(P=yqNlfuB$YG;)7&_zlB{3 zBtRBr9TcnZ%(}AoeDz{VEBaK{?h_wPq)k>=`eK*+3?3h!`fc_Ejl#S(a*ocNbZIve z!AyC64Za`yW9%B-i6XMH+|!Odgd0Z<>0n<*3S^~b3v||l6u$eTFOg}oCb^ZNI;cNC zl5s;3iVk!h#paE6GPm=3S^99BEf7{G*m+&Sjsiawv6>4N?T%5dc3nbWdXE*$Tu}a> ze_@M`kk?YSCRZQ%vTZOCBlx-Fy5D5x2V`c) zOP8!zaeH%eM>+I8doSUhC9m?qJ!}@_FbdsWS4Ml^OUpsuPocY9M;?Agr(YetY8q_G zB9OThjqy+JaGNsfR7(G&!iJ*a)$IeC#pgaeHKuJx?!==(vU#N zI;$Tdo|2?)c}P&TfnsF}7z+V~Qdd;rBfFZoc^TKOmvp;uc+%Asc3|H=f&6J;^FdD< z59AQYLAX+f2d2Vwc&ILqnd*l0B8Y%+%0kef(#%j~EZOEkR-gV}(lsR?LIK>t0c#!S z96Wg6s585Hf;Nv+>xJOz5zk|h?`cGQ8b#0I+>6+X4NBsSB}#vso<5zf^^Cl@LSMW* zTTX7hHOo3<&`(mbD+^Vl5)qYkYJDcrO$c|8d~&72-a;6PI8oJQ_iG}Ai~VROhRb%G zw=1+o4O5Q6elInbGigXcb`vfZpa;o^(JmMA?w2S5I4k`P4Yt{rnj+I?!p627b}aQS zMU{_vbP9Y9+oM(;k_K*q!K85n}lX zBy%U}G70-J7HzP9(<{`@$jq!poLH}J{)u#7J{8tbe}s4L(!iyaOsc_9CJc;>PL4GN zC9GPv!A{r0Rg8krda~3s9(SNxNgci0v^Q{i`c@Khp6{TqqbIDdy|Nj0!XF)~wvgF#?D|MOnJvp#$x(bV>*cf_0?85JEA@crTmN$U=1Q@+ z*b$7$b;}^vb&<>8llxY_cUQo9vYZ(C2I6D=OYYl-e3m%|{eld)Sr9kxpQWrr3=j71 zHdog}pED4?AoGW95kzKBzywL)I%>OfL zJTqkq+^i0APO4S|Gb9QMR7V8P`2bV>eUm18B}3O)+sPy@`j z^;*wo9Ne!uxs95fwYlQs4;<=L2KYcI+%pP|%+I0B+3JGenx`@xMcP*4DcP>3)Gt?y7OwhFP_K%NcAGB-L z+`X+0Vd@;I2_h$9nmFE0L}@AQqZiJ6QwAUa0Us&BAzQiJ z$Pw6p_m5yB&W)3san@q@yIb~_1P%vzL0~P8h0Nn8}01;|SQ}>B_tk+2ux2G!@>j*-DMJX2dTOw^I-dcnk zkmO^tv;4}+!6IT}0*1Y11Ln}nEf7L2JdZ`a;d|yBva-1PAFH*swKZ>N+{1CTCJD=C zVc1~j$tdplmKfc_A@5QW*XjtsKiA@*mZn@*Vict>M@oD3S!#ctw!x~qu#ng8Tml*% zAN~i5&XxZFR&q)i)wqZ9T8a_nUV5i|cFu4TkdWnE*HK0J_}xm=9=gT&FhB`qQJ4{> zgnHpfJ*FnXFT>u#dtHys%D2c`WjQm>|Dmd3?66aHqt06h_9o4HZVlTp5IfvwKiV$% z&(7P>VJ3~fPs5T+;vDs|Ru8!~xW+js##a~%={Ga|Aj?0oEr$ax5~#DwF(ON? zAEC_N((>{%Pbi|Jd07Y);^|i&E@ThYS)KN*cTU(9*!|82@gX;az-xLPT2D|Mn#+Mg68+9!zoB(?b$)>=QD6E9i*N6&WiMeU5uXgQ41eKa$*~hwh zf8*9;A+++m&-u*;_v0|c$#q8ION90?;fB`Bh;=Rfuxx+bpf_b@9%DR)>$N#|$TTEl zqk4zC3H5@jZqsRTYZU79$cTuHCu`wzuBnKxTC(#t!1>M)D`?%;LjrVUGs0L%9SUtz zXRs2`gXJ7&MZ_flQL&o-dS8e$HTX}V# zrR!oc;^wJpVKie}+?;;Vajmr^Jh{zYaaauNu#Bc#=;N|hLGa^B)p@R7pzDW$=4U)I zzn=RKHF>m}-_2W`#8$qC^CM4YgBx7h=M6O|_w-(|5+yW1UoIRj2X2HFC_cF#?{_;i z>ag#5Y`BCCHB~*Hg?0iFd~2(Cy8-;#iPx`SE7WC4bTBNV7xoiROwg9*8-MKea_G~q z!^0nK{6cLPmG^-q|Je9ARnfxpR3#r?$L3pMc(?Lmm-5`zofHEIuxBh8r-=Ud*95+@ z4SF0v)W|>m%hrfB#bRL+kg+kyLlbfaE7)3G)?oPGpwz@JddmD@Z73}$d;fMR+0h;< zbmB)c_iqKtQ0SnyI7g0cGUL`8MrTYpds zTYWNMZ4}-v4C?CP+SlUzyn0z5C!zZV&1YS#KjJxi^PXt-ZEV)Kuk?^5W|)dnGkwmZ zOt!B*ZZMj$Eu7F*-}{D8QO54yD85uzxR>=Iwa89`OH<_Dlu);&8Mv4Qi}Lzhd`~9- zkfZmZNx$39s`DNb@zD||XtHxwKdOAs#a2*ezDWWXORT;|pB=}7cuUdlPqnTX@J5>O zA+5`2L+$_40^ptBqKS`ZNrkiLsi~sk_lZgzqg5XYao7%Qw5=N5T4G{iZ>c+~r#0t6eFbs12f@bCoZnIqv8!LS zxK8-Aa>91ph_gT_>BrdYIH#;EL%jPVpGpS!*3iJupLyxBe)^@+=Hk#^E63l@&sr8B zMkl+M7&`(>9NLt2o_gD9s$D=3XpwV@G2RSClpYOlEvtfCuzu)P?>O*^qsTV33A+5} ziDnBNW@`_|Iyw3detdgYbxsH{G`gV%cou|j$d@hW#m&!DYCo{aBVVIIM} zPfm_AxThFURAkq01Ign}OY;5vLc~=089BROX`J$PYok`n2I>KhNtd|~%HeV!fuI)p zkrlmK2-3_R5x6)wBkmc&*RAuAm12`H^*tSt>WxSv{h|*ViN46)JZn+A#LLs+owQ2F zx9W1|TY7z9FRyvL`RuVBe5gRDU{%RqwX#K)gF8azF-QOQ-0pc#V%qSJGm>@w_x{m$ zU#OZk^gQko;gk(UJemM8zQdEJr(X2zI_=mbi>8Pc^bKo!tI_R9ljhgTtyf;?TjuB{ zXxtHGhMr8Z;m5??x);+6Jg|RQ|Kunj-OWfq`=I?)}?gnJIFdb_DD?je*np>E$DJ*1=*( z2m+DSb)y*z{BlsZc-2JYkl4OVksasnR$uk&lqws2|H@;KGU1;{rQP=ih9}_x81&n+ zK_VssU$wtoeoL`=u=z1zD5HCS=z6e^<$meyzj@?_+NkqVRO0MzInFQcGbAOfNnKu@*h|EpqoFo z#?r0dKWA7qrc6j|!O8OQslAQmp36(h2!1h0OaJX}%Mip%@gJ_a77T4v&nF;1t&LP= zcsSj0Zs^dQLy!+**4_DR@ep9QvZ-)enMs3*nXg6cML2r@ywYwZ1#x_mLi*!ngj{?< zt4V@BWm~YHRmIw%wyvN_{UX(HvFikHcF7>`b*_yIOBH2hWuC1{tyD1U#BW&o?7^Ff z!CwR9%RiI&4IA(A*E#=A07>5XWr!+nrcOj^77f1vy~Q^z23FQ&pc^r)(l5rH>0vKS zEis+x#+;I(k($Vcr^AhJCchbhYe80UXaMZ&(rG72JLo952wEm%5>ILA%1;Nv?wL}j z*)QQI;$WNSSY8F?_S4%j22H{QZsotc5)bDN2t6WJ^C34MiJW!P}sZd&*3c0c(OlAiQ_jo)Mjl zzE;(Ir}A>|M5L`aIw_80pI0C&bu3T|I_r~~^shil5358rRk*6Ed+wb<7P zW<({>#Ve2yK2%@8`O?fy6hTOiGeY{W1QmdnL$Roc1$q9jGj2yUXmFgI6FSt=0T?#xAUBnE3SjbmIgkGMf1&4gB@BAb6!~w5 z;0?thP_@R(LQe38*;Fzpb``6QZc%HSM!2$X1aJJ#PnY%_;MFZDOhJ4|P`&jja9^A~ zk%~&>UbV_ZsWC4oe-l}+Hq;I`(Fah*iuIjYs?3#|^t(Ae5%AH;)_H%<3zZ3<2nE@L zf=M&(lS;}6OS4C;$o3SrP1w47V9tU&!!lIT_c2YOkO(`3L*Ek*qJ#>ebfAq4{kkZY zp{v1T^wHfyUj!aPse(K{?zf7Sy=^|-fvk*x}bl5X0CDhYmg9hyqutiQS&P__&k@SEsC0B>+OZjWKzAd|K zNKrY-6#vYL4B-|Tp2zji5zhTgbSL^G(?10&=|hYgoxgh)`7+k&U~C<$+UryV*rmo%}#Jh&w=F;@dT)SNHr8 zl%6jh1L=Zpl$-3y?KzSys+A5i!jBdnbI(B%O$z@UdtuVi{8b>hcC14Xi6o;TXJxpDJhN-S|(_xEL7BR5WcT# z6Hge0K+2Po=8IP@zgQ=fh2RnD8ph5f`86l_%{!1Izu?_gw7wCs!LQ_n7>$^xGFzmH zfLF;f^xKH=L=c_89eKDf{fzq83w0hQhS#CrU-Y>68ob$k`%EPD!(tqjbee9ywe_Fd zReFuoOzeKSH6+FW%Z5sq*{Ol#TetG9T+fXSV@21|tS9BZ8gX%$+!oapCwc8(nV2n* z_68>0>;Dz*#lObE(EsH)bQiy_jt`{jhliUZP`PBlpd+%1A3RidX^Snlfly`x*Wb0^ zmUrZ!23QeIW+wVqWqJn>QyTF7yENc+Ccp-w74|Ij#X3_A{dFC}drzr%&=MhtQU-YZ zujipHpLFWYcpnmQI7H|d78XXIf+@9{HJ838=#D_;!!r3ZiL)Mgf904gNp_(BueASj zTZ3m@HT}Ax9~2#6J!X{p>618l1fLsg1RqI$PTuVt6T)@&jgY>ZMem~tTNCVB%@(2* z76{?C8Lj#5qv|R;v?yx4G!4GhBmG-G95xp>Q{&@1q#h0TBffib&dt?2rCqGKTon-6 z1HesAFMJx!B$3zFwjfn3_7?wT%|yiBMzW27;eph582Asci-(QVa;tA|!P5aN^jWVdd-)tvzaUKPSt)`(b1kR?7UD8@S`V;bPV*dwWZvhtd)Q4$i0(j7x89a6%;ASF`55YqjfpZ9&gd%5pFo`;7= z8J!vC?6c3_Yp=D=+oZ2|1rpwXyO6tbhM#!a-FyH3!?n~t6}~cLV%w^>f!(#8G4{bv z0c812b3X$8P)HlOZVs1wiX|qxabTgzN*}!8*8d^cz%dX> zIWKy>(q3=R>R5r|0`YQM$yS!gRnVU@s1qYEk>Kz(Y`^esatCJnw_RprxZ7K0&m~_h zqKa6kx+$Lr0k2yy?gwEbJ0FHYb?e>06nN?u2jE_)FJ3DIqw2-ASKHt&Lto|C8Yz&} zAJbnQxD2Y+>hPQE_iz9_@_)ZvugRR%p7ai#>wrH@km1-OOg!x50?B}i(x0NOju?`C zn1*henLm;s$L3|GnEx?tODiYGj?WXNs@~Tb7jRtsy8+-M&c`!q0B(J2DWp%&Z0v-W z2C9xHLbutAZe<-h=)V8(ettJ?Vn|x-Cy_4|k;a%wa3158{a2JeDcrj;#A|7MDqP8* zEM=4f;&-N~oU@9-6&5eLa!5H}1~oi-W#rUuiPX6E{K?rUY1xWUT#sA7Bq#8!x;0)d zpdQK1CKcZ4S=Me9(m>M>nIl6>V;5$TfxOsr`TYB6nvkEYG~#A zrx_-Z$XZ2dHtu5TIrJ_zMoyEt3gId}hSmO2&b?xVD<>k5B|^1?&@3i&l5no|a`WZO zpxI=adh1id215@r@0+cE@oE;x^XnDIfz6b>f}U2?09iveN9v5~nOdVAoJ*$|GHHA| z0&6=uB> z*r3uE8Vu?kwx^_5o-fP4(+S;vee_Ck?{S|>MnQq(DxWz{qG@CNU1sTo*UVdE)6<-w zCA;y{O;A$!@$RYBm-|0a2tTxCR?}HyAsG8u{`l%RJUf+MQ2N*?E|3RiF!SIu8O}FD z!E;>OY5dfXhvZH|AXZ11a3 zf5z`k(VR|gk6-~=c3HaE05tL*qM$;dG;MJs8-iN4p8TsPi)P;-#)U+$(*9FUP@y+c zSwHhzRREFf`JB)M}{Qbmh zXkMqya$(6D=>XGe90N2@$u)g z4%a3HK{JKzeeu>UpRlU-Pp1;Cj^xQx0_3kob8ovaTf8+5u}`HO zVmFn|&N9-WiJ#Qsi>WY{34<^(?px-1sYJgS%uNNoG#zk>cen}b}+}LbcIrO&Q)R^x!!p#QcUkBDXF9qCkdSEQeWKT`1#JnTQmLX z57f_RCP&c)29v#f?8&wZSd^vsj&n^(;;3Oyq<1YN2gFl=Z zLFM(~3K+B<_Q%kcUsT1CUY3sAHMo1`O~-fGe-cU;Db;Jd{}g!<1Tfqt{N$HA6u^fU z%FfOQa0wK^i)!ZsxP}SOYkxKZ--Je(i(;GYsE}BhEj{cdvH9rWpw@@zZHjE;2A>fa zk?^oz_AcA*PUzC@IaP&G7t5bIl*J1=;kMfNJBwf8@jxD={QD)#St`V4cyhR{Pv3OM zNg+K%K17N2xwmSrpx{eBI$4gjh!t0sCKVCYrFEjUh6qaTM4iYu?v*PCPrpVkCbZDu zpmtVJ-E(o$yc!alpIa*g;^5nf%xww@@*7yZ@YuGKWp|uxz z+Do4vJlTR#-9&w5sL7h{9EiP5aDx$Xi5!=&PH1FYTze=&(A-@@K`*VbVu1g%6 zcP$R#JXvQ&cZkss+mWpz#SU;pJf6T@!dVC0s|A`9nI?XbULy1tvtW7HL5q^Z?8 zU#`)(*MR!TDSeU*+=SK38XC$hmoMJEs{O?Cx07(QEZ6Hd5ASGqc>!#vN3$|NYl;&Q zadCRMNzWfmr@SMTXQb7eU%?#g$0&Ehx0vWIdzMBjVd(afp|gl%=+^MCwxEy@PfvKn z{BWE!7t-_W{ZqR|brmc@&+3tquH@AF1j%v4cVdLPEG5QX-uIfDSD%B?x!-+lC5;YO@0G|P+9ck3FOX-OZ z?_67c_<$9c=O@VvzMr{|mOFk^_dsZM8BjToA9S*pVH$zW{DkhykCzYDoG0tq+JZTo zl_oBWVaXXp;|GJgM70GfPK$!4luqRRzJJgfyghPZBJYEoOJpIN5;;{?e!1Zy%~|{R zyn)-jBFFt9(&*L({;HCy*HLI1w891!Mtf}Mj=u}4>h3Ru$OuO& zT{91eKbgB-aAT~-*tMw>guUCqW=5Ezgr?$x(~K! zqvM%_>w}73tK@#?7hxWX#QK`LpfOeYHJD z%dCio+~FH9Ur!m9-%WTROMCz(q00#va$x?lt+9%}#?aob+VIrL;9hR9>A{cb2fTN& zg9N*;vA6eI3sk$AoH^`XV2VdS%*HlXA8B-F-V~h_vNQ2K+txUH=zqGEk%}eEi+u@4 zX6wd9+Z!P44WB29uAAfRn-dpLhT>W zsq315m(B0H^(|8gS8><|@IdJS)}d+E8vrQekatf?Lh)TEkdCZiThlaieAVtMDX736 zB98Z>^HR*w#~S0d4jukrQaktf2S2%8uiz2y49V=VJh`N0+29dL z>u#shYQIn1rfetiET4bJzSC6w<5PlC5p-bl#is070;tA zhhpfM_sHh(2})dz2pa)8-U7Q>wy+v-c|~Ff>t=`HGLWguqEbJWw9+ zsW<~6d(V551<&bzL7dF13PZ0q*@Prd3(faV)1w{e3^~EYzb|Yu{FD$IuTz)GhSM>u}d4$izDy2=!+(?`Jy#9-tIi)e>E=>T9+k9kz`IPn~z7!5p{PpSO7l z`${;VM9PJOulAyKDzq{H!Ex+W4>~N6#lAZict`uk@-ch2Aj@CF>nF`*) z^)0H_I}pbes9&>8BEKf=tO+xAIJAHVSZ{d zqrT3D+zdN)(t!#iA{%dM;BoufUC7J&bA2Z_+aee6`(NM0*?aMd;udS#i`@HfxmmxbgZ7B z96%er+M=rUH7eG6C@ju1=CtS&qzssL$cVwONZJwx9k*~VHnaTk+a-@fiqVqNJsomw)8 zjDwdOWS@01GhZbhIknaGp?>$}Mr?EsFFt+x2t5UdCF;mtIzEBf+$S;k0;cnVGkb8M zBQ1z1o#|Ye$S8rM#nCEq3YA&_yWVsw#XLk-g zezZRO6e+1vzurW%voTij_+^h~pBQC{3@R)j&9*sINt9q3bOGX(BniR`C@ak8bk^VL zlhi9VkrDBYkA82jQxwfDE)Uzx$B0h7^4vW!l9F)I3XO+rE0_u60Dcx@O&aZc#+f9fnpjh9Sp+K09#-q=4~p>2>0TO{X74ChF=e;xml6!ZtUD>O%`RkPy{ri6@w@`gp;DbV{U; zNCbzpK~x%f4N6>WHmMy7>dG6L!RB-1QgB8`=M zmg}e+@iIgC;4?4{JtUC$Xm;nnTmV%zKe6&PnxT-mwdlR)%lEAk@&&UyH}GyS8ts;^i-il=kkF*agKMECKb0=`h*2 z-SuhbQR{3uHa}W=SVUbW9<%SNz}7f!hGFB`$vU6yghTYX4_qa43kK1N-u{D5)c@7{ z2)2BJP&um|GG+BSI(Zhfv~D$W{TUwa;KaC&4Pn;aK~%o~_P8qqxYkZ`nHD--8Hhf6 zD|hHrb}80_4bTi4DPD~eoSPxELP=-W?e709ZE*;e$at=fZA|S%oritj>Q`&VcIN{l z^#>m-Xg4pPy}qZEq|g24XZOg>CyQU1?tU0jdYIfZpZnnh3MR?+R*$lQ(w9T=#p~!% zVBeJaH}_JU=4&LMeh znic(1p5{M_W@OYjLS)!)Bqw)uwcSsgZ+-Ui2?Rg;tmeHH^S;MxQpf%BrRO!#mx<;d zZC9C&cy{%Z{69XrmHd;fYH#=9q^OP15bbYofFHhhjmAf1t>4rwiXX{l7Zkk1#USeR ziizAgF``QPYA05l4=naYNM5zkrPYm_x&`sq?k5`1U2NSt^>`M&eQC%r(Bd`kl@jkQ z>!2;l6-s=tVRS<%l=j&zv3* zB>zp|CSiROHECpno)S<18$~wz0Kmf1={7*q}fpi3@Pz6L_WR6-y5Eg#UA$H|G2W1pry6IXiWKi96dC6v)aA5rye zG49p2*VXz9gkqjpv&VHFE0*IMf?)n)w}w9`nXd8v1th9l-Rg{tG3D4d?m2H;W}eB_1q(R|Q(u>2*8d2&*_Ebl^a3_Z!L%D*Qe5d4qIx4$A5!KsUclnaN37%pDGP#&Ydo9 zdEfS2Gg74Z6@yD=AU6HwZ9A}GE<<1pK8$ol9?p(^D*_b68~2UM45E@u86{u?Ny1^< zvxrBAUjVJ|@vuGl<|E~A#hw&1Um@z~^YQEl%dad2^}FVuyy#iXvBkp>xoN_F90FD5 z-McA%LaANdGXt5xA}+O|ye#JV>2v>I)2z=$kychc+;6&H^v_#8c_PQb!Kv!oX5PZu zB9+!SdIkxV=T3h6BuJTLcRXI*@Kw~x0Bamy^!7aF3ZWjMjo4@%}4jG&)hw9-F zw+dwv0hVH2W1pGjE`fvMYK;(Bl&6&o;PRCm&Fi5Y{sV`Axoe{ev9ksX!}a22w(wFm zGqhEvB?6{`@Qwit{z39z!%qdMP?zKZy{mp(At3v@rVa*fZm>3UzeR|_Sf5!2QZVU9 zFA^_TJB;5^u1e2ihZV*S47d5_a&xdtD)duC%2A~7{cIrKXCdx??lyL`JUJG5FJJBu z-5#vCU6U?%n8`{s^)0X5Yk4TQ3=CL4Ohyu7ueG&D9=gWn#qkt!=U&0_%gG<-KRhC| zba%Hb62QYGG^Tj2e^1Dt)9dqp#7&+1==!}Y$*&Z+^e0(jd`#kXq}Xz^IDbZr`PsT? z5)cwzOH=oaPX z?DZ3u#~G-28Fn1dO&+8Ce|K^IZXsmpw2?m22a{mktNi_V6e@rf0$(U{ZajGJoo0Ei zCj$LZkP@`EQy@S6-x=M1`mW@JM(zs=&S!VP(4>3c`^yUz%W{4FCjSP>M<#0af5}3` z_38Mo1Reghq#F5Gf)2op`QZ5X&&hLKCDt`)+>v2+eo5VrWU<(v6hyWs++d;)3?XJT zj?65K<kgB+ps8KJ~}24*@I=Ib2tezgz#m@~R^aNqj0*r{#c+g$q2GKVD^ zEy;a|yszMwW&#st8@s?|N4OOAd|ZoVd|a>4U|z6NDTz4f(~}Dq!+yCf3DtlBa<3Qw zxddkq*?&z$YH1OYN4iFYha07U^RTEBz#hFRnz5(Xf6I!(0mQ``QscN;JV`>!3u9~t zeHWSC%jJo8GpvEtG?J;MrF`F%rvZh|0B)g`Dh0eS%%XjleMk+ZQ)KeYPTu9=yE2Dw8Y&rjtx>falA z5{r!zEV;~f(GNb_3N~A;QlJt6VoFPO<7EOf=EIA-`giIdhDRjcjlA2tn`3^5PG~n8 zZH4jj~c5{yVZs{XI^HX;&o||uq<6Evd+0$lu6u?(|v`|hD*%|^c z=1u|~r+~;md~sfpl8E&YsjL#~bq2Io0?bK37d; zO})GxK}pB1ac9)<-TE?*Qy15{N=pVufCD;9UiSR=EP;5uAYn|^K?8`bykab<@sC9f zfGKeT&fstWv&RRs6I}}1+_PhFh0{p6Tj7%U`dyq!B~Vy6rMku@o@)Y906DZ)Qu?pp zvo;6AL@SsqEAeB+Abxyx(JD&y>XCwtu;VDc#_OFq&mw;prntdg@GnyIR%Ve#&yCw; zy#A2xb8mNTl7X!1fqb@XwsRE_-(1)X6uTsHAxN~frVq3#p(XA5G0~l!tH#$=N;Tub z4O;^~1*gxK&cGeN(fb$aW7X8H*oVmZc!LoQD}W@!>Vkz=GlOr|@EjQP3SAi?xMqhm z#tJN>46lPN50Y*_21?Yg!3gT1qp*XR_78H1UQ%>ebH7e=v7ArEJZ)QeAMbu@!6;>G z$f>W~fYj~VHvqNL`U2PQ_Vspu+*fT{fU)B`PQ2`a`MkhduPlu!G+gA)k@h>RcpY!l z5xW_J&%8Gs5TGsRQ@}F+NtW;Pf?fxMZt>I>#n)6x_B0V+mi<}IQMz;z10?iRmG*o& z5i^q{wt<9)-+C_x=NSoQMPT|WL3}Gk_Q1OVMi3J}WrYD_W76Ot8Fo6Mg>IJ27Hf=S*UpCZDIV&BKJ(<`}@BJVp|&?S;9Xy zYH2JUkBHHH2{=7HT2IBh{70wK^rDL^5;TI_xdh|N`Nq=6j%B1rlhOarZ|t!i<_kb$ zk7^;NrOxV8$mr08-n>)SF9`n~?b|C3?B6>L`tAX}o21V-SeK#jVxd$LrJ_o4R;Pg$ z9}bbslA|H(^|sk8VBo8dL^y)AbU|@X$zrn8t^31G?R(zvR86L7lV4!PA;6`kwMXnL zi9TFpocdOvU*7%^4%lWn%18=_Pgr_K{45}sY}vEt?2*G_ar-WiyK*t}wq+zpsj3$L zc)%|+K`~cXMS{(RZufIBY2vRM6w@RZX?QY!56~eQS-9HUPAbMC4*)?SX0!;zfwWUJ z6%HKFCXh!I3LJul=xMD|4FTpO%K6t1SXP;dJuXnOws(ocx?L^P!_pOrT)OJ`$ z1xU87WG5bxoHk>N*rSwGrfo3+h`;(Hf{7AC7E7!CXQx~Gy4xAFxcyiF+-xeU z0F5Uz5d#Y&sHb+JAOsJRk2Aa|20t%6VlEn%R{j{5tKB|GcItK&(_EXOn|{}0M;7fw zaeUhS=F*ASZcYl&D|=rWLU`1E#fUAhuXi(lt+J)?4%o#aquQZTw^-Lz za7}8u|KT#|bh$PP`;>^yYOM#!Qs|plDXwUo42=u3OOmn9$Rw&E9`=>QX4pD|6K+=N z;fHYI<;`$|iILTf7^l3?>aZRqC8f9MFcngLgF%|ZxB&Z{P5#nPYDzwm1(|!_)UVhQ zHohXicw`4pGnvd_ZFi%dQ&&~(1oBy(PG)O8f11vesEGS5Y_imIKhh6dZgjS561I@) z78+cmFhX9k91f>Lv1H1Y4@ESjk1^v72+yofgYxuK)und2{%j3cN)RhupJh&jni&QS zRueXjGMuCVBDMpyc&ZLHsZR86r_cd3A-fIV6f#p_RwM!I9n3%n$s+^DmeF_>I& z1oi>(#vMOR_>v6AUY$7uE45EuVi!*9J|LrStfuHTHOU=0ushH!ES6(Cu=w5%zKq}C zbVY`MY-x6flDt4v;ukd@mk)?V`DxK+rOnfWG|wpk?9b`{)D5Rp**jNTR=N~y+$LXP zh+qrYj54|9kaSdZ@;3f_hJ37NX{FKJ$btE9RYqJ^M zl0I980K=svblb7{dI=m^;yZR{bl}Cc`)`fa*|rstS}5LK<%%fbOCv=CZ`SB9yR&zr z+g42edi{V_^az${;4ZM({DYndt!s7sz)Pd`V8kxCThH>S+&adTZ=^Hw4uxM_wwyP0 z-w}q}VZcnz=Q~M|$dun6T$Z2qk{{pm=ZN^4sMd zP>UM?J)88KdaCnqZ5jmE3aOrhYtsP%t2t4@abEIJ{rK`;+FP?8!dT5n^Bo`RjBt3|AsUe_a(uy^xss`ZM9X2I^7LTD^$q&+qK}=l85qN?KYzW5>UCF1IjO<^HhPmh4TATp4(euDVlH z32#uQklr5Q^U_@`k}gMNuT)}KkCNAc@TSe8bhHTlbnN>lCfi-lZyCjv`A0Ftc_9mW zj@?a&la-rG26&H4k`0;i1LBr*D#3JLYQFlQGJ6cqve`ZWmwVMh@jwPP# z?kxtKE-JkRBZRU1$9s}-fs70y4*Wk3(31GOQCPCT0kn{KB9-kDM~*bO3*ok{@li@d z-t?s*QTcS#3mHEg05!aFoTy5ku>k!jhd{!4%3ZvSJT%O925<^6>iSFiX*IW~$#U^z z@nf?hu*10#PYzL^MFr!1{sciTbz(Um1VdoULVsUx+)FQFU%Pa68z=~cdRJ631pvJF znCV~rMitbKUb`muKdTR{StBIQj<-maFDO?%?_wj?aTN#+>{KoMF@K#S(3f@Vx}b2x zGc8w>!jLK#3^*vX!)?El1Pf4C+aZ2sHs;$h{m_dXG$LLLQYq!S*WvXrn(>x@#j}Do z&?&k<9<3luFv`xtd9qF36hh)}{xzYHCbJ_#S?#d%$`rqfvxi^5B+6qk_T_Nuv55e4KM&*~7R(z`o5 zwYTiceAU#|!;9d(Y`fHcq~Vhxu6)7eS1*pNKx+N*YG;{-_P9$19_S9Jmcl zrt3=W6`(urjq;ibSO-Aq>T9nwpCe3ljNd4Yga(_RgkyZR!BZTH!8v}cDQ(D5)cBaJ zl<;3m=y)GuuYCyroA&U%XB((>8!*EGQ%TgLR6y{H-N7)JeJ0^WIuszaVp2I-xFoHS zgc41KB4)yXdWDA|NPP=nQB8EZpGD@>LGxJC&)=bZZWg!&z-l+&H-8QuL*RZfCz6dl zw_Fv1ol0q8wg^}0&CTSAro|C~EeRtf&}4IjQWPvmAdiu3&mEsWp{xUBMBrBR zcrtWx}2L_9Nj;tyxNqnM-2 z6V^eoU%+ub31Y#TtBgI&4&D{0HaND21S;xK;%=cYL70K2o;NhDMt$*mca28c9UW3# z3M)(&PsPdu7oJgGhs!4f8pq#G*q74t2yNa%-1WJ1)3^qGq3F zzPqcB#mr$@te+kx2)DjVd3G71u6kuN$PZ9o#Ti|xfK%6h`A8-!ei-JTDXm2ux_w#T zwyJH+(JwE7^&)el?E^qbbvs<4btKqfc?yW(@_66#t{e99dD(GzxG3t{>k05GbaYDO zw~z<7e+Ygwk8Q@)I)7)H>ta>11q|){y~gYl!84Z~V;|>eTKamR(4oMRkI$EIT%_77U3P@BmN04)}1m3z5bC zi`mB-2r>Io3Bk9&<-l4HTf4n=N!nQ*7}j`OOgxYVL9i=M156%qE~J9=PkL=s|2j_E zn)HWw|99MB7VAm zL)~QMe9k02(mniByHv>Ek+s(N@J%#kgI*Y%92E_g>XI;XwyE+olQhHcc=UyvVIS|y zrc#jDz417%SjPP&qY?*g_Tb&j5G-)4JC!1!rwI~OXavjh`F9?Uj}&*2+x(#jA9 z#BXzRbGj=^>-k$GYz_7l7XVgORis~;Um`;~6XMq`%?8_rn(dJwU!tlG>lay$zh^bjra<*v$OeMVBjqdu)&{s&Ncv}IMwxu4>f~+<2Vz%gj7@Q#2 zSt0&(YpJU3rhz;wFEm*)v|y>X_XOJSdgNk8Hs?8#&~>OX_yByq&J#3%Q%T;!*AOg3 zE5ONPsmO7>d^I1<$_Dbw?Md~AV5P%>+I$k>)%N+K%*=Cu2ondtw3X$jryiK|Q|7!x zyew|^W~@Vy@K;_780TmWw|zyh2EmbtE2cX%tvbKKD9-+wQr>xE(J}HaG{B%Qh9E?P}lD5$H#U7gd<2vUO1Zz;( zAE{HtKSpFg7-9$P2qq}AL3Dz0X|#GSrxI9FUD}tt?qxT+_TZysndjVe zm*s=eBKS=JKM!6m_$KAK_V(wNw;Nw-mgA2_(5B;=YbHMV{j=+rmjimVG`o<;u&U