From 007065baf883fa5bdce6d898733fb4878be4583f Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 4 Dec 2025 19:59:48 -0800 Subject: [PATCH 01/25] heading --- .../external/samples/SensorOctoQuad.java | 141 -- .../external/samples/SensorOctoQuadAdv.java | 278 ---- TeamCode/build.gradle | 12 - .../ftc/teamcode/AngelaDrive.java | 161 ++ .../org/firstinspires/ftc/teamcode/Drive.java | 155 +- .../ftc/teamcode/PestoFTCConfig.java | 84 +- .../firstinspires/ftc/teamcode/TestAuto.java | 152 ++ .../firstinspires/ftc/teamcode/Tuning.java | 1364 +++++++++++++++++ .../ftc/teamcode/constants/Constants.java | 75 + .../ftc/teamcode/subsystems/BaseRobot.java | 63 +- .../teamcode/subsystems/FeederSubsystem.java | 3 +- .../teamcode/subsystems/HoodSubsystem.java | 35 +- .../teamcode/subsystems/IntakeSubsystem.java | 12 +- build.common.gradle | 3 +- build.dependencies.gradle | 25 +- libs/PestoCore-release.aar | Bin 109993 -> 106808 bytes local.properties | 4 +- 17 files changed, 2000 insertions(+), 567 deletions(-) delete mode 100644 FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java delete mode 100644 FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java deleted file mode 100644 index f797c6b..0000000 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java +++ /dev/null @@ -1,141 +0,0 @@ -/* - * Copyright (c) 2024 DigitalChickenLabs - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - */ - -package org.firstinspires.ftc.robotcontroller.external.samples; - -import com.qualcomm.hardware.digitalchickenlabs.OctoQuad; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; -import org.firstinspires.ftc.robotcore.external.Telemetry; - -/* - * This OpMode illustrates how to use the DigitalChickenLabs OctoQuad Quadrature Encoder & Pulse Width Interface Module - * - * The OctoQuad has 8 input channels that can used to read either Relative Quadrature Encoders or Pulse-Width Absolute Encoder inputs. - * Relative Quadrature encoders are found on most FTC motors, and some stand-alone position sensors like the REV Thru-Bore encoder. - * Pulse-Width encoders are less common. The REV Thru-Bore encoder can provide its absolute position via a variable pulse width, - * as can several sonar rangefinders such as the MaxBotix MB1000 series. - * - * This basic sample shows how an OctoQuad can be used to read the position three Odometry pods fitted - * with REV Thru-Bore encoders. For a more advanced example showing additional OctoQuad capabilities, see the SensorOctoQuadAdv sample. - * - * This OpMode assumes that the OctoQuad is attached to an I2C interface named "octoquad" in the robot configuration. - * - * The code assumes the first three OctoQuad inputs are connected as follows - * - Chan 0: for measuring forward motion on the left side of the robot. - * - Chan 1: for measuring forward motion on the right side of the robot. - * - Chan 2: for measuring Lateral (strafing) motion. - * - * The encoder values may be reset to zero by pressing the X (left most) button on Gamepad 1. - * - * This sample does not show how to interpret these readings, just how to obtain and display them. - * - * 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 - * - * See the sensor's product page: https://www.tindie.com/products/35114/ - */ -@TeleOp(name = "OctoQuad Basic", group="OctoQuad") -@Disabled -public class SensorOctoQuad extends LinearOpMode { - - // Identify which encoder OctoQuad inputs are connected to each odometry pod. - private final int ODO_LEFT = 0; // Facing forward direction on left side of robot (Axial motion) - private final int ODO_RIGHT = 1; // Facing forward direction on right side or robot (Axial motion) - private final int ODO_PERP = 2; // Facing perpendicular direction at the center of the robot (Lateral motion) - - // Declare the OctoQuad object and members to store encoder positions and velocities - private OctoQuad octoquad; - - private int posLeft; - private int posRight; - private int posPerp; - - /** - * This function is executed when this OpMode is selected from the Driver Station. - */ - @Override - public void runOpMode() { - - // Connect to OctoQuad by referring to its name in the Robot Configuration. - octoquad = hardwareMap.get(OctoQuad.class, "octoquad"); - - // Read the Firmware Revision number from the OctoQuad and display it as telemetry. - telemetry.addData("OctoQuad Firmware Version ", octoquad.getFirmwareVersion()); - - // Reverse the count-direction of any encoder that is not what you require. - // e.g. if you push the robot forward and the left encoder counts down, then reverse it so it counts up. - octoquad.setSingleEncoderDirection(ODO_LEFT, OctoQuad.EncoderDirection.REVERSE); - octoquad.setSingleEncoderDirection(ODO_RIGHT, OctoQuad.EncoderDirection.FORWARD); - octoquad.setSingleEncoderDirection(ODO_PERP, OctoQuad.EncoderDirection.FORWARD); - - // Any changes that are made should be saved in FLASH just in case there is a sensor power glitch. - octoquad.saveParametersToFlash(); - - telemetry.addLine("\nPress START to read encoder values"); - telemetry.update(); - - waitForStart(); - - // Configure the telemetry for optimal display of data. - telemetry.setDisplayFormat(Telemetry.DisplayFormat.MONOSPACE); - telemetry.setMsTransmissionInterval(50); - - // Set all the encoder inputs to zero. - octoquad.resetAllPositions(); - - // Loop while displaying the odometry pod positions. - while (opModeIsActive()) { - telemetry.addData(">", "Press X to Reset Encoders\n"); - - // Check for X button to reset encoders. - if (gamepad1.x) { - // Reset the position of all encoders to zero. - octoquad.resetAllPositions(); - } - - // Read all the encoder data. Load into local members. - readOdometryPods(); - - // Display the values. - telemetry.addData("Left ", "%8d counts", posLeft); - telemetry.addData("Right", "%8d counts", posRight); - telemetry.addData("Perp ", "%8d counts", posPerp); - telemetry.update(); - } - } - - private void readOdometryPods() { - // For best performance, we should only perform ONE transaction with the OctoQuad each cycle. - // Since this example only needs to read positions from a few channels, we could use either - // readPositionRange(idxFirst, idxLast) to get a select number of sequential channels - // or - // readAllPositions() to get all 8 encoder readings - // - // Since both calls take almost the same amount of time, and the actual channels may not end up - // being sequential, we will read all of the encoder positions, and then pick out the ones we need. - int[] positions = octoquad.readAllPositions(); - posLeft = positions[ODO_LEFT]; - posRight = positions[ODO_RIGHT]; - posPerp = positions[ODO_PERP]; - } -} diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java deleted file mode 100644 index e763b9a..0000000 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java +++ /dev/null @@ -1,278 +0,0 @@ -/* - * Copyright (c) 2024 DigitalChickenLabs - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - */ - -package org.firstinspires.ftc.robotcontroller.external.samples; - -import com.qualcomm.hardware.digitalchickenlabs.OctoQuad; -import com.qualcomm.hardware.digitalchickenlabs.OctoQuadBase; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.util.ElapsedTime; -import com.qualcomm.robotcore.util.MovingStatistics; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; - - -import org.firstinspires.ftc.robotcore.external.Telemetry; -import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; - -import java.util.ArrayList; -import java.util.List; - -/* - * This OpMode illustrates how to use advanced features of the DigitalChickenLabs OctoQuad Quadrature Encoder & Pulse Width Interface Module - * - * The OctoQuad has 8 input channels that can used to read either Quadrature Encoder signals (like with most FTC motors) - * or Pulse-Width style Absolute Encoder inputs (eg: REV Through Bore encoder pulse width output). - * - * This OpMode illustrates several of the more advanced features of an OctoQuad, including Pulse Width measurement and velocity measurement. - * For a more basic OpMode just showing how to read encoder inputs, see the SensorOctoQuad sample. - * - * This OpMode assumes that the OctoQuad is attached to an I2C interface named "octoquad" in the robot configuration. - * - * One system that requires a lot of encoder inputs is a Swerve Drive system. - * Such a drive requires two encoders per drive module: one for position & velocity of the Drive motor/wheel, and one for position/angle of the Steering motor. - * The Drive motor usually requires a quadrature encoder, and the Steering motor requires an Absolute encoder. - * This quantity and combination of encoder inputs is a challenge, but a single OctoQuad could be used to read them all. - * - * This sample will configure an OctoQuad for a swerve drive, as follows - * - Configure 4 Relative Quadrature Encoder inputs and 4 Absolute Pulse-Width Encoder inputs - * - Configure a velocity sample interval of 25 mSec - * - Configure a pulse width input range of 1-1024 uSec for a REV Through Bore Encoder's Absolute Pulse output. - * - * An OctoSwerveDrive class will be created to initialize the OctoQuad, and manage the 4 swerve modules. - * An OctoSwerveModule class will be created to configure and read a single swerve module. - * - * Wiring: - * The OctoQuad will be configured to accept Quadrature encoders on the first four channels and Absolute (pulse width) encoders on the last four channels. - * - * The standard 4-pin to 4-pin cable can be used to connect each Driver Motor encoder to the OctoQuad. (channels 0-3) - * - * A modified version of the REV 6-4 pin cable (shipped with the encoder) connects the steering encoder to the OctoQuad. (channels 4-7) - * To connect the Absolute position signal from a REV Thru-Bore encoder to the OctoQuad, the Provided 6-pin to 4-pin cable will need to be modified. - * At the 6-pin connector end, move the yellow wire from its initial pin-3 position to the ABS pin-5 position. This can be done easily - * by using a small flathead screwdriver to lift the small white tab holding the metal wire crimp in place and gently pulling the wire out. - * See the OctoSwerveDrive() constructor below for the correct wheel/channel assignment. - * - * 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 - * - * Note: If you prefer, you can move the two support classes from this file, and place them in their own files. - * But leaving them in place is simpler for this example. - * - * See the sensor's product page: https://www.tindie.com/products/35114/ - */ -@TeleOp(name="OctoQuad Advanced", group="OctoQuad") -@Disabled -public class SensorOctoQuadAdv extends LinearOpMode { - - @Override - public void runOpMode() throws InterruptedException { - // Connect to the OctoQuad by looking up its name in the hardwareMap. - OctoQuad octoquad = hardwareMap.get(OctoQuad.class, "octoquad"); - - // Create the interface for the Swerve Drive Encoders - OctoSwerveDrive octoSwerveDrive = new OctoSwerveDrive(octoquad); - - // Display the OctoQuad firmware revision - telemetry.addLine("OctoQuad Firmware v" + octoquad.getFirmwareVersion()); - telemetry.addLine("\nPress START to read encoder values"); - telemetry.update(); - - waitForStart(); - - // Configure the telemetry for optimal display of data. - telemetry.setDisplayFormat(Telemetry.DisplayFormat.MONOSPACE); - telemetry.setMsTransmissionInterval(50); - - // Run stats to determine cycle times. - MovingStatistics avgTime = new MovingStatistics(100); - ElapsedTime elapsedTime = new ElapsedTime(); - - while (opModeIsActive()) { - telemetry.addData(">", "Press X to Reset Encoders\n"); - - if(gamepad1.x) { - octoquad.resetAllPositions(); - } - - // read all the swerve drive encoders and update positions and velocities. - octoSwerveDrive.updateModules(); - octoSwerveDrive.show(telemetry); - - // Update cycle time stats - avgTime.add(elapsedTime.nanoseconds()); - elapsedTime.reset(); - - telemetry.addData("Loop time", "%.1f mS", avgTime.getMean()/1000000); - telemetry.update(); - } - } -} - -// ============================ Internal (Inner) Classes ============================= - -/*** - * OctoSwerveDrive class manages 4 Swerve Modules - * - Performs general OctoQuad initialization - * - Creates 4 module classes, one for each swerve module - * - Updates swerve drive status by reading all data from OctoQuad and Updating each module - * - Displays all swerve drive data as telemetry - */ -class OctoSwerveDrive { - - private final OctoQuad octoquad; - private final List allModules = new ArrayList<>(); - - // members to hold encoder data for each module. - public final OctoSwerveModule LeftFront; - public final OctoSwerveModule RightFront; - public final OctoSwerveModule LeftBack; - public final OctoSwerveModule RightBack; - - // Prepare an object to hold an entire OctoQuad encoder readable register bank (pos and vel) - private final OctoQuad.EncoderDataBlock encoderDataBlock = new OctoQuad.EncoderDataBlock(); - - public OctoSwerveDrive(OctoQuad octoquad) { - this.octoquad = octoquad; - - // Clear out all prior settings and encoder data before setting up desired configuration - octoquad.resetEverything(); - - // Assume first 4 channels are relative encoders and the next 4 are absolute encoders - octoquad.setChannelBankConfig(OctoQuad.ChannelBankConfig.BANK1_QUADRATURE_BANK2_PULSE_WIDTH); - - // Create the four OctoSwerveModules, and add them to a 'list' for easier reference. - - // Note: The wheel/channel order is set here. Ensure your encoder cables match. - // - // Note: The angleOffset must be set for each module so a forward facing wheel shows a steer angle of 0 degrees. - // The process for determining the correct angleOffsets is as follows: - // 1) Set all the angleValues (below) to zero then build and deploy the code. - // 2) Physically rotate all the swerve drives so the wheels are facing forward in the desired 0 degree position - // 3) Run the OpMode, view the telemetry and record the "Degrees" value for each module. - // 4) Update the code by entering the recorded Degrees value for each module as the angleOffset (last) parameter in the lines below. - // - // Rebuild and deploy the new code. Verify that the telemetry now indicates 0 degrees when the wheels are facing forward. - // Also verify that the correct module values change appropriately when you manually spin (drive) and rotate (steer) a wheel. - - allModules.add(LeftFront = new OctoSwerveModule(octoquad, "LF ",0,0));// Drive = 0, Steer = 4 - allModules.add(RightFront = new OctoSwerveModule(octoquad, "RF ",1,0));// Drive = 1, Steer = 5 - allModules.add(LeftBack = new OctoSwerveModule(octoquad, "LB ",2,0));// Drive = 2, Steer = 6 - allModules.add(RightBack = new OctoSwerveModule(octoquad, "RB ",3,0));// Drive = 3, Steer = 7 - - // now make sure the settings persist through any power glitches. - octoquad.saveParametersToFlash(); - } - - /** - * Updates all 4 swerve modules - */ - public void updateModules() { - // Read full OctoQuad data block and then pass DataBlock to each swerve module to update themselves. - octoquad.readAllEncoderData(encoderDataBlock); - for (OctoSwerveModule module : allModules) { - module.updateModule(encoderDataBlock); - } - } - - /** - * Generate telemetry data for all modules. - * @param telemetry OpMode Telemetry object - */ - public void show(Telemetry telemetry) { - // create general header block and then have each module add its own telemetry - telemetry.addData("pos", " Count CPS Degree DPS"); - for (OctoSwerveModule module : allModules) { - module.show(telemetry); - } - } -} - -/*** - * The OctoSwerveModule class manages a single swerve module - */ -class OctoSwerveModule { - - public double driveCounts; - public double driveCountsPerSec; - public double steerDegrees; - public double steerDegreesPerSec; - - private final String name; - private final int channel; - private final double angleOffset; - private final double steerDirMult; - - private static final int VELOCITY_SAMPLE_INTERVAL_MS = 25; // To provide 40 updates per second. - private static final double DEGREES_PER_US = (360.0 / 1024.0); // based on REV Through Bore Encoder - private static final double VELOCITY_SAMPLES_PER_S = (1000.0 / VELOCITY_SAMPLE_INTERVAL_MS); - - // The correct drive and turn directions must be set for the Swerve Module based on the specific hardware geometry. - // Forward motion must generate an increasing drive count. - // Counter Clockwise steer rotation must generate an increasing Steer Angle (degrees) - private static final boolean INVERT_DRIVE_ENCODER = false; // Set true if forward motion decreases drive "Count" - private static final boolean INVERT_STEER_ENCODER = false; // Set true if counter clockwise steer action decreases steer "Degree" - - /*** - * @param octoquad provide access to configure OctoQuad - * @param name name used for telemetry display - * @param quadChannel Quadrature encoder channel. Pulse Width channel is this + 4 - * @param angleOffset Angle to subtract from absolute encoder to calibrate zero position. (see comments above) - */ - public OctoSwerveModule (OctoQuad octoquad, String name, int quadChannel, double angleOffset) { - this.name = name; - this.channel = quadChannel; - this.angleOffset = angleOffset; - this.steerDirMult = INVERT_STEER_ENCODER ? -1 : 1 ; // create a multiplier to flip the steer angle. - - // Set the drive encoder direction. Note the absolute encoder does not have built-in direction inversion. - octoquad.setSingleEncoderDirection(channel, INVERT_DRIVE_ENCODER ? OctoQuad.EncoderDirection.REVERSE : OctoQuad.EncoderDirection.FORWARD); - - // Set the velocity sample interval on both encoders - octoquad.setSingleVelocitySampleInterval(channel, VELOCITY_SAMPLE_INTERVAL_MS); - octoquad.setSingleVelocitySampleInterval(channel + 4, VELOCITY_SAMPLE_INTERVAL_MS); - - // Setup Absolute encoder pulse range to match REV Through Bore encoder. - octoquad.setSingleChannelPulseWidthParams (channel + 4, new OctoQuad.ChannelPulseWidthParams(1,1024)); - } - - /*** - * Calculate the Swerve module's position and velocity values - * @param encoderDataBlock most recent full data block read from OctoQuad. - */ - public void updateModule(OctoQuad.EncoderDataBlock encoderDataBlock) { - driveCounts = encoderDataBlock.positions[channel]; // get Counts. - driveCountsPerSec = encoderDataBlock.velocities[channel] * VELOCITY_SAMPLES_PER_S; // convert counts/interval to counts/sec - - // convert uS to degrees. Add in any possible direction flip. - steerDegrees = AngleUnit.normalizeDegrees((encoderDataBlock.positions[channel+ 4] * DEGREES_PER_US * steerDirMult) - angleOffset); - // convert uS/interval to deg per sec. Add in any possible direction flip. - steerDegreesPerSec = encoderDataBlock.velocities[channel + 4] * DEGREES_PER_US * steerDirMult * VELOCITY_SAMPLES_PER_S; - } - - /** - * Display the Swerve module's state as telemetry - * @param telemetry OpMode Telemetry object - */ - public void show(Telemetry telemetry) { - telemetry.addData(name, "%8.0f %7.0f %7.0f %6.0f", driveCounts, driveCountsPerSec, steerDegrees, steerDegreesPerSec); - } -} diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index aaef29f..c988850 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -15,13 +15,6 @@ buildscript { repositories { mavenCentral() - maven{ - url = 'https://www.matthewo.tech/maven/' - } - } - dependencies { - classpath 'org.team11260:fast-load-plugin:0.1.2' - } } @@ -37,9 +30,6 @@ android { } repositories { - maven { - url = 'https://www.matthewo.tech/maven/' - } } dependencies { @@ -48,7 +38,5 @@ dependencies { implementation 'org.apache.commons:commons-math3:3.6.1' implementation 'com.fasterxml.jackson.core:jackson-databind:2.12.7' - implementation 'com.acmerobotics.roadrunner:core:0.5.6' implementation files('../libs/PestoCore-release.aar') - implementation 'org.team11260:fast-load:0.1.2' } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java new file mode 100644 index 0000000..9be2d47 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java @@ -0,0 +1,161 @@ +package org.firstinspires.ftc.teamcode; + +import com.acmerobotics.dashboard.config.variable.QualitativeData; +import com.qualcomm.hardware.limelightvision.LLResult; +import com.qualcomm.hardware.limelightvision.LLResultTypes; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.shprobotics.pestocore.devices.GamepadKey; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; +import com.shprobotics.pestocore.processing.PestoTelemetry; + +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; + +import java.util.List; + +@TeleOp(name = "Robot Oriented") +public class AngelaDrive extends BaseRobot { + PestoTelemetry pestoTelemetry; + + @Override + public void init() { + PestoFTCConfig.initializePinpoint = true; + PestoFTCConfig.initializeDrive = true; + pestoTelemetry = FrontalLobe.pestoTelemetry; + + super.init(); + } + + @Override + public void start() { + } + + @Override + public void loop() { + FrontalLobe.update(); + MotorCortex.update(); + gamepadInterface1.update(); + tracker.update(); + pestoTelemetry.clear(); + teleOpController.updateSpeed(gamepad1); + + if (gamepad1.b) { + tracker.reset(); + teleOpController.resetIMU(); + } + + boolean intaking = gamepad1.right_trigger > 0.05 && -gamepad1.left_stick_y >= -0.1; + boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; + boolean rejecting = !intaking && !outtaking && gamepad1.right_bumper; + boolean neutralizing = !intaking && !outtaking && !rejecting; + + if (outtaking) { + LLResult result = limelight.getLatestResult(); + + List results = result.getFiducialResults(); + + if (result != null && result.isValid() && results.size() > 0 && results.get(0).getFiducialId() != 21) { + double rotate = -result.getTx()*PestoFTCConfig.KP; + rotate = Math.min(1, Math.max(-1, rotate)); + + if (rotate < 0) + rotate -= PestoFTCConfig.STATIC_DRIVE; + else + rotate += PestoFTCConfig.STATIC_DRIVE; + + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, rotate); + telemetry.addData("tx", result.getTx()); + } else { + telemetry.addLine("No Target :("); + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + } + } else + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + + if (!outtaking && state == RobotState.OUTTAKE) { + FrontalLobe.removeMacros("outtake"); + } + + if (intaking) { + state = RobotState.INTAKE; + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } + + if (outtaking && state != RobotState.OUTTAKE) { + state = RobotState.OUTTAKE; + + FrontalLobe.useMacro("outtake"); + } + + if (rejecting) { + state = RobotState.REJECT; + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); + feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } + + if (neutralizing) { + state = RobotState.NEUTRAL; + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } + + + // Nice little LED display on the gamepad + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) + gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) + gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) + gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); + + // Cycle hood modes + if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { + hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { + hoodSubsystem.setState(HoodSubsystem.HoodState.MID); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); + } + } + + feederSubsystem.update(); + hoodSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + indexerSubsystem.update(); + + double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; + double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; + double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; + + pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); + pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); + pestoTelemetry.update(); + + telemetry.addData("x", tracker.getCurrentPosition().getX()); + telemetry.addData("y", tracker.getCurrentPosition().getY()); + telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.update(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java index aed8585..8573dbe 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java @@ -12,107 +12,106 @@ import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; -@TeleOp(name = "Thanks Andrew") +@TeleOp(name = "Field Oriented") public class Drive extends BaseRobot { @Override - public void runOpMode() { + public void init() { PestoFTCConfig.initializePinpoint = true; + PestoFTCConfig.initializeDrive = true; + super.init(); + } - super.runOpMode(); - - waitForStart(); - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - gamepadInterface1.update(); - tracker.update(); - - if (gamepad1.b) { - tracker.reset(); - teleOpController.resetIMU(); - } + @Override + public void loop() { + FrontalLobe.update(); + MotorCortex.update(); + gamepadInterface1.update(); + tracker.update(); + + if (gamepad1.b) { + tracker.reset(); + teleOpController.resetIMU(); + } - teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - boolean intaking = gamepad1.right_trigger > 0.05; - boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; - boolean rejecting = !intaking && !outtaking && gamepad1.a; - boolean neutralizing = !intaking && !outtaking && !rejecting; + boolean intaking = gamepad1.right_trigger > 0.05; + boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; + boolean rejecting = !intaking && !outtaking && gamepad1.a; + boolean neutralizing = !intaking && !outtaking && !rejecting; - if (!outtaking && state == RobotState.OUTTAKE) { - FrontalLobe.removeMacros("outtake"); - } + if (!outtaking && state == RobotState.OUTTAKE) { + FrontalLobe.removeMacros("outtake"); + } - if (intaking) { - state = RobotState.INTAKE; + if (intaking) { + state = RobotState.INTAKE; - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - if (outtaking && state != RobotState.OUTTAKE) { - state = RobotState.OUTTAKE; + if (outtaking && state != RobotState.OUTTAKE) { + state = RobotState.OUTTAKE; - FrontalLobe.useMacro("outtake"); - } + FrontalLobe.useMacro("outtake"); + } - if (rejecting) { - state = RobotState.REJECT; + if (rejecting) { + state = RobotState.REJECT; - intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); - feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); + feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - if (neutralizing) { - state = RobotState.NEUTRAL; + if (neutralizing) { + state = RobotState.NEUTRAL; - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - // Nice little LED display on the gamepad - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) - gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); + // Nice little LED display on the gamepad + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) + gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) - gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) + gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) - gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) + gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); - // Cycle hood modes - if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { - hoodSubsystem.setState(HoodSubsystem.HoodState.MID); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { - hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); - } + // Cycle hood modes + if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { + hoodSubsystem.setState(HoodSubsystem.HoodState.MID); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { + hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); } + } - feederSubsystem.update(); - hoodSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - indexerSubsystem.update(); + feederSubsystem.update(); + hoodSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + indexerSubsystem.update(); - telemetry.addData("x", tracker.getCurrentPosition().getX()); - telemetry.addData("y", tracker.getCurrentPosition().getY()); - telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); - telemetry.update(); - } + telemetry.addData("x", tracker.getCurrentPosition().getX()); + telemetry.addData("y", tracker.getCurrentPosition().getY()); + telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 555964d..2b4c8eb 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -4,12 +4,11 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; -import com.shprobotics.pestocore.drivebases.controllers.DriveController; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; import com.shprobotics.pestocore.drivebases.trackers.DeterministicTracker; import com.shprobotics.pestocore.drivebases.trackers.ThreeWheelOdometryTracker; -import com.shprobotics.pestocore.hardware.CortexLinkedMotor; +import com.shprobotics.pestocore.geometries.Vector2D; import com.shprobotics.pestocore.processing.Cerebrum; import com.shprobotics.pestocore.processing.ConfigInterface; import com.shprobotics.pestocore.processing.FrontalLobe; @@ -19,56 +18,58 @@ @Config @PestoConfig() public class PestoFTCConfig implements ConfigInterface { - public static boolean initialized = false; // don't mess with this :O - public static boolean initializePinpoint = false; + private static boolean initialized = false; // don't mess with this :O + public static boolean initializePinpoint = true; + public static boolean initializeDrive = true; // ODOMETRY - public static String leftName = "fl"; - public static String centerName = "bl"; - public static String rightName = "fr"; + private static String leftName = "fl"; + private static String centerName = "bl"; + private static String rightName = "fr"; - public static DcMotorSimple.Direction leftDirection = DcMotorSimple.Direction.REVERSE; - public static DcMotorSimple.Direction centerDirection = DcMotorSimple.Direction.FORWARD; - public static DcMotorSimple.Direction rightDirection = DcMotorSimple.Direction.REVERSE; + private static DcMotorSimple.Direction leftDirection = DcMotorSimple.Direction.REVERSE; + private static DcMotorSimple.Direction centerDirection = DcMotorSimple.Direction.REVERSE; + private static DcMotorSimple.Direction rightDirection = DcMotorSimple.Direction.REVERSE; - public static double ODOMETRY_TICKS_PER_INCH = 505.3169; - public static double FORWARD_OFFSET = -10; - public static double ODOMETRY_WIDTH = 9.663; + private static double ODOMETRY_TICKS_PER_INCH = 505.3169; + public static double FORWARD_OFFSET = -1.565; + public static double ODOMETRY_WIDTH = 10.1; + + public static double FORWARD_VELOCITY = 76; + public static double STRAFE_VELOCITY = 61; // DROPDOWN - public static double DROPDOWN_DRIVE = 0.54; - public static double DROPDOWN_INTAKE = 0.6; - public static double DROPDOWN_PUSH = 0.420; + public static double DROPDOWN_DRIVE = 0.29; + public static double DROPDOWN_INTAKE = 0.47; + public static double DROPDOWN_PUSH = 0.29; + public static double DROPDOWN_PUSH_AUTO = 0.29; // INDEXER public static double INDEXER_OUTTAKE = 0.08; - public static double INDEXER_BLOCK = 0.26; + public static double INDEXER_BLOCK = 0.24; // HOOD public static double HOOD_CLOSE = 0.070; public static double HOOD_MID = 0.1; public static double HOOD_FAR = 0.1131; + public static double HOOD_AUTO_FAR = 0.1131; // SHOOTER - public static double SHOOTER_CLOSE = 0.73; - public static double SHOOTER_MIDDLE = 0.9; + public static double SHOOTER_CLOSE = 0.70; + public static double SHOOTER_MIDDLE = 0.87; public static double SHOOTER_FAR = 1.0; + // CAMERA + public static double STATIC_DRIVE = 0.05; + public static double KP = 0.015; + + public static double DECELERATION = 45.0; + public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); Cerebrum.initialize(); - CortexLinkedMotor frontLeft = MotorCortex.getMotor("fl"); - CortexLinkedMotor frontRight = MotorCortex.getMotor("fr"); - CortexLinkedMotor backLeft = MotorCortex.getMotor("bl"); - CortexLinkedMotor backRight = MotorCortex.getMotor("br"); - - frontLeft.setDirection(DcMotorSimple.Direction.REVERSE); - frontRight.setDirection(DcMotorSimple.Direction.FORWARD); - backLeft.setDirection(DcMotorSimple.Direction.REVERSE); - backRight.setDirection(DcMotorSimple.Direction.FORWARD); - - DriveController driveController = new MecanumController( + MecanumController driveController = new MecanumController( MotorCortex.getMotor("fl"), MotorCortex.getMotor("fr"), MotorCortex.getMotor("bl"), @@ -82,7 +83,26 @@ public static void initialize(HardwareMap hardwareMap) { DcMotorSimple.Direction.FORWARD }); + driveController.setPowerVectors(new Vector2D[]{ + new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), + new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), + new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), + new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)) + }); + driveController.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); +// driveController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + driveController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + +// driveController.frontLeft.setAccelerationMax(5.0); +// driveController.frontRight.setAccelerationMax(5.0); +// driveController.backLeft.setAccelerationMax(5.0); +// driveController.backRight.setAccelerationMax(5.0); + + driveController.frontLeft.setAccelerationMax(Double.POSITIVE_INFINITY); + driveController.frontRight.setAccelerationMax(Double.POSITIVE_INFINITY); + driveController.backLeft.setAccelerationMax(Double.POSITIVE_INFINITY); + driveController.backRight.setAccelerationMax(Double.POSITIVE_INFINITY); if (initializePinpoint) { DeterministicTracker tracker = new ThreeWheelOdometryTracker.TrackerBuilder( @@ -102,9 +122,9 @@ public static void initialize(HardwareMap hardwareMap) { TeleOpController teleOpController = new TeleOpController(driveController, hardwareMap); teleOpController.useTrackerIMU(tracker); - teleOpController.setSpeedController(gamepad -> 1.0); + teleOpController.setSpeedController(gamepad -> gamepad.left_bumper ? 0.6 : 1.0); -// teleOpController.counteractCentripetalForce(); + teleOpController.counteractCentripetalForce(tracker, Math.min(STRAFE_VELOCITY, FORWARD_VELOCITY)); FrontalLobe.teleOpController = teleOpController; FrontalLobe.tracker = tracker; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java new file mode 100644 index 0000000..2fc59cb --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java @@ -0,0 +1,152 @@ +package org.firstinspires.ftc.teamcode; + +import static org.firstinspires.ftc.teamcode.Tuning.draw; +import static org.firstinspires.ftc.teamcode.Tuning.follower; + +import com.acmerobotics.dashboard.config.Config; +import com.bylazar.configurables.PanelsConfigurables; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.constants.Constants; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; + +@Config +@Autonomous(name = "Hell no") +public class TestAuto extends BaseRobot { + private PathChain forwards; + private PathChain forwards_again; + + public static double forward_dist = 27; + + enum AutoState { + MOVING_1 (Double.POSITIVE_INFINITY), + MOVING_2 (10.0), + DONE (Double.POSITIVE_INFINITY); + + AutoState(double timer) { + this.timer = timer; + } + + double timer; + } + + AutoState autoState; + long state_start; + + @Override + public void init() { + PestoFTCConfig.initializePinpoint = false; + PestoFTCConfig.initializeDrive = false; + super.init(); + + follower = Constants.createFollower(hardwareMap); + PanelsConfigurables.INSTANCE.refreshClass(this); + + follower.setStartingPose(new Pose(0, 0)); + + autoState = AutoState.MOVING_1; + + hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); + hoodSubsystem.update(); + } + + /** + * This initializes the Follower and creates the forward and backward Paths. Additionally, this + * initializes the Panels telemetry. + */ + @Override + public void init_loop() { + super.init(); + + follower.update(); + } + + @Override + public void start() { + follower.activateDrive(); + + follower.setMaxPower(0.7); + + forwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) + .setLinearHeadingInterpolation(0, -0.22) + .build(); + + forwards_again = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(4, 0), new Pose(forward_dist, 0))) + .setLinearHeadingInterpolation(-0.22, -Math.PI/2) + .build(); + + follower.followPath(forwards); + + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + + state_start = System.nanoTime(); + } + + /** + * 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() { + FrontalLobe.update(); + MotorCortex.update(); + + if (autoState != AutoState.DONE) + follower.update(); + + draw(); + + if (!follower.isBusy() || ((System.nanoTime() - state_start) / 1E9) > autoState.timer) { + switch (autoState) { + case MOVING_1: + FrontalLobe.useMacro("outtake"); + while (FrontalLobe.hasMacro("outtake")) { + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + long start = System.nanoTime(); + while ((System.nanoTime() - start) / 1E9 < 5) {} + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + autoState = AutoState.MOVING_2; + state_start = System.nanoTime(); + follower.followPath(forwards_again); + break; + case MOVING_2: + autoState = AutoState.DONE; + } + } + + telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); + telemetry.addData("timer", autoState.timer); + telemetry.addData("state", autoState); + telemetry.update(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java new file mode 100644 index 0000000..00340a5 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java @@ -0,0 +1,1364 @@ +package org.firstinspires.ftc.teamcode; + +import static org.firstinspires.ftc.teamcode.Tuning.changes; +import static org.firstinspires.ftc.teamcode.Tuning.draw; +import static org.firstinspires.ftc.teamcode.Tuning.drawOnlyCurrent; +import static org.firstinspires.ftc.teamcode.Tuning.follower; +import static org.firstinspires.ftc.teamcode.Tuning.stopRobot; +import static org.firstinspires.ftc.teamcode.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.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.PoseHistory; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.teamcode.constants.Constants; + +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("Line Tuner", Line::new); + p.add("Centripetal Tuner", CentripetalTuner::new); + }); + s.folder("Tests", p -> { + p.add("Line", Line::new); + p.add("Triangle", Triangle::new); + p.add("Circle", Circle::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(); + + Drawing.init(); + } + + @Override + public void onLog(List lines) {} + + public static void drawOnlyCurrent() { + try { + Drawing.drawRobot(follower.getPose()); + Drawing.sendPacket(); + } catch (Exception e) { + throw new RuntimeException("Drawing failed " + e); + } + } + + public static void draw() { + Drawing.drawDebug(follower); + } + + /** 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() { + follower.setStartingPose(new Pose(72,72)); + } + + /** 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(); + drawOnlyCurrent(); + } + + @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); + + draw(); + } +} + +/** + * 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.setStartingPose(new Pose(72,72)); + follower.update(); + drawOnlyCurrent(); + } + + /** 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); + drawOnlyCurrent(); + } + + /** + * 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() - 72) / follower.getPoseTracker().getLocalizer().getForwardMultiplier()))); + telemetryM.update(telemetry); + + draw(); + } +} + +/** + * 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.setStartingPose(new Pose(72,72)); + follower.update(); + drawOnlyCurrent(); + } + + /** 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); + drawOnlyCurrent(); + } + + /** + * 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() - 72) / follower.getPoseTracker().getLocalizer().getLateralMultiplier()))); + telemetryM.update(telemetry); + + draw(); + } +} + +/** + * 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.setStartingPose(new Pose(72,72)); + follower.update(); + drawOnlyCurrent(); + } + + /** 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); + + drawOnlyCurrent(); + } + + /** + * 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); + + draw(); + } +} + +/** + * 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() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** 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(); + drawOnlyCurrent(); + } + + /** 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(); + draw(); + + + if (!end) { + if (Math.abs(follower.getPose().getX()) > (DISTANCE + 72)) { + 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 left 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() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** + * 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 left."); + 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(); + drawOnlyCurrent(); + } + + /** This starts the OpMode by setting the drive motors to run left 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(); + draw(); + + if (!end) { + if (Math.abs(follower.getPose().getY()) > (DISTANCE + 72)) { + 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 = 60; + + private double previousVelocity; + private long previousTimeNano; + + private boolean stopping; + private boolean end; + + @Override + public void init() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** 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(); + drawOnlyCurrent(); + } + + /** 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(); + draw(); + + 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 left 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 = 60; + private double previousVelocity; + private long previousTimeNano; + private boolean stopping; + private boolean end; + + @Override + public void init() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** This initializes the drive motors as well as the Panels telemetry. */ + @Override + public void init_loop() { + telemetryM.debug("The robot will run to the left 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(); + drawOnlyCurrent(); + } + + /** 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(); + draw(); + + 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() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** 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(); + drawOnlyCurrent(); + } + + @Override + public void start() { + follower.deactivateAllPIDFs(); + follower.activateTranslational(); + forwards = new Path(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))); + forwards.setConstantHeadingInterpolation(0); + backwards = new Path(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))); + 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(); + draw(); + + 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.addData("Zero Line", 0); + telemetryM.addData("Error X", follower.errorCalculator.getTranslationalError().getXComponent()); + telemetryM.addData("Error Y", follower.errorCalculator.getTranslationalError().getYComponent()); + 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() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** + * 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(); + drawOnlyCurrent(); + } + + @Override + public void start() { + follower.deactivateAllPIDFs(); + follower.activateHeading(); + forwards = new Path(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))); + forwards.setConstantHeadingInterpolation(0); + backwards = new Path(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))); + 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(); + draw(); + + 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.addData("Zero Line", 0); + telemetryM.addData("Error", follower.errorCalculator.getHeadingError()); + 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() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** + * 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(); + drawOnlyCurrent(); + } + + @Override + public void start() { + follower.deactivateAllPIDFs(); + follower.activateDrive(); + + forwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))) + .setConstantHeadingInterpolation(0) + .build(); + + backwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))) + .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(); + draw(); + +// if (!follower.isBusy()) { +// if (forward) { +// forward = false; +// follower.followPath(backwards); +// } else { +// forward = true; +// follower.followPath(forwards); +// } +// } + + telemetryM.debug("Driving forward?: " + forward); + telemetryM.addData("Zero Line", 0); + telemetryM.addData("Error", follower.errorCalculator.getDriveErrors()[1]); + 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 Line extends OpMode { + public static double DISTANCE = 40; + private boolean forward = true; + + private Path forwards; + private Path backwards; + + @Override + public void init() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** 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(); + drawOnlyCurrent(); + } + + @Override + public void start() { + follower.activateAllPIDFs(); + forwards = new Path(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))); + forwards.setConstantHeadingInterpolation(0); + backwards = new Path(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))); + 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(); + draw(); + + 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() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** + * 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(); + drawOnlyCurrent(); + } + + @Override + public void start() { + follower.activateAllPIDFs(); + forwards = new Path(new BezierCurve(new Pose(72,72), new Pose(Math.abs(DISTANCE) + 72,72), new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72))); + backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72), new Pose(Math.abs(DISTANCE) + 72,72), new Pose(72,72))); + + 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(); + draw(); + 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(72, 72, Math.toRadians(0)); + private final Pose interPose = new Pose(24 + 72, -24 + 72, Math.toRadians(90)); + private final Pose endPose = new Pose(24 + 72, 24 + 72, 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(); + draw(); + + if (follower.atParametricEnd()) { + follower.followPath(triangle, true); + } + } + + @Override + public void init() { + follower.setStartingPose(new Pose(72, 72)); + } + + @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(); + drawOnlyCurrent(); + } + + /** 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(72, 72), new Pose(RADIUS + 72, 72), new Pose(RADIUS + 72, RADIUS + 72))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) + .addPath(new BezierCurve(new Pose(RADIUS + 72, RADIUS + 72), new Pose(RADIUS + 72, (2 * RADIUS) + 72), new Pose(72, (2 * RADIUS) + 72))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) + .addPath(new BezierCurve(new Pose(72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, RADIUS + 72))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) + .addPath(new BezierCurve(new Pose(-RADIUS + 72, RADIUS + 72), new Pose(-RADIUS + 72, 72), new Pose(72, 72))) + .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) + .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(); + drawOnlyCurrent(); + } + + @Override + public void init() { + follower.setStartingPose(new Pose(72, 72)); + } + + /** + * 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(); + draw(); + + 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.75 + ); + private static final Style historyLook = new Style( + "", "#4CAF50", 0.75 + ); + + /** + * 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/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java new file mode 100644 index 0000000..25cb2fe --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java @@ -0,0 +1,75 @@ +package org.firstinspires.ftc.teamcode.constants; + +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.Encoder; +import com.pedropathing.ftc.localization.constants.ThreeWheelConstants; +import com.pedropathing.paths.PathConstraints; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.HardwareMap; + +public class Constants { + public static FollowerConstants followerConstants; + + public static PathConstraints pathConstraints = new PathConstraints(0.99, 100); + + public static MecanumConstants driveConstants = new MecanumConstants() + .maxPower(1.0) + .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 ThreeWheelConstants localizerConstants = new ThreeWheelConstants() + .forwardTicksToInches(0.001978956176) // TODO: tune + .strafeTicksToInches(0.001978956176) // TODO: tune + .turnTicksToInches(0.001978956176) // TODO: tune + .leftPodY(5.05) // TODO: tune + .rightPodY(-5.05) // TODO: tune + .strafePodX(-1.565) // TODO: tune + .leftEncoder_HardwareMapName("fl") + .rightEncoder_HardwareMapName("fr") + .strafeEncoder_HardwareMapName("bl") + .leftEncoderDirection(Encoder.FORWARD) + .rightEncoderDirection(Encoder.FORWARD) + .strafeEncoderDirection(Encoder.REVERSE); + + public static Follower createFollower(HardwareMap hardwareMap) { + followerConstants = new FollowerConstants() + .useSecondaryHeadingPIDF(true) + .useSecondaryDrivePIDF(true) + .useSecondaryTranslationalPIDF(true) + + .headingPIDFSwitch(0.2) + .headingPIDFCoefficients(new PIDFCoefficients(1.6, 0, 0, 0)) + .secondaryHeadingPIDFCoefficients(new PIDFCoefficients(0.8, 0, 0, 0)) + + .drivePIDFSwitch(2) + .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0.01, 0.6, 0.0)) + .secondaryDrivePIDFCoefficients(new FilteredPIDFCoefficients(0.0, 0, 0.01, 0.6, 0.0)) + + .turnHeadingErrorThreshold(0.05) + + .mass(7.7); // 7.7kg == 17lbs + + followerConstants.setForwardZeroPowerAcceleration(-40.3); + followerConstants.setLateralZeroPowerAcceleration(-85); + + driveConstants.setXVelocity(79.8); + driveConstants.setYVelocity(64); + + return new FollowerBuilder(followerConstants, hardwareMap) + .threeWheelLocalizer(localizerConstants) + .pathConstraints(pathConstraints) + .mecanumDrivetrain(driveConstants) + .build(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java index b6f629b..08c6a5f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java @@ -1,6 +1,8 @@ package org.firstinspires.ftc.teamcode.subsystems; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.hardware.limelightvision.LLResult; +import com.qualcomm.hardware.limelightvision.Limelight3A; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; import com.shprobotics.pestocore.devices.GamepadInterface; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; @@ -9,7 +11,7 @@ import org.firstinspires.ftc.teamcode.PestoFTCConfig; -public class BaseRobot extends LinearOpMode { +public class BaseRobot extends OpMode { public MecanumController mecanumController; public DeterministicTracker tracker; public TeleOpController teleOpController; @@ -20,6 +22,8 @@ public class BaseRobot extends LinearOpMode { public OuttakeSubsystem outtakeSubsystem; public IndexerSubsystem indexerSubsystem; + public Limelight3A limelight; + public GamepadInterface gamepadInterface1; public RobotState state; @@ -32,10 +36,11 @@ public enum RobotState { } @Override - public void runOpMode() { + public void init() { FrontalLobe.initialize(hardwareMap); - mecanumController = (MecanumController) FrontalLobe.driveController; + if (PestoFTCConfig.initializeDrive) + mecanumController = (MecanumController) FrontalLobe.driveController; if (PestoFTCConfig.initializePinpoint) { tracker = FrontalLobe.tracker; tracker.reset(); @@ -49,6 +54,11 @@ public void runOpMode() { outtakeSubsystem = new OuttakeSubsystem(); indexerSubsystem = new IndexerSubsystem(); + limelight = hardwareMap.get(Limelight3A.class, "limelight"); + + limelight.pipelineSwitch(0); + limelight.start(); + gamepadInterface1 = new GamepadInterface(gamepad1); // State initialization @@ -76,5 +86,48 @@ public boolean loop(double v) { return true; } }); + + FrontalLobe.addMacro("limelight - align", new FrontalLobe.Macro() { + @Override + public void start() { + + } + + @Override + public boolean loop(double v) { + LLResult result = limelight.getLatestResult(); + if (result != null && result.isValid()) { + telemetry.addData("tx", result.getTx()); + telemetry.update(); + + double rotate = -result.getTx() * PestoFTCConfig.KP; + rotate = Math.min(1, Math.max(-1, rotate)); + + if (rotate < 0) + rotate -= PestoFTCConfig.STATIC_DRIVE; + else + rotate += PestoFTCConfig.STATIC_DRIVE; + + teleOpController.driveRobotCentric(0, 0, rotate); + } + + return v > 2.0; + } + }); + } + + @Override + public void init_loop() { + + } + + @Override + public void start() { + + } + + @Override + public void loop() { + } -} +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java index ff2d593..705e267 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java @@ -28,10 +28,11 @@ public void setState(FeederState state) { public void update() { if (state == FORWARD) - feeder.setPowerResult(0.7); + feeder.setPowerResult(1.0); if (state == REVERSE) feeder.setPowerResult(-1.0); if (state == STOPPED) feeder.setPowerResult(0.0); + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java index ca43ba4..2dfecc1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java @@ -1,31 +1,40 @@ package org.firstinspires.ftc.teamcode.subsystems; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_AUTO_FAR; import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_CLOSE; import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_FAR; import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_MID; +import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.AUTO_FAR; import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.CLOSE; import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.FAR; import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.MID; +import com.qualcomm.robotcore.hardware.DistanceSensor; import com.shprobotics.pestocore.hardware.CortexLinkedServo; import com.shprobotics.pestocore.processing.MotorCortex; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; + public class HoodSubsystem { private final CortexLinkedServo hood; private final CortexLinkedServo led; + private final DistanceSensor distanceSensor; private HoodState state; public enum HoodState { CLOSE, MID, - FAR + FAR, + AUTO_FAR } public HoodSubsystem() { hood = MotorCortex.getServo("hood"); led = MotorCortex.getServo("led"); + distanceSensor = (DistanceSensor) MotorCortex.hardwareMap.get("distance"); + state = CLOSE; } @@ -37,20 +46,38 @@ public void setState(HoodState state) { this.state = state; } + public double getDistance() { + return distanceSensor.getDistance(DistanceUnit.CM); + } + public void update() { + boolean ledOverride = distanceSensor.getDistance(DistanceUnit.CM) < 10; + + if (ledOverride) + led.setPositionResult(0.39); // YALLOW + if (state == CLOSE) { hood.setPositionResult(HOOD_CLOSE); - led.setPositionResult(0.5); // GREEN + if (!ledOverride) + led.setPositionResult(0.5); // GREEN } if (state == MID) { hood.setPositionResult(HOOD_MID); - led.setPositionResult(0.61); // BLUE + if (!ledOverride) + led.setPositionResult(0.61); // BLUE } if (state == FAR) { hood.setPositionResult(HOOD_FAR); - led.setPositionResult(0.28); // RED + if (!ledOverride) + led.setPositionResult(0.28); // RED + } + + if (state == AUTO_FAR) { + hood.setPositionResult(HOOD_AUTO_FAR); + if (!ledOverride) + led.setPositionResult(0.28); // RED } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java index e663faf..83129f9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java @@ -4,9 +4,11 @@ import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_DRIVE; import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_INTAKE; import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_PUSH; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_PUSH_AUTO; import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.INTAKE; import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.NEUTRAL; import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.OUTTAKE; +import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.OUTTAKE_AUTO; import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.REJECT; import com.shprobotics.pestocore.hardware.CortexLinkedMotor; @@ -23,7 +25,8 @@ public enum IntakeState { INTAKE, NEUTRAL, REJECT, - OUTTAKE + OUTTAKE, + OUTTAKE_AUTO } public IntakeSubsystem() { @@ -46,7 +49,7 @@ public void update() { } if (state == NEUTRAL) { - intake.setPowerResult(0.0); + intake.setPowerResult(0.15); dropdown.setPositionResult(DROPDOWN_DRIVE); } @@ -59,5 +62,10 @@ public void update() { intake.setPowerResult(1.0); dropdown.setPositionResult(DROPDOWN_PUSH); } + + if (state == OUTTAKE_AUTO) { + intake.setPowerResult(1.0); + dropdown.setPositionResult(DROPDOWN_PUSH_AUTO); + } } } diff --git a/build.common.gradle b/build.common.gradle index a1d2fa4..0ac4c94 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 { @@ -114,4 +114,3 @@ android { repositories { } - diff --git a/build.dependencies.gradle b/build.dependencies.gradle index 6221530..fa68f63 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -5,6 +5,7 @@ repositories { maven { url = 'https://maven.brott.dev/' } maven { url = "https://repo.dairy.foundation/releases" } + maven { url = "https://mymaven.bylazar.com/releases" } flatDir { dirs rootProject.file('libs') @@ -12,19 +13,23 @@ repositories { } dependencies { - implementation 'org.firstinspires.ftc:Inspection:10.1.1' - implementation 'org.firstinspires.ftc:Blocks:10.1.1' - implementation 'org.firstinspires.ftc:RobotCore:10.1.1' - implementation 'org.firstinspires.ftc:RobotServer:10.1.1' - implementation 'org.firstinspires.ftc:OnBotJava:10.1.1' - implementation 'org.firstinspires.ftc:Hardware:10.1.1' - implementation 'org.firstinspires.ftc:FtcCommon:10.1.1' - implementation 'org.firstinspires.ftc:Vision:10.1.1' - implementation 'androidx.appcompat:appcompat:1.2.0' - implementation "dev.frozenmilk.dairy:CachingHardware:1.0.0" implementation 'io.github.william27b:dashboard:0.15.03' implementation 'io.github.william27b:core:0.15.03' + + implementation 'org.firstinspires.ftc:Inspection:11.0.0' + implementation 'org.firstinspires.ftc:Blocks:11.0.0' + implementation 'org.firstinspires.ftc:RobotCore:11.0.0' + implementation 'org.firstinspires.ftc:RobotServer:11.0.0' + implementation 'org.firstinspires.ftc:OnBotJava:11.0.0' + implementation 'org.firstinspires.ftc:Hardware:11.0.0' + implementation 'org.firstinspires.ftc:FtcCommon:11.0.0' + implementation 'org.firstinspires.ftc:Vision:11.0.0' + implementation 'androidx.appcompat:appcompat:1.2.0' + + implementation 'com.pedropathing:ftc:2.0.4' + implementation 'com.pedropathing:telemetry:1.0.0' + implementation 'com.bylazar:fullpanels:1.0.9' } diff --git a/libs/PestoCore-release.aar b/libs/PestoCore-release.aar index c94ce0a7f42a3c44f442062ac7e03f8ff5af2559..44d9c7e6fe551e4aca69b97048e49167667d1e1f 100644 GIT binary patch delta 86157 zcmV(tKX5F_g z8ao{u9XlO#?2c_G9Xokrvt!$~ZS#$7+qQZ7?7h#e`~A+XbNAkLR;@Lw#;Enz^9(#= z&M7Yi4gvD_fdL_gAqGQ464R9f1pzt#`_caO8rlFD9L#L(Z47K2f6WaY7;KFl9BmA3 z?2Q=&oy@I_glw!$%uRn7TIoADM8=NE_6eW|eeKMW_z~&MG~U$ZFxdq&ndhP!iuBR< zBBmyx1SNbs8F;cc-tB|F&W)I}h$&3}dG~RY@$N9`>D}oA($Z%~NL`>}1UD>5Of_`^ zzo308(4zpp*Pz#QA4o5F39%XnnQI#`#X`D!SwP%j z%11uTCSy2FLL>(vLJdXy&`0b{)4LR(0cnms(B9IAYMis#7D|#W{bruaAJqpIH^?mkH0%fk3IkBL_Qx_3)aYbb zwT-)R`xmTL!+4=zWIFN64FSIA19-!higlFvaUpPz#&qxK+aSRs&gBvdGwkyJ;H3gu zJ|gC?%>xSpf5QHMo#E^MO$(&=C zw9$n?{7Ip?kHIQ#0wMGxU~`D1^m_dw&et((L&#^V)G;L=Ep_hFz7Hdjl`_jGu6f*o zx{XWS5|rMLTN~l{ms^!uw0X>XxxYG29Y_24ydw4he>n6Zrb&oPhyqlDCVzj(tI@Wp zsD8J;#3fJ8eW)@|z2pr_Qtz0C!U3T6!Tk`>Kd#TLvp83!Jx#hiJ$;Y66V700nXddds`Nq z-#Z*n7~^bv`^Mu;+OCpOQ+fF_1Hzde^i<*w3@16F19&1h;q$F@oCj#(K-f91h*;Vs ze^?h*+#@C=bfa{GI_4ypl%EQe#a6r2F772nTl)>fhKV~Q{3hNk=^-dZJ(@~2oBK&e zz&G(;sId7lFW~R`(su_g7Jk_cm_1m&#OqYQsh3PH!{blWu(){y(>3QZ)Gj0O&Kvq+ z^#-dmd}0WmZaPe-;e0Y91(Pu9AE=8w#<5iDHNo5shMcyq)CO+R=*D z8ftL}keEur9E>paq>FHydKSjUnHq*QT=}UQklVRU5$LSB*RK$#$?QiQG4n+6XbY`t z2(}eBZ>G1hOUEO_nTvUF24ScY#K}!$0;N$s!M37f#4ZNC{CA! z^k4-)4gmz8Tf`8ViFk%=Y_6}nfP0g*kw2^dc$wHvooo-8LM;U>ZTkGP$Vn%k(!c+;CjT}cf&WgCld%4~nCKfC|3|fp zVUhzfA_q=E#x=-O(V}{^Z3jYP{}RVgPNXvE=Bhdyt|fg_yjjD3e+GT03Lwap4ap_E zJQ+E9s<=9P+d~7X+TjTX_1D_LC1k5~p%v4F*c=s*6^gSyCPBl{R1 ztQ948;4oq=wF_U*QSq!TDFphfI@K&2+ zhZ2ctAS+n5tv3}4e;d(apw0aBl&8pc0xSe$S|s~u$bL!aGe(s^S%>T7W7zpLIA&ro z*M%MK%Gs)gY77!B3UX=eyF%cQWpSc+e$$^nyQ${)wW}_c*c+?ofM$FF{U@@&fsfxJ z!9YMH|N1!ov&c%@xXAxS@&DaF65}T1(0*YLW}h@|G|>U5e{~CK^6~&`#%Mqp0~U0o zA{yAD(2RBKA!q#)mU^x0Q{CL&{&F$@FtW7c4Sq>4Q*|le#F%Ht-Q<TefLy0ZPBjdU_^e$HP9=@ z8UUJG&~2(O^j95Q0XlQA1h%C2s37bd0yR7Ky>{EO{EP;?15Fx^c-K|9eu@wdJOvHr zk8Kj6orreA7(SqOaB$atX6(4?z9>+BsdXZzg7uU>e{E4Dcqsuh1Mnl88i-I> zbiJN)AgOz?r^kHyBCHPh^wGU!mW~6rd8*|OF{d68l4a2ALci@v%v4fBq>~G?{?kRT~3@=H7FJW~33uYb)^fVw~#u@%jG(6b{bPSE{n?W6+7Dk0MQYctRz-*AM9`HjLBi*-%e~`{5J!lxfLCq#0Ef5PhYe7NNkylRC ztnJQG-=Hrkl>&}eJq=f(HGJ9$Pn=mNl`cc#(x!D37$z$Gq$xQykyg54#ZBzyI#-_{ zjh|0RsH-s=5g40GJfA?{5AqXQcOnYptHZxPRG!+EJzzxU$(YaU7_QqwryN*_?@lblq=fv4sDgQF`vp5cIdU0BMBbqAd&`5tcgJC)C<+tYMi4A^1n_j1_~e}$^C zkkNd3E;7b{UFA4{J(u|sOH_@OzBrH6)1*(7MJ?&*(Hyb4&^q7m=*s(`vRUX!_d%5} z`X>_EZ#bM)9dTO&fV(u-ScuxF&FTXd&*51|?glbA;PHIni!W05oNL%3-_6le+@a&VX0agT-4oAOd^FfJ+k}`c1^w|}^#0=st8GBWA zY2w*b9K#c>d@4_t(laDFr|)^%DdtYJ2){2+^~_(I_G2=chb%?Ulw=&?7Im6=O!D14 zon$QER|>igRN#)JIHovuQ&j6-=W>=x9K$O{M&V z#GmQDr0ZtIRrc0LPf+oE5_W%f1j6WGbmKXMx`H_L;soCufWP2y*=le+jeKWjvr9N7 zoMoqXN4Z4CE#dTYe=eM~g_WHmzcOkApQ3B~%2Gb0jNSP28Id)`Jn7_*^t=kArya){0it(kSHTEtUKYHe>#*gt=OeBPG+G{l2aqd z+u=rpcT7$2R3CnnjMt-&;;(VZZQ3YeHZRAoHPF=!lHb~5iBxR=LD7v57CRq)+P@XE zC&CBVTC0CBi3KMJwTA~k%ZC;rZRv}JnxJoOlV&-3?-27HQj3nG^ZCB-^5t3aA5i;F z&0k3$v?^#^{&aE0Y!M*|rX+8z}Vf%CW zbNJzyHZ|`fDmU1Fw%=`zn^k|lcR^g^M}s#^KknS`fAkqH^BrWnDPF52d8TBC%`>_( z97v|AAzZj#aR@;F{{HJb?>$bOa-u|Hbz>SW=^Twl_-Ki;dF(Zbl4e>*MVv-y!icG8 z1~X{Oc+ z>@1nDfBG0KgwN1f-4-4B;2R^s1;(1{1{m%@4kjB+99YN3@!P@8G@Ps-TX#;RgyZw6 zvIANg+&hRbzj%dt3KbfylmHgtMN)6{x2S@m$CqCaZ@)z0f$k7&%Y%T`wBlhB@rj3?`q_=1F`YasXf4G;0cbczkfiexXPK$8hW9r?ZgiX|UMUVRVw|_8i z96iJM8WMS5;s42ftbcD=J~#--J@o&dA~P~}Ha9eOU=Y&>7~AR_{j0`Rky1j_K>xHR ze`JBh3KW+YKo9gK6V^oeZkRGo6(R~WjL6GLmpX!@&*h%m__aKhopNEdK5kOR$YGdx zu==$<`=zImgXpFR$=02_l z^Wh{=Z1x%(S5#)~z7C;R*q+T#RG3AWe>1HICkW9)#3gw&s#DLSXy?@U#Jx$MTajT@ zWiF=5Tc%>Tj_Qz3jteP}7^h)C4q1q~`rW5I1hrGmF?+y82UYf_Hb-cJJAVfRNUW

kORDg#cNd}V?ACy76=Cv)pNO~v`w$bpX-LXt1nF-z#hW%4qvsj}oGf##SK$kR zROj6Qi&Kf9tbP}n`1-OCFMR%->^8bEVZ!Rx^OOK-dz}?>jyQ29mb3yn*Cya}miQ%1 zO!-bKMS-0p5IHz%4x#odZJLe_f7V5^%I(u}f;L(|svbL+Pm^!`G1a3OHF4c73cf{L zrZgeEFTYlj@{w1@B5JRtKem@jge}|>fv&i2%>F$>7e*@~t4#0`Z>HKdqO_odc)r~3 zt+sHw93KsC!Sh~LLw||W9uEEu+YNnOM9LK-m`u(KATD;6R&l{JV)RqFe}So8yaW2K zh`gAF7Jjys9#b-)|F(%(vc8XL;R+X9Th%Y(lht0&g{gs(lu*W({o=F{QN1&hsT0LTS(*#6>yC#TG~< z-DCjyvBxLU>o)KiE+qnIxtRr;k^J_wiBi z1@JUu1ZnH;2`M?1?i+)xlDpl@uiI2{ypUjRiRy#mM}iQ$32j}ta|e>dMrV#K?G>PvXT#)aKcE( z5;J*LzR~eo`BoH*%SBu|#!vv-)*^~dtXB)n{b4{80%Al^f732EST;P0Jc>DwPBm1g z5q;;kOh2C9kKT_q+%9=P9B&~06l!)xG2#A*;0DI7%Tt^oa9A^Eg&Un`ob_i`5J)V0 z#M^OWY1kmH;n3F3@FDv_bqgSZ;WjMbVv0_QZA{+g2#AkzuasdR&$eY$y8A+zKh(0S z_88GNn2epWe|}iH|5zJ8cl8xD0mf~tc6tjj%%MS2L_&!zRmGp9`<9NM#%(kOww{3f zOesIe`J4o#H&twmzSH@xjKina_uY{AQaDE>`l;KvEQ#JeK0XeAY7;R=cbZ5z7qyGz zsF)<~>cDC0j=JaefH}`6I$~sn^pHG4cz8590dk^#f3~XY!B*nj7hRO+uPqKzSslH| zcw>**#YPo^VHpMnrMZqutg&QI(9div>d?m3&HBe?`EEF`7cM(j%-^8;sK3cqIJu4x$ z=!UrJonE6M7Ttr{p$z27>Y}|>4YTDSp;VaMh)I+=uP@n=A*>8I+uswaE4_dr4bmZ4 zbG2@otHQo;DBdfuqMaaJQQ$O+PTuO)&Ozcfe_N>^=_PK?7UkqHGo`+2>meVq+3v>U zJU;;Yz^71rtg=Vvrt<~8?9iA!GTV5%N810rBvH>ztXJ<*F`s!tfR1fYO%)1#3rtm9 z+yL`fR-iS`f3FcpbL0Kxe>G*AG6tjFt1WI%r^iOQ&5V~+F+O##!}DzIor&vYFy9vJBycFuO9?OuL{^ zqCKm48bbZ}P{utTw8n@^iUqztNQzTzf2`D!p^WTgcB8U4{CSW|VO! zos)#zsENFkfsJEf?XpQ>Iv2Ku53UC*x59-;RyDJs37M8*T$5RzqIOLD$uU#I@D53Q zZq5Ly#^y1}LIa5Xz{aTs}ITTga&Wmq75Wr(&E+1tACHs>?^6352~xYrjPzvH5iik*_G9Y z(6+bvM|hGZ zMjg8%k^=vNDv&FFR^iwmU?|ic50a^Tz}E3ZT_s@lG4}NJ7NLdWpOfdA3=Vl1k$#5&DN-85aV(uGs2z{fFpbUb6x$bX9WbP~ ze}S29;tM!sLatgU)U#E$T|Ttt^SZ zj#UvvXD)3ZZ1}*xfAcYTZTkB|q^Uxa#I& zUqKwW%F#U71$HTvcI%dI6;4Mhoqm@;jfd+jo#!u^FGhD4D)kXBbwPiHD*V(hEuQDko4-;!woH5#OMF$MzSl4OWGeh@g!2+Ff90>7*DalfPJGoGQ@NDX zko!|GW6RLMrwiJpp4|Q zn@^&1;)-Ece=~ZP{NXVzjbw92L0_WtCo!O zx5z)gX3u!+{m81>9sT>+UH6S7Hq9Uq<9vEZizRL;NR0x*o^!+|6ZR)WmtnAOh@&$| zN09IuMFA+^Z-!gr-b;uP6#9pF>NMiMv!6z^k?`%rf8LS5NaSypFzjMRYr7(3b44@> z9kgB)_>aN!MX^moHo&S)i$=}r9~Xls77Dpxyx8RJ+J=zGD#W_`!EGp|lq~4Qu|X;| z!c>k8L*77oD(og-8~2?_d|;F{Z4J8I6fC`Zw?5?CpA{c0GK^O0CTn%mHfPZ^e`;HQ zRIb08f3`kk+n@Q6(gUPhRs1O%b9k)NFlQ|qxum_J{wYrmfdikDf9Fv)C=d|t|Drtk zm(iq9c}*5g0sVKdPEZo{G}r-!-=AqrqmCRiNmqG)rgGi*b&hf!Ea6 z;9buKB)DFTeCf|pr+meb2Iep`!C79Z^^ZE1e=d*j&kqlHf82ON@)3y<^$AdfaoSv- z3E64ZH<@)3oC9zeg|X<@;F7QfQ_tNIE<(&h&W`^~+AcYk1$AGz%Z|X(&9Q6mKu4Xp z_EClNj-hwm1gHg$jnVFImlD9(#Hafao4hda?!4uVGb+mSTKcLmu~|0Zs7C?l*fTn; zf0j%0;WrRgt2kWG&({#FgbtOs+>Q8z-Ef{x#K$-UZ_?I$K@lvlXPF{s5r9~Z#4s)! zqo6?LqG=vq&qq&5pi0ob#%u1LGDPzpc5h0QCAR6b)WbSg^?U&CCe(>eW0Mu(JkKaP z!)&K|OuU!Y9!8yt(1co~Q@Y22m#nN|f7MGLC+15b4^aKEuhwJf9n+b zSQ7r4KseLX2#Q{Wb8h4!cSM4=5~H;Ie2~QJ3<-62vHsks=&>xs5_MMIFeUAcf9sT9 zYpS7H>ogPUt@vpE6F4t|e%d6l@QJj1xom%lD`n!@uQ*kPKm=ZiC3xa+{G1N1T%6m& zN>d6s>d814a0f?868_Tgek_O9e`s++{g4Q@JID{fb5yJxHg5o?cW{jXWi@_Qx4ol# zA^XyM#C?W@L@Z2BbVxyMgtt{p$WPb-C0G&c76}NOSpM*9Jj9D`a+f+>YuYi_ax(ox zrp*|WKh!TMy9ut<4N|BIiTJ9KXLq42xN}2I(EbmtX&K zpduSqIG79y0%HHyC;ER*6MJ)KV*`DMznNlaW9?{fV`XJ*@4z7ZKixwAkK^AnW+8q; zc1-|Xv|CCD!CWw&tpOJDHCVYmr#@6!1%t|hj*KjigrxS*LVuS`1ioB~U0-|cHs~vf zS9sV>NtonH!1-xl^vB3if7H;^>(N!Z76`rPb&arDum#z;ZH0=iv7K3eicFDUp@uM5 zmc1@68;P=ckxE<*8_DqAB;B<oHyRf3N6%&*H3|igFT) zhQrOf$rG{(0<|1#_>6j0%G0z5cEVBf3YHzcPYWa~wPxn+aYR9zaeS1l=XPJ2iI0YD z=oetQ#ptRGTJABlFMRSBL}6CiaSYO4|K|J`PLQwbwXkcrb#N!jd`$X>@T#MA6a6LT z#uI*-Y540jq zI-)pST!=@yv5^y|x$%}yUW#rom_3~lAe8T96L|;j&+{E~f5B*Dtns_fll2zPb<>&7 zs^dS7Ht|t!(`53j20yQL90JN4TwwjB-U>;qXKFRl5UAoQXY&mqOFu)R=oNo+8WjwZ z$0#?Qe}vGumMROe_Cq>XQIH^BfGKd^ok)-Z+0y0jj%1~Z=C_58z{T~_gD$w7x4nIz z-(+}pVY~(*o~}wH@|>F=k{(^<28WN@N6|ml5nE@f%&y*fj^T)cqDK$b$fp&wyNp}c z$>U9?GRA5Aly|!%t*ZKyB!$5XoVr=O1#*r)e4Ai# ztbrlT6G-fF;PI*5I3OyNW+BuoT{weR-MqfoGB%2t~- z(RQyzMq-yAYer|GBN-WcDW`LG=+SWVbMw@5O;IBV{AN)&O6K7>-99hQSmVyjr!7%v zf5((+mFq}F^uS@tIX6S9eCDr&plJ92DPevN?$a26mNN+DPHF!h7`;TZ9*Z&MU0@M$ z{1^OOQL5$YqS1a(dec~M@xEd%pS6xcNTXeRVppQGu8lHOJ6=(Y8b23dzxXi0OVloQEMy8@NJejIl;6qLWr%B}e zb$7d9i_-hEh?b1+%Ukk7+zJ zAE3XkmB4H&n_+n{)N7Yv|;{Q>qw#He1xpj>Qzho9K$3($Pz5p zSeE4NvH`DxzkE_X=?^3q%N>{os4un7^y&Us1j8EFONQbFW^rU$lVF#l$`~|74F%m* z=KDAME~KLu4_{p$u|K*!e~wmABt@O@fN6(#{@!hbvRCL%#j0SP_uGk=+vLIDLI65f z#E05+7^FedX;(zN#155_2}x@;`|>!vj#E;570zb_A1(Qjt;XxwUTY{jm4B*ikWon{dB>TZB zHyM2S=Y33ow}~n5!ck8Q$8kO|YS*n}TfnE+x2vCNRxsSpfB8={SIxyYGk+J9@!tq8 z?7$76EjP~MW}UQ|9h26zh^IuQDSVf7X$zrl?!LmT8uf_uw${o)cb<6a-VBO}NG-r= zHN@(OyCM4G&2`dZ`Ap+h$kjG^qfVr2s$yVVm(*WI#}fA4JN@dvxeFdpZIeno z*t7_E7vjqkx!e5#C%G<5x0+2+v)*R6J7>NOo$tDbe=8&DP1Y59kjcQ$=0-9Zpu)A8F0f1T>b@(f*_+5X8VO~esNKHak zn`8@!gb}Owib5V8=Pf-Vmd<{SCW%Ym9hR+Ff0p-gWE-f+dV#oSnqU#)1hbd0@6==e zl5LPA@p<)L{etwP738atl`5uMf|*q$s%T^q^6*uJ`Gu}3_Kg4L@>(rRtB|#2ud0{8 z1@W@Q(st;#|5m%@bz3`B@;WQF!{WAx3nI;pL*gKoawald?ho{isL-+L4z=xvjzB~5 zf1_|5-Ad+>V7N}Lnmw$tx8&zUNkt^@NOs%Cc2JvLfVL?&@X=)h@#|maRi;^B|HWU+ z;jb7M`|qeRB^P7+|6Pd}%Gb&Q8IirLXCVZ0F;KtvKq0v5gA?b9OQR5kwXI!-wn;i9 zUIbkk2pVjIKT|1F5 z?@AD}aad%GRaQcBYmF376^;anb77HXN24oIUt#9znhf%)9=cr^R3;rxL4<&(f4dbQ zpi?r)WbBY$8)~f~3knixJTG*R+7+^m9d=Gg%7cMlen|dzA7}gyAJc zP|RfPTODw!zBy1nP3BOXBwc!>e^=F3Zv0&+K*^h!Hl))p-!?z-K1$`b91fWgw*AKD zhK5>?vOFf=I=9@rfRyJLW~ca8Vpg%i8@_1Yz4U#_74&z7^~6FQ6b?^`l;v{C4$lA zN5Hz?59{y$!)Myi2qvb%f2_;3#AC3?Yo0VSBCs6`4!wC0F!z^nYTKs=wwbV5mU74W zTn)Vmr$SpH>B|#cR zk=?XCsrbwLMI9R?Yu%@+e8pb5+mITrcv-0UE9Pnm6}Xnh)K&AAe_Ltq2FHyrlpV>E z+3K6(qnuyCA>FH^BALCDs@Qm@><>Dynt2U5jLBK7FwIizhN@052&&FnK&=GLA)DZ= za`e+=NHd-5CV;9AT*;EG+1QP<69{Q2+^G)6JwbgFO+zYVNikZ@Bj~F?I_UR(fQnA?5mXDY18bMZf55bCf&g^7G*4$7MDdh8 zn!93M_k(9n_`=^U@o57z`OGqo8|x2`e+9k#NcGR^>5^|*vx}cWSu@@(=tMYipNXx| z*rz-r+lXURoM~XPro`|)_M|%;&}RgTKF03J=>ca4FVFe*(_I~Im%!tjv!lFkuyvR| zC=F&0-nA&Af0z?bgct;uO>`HJl9~GC9V5&J3DA}Y1RRJfO#sViUS<;4J~SK!r)-kx zFWSd8o1ldm7QFY1jH#@5(GFoqVrQ|uP=Fr8Vyg8Auwv=PNe@L9p{b2oOLejW)ZDKxpR8Ja5FN_0+Y+)w+O zTwQZbilH4{hv$3MU{l8&^pKDyyTT@urcR!+MKYx)uD2g|TwOVvyxjE7UJ^seT5s)abZ)#vQ*IIoX4mu*R4 zbF6IAA99lG<>mQe7A0BaWk)we8iZJ%u5`(Ow}x5KxV6gVU(1BRD8Fo)Tl`#Kt~nr# zqyI)L(kxVbk5@&%^)XU+ULpf**y5OJ{or~)jKXwjJ+lsJ>#6+;ZZtBat(}(84^n)~}JL}S< zlxAPxx^u_%onW7Xt&L!2n%Hyfu3n#=e^-s_YWpoiJaTmS;0oqptyC}WXg0n{yYPf75jKbUxRW{6~}di^TSW`{o$+7>CJL7kg%twiCxNAtR%M&CE4BTXHjH2X>cQ%EGmrZ`2y99>Ug3yxES1e+C%Q zAI+Cwq$tUK0vxa{c~|Bdr5Z8UGH3yUrl>@N2-Q zcd(6IUc%QO50WEd5@WP!l0r0feDh2JnS#p4D2e%QKMXXpFlCvXgN#0psBW3*=XQMK zef3aog@Ln4#R{@|ii%#EjDw{^e;(#8_*S{70#U)ptRZ;eIBA{xR3k4688st&Rw#NA zgv;GyYZm#n#C=9!PHE5od?hp#m`er&ru0I}#|i=q9LZf}$XI-@BgQo!c!d}B-KqLI zD@E)r;Os3DE&_2S&ZIcwsh$q3RIdbD6>Xt-b9lP5juisSj?`XCz>e&Ee`(1C8M4XY ze96}Kmu5)QM@*X|X8%-XtWB=G z&4d8%m%gnBL&K?B6@0_Gf8ibQkn(-P^!(0%c7-~GK~=d{sjnnpcX8YLsAxLUNMnz3 z)4SMocbw6`+1j)bI z`!^YbkZSrvNFMhj|19c=VQlG4dI+g37o<5eezc}$an*E&vp7v!Rl8ezU+4CWxU9%= z6c+EZdldt;feGkt88IT9FugC)XwSVJ(`QVf4bYr7ETpCKZA6su&ijTrII zqvmGDQ+XBlkX9+MgZAC3;xQsrGcIu6&-t(Klc&F5?MmpbWjBlsl1^l zsCTE2e?Bv^s`3KRNW=iygz)1_Ocy*+HGcdxlT+mJmk#3j&B(orrp$UwK~4krq@#{b zB@wxZT^a=JI&K7OTdpcJH!2oo1`kfg2L|s_JBJrg?CCvkEFKxd_C7voZZm|75!(V# zc9-i;QxmzlG}#tiQ_c_N@%pXi3-X_URuhM-e-?p*fH1;|DI@dVCL4)KU{I1diRT0e0I*IW6sgD% z?W`zSTbx7A{{%xv=TVi0ks6b60@-;$zWiMXOW+&8!RJi9(Setdn%Z$YBMbhjrdO@) zf2L|4SGqo5kCcCmS>i*8Xh@4lq5=W{bG$Uq&C$FrQ;1e`4ES2!+i6v%7>~Sf{i{Dc z#~2{8^u4Xzy!FR6YTDlhn=bI%o6r(ccj*%<(bgL7dtltV0s_8!i>t^Mm57s&6KmM8 zaC0Xbw9@Mrvz<54W=N_qjh60`AbR{Lf0VpZil#K8pje;de2 z$MSfoZX&QgHat39I=mMaQ0oJWQS2ftDHmZqWq~i=l0>ll`xLjUn|XU0e9HNo8q`l) z5R@+!3^j!ueT_x}ZuR_6fH5FO&g- z`GziGC6Ck}r~B?fHZp(C&CD97WdodP8d9ex>qOG7oCMN$v;uAYb}M$E$U20~vgr6r z`3}7Y;E|ZV(1>Br{6;LZQTd|{hIJ`;&t(cpU!YxIh)Kqyd3v{Un%zeQVU25LgA+IL zcPR2gm`Ht$ANh1frar(zm9m{2615?UAx$Snbw;UHp-{t6C3 z&xJ%20wHxAjB+?j|88g?5VCF2XViIKCR@PR^qpUB^qosO}w~M#pY7moaVKHc6 z8y4HSnW*jSVl4W=i4KS&oazb{_M|fMAk9L8&O_z;h|mg)q|zkIgEFNbr4zIi z(vB#->VVSQx^qUW4htkdU&4Jy$JAqyEaHn7{T`gxFjeEF4Hv)`V$((A>yHtMwO~uG zR~dwDE}^IIf4?}**g~AQ9@0H8Sb+G+_|8HudLq-~95rXkW{5MM z-WS(hCO^3EE^>8=@PV-DvwO6Hc33}TG87pR4lR&vQ}L+?Pg3;NKarFXTJN;O=NwC3 zj}7zbzm-LU3b2)1RpnGsh|KOs>nAw6jNlQMdk+#vL?82sOhMmbU(T$i_HV{{gFI=y z;y9AEe~V^CW^bQTr_8#%7c$IRd@A?$xuO=2{VFeGM2sX9_@0f;HMrf&KkFn-<;Ww> z63;30I|(x+P#J79{S&OIlt9pdO(}RfGyEM#TE8x_X?*GFpXJi8~cC>esw=r_~{|NoSUV(oLeLNTpf-Ya=L4TtWqkvNw3&FNaF1X)P zt5N+nx!$P0!XctSOa6qLbxriZ=h4Oy-qxr0Db8*WcbjgnuX_vu!f4|LCaV-{p}XcM zf1c)3sH781k98#NxrY|jy9zHIR?kaIU(=NK^}9w4m)<(d!L)<()+97K*id%d$|Or` zf9TD0*5*UXUSuT{F>WE7jo(yBNpM=PqIOP&HJ^@_l^y*x8Wsu{I0`(uB-CLp*%(tc z^yrHs#yg#Pf+EoVJet%ASqx_g3_48+e`3Gjelv3^JCaTyvjdiP=98?d8Vt|z(f}Mz zmD(FSCIYKE+KDs8dEb|?xqRT0GEMydJR!D^j8)?l)gR?y0f0}Ylk~^FrkoF{cNoHc zj6R|RP6*5mQ<_m2<4pI)45FA0i4ePR4>a)tip#_pKx`CVcpT3lwH58NHc?Mgeqy)r8jWwd0JgGq4-;j8rnxp)mL;)5+kRTmZzdk8`Dh}8sG03P7tlb@-X;+|@l(|e zCch#vF6#91>6;AJi;}l?AFuqCB!FI22>J%Vox;Ze_I|vuHr_Az7d_Xvr@r_BFC4d^ zfiIB3X$RQVcXWapomU2lJMi6Nf6y2ixV1zS_Cx?RK+3-!yR>M707n-yHfdF!QR0N? zV;+%H@Coe8*=54l&A6`bPb6N1fSs~96GO^lPDr%ZCjNU3+=XnKeMZdJle}pvX6avf zSTRF`(9uk`*U`2(dtd}lLKDKtBtK*!;)LiRuA+QE*Al)FpQP6c4Zn(fLQpWF1b<@W z)#Og0Cw37N>>Z*M*xJ)#%I>4B^ZD6d)5@5JyhWuw5#mTvitykP1~|hZ0V|o^zw5hu zZ~sdh;NlEDe*0@@z=41${$EN5MPt*y68wK@?@E>5E@&#~8*_(-aq9)mx#(Kq1B#61 zwbbem=B0=dl7@2yMzaFKF!7F5;D09tCUIe5$Km|HzI<)?hKc%S3&XK=J)bC_(L9~p zE+_s3)_F?SsX9OL9c5K#wcZW!^M66O|$=Cf4*4{Bz*yqU>-L`Gpwr$(C?fq`sw(WP@wr$(C&Tr=Y&rN2MJ2!LBeCbXl z&xa?~-K$owbX5_>Odtp-2omH_nk#2mvDFalE(Sjm!5TwEu^_U`aw;$V4e4TlWpFTr z>Lja4rm?jcKr-d1e^scAr+-I<<}~CQW1yLwL4~?pR&t{yURuQv3+8et$s8|(I+tnC zk~?85zIF{|w5+;n?e1rwv+1W^ehy5fZBOYQXCOSDfPNquWYoNqYF3ysdr+yf_KYGt z8KE?H3Q=iML3}_NY{E9L`(hi6PFB~8H^-EN;%sVB(=DTtUSF!5+kZ7|!YXD~H0jXN z&|6_5HS|c^k7iNPW9k}psLf*cY_BXyY&TIHgN8XhzM``^QmY!4VWM4n#Y~M?*~?2d zo<~8ceQ|>ilpwqoPb3U71>Nx~vc!Z6HM-xj^;MT=aj~XWEZ=6kuzk=KT#19nP)jI+ zeVZjTc5SJc(CwaQgnwd3&5ph1%&|Ia;q4Wl+n`{Ko3FR5c=p<^zaC#-*JS*= zqlPt0b=D~zupHtwxE=eGF5!JxBCB;~dmwtjSo4 z6nZ`C3tEAvB7dyQUuABY%H|THCnYRRe83Bc5UP7bhv(q9HjIcqs)OV1I52EXH=>j6 z<~TB(L^sp!F*58-mx~@=?!gY^qoSid|MuFwXFpGW=~WPcYkygW9pEP#jQTW4%u`xAif3$l zaYsx6pF0{Jk6KTuhE3>VQf>G*A{>9xZ%Dte$gk;$G7EfocyHykCK`6@bY6d6{oH+T zl?o4>u;#!OVV;T)JVGejq4yvEk<;N?8_i+zwoTsZ zEn-y>{Lhe$D7}kU9Sb<|#}^>`E16n9;C$q&NU z``X9yBlY$?_icFTA4GLefd}G5{X;;!kf3(xNTs*Elt{T-8 zyhiNwz}UueLrhm217t8??zV`!h7fy;n4Th0FOj&>Tb4_H$^reRH~&GUE(HG{OXo)}GVR$oDc>3{4~ zUfu~?b#JaWQa*Ydhz8&Ys*LAE;Mg&|egPu&swC;)+c%L?T481%($=cz;0Hsb1FTRa z?A`bO267Sb`L7MhMl-n3NXd&y!wA1uO}SRBL_`aMVyP|KBD*uxR-#}-VCo&$u&qYm z=;Gw+J!7jB_9Q-uv@cgj86>UhMt?5VHCQ!oinSbZZ`IrjP|b^QUf-80v{Qd1N4=1= z-&9WM#);SbanRbSRCK20vQs)@|MiI+e(BI7!WLV$2aWY0Oxc~chGd=q32MLbBnt2R zCk~ils%`Ft?z|4nKH#uU1AJ2`O%h)S0e=@=IMomxXAj51x&+Dr<8E zx`r_(pNsQjhD8G6%MV-AB7fqE8NL4iVP*`RuV-xKc|iV;8@i-PI^q)^0Dy=J06_A8 zW<&prHgj4VXsdhfHXKW|#MutJWsB#mL~M(sCXIPESssuy+epS>tvivtFM|v4uf?u!YW1C*$h4hb5)PK8za%rrufdTj2 zZdFxTzjMiQ72v;aJ?1=iL1?kr+&6UA(GNABX!eR zvt=Wupn$|FFE(?mDoB-~DmSjIBsb&vph@W{G;_k!S^+FY zMHxeJ9$i`d$hVPb+Lwe?)s;+tgi%l6Xn8azLW4u8Iz5!knenHJlLfhcKbk*BA<4;2 zMhbOEiaLzd$h61Dls3$@K3DKM1Ch1t2$eO42B^siH_WYpNq=95@a!4Kj({Q$)*O{H zM(7+mi^FCGB4(VDwczL!a$|U3EG8VYBPB>$z>0BZ?#9vCu7Sc-&!s?*Ec8xzM>HQ7s_J+%cgy=f2^C$`@aY}#F_j6_~b zkr(*UlYcW?HW320z<>trVf1^jCm%g#3rnj9y8F&7d~=@`ha}x-PmhoY+LQD+V%q#j zkTs_8NaWpGWZsBs{=uwqfhXv>HXk+a#uzyHUJ{N;#`rC7hRTymLZ{ytc-y#%Wl}JJ zn{lZuKRNB4}WQ+0j|kjG45X+r$5-*sWw;?GV)1| zHf4=UVnqwMf7j;4RpcBwV9gbbR2wbgCKC@M-`pKNsJmd{^DsH_B`T1ll&>$~mJDJ2 zxx@7TxHC9pJ}tCXmuvp9=t&yv+`}u50F{!JFd1`I@m5dVPvhtU_rrWOp1XuuX$PXd z^?#=id+q;JG?#p=m=4J;5Bc0vzjojcgYTQ)42rNnOC6UL&S&tJQ&>9*gB1S z2RHV^xBXxUi%Vyd)w27*2m`lN&T6sbkbmhcly3QA3)?NAt!k$2FPQf*aarTO$thmm zJ-+j9(n7xX_62%ygv%q4puJxxK=cS6#P2JDz{P;YMKk~#Orh0ty~D_E9R!7o8w4Wz z10kZQFM_2&L$WmGg zg_d`6hv@-!sHP&v8%2!DrvkKeEV3uh>7xe0Xo(bv_LDt$YEdwMiVqF*`g3nZTw?Lo z$s>iOChIA7w8*2>lNjU&FYFeY!PJdK0#YBmt{?vDE)VAi+Aq9jcmip5Y#U z2iAZ=WO@4BA>DlXL-;XF2EfbVUC6$S;mZK-!O2ZLI_X)7jf|F&c8$}7S0_rwN@@k| za81YNs7vGekRcy;(ain~5GMm=i!R$n?)f|zh|=^GtsQ#5eEubul)kxra=PQxN>c68 zX#J7VSn&xhz8aar7JpUJ_M*xj8{UN&C+C<$H6zrVQl$n2vMETN7i)ju=IS_D%UFU| z5u$tE_nrgy$7T(#@5eo9+KUPE^qFi0%E;tkBr&%qs-QB8Es7OIo=R<@)>Ub&VjA`1 z`O)5Ul=S+U3#DVBPNtAj_F5iho>PfB>M^qj)Sz0$L1P zzB2{|&#H?Bn1Zj(hEZkoDSqLF)jf_>Np^>4D=ULu=kw`dK3C7s>{mu}(A(1Oszx@0%^XR2+EP4G>h_LkflzM zF`AnNpOZ(k2QR0@a>4SDm61iWZ_Vj!D141n8p@*ZN+n4Sb~Bs3devG4q}b>mC}XRd zEg+%FfSp@^`BZh|c^KpS!WU4uDmKTP?SV6f0QZw)rrqVHG4)M{;J0ClPaMYvC|f%}kXT zEx?G@ue74NirAAJ>kw6$u-L=tPMZ(Hp|5PkmS@jYtj7ujD3usv>ASl|&rUc^2%L?~ z!ImyMxqmT`9y35*!8lutHs_Q}7@ZefQTUR$Cik#Dlvtiq=vw7W-m=r8fx@#Ha_fe` zN&)j-1{`Xme%lg_nEC1y#a$Y7V{AU(gZXY%$FW}&Nk?Pf2{qzjXj2>L557~EzPB3k zYL7;9ZvN4T{>c#by0QiNzAAYSEB$MNy4}y!qnqajc z$=DKNyDVwDI$UlCmnO|p0Yta>2eAW&kzKL$|h17M*%y zUMOG9wZ3`YE586IS-D9kv`;j}uO?>OPeR9D?s#IxYn0Py>!1@JrH&I+E9+qIOrPYA zctdx3mn^x%79^ZSNUs;{+A-MCCHG1CCYsp#NYwR7^d;3k%V(XqZmHn%_d411Kz}wZ z<7R^Ey2wk76;*V{?7aV!k+;W!XxAj(o{48|$SvP7{L6d~Gv`Zk%XZKaIU?3gV84@P zKP(ESHI2~*1x9a3>ygyt#k7B^29Yt{jw#*F2yZEtDrp1{IJ7np%eyN>4N~U01GMcG z$>;7G{txah-QJTh3oo?W=4ii~FMk4{`Sc&*Yx4rXL(PrvdFX4SuQ^a#ztnnsrf^=7 z#ju$3L3FgeEzks(;weI!902{%#0R7vUu4t|v@4Or+n_YY1bsmIR9=1`bmDJSjKJG| z5FdQqC#w#9Q7VK5+g4&9Pynk;DS|RzF ztCtZmmN7iHBs(vll4Bnq94gCG|K3So_tAQvPGX^W;n zwv-{WbdD_FD4C30Y|LPtnt!Nonyk^x*jwXPdv?|Iugu&$Q#cNYz(e0qN69xU3%95P^ttHKErusiBt4j8-h$nv%AG z(&8c8>#)|$e6~klE_KM~e_1(N+R*ouwQu!<`TNt%JI_mKtQkP85P#bO{XScIdN#jRtc&`&&nSb)NrGUz;T(DO!&w}lN5?b@$_yDr5)3P*hW@S?3_)OJJ`nKYs z;Uz!b&O-A0E^mLaB0~RmLF|g$O@h5`g0+#DVZW!r7NieS96;#I#ty)tv4%vBB1{ef z-J$ZT+_hMf6(*^?zHrX^21?3rhdpZAV(y zB&n(vcyY_QLPT2_?@?vf!B6~lcb^q~i$gL6`DPFBYXWh}5a6c_@RBk&U`~;Ik&C`| z??-ckzcRjMgIq9&SQrhRnKb;cq5llhXFBQ2i0PVs z{ScpB#C8MBC#dulyQYyl-Jst*(&u#Qn)W}REhBN;Wq{}X9ScgMdEBE-eVf(V>$QoX zZ=l58jdIu5(*8v0Vx#0C&!+FHAJdv_yii4MZw6~0iag@FMa4rbZ6J6hhIV30Md>tQ zqaDGdX@3yFrB_Bcl#{7N=EN|pz{xT`$5GYA;+T1@`^Ef^3Im9Y;-}}oCDg(K0BHW-Dh&U65k&H@`QOWx z|38X@n(aR^9mS8%elwV~SYxiGrztRzCPc+1N`Jx@nuc--B|Z(HMvFa5`Y+4X!A@I=M3j8=j+z@M#YQ;O(2IH z^_kK=)C>bnj|!V~Ko5N~vgyVVov?d>-hT>=at2sDducxTQ8k}Z0C!e41VORq=;5Fj z%C?8>(i;sbOTncV6SW0L-GOUY|D0v2ZrUavrgqQq8cfhHk~wTg@e?g7I*6KhZko>_ zXX2WtwrJf}f`+D^lg#99#2#)}RldF`kYs2H*xdrVX%^gkoi-h+)=5F}DVo{{x_?Wk z4RLziJ%KX5f}`XS!nc(^{gN=1l2W&`#CL9_Vb`ofCb$Olmb26`fleuOR25Y%WK^u{ zXi4epY)zf_7CJY6IYtV%oZgCo`S8T&Fa=6Y*DOK%A;>tQ7)-~&8;0s067A=(P#Nmj z=*Z6Wl8xiwOhc{&n{ak4tjE!lgYtVeM20(ja<}gG>=GzhrD=;d6Pm2qRCebrT_z{e z1s7ACMG8~cRisOW^#gR;i=|`ag4}{`4bMRsJZfGpSI-{X44;*?nFQ}JM^_OoQ&q%zuh zr_)PtMv{ri{Fya2_v0w=vXN-jyaW$cRw$a#s$Xg*o#OF1kWfyMv*8#$9RfZVPiarW zw{saYmAo1NzZJmpNgP{hE`wi?H7JC zNin|*JC;p+#Q*H#3xAF{K#09+L$t^!6b5%2W@Gt+zd8`>=`seWLLa7TVq%vv*vl6Q~(OXWuBjvR3HvR zR|O8#G%jU|R=0}&{HIKtb6-icpnq&KXaE4I{~^5l7r?3h%70;tBmAJjjLfWq1VREX zq$abpygLeHq6r}Z@!?1SDjUn>^PjEjO$D?!-pmMk{`pxfv#d&2sYwPO6IRX9#UCL+ z*-xEVh;cVJKgqH;Gw1*MKJ^CBFGLZ6*80Aqv=HVVoCf}Gu1$4mEH8Be=ecES;%Af@ z^c|VQiZKN~6MyK7%MZj>z+ih=Nw~O5v!ym~7u!*s+;XhxGIee?z^?O@b8jo^XvyV2 zYANceM~hYx)MuaiYnpCX+QNS|9s)(#K8-+`%U=em-qhRnkTjezF}^In z4e45^@JfvlZ*|T(DXq5SunXbZtKeU_r|ctk!8^&faxG+KKfA9YSsFq7isD1pv~NPy z&6>C3raXQ$VkCyKqkb2{(gcOHkwsgycLQBi9+=J|Wm&O2EaTjPZC>I0P%*i_H;MS1@BeTY{+abb8?7 zqBQ(IC9qBuK~lEomYSGc^Gvh z_kVC9-`GV9;mS_w>^6J(*|>E8vo!6EUV4AluXN#4pMvf}jB-^=3F{1JsCH9IzMvJh z>CHt+vFR!0`FNF^jjs~J+pG0!uwh}l7%J;I#VVpJv}A|!c1^lgR#P#9e-0V?ek3{JXA`1Zzq8XI>z3TXh}?hPPVSX zTeccMG3p!;yy4w|Vey>-eNlX~DD9_eNLc*{rkGm|GM&VuWC!BBu zKA?j9Fh4|?LiEA2L5iEXqw7(3m%>&wnB7BgfuB#rPLPm&@@mg`m3FX=1AE3dYkyvm z&aE!$ZHi{#Tx_s!rNf@65#cnf)A-luQC{QS+i?A+?p=e+s?8b6ntI;UAs}WH4wt}) zOb?V_=*7)_hc{e2Xd!HM-&3_9bCZ|J%8@q8k_1h3wwO zCvX&$d^6O=o^kmprR&7OcvmeeSy%3OC1v4x{S&ROnJq8s4W(QR1b=p9AlMrwR&%xG zLo~06Mn?@cX6Vb>!MwZ!@wBaS*%@RXchSO%6{vME?QgPivHq+{O^#5rT7O4KrCh;A z{vKa}RlMH;kEulmFEI-sXqE%Nux=m{W3{}@2Fzz#c%_OQcoNeBCgvV66dnqgbx1!3 zzhzW^7>W&IP)|~6LVrUEHse=)AlkVO+^nphNWU8hW^%#~u`uu9eeTVCzhS6@XM3dc zG@HysDm-D6=Y4sg+m(TauT+lOASEj^BA!fkp(G3|_;a)!zL^H9O^o+^f4#dY^lJff zXV+Sd0sIS76Ri^mnJTlV8fodO;m0zi6JI}Nss)1@j6-m0Vt+^i6eJqRIKdwFk&Fi7-*7+PQug4$|=9u=g=cvIuDxTN!~8!!isbD?6;JjQ*Ed!&Lr41^oNKYXnA=LFd$VE0f z?!^@!9~1uq6Ym!L?4|^}&Y>Bm+_F6%G)pF?(1Z5aoYFZ>UC)L>CpI=AP*MGoyZ!*z zKtmg*&(v{R2c@>5REWZE6*cWeM|Lr#+6t?+IyDxqV}1=DIy^oncv>!MZodR!3Zaf-v;4 z2hR=82_n5A4ubZye5F{>wEQk_5^}c|DSsy{&+=3p@>($`@`y(%yTCTBaao}KpLx<>>r;4f&lqHGbStcD)eoFkC3t|(3YYYfv z)Q*ce*ytTdzDpo=?maCN0~!GR(Uy{aWwkR> z?#QdCKVUY{>+(z^WMi5TB*i-b5r4Rb`C#K9*x1}7=`^xq9xSP&sjM?o;R0F3+6%>& zi3=e&=RNi$v`lsjrP3S4vi|3B-vy^lzv8p!=kDS`B*=2Hq7s+R)t@_A?ya{w?z_JB z-=`_709QlWF&Y6WgiDl5MS_DDnBUQOv*+(NJ|<2hEIhEVpEX^_xJ&ha8-J|}5vvg3 z3KR<8E1S zPO^Z!+6<1FN{b2<*{Q!eFIlhr*)c4_i@`>e$iw2E;-2y4pRMN>kosVuupPxgZ*2o#7k|0C>PT%#4vRc$ z)dALu9ng2m2zidzJnhG_jj(RI^#TqY%Y@XMM>mln=NF6WHJ?~MynjZjubRj^Td9Vs z+;1tacS`GZ-Rd%np%|rJZdBG(yWPz#Z}CF9d%*v;(s<+v(Z8s(-6HMbfA*4mlwW7c zI5#}!4}8v#n%r}eO=a6^>~Nm=$R-Z;4nkE}{ko;~ovCvWK@~o>SbL`C;I}-0x_3I@ zsA80#tSKLGlrlWI#edokIO-S{XByi_9O8vA?pv@y#TuV<&;L=>7(taYDjY~eS)1)a zujf~qb1rsv)Gwv4+|z9L@R!STpPp)CHUEg;t#ZJ>S)DUcR|N>+LnrHho?SMicvduSw#lMYPX;;5vaPvU1aqXxa3;YMSmtVVSQSPXOBq_Bu$%z zvCo`w;i7eyfpaE2Lbajn#+?Ka6&_=S<<4`&zK6(0&;gYPx$5Z|C@_SLdK1`5XVWco z8ksttk`dm$P|88;oTbVh1c#i|Aw1Q5(hmx!M zhLT(KXlJNYZw$txot2%*wyV#rL{H&^b!u5~lS*d>yUAsJ3(OZa8*=9v0{u4Nq|9x~ zDHaQfX%seHhX%xrn(+4w}X)%m$b_hbw*3Z)WUA%uoNl z)PF+8&E%XH8Y0%sPS+m^?3I}o!)+VH>usIx?r`o9H(P$`M#UaW9cofGE)7@13J9m6*GzaJl2Wouh)&ksCu=7NL&{`@|=xfhnpAJwsCd}O*iU@D46V%tOpr`NO5Ho^+GUZuUbRFM1Qoa zBGB$81Aagb1yjL78$lp?#+0GJv`L2>=slI~?KB4~z(#2yZJ_43akp|P6;-fjboC<( z`?(~y+V3c%8=bx{#Ra-S*(j(@2L zFD4=HKbanL2^xq7X!=%Y4}X%>p))FxkSL+w2U%%399SQxSZNK6(HY8spf|>|_4*!- zL?Rd{bM=SJ>GVh$^hxWxY3^LJ;X&jYhQ=*7307$KqQtqm%rXx3|AI?HC%-S(iux28 zSuD}Bz!jY%dDc~K*;0&hhVp+n+8HMQ9F2N{?%a`fMeu)`$FuX$Cx7=6eChv3sv*{h zcE||~0MGyi0KoI#rW*ez)8}6uH&k?$ktI=hae)XOg%~KRhgkFfj1vs$_OidJMkG@z zQsmz$hDoMH%PiQ;{`ojr?77}u^WAcicC&sJ-2GNeEi)I&KOz+^S@8Aty5W4y?%~z% z`T2$HbLHU)0r^mp(0@7`{nKZv-b~ed!^L;1CR!zn+95SLky?~xj|1lVS^<@UHrA79 zDBCPt87Tco0Q!T8QlV|4~jTbvMqsGba$ciqAUYouSXHP$D@7D5Qk2?IU#JT_-> z{T8*)tmx zy3S$0FRp_i!Oly&J*RAYLsQBaFpff})fP+{d7-$FDb9VQ@{K^%+}8E+wQr@nCs)_w z1Ft0O=Lc`1aerwFP3r9Dxro@QHOUsocxP1Fo*PrQGKmc|o@pf&u$8!)>PTG8oyC`T zl$Lz?h8_Dd)$z!HY3CWxcU_W{Bb_400*}>k`eK?Yns{v>dLg#CeZUmIkLZr>wc<0S zVl3!JYmy_MlM_4UM;n2^9Tu}@I!G1ddVM9yX2ra5pnrL?b-Rs!IC)9s@@0&f!P;D< z+kS=_dKEzUSeL^a=7n|Lvc$?pYAe0(cZ*JsHq>)1H9(?0bTC>Pr=F7*t~kKr%hEW? z`5M$*G&O&60lO>Xl-pwd8-%czj`W6JcD2PPx9R(d(OBb)a)p$JPn511dx)`TVTeJw z0OOP+hJUCjV+f(%#w@52Xax5tfTHSbe8*QCKr00~g$HVo>9_b&y$?y}= zl#^$6N0?}=@u*ng=@hFlp!qXG)H2V}Imsqfp*++x!x14eBheF(h1;Ty$PHot8-xkP zlbjOqXN0mG0Z{us3fI67*r5~n0C7!%1}hr$lYe;RW&_lCMH~g{G^@A!CuiRBSsk6L z_8aJ$KG7`jSsu@^a;@Nu{2ljaok_(UZf5C2I_)K5e$eyiPm2PF9BNfM+1eDMw^#>? zFm5DBrQ!_GjhJTO@YY}u_-W67QiLk))^z+p0RXxX0RVLV+ecEx!pYQB-NMw==Kmbd z|9?sx8vd6!WNVQ{wq0EEAb}{@Ac2KP2?~XwlE1kiwP}E@4P~`$LpPmDg6+l*>H`pY zM&A3jY=3cfb`~zB4LZCUjh{WwKYqWJW!qRnX~V5T&g?z2-q`Cr%Nyq{|MPYFq6_eO zZwJ6veP1LdMteaLZ6U^IXBt(Sz-FV{cz+;jwjOGhPLs>{Oqr@iYc_1Fygb9a7+Ln0 z%(zH%#A!S_!Mw$jQ&p{*>&ZiM)-;{6fUiu;O=^}IGI0RCCJj+QK?r!VLNv;BqNBy{ zrY|HhlQ=UDntkYkRC{)~lRA&A4OUYO!Voe>Yn(;1pU?E)BqC7A&d;=+F%ab1i+?6W zpn5pbHLJvi)J-UKTw-9a0+Z|GN^z5F?dprYN?0Z~Csm1R<^iYB(#^E?Qqd7I9w~wt z9ODxm9}=97IO}C2o-hOqH@F4>?+yp`>%k z(siVZ*fY>=Ked5Oi_LI+N5~xNO%(+1`TbG846FM;!8y_<{8gD5QB;iGaLoB=miLfi zJrwglkwJsWs{>HQoqlf2F@EG136;t zdMfaw>{S#|a@TfBf}HGy!5o1Ye>fd%q-g?IT}(G^ZfR|;v)ZLb@=4pEzPz?|hs4!+ zGk8YRKX*~McgWk^{3(JMQbJd!3gYIl zNtTIuKKp`L|9ceZ?SG-Y(7mfp!O$3WV)&56Wm16cr<3I15JG!4y6I9%11%F40PQC{ z5P<4RKAp>#iA5S+2srIiS=@_0?Q@5cOr|Wz&gl{*Z0Uyf&%dv7u^cIUgb`TO)FYF9 zb~1>~GXHT&YWk|`HEs+aA!1!z!;4yyHP*g@dx^fbsmK%jq<=q)o;jFfX&JFIw3Z%( zL5gKNTd^a%K1o#&#dfeJE{c4Mr;NXEa#kxe7n1(JM0aXH) zBp)%GXNUEVmU%b7`(i1!w-D#cE;+@t$v+h@?;k}8k)I2eN9;FWi>0^N_(aNigVJr2 z99(IY*yk=!?|&!h83q0NBi$BL^@ezRNbVEf`G&)9jMjU={_!2Mdyk|^r&LPe<$+lT z5Qsfmg`z!EfnuMx=Rsx-GU}{J-p0bR1WhNbBj6C-mcKV+IM9$yDunTL4N!oZc3gNn-Cy5Du0kovAR5B#^6K$77DF%`RCFR zuidkL7I1gqrS2AbhI>y)^^VQnAgIu{Zc|12)!iG;r+~_%k-c6M73UtT#Xudf?iGwq z6_ni@SpJ{U3s}Dz%I*%VCwNk|&(D5uwGu7js6ayEx5J|+fIY&l@a1m4H=A1JQ~e&T z7T>m@=zkekrvm!xKQ%u4xatf&0tW!#Mgahj{h!1A|0Dp_ha8z>ZVC)xC34-P#oNL( z1aN>r+pnc#4Udr09L^iSrm{{wfjz{(3B6H;4y@?x#9vBrtlT;M{gw0%fIFe*J%0j+Snt>_1-dK97Bm1EZ3&@+;%0#(1k1!8A=&~K!@(;T! z%YO=07oY7v5y4Pg3a%H-M{~vc;3pErD)cQfMvjXior!sQ&f&>i$|p6sV}r6uOwe|y z@2-)}bchp>xrmD;6BCam8zq~Sg&|7>PBgCSW3!=mbQz29>hU7fEZ75e1TVqn2E7@k zgC#Q7yF+thaoMhsIsg3z!l!=qufuNu2YE<>xak33J?kKUB;1nC?8!HY9w>v&h#~BOplz-~% z@{S`8`avQdli-eH@K z)mR$&Q{M*>YhBJHjg6H`FU;j3w0FpKTP5XL7wDu!K#A<{E9TDo?iL(%2!za0QZT@% zn?&lNt6b>G6D)6Gp$oW!D02X*xqmuaAI?sSluXE)i_B3sqckz);RP8iDFcZip}5_2 zo}=`vH{M3T&|S}i84wahI0a#Hq;<$-oKJX^8JZ*8j%Z>S7LV+q1hwYxo+2oWTZ1`; zWw}V&k~SqXBBP2I`kSP73QD)n1k9Z^>!C&`oXY%r$+Mk77m;#Yq2i^wM}K*)N*jaC z@SL2IgLkMryKr50UxC0!dk0g?Xf5@66@F8KX*1~Nn~(gkd{X)Ax=43sx24HJG7`)JhaDc;OZyC|9`$oUS{gD_A9RJR{B$s609YHZ>G zG7udJBc7Yv(;|Z&nW_Hj`hQ#8OL#{LnU`Nc{K2xB>mx;aqz=+U#m?qblvXm?;8a>> z?qg2mfvgX|Pa9yrmsLGZy)eZyl_57XRZ2sgHxD`So+4&;jL{Qe5A6fKYZ~GRt1DDg zr*iI;R5XS#@XCs#so6p`+;b5*U@fQw@e^|C<;R&2I5k$*Y**r;5Zv{Ysi zei3RrVx{9w!wHYJ>S-BO=6P52_l!U~$X%P>$EtbDR8j6zG*Z=YAM5m7y>+H;XO=ngv1U2>;dcsUS6|{Cw(`0bc zs`LSMX=BY@Z*+Djtbc<^S`ESDL-3et&ZsQ1_GF6QPnIS6nM=M+Mw9ML-EzPu9kNK7 z*)d7(*=;`Qf!@d75wAF!yXa#BHfyf#t}RH!ZvAM08)I8dVA$QDub(}12>Lp$chYrh+$7y~f50TMp)C?z+ySo>Z>aO77lJ^aBtA3%AtgVdImpf}0F7@c zp81cQ`77VIVqMn+h24yZb=T!yu^srgt@8Wf_YiPp^AQJac9Sgnku8Sf#+ujJQTRvX zm#+Q5_=jiDLVridDwrI~l5Q-DQ)uTodGr>r6}!C8Jaop9ezXHbAxrO0ebxblM}Zc8R}Tx{?=Fyi^x4oF`=qHdlK zPlqPmZ@mn*pjqU4mYr8en&}J|0XJOY*>DSGr z5bABElqWkSrUYLjJjD?%!g(BmX}Z@0l3N$16ANucMK>d7b}5X!3HsEU6h0a_i_vpv z@b?K-_BAjE3d8TFK{+>It$M?(e+$!bozrm%Yzc9RYzeMwEuvLr?1PQn!!nHtYt?3D z+{4-}%72Hc_>2oOCb!mX+||KH;-h8VSCiLE4-lb8D~*<6gk`Hoa>K~yl^WU?bg`>) zM#+u$F(vb2R23z=dsR?rLd>IYWR;BKf>j@A0kEp#Y?X{iOLb0vuWM4HQOD4+AQX*W0D((5^sp zHXTz(N%(&?kUV+W%;+Y~@b4vgT;I&7qZyylV>Gydow-3{a-ZH8ji`|KK+(${on*H| zesjs_qZJMC?~@MbgO(|VTF_lc;q2m@TjLlM{xbC*)6bu(W1T(JCKWEClCDGSG{-zW zP5#ogvQcz3U%K8Swwl z8>;{6(wHMZ2?r>MQ2nxI%6mYJ)0Pem?kG%x6amc7z`bdx$(@yxfl48pC8FHhpQ2}{Q%0F3 zN>t;$epV@ z>GAp6BSnLrST`&GRg)#Xjbc3~K;V2B+L}zA1v;d;bx7U*)+;9JEZBoV_pHyId8~iB zk=(MAMwKv7RMcpmQAFmj4Qz<{GnMMEgd%}&d&#n$p2=D!j9j+;`|h#Ha-`P$uw@z8 zF7QJyF9)XAT1qz#Ipqgt1jq)q9lq8L!8pf^*|zJie-X~qOr)}G| zZQHhO+qUhV_DtKhZG76cF>T!0J-dH5_VFwf=P&-PxTV2Q(W{A9v`{d4oxDl0 z?E&{lp+dQPGRw-Bm0%_kqdCJd)A^wHt2FIl+IC=e7Ap z32CWR>6_UN-}B~<*Otr7_WSA%$2U+NPQg-NxSG2vjsW8DivqZ1+y(1OXbJZs_oULUCK$z`jJ5^GW-;_@bk73 z93nCz7RIE?Ds)8T}~=cmJ#w{}<|LArCy z^I|Kxl$4Rg3YzdDa;)_?3=b1wb~&{%IN&k7BC1NEK5P0)dNU|2#bhf#42vxiLph?# zkj51#%~`GHvV0}38gaA(+!Iz9K;MB@G3i1`MS9}CuUkssbX$fIS~Y*Ot-;iWlvGS! zk|i=Gr?s|6LEw9RnrvipP6IoJUAUizV-vt@nn><99dL`w@8)b~CabA>PK$CNjMg4{ zN^l5o;laJT`asO{1KNZ@^^|2CTzno@+IR>b9|><^_@=@w_*x(WcP7@{)G|^BU1@pG zkfapnCBt9bKS|LJjGTYBkMNs|QwnXoT6pRp^xQAe>JZ+sv@@WM3)rv{l}mhu$#q0E z0%rPq*>|4gUAe)p9x>V7E3r}xO(&}JNC?6I7&Ve6OA#P z0uz^a9+j#lw>*8J-8FWsKb=S_Wz2AbrT0A(Zxqw}TAIR@F!o^csvL8mhPkr2>H7SH z%XqLYu$*ZARrG&_S)}i%hv%GfzF3vnY(o1`;`U@=G)be@eGGcDIKZUe$xV=R=o7(R|!>a3p!1#R9Lc`tC@4)S4qmNUrlutBTH4m z&10e9b5hb>VgBA-pP>hVn#xlF3niKCEVQx0H|N85(w2W>!B*aC$rA(5$YTl<*$I@6 zTy?|*n`9iBmE>CUx*v>nk^e~$W;|X zxm^ZB!s+hNa+-4YW~Ka0&y25$hs*ve8k_s?O1+s(zSnd&r~QR*#F2qYrSNQ)pBDH4Z4Jm}Z#78zO7&*YI zyD)$4ft#K4$P@?@ed;Rl?r-?zIp-IdqLlNf&YBTzm6B!1@$i>)D^*9 zb;1`oVD|5qXbY-klB;BCi!xvmLQYUgq!i5z1K$ z%O)+TdGaru<7c@pu>*B#Pn_mt8dXk*1L|!aKd8P)SfDyeQ*^JxqUIk@I!qD-(eTt zO`}uEiGER&iw$EYV^+d2SH!XbD_NU1Cnz1M!SK|*`0>`_w@ac$xsuT;*)ood3C#HL z5W6dp^t@>Ktd@gpE((W*LTCGcNs!N^|-5bwO74Obz3k` zT4C>wz2WBj@R;5UQ>7y>l_$8h@4LAWch`j5#kYyFHhRWi$qPi6*eW4ZZ^%Th2 zT$jx&T*J8ei*L1jN&rJ|yip+2r`uX#}|WYj44L?S3Cs%{HN6l^IDwBcXKcenjwJOVcpiJT8ELbPRBqnoweMSCzN1 zz)02p43OE|xHqB`c)UAoobK8?&q`)7;*Eh3;w``B)!$9hU!1Uox)0CeaF$|G8asuZ z_^qAwn=gEJUo4FH*i)DbN>8|Wwc}Ko!%~YV(hGlmVx3xk%5Z+_{%g1)o6>+W{YrcY zy|89hIyt_Kh{YlnwIL-OZ35q@w|}Xt`4Yyx)Yj2pv}wUdUF+h^t$fP94E^CS2u{@ChC&n>&G24nteELAI+u7*CVb zYt^*nAJWaIaJ(iz6HCj{v!>D<#_x{%_27Tr9z{}U$lzRb6FeVtD6#}*yu35-_{XJv z0Au1|6uP<2kZ6h)kFkkWp|tlzwnldqM#>TE#GImH(G}?&+KD|zb`?i<6Te5FVsL2= zC63J#kBH$@?E@b2v1)HUFz~?fDvM>JuWQqEXxQ%@SnSJ+H|E3-HjqRh!sntm^Z0+| zTT>$UeU@}Jn6Y<8EA_t(cOhPg^cDcZtM4^-#WvVxeiEke6x22md|UR(b<2awrCR*y zgt_-f`GS#{eUhUza|zhi?i#df zeQH5hhsF@yJ5mNdFP%7pkKOx6l52mHNFR|zv|g_z4hLTAl#Srlb@dO>Wo|QjQ)yKj zA{S2!9s1g>374aeff$3)ZXjkC;I}60bSvHJ@%{7y;L_W$MU8le4w4tGs*_J!yYDv$n9#9L%TpHI0pG2ZK6L!-0Jk_PG|7 zYazaeInJY0Q1Kp?rJEyo!6#^Z^rFap;O&b!WqJunyCX0$+>oCf;6@$b+i&s4@6tLX zCG2DJ)E{_)Q#c0Q1;DA`Td04SCUw2!R__B8x^UN~)&!0grHlCE3+|`{FGp`(_`%u- zxITgvh-z43I9`_e)UF2@UYEw2-S;(ot%*m>(<7H@xv~92cHWfYyp_O#_qSclJkGoO z7u5=3Q$=1oX{euR)o1jSUZ2g5@cjANCME{lws`rwF^6h^t!P8)&>nw;-h31PfC6|T z%0bIXG0)47?}lMwfGjG2Rx^Hl2bTNwQLWSi9f>eB1=065|rP*oVh@p;tr<9Y8CnH8G{(3}` zLAF$(6-E-ZG;U54guz55h?vH0Fl)r|;0WxwGkH91y~X{_*K-Tm{;)siBzE%_k3RfDbe2}`sZY-|#YDsaj5cmEvCV!bIh#D(BT0WobCEjE)TqvHn`8BV!s-09 zf91wQ$ugHfHPh*yWVsM-N)$~z%eD6pKe)_#wi0hHCXM=qgNi9$TnyM~`ZvmMFm=U1 zV3)adMPM;=uNX(Yt0`N_MU&-Hp*MJ0J@E{Tb*DIe$_I~R?oQ(Xj8 zdnO+bTNi(~kZj7y@4$+DN1HfSPU)${>!c9%T6@FZ^b&372;i+76*!3-%}>;4AJfy3 zBPVX4f~4IIyctP;da5%%e2XxsiY$ydpU4$*oTFXGz!kj1)s}*BN7hl}HoHL?MWzsc zb@CrZ65uCzkFNn}?z}HFjdA1$*@jG1;FT#Z{1ktn6OH-n?e@@Vujkt>Ut*1(lGRq~ zh8>@UXIy(IHe0doF?ey{447gI7Nb<>+~3m=UC$nhrSr1}VNQR-r^}FdhkDXGg{n3d%*f#yooXEQNPd$<&ILpd zJQ9D$gZ@at6c*4E1bInR2hU-oHPY&~E2hTsjyMFFgKn243c25!{0uL=(`fUKO`v)f zns7P=rC%QryNeW-#@%|c)BR~h=7dt~*oeX*+*YaQ2!@IlPya^W=E3c>3hB`eb4|jl z&e?I0r#MeSN~Zo7 zY+lFN(4>K?1pen1-FZn#knY-spSQK;R9Kqc6I)qLsDX((_ZVsjMUy9im2A=szG8p! zBIyNIm9cth4oRBwi+hI+BN(pW*8_>EZvJt#M@bfT0Ks1cV9pKc}JpHDgfD!PL#x>_76TDLM|wLVsy! zQ0>&2YFOI_`vTAMO1oH<^=?WK z+nN^Yaxix-i>sIAWa|6l>)`<-kis)p6mpM~7`!Nw$uyxV$jn>4)vU(`-${pgNWV=_ zqsJ5yBRUSWh7d_&p$`}~{G{bHQ>gPKrYx}rFOv^n(g>y?C;kTBa}nCp5Pp9n*C$Ae zz&W4~A$0MXQ>2NcVTpI8ilQbg} zaD#Bun91_+3#M+h@)5u-uc35{iaKjIn+{83V& z+gHnumGgJ^vg%EKCDg_}cKS`l_non5%T}O~g>=`McLgIUu8zUmAE@z6Ypvdws@ z5g~dw!1* zKMgcfC+2p#<rS}-! z@zfkUi5%9ufBfNsuzHG2!E3~dri|lK_~WI`^Ev7y#zUXLKFc8X877DQTdJNd z2=W`D-W_USh$IfMaxxk4k0d}4=a_ZWzYW&;dvN>@zt#WZEAeD`;0G8{A80-WDdK;? zC`jV|sAneZ&kd!>u1KV&IYJ1@5}Sq`z}>y1}Vz=3HPkm&W64n=5LSnyE9dm zACbpN0~>{dMoWNA94d;hIeLn|WKA zIg7ac-G~1n1k``!Tu?O7`4qO)C#zeI5JW|T^MK&f&2WN@VBs-QX;FAhauASEM9AfJ ztS?8Bwa?P?5?{w8l!lEf%yX#Of0rnWnSn`x=U`LMn5#DyTzv$;f~jOp|!li&= zqg!`-ym!0Yv_Ee?ztswSdg1gj{Z(V2(}DJda7IBjIZuD#dGzZ?X^&w?Ir2T!i2O(C zTjy3k=(w8Z;vv`JGSQ3bK;ciimAN&mU$z@G+#ZBF_CeJcZeHcRhwr52mp$?b{Z?M* z+&+H01q>pcj`ZYT*OLem=dF$jj&!R)8p0`=+~b3GsLXl)7` zeF+d#n4U&x-e7Fc7>;yj&g1*PpBMA!IT$dV#vjs6a=k;EzosXkD@k! zm(k@8;s8_V#JSEu0s9QMJ68?>Yg&}oPRknTXL~=~4>a{1Ub_6O-^ZGgB>Gg|jX87? zn!bOwU_!-XvSjDcML(;YJ3YGCQr*LMG)VfGEm*GkCiRHQKA zIA2!FfFI4DR$BC$Ft>cj>oY2D={)MXNyS}jDim&BA)88ZTqB}mCbTYH`I^69fYZ^| z>m1A4;Ju(@xa-nINdKB#?|(d6J-(FA(}5Vwq;K=}Q_AbsNSP&`E>uS&HJR}do6Ucq z`Xb;g8!B}zLaV8&H|;2p_y%7Ab5H9E_BmML+M!`%;azb)Ss_(X>P+|`n2L*|$R#en zAAa+*JMMB5xXE=fL+i*Eb&)KKpjee{myNLnmbmsEh_kZhmaI#F!`dGWj>q>pb6KKe zF!+i%OoMSHGi`O=hF<}?xosa>BW8bXX2@R;mV^@sO~T&xkBnD65pfMDZt0yovA6#r zJ0Jl?c=HE7*nL3#1{Ekh31UeSTu`bw&~aEWLbU52^2SW#iLiK z0Q=iVrG93qV2&>{AoPW#>ybr~PmbshyYTriTsV!0cKJbRSqH&uV8r;4au zT%_m43VY0~;V)7LICp<{400k^yUTvV*p$rN+tosh5qw_pZ)1xSbp5OZxzjgKPW*I- z9#IeBgov9exzpCc{q5dwq#Q^J*Vpi}NOt>?>Gg(TQBnAP^SyWuq6qO#+>N22)gqrF zC_W^4(UmU1ZnSUxw3zqa3<-a14cv&_pWY}{VqA_t9#Po%TPRyYg&X8ser#`ng*MUG zye=UA0bzH{9UmcFIKGaQzO=4Dy%zKTw63 zr16Dr20kG+nl5)o%13|T4~R5Vuv9Ylv}pm+6|6}95NHE+jmab4Fi{$_p7^}vnpYQu zftVlu4+)}uQ^jHK`N?RdQ-ersfT6T0Lia535~km58Zr$}SCqlDUkr>#y^X03^BeB` z=op>--ZVkeq94hIfpIVC5(OIXf`mHExmTL@%+|`-)y)no;F5o$B2^iOUQsxMGHWtb zH2(Pw?Y?~op}jI%DZ1yK3VdAh$)%;AGDhb`5l`0Q7Uv$43ZKbRz?i}715$_@#Pwlg zB*|HpEbv5E!4$<|E39xQq{c4-Mu7mz4!RPKh-MH5yjP_*AR%GN3duMT%NO>wIjf%{ zi|_j%?m1wQ9VmYQ1PJKyuM=bXKXqUtR?a5>sUDlvWE@a5P`~VR?}ifkq2kX%?;#UP z{KKsF=T<_=)9N}RlL?cksg;%3@?*(E@Dy0_HH2t8gex@Fw3?JVFN*Yv?4hkeZH5R8 z`w32&0|@7CW&q$aw8>y3v)w0~H@P>tKG#_n7`5Mi;D&$rGE%TaWyYLvU`|2voyQ1e z^Q=1YPL2MnEx^SWW) z^_sUGP{S-7FpA9iyo!h zdbsc{o9qaOmRVv<=%C0|A9OB@S98xN2)bb=7;%4b4O&?!h^a&LJ3h{4=`?qEvvy#O zz#~jjJ~e*v&@vP_F;kt%T<#3G9yEozQKsP0I_@-een0H^7^_Dr+8613owqJt(m$JN z(o|IeG!1xbMj0=xt$-Qq@+Vc8(-fq(jV! zdI8BvH31~p^p;h6zrfva%L)E?{>pGG%|45`vN%v{^j23m#VRkPs5%E2c&=|qpO)ZF zpOr6k%12q3wGx$co|c5lOP@A<=^sCP9Y24j!UF1Cm*-tN794*aLz9Mk-TUu3ef_`- zFb00-j5~Ssiem8$YvkjGP&%+66ZZFu6;W-LNJ4cE09h_>ZCMznlqyn?TO{XTR$>o zVSdWBb(KbwCQd!3f-{oxji_vjF_Np=XOV`!jui8iml9LKdln#HI!e3-@qP?0gx3zZuUx*x3P`+6H#xehtqdO)( z+IWBQ@Bg;9?7!@0MI&dUe?K>oG&3@_vbXrp-m(pQ95qzE(Sz|9=K4HN`7QFo)buyx zNSk$VSz*g4A2nb}xTI{t0aM-~6$A3@EJrWV3haIa!Xv0ZrTe9O>Fm_XZ=rwGcXYl# z5U4I<^(a8|Ju|s{Zq_XFnpd}7z5oFY5WB$kLx{meL{%bU1%l`CckN2n*jLR95S1RZ zix{UlEgLNYBtH*fVw6M?mk}3{BIp^dxT}*j3_SAGMqA}-o9w-MOt@>*v>S8Nk2+h9 z()d|*N$RFA(v=!FY=F;L!cTv+Y8-g%YOQ@ntQRYwBFW&Of-ZkVO)@mpwACDp%pr&= zW6m)}HVKw&|9Auyo>Y4!D>lI#ggVdai$fISJXSH4zq( z8s$m_ONOABX4mTKbDX}nU9I?I-F1ZX6^;SfP0B^90TTn7<7SQiJiBIh@fo*LaYQfK z4hnvPyJ$&|T|@V2&v?0NC)~yM{LRfmHm87XZnCY3fXGJGc&?o<_FCk=;aZ)({KUhS ztoMuD4!sxgwno_`=f{7d)_3ZBmK$OcUTR@qIWRZ6}eK&DlL@+!RbKEcv--PV1S z-hFb-QSPFGZW8AU;{fV6jeI>Ck-TfBOaJ&!Hp-Jg8%cKpNwcG&g;ha)&ybsk$7>;| zC$#7UBLDD~u%J7>Km7Z>h2Kvmqy^}s9*NZPH&=$gG66zQ6y$$2A5MY*{vHxuW@spW z@s~y1IbP(pF@`}rL)m>f!a7o>mT-6EeJ+kLR#8?}OhnHdM?Cox&%oXFRUSrETmXis z%8$0~@zY=!S)-25ckDAt-Nj+kq8FM5E*FgAPR}EOpWq00vd^Ancko~)1WX|woj=Kr z$M7mdH~E26xQ2fuubB1?=GSQPl}kWPW}TyMS`bM@rKucFl3kM*_E=DB(ppQq%l#8f z79cZR;^fVlTUQucQ8-f2*m!@Nv1a)bfM~H5+p$xh>&fwYepxgWnUS>>W*RRteHalPYAKsA}XkN7~#)Ju(2CLH~Oq!z8>hsVr#Dw zV+3|zONGZ0oxa3v>o~_S{TPOZjQ5bWc0w=$f|{>j>+?pcz{=FZZ)99PtHHCY-{AjB zJL7fVBN~5k9m0RtNAWMT<7z45VDD;VWpCz8`Y(UzUkc8qGd3JHTv11Rds(A$Xze#7s0&G3Z8ga@3emQ<_}HnI$ZDZYU9JrBtfTOh7s&~Sux z@eO@;$?qa=;}K6RI;GY-s&#;c)vjFppI-fEUiCiSkFE_`d%zuGk060hkq~2vLKz3O zvYjmI^D&BR(?8!Hoga?cIMd(W+|A+2c6RLyTiMgU*9(6`4w~d-y+| zM;r;REimgIDrB_fa;tU8nY^8ZmsM?&3n{XwVLStk5+v@GE)Td7m}Bi|<|)M;0|yC= zA<1HfRk?WGDxAMs1?)e@$q1tM7?X$6E7ZtcU)z0AsH0LT+mAgd23@mBYP!Es;MiME{8dMo%!YBM%nJnol$ZrDe-RPzj zRO*j4YGZBqBWjvimG!15#9ybHR(*e{v@XlM8K%8`Zn5+qw9HOo&&;Wb*2YO%KUp#L zpSwF&oL&S_zenWnpI)F{S<34g37BEMlQ6G8BK$rbRW*VrE|TL#CSMsGA$HNZFC{ab%oux?~8 zFg-fj6ELKF^c^r8oW+};+th0D_O`@v`eMc93+c1UgnhPtW}w2)wcA9-=Mj;zODDW7dC%%1)fU&ZyR6()q?%+ep(ezd#P(HwC^iE6=e z$N|nGf%*KL1ndmeJQCvD2m60n+axTyg*FAYA`Wdt9^e^w#fW$&aNZm^`3g#y6CTgq zQpPXl?J?y#vSbmb0d0l3hQ|afB*(2!uTp*Dv|J9Anvuh46rU#Rq?Hxz;$&AlEMi z;aU|3J%Ll`ttVibg(EH4CH$m*>6k8Z?p4AmmOHMC$#wq1{{GWYQ!ziSw1arA)6h$@ z^vrJEOY(OK&9W~Xojt6j!+8ni4MZq_^c`O4#vY1pUkbx}B&CvJg zfatWAo%JfxR{0FNCqjRFc0V_Upw*Ai8Rs{cws{siwXMKQw~3i3?rV_#)Gn2VV3S1r z3jb_?-E9tDKN0U0cm{9C!B_C?L9oOveL#O>zG=U~EpEOQ7=(8J&t*#h)}9YQqa#R=uB+) zA(ex9TjD$^xN=>J{J65Ks+{O@W_Q;m`M3@Hk^07Yz4V+@c{068sr4+ihmvY83)`U? zOGxdzw!G;YYdgDTN5)N$9QJF=bCpQv8W!}efKje1D6U+i^&Aw12ZLchJ0 zF&W+rE^`YuS{f_i%nGJ@Su(q?$8Qe!VkmGtClhql$3iholEsKDoY7>Ha7n0I9@y z8w*&2BbEbp>#Yr0P-Ki{}JaM&`A68a>={huoIU1)mwU#00 zi?TyJBci^7rzG|kz%ljIVwu2_-L$D2-ZdhfN0!IYdY0RCb9z2k_YeTM2w&3RsiA-B zK8UN=SZ{6Qf@7BHR3S0_)sa8|?tC!lZeE*deEl~tSpob^a}uSOKerz++OO&b!#MSp z>o_DMbKd}BdR_h#^l7-)zg%~xUOd+5n_x4X@ThY}tb|te$8J2ywU7ra@6uiWxdDo6 zYy!bcWX9nEp0k%NU0(Ch6X5=OUy6TX>y+017J{VSbdYsX~q9i12Qcbw27briY3>qewkSlX`wUR_i>~nTgGTw$s&l+bw@ePnN%J z^KlR+I{m=k-%8#JNhVPBNW*zBdg0q6bcXkm`ni?lQ7E>e8=NFj+LdvvM02BvPeYs( zqsbKIbFYc_dxC`c!REm-=H*_Kfq;gho+*JosdZx1&TD8}{mVCJ);)8gC%zPS`SzQ6 zGfcZ`ByUJ@w19{x|M%pX1)qPhWZHsJP7 zr)XEqU?+PLP?}WZ4G&=39#sr@xIxU!{QBvIT#%jlMS*4`LyezVY#FtWy9E8~CyFY6 zm^BIs#7J#E#pqUB!mOI*Ay{kFEWYuDSY|AT5e4z1FWeK#1tSS#bTfbSmh`pCtfeo3 z0AVVG8qpO^#i8!yL+#RD(OqeCVMyxrG-pzsp_l3bI zHBp&A@}NeYtGT3d1%=b;0F|A$@!JjXLoh^T`glLwsXWi`nm3N48!JxYJ}_lrew6AvLd;`N0a z!0n%Ybj#QF*RwbblxUVG$oCnP7d-cYscpJDF6tvhnyxCSO;4QSN|+@YqzW8JY6wm! zv4?^0px=F-aB8uB6UD`N=_uy~=%|e$z&7djZ=+AtOW~f-2)7iFuA#BG5XTf$GVD>k z(%)!o_uWh8%@ltX)Uq*st`0of3ZYJP5iHBTmI8(kx2Kr_BGeFB0trZ){Qh{v!wHRn z1-o!>KZCJ}GU1lEYYpe^YIp5)cX1UUu5a062FnE*!ui7}8v~&I4cZbNZgw$-!*3z3 zmE@}{lkMnb}`O-q2LTAB{)Ig#D2|Q(n3v-+zCtsW0^e-{PM6@%muRS|Qde znpr5}&&R|i7WvL0=nrJvOB>}Q7`qeze4SJXOE4fmtttEBUl%GFEi6*Qk(gihn%;c1 z_Ys+oYp73UWxwf=p(SHFB9|N0c*j_OVChe}HzLE+95TK+hCcscdd2I9mD@vI@Wj$W zFOunTsY-uPNEtnNA7@gTg8&K&mwSk#D==% zLuwz*EK4Ib>0uS^2!dsvrNuNKM?q*4Dw}Z=fb(X=Y+0Ze?%fVrgb7?q+Y|YUN=6 zzr;^kqJRvD5aRF-skg<PfAU|Rkexz!L~hMYw^Z>58_rN z%13`}Zh#zw#UXmMi{RnU=N;58vJaPcD9#Z!(s`*zT8uVW{UKtWbN+Cy-r&3q{J#81 zhwDh2#}mat_Oi|IYIrt*jA}I{o*a{qy52+wWlXD+{TA)I=uqK^v@}OIZXF(b)~sB< zQXYhwKhZLFnU1%sj@x0#@z**yZi5NjrxSm-&CT=^@wABX7QKcvhE`?l4FO5f5}|ub z+D|4VBD;wu5svljRC~8OtEQmB1bRx|3*-$=f0D}A2GPN#8V@Ox?aS%sULye0;Qwd^ zjCC24`2LGl|Jqsh|H{syW+rB~X3j?cX5N38S&{GG% z>$Riw&>b)4Vn&vufQ_W4o(exJGcbfWl{-i%C^(>TWN~ zEGYf-)J~BKoGHhtjGKu0hMP{tf4_flP8B6+|C3E^l5#qKW0$cN226oa9aC1A1y$DK zdVxFYz$3Kl`Zo}{l3$C8IV?ykYx3uGivIvqAW|LzP}3w$w4pX3@Z>Pc~5%wf9 zdIVk-e3yoaj54vrd-fB+cma{0wzvN%g;{FQ(Cdc)0^-O0?|KaWcZUA2;9q|d58ayY zE;t%!Uo{3clQvxLm#lJ@`@Gqb6C%?4O;Au|@npmHx)jZNt@2Pt-RomHW1SUE(kMSs zp_>Gu=I$v|pWoFijpj@VK|Tf)J|K9(!$)t;PZ>c3`e2W8E5(uzXd2yEn=PJB`DZ+O zd}i7$Zng-%PkaP`7-KOy=7N9K;q18A=ZO-Tw}w5PhzuN0^k&&(?z+?-brNTNB+~xSowF>$-cKx=c@))rEe>INozjHZlY6!{VGR&4(olTI3(k0%Fny zU4yInRGFPgF%A~WSk>+?b$QcR?!{;ZRT3BjYl7kJcSYDe!Zb=tW+Wx&jP?(WtPn z_duHzQ&U=9{fy^vq!>;{v0HNE9dzd;iwM#AZ7tO|$gLko0-S%X!8jEIo2L7NTBVLb z>p?u}=f~@?XEM96QPTLrVU~1lsDE61=dE^-{_kOPm?lAXC*Dk`#tLEebYom7BhXQ{ z*mFr@vbwVLjPhd!%`%EPr&LZa52z;bqDDQ=ASSp2?(1X2E1xwcB+U%jQi%@OFLDZs?2|-0fJRv=i>H$~`+n_I~RaWOl@&4nMowZ{+fLIWUoHHSq%{s}~Gp3i7Ac(_9&T}~U z`o_CKj|6{Z3YAxCn%eH!a!Fi=v_#HvuMX#08be*Vx`@UrxDEbBUD9~T#VoW1NyVV> z1FSn{Poe(3O2su0iDNRfh08&ra&C3oI_o@a`AO_~qK4MqLcaYumlhwjvleb;eimpn z&Cw_vL@l|w;IKmTfdPfvOISzu>7-Xay(41-bfsrsWH+2AMvfWwgoOQN3AIjjJY=_O zKN)}R_lzcZS}QmPtMN9B?2AD{0@`!RF;FPE&eCA3QagU}r)85HGmbehzs*89fozs& z)iTf(>M5I-4#5sCoe&1&XnVMwk^{SxbC4~s)K7pg#|~0Q`k%sr+TO>?0tbNd!g8J| zOaNn|GsC{}wXkNq#2nE^t4U?5j;|LEyHtO>(2ULAESEC;OT%miAHO_?uyTt`m)uVo zKKi)_V#4@&OPoLYae9OGfEwob5%&xy%9irjJwR&`J&Dl1DORURx0$F(wb^B)-sqt& zCvH#pqM5DE!a6RBnQd&?q~>gbkpJT-xT679H`=`1!%abFcsnzzI73mDyJ#$mjH5rn_o^&1@gL96T4 zJ0AJ1&t{B3;x@q@;g=}KjKJWC!R}sdTX63lQ&;5k{*5N-lBU_7b(tV9CR00g8F}W%fu`8 z!Sjx!dMIQ^=a01?P&BvdY??RBb^5?Mi$GPg5I#BBv>mXvfqmdOfmiqa_$nc83?Q9p zeeA427kB;J@gBc`yX>$4Ar)EnZjvcHoU|Aln#(Cr`I5seml*tH)xV zUYKIENko!Vs(J3AH(9R%gNuL8TYG}Lz$uKM7u@nwN_!J4yWF0Fmr07=X3AjJaunMk z6n=pd*Ffu83vd%JN_oyab}!NQYF!G2zLc5w?{`1K?j0GA%5R&5xsYUELtYYvy*wC? z5DrMxj?ycfA72G0W_OFBCwcN=N^6! z3d~cod|^VH7)3qq(8K)-CLV|ntiT%ZhUO)X4_e^vIw<32R)S=}^E7Ui^rhV)33MkweVrvuc?Uuc67F zUo->JjYy{=Z0Mejg~D*wP?O{g!HT?w(W!VJ}XB9q>KoZoalT8cPowRMOX zNL}XYiiXL?LuN5(z?#V}YtBw<7vBitRf=S$a*2>ZERRDWW?&SIbE_wT&t3* z;qtAabNptVP|P%F>PBwxS!lsiSKkVz!RBL!#wL-`D1lnVbCEKTXnTuQgiUhG`oNRg zVKVcnAxFkRM-5beA!L+KRT`G!i9heJh!ho3E!6;lExEun#3{ zIT~nNWk4()7nph!@XP}ernqZg14&fBQTk#&JxCt3-l@46xE#rp^gVCk*OXbL5FfP0 zF;0{BI5JYVUZI94MuG;WKEtFzi6dLhIGqFHdu=}VyNgDD{){QD`JE z*W76Z(LLXP`T-eo#~MkO9@RbZy+?SlqIvt{^zjU;F5Fr|)HsFvy%hMmEh&--SI(bX zrQNBrqD4XJzmPnp>Z+C*dzAOcyQm#_@@}4%#NV?hNsha;_t2R}X&~CCqQh&IJgb*N zs={d&1H0t++{gEb({U5-)5vsVIdt7Ju3$`Zrulpq_!a2+8qHHEm8olaCK7# zl$7qlHi8elM*$C&Y+==agaMyB{+1mmEG6~9%qr~u@$L6Et0U8~eYnl*QR35QDPozDW?W}F|R?Ya|3|lCvjW=z#Y}yl=FGO|@hp@p0jhgMNXJgH_R$0KO#I;qKDSU|3i~RdWhd+M zOeNk#qa-3YRToqv7PpZQ1!^z3rV_7JwqL?`WZ8BXl}Bffl2DitUdQR)w{$XGskuLau+7Lh%jGste~>uku=? zp6OD4T6lRR7OmK#_(bm3AAf};LO5oBWedAVw~&I6NPp+uik1r-+i${%3WPtkFc`Uz zRJkEqKA8shieVp~Tc2%dMfL9A;C%}2=ei}#ak8wcJWD=fjk;x+D(8}Es({>;qI}cn z6VR@WAPYr6jgY;L$V<}-FBWY{qm!kt9)q4E-jm-eAbw1WKZ~d9`EEb=KCc>oMHd+; z;8DseNi1?WIhs=dPS;~JWI0`f7@u)OOc-nDBkxOnVJMSVBzediT`^c^-x|C~3HyXA zrVf>LmYePHbp}R$2Aqhyd-n`5XJm^<;-#lknT{AX^m_@TkAcyewq}!qn*oXB4kBq@WU z>@5bq(mKDXpFKxuGtwv)b^gIT#Aa)4X4dT~Z1z_4RMnKUqx3As3+Y%-NYwWbB{s2< zfO|=IaqYlKbyf2UdcklJ8c7#dHJ~3rtpB8DjI*=(bjqbj{-dL+2$xZls9>Grt&J|l zpnqXiQ$>I}!j>61P-QLsy5x%YyttD4kx*C_nJweN(U}Bk(-1b@AFi9k5#uX_d^8Rn z{v?)Hb@Pt7`y6f(OJW53A;sCgXb21|H@yC%qs`rag>F%km&LG1r?S)ZT;P_zpJT&-RB&jzl;)x1z|-V!}Dfyxr?! zwF#<`IXm<%gLX)NI3uRka>?uH{w~bi-)nIGkk-j^BQqcDof&uOVxqWnl{r3t)$}wP zlVeNp;*KT*O-y&Z3BwC&9*XuA{Xw1yK6oQ$@ToBGJ=pNJNRIGv3&jM=n;*)N8Mhyl zVrl%a03`*gn>`pTpH50YdoBfKBiKf2A1Yr{agFq`0>uS?0=9ULjyXXPPnF6 zk|_Y#gGdhxy5~yCpKb+6*@Iu?m;9o6`lhUL&z;lMLXBx!t$yRt_SU<=UGB&a#&Oi1 z45@0=-n3K;!#IaN+CzY$1s0s$%ZEhFL+0LSB|SKQ+sPFRTcfJKRw0vTbAKU!joxTa zG0;s}AD8-j2Z1Hb&G#OK$8N?+QUrAbYEw*O=ydVZAsR|l!;%8)d7hptL`|X8i!W62 z6Pf+Zv%J?Y>-lfQE!Ekk+@AuX*FA!m8^bhr9DKs4J$AlL*B;DfpnZZQrgnD_c*geU zJ$;^ktz5iou2(dr)lPOwcR2+O4G$c6&%RkMUPzKZ?7Y&9If*IXWnw=E5IqTOUR^{# z+MRn^nIoT>&4#Zt5I$|K{Ui}v!OLfFxkcl2TKk@M%K~^y(fg}U?(clO5xcvwe0P`G zu8t}eI=UNSA3~bzMfp9??BC}DSgmC`M|k~zy|1BruIAVvEgaC6qGfi`ofF-5QCpVW z%6LAzd&U92EU%wC8w~fbZ{E$Gqh(g)OL>n{=~H8o2z2tWI`P*p@7~m@Gsf+gEdp0- zsuw`7oGz9)3w?34E;AW)Pg%5T~(05-=Xrt_OB4>;?C0zCaEr-NcL!x8HaK}e( zaW(^jkEGmHftC2Y$Lal7Kf*{0PV~qoH^a5%>Y?l8IeEXxECFv`AewIzBS~zFRQC1W zXqx-ML~3Wl0|`Z`oNMP`2sl?H_5RWSU+tWihXXdtC^sw6aupMxUUB1qY@Q(rQjinth8?%8M891(GE{j*L z3(Y9s`x(?Roe>3BGqyH$rE2GY{4~;L6LvSXEoo<#_N0P0ry0uOV)F3GCk!um4w=_y z4@1VwuD-^UC~uqC2M3|ap%!a(LUcwy{j^bAUlChNmq+@{2z1=;*5MLyWuU0NNM+~vo6VMhpIEf)!jbJ~I3 zG`P-4auIu(<%%DGfA#P5i>8|bzyJWK5&j32>~gk_#*9M$QM+NSh^&gjYZ(Tq4~!^} z0#dK>5YP~ix12|Vp_|u#r8ZCA)I&Y#qAu<-Xd<{QlLG)qtew6!@t4^H!#3&O_EomM7ZJ_seW=m|0Sf^c-NsP?>NsIj$1sCyA4;1uXer|sisvid-Di+z5;eR6fBmFdS#6Yx9j?UlXYQ*@>InQR*k7e z%2|r^ZsT-?%W8E75omA{`YQ@Xfp#(6v#QShd7MOcS44Hjd&HF* zViN!Fbs}%2+4JG|SGjv4|5J+M`;30KlUeRqMs5i;{CJ5kuxc z&X7=P``Or(sHdbTb5y8{>ii1n>DvHrmpL@y>84?uF!rMP$a-JB;D^lBbN-IN_8I({ zM(egR#qJ%Ia$Bx}jZn_U&xC*4i?7R@e!s*YZ++sd<>ZqGq zO5gPKOu;UHa~xuMl$Uw3)*hKe_F6b%pHa;nen=_SXK-d&Ge(<%uGD$OkUQmb*sK$t zYsII&jKasSy412|t9uE0P!_RZO614CNEOe(2@F*>8}BZ<6Mo+UN_H((A(h)5kDmoz zG!)4>^sh!Yt9KK6I<;}kNESTjTwL&G;j^7+nX!g{hUwP)(sJ%D@q~CO8fUfc08BVA znx}3Lx$0FC8}`awrs+Di@VYwmU}2wXV2Rx^XhZe0xVg}XgHr};9yVw z@}Qeq(6aAXaefOQ<%0#rSFwq z9jP-*fiTs^S2EOfED3>y9WopYWJ11PCTM{;2nNbWw}>SC1($LZ2=18m?DZG#h*F4u z>5jY?qNn%T1(P039|k?6rqg>Xy&k+6ayHm4rqUs`lZ+zY*s&gyKOnzzTu%}R*cp|7 zni(-OjG{g++F5;3L&Q>=9cgP=0?dJ-ouFR)5TUu9Aw){t^jcBl(-4<1l;9~GY!6{@JerJ)jd|Ho^`v2rn-)d zDq2laZ`ce-tw$Mq@anw&pZppK8H_UL-%E*CTD9%VYL1ol$1A)nxxvhiaVB_wEWMj^ zj-Hk?Dt#5nRvxs6KOiw#XBg0o(*|1M4ZLTq%t_jVFQ@gV8N;&mSOXGGLK|!IDE?Z| zV#mBAvhq2e!&BO05JV`2~EY=(8<=}KPavHpOhxKqmPWh4+7Hsm(dXNl`G4h zNO}n9P^~CcG*hRsR){bDXBdgnF9EOsQWhtHzw+v969t|9010tq`7OaHl34-03(2lBD8q z!2iC;IJM({aa%_d3+Xat{o{;nnNw(QI^!h4tSMw{6@mCZ5DYicYvwO-0yxC>Mf7XJ zhNX0UZV$PZr6NbY)+bQGraA*|jj7AHFrOpuz3tGC%Os-;8_qSRoDF2M?HH|CZ~r(x zzRs$&M0whl-;8syJyfXL8R!?|=rc3Ch}HI-M1iS)fKD}>ZijX#p*(QB>h{lmmWSV* zDz|hkwVCreO5r5zB$MTcwdJCdw3K!|b&2H$8b+C*K(L`?JHdT065o< zE4@a4F@lItcl&D5pM_fTl*yigKhX91csD*!huMFvGvx20vRE{FM-c4#XtZGDmbGX? zY8RA%Xit%jao}j*$Ui=%Yqh*?N>bP8e$&&4kY%^lOD2vEFUR>UnX<2$wM{GaraqKW z1G2)tg5I6`BEWWnNVNQtkLf|0NglCX#jh5BHj!{rd-M8HeHin)i)*%>2=LHDz|-1J zsuL^%lXY^_O$}@=?ZMhMf!agn0>#<^3>{!=MoanFVKTu~r6c zvse?fgz;(ts}TI~o<2_MWnEMh*2ugQ-#>(6sH~T%?huHzrz-PH==eq zf)gb(`VNyv&(9!Rf*>M75e6V#^S?dwAKNEwp;(c|Bd7B3+!S#qgN8%+oFRt#z~iEi z@}bWm_jdLG)ASgZthbhtx$JTWoj5F@B^HcP9=&V}T83$sLPB^z-P!I6F8aJkOG*GU zi(K5}F@Aw$rBYm2n$KQuDD8TG8bi!#LXY}_1sg2a62t$xhw=%cCXWW04wwQ&K+s>zdJ4$nn zKT}`QbhL3LMgJzp#FUW!w%Ere+qC_RB>WLFq?V-w)z?`-ZSnLB_SSZP7jM-GTQul= zDg=n#uQ^dHqs_AY{I}k~{vHuIM<4)zlfQe+|5rLO(|0g()&KkQkK%R*TPr1ZyMH$O zCM({^F3O?s*j}wvqp^*`8wU^;Smi}QzFG#+>tQ8Qk_M*_%W9X)Ei@Nh(0{8kA`xK0 z=6)4Mz3@~>nM$p|-#l-Bd0w}dveoYTdVPcGA|~fr6TQ+c6TtWNhIG$yiM zXUb%)eUi%4Xgi6kP1?WoFj<2OBRhg->G(aFf^BVeRohMba$y+^RvxkoNBxmLh-=(Y z;i%=+EVMZ@uZygUd*q6rmljcgHq0EGj?-J1CH~}@R^0P{5kyLHFM9Rs0aDNu<6A83 zo0k*0fE3XeXE>}kEN!epoz*d7o{4@Y_Nza)RFTUxKM1@)#x-1~MvgEP5b;e4nfa3tIIze~EAd^N#w8EhaQ#mpc5pIwlQOrlG&T}cP&9UMvHfR*tAe&A zGCvB>Vv#y>;?juHh3ImC9`Z0M3L<520wIJsdAJgP`73=o?sVFAIy+aU%1`)DKHa;* zZ9o2AEYgjYzpmRG%~W$Vu8@NjoeT2cf%|8>%QKqO#vKx|#!YF>YYg$k z<^jfZk|7H{2ZL#GBC8O1_zsm`yx@^GMG7H*rrSS>nVv_FEK%<+ahYtMM$9oRDuo@SY+s4eTY1lgPb18W(ti)_ZLjHxJ`p zO%r`aDr4vqWEZ|>-}|1tM{7fr*5s5|t^svR^z-{_Qq`6h%OF#J^DD00RKv{GY=~ z+V<~R`#&t>w#;8JeTSsb(pbKU3ils>;9n6|k-G&l5afl6lYl{x?xg9v1|?s~WM>n; zlk)nxYLUx}cijSdksqd?X($O0t{WX^HU6WaCljBq*BhKZ)|14E;N;g$0XAqzu-xSv zU9uNhf(XjZJ3;J{Cf{DaOp?`Ki`KI*@j7YkP2xt_tOWmp3H4G)ya113Qu*|MoAq;* z25)iuHhC+7GY(}b{5ptcg*Eb&f1ZC_m`*Fi9Xa!w*;)yu$VahA;~Te!IvMTbiF_S3 zAJl-Hb*g&;J3zngJL1Nk?|8hWw+6MiT}=qn8}3~jMlVj`lP*Ds3e&dB8p+6}T*tIc zn@@AApxkASeoBIn zMGaB9oXMecPLPDie$OnIi?1?iWi>k~MySX9PDK3qcypO`!sxSY?7qcS5wu|VuZDca zt?C?Sa2Qe7#i+pJrU5$}?FYRVNLv${oZ6Z!%zF;wW?D^3gjm8r29JW5#u5ang{jWd zWY>97Niz};V<+^!DMvDY?}R3n3qTl;MNvJx51>)5p>{fqcO%1^4BxRuj^FaeNn+T2 z2sQD>O}OC~ZGdWLq$LpD5)FbRg(5(Kq2`>h>w!^Kd(z0W4E*C7qTzd=_$1D7=w>EQzsu>!VtHqjvqx%Q49)!v5E9%* z$scJTF0fgg(vvPR{F{YEFQ^6mYPpUJR*{vftx3KNvOc1sB|Z(95!fW|F>>cWp4fPFmMC z6M4!HSa47lfCTAzRv*V`l#O3Kne@SD$nHywlcXO4yVRsF;_UBc#jshumQC zt#Wk?Aes6zYiH9}YXTh`>u8(`^%Ub;`7G^@DoRBI8Bj#^gY*lmT-~Q44U5Hr)^b_=dCBjQe8X^jymIAJyVfuMZN~FbvGivOXhgsup``X&FqZ~`*{CI8|{m(_m z*gavxpk1LaG+C|ofcW%Ny|_MdQ)wG<{VBH#5pbXBY`P;ZHg86 zm=xxvc%?5e z2xNLZ_t2sBlz#XI^wCr;MtXS(a<1|yO3f3+`M;^@9peLE+05Dan-I+^o9G67NmRnv zEU1MQmx?=rw3@NxnC-J(4<+I7iYAM>!p3)i>COeDyJm<0`$SNG0S@o#eMNa0ACrWC zxKjD*QFlr%SX~x{0b=MM1uG}KL{d)q&@!C!&?eD7j??dqluiU7ennZ*E-x7jg_F0g~z9PM?;45*8iF zQPZQY_z}t-XwRNVIV=_qLrjGM69l$?Q3mJFH8=?mpo^s1VDzA-DjAmi*FX_I6n%LW zaDkn)%4Cb$QNM^>J8W%C0xN_>kRK$>1NcEogaJ;6KmS%m*!xwPQS#T2Wr6=!LAk$s zhQ^ML<~F8ug2oQU1`f{F|FmF#%G$2T!WcfJ(jC?fUwJ_m5|;e@32P0g2{${If<(q=Dl$TiHi>tKWcho)^-!?csf(rCaZj>^N|*Go->6&17{ams6J?Z(X{L zzC6CK5Pck<2%;dsUHdNQ*{Eb2ef75mrZtZ6|btTUZPXPz+&2 zw96Rh1?YsQIgAW|LdE^rQ!@)la0VO*w5O8ZZ_mOt>{b_O-J2;qARNGA=&2v8b=L{#(Fq`6uWiFRDW{fTtL-O*urNc)kP{L+TXf3_gTDa>*MS9E zwNFIVTd(b8&y&1XR6u_CYm!^Jb%I@>1)80-DuJAI0y`RHVHEBD>qZ zL_SE~TW*srJ9Fy7OcdwGJDs(W*@A6Yj=l!yr!1SLTYvkXdt8ZX&MhMJlOVg}?!-BC z!d!heJa>)Qo%20^J}WY!0_QSKy?`>&amzmipe=LVtdQ^3Cpdu^cT;vrYXhEVCP=>3 zK2k0ai6{%cGuIcd-X|Dhm?MiVXA(5jC0)-B?RY7~1^JWu`O)Dq5B#i#1r6Q0mflGH zr2e*zX!eNhulqc9g?I{nFBL`GB}avkTF@-oNhw2_ zWGTPkY0w;4?ASfcc#XhOB(TR&HD~DrBG>0B zBGIA57kmld3C(v_FT;k%B^iqsU%+l#Nj6ywOCUvnslw@oe}HFiimv?`S=%xsZnbl? z0UwWkgCoU%*Nccikru|^!x%)PJzM;M;ToeIRj40L+Z<40MZMT-(wVu`s}GFj9J3~R zgK7_yJ?k5XD9x3r^l= zgc>E-gXL3yB&^r(;x#~qX>BN#JaJoo&FPyGhWj^vsBUQZ;~i{I@t*D6Dm7Rx!9dPo zk^c=0F)WU6h$C2oEW~`Oj)^Yhz+=DsJOs z>|mmA_#Yt@*?yTpdKhoa!eHyZpjQZl0K2v5L*k*L0l2*FZE8)XVsUZJxL2wgoL2x| zsQnOsaj~s1BfgJypBTR09Xr?(UwwBAD?^q-9pU+-IMx%Uw# z1u|c_u1gz95D=F+9)IskLVYO?u2`5&>`uJrHL`fIHdu@=6ox+f19BH!uYZd~^<^cV z4gFnV1O8V|{D1nHA`btUv|uG=YhX+)t#9b?&*NZnOt%dX147W~=T<)`5?%mMMjFt6 z5hxOYFkwNM5dTS|irrW{k9#(^Rs{ENJj#iTh!h%=qWR0ykFSq!z`7B^@SOg{6L_jp zT8HWKI|HtSp&TOhY3^|5t9cv3*70DPRc2pDUWai1{>#grELa)n&UYzZOc;{(vK?LO z7qGy-t#TTj6!5_FY`(%$X=E|qT2lOfhnW69&DIpW;A8>{1{QT4s4{@GZo&SHzjS5! zL&@X(C8Hby?u4nf%2mg9W$w}6hpaAM|H8&E>+B%{{J&{f#^IHqk^lVhLqBy^QL@+S{ zJn1q5cmaWA1c7>S6~=@8q9EoXkb65pvqjE)a~n>8b#qmCpO%ME7ADu3 ztcPsJe{`{3pznCyV*;dxTMCf-%lhjIQvd;>vRMpj5SJH&5pH|4o!e{vnlmbb=~VAi z?e=lS3?NrTP+)+s=o7YgBu~J9l+rZGHOIb_BCa;IVzSZj2(q;2Nn|K9&onNvqQPYO zaPq%zOFw4=Ye+G{HlY+ulpi%&VNHlHi?7E0Q@L80>Do0Q;NDf%0T+y@M*+Y@&K%Qens_ff1zbIHNTyOK~Xe3bD z6Ttkm@SivjXstG39H+x59C_+QU4qae53C*zeH=F34h$Y3j-b-?}%@3rYa^ON{^4Kh8NaYII}#11(wRhEsv@$J|N~Ng3T$W1YbC! zWHpSufLu)!+0sw!W2Agez?ok-6YH0}uMpRh7m$R*{&CwfW)0__KQEUVUMMDdoHOA9tEs!Q{$rh_eoK_^*|65FPC4K`;olVa5;r1NNTj=c9Z;J zAQ$Y94H?AMEs0HtTAL>9a)Z;UKSE1Tnoz0<>N+v3Qu-=?PE3JHx0Q7)(Kd4EjBecq%MH(~c^!oCImHAg9(9J(3;0-Z5eGtJd#We3^h(hK)cy;M#_{xma_Q?1OW~oD#Tmj5eC}l^zT6$Z zS6H&ISfnPY>s~;>6@R}7#iKqde!r->@*ywo%FB^|G5T}|w&3Rhos!p<`8Z5XCI%U? z2Wi;HnCp5HERFeA0Tny399QUKpcMq0W!L)kHv8DctzU%ffg+GGwOMutj~S!C>P!P_ zP3HJu0IK9oYB1S>#jnfRJ$}$!rE|c^8DDO>Ph7NPkMbt<>AH0J_RH*%I=5 zv~2gVkTsgqc1P>wgTSdZU1%+jcjZD+*>k}T>*%1{w8?fN%A7t`wbDi58&FoESpn<9 zrA$Qz(rn0)#14~Y;zWnLvIw#xgI}34W~}~ye9j$xTqONuz-U8E)D|-u%36s}H5Ib8 z62`^JkWJ$f-z=!QsnLQAj8}r@p2T4%ui}ymbBv3;>7gfg(xAST2bvA73$w%=G63^C0);JZV7Qbi8x4#-L zTT$QtK+zMD-AZzNe_A~A_-Od=(2#w9Bfg#NDu06Y9;L*8hPAOo2kb^V7 zR_d<*=NU;uszsU0@-FcrLQ`~cD!|L*!xKyvD-#UamQxeB@ppEAgbDaa zK+rH6xv7ODTn&yzOHZ)8Xq&9zq2q}COQKX!wHo-c%377__L)F;wP{VOX$BIdij@q+ zM{!Tf;^N6Ta?y;uMObx4X_i}mY^Ox=3$8sUZ zCLNBkp~Uryo7Pcd>uD=EYz#_jmOYp`MV!eZ6P(yI)BS16(kH-xy4i@-FScW!z$CPU zS$oqV#}Z4DeY`ril870Pdy6E|t1fP5Xm1BnO1yic0Ir(z^PT0L7F$z)$%~kj$_>Ne zLNr+rxTS%_s{{^G_mkI~>@&(jN1PY(<~H^jqBE~5^qCaKnH<}Ab-D}%D`$pFj-q3( zLyAd1Lq){YV|eeyZTX>)Pa`ev?)x@5T%N%3I1<&F`klBIr)%+8d%Uc7sl4x~D)Iob zJ7>iS*Y=5a-;Tu{24}{9o2n)pzicF;IgZI7kCrEi4vmWOalcgp)t@8N$|&+i%x%H5 z9O0LBnNU<~uTjI=7a5GtQQ#jA8_}~CaOcWJE@)$H<^O;K6*{Z=I z45mgEE!P(lVgC^@3MpLN@+2E~GB~g?`H*BB9?7*Sl%PN9-~wfTUX+LrZ&QcUe;hd` zhJfVzKN#&}Ah=c?hXve|9jR&w-hdB^J_&1}-=K+A(Huzz$oehKr!j`~MU5bTz_Nyy z54gXTwE^WRQaI0fbAHJcXi< zdPokQ40{0Y7uV~5ka+o2v0>;SVv8~!GNU>*soyWSwMhuo(4*%m4|qOi&RQp0=%Q5olw&8uRRQ%@26 zM40%*PL>A|k?rmf;~=gLr2_8Ru!k9=8~kv@;0$`}>Kt!>Km3RdVoL7EX?U3o4SZCr z;E@a9DJ0)U!r^gVBoEMjI&3?nS7h;5z4h#x?A#f-yEUC@^z4T1?Yqe`eeu9{u|x1c zz6se4f1^<&@TD-3V#@GhCLm)Ivv4X3kSD{#p|c_!ero%u}nYb z!5G~%f5UZugIhiHToZ+1n{&u&L2g=;&173R2RNz!YRW7)B9_q?d)4D~zc!`C7YbG* zogov?5fq|ErxF|FqNk=sP=35|i3&^h!p>`+jZ`*Z@oKvBQxlANEuW-YiE!4k9CV#9}l9kBQKb7xh_o?2b^V2?o=!a|(lhaBkDp5t7lCD!-7|v5(LJMKOzL z6XI_Knz>yiZ<2jgh8hTXvE2O~?tpYcRYoN*Yo7))layM35Ycw&9LAStR2ksTH7&W7ZNp%H!#t0OZF*S z7*q9sGpPpm;<^mYoAUT>@%m`4FtW?yaei^=W&{)~|8OX~cZ-NKvtK#0dp8I(QM?xE zdhoFGRNHld&K<#Q2>7ERr33~YKa2#UcmR+=FA%ULu)azDMGJQAV&(>q>`R91jljAy z*?Qx+KrM(b+`dLk>w3A&X`a%2tWvLTrB8l;-YtF8W2rY`#5f~(CXRW}Lsp+2zf%!5 z!UhnMgL(orf4Q7Et5CYMtaE`96uxu2Xz2F5o^gU$F}}Y>V0&l#=KyhQ(E1}9>5r=J zSS@3d@5vyZdaPH>VdWUo9<9l#P0}H7nUTC!w5NIxZ`3q(sP${w;g-Q_n;W(|)XBAf z#JqqRIv2~dE*_;JAd2Svb-#B+Rf_se&X5D&u{gD%+xp-BEu(Ps4hByu4n>auHWaE0RgUdICvdeF7d6bW2P^dCPqCiH*-3s zz+GRhP#|;;W28`}*~7hDNJ21Kz0$saeUns^<7!9FmiTP(%~MZ_aZu7=FHewimwL*e zFV0{%j?bvX7|Q22g2Y!W9!dbq+{-EPOfd}nExmFS(gixk79G+_s$AqK6p-ePJ{18| zOL%2hAJ{&ZxLu_Lq*>?bEx`5>U<3+)h9<=6Q%0!#HEq@wlgIfeTnWBRunnkxBQQ>W zLM_6AYCR5z0G1$2ju3DTr5`GyDw7Mvh8^_hScwB6r4Iitd_Xs)x+YhkvsCN3OkT=R*3Z2T_=ZTSGV zKf6e`E#lu2bKCsO@i_S!kyZWA07PjMzyeq0wb<2Q9Ok6AGO<_!CWF4TMLs^Z^!fDG*=N2Vpgv||*Bo_d z?5qPtm%*wClnZ6fJ#kjIB=B6cKMFr>lMkVEJhOL_!emT$PLZ}}vy4uV{SQ2Hv42K!h20E|?f$>pGJietk=}b#bQKig{k{G@SbBRp z3n_Z7sFA^QewY^ptg`iOn-1Y<+oSQJK=?gD%*}v#5ZPz?Gp~nf+l{wZFHdm0AQL~J z2wn-6qCF{<-bj1^34{>IW_Kw@L0dSpmE|U)AR(xa?r`as1pswayK*Pk%ujSLEE`n z@T8feAmk;Y`1?$E#^dvt7{fwl!f`Y10*N&*ij+sGKOm*^KO;|nke@>+XG^eZZ}j~2 zi@1m&f*h(*x=>t=%>f)u(QBg1)EhZKVcN~%mZaEeTjx4Ad#Hbgmn})bWN5ffI@+7j zXsz2CkXN*ij5EuD_z zk!IWWyh(H2;Mdv$(9Xxm32+D%`%?l1B$9O$h>Jw3-`7z`jlE50+yx^x{DPt>)IlXlPF}4+%eS9JLU`=9a1+Q(*mC)NjDb&62S}EbL7*6Wz;f(cFKP zMjdKx)b?L#fd1VR`fp3)A4LNHCz(n7&v$EUeH$ake+Ft4ByAUeBYd;cv4t-NE!_Gj zmLXF{fn)_x7Bz{*4+sJs_1LRKQ*CZu+epOiiP{T)9Qm=oh$>HQh`1h=LNd%*D6oI~dRTap|H18kBQKB+XwpA@|6Z$E7OcENd?t zG+u)-y2PJx6XJMI#*su8Bl)CIO^nTo$lhyaR$yR$4mz70BF7XCn3?UKu^ZoStj`Hl z4kf6Kv=9=&}#nya8)0w7YIwTjT1JGiRk4>=`NCH6j1N)i|(EABo=ND?e6_onS*s#-2r1bAsVYN48 zez5;lWIfRTNBI2jH2A;4M@iFmksgERdLy{yY$ZAQBRg6LV{&A#+)RK{FhfbtpzOxn zqB=dnZSAZ@6a-1^SHJB(WHk5?6Cc!n9mlvDS;U69dmZjc)&nm7=G)W92Ry)EnhixE zg(;FYq92#rYH_umYz(Bi5H`)^A{hKb#AY|B91?C(ojrBW zZbAW(fT)tC)mRrwV-)%-9q<`cVOt&J#CLX-yamA7xL z2BF>7z#2kd>3NdOMH;rfy8)el;Soui{WYDnvx~;-=sP?DqR+8oq{0ek_X%QSWH0w^=eJ5uB}4g~ zo$H4EtI(ck06IX$zY2m@0{tdSOsR&G{ZT`T6H8=-V~=7o+eFw@_%P|cP0PFae{Ip8 zq-Ixo{k@C%Bl5y{fo<&~HJHHmSdYtQ4e(r%91`c=HQRjv0{6+FnA1$y`_@rnh8*ON zTGNI*0s9##%R~a289-)#s9tkG_+U`04zCgVB|`&Le-3YnAbmJV+x$G^_YN=u1aW*w z`{@Kh6j3^DQtNQ^F|B93-z!c2e?4`3!kX(U1r7j!gZw{;IsYeQ{vRw>t6C~zuVVVd z#H$mdN!3YP;EdWEj3)dVyW2)v8_^qGqY{gXHasWQE`qH>MB35T&njAd^pQ-|+5X5b z$wlG@mgZSJmMmrZn#-L#D|LBCXG~u>!KqdO8XuuI3E@G{e(0Hf*qPz*fBo6b{f625 z^^MREwqy=*wif2$pK@^=l|Giyem69?=1g@3x#YUZvB^ashaMemW`?jVROK510kjcv?PkOp+NK0wfq{^P)QuVht9d)oi72WIX zoK14&ut*v!I{bmMVzD3>f0qD_JvB>SxX_+VAMbRqh>WRrs35q40Z)uQf5m8lWR^*j zIW9R?k8S*p|4n{B}D@3^eqvKrVUOP)n(Pyyk( zZ41ff%;}@`k6|ezNVT85m^J~;iNG?3e>9d}l^&s_&X1Z4E3MNUf5gL;HLU&paGz@q zy4i@6Xo6xEsd9~XdqP1F(iQ@To9!l&*X$AQ$Ex2ExKdU6$xG=<>~uNU2$Y|dv7?Zn zjY#7(2Z*y|CpM~&gUJ5)yJXY5BQE=rX%QI)d`7KFw8Hh)p_agING&zU2;_>r2u8PCMg%xKL(!zaY%abCBhnqN?!~?`=(FyPA`0^voV6%3}Jlk z++K4Ibeh&Ue`D_8g0Fh{^d>eZ_WNHJGNv?(6ePJM&>f|PewhB!!%PKiSL;kArp6#3 zt*izrqcrW!6o#G0YAX_NqT+6Ac(ds`{rTw%%`wR~hCJ?B-0@y&_YtHC_aS%@T?zBW zLvpzlu9>fqENW?3jaiZl?9`DWyw)b7Qllw`zKnmQf7h7Tzdy{Xyqy#kg?5mwm@IoG z_&-$OqbCAcSqo--)a@}N;8ilp8_d_3786nS25t5174kr4b{hq%*XMz-OCto}YgK=f zmr}}DvXl^-9o2?{bewtyxI_x9!gLV-643J@hs1yf)}WwQ5B{pm=$n6nHrI21-u9;M z;9VW-f3y6AmD8_&H_!7%9Rlt0Q69etE(>OtamLEj^6PNUG{@_XK2G=cQ-~-?N-Ox%q+|@bh ze}E@4j1Pl|qw5Fa#zE~BoY$p4|G50Q7m-TPrdLWXV-V6@-g(aG7bJeJ-do#{ayc{q zOf+;o0SZ5m;odzc*DDEldi(;m3xcYLhw|vMjde$1PB=*Q*ZgbIn5a-r>{1LC`jGCm z3hA8)nr2Pw1Vu;K^QWa0jFM87D=5_=f81$TY;5k$48x}_p?#p(p#gltLRjCH1ky{Z zbI=`Vp3#s*ameQ+`f9_^YAxO!1n!|oLcj86Q>JI)2__@L(><{wG^zQp2e;qIdB@Y2 zKMx)tURsJ_j0RUR@~dB=ddHvn4QNh6O;$qZq~^x#PQusb#2t1AvIX1v-nJO0e~U{g z+ia6IWOYbDsN}4-3OPfO9@M&_%N4n6|GBx7;v*ARXhvW>>rxkCBNks+$?|Iaz2MR&|_DH;+lN5Iv4pCVuSlDnQ zvWkhJD7axAH3C3Fw^e9FsVb~_37u7vujCt%?Q#og3T&-@~fPFEnf8DXH)oWZ{ zQtAP$QR`3Ims+cA6YCY7ncxg93(9H23hhZk6=GHu;%4PzdC&q^g(|JU?*tmGTH%+p zq-&255_W;M$6fFC1+l=P>D0VTvzCbkHXaL~yvzXbckeEy{q^DYG0?C0@{LxYOm-C@Qe@JOp%C7WFg?vt0jP?|zM$||jsC}xh=i1I2cNc1#w|E-| zo=e=L&jg|0|FQ~55^!9%`;Vmx`rn-=_)qw(WNK>dWc^>d!l_Cuir_5BISP!PP7tVf z;JgLDQDuJ=i4^gQfXX`JMccXYk^0K-qYr{d%5)T)e%5RZM2PY(sQp3yfRrwa ze`%!C<&#L%gM)y?LH&1vZ~w_@$^aK@^Z)8I^<76aDdeve!S|2DV6+f$U_zGBa5!2v zhysZs7z_!;6-BKR286oJ>WRHyWk>Y&3d0rKw>Z%zR*7H>e=$m_dh_fj_}i#D#@Xct z3DE*lR5 zJd?;wo7I%6@IRi4>mGSqI+%}kc@4?gm{F9-;3kKDhJlZ<$hY@@>Mrd-hgc8`a8=ny zNJBXwN8z67f1^kc{{0&oo|n*l2%*q#EIAM#%xpr<{oY&Oj*K!7Udp)eL^ke-5g z^+*6mkyBvBPb12>Jh`&3A9+0%?(=?tf_1YJl(p_6ju3r9(bO}Sfv%Jm-V$nP`^d;}8;i-u#x88tBU+Ao74tmQp-^x1xJaX$teYv3t6BX5vY1hr3-DO=iZiV4 z+G5M_K7BTY*KBnP zf8CGvSB8_Gho;%9mn68>c~(hf5BHv~t>Qry?2_MVa%)p;@5@y51Ag!ipH94DDzf^; zL&2B>g_Ltxqed`Cu**<~htwN0`~sMNyL`#(@TSahTn^kw3ar;xC{fDfMcSe(vh zFB4;lkG0_}&&kRpn~?>n7ua^6r1TLsLwr7Xkp#+>tFPtEyz<5f0q8S zghBr=G8^T8d-%VmxBgcQ2#e`a1Q&r19Sy2ShAt`%rlpV*kqSeWmi`dOD%jP_te>|a z*uIuHSf=&@A%xv8CPtTTU~hd|XUjLbAp)7Hcbp^3@yXo$=(H+HL-lKgn~~^dw@dY& z;VG#k@Vr%BkjuceLq)W3IJ0x}fAOiXyo~P0+_#c2kX6-(NxB@qk;RrTvFA4mAH%(; zdMar`MXcsbWj;Ac5F_w5pAJ3T3_PS`%;~(!nKSBKv$?mLzR)(gb+ln#Ui>_q-d>In zUQ>RW*FgGH?r17?qWo95WpZus_Fo3vq)_Y)ZNWf5q#^$=3XT8nCv|f>fAfFaKKK5Q zLZh02(!Xt0fiu8umMSN}!pf$`izaFaqGE8cu#;2%lZ{Dx&*1ZQx#@Vx>3Y9-dC3Rys5do*9>iotY{Uj+@Sg}=zjgbc6LQXk zm19fpjJ2xYU;`&@M=>RFe++#^CXWr}LPf}w7oxW)<7aR|k+SQsn)}Ao+D663@p_$v zJUf^$v>K_Z^quiA?Y8Mg>vii4Jor=#?eed;#aH6&W5^r<1O4Q%@W+8}-{hni>Syjk z(2ya++0#g}&De%%wr$wDN>vxn&3o2Wy%JZWjHNR1?+sftQ&t@kf4~Efj%Drbnh>6= zfRzVGB#!&J{%%Q0g!`Qrj@Pk%Q-qCe#bmldcboR3y-1)dOU;jXdU_VSi-zJRMP7HQ z&BH_vMnGN!X%@+I4Wr*YD(%Na!a7pc(YClkD`cc~M15Tti~KTJl6wxc!tWT~WRyXN zE5x2>>=7$5_a>H&f3#6PSt$GMGoYH8V*IGGMpo_hj&*@$eO44EPK?NXKn`&DGic|0D_K^ zS7aP`HT-YTi;_m?pa#JlIn+(J=15}42+YHyQ0ZOTHRhv3e=o^45-~&h@g{M{v2sP) zW4J9mVMF5k%x~gd`7t<{zj{%ff_gZ@ymJ00@YXDfvNBCatFDJ@`saITERbW5&fmO? z{0J>h!$a~m2OkA*KUObVDi(gfVOf7xm+YLI7RC?DMRhxyMb4PZ8g_`9ma^+n`o8}Q zN3xFO_m%wTe=jEj`@evDb#r?sN0ztXS@O5`6FxIg&uUPZ*^N0SSQ5I*J6pMq4kZgQyd+Kw?3EY>63Jn;e*C}fj=JbZvi=~Pss?-oo^;;Z2;R1@u z5o*wMjS$v;Q%Vr%?Z&@U(#CzlUiG(L@x)kaH@R%ZN6EAs(BAm{OBaJ+Y|4T79~Sn8 z@ZZr_H+Khf7gwhLeEdM&{eNHAD%CvmM3+GRe|Cq?#8>zU9h!Z-6KXnG3xP6*E6fRz zgpH1InR{gioKj?B>)F5Uy%k1x{QW+Z{PHM5?sway)c3X?82U1Fo{0cs92(~D*i~L# zby0Wzc9<{M2dW+Gx=cNY4R?%hs?uM-q1iFiAM9j3OW~KQxuMxBKNfIitySqKdhAL| ze}+agnmph*+cqCmXcBVB<3l!>;U(sYL91e3m{kmw11JUHJpK{0h$A4sXPu)xs)EaV z3=vn|SV--ii@WcHk0>nDdd(CYNVg}Qt*7UR(iKyWv>!a0UalDSfj$T@#brv%4Ux?rZ*(lCNj=bD13e{h#ng7#vC*Is@P{oveWBgV7i{R zbov%LWQ{UL3^3{u{pv`QYI43MCo{(#b(=D-Z)Um_92D@j-HLu3dD4C3VdWw|sDsA6 z&$oD;{gV-bJqV$2XFVIwUR>(N)>&tYI+1ChFzFWuN%{UtvVW?1>}j)a8)7ije}L@_ zq%9U!wE2cEwUYh2E*^iFJYksN>4&;le3dxvlM!5iU^H)f@>qTtw*1vr$3P{h;-?6!=RQWO=dA4oWoQi zK>j4%hn?tFyix<>R-{=4Hzz6)qC92`n$9CWfO969IX3}eib zr^M^DtzXsthIWtQV=^y(GsSZ3N>6pmF5J@mOI9X)kN-miSG~j>NhKLhR(5wKlJp1~Q0Dz5$s(FA@6_zM4%YDWZe|K^RMk3wDnOORx zAtCZjw$TKwD8JA*^AMw3Hg8<{fF;5!GJraCg(*ax{AF+XJ3c9nkcvJ&MMJ zBMVfu7Cw5P!CdU4vBl}D*TpPlV;!Ap7=C)KynmRFft!=DzSw2%==@hlW^HKPZuU(l zGz6%LstUy|nRt{F6>>?U$Alb&tnMZ4+Rlvl*-sill%lyVUp=fcXxU++u5zeuFdv$OX z<@V>0QziB*e~?r5_`mrFm}+dXhmu$?S$0DTMgx!lD>=Zjt82C~ljbq}Szx zThR4A-{Oz+np>W^*uqr)Gx$S;@M59hUd=3Ef-}rNr$7+(f6@jA1C+nl=|*9+jr8>R zBFHdF2^7V7@uSI&j=Srxt##jj++LD*OB>mgghq3(f0Q#Gw20*3qv>e8I3&L5p1v3B z_X26}$JXh3Bl|O$q2861Yz64$i+Q|x!(5>(OfVsx5joPaS4;>!Oawg^jeU{fDqWcd zK7!G%(isFw>$-;c`G&Bv7G zfAb+#chu1h6mKICLih56{z;cHpb}gO&#_Rjo$aD&s4u ziK&u^oc8CmY@Vi%S$@8V%$0L6HPJa{MK)xSN7flqtRS5|k#oMN6dO~Da?Re5wmCq& zdnKNZMXjGcj&;gHo3-JP9Sfti7Vl0uf7u*2E-fNs8=ayLKBiWPfD|C|VPbMD$Rve@t2v zTv$WuD+?3*appwtQq75vIQgkzk{C=IH(X&+ksYcBn4ZrfNThcx^tW-Ix1y9EkOH{c zs^N)=9l2;MPax3mYe$*G8|rcMfZNhB8oAd`%6U^apj=_J;;PzPU;4zQwg-ujm}bLp zKwLW?U|!yvVw_@Yxo$zr_FXW7e?r0wGGJb?4<2z3BBVE$=1{rgKQ%_7m#eW%qo6j# z;sa{TGjN+81veV^wJk_Vn%egH6WqhPIP}&Q%p4*KVDoDS6|N+$%>|^`IF;M+<)W{X zHU_cE1*nv&!pLgKDJm2Oa@TdVzI}*v=c)=~P0OQxuIe|P%n1rB6*ZvU8fPvi<-cQPLUj|V>WEQ-k!yj>Rj$#sVdj>fJ3exs zx}@bTh-&DB{()%+i718Z4?jssq#=tX>*t-w)*RDyGk!szer^@we~aT#G{{_KHniOo zQAWT)!BX_BZK3LZTB83`73v&Vg~Ot8pyDpCp$5}mX~Xo)GUYh$0kf>ACwj%TNLwgZ zF~GcdXNby`OzuWE823gf1(m2-I(A2^<^8qwg2L$vlv;#r8JNpyE~Qvnqc%aAdfQOw zJ@cR~e2T`-^x_yCe^6-l)w8#Ayf{@>kgL^_kQu4rZv&f%M zJ)Rw4n;L;LnN)qPlcS>bQ7-;XlBAq`dJ@OxlS;VRQTdD0e-?$1!txd3eS^WJqFO96 zi_lIqFXW3peY&%2&wMj}gBDnz&?snk{znR+fSTSM+OXcFW^zLHk00_2?JM$V_#F!D zjYM5B`{L<0r%tla#2t%HLNxBi1y@}v-Y3MU2+rx5rbo1n2ki^~@A4zfn{vIA`(Kci zmu&b*dm_ACe+L3rsv3D8%%QZwCmp^A11XV3$%zVO3~6DJdi*hBuu$BD{Q#guvbJ0X z={tjN4z?(78l0V(@ z;U4Nhu=;x3VKi*-(4D#8F?~I7n*9!>irin9lwre%e_V;D`raJUhT`cPcNE4imtAd{ zCw#Wq{f3-Zhwee59}QpWAp5BMdaOCcbAHMX(yhba)gjMjZ}BxP*pj=K0o0IJGnD^g z`BIZsUG=#Oe|PXD5*wG@*}-7?FY(KpSRB!K6ZDY&P1n&*iRG-z2ZT`RQ>)xQ&BnCh zM^4;FfAH|18qy|N%}67c57@q$6=RuVYzLfjsCcwuxylJfsbb%DvG^`?r7?YiavfcP z=cARm&H>4`$!ywaz7~+}f%By;Q>NIAC3v^vQ)7q5xwGXf{_&2I6~#_jPtV@2qheE< z*f?iZU_(5_!NR1~Mq`B@!T4CF~hkj~PRUBvaAKlBMcJs2xSf@72v6&=}9lN;#mcn&)1`N%F ze+z!fb&iC*`PzhmD8>WIF=xf9dsFT5fo^y@ro?7t{v$C!klbS8wsN5#G6{UaPa8Xw z&opCN>;N%G$X5nf^L)`m(RGaZMXK@Q_tvh_pfAMf8t6&p%ZuSKgqQ;>`!LL0C~KD7*Kr-9-z0L z+%k@~GAsD8l#{*OGDt8^XqD`*N#o(7DtH@Ab0@W95L~Ev@p$);HR+3NC}bQ-Ur;N* z2NpZ3HbX-nIj9W~aj2fsE~^X?7wj&$dWngYYaEViB94ILio0sbkwGtnVil-ge@yGl zpe9vrQgg1h}nM1qI4&Mm59O6X=af|7-C8AAnqYN5KEt z)R^-a@5r?s#+AN+euh87#9w^qdb{Kru0JJBjxWLSIa8=-!&vAj7^|)?b_%=T$T86X zzgh$Zry|9MLN5xd(T)-A{KLNoj^qF!=OiQ}5OFLnt*LCMdEl&jhyL_5e_Mb#Yr?VK zf$~kMo+mCqCrp+tnfpo4&Vq5V#-TkMY-O>$Hl|53kTpNzVS*-yD%CXK|28*%J!0WO z_T!XQ*R5A{a-tzD|>mmy5H|j5C|B}qyC&QDv^Tee=?c&k@vF7~OlUei` zpYvznUVaKBQj_;9*0^^9f5806Jm>yYh`bAV!g@nGG5BY&2J9bi{@+hb1=A0tnqKJq zpZu6PLjz!5ce`wnT)PT%!i8I25C;j_a;y`>4gu4obh8~iUZ}HOe@AYGe0=*yqPfiv zo6!frCMIM@GRhq|b+t+8>awTNwWqW$O#^)HO?JQkW!US!dOD)_e;>OY=D#bb{#W*? zWMScI?)G1b9^0O166oIweXR=VttloVy_kPxqs`=Kf}yHQNmLbN6lDLZIw$3pz>OPrmXt*Ln9w9r<~#y=5`uVLCS^Mspp(phP|pVVTPRS zz_w;uRqS|=+y#omLKt}A9S6Kf-RJvnU3~NX1;cdz;It5|Woc(0DgQQjAIl8p; zz$AmshB2RoAfJ7AlmR@r?vl8Hm3w+rdUDmdrk@0^$l5JNX7#CyCC*L4^v~6;WA|D& zp=ahxzC0ILe^plo{2tmI?S7sBpNTth4Hy(e6C!-Lcl&N2IQ$~hO?bjyo@FNxz>?Y3 zpS@MQNoxD<*4};7#1*VH^04+A7%qp_TMz-P#{>vgiOe@p1do3)5ONkf2;vhR*FUAk5o zB&#{_=*udwY3D4PdTMZVHB#fl;?VLzUgQPPfwA{vx7v1#jL`zhbW~IwU^HCPA2jrL= zr%wx-e;(pD!WU~4o{*J7uTkJE3@3tyWaoH^3~Gh3Q#{g`s-i67bT*$f81MVz5fP6% zJyN*g_)rH=I`go?=nL-*B*h}B7-M^HSmWTN+NiTvkJ~1WX<@fgv7vPY!j>qMrrYZe z$yQsl>AM0iz89JaQvA+<)ECn&cfpwMHm0&ae+^ie^;?{$jg1>S7vke14VfP=I0ZQ# zYsH0_+NDU)PbWhX%uWtP`0eV3!YT|=Z8AsK&Q}Z4zMhwVh0)um@}KM=|q5Ctqw;Ky_IlbL0Eh!pD1gq zf8kAUo*0sZ0D47Go*=pvzeYB`a?-@gKQkURQ)5nX8q(!`7-;`CV1aE+t$Imw&4R(? zZ5$yNflQf@Y~&y;f|?D|uPJf0M-y6Bb$W|htxE9u-UoUKN4=;gcHLir+2MUNyR2%!C_1%Tc>RUjAy6e*zHHer{`wW0A`e-;7i zvlF((q_4w5LuM=GjTTH_F%b9k@CV2i-Vmg2`I272lL<7u7V1P(1Ju_>+h4I?#@}u9 zd5E~I2uQ}W-KxSW$e_o?LMn>IJ0zN@FY$hswXAd9{)^sPFyyD`I3x(j2K@i95G?O# z3b3>G`TykNS~^puxhJs*7sy3xBd0M6sj0rWB+U4m+{FMds8)Tez*t@b>PvtELw(JTr`rpDS`6f0mTwG27E@ z&Dj00$CiD`ZapJ1riPXBnN$I~Adtiz@4-*YmT=`Dgk}QEElW@Mg4Bg95b?W!DFZJQx6CsL$@gWSHiXt(rtw=U zOe^k7DfpV$wj&sJV)HISA$&NQMyJ=x0DPkiRUk+^?Vs=zb&n-Pf24PSxCqoqCD=tr z*DVL5_I?rYQAKuEb#4)uHs4yH(m@C;p)v%oR5ED=dym8JxW_mePosF5sMQD|0t0>< zZ9iOf9pb3xR>tAmJ-R`fJ|~4=W%ur+GvBo_wOn+}RMe6KaO_)ivyh)5j4A39_xgzY zXBV~yeL{RNV4NgSe_6uL?3NweRxL@F2a%SA4N0jognLxr+&Ij(EWBJvlsj|~cZ278 z*dM-@OCJHA4t#=sZRa1yR}NhN>rWq;eh?O@Ce&x?YVI? zzuhR~ldRfcv4}Z+2(U!8rjV|5E@(R*R zMA4rW{i+u@zWcX4sj~a{{LU-_m~NJ8LRpCTCOk~ea)V^`6482BcM4Oi%LA0wp6W z%4&FN3spFa37WAOV>M%78nP8J zhV8K$9NqZ)+PgqZ57De9U8y4YwB4BH_rAmfTw@ADG{KkS+2!}z ze|YXLz=*}BIL1R~O=2IP6NtRr=@A+agBS8L);Y7Eb+z-JZ2AN3eettyKMy2uCE|ORh`ByVeA3oLb8TO zj{1c{6x?WLU-W{M+7k5nbJuD}`TMT%==o%J9Dv>u&S!UPo?a5K-sX>g5!Xsg7*yf= z0RqyC^graxN@o8qeDAGgZRTe6U-02f4SyBoTcB>;K$1AfjEpWy3pP!=P9ofXe|-!l z0yMPgLcYlo)va`; zW0h6o{*~6-5gx%xyPOAYNiJ98FE}J|*$XcaSD>^FIE241zu|`Kwm{(x6wRCt?^R9hBHy)#>*?LQdue>^c8fMGAq%-(k1J1YR_i2J3}o7dDK!{j3?@*}gAWfHh; znr44aMPGiZ8&|PbRuBzvGEHi9y%x`N_2miB5~sica#7RXI0sk)eqig)oHqF^tkB56 zr|$yh9`u=jgzA&wyfp_Z{3FPzh%m1->1uUcxjBveE`^6!4DslSe=vtDHG)!#9&UWM z!oQdC`cb01W-&VV?!X034hCqQgdEx_!mYaCH#sc+(C2%ONaXR|k-|J3cKGl|8bV5G z@I#6Qh2Uw)H&kVpiDLlW^lX;*SoT%k9w|8i^3~|8bT=#IMMR^}<+2jV@NiD&>M=VC zYAn>wO1X;+EJr@3f1)p;{Mee#`Y!D4phK~*pFrZa@#1m~KV?D=-LDL%=;9B%NWV#i zv+(99%LG7#`~{@pl7frjLER|}{(|aSAapV8h`O2i+)ba9plql<{9%UjEx_7xyGPV; z1EY>>&nGxPxk{<>6*`cDGJF7DsZ+POX z_l*2-fA{S$tdcbx*KxpT%V;}MTLm^ozK(;L0mPw@$x)%IKMz)eHZ%O2?grCrV%?e}n{wO^+w2D6$^?6j1N4I`tG`$hcIs z9x)@riCMaVBy(^1y@I)(KHr(;aT*Tp-zQg19xH#}X7r;=HksBhzSq6~kEUOKuZ{Fi zqP_5-b|MBgtsW=|T1&^)S+R~FhARX(D~CSd53KrV;0rym;$R*mzYD_qgfz0w2a^@k zf8oBI1imAPWC;m^I1UiDXSXdxRlhzL7 zqMeqQ*dXc*9dv3h2JNR*#koTfB8NY)e|MVewu7QuxyNo~Rhv0^#HcRgZ<78u&h|q) zHI7B=p~j0Q<6kpdE54Jv*e9#a)wzY2Y|oNf{`1r}yef-ea8zjvLX9p`6Pe*zC! zKH#Ko9r=T@y^@yqsBM3%*)OA_&kT6w{PPlb-)!#74_o0!8l2^oieVkkBBsr;ZS zW>I|c1!s6=2>_EsbqHm{2}_0kr1`uNKB8QBcO*6XHsUYevy&PP9E*Xjs}cX&C$0&y zS4fo5XB4aK2+lfRZE&>5WQRhve^n`cR-qZ44L;02#1aW+{z%g7yT7yj7#X!Se$a~r)Y!fb_Rohnvkp(Qw?YLp5JCbSs+*_qjyt25nP{&E{je+Vcd{TPoI ztF+q6^hHHWlnND^TNp3?T3cTaj(tdim3a>qCS~MjlD$l>>7Lg-Cwa%7GyY$fO_m^b z140ATV$xzAaj@#JcCs5CrvXM5)>9G$zC+JRt;Iz)@;Zhqtq&@E`AurHSb5 ze}z*r-HN@BeLRR49~h3?=S5}{i)rhUXshwhGFv%@h#=|`#@7Y3jGavgGaDvm5FrBT zUu6jpwCR;EWTyu<{{R1aXQe-xO^6Yv^t@ATgE zG3MHJ`z^eh#-+bI!)~N}WsW<`QsbVvTaU->1_((^f$M2yQ(56w4Ryy!B~rj@nJ-#` z>O0<`&J@$QN{551wRQSUJ3SMCKiC1v87)`V$2STWu28yE3_?p(seZ93f-VHRi?R!m zYrGNu3#mYZW}b_Sf15#iL^y00=(lZ^GsB8ayP_0c5ttsMS%_ET?6Y0Dcf8A`!87Qw zof;00#YTy`gi=wTtu(QRh#2D-xn{`IS^=O~k;b)0_@tVnNI0ar+dJi|y}k=;B`Mb^ z1kY_Nf&pxqkU~n)8!_yqEcB|RxVTIV*t*qymf%xt*vQ_Gf0RT=pBaldofBmp0Yi`A zLQ6*@O@l(C+4k3hvowc!1EmVA^y95Ch80Y51e7hC1Amv5fAiLBRo;?+u#K7wVUZ1= zA{plx*RNGg3ab^xWz5e|hi0NNZHP`{nAEj3YQc1hbcWsmMSBO;D5D;>4HX-w3`2T` zZqx~bhjMuYf8WRb^0z&hMxFt;M1XbXWc1c{YqmjI2O78?3k++c5z%ToIc7B1x21U&VnosKJb#lT6yo!X4NfJ zP^!O6KCAw&%1HYa9=iI3a@tino4CVCgjL&b0)t{gf4oG+W0|`aP*<*>R)@$EW-1Oe z?05`mkA6}XvFb1pQm|EV2{vWfvlGs#q%du8HR}@Tp0U?KU;QG39x;p|+9l?SINq78 zD@`jwGnXk`XYJsQWz_c%G-s6sUzadys9U9n4EnQ=;0upFc9sbs`RB9HNw})K=#r3_ zsa}Ase<$@gu>Pbp0kc1_IUY_MmTnnqa?GgO3F0k7hj(MlaO3A=4Uf8f)FC|%S_@>j zUuG9$59Pdz1mxyFmICsLMN0>q_H1soZziH^5k-1EH{;3?U4rA!xPOL}(Bp;KH5wAT zh%B|Y2+N)NKszqqauPU>@{O%wdB@R~lza=se@uE_cwvRO47Uc=Z9434_UeuH_~ov0 zhxuY|fc1JITpzygD5ah(r$bph3lbphiMSA^-hf(g=nWP#Bt9(VH#hRw%A+<;dMpFE z0b@UIMG%MG%?YSjNR%DsN9aUaE5LW3QsQWyB@}4q z0y1t!vIMFR*?UD#whL%TZC^C^V}v)u5>D`ktS!g96h~L@V!;SUOQlr&SNXm8<0Bb= z6prKa&=xI+Sn&Q999JLEmp_x7AKSY?^Jd2}V4z)1>Py+HF&wFoaYf4%Q) z*SR*Aw+Y#tO@=setkhAf+F?`ZF|?6Q!kzmQpb~=z6eY z8M!8}DP_zn;OU6>Sv_DF2x+|`*N7jFK8CZ}7^#A0M{sgXR2wX_UD#)wZ0yNg{U?wS zJI|;Ax0mxRUGmX-w+3nc$-2_VATN z>u#w6X769W$#?ongEf%|hM!{jD}_F&^K5FUqv-R0i@~w*6W+pcY1YWFIg@YyjOW<9 zMUPv1Mi=CXr1F@(t=ukRIU^U`G~8Afh-HGt?{~?|MfO4*-58A3e?{}plXsYp`+f-< zA$@xM^l)-={nWzaFyV>)6($?&`f(|Dxu?9hHyTo5O)709>0qeH(iB`YC5-fms7${t zGvACgjXk*Bo^5hzC|+^eb|6wS4Df*y45H2(;>{_TxrFCbX0{uOZ@}p*`dcLM)Z7l<+Ut#?CIH2DBI4jgWbPZRuf!Q8_Ywp0wRb z<;As>UlQmouqL#eV&+!q2|I2yAWia0OwO}dpjAd5f9)4%JPr?}FWZ0dYnkoxIJX9J z_U}=Ohvw3HY z0D7xdbMx(t9+kfM?zA2zSYrIddMa`I+HXNaIC}0e>QN@~Q9hUEYc}3GMkynIms#x( z!hY{ze_>o&a+5S5G>vKfh68d5&`9%dqtBSz%I0(EPi8cCh!h8s&_@G<~YW{H$7dCm~2GHE@Rq~HnLckFz{0CtjGq; z>N4VzQ;jPyH1bsath2u1&6riW)$85YYx2wFixPxdUVt62zHPygnxf$zuD{ydQh}eC ze>-Tc#pvL)^fK%~A7-BB8CZ>a$m)gxZ4Z+0K|fK+0T}19SYNyFWTuAl0D(V9^+ji^y(oo=@TSYi zJA+|Ry-g(zIz!T_Ek3L#7wMUzPN<7v@@#Gn#68SQxM8A-@JSUZ;+$?QNvyrF?L{V%D+$sa>dbzO51J}rWaUddgZJTK z*`@4Jf4o+qO%3tzQP!$-6Eo$x^GPu^KX|*cl=(c48otVA2UP6BQSrI)|;Y*vSFv z3_hID8XDGce`j+FWwkg0>FFlw#=~oWi&V>RG5$gn`}A7Bt0kS)%af3LBj|h$rOv_l zB`{_xMjD?c{WHN7J(9Lpw3I;rXF#ovdVkSW1R+>&5>l`nFi{u}nvII|g6^l^LwW)4 zIPll<&!|Y$u7b$GyrIaby&FUA(0_%K z9|{$#eZNhkLf!M$h>WfRKSoE$S7g?Zum@=h_Jm?6T6t5nw0rou7@V{gv+g!mYsB4k zeGWg7ykUm4zC3?d#7P&~QzB%ya=)3JEu@89w%xgy2p-}_gdJVIv`Kcr0hEc0*Tc@u z0wPBcL7g#E%cjgEgaG_S#dajY8h-+U@0{>#HYaU<&ssbQe{d7GaK{mHE?+R0)e~>l zEl<`RWa>SW^@&3BAsy>0*Xi#U?kK*~Ati2LzB7K`fw=Jno7{8Fh7a5IgcgpD-r%Yi z%)?Qxp&!uJEAuEDbd=5ugTw@H(Do67vX|Vj+!?}g;qPF@UvNHj^lOxcB7b7peAs82 zQ&lI{*FF$Cl8QF4(Y{#Eid{*!n}t&Wq?^OeaHLy+ay?GJf2h*i`S-spr8pSV&~pD1 zxIg|0+#LVEf!o8{^`AVJNzBpS$=%J|Mf2ay|ByVobb#FSaJn^JZ#>8C>~nFlZ0|q@OC1rAO{-P;B{2(r?_&-BGE5u zA@ex$wFat)aA)eSAZyIs_#Efxwc)!8Sa#;6>M?&{vxk~;gBT2o5Pt}qYA|=(<{Qwh z3an0H=oSZ8bX?DNX{@R-C(^gxac^qsNHdJig^T@@*}(7B2M6_R{_$2TSf61i6FJ)v z+-Ay@T)ut&g{25Vc9V!Aqqo>r-65A}X@`CVg@a?q!dhbrQ4IU2v8j{kNw910g8=DD zV0_h%YRFqpY(3{BK7Xp>Y?o!J!B7l{bTZ|QI|PTcsoWs%c(@V1&aT{yuhl_02N7Iw z2BX5M`m;hmY6(`p;j4(TiT^G-X~hXdU%+MM9Z9q|B7xKUYH2*){iUEVF);}@nG+`i zSkcYQLGQFCDEBxk3%xcau=H?SOiomqdy5!$<+bp{EHCMYB!9s2#%l4L3!leq@Qe){v}D_Fg%i;TG0c1VWNr0VZ-;&pT`-x`do zuA4;lTI$7aDYO9;*xJCNiomhf9LD_wnI_JG!TOd&7aoHi1S>wZJC6*GI*Kr6I|hL9 z7fkz6UAq<8G=I-cYK=-BbvK=nNuXu4cY*q6ltNK?)D5;}+OS>cOy{wEi&LvV1G=jH zGHj<^_!m0@fK43LCP0s#rs7FKz+LaktnMQBCT z>QSm|QGY1P0TqxH1s7zy6p`9hX|1xT6%_Y|V28O(!XzNaBR9u$zdQFecP2CUzm``M zDf!mtlIPpQM?aGO$)vBM`+nN+g|b5H5#PF@x-I&74c|273)*Zh#6CZ;B6>()#A`UB z^Y?}C#iE~gz55<>B<8o9x((KsPc?Vf{mx}I<$sqwD?M;`!@6a)9k%5!Hm}NVPu=5( zE&DFD8!WuDe^^%g*rj;x0G9pyZhgu1hjs4HJa$MqM%9mF&b}OOe&U())xn{i!;<4z zmhGcTP2(%(Qtv&%nHLV*G%b<*%{B*hzq|O}{8;P5jsrb`O{dedEV*vk+updk@_zA+ zlz&1uY1XJik()H&&8FU7hv@wS^BS``HC4>8RM#QHtT#&5@~etX84_MB_l3)k?K!tl z)AYj8bEQ9i;!wo)vfmY4pCK{aWcYrLP@rpN-;|r`Z56LIe6}n6&3#z-qTCh(yO+&N zELykh#O*JN-wBM{eX}U|E3**Y^|gz;bbmLxwPf$LT;shH*BumJ?QwQur>=ayxWlZn z&@#kbzth>K;#h6Df&Y9+QwV8*&TuBj)M zv_{6K*9`jaFj`^a*k1ILQ@=^-!B0C1TKmr!?``?V5R-$%xs>9#;e)6&o>gm0+J8~M zBOZ=MOD{%Se34@ri%E=1y0V8m9mR~>|88fcx0$|NqbK2hc|GR#h(YI-+{2gdo0{}R zI&4}!hTfj@D%N`F;hpnskBk5F%(A(9J|k_T{`Q*z52b(ke84VkYt^BS%-q4ilzy$Y z{)LrmGXmew3Mp95xMRP@ystApx(2dzCm|WyY9LU=5Pw+P+W6Gq z<2eYjSyTQH4WV`G(A1a$2@B+`?3g6Zb|>P1&;#N&b>K?E7b+t-SPIU@M7F*t4@*Kh(=-J? zO2iJDhaeJT1aTlKv5Qnt0)MbH>imChyfk(VRFX63My{m%HI}QE|1<~kPG05Z63`+- z(BeKMXzePckPuJ7Vo?#W*z#b(iR16@%0Bk|;{$3_s+U)?77WWGQv~rNnX6Z;VFqGs zl%LF-PPOl7Z2A?XMBr$BNouvV8fvHn6Hb4qS4XyKYJp)>Yzm`uZGY52Ww#K5lBPqq zm)|)%2vTJlaQ*T&&_u;Tl${`dAscib9?r)_;6I1SKc!YruF4OW1xT|4!y=rd*1M>x z`U*V2^p3J{ev$y^i^qGF(9&zXbBBsiak7ZI3@KH{_)aiv9)ab36sZiiHqA~My!mVa z2NQbXLX1spvJ01^Mt|zK`!i6ErC|7OC6(j4`|Ols;?vj9!LS4z1y!=qCHLMa7~BUy zFAO0SrO$JAiV}jwf!?90TlCg`(Tjqr_*e_}H~Y_yFT_xe7b-@n{mL@|xuf9ZVzCZE z{7L>&=B)VCtR^#fG)*?A>LW-biOq*sTRT+{9)NbP*p51pi7)PZh2ogXlN5h_3DhD;ZH{e#(dN6M> z^yH795b)mpG+~Jh`(yZy)6~{o?0<_{;0(1y3%1O@RDaEquL%PMoa96W%k2+0G{=J$ zM9L8Os`TxP%X`8-lknJNDxZV_-5|$&iP-CbCC*X=Wb|u8sskMLXZ{nWiAy-kyo`6EKcv$awq(YNBXS`~ zyMJiQ0|XNi`<}|u_|E#&4w8`RQ2^4i34`pk4XW%YIUYEeJK>!AP36$;aOQ9jbt3b9 zkJJjO4g+wwW&$V}o=Na#*nuM%6Hd>QnZ-4RB{(WDAw7GlZj4~qfTKVWMuL{cjABB; z5**fukTi8@N>o9PU{k-v>z~mc$?8h;N5{?1KvxQFnCKx7`S5Eob4tn&55Mn}<2}&LWVg+bv%d+qTKR1>m$b$$lGLioSx7@1%CjkolQjJif cO#uMWc9#vU0Z9UDpO;vz0ZRrBpaB2?029wpuK)l5 delta 89376 zcmV(rK<>Y|!Un0^2C%JBe?$Ys-4t2@03?M001E&B0Ap-nb8}^LE^1+Nth#kjr0tU} zh&zqDH16KGH}3AxxI>|ZTSMdS?(XhR7w!&?ySqEvJ2Q7<;wsdf^e>b)VTA4UAJD52G z?M>{R%$P-7tZYq1?d{C1ESOAejhvmM;>Hwy3u6Xu*P5+Cp_xgkcd< znyF*N1-%pbCP}Z!f6Q3nwgX}md$?JPLs2ZA01QcnM#JX2AV!f3sFir=Jcqz3cJiHz zLefqPLCRrHd6Q`}5=AI+S{Ty%-=r?&$;k&K%S{)N)f+@ne4e}d_G!D#ABN~^l|7nw zA~{}jo?pxY%I~VGo)2n!8@I8r6$`nYT>_Ns@b=`Mr{qG<3cJ_9)P)VI+B;B z#iYQgYubt5JLjk#CJ6ha&`(fn4D>%6AQ-k$si!W84@Gz|V|c^d0t*>&t&m=r;Zphs zFO{%Lk+FYce|~r{Fs}b2FGjW&_D)tnOMo-8tdT9i$WFq_7HH=5?;K^Ruc{D8q6&~x zxW+B%VTywNB8TNWf~dR>f-;JP&n1yH>U9I|F)n*URCYIRXNvc$!nVx1-D}>*^949{6yxXje}dc#;5LGqCL=8+3DgLl{PC`& zN#Cxn@zw4EpE4!yzS=77LLfLlVB>Cdx?&Db9!4hT$ddn%|j+EIi=fk=~K*O)iDq zZD!*W6KrG9Pkw(gy`8Zc%fIu8CV!n-mXCEU11V6_c ze;G%=1nsge`N7eE^k=tQ1E4MM)*@AYZD zaa^-g?D1NBbwUtd`kn5xl^EIBs`6vvEb@9asDfProWeRB7BT~WW)P_O`%knz90|!`%mg@YlwtXZcwNdpr zI} z#hQ#m?})3G@!QI=iqNWPBsZ4Af3vEjbqa?$boP~XR>;0u4uv|xMKi~XOGL9i+)Q$B zZtKSB4z)T5N>8O?4@O#eGemk!J&EDsO%21F{Q0I4nAf#M738Y3+piq2!xlgqIrB*M z-~el20qrTPr^f7msI^G(xfLRJ$+VJ~llaot1VSM`=P5vD|!vCEnCvErl%iPGs z>_56)EUO}j1vO|2I=)efh92FkeJcnW_q!C9S`v+M4{!D9a2@%pf6DbL?i2VMO(0R8 zLTDcG#qr4DW98-P>n;XZ^)`P9_%GdUd}7WjH+o4OsEtu!1#V^@{Qb^id5kBFbeQu3 zPKx*O!8!?2XKquLGRKIuTy^id@*)x#(d{#xib+|Rn*D~`@UeE*P7#q07Rj5JceCjG zbzjXnE*SCHMvB5^e}@JO(eM#nX8NoTZzZZ67r;UYwsnf1w!){h5leK%qg{l40hXg* zBQOhxtv>ux2-~ezhg~_^zK*#H!RCD_&<^T z0ebin1px*o^Eb!+pG8*A-c9K*ivREVkrY3ni18hFFz2{=f4!LjKxMhh?tW4Y?W}vp48oofzcx^;by#3a3avS{IV>vCxtQO^kVW-cDY6Y`7gP zUD^wQRT@)pF-L7obm%M9hi-!YMyPd7Tg&+$7 zSHUk?Y5^D?!8d9Cu%Gpug_vw1(zr6dqayHgNVHtIcY5v1N;BGs&UEQ`Qr(vkMyaBB zh*WggOj~54+mRi_v4SAIkdW@ZthjNFJqeJ~Qrkpqe$vGC>orl%hQ3! z96O1#f69UJ=%d8Pv3kUp9)&)6fM2Fg4N0vz*z6Q-)^UF&#@J+ieuE0ialOYC=ktq9 zBS-F$+a)vtdjU|ig%VcB2}e;R-=(oBQ}bzpcd3};?t^(ye3U|A;EAqly3W>RAsc^7 zM;wj*fr}$=IfFhzD~1kjs$95`h~21AGZ26@e@4D%9VwSXzTY^2hn_=3UMLxO+KPsu zucVfwQ`eKLwa!>tCJP#`ejKjGX#8*#n>e*gE?b7ir%&%JG)YqaMpt@bE~k3UfuGdF zd!{u(8t)XZf?%=L_=PE2TYjJy$u1getg&B>_7>|lgeBo?EW03xpBI+xPPH($_F@jD zf1lCE`<3~h5_jWdsj~PR|A7SqWBSiZTuEB&e;FfPMFI;{0UHx$P8*Uy)D#hNCisW= z{y-5G9Fe(xR7?3>VXI@Gx)$@@vG!ArJw}zB7ubA_av_le+ze6GUj#03k0spnY*pC=11xNR-KapX9<$X$8WTb z2T+!ay)MeK{S5@o%zIPeJT_bM<5trIu6xwcx)YoW#w^i3u@E{p4f2J<^Gd{aG zj{Ci=be|gS^`9fe}fzepSay8JW^u(|7zGRCC9=#9x=Edgm`J`mtH9LYHD@N;41fi@Pkn zCIzn_k29C=szf{%%3&k>f4SC+HEYwzn6oOM%GqJa)f7WtqMh}4-udrG2rIf2&q?tF zn^2%1>kNA^&yEdy2>X@8*T@YAhn;`ypQ8lkIU8`~2!Es2nVtY5!hgfF%3FFvws6bd z(nEwacSHPTF2vNxLU!n=O=Ze@>=LA(hFv^9l*;>iocW~Tu~lC(f8dk{X!x_hlXzXO z{p+vR-ohc)Na^fituqD*+Cx@`+4LdtO4dMn4x#uo=Vrni?pP6+*k1=(>%Tr6Qgl_CB@r) zzCTYWR|tW1L+38CYMtv_$L+?rWzEN1H`Enj3}oZ| zc@}r(eVKGkq;vO6ZeiFTU%!79xWkKAOOj5iX-cOjpQF=`7%f$^in}6H)k*KHjMpwp z9I=q7#9M3JqRhike4yGef_=FCQiBG((qV)W@e`d>nHpJo}eT2;#wCXE`T$_q4u+-Kx!tn)hv)W_h!2_GdZw5Eg@v@mVZ(YcV z$LG@&26VOgwvnH|3yAR-DL2`w0<0s7WnUR@&_yJUEn-F3rT;8o?)S#gUV-S4BOFM z$@<>$Fp2v(;v`jO(PUFZeskJj#LnIGlW$pUyXDdWB;Q!)vWNgVrqvTh+)R60{9sgY z^Ar0T=p8QDm?ZFm_)qTRe)W|XK!SnY!T$d_GE*~GD-$zkW=SJ}nS+t(zj|DCSyc>e zf6Na%Vs?0(ASoqb%piXXF&(t8CaL2zp%NgI$o$+4*+T@zJifX0@5@s;spqz9fj(Ig;6$H?pG z?&52)?~j8dXRmPaCFIBM>XG`yoHzp{f5h0uc+z|Ef|0$%-BL!Qy9~XGw@=KDJ)4dA zRG3HA=VGgU0aC zQUkq#Z?Z3DLujWSbNBg{5=v#(`=Q&YqL$j#9Z1)2nvvg>`)8`RS%%PnEQODZf1kyA zB{G%aD&pwRX<|3N-NXj7n*$Ej#3|0evhG+R6pB6oDaq6H%5&Bcf75SjjjSC~ zov^pXlqGcZh_h{s*fN3rH_fCn4Zm3zF7a{oGy;N8GE5P67}J385)YS;;uNCJeHeo` zg*2~Z>}y82%NCpLYi84@ogPRy9~R#i1ZtQyoU%!EYU!g%spZtSpDrMf%7S;H&MUyq zH^HhHRtkXOW&6;<1cIIke;17MNKCWe6od_A9a?6u_V<-odIUF* z+(p=4dD9S|d|-4PyIVe~a5woUA0B0%!r5;fQF)dhb-j9p3jFbW=R$*Km7X%0KKdiJ zM~Fr!OrR4hLSKJJOwFTu*A!x_dS{0JjUtp{OLGn4Eg^nVDfiY0f2ui@sWML)1VCCxvx%u^J7`u%^m4@ynK0Jtyd6yHT)lC~He_T;1x1Cp5doUZBL#-4iuh%mLyc`Z54mz7N8thRfJvKi+B>!3X zb~?@`if~|HZkS+TZ2y(Qmo@YF_mVHtfOS`0!ut3ce^2qe;>*wCwFI>a6{ro*K{;s7 z11A?p%IaP9${=9tUs)oh7;UPJvX(&>t3#b=7-1I4W=QJo@j+p%Rwn4V>x_GeWR zNiTaPIP&3W+as^y(bvrgq6Wb92qQz_H!k2~OH4_wPu}DTOO5jVDaS&cZO^Ro^oOy! zujA0@HKlJfe;+&Hc(?InS{*-g_m?mS#jme)`HC{nVL($w!ALGuC!AsWmyMsquQvy^ z9YcIet=P}~m;_`rSFVq~G5G%(M@(z@eNE<1Y3LI;X0oL#L5osC3}GK@@jSgf8<7gYtu4>ufn@4KCdWPT^yvb zJ$#n;#T|2ui!Oq|F$oGzcOR8rWzU&loLOJgr;o3n{S}w(zwWwLwCq|re~s?1-Ws@Q z#%>7U6_V>(wkf)Conk^BOQ)azK}(-vQ$u2G$C*ZKTk{4%9s8__2+WriH8f+(0%}^N zPU}^jf7$(+EHI$2{c_6j6d(59DA1mEirtDyU^S4?#;DDg(ty#}T!iGol@@+BTC!_5 zD=oR`fxP0IQL8N((~I4y2I9}|roYh$ci<+YR-RmsO_D!rDBYGPt_nQe+ZC-ZJBK3= z)+btZw`-oO#yxi~*)6oCpCJFE%wrmpve~1Te~ZFr`KMu|kF+I6f`{AEg7&h#mvYE{ ztA~K+Y#-vCkV@sD+6j}7!5{phQ+xK%a{ciRW$(w5bORr$VS`uYeAY1$Ca!S}O&IJA zC{1N?9l~o_ncl46tyVbQL*V?_pNP#9-hEZ!gTfWe8rKhf1KS*M<$d{6=}NMYQ`-H(zSUBUkYum zEcGS%mM9j_Wkk%@vN+Rb1}@UXF*Or*oup^&L5)4BL0n;{P$)4A#?TV7)@Bl?>twx%jz zVV+Fq(n6KKJT;;sHKIIqUwyou&fE&Cp)g!qZ=g|~b^dT`)P1zW-Fu=_jmSbzg?`H3 z>xKtzDASwMu15C8mNSwU$H_dMe@91@>(IPvoNATG3B4^CtQ&uD>B@y@6ZMIzyU1wL zk~;plYm%4`JxPE%sA(*`Lm@d_|JOgd?j^O6=4y zqI0sKhbus~sbx&2$XI&Gj_ZoZQ80(v=$5b5dqkBVVrJr^-yct%Ex~3>H{m&Ue~j6iI&sBguR<(CSsd=*T_B%Z$(*Z3 zchOm9br8q6K*{|AN1oB(e;?5@jg$bsl~Vh2U|u>=!m|JhYA`=0F{itw=kn1u1xkr0 zHwg5HnA3xM3Z#L8a+-q|UuJz+9v^9xPvVkE`#EzCy(2XXfqie=AOl5aL*JHz(`w z%Ojdz{fwWTxA;64onPScf>vpjbtV*m91?mzBKHObR;)UR2P~T^tQ(KlwusB=lH8MO z8!%yX0XN6;WlUU1eal%z~zT_fX{BKE*i*q z{8^HE8LK9W$y!=Re_HoLd=q3&t0DVS7;YL>WZIhYVZ$6wqA`XM0UgZ>tH3Yb00(@wu z1S*{&6}b8s4^$KMI3+4HJH|W~OHOY0&!D;!GW`C-Yxgp~6^^2tBF3H!UX$*TL;9VG zUS&NWTtVrse~C-x9i5n2%KL}(bh3?YWh3dXZ>TgoKZw<-%iK;q(JrrPL{%=4VItgf zB%>1MU!#70pFQPw3ZSUr0{-gfa^EwR-mrv1j`!;&FOj~XA~y{Tf6A4dOx&B0Scb#7 zCXLA?A3-5#k^rE6y&i6he=8+LQtlt(uh)+M%5@Uie@-U29d}FlEM2fs%DjUeqvwv4 z!yDNwy5DwQ_-hPNFq(53x)EM;S|WPZ=%@rTsYuiV>)Aek$03wVK{?Jd0AXD4^gC90^X8!2b>Y&BZ`*x=(`m{6BJ*gKL5gkf7 z%ZHxbe|y#1i$&Xgj?<|hIU_)>P5l>jQ!c+@_d~8 zThJBl6=e65F&VxOi(tl+?1^9rw6PW3Oh~p*e_F$XzKz?%+td9$!A}qV&;n#qWFsOp zF}!xSCt@zTwGB4?MAtw(7BL*gRfJ?*k+d^Ur1Ma#(9@%zlMYM3^5C9xPlXY9hB+?1 zZP@5z_un)T0%Mrn*MXWrV`KC?TV+IW_6ZpQq~_1e0^6_o<18vl0yh5YteiH@cv{f_ ze+I71PTS?O0>pKsm1=JHv$ItsThRkmUQbg&F%P`QW2rH2k?ZtTe{dvg+*#I0dL$4I zkQB~seH0v|Ry@t`@BQE{15yv((|*a@RfB5T#qCRtw!yWSmc3u&t(gzR-+(#RZ)&zB zp64IMWS;HPicRp*-NmX`7oE_Ia>?-8fA>*PFsXk2&4c}1#1GOs_+4kdg!elplkNJ5 zPOI5nzalyCF+7DXQ5uUdL36RqVx%<=33fGks#fW#q$d-%=(E~$D_hOihjigHGY}KM zs?Cg8spQXiQG|46vpNcHeaav!g$AVEh2U;=e986~&>iKBHLHe#zLWg34O3Uvf2c`l z4KK$O=2$Y}s&EAB)Cihkq-$Q(B41>po+^u+(tNP=%M2N9Pl?gosKk*1)DmrW{xCKD z^{=)m!?rXN%eHA&^c$(sf=5UJB%}06Qn6z>r3!`qQg`a4)9>*b%t1&3(o2Y>5rny& zym@#xMO7A5inNpQZjjDE88V@=e~5k@=e8IrVx!PV&Rghrz*BUbBCbFnwr@zSF?9`L zc8?R#vxsZyE%Gi?S~?CcHzu^OF4EUFHuM|(fGWH=ZmTqueVkCl6#?>j52af@z8(FT zdj*Bj0qaJr`A^zsw4Frvnnqc4T=R$wCd?cY_s^jmD zx-IY*GM|X>>(X$UKY?c_e?c+tBZtvLk1vOp8MFR>kV^wVY(byORu8N+fE``)c80#gNxsej`Q_mRg6B{Hc}~<#NX) zi=5Hw)^M*M1CHHi3u08s=X1KSr(%xMjeOcCpHM~F=|{0ByZsyUpLo@Z&w6O1l2)Vb2~s8@Ga&lk zhtNIcAyh_}%Jn{wSe- z$zvgh7Zw>ue<07#3!Ie0f_i(MZ37zh{48PQ&COHE6)-cyc&>wA#ji&=Rug13IzZGI zt)J*GwKAIs$l|;W1D|X@BN_o?hbnxw1~<@U!y~%d{Gguip@XWE5Y384T|^-4>{vJA z6EORN=dmKM-4*~aV=K;5yi21c=Sn+wREKy8HqUj@-!#j8d{Z3A9g$ex0UJ;xPVprSBYA(dY*MOZK&h%xGn`Tws?L^^bk_YFeCV! z*LBO+|LIkpe+SNI5bE)=R65_ak{*>tOS!5w~V_G#m4I9bK+)X{1bHt26n4g=cookLBK@zfz##6P5!0YjQcEuTY ze`Pyqjm9{l)~s4XDP{x>Q_p#r&=jzJCI-hK2Fi*Far2$T0(4!$sJF}dcOe+1TMXIF zsBeRcNfSO1=Ze#8Ru)b7f-{=O`bzdxa4 z$I8#Bg&X|5X+&)22~H*Ofu2=~ad<3ejc=}r8^5*E@2FBVw^I0tI-p#uCIS8@e|0xH zE8Y3{1J0E66NDV~RHE7)QWHDUUG?qMVR{KVN=v^f3@HS7N4}%aRLKPT?&aq3P%9};Hf$C$h zRJBwLmsxLLoVrmCpS}DIfBYnW8uS8fVaSTR5CPN92||5aNaZiET`JWf`foQA&o?Q9 zKSTix?#TCb8E`0r7Sry?1WBFhBNH-qnobq*1f3`3PU<{QNPfCXBb!ZEvwe0jj&S$f z(JtJgk8?VcjFRKRISBR^J|lpH^uRo*xtn`ce047u{#gykBIilrV;$WU6%}`SWWIXVSfxM^ z2Y@&4()nOS;tAle+%1mn5YT}6b0)&Mi_R4t_(mvrDQpf;BPmX4s#mS45-`{mJ&*s$ zqe8*Nqc|CI@$+p=SfH6T{~Ty2i3gkyir(?)+!FTd^Y89wf1MSH2yp$`!drX(#qyUM z+V~G7H!jdR$bk=Uaid<&(vem7O59tz$^x-luB?^VAa753R+Dx_ZcF#ieowws+U^XR zxOg4FWhK=1kgqZ43sJ7<`pvcC2g*j!XU+C$I8=ApCB&ao;RoK>t}mvS-ov0k@6cGu zyBB_e*{m(0p4hvP9%?fu^(EQ(tLhH4>K<_Y`VTn$p%={`BnCO%~aevo^wa@ zQQXeP^s4z;cr#n)2K^t7?6p_Pixo3Xo1vFmlui0k?rADP@!hh2868X9^Xv*}_~I$D zPqRfXeQ)0?>{~>rMB?fA6O!zzJi~T2Rnu;Z%khlue`9bTL7)r)%hHH0-9*>ONq2HeB=_IrgXNwaL%5I^U;nLStjkK!{XSQaiFh8+syO& zYNndf3VLLlAQY@Pl@~P1n0Q~g5y=d$D-0QYf5x8h9F_9?_d|yu6^?V{U5iBPP#3t} z#66c@r{^5wWa*E~x0+`ZrZ%w8CJvg|8fi8T@#x}_N$7(YakgiM>bO&(>x(PRY~3P` z*4^qpA~)oVRvU+*AHOy`Y_8fnU{cmNaGe*o#NCkTuAP$xan!O<5%QQYJEOzKraLva zf9^YjOehZ{@C>ThMnVv}bZd8U%3o8Sl4Mj+e51G=nmWMkcK~`8e4q!nb>z=~*;iR- zLH*}{Bj>+nT=Ku;##G(Roc?zwUZhl~0AfM)v73bw$-_eb+6#l^ZUjl1CnbkQ6yCmi z5!No_oOB+1X)I#A1^GmyMoj{>JoNxGa zW_HEfl)b4!&Bo(UuvFWMDy}wBJyrsVlIFsr$`42XM1O``Y3VR4X?PiQW6_v*f4T${ z10HYx_<>wfz$W8{4BOG`OxV#-$P)x$gEcQv?HzG*LsRdK0}4V5zKVLsyxu2laBTd` zY6G4mLA?3b-?HNUHxX4cvo%w6_*X=`w4QYdhVXntY`*J24)%fDnn-y|LFk5^bJy)t zph68Y_0KOuSIb*`?i2k#q~nfC7IJ{%nFTyc(BtkgCc`s^ki+CxA+fBJNXb6T76 zD+Xq3-s8&CLY3rG@fdB|Q>o$#7SXp%3!)PtCK3rs&!%X6_;pj>HsGQY^0!qp$EK{h zdWrHOM|oK$-HL)Qr%=|3nZ})7FV(4P-mDUp==W+%+2ha-j|0%|rtCik57z5;E z6h zSto22+AhyXM~*zpwVu&LLzXv1rb$jw>lhnmqBU#0jm=PW8+&z^4qbM*>eUqC9H*4o z)m<>mc$*X%7Rt5ye>bTv4AN3+BGoNK=r&WBXG`zL^nMpl8sE;!IF@KRkitieDes7c zGhcN`;0PUVSg$!M@jaEY)(a~&0&d`U0e(BQE8~iW)|rm#Ou?d>y`3#j4A>4gjmt5X zyHnVjI=JnzbG$-~5u4vmv&}w{F9-KfS6vayb{-h{VQutMe_qVC)|r|AYE3YJ!GP{^ z!BLD#@n=(ijQ4TW(kXZN_eE|ExF+xZRN~r(gMQ^;kCO54idzmeYlp2PN3G{70onEf3n#OD{q z5N-xoAP6;vf1g}izQ`y??&QRnM{R;HH*$GKJX0VNU=$MQ8Vo7Yip7PZx3ElK>cW?t zk5nni<*xu&rBv;-X^5j?Vks82<8YrdxEonMMXcct6 zG$h9zi?3nUF-1Myk$TI5jyd$2_|?bTWFoqL%S*=h9dIFcx9Pb{km6y!7V551RG4# zj#Yr4z4+O`teupyMLizBNI!O~4s~4F5wp!Q%C=+p>uR2+kkTEuj()owcxCT27=op^ zC(>-pe=xsyN76>$6Xg|TI9H*<5LWP38yY&G4lW83tlq_VqIjesXHgfq=58wQFVQ|> za=9330(!>)iqJiLCI*HKC>4&m8KI%Ecf`ym4}sqL#qwpx?lY)yAjCe*n2^$lv z6j~EG+f`N_w(3i^zGwU4k)xgJ;)mCD7(>_{t?*5%a|NC;cr;Jv{7?u8U%2~Yb-J;( zm%2}!!1#q;JV&$y39p)Q^L?cLEKnW<{J}F*^v-*atbpm(##bHM-W&EA(qw8vUp3z$ ze`7@dSndeFkXY-ERaX*O*~Gtlszn2n@=(s0hn1lY-|k!2Ks+(dcjk}vsIS{E(-**& z{=&2XKPT@pS)VOoIJE#2VJMK3yQNsaq;Fwr>P#xAsn%4Lx@j{L$nNbsoo7(_x}o*H ztVFcacZzN{%a~-VSXl{ye82`jnC^Gee`wIHp5xZmKNJ6q<3DD=ark&$$dLl=dWV3* z7EbJ@x1$0Kk_;N!N89CXEax!Ti%>+X&KdrST`#4bz(A7(JD&K76VjWTKpsV`D*GNc%CUoj6P-sq3NOKC`&$mNplj_ihV2>m1lB1t)$nEL% zN4G$<$_He#_@s!~sCllqj72TgEa$HkDX(?p2CYvv&dFRJ6@g!i7FZi|Z-C&zO=KGK zA-c6t>kX$xBaAc-6MD{FJYT>FfBCLg?CYMCHO2f955FSC$R2c#^rFSAw=z|V@w86= z7FD#J1Z2~?*cU{k^nd>(VNw3VAAdrUXlsw0(xLqUzkv@wLDEUmpx}cN=aNbs?qIJQ zm$?#G){JN6RqY)!*j zkHwGEmUg)9dX>bp#r_o(aDTw8O`9KQeA4yXrp*P|upZ#ovDIg|TN zDKF#)qBz}!f8?K`Avgkl>@#$G;_LjuOH2}s(Zv?2{XJy?uM&;kC3*$=x^O78JylMU zG&@gljU)3y|Ly6LDC!9|=kvt!?dv~1q- z-u^Y^N;{S3%HL5E{0+J(;#{&n0{5&QrTxS zqaS&;kol8Lk(fRmTnR#{XzUH{+y2d%6;)kz4rn4_hHge;`jj+)Owvdgf63wzfB3GC ze0Du@f9IwnzZP4V+sHQw)Yq>fp%iyahk{?jkK}02(}3ke$Dz*T$IE=j5?Jcs_5n#g zzU7Z4pkg`PB_z*ngz~cBS_8^&^E~Nlqc)Z%+hb}ggkZd0zSMp~{}a#}(g=-WNH8!K zI504c|1zMG_99lcrbbFub`JJdcEEqTdvKxGbDsYox zDk+UcP2nPy8z>CGIe}84p+I)DrRHdL4L$oA0vnT0Qx;BcM!^H(;s^Wu2+z~_xV8m(~LbKl!T7Fm@GOl5HKe|_tX+2;5LP9 ze>=xasO!6xUTuN(An@A1^38jU87kYz*Ve<=Xl%W<<8`q4oUo%ABQb4j5_OR*$x@97gOo<@;4Q_#c~3^ z0rRHrfse*;_y>bEhGy%D$&jpbi8c_#e^`=v(R^iM+FfLL8Mw-;-mEwl9+iAn{0Xx8 zv7%D8I_p^CwW`d$Mn%J1IgStwLfBN9J8=rdFk;7mPDQ@#v=F|pmrCkT1RGPCRn~3xHE-DXPu_#pM3zt$q+5?Yo zwE{THg;iPd3}wDc^f6rODA$D(tm)*XO4KJ!2m~Fd;KiW#%UlTF--}GRR(f7qPTiyr z>ZkC-9@0z+Ak!YF+u*PN05$M9f2Il?;7VfGWX%ZM^Z_ywsa;;D^Kgmh8s=5uX+i9a zn+94sdV7n=27qch(i?baO^pdVZnznSl8w))>B=uc&-e@3v+LOwIvJc?RtIbHn%bdI zO()#R)aGk9W@l0~$luWhh~^u+#Z^KpO)CVt(lw?{e^1tnr(e1V zXKd>RIRxxfZo^P?idtqf2$cyQ_zobVuzq5Y!k-3=*yNxK#TXA8PzjvL7m+{1x<8YW zjmPl!ZRWOkj*7sW)hUD|Z4ho#<%hD8`W@slLmXf1;+ixfc+1vxgW$Sx>WVF+ z$Th?S-UhJ5>u6m8RIp~wtYH(x^=3w(w>`4)#lH=-X|i(4>!B2NKrG16UC zcdS({98MEQ7Nf;uyHr7Z$hstB8}1(#QbHe!1CE{aYIN=>O%Asxd;5n+ZYqiTkrJ0C z$Hb=o$tJA+5>V~fF^KF`(**F^xsLuDi5%j+(%?1p>2zC-KkcpHf8{aU55PCNL)toG zPSdDadoAWyrmQHsb90_4t9R*bw{6aL2ndzHW70hkU5p5pv3p_^$Tvc|v!7xA*%@3* zFs*(gMsP%4|N7{I}>|TGbb@CCo>bEmA&16bcaNM;+zuZ&}WJrumXBeEH(^< zzmy&h3wl!+ZaA1!f4jeuTf}=IiC*ta$7%JNbRLB~7H-DU{XB#%TepM^)u4@|jruVA zljm@$!Rz(>wWJ2j{7Os`7SxWzd1h&$7<|uyt#5jHP4lHo$;nGL+(+MyocK>2u!~Di z;-TTH?5brAhin;995p3TEIJ92d2Oejg5uE_4Mv-#P_A%heo5;=QO)pF%(yJjhyf5-dTfCx=U%&HMa)!EY-e-89bAW8Gn}x_n8mb{P7=_|;MrdS6 zNI3MQ7bes8PphJV`)%0Hx9Pc^3Z9?oivXGssSV%-mTKBmN)H$V)V4TV!+&h$YITx_ z3Z90Z_eN#J19fJ~XGk+2-xk;0Cg1sP&+`mO2tn`}f3v&vB91sr@|h|uNC(!a4rzom z#K);dS|2ECNNu-z5p%%Omm`w`#xLbD;KH00w$-`SRN}LHF-D0%w-Ex;3g1D}$e1HR z@hR9F+>4o&wEm5FU$95r7d#+EheUQ%&ejQS>a5#a5%a9|hg#oncl466?-k`N$Wg?? zUvqGIe+Revgl1jjXn_1u>!<6*_%55e@H*5Px#-YPXLES)a{Qt z_{(&}H1Gt@TBQAg7vYEON_4+{o-ew;Sf~WZMkw)mO$RgRX|!oXpzZN(il@iR)4s>& z^A1axIL54z)i%{m^tR=ZzvTob`Pjy54MlJ6zE$J4(np`e`@+WGBDG`fwh7Cvuij=b ze|`U~Eg6FWK8y>$D%r;F7wkp`N6P_qAF3*vB%i4L`VX4qWCYz82}hTr+7F;jRcC*# zwzcv(o-%(P8Ev>*4%U=CBj%#G*>+dHh&b#oejVDxZ01uWX8mR)$?ph1*m%`|c22c-$L$`fXB)stR|sxCGk6^#~23! z-7GofH26nJ6Jw6}#ZMq7a4%+;e~Di<;=8{-060L$zmoY71GdZK%}uC}c%U&}nuYGP z@fULF_E@lAj`OE!*yO(FLw-HJwPjTaH7Xn*uz*83~;)lm$wLgjZS|g#($Hc z7U#z&4s=C80adYiel_y+-TId?z{?YM^!hi>L;wR*`5!6=6*G&!7W{vC?<(~lZW!vA z>vIPt@oR-Gd6>Ep11c<5b+lSgR%OW2GA46{rnACga0x&f$m2ru`0((f2%+zv{`P{y zB)?~iB5(}6AE}=(yj?slCVmFhdwN$ux1PLf4yp_*pRSw*rr7kEpCY<~h5!H&iy z&!akDAJoZ${C~0bjzPMHOSWL`vi+59+qP}nwr$(CZSS&e+qP@(Ij85`nK&IWJ<<2} zuQxK{{gsiqGIKo%1_wjvZnD}G8e5A&WK)iYH-)MMdH@WkA=fwq&D1Oa`f5eVjh1+M z4MQx1%b_%Dq8$1{rcq1olz*+{#x;!5viiEccYuM;W`KI-B`A%yGqrbuf$(G!=83y-n{6m2MO`n!98(UOv!zWi7?m{Y}c#U5)(Si=waK|S6!aP#hO~N zVu$V0_EA@GH68&&EwLExeU8xBwXJeew|9XNnjMf6cf*-$b>7DNTYP?#c4;$fFIx~a z;o%7utcLoYHY06APk)60XUm@no4y(n)KVbJfu54%nTq}bO>ICGM}e`%NMs}<$`OD< z6;~NinW4s5d{`322{2d5QFhb|*)i$>Q=ZmsGokK4jehfZTs~^v&r@+u4&zH;rX}9n zsKcyH(z8xb@)p&8&`U>}VZHJyu4$J^T%NgZe6|%{e?1}B{(nl7RE1!1o?6_>O>>A} zXt1n&@!Dy)nb_FSWNg}1!A z34Kfl$K7#o#DAD>R42#Hadae^Zno27bi|o14?Uv7gB{pMMMrzsS7pyOL%|_@9klQr z6qn{t2#kE{d(8Z+2uzx8s0)NVHSih*)ujQCB8)9T+ zfAy_425$RoL4QI0!hL^@3J-#?_Rtk^fr<|zSZn0YK%%+=9^Milw@C5JG8{^RM+niu zAtm6{DTm;gK&~GrhX9gW0#O7fhX}*LAuE8JLz>~-KyQm(xa)RvS+;!?v{0c}nP2GR zkN@b|NPnG;<_LMm7H`cqv8o9ESLkN6-sKyQ*aP8rlC4KiQYZ!7PP5eOVxxP}c| zNo`a73wwnBk!in*W8N(nQ4E*gkT7R@&t*D$d6)0``}_enz>{|^!H|mEYZ>Yd?yvt! zbP@Uz2uZwq4{X2=|e8I!GPbU!AaqIcdM3r5Kb)(qX`Un%I`MsMav4=(Vel1VrND zhDGW*&x^pbV|e`qiqfl=q(kW3LVr$e zhn;&&U$3S^7z&jRv_h4zcRy$f;v(SlUmuo@VQ`_5k{6SP75=E6cCB8Gj1dIGQd_b` zac8KjLdAx})H|tVTZ_ce#mUoq!B#2iOL`XRT&amRNM6&8TCQ)jYTXiRJLcZ5eGs5p z5aGOeC{yU9{!EE}CF#7an$(RKuYV12(Auq1bf)F9Q#xk<>k~Ed+NDQ?Ew*A07Uw~j zy0>5r#XJcb+UIADgUwzVI&`!+cDh{HMq^h2REMSLj)@>6`7r${1vr5mIC z2k+)~sS581IKVAigwaMlZ_UFt1I{y=fUw^Xs111#0 z1LLgn$Wo1bTCn)nx$=^6IR@7!g6#_MN^;~x& zXf>e>S;$WMkhwUk@(x$v8(3rV`FKBOIAmbHg79@MBA(c>hfh#u#-N1;#&(`Zlz%tq z(iZ8+F9aYUA}Syt$^RLH{(o26%xP_)t?s$kcp}jjZ#&|aBc8h&xg(O6Jnq?Ic}UV~ zBN>ae;Y9MW0y^C4V!J1{s`@N(D1;fz#8#k-xur2wywe4?>MDEL>L{cMakE~4ZF+?l zIxtGn;0ng2v9S&g(s#FAU2XlrCCgQa|F-><`_zkn#;rd0bDS&>(tnTVrjDy3*otd| zV`Tsc=7n;db#5Xkb;x-#S)pXjS7>fBSDPf0mwrdyPQ9NfPYJ=vl_xiARR^zzr?4dT zj~MV%Ki{MfN$r%8y6rCZu0g|5uny;ff9c1BMb6!}5mQh==9CwkJy8{;%2bt`P*#$g z^?cN%bQGFB4d`~Arvl5zV)!S=J#vb(ClVpmXa(LePKNy9d>sAzT{S$#$B#~{*}2M#%%}p7 z1u0UphCPf8oqrn`8r6PR^r2@53XXchX?_H02 zfin5HKCo@{g$Dbjr%UEMgg!K_I<%nsY}`1fh#^~y26a%K)&&XCW+t4G2N?Ha#t*!` zz2X?#$X>=O47cEf!-kMyn9Ie~(#Kyq_9

86aX9E`Ku>AOi_=U(?38BSZ^Ga#hYw zeB67C6|<($=hs{j0?Y7>@Wl+H1S)}8%YX$CsAOR&5(cVnFK=&599Pv8FMam3HmHo2 zAzYle0Y~r|cd2p`c`Zd=kS9;h9N8pDxIzOOw8ycZp}qq2*ljGWKA7Hnvxuz&S{#xL zqkTO>B7Yc9(v!#;^J78Q*rH>R4{MPHBdUc*v*tyf;Fr1rK>V#SNXmmGJd=#^d;Tny zCzpiIfHBC9aSO|oU?4Z+T0;@Zh!kR?L>p>2CxM=_C>tZI#EM<-)p`JFvjMKjehF?9 zj#B`(cA5oIiKCet4)oALY=>}n@4^_@R`_}jpjqPgT#?>Pzsh zf`0?SVJujF z4IdId)YswAfyVY({0D@wAHMA;LwI}!o2-`ICq_7grE+$gC5KFRk#yTPTliifZFMW{ zK;eRiiOV|oZEnfR-pRdpix$d*w=eLcBY%88fduWtVj+@8$Pj*iF(fVq94?Xp_)sdX zp6fkEPWuoTeEbkFSpcMnqP_^00u9OXw2ucDQK>mY7j6c85zg`;%6$ngos&k0G=OSd z#ok9rZ;%NI4_|5bY@Yw zaE1>9|9KRAaG*hgL-dh%bdP?YeojT0PcfI8Mklezi=f{!r0@7{?GY$ggZ%tLw^wd* z60*9q1#&Rn!5-wuuZ9FS$@!d!<$phQa3=vFKFog_FG3ltA40!zFopBySKpvP4|0yH zMdJgeVseIdt(P@we4KHBH?i=sDR?qqVI`;-^27i5ULKX}MRN~WRz_ueC4YM(a+H<9ZVLGHFkfnB zX%4DlIOuKZ4shb0<&O_BIkEGzhbW_1D0AbAj7w;ITax9_cU0>?#5$n~(*du2)T(tS z-HZmzRFfS)SdEvlIIy20^AHcutOmv-SG@U}MJCCO#Tr(|b@{@jE5k4s`qr$Jz?vT> zf^y`it)jdbWPfSXWQ^u!As6H^>>(?uaa?dbWaVTr?A!A?n+o5fRfe*tyi&=ML%qyq zZ(em4fvGn7hsxNhW{b!G8So41Z=dR3JP%`hUxY#mSH;!@+3{bYR{P-6Yu5#fF}@ll z3A4rQqbWH-fTe7?>diMB*r5F@=mdqOrAZk=Y6c!9sDDlpEMHBbNTI(7T3CgNHBp>d z;>pCE+FCe_)w9#3MvJhb4Xf<{R}p)X6CI*z6Bc`T-5K*Cc=XlnxQd+F%8fXIK&4V+ zEPZ#^n7K)(NrCgxdAPDACpQMt69%YjSZ9l|*4zpSql?083SSb}ls?wSQp*bpU8~%w zJ9b($Fnh7_sF|-$ar~7*FUHo(1Gw*YO+5Q$v2+afy-+hA zhBmc<{?G??*+;t}ul86B=T?A5%%5DLaaTxBtg1k)@`UbkU!;ugPsxU*;y^q(ua=Ih z{17%Tn}RVhFPHh^WIXL{d4YE4GtzZGOgHtwZhtSNS6(`f)+1+rmcym+ZMVYJ?g1!o zg{f?X(QL))-g&Tg0ru-)+zw~<=K~r6{P_b&95ZaBX5r*m-8s90RYalZcGyYz2KY9p z7h@adt7X@XK;#=qj z-^e`|Oe9qY4@{bPA!;7uCS|N)nX3%wJX9GqhCAbR&=2=fh0IWgw^Yn1U#1zA-~$)K z#iq#qLJSs5h-r)!Me;RV8(SB@4tADoWgbs+N`PIa12T17HD;!VFc#U$KZ5?zX zqSbMN>tr45o#~U^k#6bE?o%Xp*@A_$3F-AhT)T$4dgQ)H-$j$!pNM+Ch`yyd=lHCX zHY^ofnr>1|4`tIcZzs8KioMiW0iwHR7XxREynPl#dnO6?Og!tuZUv4J-{$+6xqsi1 z+qOfFD3Nh)0tekJ2jS7M?dgm*sIYp&T2G`VuciabwMdK^c1#&|MtI9{RLP@wAYpYu zSl&IEYEUvSU0@w=$UgTs2m!czbo6k{*%!d{F?OXxAb~cfsk5iTc0j z(|GxP(20LkF@o*}Kz;CapRuO<5%xj#=ADtNQD5=)~sEZ2!E}p#n4;E z?p!hf;O_BD2ghU)D1_S=EP`6wkWO6MtcYQJs-~c=Tx*#E*pMx=8+O39BnsWlL!g%g z3gOLDpqC^H=}V@-wv?fBbdD@Ps9B6$Y|P-@nt*pr));2&?Fp-WyBhj8W^SHo90w$j zXjMyr+`Ey+8;=?PGs^;qj>K09NtS32Yie_1)&I?(r(weR#p_y^L>yDv&i+lXvc(Rd4=5 zs}M!|nt%Oj{KO4ty(VyJ@LP}K@!lY~Hs$L`1(R95WUpD71K$TDwC2C{`Ng_H%hJf1 zokfxBGhILB+m45Zmw)nfHwVSjOHT>D0EXhwB@jj?&u5jkKLJYeOf zAp&JADBZNziM*jnQe7kP>Xv(rgtj=*r^>E_pY-GIJ}3GfkAG|m`okXR*8=L2DZoz| z=p|)tz?>@iDi?F(K7i(iaBY0Y2DNAoxi}U!KTRTmAzKU8Bz;$ja|JKiNUmw9C4Bn@m55#Un-At|GugE&_$zMOI(C|& z|19!X2I=dl>AHTyFrQuIP9y9WnDjNfrja|{klzCG*MCgfy7oVQTS4Zw%Y?{p8V^pV zdD^EgQPu=MXR;oPyC<1?sUMTR zB$#?z;(r&0S3BPWdOPrdK9Jw{z#2Pqth>#<$q#V@|SUT8Otd1>gDTe-j469oxK0g z&saWCoe^;qS__qh@%Tk}aO^cc^nT_>8Ywa`dxQPf;$ z6@P$k1S2f;xHzC##)+9UkW_EN0VW>KD-%lp7E>ElGEv!}IPzMs<)Z1p^GG#Hbg%XL z(1S@kd%*+LF-L8__z*6~P{XIzCJp#UfTEm=WkNS>*QmG#v#eQ`z+OjCe_YeJgvgzZ z6G=egDQ-;snZoNKt>QtG%0g)E#YAr2L4R*#%OkvStEPjl-IuA&XQ~l1><{TImy6_u zHx(UZO&u`(*QhiJ<5ORhA1866Q_poq+HaHrhswmv`>+d%q$0(W^gW`dOy8LfuZgYoR8St1asXR_6ADP zl99LY5RD9Tc3#95-sD~S&}5wxbD5yD1sZoLT&b$8iMBA>&ox`neiSO6D46>YbjMV~ zSGEm{9WGN1M-%YIAl*6z!#X5Gw10tWzszzPKQp3uV@qYQ&+m3E=F2G#kW!wh_%NZ( zo>OCc+SX-yG+lf)!Cj&_gIz;DQrI|6r`fEWA{XKnHn02)!{k!)a=C=|*<$*rX`~#g zmu6ott$z8rI78v`nAu={VG)IfXpBx-y;P1$=2G727!F*Jry@A8t?R;MihsfV8t&mC zQW+O5Kg{AWj-++(b3_~}>Vdt)-8!xNzTag^cfv>x(qz7s0PjSJP!~~G)vM=eun`ESvN7Cc&D>ws=)kAcmp7`2iX0UA#@9YU5 zhoR^`U(G9ar$vkA9m?+JaDTUWzAao3y>W-V7J?a0SnZ9b*0MoYA2EJr7qTB9;tgMr zoFi>9#N^c|d{>uj7h_)sDS05hJ*1v|Ce-v1)(S2eR}>Scc47+uYOzZ-LbtbmM!)7M zXcc5bVX-5uvw?K1~)!H=e7FqFE4c={y-6aD6?_$Q^3+e~zxMra(^jra^jzCla~ zR^#%*tP%EUprY92lGbhxd5Ih6|97m5I$F(R{fBG_4Fn|hKZJGv0ykA#d2De+KQ!3U z*-a=Y4p0efrN#Br6Qjiz!UXjDgJH_yWek*a7~U_mj^XXXZhvP5KY`!RYb~lWRcehx4_4TV^;GV-0^)H0}Bdw{AVGmPdytbuP z_adF-6Mm~P)&4^qHtSJ@A%q|#7{W;xz+97(t2?u`;hdXvq-`p{g_3udf~#&(X5EWK zI)svU+Aa3c>VLp{Q^{NB5u`?Smj7V^P(jchMl` zsEP%HQFMeIen!$&rV4^HEJaI`HY!TF?YmuxmtrN~!G9+TyJXjC+jof7Sz9}=K#EBh zuXExdb6JeJ^LtZAZ*SU^i5dnBs%PY(6PT+E`sOCf^phJI^-O|7L2izg7WMHe+gh{t zo+gAb27+;b5h`{)FVZG)bJDTgC9Ho`h;OVQmsT>oBa=ZX1NxAz9K0+~HeXmBky%|K ziDJdMEq_y2E0wSB_+5&NKy{-+gLLg4tTHIW48yv(&TxAyrpKV!CHt_ejy%e6@`5;S zY|$tEkp_3xahiCh-?G>4x;{ZY_#aLPAPNPGixF{Af0Kz4wc|Y+Kja(=wOv?r)8biB zJDPw*=S;f~Djcg$GijiNZ7|IRaGjwAvw+++le4i%Y3qp$2FIlzcj3UQ~S<5oE?IM8<5*?@oJP8pBq zNOLeR_x*|d==%JPSUMJbnPi_U@j~0{8pfzoSjz$@xweVYr#Qi3mnl&`yV*EH*^ju5 z6n|#9v6Uij`E+~@SI?o^l-p>c6fQ^3NV&(|<)FERX4hrpA(F%7mV+gB-sToS7;opr zdT~;0ACB`OrDr=%Na}s!qRLcgf^g8KP;f_8>nB8>3wles7fd>~OQ<0%GAYgaEV-dS z6p*rJg^~8?1xKtDx9aeveo`i}mu;ff1%Ii4h~xWwHO63sF#=!ymk*7{0fom2_y%Fa-k$*H zxW`T+Z*13U2qb%LT$H-z6Ov+=jU$HWP)2`C@<06J#e(G<55ZJeTODXzeNb!yUw>6a zhA5JB$s-q;Q{bP>g4~)$P^KLu!5%cO#L6uxmIUEJLEPaRKrS9uEX67Muovo69Y=+1 zsYVinUny&X$0Tc44@Ib3c3JXlqRU6Rfc}oFFHILqE7|mi-91J*1{vO~_q>+K4}l`L zxg$87)<;Q}Z?tmdnp-oGyj-Ojgn#sfc8CO%Oc$XM4e|%%-@!>#t#q>#3Q7Hgq;a zNwD46Ly3x3Auc(Ji;vDZ_{7E@So<;xUBJzjABgu}<{Ww6%(87PH_O0Wzki#~a=c&N zXE&VZINxq(e%Jj4HbB^|352NbsZdaeqzXgHN`%)w(p-|jXsgpaplP=eW|qN|%lZVB zuRv=bY^$^~@30K@?kqENx;W_BKAtz`8O6U5?NP3T^^WIs6UZOHoyKgv}n6C&d@T77Uvg( zZE2UyB`OcJi;|=>1$K2>y%}m19Mm0BCHEQmlu~%{S~3rc zYBRV4%L*kmT)@X>$Bd&vQl-RsBR?rYZW{1Lu}%c51{2KaH;ESgMt`+Vh2~o>Lu@R~ zZuG$iCcD_Fljr;42gZ$Pq7c><5APB?+RYXI1%WwuazZuBy2U`L%@;C%I06E#)tGGf zV(BUbSH3*0(ZTPSrDs&ZRbuY)1vyk@;Jh8p7UoO+<$%B0xE0L{{c40SJOw<$SeG^7 zOvShZzf^5D@qtmUQGYa`!PrmunKG?mGC-AWPBBUD5-Z-r(cfT9si1PjN+HS@@=zcl z7jntaQ9=y?h-4cBdu#|I_K0AcICN8Cr_66EKuEQdb|*w8{Ft@b@V+Ki+}bQMtv@dAFy_u87HCD zq*bH`KR32Fe}12j7ex9(91?KI#BD!EjgG*5+-C%H36k1^wa_!qYPmmsX3*Xl%#0(Nz;{u%WI!KQ40NAa52$xEMq?xR}>BcgN)r z5SPZsO3QDtOSV)%fhYaZp0Y7SO}`3&7ax-tsIY#<)p>wtsG$YlZ|X2(gI?1TCPZz& zGHrjgkzY!zvBGMvDQjcn`b)QSAlNe9W_q7vPaW1G9e?8Tu?J(h&@IbY^U9_k)4el@ z*WREGiT*b^gzIg@h~{fM@WvemVtY`KFy}A15Zzgo3`#-AgRT1?l@jS7`|GNVU^QULZ&=N>P4I$WzNL zK1l}r$Zc|I{V=lxpDGj>VQmSsBjQ;?spt*W?KSXo1P3pzqjg2u24-1v99vXxZ;CCl zf%}NouGQ|yY|aF37PW2G?nrFL{vxfv!Fc%kVSnaei+yn}3FB1y!Kq|B&KEi?LvX~vKllf(;PVys z_=J)0i9_ofAnO}J>myxS`$XB_^Y)Fn`h@F8c1PmhL--9ZnS21>;Fu!K8K5R?H!Dz% z1%F8^?D8g|aBCBC#`360#i6K^b}A2hlCq2Gv>uNZF2O_HvN-ZhJ_@l< zeES)(t4Y?gvd{Aid4HbIg`%oRjsP(0lKd(0Z!e2Y2yQSSQ25s}>W#jR4y(WNLp6bWYIzz|k+(JQ)_>`sc6IPL)RB7{dG0}HQ-SK~5q$bcItqF2 zO(Y$BJ@;Wq2U<@8^M^)|4eUMl&m1d(UQzq6%S#7J`~~^+howc>6}>&q*X*LK{+jkg zP2v8+>Z&)csyem*_n1(Ol1jSu&o$JjKtMwOhcV&*4gw?UAMPk?fIr|iFcb1jW`9sl zYQhq|4dWQbh}ypoK4K8@X=q>mYB+N+kM7~UL?C{x_K^p6Gar3hO7o?HHr2_MA%&6BW?X2%u!(8p*$Y(unD?*MVPTL0_DFpnq;7h8Ud z&&$QY=fJ~SASf*jv;|-@QU=`N2E8r)yaLI-(rm3gXElL z*>NTY7B!X&t=o$C_WB%=M}G^gEh;~}#%yP5&a=_0OQ_iGZSMI7AF8*}YZXN`OtG<5 z-capkukU$h7s}fQ(bP`lQ9sCcU2nHb+Ry*$FZs;4#hQ6)bR`(-euS7ja+bm3+-B%` zmigo=iTpQ?qQvUwiawaJz(ECd_|$gok*1r$3J_&i?*K~$yW(_B=YNc&jN!>V27ka& z=TMYpET4JA7wULm!59^1jMmc_pr}EHdOK#4N=n&~?@eytUs7=<@dTw`MqhQV**PpA zm+w9^9g@oKJHA(Z4}`ZoZ==R3HeZTWJ9$w@ z4ldGRL17|Ljg7m+>VGMK&9$VPOlZPtQ%P)3lo3XnK1XApHS5Af>n;QTfd~!Vma-dX z8dOC1&pzYv4kR96a!~aFlwUvWY8)&zhDi8S7|dnTDzjOgIhmGREnPb0Be%}bXAgdZ zN%W^Y)_me=;k(d(*zvPme9Ki+_{#1(JXWNRz-4)j0Zm8WD}OL9-n4ub_k=zf=y8VK zCkZ8{AH~q}pHp?Jh=lmc9$5HiI&&s0&&%d5A{JP4R6OBl7d_fJ$k!Ra=2pqe>t+yE zqX%o(SHGbB$%ynt7RHoxYoPR&pI0p7r}i+_sD&dF#oXn(;1;rrYO!_3qGBC zY4*hsU)=-jce1G%>+_&Wz52zIyhdnY$h}pElD?uuHr}O)W<|Ho&PBhSYolrI8bVWP z;SDAu!1U3`cgls#xpL4{7E(5l>}4G3lR@J^c4LM&#D88I=9dS8_gc$kG5ZSR>l8Tz zLOfhfCXR$`4#rwS1+z)b5A%uExbWGY_z8AlB}e`OFT7Ez9Fy%SPcD#}cAo*MS8FZI zX`|GYTPo?$`6bv8PCGBO>A~{s1Ald&n8+aJhN>ENwx&|X$HO)hmd<_V;90eCr=gNG zHX7IOZGR%bGFRUw#VC6dl}OrX`m3{bdfr`eo3TXfq1HF0pJf|C+BS(xml)!=W3$3B&^ zxH`SmCEccNDGsqK+>$y+>S_-0E1W=vhvd}}(mL-Yg@wVTHIzA@K$e5z)g8=K_towj z+v}xK>9@7$zwsH^31r(A1>O8OUys0D4$ex6?Gu~? zXiw@G?|fc5-Ab$=FF}tnqDxsq5^-_&{1=qDY+Wbv%dJ8s< zkmQyOpZuCYhRu1NE?7aln{mT*Sa{8adSkMlZ+1i|T=w9=wy`}>A1l_76f-(xV%wZd z8yHGr-ZZg_73}M9IP+l96Z+mVtbHTOLlvMmxDL#hpo6X79YKCL<1ECF96xKCe1A11 zy2k_|V6;9K;(H>f>3K{=q%rRzh66M!Z zvfZR|jAcS0pQ(vmy!qv*?<4euuw&dgW$KPN{UHze`=72@h&7`fae@E=HG%^H@%*<_ zhyOKa^RG)5D!R%jlBm46z<-2}LJSl&!>k1X69mJ$zuDhaBU309DGKft!zI&WWEO4a z0zOZd`fm2teYc&Y-K^gP_kI-9%FTrej!8vJ7k$0GZaLp_`gryG{``gNcje&;1^rZ# z&^jLr=r>hwrTTr##doGAS}hCclA4-KE6%pZ0e5|?gib{p?@Kb2ZGRQ6_0f0oEmqOH zWc*;LwK|8OElG?-Qcr=;ziDHGGt#fz9`6@o3nhf%goT-Y8K1Yfd5_^KKc#=!~!4p>^-$=P!Sz*7~tZ`+myO*<>K zn3nHA!&b3d$*t+t@PBIiEO@GU(GXoheu6`tG0-uda|voV`{rW9HaP4L#B~rQ*m-Gp z=9O)4Y04M_Cs66MIzlL;E)^HE#JP`Eeh{fzJ9<9953F?e*UPbK}PS zXe04=!eiG>hp2*GZ>}ZTte7_sHBYzicJPm;uBcqTjWIJ>TdQ?D&oRTU0|}q%b9uwP zux{FxS=mT!rGF3n?$GJchWl=$21&Gs568;l)pOG$6bD&+S(?W<--26et>W2lgxr%j=ms}yH}Z^bl& zMz)87ArcFCY-LLMwv}Dz6sb4r4^?Ur$>XZ zjou5Z&JVkj8OlF`n;>{HLpRhgYtNz3*O!)@$k-L-5B)u6P_{Yel#4|1J5z(DC~k~#Je5Xa2-YUh zngKf`{!uZ!7n%zddHEBKZKO6uHGgj@F?M)$T*--M{9ZWjUNk`ja>eQRRq=z^s;Hq5 zZT_z1JQ@jtIf60#vy&LZ38246Sc(%GMUp7|NJw)$Wp+p-40{G`aT6UFyGFepH=9GW zeI+J50LI6wEdI0yHZ4Dnwi24|d5`X~n^o)@mQTe`W2!t*(D#!~56@=3ntz{rAX}6+ zt-NAkx2a`q|m1$hSRezTw|sh+1V;vk z?408}(8WIvlmCvqrV6W%)X=rZj%`OD-Ht%@b+itwdSmidMp0)Dz~Qh)m5qM7>8&&$HYai;tsgw!H`4w3xpCo}&9Ot3>n z`Sny>sSfJe%T*9p- z46y8{jZI)#q;jUD%zqq`{=Q<0bZ81#LOF2oz>|W~POH^QtIbNQ#jPN8(n+kX?s4m2QpDEmlzrt;V> z@4%DP8g$fHgRX;xg$0^UNJqdSrla7H&TwKei%bq9M@}cwWtl`Jju5U${0dED;1NXR zar?SBa22}W$Dl;#ufo>UnT;yL4SgumSwqJbz5p?B*VXR|-|;IwQ5*OR=U(^v-c#!UjoI*D}{?ilR!muz>eR=IXri+?!wv;X(M zgT7D*9B&H*5Ks;Z5RmNu9O(bQY!0?M;15|`t%P5iF@LvYYHEw?6{)NVx17}&p{((U zw9(pt8g4erlm|;9SsLr*GzGSHp#V&2ON&kEwSt=jbgHoyMM_f+$nSx_LkHgWqe(fS zaVyIBK5=KW-u8Xodq20`Z@ND}d-i>B1?c{<2Dny28uSX$TyWU*7wIn^YICJWD9-6J zLrV(o>wlA)yGU@XH@HhkHUb;`;c`0yQd3?zuK zVuOwtz{`OPLSi6e4n;5*>51>3vBdW$f`9T#bt0%=q^t*;n;woddGE3+OIi)6UdKR3 zA2PzcntKWiU${zw%R%`_p8EQ7-l9?{150GS;WT$%j@OXn0#jrqPW{W#{F+;(taNpneyF ztcUhN*)x)@n`C-ou;=n*PH&14QZrYeQ<;)^Ve|ppLwcv{8-qT=>Vl2ct6f+j6Nf?^ zL}0#(|3NwD*%9z)YY%}vUQO40Mc(n2$HTDZ-4oT#-S=lxm7EPQ%mJby)Z|1yEpxbNyW za*w>4s}pC|ROT#!y~}9mZhZ;vTT?+zaM+#jpY#1W_+1UzrXTgBpXMY4@JB+@wTVCS z6T*Q!SmQ8(I7&^LZd6t|Dxa5@fXN2SR~A~JpTQ~%*JL6-YYkgLYz zy4yjruBPDI_Cvm|l}R}MfFT!_K(?4hbNM0^c>@GLnPoKp;&&*&s=DXqcT7Jyb{01= z*Ff%G7xChns~Eb&ho+r~!Q0{^$5QEceXy>QuuOp=7)WIZhJWo3G&A$!g>%}R#5%RO zPqmo18jM^RF9t5Hzd~B4G{yv+R|Zd=`lZ5Bgce)#TO-S%F_`w6Gic5 zk9nkkQ?H|vvVYmrTrJqmfAZ#hp|4!)3=cw@lAl0Ls!jgcY}2syLc!_gUq*s)Y%}EB z!9Oi2B)j^E2|cZMFpS>WL$nDqV%pi$Xk;G|r@^U?XH5tj)hO--l@F73bZ-4kx!MvE zKRo!P3)Lu$v_)R?wzR)4Anp8oXB-yR{Ke!)@rXca;G z!w`u#pfoX#djk&C|-xe34|s zWdBf`xPMySFx*addqCkg)sA*+LeI)(%v{?Ox(60cPzMjDK;7G?>C`SKYeq$+uO0P$ zcL#mjhnv$&{eIIOG`9mky9byyqX9wyH+QEV@QwCR8(l`{fu5r~fMK^&K3ApK)>3+h z;6bP885gN4-KN#m9F``wwSD3l)^C)5M_K-OiGL&Y>F!ymm|U!m*V9vQVq!a8ent=Z`=4I@vD{TUd;TFQ{{T!tv%mV^X-WF8 zD!^R%DfnN4h&8Y4ro4y5I2{=<5RSqm$dMrY4BT6Wn%vo$y7*`NAU-J>BO|K#T~*!H z%9UeJZV-PAVq@Z=4Jw~R*Nn_u%bqngy5KbA*_`KPlK7N!g`GnBxjAWt>{f?v8MV^w3P(+FDH_p3buJ6MKtw@Z?~30lQ^g;YPioTqTtoC53Gv` zm{ouM#-(cFhMsKzX`eUsBTnGkn6=!@$lA+^7enubO?Q_Sw$r7a+k}z>ee{R(;CpOi zc9oPfc=#ef+oxQpkN9mAg@KU)%Y$=;snmbRIIz$#=Qu6X={(RFW4`zA$}|GrUBUqe z0zyFj-&snf;%@)np&*p8|JiSX3K?>ucn$K|u(`+vC8T6wXDnwo+0l?jrmm0%t1)M=i;E z!3am{B*mJPw~y)TBBW{@Sb?W5d!)lKWYIP{L`jRL3Kuq+k;D?LrDJNqq^|jYvG$fh znFUL>D2=XCJ2Wo0&%84)=A4N8=FW}xV@K?) z*ncXcYGr2aRk>&iVG+ZvIm+ZImo3AO&-Txh%2To9oD!HtPZTqCrxtU!&h}Z!VK^$x zDq>3D#S}6^yj9sa1p4RJ+uHH=E15OOxS$JKCq*@TLYMV5FH0y&jO0p^ySRVP31MvR zbS`sR6bHO#Dp9;8mofG>it+8sL;v0 zB@3f|eO1(73Bo)9=rWN>xHJHa>+o+^JC=p_Sz@q1r%_v7esY9!3L4Kea9fmvQ?>PS z5<|Uqg@_e4sQkjeIHYe2#q57SgMp7D#7!Or6%ZKQ5`og4H;<4C#_Ga8Q=(OirYa*J z5eT}G;V@xU$Dc#ZdST|dc8vqh_s@0kZx8@O6!{)yfe|0@3~~?+t62|pDJ8!86ndr> zMk{^Bvf)GR4)dFnXyjFDy5fJHz;dj#0Rcwg``*pi9;dFo`|q*>@N6k1{=6et>!L>Jp{ZqYVZv`nogqf37Qd!Wi4yL73c2+K77 z@GVDr?TUv_KyXKjdx7fo{+Y%4mGg~)k$*Bq;A4O2i>#@Tv5Bu-=F-SL_LPc@{1{qK zp(bL2LpYAYm^QOTu2kz;Ha7_1YzPz5rrt!YS-M)SQCy-ICB9_ZxOV=h_Ip(lj;%$H zj$Kzbk2oJyZFPU@*`c9Z+VYw&@!3EC!Akd&NW4TQI>CyXr1<5$C*5{)WGCnL=1KaY61jSDOdh={8AoB5 zB=DATaNF#Woo~B%TOT#!)duk$S4_{!F3fip)m`5L*i?UwDaM41XK;rzkT};z^z9+g zcIO(LW#LUccB3X~o5y7H`|W8i`3T2K`#P>ob&_F-2|d=^xl96<%4;P^m#}`6ro|SU zXWy1~didm)cG3vq6aBgvgM!8)@B@m_b!JBxcVm;Qq2{MIZi4pag#H!gp1qZ`qrIHi zkDW0qTi1WpviY%~#gkpWXJ)v7iq=+lNT~(wu0U&T;bn$`$|zju>F>-4UD@Jm<+q-= z7Z$9)!!1tu#7RJEi{P(QCRfLnk>(@M(c2T|!C&(3Jz%s)`nyiykLNj>~T~p{8Yr;1-fOmND>&$1LR@)*G-#g;4YZncv=cSHEM5_?KH?Hu3u=B=grcyRh4zKe?7r0?}H z?UjP=#0>{Ap+9sqaOWG1&_S@*F(}?wLG&a19mND+#enj!A#U&FzByN~e);a>w8I4} znT>&BxA%*t*J0NVw@tNwqasbeY`_aj%kh8DceEBl93o_bGEL`>qO*VNNt@jCZT=ta zQ|~Z9K;-`aib?+&gkl2FwJ<&*|JD{RO;#W*-!-fY$HQCkKp{XG>gY*=_?ck}iJ?=r zj6KFKW?0$eglk%9KbtjcmRBt7{8lWiY`98lR;13Wbbr_V8p;2inR{Um!Vx1ro*;kV zan*C&b2mFNNyO9(|DElVa2S;yp;&|@R1$$JcYgL1MsC&ul`O>~HnqI))}GD5 zn~#J3GEzyr0X~Vj2v$KEcSOydan~F!Uck!7d_n;oezi%h6+pfa?=_RLWH6}U8K0NM ziqFL&Xh$@T8_tp3>JomekIjTs4R?RAU1U{?ASI@*R0_Xpu)4flx@$SQV^ZBnmKRGL zp3ZEqYB}tT@Mb^8ifiIWRxI@xOQ{t9@F(sPZ?%A8*p3ckn^-WLtgWF+4&Jj^G`pG* zPbMDz5|2p0`)*9wx!Z_+g}NJtON*m(m;i|>o$o9(H)Ml^e7opIvwC^%A|rpZnv1K% zc;inn>_;2TrmkFo+M4k>hJ8wl2@Tmb&P-0Ur7QK&yv{O^9~ zZHHUW4j2YL_P$7TSi|eAQ6GO3FLAeIenV|wxbN7HBhP0r)AN~mPbKo5iJ}(qVYn}& zZs|Tw5QgEpj-DV1YXhi@sk!;EfgrutrPQ5dYMSJiV(F6!*dM|Fe%XJAjbIVkh&>Ao z4+B8|^1+CgWz~F!_;XGGJ4%7~L#Ok6{DPYA_fJREa`sUCK@QJwc31L!G-G*dpt4kZ z@mx}RNYn_YJ9)~Gr6}YYvwRp^#)9KHXlrsf2hJc~T0`;c1IePCnUvk+ddjSJc-5}3 zl<%B7Yt&-dzPI@{Lq>lykJGx`av#pIj^$lv+SvK=R4gNjl75_o)^Q@zpeFTBb+}J0 z)Jg>J6quHnr>m0l_t~3_aD!DdV~FTmm)$TGb?yi&1V65DrV!E5Mx(*)_^*Wl?hwCk z*RcCru-E;5xa(LM*{&%zB^SQyf0(F4y@;-m_P>Qa!A+(A&4hp1>8VP=?76prLhy^DUlIV2vbn2l!_kL>xSJ4?X z_M+kqkKWue3l`om3yvpi_KYB$8m8CEtl4|vQJS5VqYEQQKLM1jM0A^$dufumxCU_8bnl$R9-tidiEzFo{5G(h{~$)O7X_r=DxDE0T9G& z20?T}_iT-Ar1s3)+c4+6V#7-l^Ak5objX#a^J|yTqb3c@!+W!?^|$(SdP!SRp_q3# zUsJ{-+^YwAFC7>i&)j6nEDKzCxtOZtm4_upd7I5fPz)33)w zYK4Xy@+o*U!)JK`+B34*bDaEC@tb|;%E~ESM^mp0n))ZRrVc;2M)C;g^|vvU`lE&m zCjex6jK6<3(>^ImeKXiG;jFd*0GUoLf6v0jnR_9)c1asjtHHa6yCrRR!;j;g7Zk}H z2h{Yru`p}B_~h*uEJ=i@FwMMzz*{RpkC>l^d8KqTm>N!6Q@;!N&(u^son5js(JA)L z@+C$uNTuH7qYkFO2An)5WCntn6KC-hnXWx+@!x+NUap21=uzYfc3BS?rdQc#`!&5* zUz3%@jJ7eQ1;eR1yoQw-lOlqco*)~A5(j(r89lVV-r9wPWT%l0cdldJy$R%aK(TXw z6uQ}GNVJEVC(+4jQ#iZ9IAD6o!JLb?{-_r*Eef?y@<^K_yURm$kGWtdR5}ob2_cn| z#YTVgDhUP5zM6Lr{k|lJN3|iQka(p#{2A@`u9vVO5DJpYJ!Z%thg{L!xsnc zFFdVbR(vbgePM(P{|+rgNfGySG!nROuDVE##|L2JRx#i^J9l4%$@Zn!$iw&!Gw>5+ zmqk4C8@xv^_=hDuW>;+LT+PS2z;zYVv-N+|FGxPV{LyeMN8Le}dh?y;rlv0Iaok#1 z+d`(+=buNt<3#;69&5lbnIzo zRv1HqPF*KagEYPe>8+YXUXTfzFW2I50X~N)lT&Aa#|w*tx6>rBhdYtY$qU-KIxI(M zq}y+=;3GHaO_!)`Q*_+BZx`%6(!YPe1@%UHwLYk;k1z5YT2d<#_Kt1CB0r%0`!zG@ z^oN+%q8)Rs-lJuEosuNy9xf}dN>h6FG>2rLT}Ik{YD|G9kJ2@Vh8#EnwX@> z0d?vA+DNbjFl`9@lZ7U*dP$NsXMQ{Tc=Z zb`Oy%MYRok$>Hs}to59S5)Z;j=y#oeyI!CQnSPg$xn5-kIyRCClf!mrJE%&SN(`Rxnu z08k&~AXs$@F@9x54*#a~3}LUX;N!8Fw9$mnk350iWQMbo9>0MNm>aLQ>{Jg}7Z?H(OX)%qdhs*mJpKwGTXSx#kTkzXK(WHjwBh+Md~@zqC0=TZjLql31{%rt;mUo zk!LM|X<^Vm&U7K(lq#BdQt0R(zIU1RY$M%VOd9nI2bWMjKOeBs_HUBkVCjy5!Yy;_ zj=*8%T``Gz(@?cih^EM)!EBPSdQ%?FVTWIl*Bj&?T#^u9Q{C4;axNNAr#TO%^-Mk* zwk~cZ+f-2e4KIK86%BB#nley}*GnP!W$g`r{flHfTZmxYINwRqcz&WG>xhwo5;buH z9W3p3;MG|A!&8&_{!5HWU2I{@`BkQ*61|k0qp{^8yH?p1*md(o?ROoC3D_{a4DLI%{n3WY4q^cya zYze8nB-Z}S4@lJ9dQ6Q2iqY}5^}dS`4L`ttJUrun?Um74RS}1Z4o^H>tqGG#suqlrPg%ZYGT2I$E=j(Glnld9_}tFZ zp-CfkDZ-B}hO?5AApNxsKW}TxsjxJIM~<@EP$PgQ?-+UrRkJ6Nm3-0+p>pyf`8iIt ziDrLkHd&hLvwNov^-ou-pW9WmTM+AgxPJybCC^E~7X+F=jw_+hfyykwKyjRWCWL)B z->ABuAK~lQ>EZt_F>z>ikEIL>0)h?kKZl|JM?_D-!PL$6pW^SiDS8g5B7b3MP~*gz zW?0t-_ng4;Qnz~u9bg@;AYZ}R|J_<?&8bZtUn0DEJyDk5(0h@FmmKa59p$`;3{J8ZbL!|3CrYy0RAVYvq+88cBJN_Eca}n0_JK{!;Pmm6gb3lI| zQt09nw^%b-$qi24GNVN^!*3j2_BFKL11gR-pQ&81LoF378N4xKxr)F(6GU}`7c2Fd zKGZvSnmAtcAUcD2GtY{o{I_(eR)F=5#CBEfVbn^teH{~>4E???J{@E&Ak7#6X%uc6 zGZ}tUvb@*1vJAApOZhbE3Sm+1V=~G=yufu=6pB9Fx z6Ke;Az3OM`^Dc<%NwR_r9|ILzO&!Oh^v6q=?_<<#;mS-$-sj++)^J|InBD`*8ga*Xn%_jDh^RPo>7l%(;$ zHLw!*=Y&#aRVLEX9NNR<2a1s-d)G5eK0ZBtf&h(GNXTsCx?C*1ubY4Is$n+euydRY zpU*C-bs=Eht;IY0evo504>W2N?}!c2@3Xw<21tR@9ad)ysgZf#oYex z!+&b!s4F<&X`l-*u@Qf6>^BgMx}7yAa+WR;^*im&p|_O^19XEI0#hec!Aa#u#8~45 z0C7~M^|h%Gs2j4jiO8rX%fv}YL8(N24!ch`k&t-ZGDz>lI! zNz!D^CBRA(bynY0gB9^S!7$QKbk#twNY& zyCZW-lX8R~GB6wAw^o%>w$OVs$jUPD)%G+luGN1;9EE?Q^R!;5*eyN~SUu%h*B?6i zTmM~x-yz4D_BI5v_x9p#Uff61MWu9oE6_ig@&7;`kD*i`)(9*J@U(|^eTLEW#IKbd z!t3gIU||}b>L>KJc2cCXjRmC^Yxnjb}3=uE%+`u!&U~YN7*)k0NimprzN!o zU!!I0TN7m(4K%ks<6FQ&*O1QSD~^Hp z!!Hf?AcJr@!9i;^GAqHh4VpAg(N99_yu;UGdaIGdJE6{xqIlw^`9J!ts6Wr7FaEr% z8$+)qJBW9@4JeR=qBc{aF>{J=r6~2du_tPtz|Ma}Ns64E?K6eKmQcjG#mym)v4{+h z@X?kQcthkRDU!9TODs!Dhy0Rh(b#w+NU{03M8a5Ca$eb4aLC?q560@nQGRK^x?G<1 ze0nXk=*CbtLC|S35uCTEG_Z2V(lK^gV^GKVV?M`_ug``H4K1oWYxS!O+iZ=?c zs@H!dMQw}a?ENe#%u{#h`p2cnIxTAGn|aOxBTO~uJ~dYg70c3Kh{B&o zwtdQB0v%9$GgRh?q}4E_v`P!BErnv2dJDezoTu=L!{({@C3rLdcuT#kM72WO@a; zqNhYZ!|m(SI^XI5OKd(6XP+V%4bvF}h3&58f7Btl^7yYGA`MiO{=4c$z#=C|z+Y&1 zfCK?y`9FmQF)L@lf5zn&4LJuiE%Zl~k}%yX=|FF(ldgmN` zg(Jv#6wy9Ho@3mVG%mIzY4SHEOLz)xqg5;!mE)crWtDmTF#me(;+gFtuMyqSo)L++ zx;%V|!9DMvGJ>yL;$X9kCTEvp@KoO#Ogm%NIJkD{N`9zqrV(TU+(t%~B1PdlO zYV|vV%i`tS(=n2M7yv6Su2Clw4LNm)@wbn&SvuVw4OU%z2AQ~I|1gJk;;xm24Cl`^XK%B7P>Tbbs$|M!J6@pXQy!s zXiA=@3;X zCSjwzSYZ`UwOTExjSEh23?um?#$XF~l%}o{y=x??G97A8+zUiOrWt=I#bL0l_UjYU z4Zob|k7vaXx6-WBh)auojV5nRr4yX;LaORBppobLhU`fR!SreQLYHEcby*upIrm9P zsG{si^QYm_lh@HhDm<{>b$Q;UbHTCV2->s+Q?;^Wb9Bs3pg2KbB-3Us%Jvp!1`9V~ z0FWxRJ}|n=!g!mmyWfA}5)rX_FzrQzOK5`b(|zZ^>-71JAixCljXUo6!7GZ*Gpvcb zj|YFRTN$~$o`=G}v) zbo4FyWT+jqML#Lx#D8f&-_+Upe&7|GYl4VgEPW8;tIcKeIOEaw~387N(}ZqDI=RL&}RGf z+p@at@(B!RgxUeMA3_c;BB>UW$QM3~zwJ=5#=UG=fU1A;pkKr~$!^_f6(TD*fQwNP zM_xu=M2TQzw&JZx)-v+Q)fjD4sB5ILxDYUnoQq#t&*9;OMh>yy<_pQo!dZPL{cEY1YLZKnq+FMZLi%QnM0CL#hzn{Y!)ur{`LSaI;rtO zQ4GKyg4|g5OnkzdGto2^b{0FIt2l<4xcLFjzhNU0HR_tqdch)$xu|&oI2foj?;Ix ztCfGOyASa`!?B=y$a(0s;9|hD-K;U6X4mY_KjME@Di0Z@JHR22@fR%_acdbq?3piC z?L@mdp1ye5DCU%K%>momNXQ&CO=r4!5-&yW8?H6!%a42<$p#gac9_4AZ)#Nm+20m* zzM|h&2=tCdHt6zk%B~ZwQu6$Oa&21Fm*H)936`eow(g^h?vrbd3g?v!lX#z4`!GN0 z6dQjqNEBT&T>8fgIH->UZKU0aq|FY87FLA~JwvYVAFf1T9xqI|%~?d&&4&VPOO%pBM4x_)*)(m<9>H%kL== z*ORlfhP$Kg@on{$Q7CqB7^0;6XcX=KP6+j~0%0GFQ-6BE&h*&~Ax(X5f1KP?)I%qTiY!iy$M`O&UR7)*;7#)fRN6(zEM%6IF} z{{^#Y>ovsuLC3z+H+RTC#KoEbY>p%EzSNf zH9?x=QCmP7m~T|VNOg=jZs8aLJw!u0dh=?NMStRCykE$ZCCyZCgpMw)Qgal$XezI! zW0)p;hREI{QtXwO8u~3(_)`*m?1sp-A^WGV2WGLv+Kbc}k=^G~;gM9AFKK`KI^Gdn zKi2o}%y-arb|P>>!rCto>+{CypsKW@uM|8!tHHCYUy%O_JLC0VBU*p$dZho3E&eaC z<7)X2O?P7}doyS9f3g0BkTd;b!(qb}ee~Ba_NZ)nyUuF5AM=g^FuLYW73bc|4^hv~u%=NU9Ohv}lN zP8;p1O%&#Tpie4esO6+o4+q!kBv;am^lNOpiq&Xggpd?jHx|;ynml2;j1 z!?PIz1a^_QYV_4Giu%)wCAeS zRlCI@j4bIj(DzXTMiQw{8`YWQ!YBONSS%STDX#SApKBWhdNRSl-7 zBwwbQSAA%7F3P-_roDY`a18Ht%#LGE&1p&2#>v_~*s%?tdOBAW=k3#p+w(=j(fAZ1 z3Ohoao`ulAMihVV9-m=d*~;sih*;shld!MeBm6!bR&gsGQ+7R_sVd2l(@b?(rbE_j z(|3m%?X~ixP{R8r*Ek<6TL;ITMz6J2wIDa%{M*=YuI10MJvuuQuw;A;9k3gnC0m}_ zHR=dVonGhudrSKwe4fjmEEAB?oVK*0@fg*Dr(-+LQ-9K~os5C*WE{BP}?k z{A4QhOc%L#s}PjS9oHokx+-wL{xsHB&QGiSMm~SjYy3sF^u%fXi|p?ZhGkzkCTCb{ zr}GlpE0{1GGj3XFYI;K)a~WZ+B%(j{gUbxdjJ3ot0=tB};?6 zW!AUVm37+mYjzbX^GUQ;jy-azrlNnYO>u#%tYteaQpIgWQhV!ikrDnht7{c>j*NCZ zIu3Pn1G@bySu=uF843<@tadHrr#(TiDtTY{I9y%KX5A1%rBWqJOSs>#;q_6J{mRph zW)~$9qP;aN^Rbu+k}Sx$&4f`BOXBC7?KN~mHCscxQQ5}BW)am>cFayff-`^G>!X*R zGc8i>qsqug-&2AR(Q-YN2NzIZMAUVTOKK`(@Ghh+Sob=S@0B? zX-_jt9A5u>2yJ2G9f!}R3lh<~{fkm(QrjB;n&ChS8LHk0Iw~7G2;5<*?APQ#11e(7 zsR|klH+j5wm#Sj&#N}>YSXsk`>(CJPhzyFydQ}FXtSph!aY-D~R!o1RiSU7~Z>b@i zr)JSm>HB?y1@RYXHWCIT=wT@Mo2iJIGNmA3ugQd5nvC#(mfvm<$2Xo@GNWCSRdMIj zQ7OUG5kv|;Ckv*TwU_UQyzU^t9U^ZSOWs$d;>pZe#_4I2GH(>{e1xNJbX!uua>4~KdwP*y{(A{fmNThAP0xU>#5@%FAvmY?ttNsOnb>gkic|d5AG1 zoHY%&I2WKVLwBkH%4gT1kC~I#Li-8LQKz~}>POEHP^1Zxf zWmr?A&O>7tGL3&#Ps4ysVC;p=A*+*5SFx(2VdAQ+h@%(1Org)zg!y5Xwi+#pBhs5q z=Gmynm;pNOj56&YUFzA3hNcHp(_=3Zd!; zI_~|^bKhQ(Q-bHzkF6w+LWvdq;3TQi?jJ`gbl1v+bfkYtG1@FqK6ly#KPSjY?``fa zW1jD{nTY798dwq-liDUm?YxGzH9vi`XWcUgigqN7erHVrOOtB75rG`r zqsjsI*T{bv8J`7SsQFnLpHvt&aji%)-gBc-T9Pt<)IqI!S959AN-C$5 z0UA4Rlh zSp?=Q)(IV#Itwef)9IOu6k3u{dz9?$6^r919zb)&8;UkU+CP5lQLO84U~?EK(JoI= z>@zCQf9iwK*mQSXG(?ItT~*SUo;bmmGE09nN)_6d))Jmj;S7WPjd}ZV%&o)zMG_a| zrKg%3pr4_#k5QF!g#H<-FGLQJ5!Wj$HDTk zI`CjCf1~ ztJ|^D-@#Xcy1LCGxZc4U4!?oAQcE>w8+W#xPk zd&N)>e=r%L5cNm-NO|s#e5+W~TS*U+vwy;PIM`3;5ZGQFD-9u(Qs--=Vm;Yiwg_Vx! zj9hNg;2&fEhGRJ8-h_%scfkDW82a>w<%OUhUSSt~!4pRZvq-Mjr8+?=Wpw|UB5%my zMQkU*6EL|S{y zEt7mBt=r6(jKpGH(OTeL0(q7gyrsrlkD4WWpGDy8hz)J)yUZSjS*BKM()}vNAsj`t z>R^{GGMDDV$~oO@X>trxn*OHS$KE0Z=8xS*?_Me1(oV1JJ+E6j`hS-i3|ea^`1os8 zfBPR+YLX7NwhkVD3pFuIGk|}Mq?Nsui=~;Vq?`SJ(eqAA6p{lIK_321?rkyiTvuP; z*f2LDQID)DGay4;K&=hDtO3~XZ`%X67O%~Bp>D*Yd?e-uD8bkqqDQ-l?*Dw;!t9{> z@OX#f9pa*#m3pMb=t49cAm=*g4d)mP&f6gFDUNiyj0o|z+1%7;|@CtA)f!|`U-aXSn({z?ze zZ7_lNWa6f!g>fRD9y#9P*LS+_R%M)x0ZGwPp}R}Ej{q{UokT!{V*@A6?#=I2Q*cot z0~PND%EsnDN#$#Un2>)mO$XG;_T`LoFA>0L$bakE9P2VB_4U_U{p)A>|0_R>n*q#h z&76(@;og69v$DWH-0YWqlFPG?1=L>Cw%jiQmL}sv1qBu*`a2M$Ao%bZdnkQnhY9r& zQCz`@z`?OG-5IoGHhvikpb}LYPh_ zd^>ke6({QWlSK_=UN`+JtQ&yM>Q`YKwjz8+aC$i)Ew-C8hT#Jf1$WJS4 z_UCqre+O0~Qy+f-(c0I6>3z3G4pZRZuP34<5%y$q21H(!0vF#CndM?hckL%Y2?8QN zY;XRJWU$nzWzY`=0wRe2-;uEYcaHwA#=jgq^k~1i{NtK>t&z>74UhW;yMpB&f0p!w znCxCN3=Bm)#jw3TRf|EJB8+j*`dIc@S7oy-S^+w2voL?m+#Pl5)0>8+@ti3!*!zIe zI}|@;_~?!K2{V{bAN*lXl|=GBU6UJoi^b!K;EYGF&rFBK^%l|Bv5yc4b1YWpT(BmB z9q;-)Nh0gku%{D=k>jz!EN9GZx5k71B7^pA^&z9KVSj7%?P7RaqPq*vlW|pjPp?zA z=`pLONI`#$;~mdr6D#N*Jl^Tjd|0BeMc&aYFeY8tHMmAVoz#$L6*msW9wUaz&+wyI}ji}ifLPV8k*{1H_9iFhaRcG{@9*0*$J_sr%j%a zKt(a;PSD0CZQ0Mt+L}`8f3^LSY+!ehZ8?okhcNOKIQ(!9Nz1ra3}D(5Z}TTMaDLZ_ ztr35&QXwVBkWPLOBzSWQ1T|&UJ{oSm1P(*csj+eP!UBqEsjV&x;`tn@hLh3kmfZLU z-MJ|uLiB!G%k&NM8pe@gfBW&l(Gg_7C||sjKV^9xmQ=Tmdge0YM%?fpl5cyU=(a)7}pU zSyqm$ENO+fso4CiB}Z9eR9CW4<|rR86}9GIY1Yix8S4z4#=a80BD>YwlbFN+Tta_j zAWl6n)KRGGQY5H`qtEHiGM&?lL{GOFpUG{l`7XyPmz%D>SMWYUe$YwZ!Ezf{Hq;UF zIO7zL`i0Cb%s8w2*fc@hqKgGdO-wQ(>>hN~p7SL2QDQPBchM`R%0Vym9jyqOo*6}N z=W2|$HM?jG%_r!(4jhwNDZ3$4v#EbAGhm}4yAVs}8vKuZI_7cB06dm$&?n3)yK|Fd z|55AjwIc?gL=c*SGcknCI@#wFwwIMKn8SPaQ#j=M#+y;E6m<%XS8AHZ&gpVVT&Jv5 z_R%jr?zJ?g`f^P%trtie!j1Z*@sjgdSPQbsLD747ckJFm!#lOgD-bfrWLSR-m;FT5 zoSOD^_Idd7#B!%+mNI!bflVWpORBPzG&u+E;7 zNv}LcN9IP@E>kkoj4};+dnIyIP$kY9;BVhtEX$6ZirbCR_uAfpcTNA8rLjv3=Y($5 z1Ki#`Yg0t#OpWE=+2r>DXP$p?yUc9*8sm1DVrHkcDEwpK*&cT?D~Z>ZjCYy1ce%0M zCb`z>Y7P}19Iz3nZg`K(Tr->r346;@8eN(MsBSfWa=LFnni1)(5SXmS+p)6F2Z@R3 z@1VHCPbgRM&K1SKDr0oP_+a}a);g$hDhY|-jv;48FKHqV{HojiYfAxtLG_6WaA z_U%&6z_z?nKY*fKzfn5V{}kre{d%a%cL1s`Ea#fS1u!Q%GwrEfiE777&5>-h0jg5< ze7*2EWjaJ=Y<6dPR1u#WXMYF?Dq@MMw#s!Y6vzoM&fSv|$In~h{V|L)7;FI6vc`|N z|8SyiEsxy=wk0u=iR^!w;&cIe%)|jTW*3nLqX+uj_`TtaX100@>-cD9wy|N8+Or8F z{tu&&jz%~=81oAE*ZE!H9jxqWFx%oFB>DfB>w|cM08CBGZ2Gcq!z~` zX(c1)B|k%c5~(YiV2WEYgYAY$&>U}_c){I&`Yo*)3f*)e8s63A(WjVjF|>=;@Xz6OhS!`B2RF3$7Sr5}7QOW}bKGRo-jB=)CL3 zp6E7k3aj9pS8+;ZcVcCS*Hic+N!i;>6~bD9YCD9=FL2@tWIb~MVd7aO*O|}mIr>hc zTdB~OI^%!t?e<&Pog?#M`AxGZ4~qOt$aA8omk0A9(mt8SVS1(W!;A35>`pQ4Bwrp} z$vX>wmGU-b?Bi(KM0N;G0BF8CwF7+FJ5A}}3X}`5JZ&PRKUJt${R*k{y0V?9YKF*GH|&>y|Tl5Hstx|Cj(s4g1_hg z82xLepn({97J~o+GDZ5|QM~>)nZiG>W@*ECsxM=FDzQ$s@wx21 z_OXAlo9$rB%p}$g{u##PvfXo?=Q8^;>wN8%!0)#A4TNs&wh$zYupPauUx9kV?1BYU zg^Uv!xY;%dPXT=;N7^85!cbV>T008G6wQA_gD!@mE4t#?hZDP@nV%LJnj^gFimEx* zINcX$g^&%yXTlrAAZb#+94%SXQ)ZAWq@8~sD?V7JaD!8rc*?yjmrhTzsk*^JVS;y_ zC!q+8zhHTTk2nmi)*dj|TyzH&$+VwQWXCK-UlgELw=f;kikN^{n&C>z4ycT1wkkQp)>ehz;)!Z=LEO)N5(?wHrG`Co@_E?7J~t*o$Rva?6h|Ng~T{H zVMWL;CRT%L5MtiWfdfZDswtn{EpLC!vns6~uGkhjCur6M!%BytY3zoWi4i}vxo!%LFne_U~N@_u?##Ano*!L_bAwsu6=)vWKsRb z>5F-cV7agcC+2353S?8Vcl?E)Q)ZDO0jvTe) z3=YU|b$PsRE?Rjrru60y5(;*wiV$Fa)rtY+=HjbnCS7~3lM<8l!8A^~Iec*~8ep&? zsCuQg8f_H4abZ(-8)0TY2Ihaj(@U+=jl(kPQxBS4VWsqqpTOhItPrJ0NboVH<^hs5 z%H&Q4>1xn0w zUOz5LzGYIA9d+yOVzP|VL3K<;hu5ii)+~iohtn+vb}R0>kMEME<0ssuQRv5V?Zgpo z7T!?eliOw#Ee5lZ?8PdfYUV?5#`S+UsN1ARq}il+`m}02&43}g8X-YKM6;e{FZAOM z_Tl%e8rZmTA1IR9f^L8Ba0Ftt$^gB>HBFh&QhEm4iQWkwggn%;MAZWl27GP>TYtmg zsAvvmRO9xKpY8U)!Ejh$hY4=Rh`#U~>_hX>2Du8+>Cs)$jj)vPW2;~fV{>85eke{~ z5*eZMN%VQ5?8ks?%+mK^&T4xW&qlox zpuS6ja^xg$A3dPRA{d_Fa|08mw5JwYcD%00QsPZAN+yO^eNHoCaT5uZukoB?D)q8x zBS>dK1=tIjrSlcRSDxwQqO#jK2$^&yJ$>~8HBxc$e`rF6g_`&yLHHdZGPV>MlS#-K-j;@lYiZAiI{YIZ|RL)(&^;*!*17e9+VQb zFOkp=NYh17APU#>5pE)OlZoQ@47k2K*GRjA(VF+2n-27*3u7|ej%|G`JmfA{SBO&d zcj?_x((1^zwH*1O6qvR5a#*3kSsjTyyH!E!AE!pN@7BKFDJ3g^4(R?dzZ;G|!c(AK za&jfy6OQsvH4>W_DdRX|IF@mQ$P0C?ls}N z*lxaO@*FS6s^+8IBkrhYmW4(>m7XT}Z8`cUgE0vsa0E>}8g_*0c|=8lQDU)VQvr)A zbM*+~4CRjcP8H>UZBph@Ci8p1*5j|oRnxc<6IDW56?NG~9#tNue50U-qj%>Zwt*Tj z>hi9-wK;67BNjn49+67KxGG`VS{byp6u+fvK%nm|hCDO6z37}i#u~6PsFidb;OygZ zwY9Jt^%l4IsrhK>$vM*cloEz_t|g}!drOg<+sh(8Wx9KG;{Wi__6>c)b{8MXl+iL_ z9zbb$r)N!nbhLkW&8Ov(Ph#;6l0R7gR*SQyLiH<}dwRc3+Q7tzXPr#ZQPksPD@CAW z>vTV47Nus{Q};fKhugoX-HxvCM}@ZGo=f+|{MxdeT^94@Y1>6lI6*ocu2zUYLKzSK zF+(S+uO85Hhz(mQ0e8^PxOm<8Hc9yp>oy4yH{sELS_k{@iAu|ZEhr$K>Bb<6P5ew-!K~QVsmc8r&(oT{dpCk7SaS~T{ z1n)k7-OZ_F2og6xs^P7(-OHV6QBRQ1VQcX>C*HiJ7P&EJ`mT)R@J>_eE4tgMine4~ z5rbzVJd~G-G9_s=Z%K>FWkZG)mlQ&TgKiE_`Nx>i3;dS+@ab7z1pPoT+rW}o7fe&W zA5DalH_Op2LSdl87n?GLL|T4jiKF#|TdY-ohwu4nGi(!kZp2F#=DN!P5CeY1b-yQsJt_NgNK(rr7x{Ll&mA(ReeqFYG)l<1^O1 z3L8?`di>y@;)2&Oz)guV>BAz;JcvTawFZM)01tuDKMW!tv9YI+vEeHc(#qR~DS{U8WM@xa}=PRn!hk#US z(LAZ5+Hg@>C`tZU50v`a1jcj`;;&SHVI(~!3c?9O_6t|V>M4Sofe@+1Znr1P@9;=7 zGp>F4)*HB0x)_qJb)doPi0^I3mDDQIE%VP^T*$?3?{5gf!KO`cp@PS3ABwh+kv@xM zf?#tVzV+a6#n?Y|sVF~EU;?YdO) zXIKJJ^$-;Mp*U}mzAkUlb?Y=SS8bM7V_1KnLhRj$A!zXHuq#X_U(l z<37OH5(mNl`CTgJK67Wdf)SGA_>zsIUfo}(fW@=1w?MGkV7RLY*BS+0RARCR&OvoB2YBZb5DlcLuTo7peq z4fW}U-{1KpFFQmr*T!k?c!b1JJDdXRu3gxTAiG3KEUoTfh|H}|JBEB4zX`5*UNBUa z+c~M-6_m8JJn#@bd!~8#p~((7`DK}N5>viPCBFBdx)M0NI!L~C+jn$-GKW4g8;xJ4 zpnO`Id&wd;f)`I;e;1B2=Cg*Ml`>nxU(dIk`V5tbnhdp&D-zBgyOv)piYD=^Ffh^LC7DS?)LM zZCRl=-Y3So>hxFzDmb;$_lxR%e~itw${YTM6o-M8wjA?vyf9JPN2s3s_#nMI5i-X(bkHmG$GUMgl&5snaLLHd`8FFb57oI31u2?h>y2^tRXx@_EP8*J$s zw`b|h>5{_{>(`5lU3Am5lKpMSd;LeD@Lh?Ve>Si0+Qm7 z3q(2YP~P6g$rJ%MJonbiAE$uw-XDuuxgL42@-s$x(y?bGatjQLyIMm+=P&AgfC~1i z&}tb-7MuNU{D#EuIr+Q^WdZn`ZF)Vn--{1-q5vp=Q5_d4sx$h&?KFh;NJ=pWxyADD ze{`}N7EU$1sqmtl@6Yw=&zaL$^K3QyGa28XzRD%@#~Yp2ebQzVki(Ks z8=0PeIrmw|S)Lf*U(eIsVdhC)vNOOD1Er!xl=v!?k2>2kjR{v8Yae%j`5Sa@PFtQP zU)?+ja&7A(&c-3iJSE&R7a(VaHMQX_9?OPK5pK@dp1+YvwY8FBC#JwKwoHhy^I@l#W;=?L!1INUw>xSR* zY1imw!twG4syN4}bc@c@vB+an?SD@IdtLaW?}1a4&r%#s0N?iko&AvGyVWjhYZ2YU#oUsn6rn5=~w^IaqcYkgnBLvG?NjdS7;TkMum3%Z|w<@LFi-I-(6!Fn=ERx*6B$MquKHhre@RETb);vn?! zZomqCxAvQF0-E==p-I$90O71mTGN^yLTtkV=Su$(EuQvZwdTIg0^Y z4;CY{w$ocPqXD7>YBt0Tw#q)Olbo`^$dLhyKd_*4Tvrkp#3_x2IVmfgvLQakX+KIB_X zzY^xNKh~RHAwht3=-+1hFELqxdU%7+SZ_Bd<=*LUwbjGtn2Hh_(-Pu%Q;wQLo|N?$ z@P7^r3{&usG?!4VFhOES>Z~L#JcQ%67|Zmq3zOlr;st#Km1LCHtIOHE_slFO9ZgDb zX{>D2m&V3uNr>%#yIWFFOBYBbHhOH@!z;XD)pyvPx>oJ)8*1A!D(SV!z2P&Ubspp# zAggkFzw@f0eRF@Y5*$gj+Xe@eh0Gx;!FwHy4Pm_o>o(8J>|*P9`yU) zU@=*zSg_2KMmpht_)nWzlXUx^PwGxG2IcE;`lK2})>dYJ(foB_C64%q|#NW0>4=3(Qy8iIi}soJIsqLOH%X4FGia69J*gKl%dACex-QwXI_!WNEVU z6_}FQpVABE6{bsCqNkCxN-9n!+Zc(BCx z8ETH5LLt1^a+KpXnFi?%-0=PaPjN^vjdOSnU6hLCkJ`j%eFu4{Q8k zjUhbSs84c;PpV8BHv-rnPe0Mvht!TN`BpMi2o~~d8AqNet`o4 z{Xhf)V)>r}nwp8Rlbz##LR#m)AWeG95EV%f46N}lq9Ns}R+K)HbrCV3TT`oPr%vK5 zk+vIux&}6VLVwQ0W}gzCq)s)&pl5T>6V4DWo&s!bQ@}}BPG#N=U8g%+pSh;pr?{T` z^nJf?DUiKodE*qr3^PQd4xJEdWQnOBVh_L9OB zo2B>)saea`8#~(dTrb$xS)4iaIdrC%Y=%dFQsLW8-C`_SUWx6k&5Cp5?(pRO1(m2D znFH=*IW7ynurAdt{2Mq)m3QkSUsB@6if-<gek!QEumz!#M~SWx^qAX?0BPuTxJ#kBG|b z04C|NVIHS4Q|eYqtFWi|Y^oyCzudK#%S9)d+-WKLx7toYq-g~I5PqF!oY?cZtzt-o zbeORpIOAI76gZeoIZ3fra z@d;G2t;#@HVd*d_$m7a=YuWeXG0mvNMR1KN;{Y3PIl?G1*gcAmueB~IR-LpHH0Pdg z4Hcsv&S9Gt zm0|swwU_80lkePak1lGS77M1)zp=c>L(!${wHRhs^MVlH2g$SL%BWR@Bqq|?x?FfL zS3{XH-j#mxN=^9u?daWDoi%~;c#gU z*0l}vwwAXB@3@w{VEBQ5P=hmBB@_tF%YBR!ND3k8Ek318+-&iS546_0XSDS9wc?u& zx8`cUB-csd#?YuFXL?X#8DBPODb!7IqP9Y~D?)>cl)6T~Q&BYkJn#Z=8-pUG!ee=^ zULhpPBYi2$S#EAlb%R^|Bf{zYf~*-3fE`HSB#|KL2KvqMdO=NptIS6H^CM<~|3Ud( z0_G0go30MFM=fBb6~pCHb4Rd~t{XQ|&Vi#>@*SN`sa|;gWl0+6{_gWtML4i60nq6xC#(DE9JEE(7_8RPA@}(;A zcHMFE*$LUoO_i8`<2EFwfr}*tL;;$Rde=2ij;wnuqmc*BXxI)Kx@FB;jm_p-Ay2!f z>IdpG$W6b}98~#qoa)nnUG#MwO^97iQQH2_wCIZD8+=hcdItcKB$?TFkTQC93e^e> z85xE+0Od;X^-1u^A!!56nmisgRdDONkT)4T9LnbuIn)P#5g&6{0CNVlyS)pPuFIr& zwYikSWt%tX*l`XcF@J>m@Oe|%Doncs8p;Fa)^1yP-sf3XS_+g^?EH>^`4cQFmFnEe zV)|-LW!oe7?d^lvM+!as9?F`NaK9@5{gz^FyPSQc?q(Vd;WGd|56F@&Zq%V$VaOy; zMO3dHLH8(sqqiGGW2ibs6pC`PnYHyToQM0-Kk*20q%{gVij_*=x7R-PK%P;U;s$beHwya2Du~elCy|;wIDJrFw@hKKvGAPnOPv{o2nYW6XF=36U%8B#%o5`D z(}w3&YY9iqwy)P0gaNWV`T*7uZMUZNB|ex>KO%mGDsQcJp53dz?gmR>_A_~B<+~o% z%hghUC@2p&gr+baG(=hcIo!R6FN_I&{6ZWGie0%Cp8i~}1Fd>fGrRlVpAc4g%4r&g ziW(YRURP0JjKHMKa@B{+@?Hgx^=o_dek?`C(p~CmrUAO;XX}tWFTrgN#L0XskM_aI zp)Q-?fyv#r04DhT7QqyHDAk%xQo_*U^(KygZ6?~o_O@l+`bBD2vM5ITj!nmBF!~=4 z6s#M4q{2q4w^{bVhNRo;ulWkn#MN^!^~n4Vt2JwrA^6tm@TttW-}b5}z6xs3bn{i|{{1E-HmfX|>@|-vxmqp9aWzSQ zyB8j&D+pl}hp=pIKgUyWZLBYAI_aO!t%4!SLbefT-_!f?P1?!r=D(sQUPa zu7tU15&0N{tg-2M-33{akDh5oUGG8URCnT+KklK0&9J^C!oK*qQS-@>eenjvy2H{& z$~D;m5wk3eQ?Z}Dze|*P%<_UD^W|KB!{w?Kh(kma)6?;JdM69M8)!6kmMkcbX-!mo zDu_v>Yqid{F8-o|N7lT}LOe*~lbX)Z#Q!52o^ ziJ|o)?%8YsDhHZ}28NJ}7Z5u-dGrWzZx-H z8&b|AFc6Rk=zllh`d^IL(aFS3#=_Rh7}N15(>BvNc{0_$!@u(w-jr^733p;quC0a60s~rL zpZ70vJg+)g1blqn5q6;2X*7g?hlkV z;sa>uP>raal zTZSSabgb~=hm5o>R0=WM{7zgqg$l~1Y5sC=hI4&SccG4FcvLBh(Bj%jp_r3wuV{4G zpeiV2Ug(Qb}WHOB@0VVot(Hs<%pkHrot=<^n_ z`+W=BQjqyP>BV;JSe4;#mqejd&Yc-A4i=j>UfX-+A2grucz0k2T zH?8Ti&yDYeHCJ+fCa^fi+k>pl)pYmY$L`zi$JwLX-(R;Be!w3{LhxQFAIu<7%y35! z=!ad#0!vjLhV(RCi}p)svWqEjRt}QRjU%}k4mM*?))aMPNFBBsAsiDkxN;UQ zdhQx3vL46i!+N!RljH>v&V#fV=@o;>3sO*{rGXQSJvN(vMFF+Utm;%J)n;~VvFkA< zHN|jNn$yrfLe_YFOBOq(X3{)zt4kxwv?9l%j^idY=*}EugaV`X%}K-GiR*ZW+0B+= zz)o>xi?FH-5lk`nyRzeEC%DL}SQR1@Imz-=#c<_NkFMetN=~b#-_UnWMr}fj`_x@k z?xWBb=K*kk7XWV!)jF~*qa~GstR<2U2-9L!6JakK|8FNFtX2H`vfZcUFHS!TGA$<%c8AWAdZaXln@ILB zC%~5`8^X55SNf7;ADhDt+0}K4`|@x|)?7q?PCv%^V6pK`s#TT#Jt)o#Y$wsuZ*K~q zQOG!rQKnUpESpHNPtCId$TgX}i|N%wDHEjZ*+-4l=}A3kI`^WPtSqSjrxDO)`nW*A z^&CrYlzs4vL}pXUbW((Qkq87B5BNgJm6A1Q@h2PDU|yWU{Rr^~Fr7qDn4>yB^+*>B z|G3u7H5ci{D*{w0E8YX$6-lt$p44T3jQ1!pgs@TG!x!|(em5QB^pC7Vi1np5z}VR* zFc;4i!@*Ckh>Fisz+E|w$H>l&BV!#Dn#2qFD4lJTwwbbB(b92>AFILZLRp=NKcmm) z!(w-mG5W9+UVAkdO+B)SPxD{M?=Pc^_p|sTB8Js*x@2)Rf8a?`2`Abi!V5I zM-_$H{XqJJpQ}MH%{}2IF*ukDVutG{PT3+Yv}ljJ{{=9_B;rlUO0zXJp@rms1I8yU z3>SJv1?i$VH-ANLoUJ}~JCrpkw(;L#HaEn|J<4CuUmI;;ls z$G0s@tRO{u{WP}7@D2pwkV1%7MBMZ?|01=WPd170!QMS0EyEW>1zNPX0!peIvum^VP^k8BCPKdW9@Gr80a( z7qwX5F&5}T30D^Gnw-72inre0(XKPJtd&x)x(@gd0-$ckHhe+;uh;@)a1OYC9L^W;Llmr{Xtiz(3j}W#dYkecQkP`-R=7YZa@$VGxEdAuxE(s z0IS+P|C|?gQJ&ab+IRf61m)a439s5FihRz8{bD^B5f_MH|1t7 z0-;$%MOhGydK;6d|554HEt!w8Tq~_`-%GsW5I?a;oSoi?8oEGow#sDfprpd9ODLuM5X#C5 zxs!y2|-TFE3&4Wj( z{!Bo+Ylax8PXz5J@Zh$=XOx%85m|^UjjsW1yY!s(MPV2)&NR{mt+gYQlpp~o%@q%g zQrdIayNUIvwHEze#lkEo%HUb@Hq#dex%r!a{S!L>)ZU~uIb+CZGiRwGGJivvCTtkJatM85#uaIsD3*Nb2I=*mHAfJ+f@!3`GRj{cm;9f9 z`M8X`t(&rm)4zv~fAedAlcBAX!oRhb3ftM(7~1~&50|e}9e4ce@_bchq|pf)b+QCf zc(^DJ_LVEaJooRx`Ioypc0##@IHyD>Fo;VuMJBm~f86!G_-f+oR+XYY8h; zgt@S5BJPJJp%_t)*aX^cW5DlXO$rv*AmZhjyD}X-Wn8HQkz54SLLf9}vDFoStyjk| z63+yLS#m}g!>#g3q21_p6xXhanVAEIky3{T0%y!p)`MZ zETl+1v@^tZ`w%{nw~iToy%Mk<2UtD@v_Uv;SibtUfF|kWmQ-UUU!z|UH!fD_Y$`En zs>|%R_eMA&l;6UVUq3p3bJwJiY}6;RjYL;qn77ynG}?uivaL6re0u)YS4)QKbSdfG zSshW9#tkHH=5C`40aay4K(6BIXw}^Hel`$hD=>C2Gf(_{6kNr>%GTya3!;^bOhJ>W zZcW!M?&xDAT^ms z6)E_=bYfF-O_xEJsJ{oMbh_Q+qvp_jimSGz8Ijfh{!2EtK%o!P?+?F7IwPst;NV+` z5eVy)M5V#qdid~koBHQ1evtC*bVL#66FAu`q2%56pVh+re-cfyf+aQjy(}fyNejy`W zoJ5j|niBDrkNN6yEPU#d&9EIDatC}fhy7rZG{B;W#OZKp8A(f|yiQls$9o}D&Q|YU zT1`R*;clDE@1Y{T*VuGhlqHyC%1{;+)=?*)sJcv7Jm*S(RN){w2}h5SuF!XSGd&BS zeCBKls5c+K>GuLJUo^>|bX#gYYn*>Wu-vv@RLwl?K=`6FWv}9)>3{O=0Iuxy(*8<~ ze;Vhi}sT$L`G2_b+HD|kCr0v#h3I8v7vgvr6tz=^uiAEmIcD#MKx5^*Ol z%H~0qL0_+b>-mdUAIOCg3q^=*GPvERshCYqdf4o+BYuc_3)ZtMQUQmJ%NSd!&lHKH zSDeZDV+BFV1LQoZCKxlQp;C@5?d7X4o&{w>_>dHjy<_BG@+y z_8wwCHBuk9__Xd_Hr=Y1|dn`Wm~ z_;XtYorj&KiZA?6SP$N&hpthDJT-*4tO@BZ_w88E?)T17J70lU^q&F*q{zY>Kl?;L zalqGquEw}5l7AJM>rQX0y8M`NTP@@4RrPnH=F1+SXT_GtSgC5(ZqjZl)K$yLbOjxL zstR~8yRUwLQPX_wqNTQ~>_U+CRD&jUW)x4!s!5Jnw9W^w0ufULPizR*6no6(BY)as znKtl^O6*QMTf&#p|E!uze=RW0)Q?{=i|T2;{7!1 zoN~}K&Au#ix&qfs^gmXK2=q87Lao`a?V-2Lw!fxf7)X-cqilo2V{yQvU`NV!wxUg_ zJN{KxTs;kSA#Jh@S!0K_5uNDP-$R8;RS5p3Q)52KnM25l-hJja)@%y04r91lT|&!$ zMo3vhEWMO8_W`~IdK4Edqz0k1BX@Rq2l&4HGT?6hq}?p=r%sIEa9H~p8_rS-Hf6E) zxq8-Jsh&*OVhFZojWP{V32mdJZi_me?O1Oe_jC9gElXA&my>3uJ-gWQL-JuSYZRDM z|JouuvD1pL3S4eN`v8Wn=*1^Fw8S<;-!GKPOMyC?~54Eg{JzcY0MaN}-z|kkxF* zDrk9!$sA<;$QzjeXh-eS*gPaa^BA9y~L-AAK8*Pe%dvHe>8X#o(mg^8{%t8zBm z2S#mc(m{lN)(=@otI+;BLL8TQW zN8E)-&pjvG?eG^h_Zw$DoPZD8C!$v9LqmP4`!7$wjPFsmu>T?u{ODtUVA?opWMa*D z;q3^)y#c?nx0&T~)E5$KCuDLCI1hd~6pl6gf{T=1 zUuhP~@`-r*J=4Wb5rw)(4jf4Khz+Z555n3^<}r1KLypj_KJL1L3@5T)!$z zKwO4*7#Q?9hp7}ou{sb56>e!nR-oG7t%YC!E&BEreS$40Q%Zb4~t`Sa^(fDjA=|x{aN+FUaRdV7UjkZfrQLea6f^B+&UZ9Wy>{p`qNe2r15OOy+X|-93Bqg=uUTCWEUV!*v zc0(j3Ho|@hys!Gi2y|}=0Lj>=gH58R9If0Ghc#xSxNj-iQs}M6V$g+Ubye|i@maCV0FC!b*7;7Pd!9+`880fuZ zZz(u?vnHDP{YEBFU@~<2-ZbItR=B|o$Z{8T5$tt(O~J$H-Uq?_UK{fDzOhkw8*);j z@I~mju$2aX19O?-^Y^|WHk9GwiG^FoZ6|nIp@^4gfyeqpW9nhtqjbUd`bYh&CoA!E z;ID)W{NI%x{>#r4bNn}cC~FxzBNI|tLu1E(W%S80owguMNI}CN8@=Et1OXr!X&{H- zC`6*f`C%f0$MtIVBdvVy*}OUtygv!3$1);P=u8WLXD?3PKi|KAYlnoxb9xhx5ot>3 z9Vg3fjd&6Ua!52MdBa&RXKjg_M}z5>S$zTgj^X~j7Z+Vw@N%&2Z!-MYaAd8eTl%!m z5P>}#WpsKekb!5}0tF?qs1m+4LP|!KwQcBf!1Qjx{>(r0WC2;ox0SJf{|G%Rc|Ns6w|2jq2^z_18bpEP# zX{^_ZHK}{?x3)f@_@g&I&fXLhKs&18MuuHeOOj|H)=pw^V`-M2jgCd4f2kjp-zY5{nHG9-M zeO$2vD3y_vm=Mc*L>&N>3D`2)roSz4Z)HfU%&b{#wLF5X9QYEMN-Z)?immCe+1{Oh z{O?-Q&p06dq?qEGQVS<44x28qC&ZV=*Wsck!DjI^t{7>qg?XX&d4)gX`2&i#Y?qk> znKsqzZIR#7Y-XL1BEdc!*}}*`B2uI@isPa36A%Zs;zo-DG{_m{`QgmoWyf<*9R1^T zuox%(3ke3mqxyX2<#5W7)Qpk?7O9ti3~aV`(4^W>XP8kcde+X)^XCgzTYTE;iBxuk zusfNxBNZfp&ncpYoI9ju zH;z1qUQQI-Fih-WrhZDmo1HtA=#{=Jmo!iml19LNzn5Bn09}tNBoJcRD&CPor(2<} zC9Mh2X?#qY{B`5uCka2lBS+VNrH?zKJsH%cTn`D3fe}1yLSV?AFH7E(EmmRHrQfYB zrBh_Y!!04ERR_nX90wZ;epyC)f4PTf2$>JVt?HDQDP^_~gZ`3;@QG7?te{-#<7mY; z)z7w4^rJW*a+$eykQE&Yr%A;ifi5x<$;It_p%&6keWt>Qq1w36G-76dQjl)`5G-Nv zSIx&>Hg)wdf4&^o_+Z`x`y{V9iuUiG52~V#d!nFtg}j2_@5u{)E+z7AO5A%dwJ zy5aVzrIX4Ss=7gIsD?xy456e%0s9t5IuRD3ZBLU}MuswYY-(!XM{L5>s^av{~Xrh3xKE*0Lx>^{S39Zk-umb`4S73@1%o+51_{=Nt$RJaxN z3QP8th}0%`-3bV|6zmnFdN4#M>=n0A-RH+&dOkG4oNU7t{@7zs@!GH$g{#iQq9FAk z4|^YRT}^_gv)IUgr{N@3;0c`%w1(oa>R7$nMaugaM%>thz531*veI*Ml{G(x2L3BlV^o((;e*k;;Dn&^028bNVr^dnQwoZVl*xvhtXtd{~5V}OO$a!N~8C-JemT)sxi zq$nA>VN~jWiw#{rHCmX7`BK=zlQiu3MN)chhIyVpJ@oii7TmXDPy5f?1jCxm6z#A> zqVga@wp7<-$RYJ?LP|B6SUGD+%qeu)ktq6huXLrsDQ(5UVSU_fLkng0jimRs@~!uW z-`fa=zjM9nz-rpZGYIaqQZOX*i=I5V_ zX7slM7)D}>8)>eu56dS$A1(haI*Kpk*W+!~4~Xu=v^c|FfPw4C;dj#R7ejcS@ls`0 zk8j0)3n7>O2sh^ZXjIU_+IRU&V4>X4R5BJ4@NI=#UnNF~UK>Z+n=e$^LIs0!}yY9XT>yxEl! zcf*4x6fK!1RUWI`#PbMk@%f1WFOPRm2zi`;Ok8k;sU_=-e90cLYdNU* zqOPX-`QuU4!YM_|u&RubEVtNpso?YCY>>=ij@4ou4kaJ=kvP!c___8!!rpC*1zhWY z40tBSQddiEI*0YmC(V%XF=(k-4iFYpai;Su2ojSlcPA+eA3%MY=0h?+IF5V*lQ0sd z9n1y*#a3jy1hsC(5mO#_mPz859lXx4-j3wd1b4pzc&g9NwidUV?98OkV^S*Cj0X!a ziw+&P*3vg-1O5 zRO5ce%E+llh~D#?iUT1ZzjSyz?^+b_`2t7d$keCmw&I$ct|Vg}2(sQ}a=)S~DFY~O zot4L2TgO^`+vc~JoSCmH8}R(HQAlRE#)CYX9;Mo}%11~2mWkBA56vo~DC@C*H-%4g zM4wmXLeXu!hK*~U<*+`6LBF|d#ZQ|coh#;fU|H3^sk$iN{N0#o#)Hq!rYhj4EBgnq zSnAbuT%S!v{f8i^WbpCJl5E{65FkbrLz40Mq*o@;f)3Ilg-X4sk?&t8_9qVjTw?4_hbM~4bdxq=w9ImaW(8KEU7vMfUJ+A*UDlNYrs(a7xXto*5KkE z@0Y4Bup(6o_ZffAcgq3xRxr@60LWoxnt=anr?JKjSQ50#gBnuNq5#*h<|SVSUKq z5yQ9Wo6-fwnyQMH55{x{=_=m!8i_OHCdJRLKnZ}xq3}Zk`vFXClt(_dl377BMfd}0 z>;pGh5ll?JvrU4Fv?i1Wv}?@)ZiJ!#9e~9h^xDxr+PeQ98^n^_i}&YwJT&k@xtvcS zfUkgZ69tdYd7d&r_i?{}WuH-*&0qb-vtzt{Yv}gIY^vU~6TZ9WI?L?Y1J}hK$piH| zWIOzoPJ_so%2b9U7eqZ5dwnM4GN}#66KN3sr0?=%2!ACU(gB{Jm);ATi8sb7{frN5 zc-`U^-wk1T-*ZJAj$_6#s|mGXMLv^b?hNR-?z15?|BzJ9P~ydZfZP4bjGj;=Sc80u zLNZ5Kgcg%VqMwJ6mL5s<;o2oCEZGY;w{bdB)rifj;nq(>IOe5noM9=#S;uPVeoshI zHrs}id?^x#*&H$^LQ7HHXA#gDp;R3Vp=IwB2IbtMuO}j>D^qr^sOJ!&2aaYQ(IO&P z4>EPLOxYm+q6*W07w~Mg{WIJV<(Q_FMp51&4Q?taH6JOW<-$2kAoo{Afb09|p|?@N zxJg~Q-mAs^5_HFJ+OBu#4VKYk&*599;;mhSh9wdWy)4L5LYhdZiuM96sX=v>|5i_ z*MK=%VM5W?6;gWFi$!jWl*S{qI!$Xs%Ck<{>nG50TVM821 zAvx&BFtZnbi;2@pB@2ss=V(FUTQ~E@ZcnQj$H?WQyDLO?w{{16$Q%7O@6jj+>iQ!! z%niQB{REn^UNQR>BPcucrYE*Z`=F)26m_CKHM{tuCTT-$UefkAjFwy6a5Z6$ucT&$ z%rSY`CiMxZje*g$XRms_BPvrguX6?*1&$J&)?)l7y^#lG`a)=9)zR~^reh1; z_SA?3!sakXid2~2-zkJ71XI+h>^d~aGys;{ayBHVi>@ELicNx&`n&mpR68_N`hD^G z!|{B7hNVW(KE9BoK4S^c0@!ArPe`YV;1F*ZRijYOF|jrnP>xd-B8Oo>w66_mh*+A! zD>`~0c6lW2E2N;!+fQzQHV=U#(15hGp-vt%LKUy*vo=^f&V~_+3FU%q!2zInc?mU0 zbLw??TtYa)Y&jyJIn;jW$m%Q#C~BWF8dhX~mH3I+z9L^7cr}?Y28;5s%4WLJ^Ykz~ z_^vyhtbFy;N}J0+d=)gO0-7+kfAZxFi@spEPQ$K**~y!_aAEMwCi-y*KJT^U0o{OL z-blXsO6_v26pkOr3lUtUzS25eKe5qI?#JAjp8nz_lZM5V!|%7sZcHd}=2B#?RREiR zC?GxwJYP~;uG$cssTwZXD38a--zI8EJy{wL`qUMBf8Q_^Fj(cB`nrdCpNd@p=+W8R z1d1<0R1&Ec$enrOEpJE>xahtYeAp%L!{~WtZzYAvnQfh*Y)-e6ckTi8I8S9nyTS5*eh=%amh5qzrN`Qz(Q8m63fi%&{OCSv~787G!z)C!7&YLf_;zgD6Aaej#GW$LB2>mgDcDews@yaMzH;<1D zCd{QCr4PeX-x$Ev5WOP4NV}GQ0}`g&7;Z(5o3?SLcfEstFt}(%4k1U!bKKV2h(T|i zdqqjWUT1=pvZ(PV1|Rpv6aD~GK&-zTQDc!696?QcC517-=6K^3&1IK57P zcGe`w(d8?LT9zBsx-(LXd&p?ba1*t{PN>uK&G<>!s35n|lfRM}+)YFLB*1zfRSJkpPYf4h!hs(+C! z{*UWmU7$;0cm8Sv{O_8`|5zLUQJ?;|eiYJwz5jc88t|`!8YOAF`JYH%>?^Fd9! zpT!MwrHm-{Fy(P`#G){0&`Iw@nrzk9cJ1x{U$9^(ABb|Lct~bGXhuuymPmL?@%`$$>W;Y4d#%8j8_ zA=xmUTi`PNqdp6;V=0Hb5{xZC%7O$AE$>p4>ri=9#i&Dux){CFvB(M}W?t)-vFSOz zxR(I66E`;#fc9ZE*YQEF%3n%)QYLy6dv(b|T@cQ!wMY5U_i(awe=;z&sFwUOV8Wxg z8t3pjP7b3@wBNR?veu!2G;r%`DLDki0ewH;LxphDsSDbFn&Z!@PbO25#4O))$G9`k z4$P&Z5?dkki~L&CGkc&B#=bEhP&J=^H5ru=#_{0(5LhD!`?inPZjnLU z{)#YoI#uqFqWH~RpmXH|{4OI3yiBP!H}2XZH#>=A56VHM4t?grzfofQuHWtn61vNS zqr!?USF6=Sr9o%n6U*k625P;Ju%z764hy9Bf_p;(?DGa`e*lbYu@RK|#QbNgmrv!N zwP?X^6y)Tj5d40zLOMc_SjbHeS6l5o05H3O6~Z1CBs-w%9- z5_Xq!lFoUVuJ?php_9Ydf256*Xe@U-@1Vut#C_RJf3QB91`$x!906FmYb=JpvFx~J zc-+7}^9lo#7;Oj5Dp5_h;n6tO-f{)uVL$@zEhGywm<^w@uI z9{Y#Ks%YEIGh*>wtpzuoE+r?wXGiN{jSuaVnF~=1XQ&t$m0nv|R;4Gnt(-P>2mAzq zCUrZ6e~yM6U=e`1wXh*-05uf;#ky2mG6e|>y^M+EvC*@U8z!xhT@VjNZ2XmYg~ zuMea<7d6Y|A?iOM;jr&l4GFib${xo41%DuOV8}ed)7Px`Y!mCTosdr=Brak5XuY~w zZ&5pXSZzRQeOpTvpa3(ypI}&|Wfd*TN6ZE%f5SxkJMRDC>>Z;k{hMvkxZ{p(+qP}H zvtrxoj#j*4+fK($x?|h6Z727?5AHbcd&e1j@B6WykM*mkW@*gX)cl(eTX8%OV{I9Q z&2RIGe-)K-DE6*+(sby*R35q$ze+Maq7f$Vv#)6d3cN}NdOOEBkgx%e12Lh|G z9vBNk7K49{l~~dbBnM&wixW$fBx4UinXOXXTEe(2{+8ukqK;S(3R8=J0{x3cBlE(A zARV2e^w?pxxem*wOo%+uToR{W_1gl#f_JFlInpe6{;ptv`dw5HTG9qOzSQ$>9R{s9Jyd#&7T91c?&_Q1vj2L#bnQIHcAR z0C4Rm{a-6B{{7(T8^^YA!#`O74)XtJCiq{G`LCHkO;K506hpA3(chj?MGjh6Ma5Q3 z_gW?iQ(_H+lcE@fB&KHkp0zHvf3rI-$xa@C1LIHN>^QDxg)JH?5tU0o6+h|zzjV>Bbsh9ImJhPjrKG~3G?lZh+!)re`d zxU~8gQQ%`*&MuxZV;(cLLk1Q(?U+$#6`RQ63aeRCE=2#(KQtdp5zw}1kQ9KX^Ywo~ z%{61!yA-;M-!WwABNs&de`dBT4@BNSo0d)bY~#E-m87W|tec;Z!6A}WzSH)6 z21eaFl-BnloN7D1j`Ie8WeEKO?~rZ!j95G;apPEkuEd{A@$*+$f3&#;QOQd7S>sR{ z*%$i1Mg_?wnc+Ar7}yxre`ERce?-Oqx_Q&Kc0*sn?V3sv)FHwT8-SBrM#GZj3a|YJ z_*<9HIt(;P5wn`DarN44ve|+aJdqO|Z(S)zhmG4u))<-w@)y7xX4b`uh=R{(2nx*YI)j+wx z_C%>asIs^xm&2bmi5BaqW$QT#)Y*g(2R+lMNUl(am9o0j>5&}zDb8FejfBD+N!s~% z?La)jrZoCmrksNQ-je; z12ooP$ub2UcdPV}fOXd_SM_H!V;I)44o%o$f3=e1wGrVHAYQ~h7C0A%A*vpJ+dvkJSt8B3&RpxV4)17mYUe|OwpS>aI9#G2jAa@DEapoAw2AaF zG?S(}%vmcHe?t+$55l8b$>KH>B4K)q@#f=w2ZREX`LqB{A{WoOC!s~AdN3O_D#Q#% z8;77dF<1Z+5+7cjl=0?1Erebyz%vaJ6#3@dMpj@-NQ8A=yl@@Vc|q31B7$G5+DAp0 zStn^c7j4k8J7agM5ruk{Przd`OMEdw7?x=Yp>IN|e;fXa`j?!qnN-fF`9xtApkFI7 zmQSvBdN0gwvUdS}xiUt}pQ4bh$}F2(S7~_tZGJ125Sqzo&EdjF7?+F4bxq-$f^|{vO?cbZ(fEwU`ZP%r~&Wt=fLZGsD+HO zs*yv&K7Pu-DZ!U1aBy|f#t&|5nAJSAqB&?*e_2FD|CAS^zd;;qRl3nVf#bMyd{(O~ z7!Ugh%|OtbGhPaeepqmoh{P(_Zdb_=Enr#D5H|yKul8H21=o72iB0qbDrWUu0Xd_> zqDj`((hYID>R0ZcbEWhyi;PT8=rtF;?7>!Zs(MIN>$PLK^h+&`i!f-SoSR#vIp?_m zf0QFPKZ%mAep*TzLl>pb>nu?0u6N3%!xD3(Xl0cN^YL?84P5P9OTHSwIAfSr`&c+AF6Y)G=Lkt)6s6Y|Nf`c%QA6p7k)M)g8HyJ5|=7^C?Z zbi7fYIv3s8@>R1uR;i+Q-&6)^%=D9$f4{!Vu*6-4FYHKy0i9b-8j+s%?J{rbM0VEv z?5cKeev55=gjqN%K}wF+W#hh0?fn3iuRsX6kJ`VUwW2$~Xv;@P9uNs*@T{f+pY(Tg zE#+MIn_gZ4x22nFIgFpRX3&x1U=n2Yu6wG;k%{uO$K-L9=n>K|-L9N0i3fMye?jO- z#&$plydC4lFhP#CLn|>{3Kkx1r_E%;cqgUxd?;3S(~Q_h>6_KC>(==VCZgs_O@;jl zcS%UR#mt(PkD?{-aHicz<{FEu>kFPTKiS9^7t#{$klGH*U4uWImW$jXoBc}{r=_pJ zfl=Rkc6t>i_Y;MAz!IirR+AbCf5Jzf&tC8J(s)+bmD=yG&2#bJ$rY^z%+VLd^u`Mu z>o5!3q3>2+r5Kf$zCEYU;7EVamsRPsFs1bu`**v6!bv6#I{34PtwJexjf{Jt?GT!` zGKc!foe<*NiGIv|^ygFbr#~YYtSwrqI@GkJ1z0nEKxG95drf8q2trxRyh0D_P<})|RMrAef4E@({9$ylGUy<}&lOowdF|`yzPa{(tvMfd1TA&_*Ii(^ ze$k0gG*G@ZmDv{Bfoyt{C;EYWnUCYqGa}yrpwl~LW=#9udBv0mnR2c5N}_dZ)Byih zs|Tp04zif+2+>aVHDMZIf4<8_?g(wd6T8|0@BM`DKJEQv_k(||13XLDZuB+q#FmzK zIYaUHkz2KeL=KLLoBqU?`fybBhqNzhysE~x+FkWg3g74tR3(V!y#8RB;Edj0o&k;# zg|Wh8}+pqI9#=^BO?_$$T?6`v`}C6Uq}S5B^I)nG;+i*(p|zy zz`65VbH*L(V zKono9Qpj3=&L=&hf1L`cMaHY~(_T;)Ll(Kk{c*eX_97_0Do4aomIZA9XTM*!%b#F! zJ98wW4va^Kw!yt;@XOt zNkEsC{6c{+2i_Uf_1J4u>~*Y1^Fi$y`AuM3{kFD6JIlA5e}Y++Vwtf=>Q;djnT;f= zoPzjEXQ?6_Gv66{rHy^sqnhD1>mSSR>i#@eB|734uxip_gP*F`a@8&uvTVWwk@2^W zahr7eaTWjM9poq1Ir`0#uftpT=Gate$ffBgJmk8Q*z7PXFZ|%&1ujIR`PjS{~#e@zT+3w8~22U%*|+hC0ZTDppSv2i^5fS*}ZKn=$oSO?XHZwv|!*GE2} zFM=g=4RiQrjPgk*3-ncn)Ze4I#>!$)quWub zzw~L)Tby!%wqKG>K+##p_wS=-?_1Xd*PVKBcE*z!e-+I~@6g^y-%Q5y@5D{N2nL~P zXKcN^3pl14?EZ*Y8~xSm9Ik&tliwUO5=lXCW>_yE8P>y$lT3zk>w}~~Xn$8fN~Gb- zWl|Ftekx(qG8HKI({={zYNW&eQ9<)VcceYiti6YEa$O?pRAhaRMt$mHn+g?0nU zm-iPzVjSolgF1*A zNlQfoch?lKP_eKP<-=lYiJss259%WU{Ct|Le`=*$8v_b=E52_&_j6Tj4(wNdSBkJS zj20Nz9}}eB;M(L7b3V%rwLtQ`4Cr8G60n|&bY1tVTq{NvIR4QfLk|j(y!+DB4tbq% z40iX-`ue)_VTJ04qZ<*#7>VBxdMnUa{JZ~7cu$pzYSY7(iHQtV+5xlEClHX-VexMl ze?|1Uq>{D&v>70n|BSEu|8SZLz{T49Uwx*r<%lkg^0_GV_P!T{9t;VL%lI)6hMozg zNU8(@M@o4?S?z=grD3ylWbaqr7InGEc)|W9LA-`tB-BKLTCCAH^#S=hq=9*Iz6ytm zgxPsMIeF>FzBPXS{<6Dt1jYp54aV7}e?mlnqrin(dRgjR-1*eI*gI@@q7-*oy%Xde zLt$R4q*6ot_E1=J&)3w(vcJV=M8VF2s!WbB*8eLMa+p=2wdX@`eiJs>f<%zJ!aiIE z#sMV~@5BIAlIZ0nBrGSca}P?f$5^U2Hi*T9hUcxdoE}>o>y~FY&c=BJf78=!e=tP@ z3>u-2M~c&4;&I9nz)DJaHwHw67t18 zAp&Jqo|OQt7}G-EPJI{kb8&Zf&H!x|m-Aq62hUjC*A@Ei*5OQ~7YXO5p*cXGCk#G# z$Mzwg@Vu)Lqud!ma~?LIm{K?Cf5I1miVBBns|=0%EyPj4X#jW+AsiZo$S(N0Kvbo& zKjuM;QIG#>rumxSNu~IC%9mc_#2~$RJ^`strGDB*mCIF zTUa%DrTt)i6jP~@TaA8mCK^@i0y>IHzWgYG6+W0iw!T%`zMZ6V&*FPZe+Jt5&O2g% z4UO2YCL5T~A6Jlr(f4hi&>~B-7{c%4>tCy&kE}5-W`2;qXmY)sqSn>iHRd%ei zr+IS42Lvg+!@>OMB@oG46pb_w-+w1+U1wU?G&t+qAfv~8yEZkWQ+7UnG)2^Eb_&^v z@>fBSnSrICsg0K(m_d%W=Mis$FQ$@^GPBqPoLV~K$O zH#$p||M>Vn&shIw4hW6zQi2pk3>gZnMS(3S4x*!!7nKf0f02=Sm%z^3(oe6Qu^`;I zl-ymQ@d6`)-zg-)kg4Nnepq48{c%MMHd*U9O`heGzV_a3Rg{9}*NiYJ*~wv->^;d_ zR8Hu5tu`y4hG&O{Y~gTX=jP*6W_cdfgSBHNX(*>=0GDt+a3zPMP-HLgBWxJ&minQn z0S&p5E1Bi!e<)6z(A#_>WN+=~9z9c5`$g9DkM?DoTdRpP9g}NE8aE& zm4_M4?}w$1rqV|$FCtB2%YE1Q|LP}cRC^;^2rw`i=>NvX<$w4|!`#mNKgh$p|JTMv z-B9^INHHK85!Q-T;^5)sl4HfDU*fMd2pSW>t~zM^9XM)Dz|r}Cmc;MeNYp@&t46C;ciI3oSI|+NX zF=J}ie^XZ&IOAj4ZO{+Z>eU!}@T=w9lDFtFO4)fF}<@wrQ{ z?ZtC40dm60GDsh*nEYnY=-x-;R=#KKZ%8OMLq}ML*VcrxDl9-GxM#sC{*C5KMD269 zK<;|P8MG32Z(vR9|jdm*2|{Da9vBi*n!h2hOXN ze|+UQs89Vu%b6uEAVyI5B6nk&%ao5-9k2QE%fE08MeCS=b(==(#BCQUsZJ^$K-gCF zjDm}(PVfbOR#fjCSSOSvkGAI47(wC~jUXw9l5C)=>U?HU~>96N@711alyf{Ow^JG(fqv3Ib%fRkW52qRFg?O-Py9=eEd$q z>0n)UK-mx-Z(PhTG^xGj>=6i~e+96$(zD8+aH=f41fCnUaTO=mjYm8B&qLrW39a1ZvEFP~~MLgbPe{t}D2PmXK zszTTMfwcUWN|I22EB2|J4)g(k(bIgv8*Qo6;IbYYDcfpDcjfnQ>s(P?jRvuQo&^T# zKYJQCcL#G9S7r%-tCfi(z{Tu;5lH=S@~91^e^SdQ5KFEF0fWx!qwupua~Z9zFAW88 zrYIbI7U8O74ep;r%)s7Yf9!|u5B^&*8jaZx?8hLt%2X9}Oi6?to2$!Y&Yk~}V|T#U zJM>>VErDoKZIR6(9x5CyaZXrdHKKR|C_VRNq-3l>9*nw}Bsqv=L=9yqdt8K?mPAH1 z94ew=oz*bJHlITEeu_wFFCn>WTrGm46KdQvM8!B*Q%#`FoQ@T`f52|ZmZrfImxf(a zB#xZ_ET|PrUjU$E6FYp`Pw(}<=0DNLVF6F`mNq~jZp$IKA_j<#ehOApoENaEWYXMg zGogsxw^h@7V6WrmBTD``In-%e`m?`yL&Imu#eO69PKYUQl%=|UQjqm5KRJxdcHQ;J zX=KR!h=qKjMsozjet@YTH8{oMi{Ah zlJxQ?IQ7T1_@v5)tSSAs0`i!mvIicm6#a4&xpGb$uCMd6f1L1s53!ehQz4S(74_!T zlf{@T+vM5qmnj3ormiZg(-aEB8N@0)gBo|_bZ%Iic?!F``WUg!2OF`D$lR$rOei36hH0Nv6{+M! zU({q_FB|b3f4*#iK{?FPviO6Ae!~Rw+ji;IgdR4C;6>$s4NJn|aR-urnuAxQ|E#O} z-(mTGNGfW$|G%2u#abtx7?LPo?y%_uioak(G7mOGO#7;#P>1nExS$enFfh-vFYJKh zO3dtCJJ;RUA{dT;-})1u?nNp5t{as9ysrEVdFnq+e@B8d4hi*l>?p0QIIB5*-OH8# z1FjR}xOjL*AF>CGLqyr)r*`Q3#U-C*k3uOad2@kx-7bcvD=G8GuOa=`sKX?H zA6;UfZ7I?X&es&==6FMHY}_QfHL!TMxfah;hiSn$ zeNc)w)>E+@g~e{{?KP%oqv?ir7i_VW z+{=nY>|WxiQJkkA+Fap9{D@Cl^lb>f9HJwqc0oMAzf4ErSVxHf1no`BE^ped?NcYf ze+p-ElBQKxHD5O#9uob4&_ZHci!sK)a3qr#;nMDgNh3#=$ZFmL`Zl3|oez07x%6YYfNgCP{2Gbt=|^Cz`3KapnaH&X8<6 z(cNs4uj0NTV2Gu&g0}uTGneJiH;_@^e~~o=tD%An5bx#hK~&MLpr@ zWPBER&^PNXTPRetF1*^S>%B0JF5T9met``k7ts_NtQ0z{V z?veb==7q1O1aGyudNxUT*;E&}DVv>@NTKYrvQ9;!HjAo(jTnBp^P9yGLrJjWWSiH* zA0+h2vf5#d#q=)b33`nZv7rpo%mhG6%Jt$b4AGWG+I2*F2Tcbz(xmloOJblt_Jq`A zx6J%?trzkVkz0aqqIeob=HFEle-Y#~`kysiF`|{JZ*_4IuX6P!=moj? zzUh0IopL!ND!Z)VUJ(H_@tvf)F?(Jcy>KAzYpNHA)EuH1@EFb~w$s`uC;yk$E@TDu9{0`) zn^dv_&XR_uw>*zl4EKk>C249(Kq{E>qf8VcpEIkQkRl3(cmm~wS|xVM-Vs1 zP)uR!(q$oQ$#7e{I;Nj~e>2}9%K>n0EXEh7#2rK6V&ALXafW<6e$;Bo6Fly(Ez$HKA8`))P-#Tn<*O$cojMlnm zHjW6j|0F?wAEI~&f23CM_%dc@TWP@LHK|uhOuNC?sIGrE*`uySKSY(7s5_|+v z6h96+YcH+!-o9O*Q*_Gwuqg_O;#n+Z+HDfeB0$&Gd~%3?)jNJGH0TD>-43tNcSrQ3 zvB12kDBB7$C=~K~^M$&?SeRfzJ0o+Z;w+jFd6)=!%o+Qle;|~*GWW`JjOBYQ-@%rPE5b<(enOj#)a;j-HEgjiP{cUF7)?yHwtIYC zfoQywyYq<(rOLOd>2g(1v|10laWymv5zeZ50Mp*Sx?|CQ%TwOI$8~EwP6UnQ?-T1) z_uHi4(YouG>*Y_E-T4`5a0W~DcbZ?)qNLKOk+><+e-ma_o_g}r?6~#g4s#J1DXlU`bOg+Z)j}21s-+#?rH@_b`Ci z#w~Q%>h?IWF`KLLZ&VV^@jxlzX&V@ne-IODDDVC6>x)d(7K06i>c7xHylG=9yLe|s z6V#!m5A0Rp21)#xlX_Z}#zK8IZE8_e1L?)Ae-oD%Tq9mIHh6+Q0`sN1?Tgtc`HLJ8 zC#sAyqI?A)Yj0;x?>#Fm10F*%fRuabpH>H?^`8Uo)hmI-ceN^HRYCbxWWI86G4Cf% z3@(*i1ju6_nkMlu_{MHon z7)RT69aiqo851}(q7Wn28AsnfPajfhV{sO>JHbPJBu1$^>jWxVT?_%B$~+CP;a+I9 zen-cGjI^O;MM~)q54%*5TDc;W zyo!RdOtCk6MOXXFhgfgAA}_`i-6(@z=V)xzsd1oaoMuZ3eBJC4RV(;-;ngi7wV*^s z-=A9i0$Tm27-bWup_WsGH4Z1JTF!_0&8}$>l=eLf1ZS0 zPLWoiCpw*Bgl`0tx<##@ITsXOWpue=08?ONm^AotEV84%fQ>ofaAUC-*Iqa9z=}zu z{PxIsK_9YwJ!|oc5hG%o)jV6#1;Pcij7)16U2bU%R*0$;Ik;e$sG+fXR(0M!CLtf5 z8mX+n&|)z|y7dv3QZj)XHfA(8f6(H&PKXAG&QR>8iw4h4NI6=wY#4dEq(oRq8uk2)4= z?#D$2ztmt(ffcx{n!Bp*3YzM0J>@pckF4X4GahgYO8R0K+;epK@@2g&e{(lRXxxbu zZuEViS0ZVcc&*~$8#-<8&-Eu%E?1!R9CTCfbXH?A<@_>@3F`Rks$%zv2VMR{6i&Jq zXJ4;kqp!Zbo#WZDilThAwydOqJUnOdz)kEr#&cHn`UCb9E zMbGdFw`q4-gJZ>3!yZBcf5*XW#5pO+KU*b{a$qbRedqIuy$g+^hadX9o4^)zLT7U6 z+G;09CF}icf~y26d4<#j&b0^CFth#AC#Q8vVa0_D%wL?FYC%R{pp|BfNfA}lOnnI4b<1a4V zMB&jJR^7NLywx-Anq>SBs3B3@;}b29C|wV_CxXAF`&w6}`bW3Fq07(N3BGTO@^SA9 zUZ`p2yt9PR1s%2d?)D}{6ePwgmN2G-M(7Jfi^Ie45cL3nl8HLCM7v2z@Up9yO0&mz|9VX3a3;N$+{bbGH<%UC8| z6n_)gM(^qTf4V7iOxir6+rhE1L;dv0!iB&{ThXFYyPT(IcgKFADQyhMSq)eh3$;5t zX0=*hrcXFBoNoC<{jwQKGila(nYI~Lr6jK#^sKZ>#Oh%omvX5^w=-X=HV}JRz{G@2 za&>A&w#59#Ki-Imso0*C%daX>aR9`%Xpu)t#4v2He@-m$>0`uRM;R7q@C>L z7r=sWLn`Ecj~NdXR3O@5nLDW;fZ@T+NW{7ae=p0NWx}A~O8J6Y`Q5SFQMVWw`N+ep zf=R%16?a&riMrr)Ak<2ZCSBrkUJ`Q#9F*NuN)7gTAr-2^{AONZ3E|$YOBQkk^z(D$Hj4z{S=)`}IMQ9|B&@Y2DILrpa ze+OUS7p6Hp@6V|&uRMj3Oa_AfZ3+1AyIejGskA+F6~v5wpuq1>sn z7$*dS%mRgbuGjOfVFu$e6aP0{jzTdS2I9x?vyPmjb%;v^FbJyB?5GT4 z@S3fdQO@7|yAVis0rF15vV!3U5;9sUc3Qj6dN&vk4^w$qQzo1%ZKz*V8aWbz^djV$ zQrRC29ITjU%bYq>K~@$E%fnivy%{ru9wzAWXwnTcJ+IRvmxC4_#O~GK0rb9ze{0Kd zc9zPaHn3Hp13 z_cQj0cO1Zc-#qK~SeT*%Wz>3ACO+s_kS6@0x4_>A=DdkJGA%C*fe!(!to~jIubVCQ z2<|OKdXfBfFR0zPOnJ7^0f&GIe=_>1HeN5Zsg9SyYhfSXp1~*{^SwrlUWn0Axxutj z2QEDwQu>u_JHj(UEt+@|0vii zt1&6S6osn~&Xmo-zJKuDf904$S?=}n8d@CxmjjZAgSh-Pbx*}G2K!k{FIoVFhebC9yiKgE!df9V}#v{^Ogw-DmD z?~F7=gw>Ftl<{jZ96fIMwo##1mb<#!Rm~cCp00iktYgw0_`T?I!%la?YRQ0rPIS3;4^w7p$UhIY(h+c@Mhl$ghZTUz6y)m&arF<0$9^KdNS9moqM~=Fne-y zmL<-=#qi2)qlnw^e;r^HCV(sRzk`VR+*c^dMffo(&yeHG{eGgqIfnqAB}PY{6}Qlp zPHGw&r(@xOgzU7IlXnD+*>>Gd)-`c$Ia3xu)KJuzvk3SiCHmzJG z;}3O?u0PcIu{pJUQ0905fWbl8KK{3_v8ieKR#S5e%ZoEo<)Zkh@>c?~%#BkggiQAc>JbYy z^N+}jVV5a!X9wcJgEOWp{%@rg->obD;zaD8Zk#+-TC z;0#1IdlO>5f2$hfc&}RH;wIZ@a8!=i#t&=bG*h#qxBY}KQY=ojH|UqEv}QMO1)hD) zHWDWJod9XhCYo-7u-t7-<$f8mvKTZuPZ%55x6j7LMi{Z&pK%Fs-d9TqGq*~UVjPbJ z$C(}Ni3-@&^oN!iq1mJlt$+^A(wDSaZztLm&u1!ye`vG)L_@il|BboKeJNAOFz=?wUVQcaqChQd>H9o>aZbJ$CtchxThfCa#r_I3c$uqNLRCv z=D^MRe;AgPxm%-%EGyc*#jKVj`F*la#!mJJ3GzH|Eo-k#JtDgOSy=X{I;j5S)?ZS4h~Y6ZCc8N3S#WY};ow0cSZZ_Xh>U_8rk>yFR-Tg2Gc7nX zd8w5TX?pgvIw`-uK))c3Bu?=T?Q2c_e_8C(Jx*(B)4z>{|Z?_4L~y}+E(nSG7vTdy3CtP6Ef zCu_1|qcuFUT*vJnh)Ui?V@7fFQBG;|XtNHGIqeiO)nN-Yi4wfBPdn?x?#ayxTLInQ z%H$M0P-bnQ=$#=Tn&#vtRF-)3xErsm!$OwwRK?fqf&K zaWf|8ECkAji+N~bxdgyJ#8?6LeY5ogk+SB#h?wjK018JNQ-+^&bX|A&(b^*lIi$qF zrokf$*Wz0ZRNf7SCsKjplTIWnOG02G&smVhWEA68he}Ar;OHPo@GpdrE62NfOF5x+Uqp-k>bMLe-T*1be9ZgYg z_N{LCkcTsp$<6k7#|x|r5h-fBI0^2zHeQkza06i>(~@LjG+77~a3F`-hQ_l&&p5>L zF;~GtwC@G`ojs{CvviqOnGtSC@l3o#p0>8DN>;Mw`^(@slYgW`e=uVeNh`Q^BVusU zPB#iv0v;j=qih%-+nh<9b!8cQJ;n>x8qt=87i1bzCCnrh>HtS~+nOk^M`3`EsiowB z%vuFEL>_SlH~fNVhlDJRMSbkA)2Uq~UZm!{g8=NgMnu{$Yt05t{&k~@O~jrVMl)%t z-blrT&yxl}*9ISVe~zv=F1NZ*4Xkm|P2Kx8l|om{3L2Wfk>e9$kc?zFDfnG0cyRL{ zeNuVn!Rd`zI55>L*@UVxC*QK-w?m@}yWG!u#3}UppIB_#z*HP9#TDAB6Ls@>`idyd z3jI&Kp)(w6<-~h@5@OSyKBMwR!V&X?*$Y%rkILYscJ0=Ze^u)v3Jqy&dj7Y12`E@jr3}#rS zLd=QWd;ee$K2fRKqEG2sgr1wsdq$)dcgwcjQf9H!5rmo9W!W^*2u5)w~_|w_} zX1a%NHRehk&adOfqOkob5#Sn~AFKtr5X+&kJtK=~2-FNQ1s|nM62^CT0fx^tfSC52 zwMcw?j-Ya~C!PrMjnZO#oR17pnU5snc7Er8=RUr^3u9sj`IXgD)#Y^C(%7BRw4PaO z2FE02e_t$1G^jH^ssSHWk-ybq!ZfSSZGu?w76Gl-QWL&Uk=V$>A ze}^ESSCHoUaP#W^^xJpqee3EIcAKSUNF~$;nv>2(b;xPi31Osxa-*a!?tVRs9&u?; zR%nb6(BZ&(f`w2sl1MwY)1FFOV%?+SIq$-7697DI?)Sn#mB8%Rm=`zap^$uiF(Dae zdpC=J>qRPxOz0C7PG{YKz}|F4Pocfle{CC5$z2k3ReJK$V`g(JUTj-p)4YAA^L9i; zveKy49N^+$y|4NSzRKQur9bKBGVDs2zedX~{n%f`o8q8OXqqUk&nU;|)8LYL= z?De+)V94X>Q~;*E3=2ogY4?;Mpbhj}w>zhyO_te5PV`%PGwT>|!!*VIl$xRRSPxXT zT#^?Ba57D(cfFLzarNa5(3YUYe+6>W&|NtPSOUJ`=uI9s_{=WSD!ip`0jBQ^n1MtZ zV_|$%yQ%_%D9Olh&$OxPHQd=*^#U&Wd)SPz7)o$^i&a9>N*-?f*CKxx@Ow}ry{0hR zw{IW?k9K?MoP-@(DZ{Kf5Z5>@4jFPi2PJd(Z^+;t_S$>|B8;G=H3gu>e*%N?wH4|r zGD{>dfo}RX3)`$as;~D{TmXeij3xT3#nJ-eA=pwm$wWj1r&EpSO+|H98fWF~IY!of zA5*cX5CI%5X9E|GR`C9q=MNxB%Sd6Vrk@HCr`~6pQ&i!*U4-A5;z?Lzq-7i+T;UAb zXkO99Xt(B=m0(tF`6p~4fBc|^nfdh9A88@E5Cg=$G?ian9(X`4fnQBP;O#{ za``i?kenmnj+T}7F2Ew;y%)H@V~v?;`yG~KXf2@B@ZLpP~I}~Rp z--*zxct_&Ps3ykno+mYM%s><6j|o8u1R-4~OcZ^2>4-?3RPqO)v}gEj@?su|e3pMV z^{E=Br1IG8(qRnC^lMSxPJ|aK-kqD3_kYs=g<}KR3o9fKu3GNrENW~rbnWdY+Jmj> z2RAj>S3}i$m;yUVfBR+W-qFvlj>x~-C}G1W8aMPq>ju-0vmag&o3C%5uy!{kTj3Is zyZ><7RN`7J??DpI78}QBjVo3R)z2_U7J7ZpwSFO@06$fuli@7{7@Z>f-9lPfNh#WD zWe?scze|&UwtaZ%!F)1HS-^MS4I{f1Lz16qKxME6!%u&}e-lDN&m5<=+=NZQ*d^D& zx+Vz;f=9I=I3qC6*)}QFw?t#unYr?tgOywx&>{9LhjJ--0x!NL{A9*6;@#c1&8R}o zXhhcmvn8$NNPP)dAMrc_VG6{n9$g@lM(UXL8ys9uu)HRfzZ8C+%yb(&0xa{&HAPpf zwjStH6l^)0e>EjmLxUgrtlWWMc%W$7Rbs?n`fL4le+a1H{JyVin#<8IK-Ll@t%moM zjpf^&rf@=g!Za}T@=J`D#EuIN3Y{2(w3h^fFWim0RvKK3<~_|PEv6SU zTPyyfo0tcywWaCVr%cbHYJt<_7X9Ba;AG_6e+ML99tmNds!-=r?4b+d7&^Yk%rRZ_ zSB+{{b+H+t9~w;PH2IL&um?;92!AM(3<`vvkO=;6Im0^6OfCN0Wqn7GzIGG{%=AiF z*ru`lt8Rx~ekn!FFJ|S12ss`yNPt)$g=1ol*dS~i@`0(`@JICKyH{IAG9hRf`{0X@{nQ_Hy^IMT1!06SV%^-q^km4%wRVO-t}=m&0}$ zVGjtzM7hs={Tr2Pl#z1PAS@WzUsNzKq5ldZtAD$>04&V^Z!1)7Z!ZH)%&!fFgj5A0 zStRSs>DBH<5%zquc2%pAkRn_$bt*+g6FSVE%=FCkrO8fifBDsUBvjEJ%=@z?Ivo{; zf`WM}#WJmR%qM^C_0K!UKi`GQbM7omN+?dGx|v;5Jui8Wat=Hv{XfqeEWzx0g?nkl zWq-umK=2yyc5z_uDpVm2`!M-zRH>cF5!~2cM3U0o z3cU|}JV@s57!O)!M5p2l>1q<_DhW=~n}0d`iJ@xZMpgv1jh#)1((6Vik)eJvJj)Rx z=`g6A$x>H$0+O2&OSqXxcHh0rK~fxW^JYbfd?bVm)OQd|lvpgIh?;J14BiaU<~lVy zO?+C$#edsFucUot586wTL61Dm2P1a9M5Ly`m6Ve4j4-RZnuCNQX<()7Cmmts4S!!? zdy*-r++p`(d4*xkPTvIJ53!4SLdTu){)NhoC!8uBjnoubY*1*5qzA>}qT)jA8vBFb ziA=CgE62sf%`i1Q488;W%eKOqanYt#NgBTZLZ8Vj*sFf((XP}x*5%yr5&XbT9hcW) zwMau!x!{kj42g%RIMXnNR`A1e9)F-viPp7Cv*+wYCF$F(La$FuvP* zI3vUY5v8<}H*)AxNytS}VPT0luz9`nB+jSMsGg(edjdT}dJOVJR-|<}90QUI9X+iK zEh?>6%Zmk9aTd!eY6V2``)htQ8-&y#IC~~1!4{jq+O^k`f~7!T3k^Ba9Dh3jWg_kY zo?o-NGk2}(i}f*(*cAR#!+)+;IEA2W1OwE5O3EB-+*vtX0^m8NwaWJ4TE#U?V6wkU zE}OxY>R{^yK8D7qO3FnkyM)70xK+zvLc>BL{CK4U*_$SCSMFa{dnl4-st&Xq_>3v{ ze$o~(8gSv#@D-pqo080_QRiebxE6$}70Fc3n9IP=9??FJXr^GDB7buwT<>(Y#fHVe z$@3)clU7K_5}MmP+LQ9U&vQ6+wDsaWMuVw)$k}@zJIgq*+|w!81Uxl93@K==WG}$_ zg9ZqqCm}`9><~W7!)evhEp1tz1x+VTqN#uHW|#$G}>e1 zly8oZ!u;EOKrV?`aeuGVw#~K9)o4^TvS_#G8mJW6B`EfU=T~qM1AeGoy%C9v=zMFF zi2Sh+tmDEp7op=2|L`)lH;AsN=u0qq%=63(JJ@BQIk0BUVP~ydf2hkZdxLy(-TmA1HbIW|l$MluIWeKP@UywO44jRFMuvO>=sqoVGV)_W z#DXBsC1qO|vi0op7B`9^k#p2C|sAvG(hio?txy=Ze8awhfpR|O)OPopJ-%ZDZ_jDNCD!Sydsp&N+=RfTGjtC%i?CwT+xAx7OLGOA z;I*kls3XU6UG<7hcEv6u8@Uu-Y3b%&9MmG+k)kV}dzrL}AxZE5r?oQyhpKx6_z=oY zjZl1+)PG0Wg{;~4u`k(;F)@}QGxn|QCX$MXY$Z#SvSf>73xz0>WJ@VRB2wvpRo^$C z+tBDA&pf=B=ltHYyzf2d+->AUdu<{umllaz? z{)) zLbZH&4a=OdPu=OQnf%=4;boZv)}$h|AvN3V1j>(*UBK*;q77lJ7!ln~T17#>YsK47 z);~`e=C zviXNU^QJo&^5Xb2?kH1>$o@4;EooY)DRzu!@OZrV@GSJylMhgNshGdLJ7@C;vwuZi z^T-d_3>wSD32kGm_e{UY;7ix?v?0!7M^L&B`r)asixJJ-3-e#RJv=a9%yx_0OT}G} z(2B!+p3rQvZ!s{NFWO5Vh+ zQN_Y0xIeZ03EuQZ>9ov_DH;iVVSm@g_#3QsS(2TH^Dlj6wqKGgA60!8UNSFDnPv1S zOS@3P3fqOqqL$0vI-n}#uSy{k9v@z@Ri>$7f;nE_JtVetICC=7d!KU7^42A;yDDo#ZR$o5FGVWgLmj=t|G5b)XE^Dq#p#`(&mVz#65T_28>w$bSUVl?LUz zytgoz(WNbV^p#@QSJJx6#~3euVJZrK+pQWrIqI_%%RH?RPz}@L9WxjP|3-zoVzOzlt>1hdXF7FQ$lNTOa z%KjSberoBWn?=#is3cuXNBY3b;$X+(Mcb9nBkB*Q^v(}p z^V;ui&#WxVX=!k3Z$eqF2tCuVJ=(8o?Q2+-mkRH+5ZuM{cPmWb zrc}Z4Yp5CNnu^~JJu{$b>l!UDVycvI z^tGvkHVHqFy4#0)f1!pF`pO^;Zg){6t+B`OYzfVvi__dtindF?DaDIuTx@K!)6ofR zh+rbenI{4UX?x-yR3>$np{6~hQWC?ZA|tnQTPby3^?%)`z_I(m6`rb4%I$s#HS4Od z^SnntquP7;g>bKUFYUSjs!>MV}B(US3ONP*!rr3$(7M2v2ut_F>!cYr2t_TX|t$_3W*$HuGq@ z+?wJyyKa5;?2zZVv+8|_I1|l8mSn|6S7k^$sm5u|w!BFa^RaR*mb1ae0{#-)OiWPJ zA3M{sw9Ldq_z$#QYmF+pqj**4nc#Ig3vbJcCrRB-zX%Pqy3IXF<9_#}(S)xf0ZTJiPB|Qc%inmCFi8W(I17YPg?LET(o?D zOMkz%A&GoSL(;7H6NS<(G-60)G(no}NMn6MFF9L5W~KN;8^snktUyuYq(>m*-=c2y z&NpG#K0IsIw1CMnRfes^TxeAA=03;LrW?K^x8$UTSJWG2Y7H}Ci$Tfq=y%h_X|fzT zHpv=RIp^ndwM zzJGDiCNR>)H|0etNy`CWCNBHk4KDLc`)YY?a*vU@cYkci`?y603Y})WksSe`Gm3ND@r7q4VZ%7S0(>)OZf!EgBW@DzsNy7 z4HeE&h@eQ;usChcM1HJfaG&BlSwEQ_fK`qrprtEH8CcoS3>Sx*w-= zLMdvGXFptL)+O6BlfbBH*?)8EYNd9%qbu|+1uLtoh-e{#>=MPFEVF*1Cj4O zM*25v!OLF$7Dv+DrvbW518kp^+MOgKq20SgrJEDnY`Lf{SITaV4}V>U!P?r|soT>| zX~KIgQqrJRDE3_M*H^-)5$ulM*q*ZqdR@!WO&IB;K09+S*ORj|`$(mny8opT>B0Jb z*PQgV;eycgiy!O?n9jH^MK*Ay=#B5egv5OblF5KMEg35|V_hoMBKQ)mh9q`ZRz04z zZZ+(;$JIJo#yx}Gf`7xrZjs`$w=h3Jw+6}!wY`Z9wQ}T`^ltEG@AWTwJ}=;Iu1o3g z+#24xxYMo0!nIc`$!CDqBwxxHYu?-*>3GsF)A$PxmYs{6VR1}qa;@s98h0!6C=U{V z8oE8Es&b85fwD~(U%MbmpL3_dr>S|%Rqw=iVIDqTGm@sm1%Iu)IQDB`MfcR;tY5y) zn0iDK;D1E+ZTTnpm6y&wP35u;Vh46pQP>{Ni(Br6!=`S?3<-XSdz^ah?NSMIMBm=( zDVAU(S=#GU^sg<0u1Ke0vS1y~uylBMnawdXsMWyrx0VK0&u8AXx0vN_ckwWp8|=VU znETvRYf@I6&wmdM{Cnq6R^MyC`MUJe{LAV!b2Ue3arIXlPrBb1th4`^#$h!_i*c*Z z+Zw@WX%A27HL=uLww-xIS=kK?uHyQXUt7M1)19d_J!XMbD%W&YlRa&&ga-0^vzLS&fG zYz`T;g*{L;-XOT{ieMv)&oQBBxWYK|1hqZ?6|u2?SYt^*7>|>DxD8D^=j)`0-lydQ z!#;^7$OmfkH4YAnS|yKdYY2C!$kj3Sm6_WfMsuDQotwl;@8f3g^jYe8XY>;|YryGG zm8s89iGL;_R74^TYJ+^X%Wb!d_H?J*C(;<>tGdsbe7?NblrIr!$`sQ|C;a6e3wPU* z<0z3kSY4Q7)T0E0>|KVG2dbHSDW&CG!_V^URXvWPoW!>GONb+UIX^OY@5(vNW2ive zBO#boP@PGqnKuG)PSlUT)LY3dntJGinyOBh-hZh%hbWxKFa?tV{r*uI-y)VabLW7H zNlpJ996QB26JCgq?DWkz(;eG3QVKoWS~jQS0CAK`MWMF8vG8--*VgKnuaT!Dwqy4l zEA9)?JoZSR9p`()=X=Dk^utd(^#ks+e%VXq<8-mhc6gbtrzPe}(`(k9L*}A#dsg7X zq<>%S`RArbtM0!`dbY@O?*=u!pET{!N7~bY2UEs`{j75@cL&Ez!n{Yw?~gF%@CL!` z!VF{oq8}C6%Rba&M3rSGD*@Y4XM7|uGu$>tZK#NfQoP|LVrj%yUz>y!vIXyqY3bE% z^++I)Dd2Meg8wQ%0ol+sD|w+@9sV0Y0DoL?;a2_F(}35PrTl&(7GH2O$wmdkT^-#$ zQCKH8jF2|m)eVkTL%CxA*~bJ!bk4sK_zXxLK#>Y-AVCzr0Rd(70@JJ;KG4OHLLgdX z-(RA^)B3g&Nz-xn(FaQ2s7^i-!bOe%p&uwya1Eu3ib#sSrV8P*8xkE$@`1JrB!B&W z>&2JtMo(nfMsDuzSSKSa(t|J}A*{aO5+KiS1ve6kaU+BS(i??9VuaM;Zb%Qf!!No5 zZGl1PZG%93pb&`Y8j3yBCMeoSKf>j|Y-n2P02)aG7)CN{$|w12bLIb{BD%Po=JP<0 zcmh4Hwg$w@wIRq8<&Ct5V*nQ7`+o^?*Kg-{S1&97dx0=BkP3I67ck2NRtQ964Rg<) z-(bR!2sqly?N?Nh?uN#aQS{98yG%rC^QNK{Il`*tAwf7xqnWYUIAob zz${GHP?M!LOI3GQ0^B=XABFaCN1?IbMwKUz%D2I7goR_hFobpR&V{0m176K(VNEfF8R6^R-^1M}fkh(c{O}f8K-9cXwE) zNu;G>CO!eiod!5>!!@c@Du4eORSc1i!01?SSPWKQ7=!~&5l0T@^JxAVz9$mypaRFj z3G;JGwPQX3Hy7^x-}ArY`3u^AgijcIq#|{<*Q!sYg+R>LV9l)lPwWpXEeJIaG>|K)~KNj|1)Y3=Bk?JJk0@mykR>8Vz7ogjNB~uhkt+HOtmlVNZdQH zIspJ~&q{0X^Dh4%o-j|XWapR^Am5<)p5_G46T)tm_m4>vCdpmc0to;bwg#BYSgj%5 z_1P@R*vS)#G;=~CUH@Tjrj3=tY2`|RHcs0Cfxy;iax3VMX+jvi%g4B~29S(Mz@xf1 zV$5cdMNllrXIa%kdOOs_wkt$l83AJ z^EqHrtGz~#fm44-55nNH+D|MF0Dg;}>ig>_crf-nkzk)y*uUoc4NaIej(pFo58R+W7OxNYgn#=Tp#e+~Q0R5`30jN4Hk$#YVtTL}8^2043G1{vCx@fZfL*PT zHnc7V$;NxSbBlimz0Q#9uVDWINQETe3dUD%f}#d2INX8p&7#RX9R{ak8zi*dqOn!9J%(@;J{_<>K$7NUZJLLZg z8}_LQUG$riz?|Q?|~ z$O)K)*qY*H`iU&w6j&X(d#(qluT|5>03P=h+4o21|7oP5jQ~zR62l4oSOFXRd933< z#H$$67l2WxvIXov^hSv!tY*E?L7`oc4$6k#QlbzhF^#DkkpX>i59oC1HKgr~2HCU7PL}87PXv}(TH}6c5G6&S@1r>NeOV1M-#!?ySiM03h zaw81rE>pa*07!l$;LZv9NG#ynUiL3`>+YnTeSZzO5y);5@UU)MCX%D(xq7?!7LJqW zTRy*anoR5P948%Mp6uW`#Kfn~lL#}w$szF!D=L!zD^(k$C);dB+LM(9KbWkIf!HsNI(FlfMfLIDbk!oQhtuu|I>~$C2RX)L_;`uL{2cNa3;~Dh#X}nTHiB#zycY}s2VccQ zEcuCn5I)KQrhtR(;VBPAiJ)v8dJhZ($81)?!}R2chy4_31&jelE5KtMl!(Br6T9H2 zCzYT>uXswB1`(9?j=+L3;FCOf43j<)m<`YMfLY*oV(~0Vb0Sy--jMz2!7J$HEj(e? zW+TD|uX5>YlT)k~p#yxM Date: Thu, 4 Dec 2025 20:56:42 -0800 Subject: [PATCH 02/25] control --- .../org/firstinspires/ftc/teamcode/TestAuto.java | 14 ++++++-------- .../ftc/teamcode/constants/Constants.java | 9 +++------ 2 files changed, 9 insertions(+), 14 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java index 2fc59cb..6f2217b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java @@ -26,10 +26,8 @@ public class TestAuto extends BaseRobot { private PathChain forwards; private PathChain forwards_again; - public static double forward_dist = 27; - enum AutoState { - MOVING_1 (Double.POSITIVE_INFINITY), + MOVING_1 (2.0), MOVING_2 (10.0), DONE (Double.POSITIVE_INFINITY); @@ -80,16 +78,16 @@ public void start() { forwards = follower.pathBuilder() .setGlobalDeceleration() .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) - .setLinearHeadingInterpolation(0, -0.22) + .setLinearHeadingInterpolation(0, -0.36) .build(); forwards_again = follower.pathBuilder() .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(4, 0), new Pose(forward_dist, 0))) - .setLinearHeadingInterpolation(-0.22, -Math.PI/2) + .addPath(new BezierLine(new Pose(4, 0), new Pose(27, 0))) + .setLinearHeadingInterpolation(-0.36, -Math.PI/2) .build(); - follower.followPath(forwards); + follower.followPath(forwards, true); outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); @@ -110,7 +108,7 @@ public void loop() { draw(); - if (!follower.isBusy() || ((System.nanoTime() - state_start) / 1E9) > autoState.timer) { + if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { switch (autoState) { case MOVING_1: FrontalLobe.useMacro("outtake"); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java index 25cb2fe..65d51c9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java @@ -49,14 +49,11 @@ public static Follower createFollower(HardwareMap hardwareMap) { .useSecondaryTranslationalPIDF(true) .headingPIDFSwitch(0.2) - .headingPIDFCoefficients(new PIDFCoefficients(1.6, 0, 0, 0)) - .secondaryHeadingPIDFCoefficients(new PIDFCoefficients(0.8, 0, 0, 0)) + .headingPIDFCoefficients(new PIDFCoefficients(0.8, 0, 0, 0)) + .secondaryHeadingPIDFCoefficients(new PIDFCoefficients(1.6, 0, 0, 0)) - .drivePIDFSwitch(2) .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0.01, 0.6, 0.0)) - .secondaryDrivePIDFCoefficients(new FilteredPIDFCoefficients(0.0, 0, 0.01, 0.6, 0.0)) - - .turnHeadingErrorThreshold(0.05) + .secondaryDrivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0.01, 0.6, 0.0)) .mass(7.7); // 7.7kg == 17lbs From be92918f0024e7f92d0334eddeca9d6f38f565e8 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Fri, 5 Dec 2025 20:03:44 -0800 Subject: [PATCH 03/25] kinda close ? --- .../ftc/teamcode/AngelaDrive.java | 209 ++++++------ .../org/firstinspires/ftc/teamcode/Drive.java | 156 ++++----- .../ftc/teamcode/PestoFTCConfig.java | 3 +- .../firstinspires/ftc/teamcode/RedAuto.java | 297 ++++++++++++++++++ .../firstinspires/ftc/teamcode/TestAuto.java | 150 --------- .../ftc/teamcode/constants/Constants.java | 5 +- .../ftc/teamcode/subsystems/BaseRobot.java | 40 ++- 7 files changed, 508 insertions(+), 352 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java index 9be2d47..40b611d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java @@ -18,144 +18,141 @@ import java.util.List; -@TeleOp(name = "Robot Oriented") +@TeleOp(name = "Angela Drive") public class AngelaDrive extends BaseRobot { PestoTelemetry pestoTelemetry; @Override - public void init() { + public void runOpMode() { PestoFTCConfig.initializePinpoint = true; PestoFTCConfig.initializeDrive = true; pestoTelemetry = FrontalLobe.pestoTelemetry; - super.init(); - } - - @Override - public void start() { - } - - @Override - public void loop() { - FrontalLobe.update(); - MotorCortex.update(); - gamepadInterface1.update(); - tracker.update(); - pestoTelemetry.clear(); - teleOpController.updateSpeed(gamepad1); - - if (gamepad1.b) { - tracker.reset(); - teleOpController.resetIMU(); - } + super.initialize(); - boolean intaking = gamepad1.right_trigger > 0.05 && -gamepad1.left_stick_y >= -0.1; - boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; - boolean rejecting = !intaking && !outtaking && gamepad1.right_bumper; - boolean neutralizing = !intaking && !outtaking && !rejecting; + waitForStart(); - if (outtaking) { - LLResult result = limelight.getLatestResult(); + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + gamepadInterface1.update(); + tracker.update(); + pestoTelemetry.clear(); + teleOpController.updateSpeed(gamepad1); - List results = result.getFiducialResults(); + if (gamepad1.b) { + tracker.reset(); + teleOpController.resetIMU(); + } - if (result != null && result.isValid() && results.size() > 0 && results.get(0).getFiducialId() != 21) { - double rotate = -result.getTx()*PestoFTCConfig.KP; - rotate = Math.min(1, Math.max(-1, rotate)); + boolean intaking = gamepad1.right_trigger > 0.05 && -gamepad1.left_stick_y >= -0.1; + boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; + boolean rejecting = !intaking && !outtaking && gamepad1.right_bumper; + boolean neutralizing = !intaking && !outtaking && !rejecting; - if (rotate < 0) - rotate -= PestoFTCConfig.STATIC_DRIVE; - else - rotate += PestoFTCConfig.STATIC_DRIVE; + if (outtaking) { + LLResult result = limelight.getLatestResult(); - teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, rotate); - telemetry.addData("tx", result.getTx()); - } else { - telemetry.addLine("No Target :("); - teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - } - } else - teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + List results = result.getFiducialResults(); - if (!outtaking && state == RobotState.OUTTAKE) { - FrontalLobe.removeMacros("outtake"); - } + if (result != null && result.isValid() && results.size() > 0 && results.get(0).getFiducialId() != 21) { + double rotate = -result.getTx()*PestoFTCConfig.KP; + rotate = Math.min(1, Math.max(-1, rotate)); - if (intaking) { - state = RobotState.INTAKE; + if (rotate < 0) + rotate -= PestoFTCConfig.STATIC_DRIVE; + else + rotate += PestoFTCConfig.STATIC_DRIVE; - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, rotate); + telemetry.addData("tx", result.getTx()); + } else { + telemetry.addLine("No Target :("); + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + } + } else + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - if (outtaking && state != RobotState.OUTTAKE) { - state = RobotState.OUTTAKE; + if (!outtaking && state == RobotState.OUTTAKE) { + FrontalLobe.removeMacros("outtake"); + } - FrontalLobe.useMacro("outtake"); - } + if (intaking) { + state = RobotState.INTAKE; - if (rejecting) { - state = RobotState.REJECT; + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); - feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + if (outtaking && state != RobotState.OUTTAKE) { + state = RobotState.OUTTAKE; - if (neutralizing) { - state = RobotState.NEUTRAL; + FrontalLobe.useMacro("outtake"); + } - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + if (rejecting) { + state = RobotState.REJECT; + intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); + feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - // Nice little LED display on the gamepad - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) - gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); + if (neutralizing) { + state = RobotState.NEUTRAL; - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) - gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) - gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); - // Cycle hood modes - if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { - hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { - hoodSubsystem.setState(HoodSubsystem.HoodState.MID); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); + // Nice little LED display on the gamepad + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) + gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) + gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) + gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); + + // Cycle hood modes + if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { + hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { + hoodSubsystem.setState(HoodSubsystem.HoodState.MID); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); + } } - } - feederSubsystem.update(); - hoodSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - indexerSubsystem.update(); + feederSubsystem.update(); + hoodSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + indexerSubsystem.update(); - double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; - double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; - double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; + double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; + double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; + double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; - pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); - pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); - pestoTelemetry.update(); + pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); + pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); + pestoTelemetry.update(); - telemetry.addData("x", tracker.getCurrentPosition().getX()); - telemetry.addData("y", tracker.getCurrentPosition().getY()); - telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); - telemetry.update(); + telemetry.addData("x", tracker.getCurrentPosition().getX()); + telemetry.addData("y", tracker.getCurrentPosition().getY()); + telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.update(); + } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java index 8573dbe..b8ed77c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java @@ -1,6 +1,5 @@ package org.firstinspires.ftc.teamcode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.shprobotics.pestocore.devices.GamepadKey; import com.shprobotics.pestocore.processing.FrontalLobe; import com.shprobotics.pestocore.processing.MotorCortex; @@ -12,106 +11,107 @@ import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; -@TeleOp(name = "Field Oriented") +//@TeleOp(name = "Field Oriented") public class Drive extends BaseRobot { @Override - public void init() { + public void runOpMode() { PestoFTCConfig.initializePinpoint = true; PestoFTCConfig.initializeDrive = true; - super.init(); - } - @Override - public void loop() { - FrontalLobe.update(); - MotorCortex.update(); - gamepadInterface1.update(); - tracker.update(); - - if (gamepad1.b) { - tracker.reset(); - teleOpController.resetIMU(); - } + super.initialize(); - teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + waitForStart(); - boolean intaking = gamepad1.right_trigger > 0.05; - boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; - boolean rejecting = !intaking && !outtaking && gamepad1.a; - boolean neutralizing = !intaking && !outtaking && !rejecting; - - if (!outtaking && state == RobotState.OUTTAKE) { - FrontalLobe.removeMacros("outtake"); - } + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + gamepadInterface1.update(); + tracker.update(); - if (intaking) { - state = RobotState.INTAKE; + if (gamepad1.b) { + tracker.reset(); + teleOpController.resetIMU(); + } - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - if (outtaking && state != RobotState.OUTTAKE) { - state = RobotState.OUTTAKE; + boolean intaking = gamepad1.right_trigger > 0.05; + boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; + boolean rejecting = !intaking && !outtaking && gamepad1.a; + boolean neutralizing = !intaking && !outtaking && !rejecting; - FrontalLobe.useMacro("outtake"); - } + if (!outtaking && state == RobotState.OUTTAKE) { + FrontalLobe.removeMacros("outtake"); + } - if (rejecting) { - state = RobotState.REJECT; + if (intaking) { + state = RobotState.INTAKE; - intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); - feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - if (neutralizing) { - state = RobotState.NEUTRAL; + if (outtaking && state != RobotState.OUTTAKE) { + state = RobotState.OUTTAKE; - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } + FrontalLobe.useMacro("outtake"); + } + if (rejecting) { + state = RobotState.REJECT; + intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); + feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - // Nice little LED display on the gamepad - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) - gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); + if (neutralizing) { + state = RobotState.NEUTRAL; - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) - gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + } - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) - gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); - // Cycle hood modes - if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { - hoodSubsystem.setState(HoodSubsystem.HoodState.MID); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { - hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); + // Nice little LED display on the gamepad + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) + gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) + gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) + gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); + + // Cycle hood modes + if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { + hoodSubsystem.setState(HoodSubsystem.HoodState.MID); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { + hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); + } } - } - feederSubsystem.update(); - hoodSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - indexerSubsystem.update(); + feederSubsystem.update(); + hoodSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + indexerSubsystem.update(); - telemetry.addData("x", tracker.getCurrentPosition().getX()); - telemetry.addData("y", tracker.getCurrentPosition().getY()); - telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); - telemetry.update(); + telemetry.addData("x", tracker.getCurrentPosition().getX()); + telemetry.addData("y", tracker.getCurrentPosition().getY()); + telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.update(); + } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 2b4c8eb..87ed0bd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -52,12 +52,13 @@ public class PestoFTCConfig implements ConfigInterface { public static double HOOD_CLOSE = 0.070; public static double HOOD_MID = 0.1; public static double HOOD_FAR = 0.1131; - public static double HOOD_AUTO_FAR = 0.1131; + public static double HOOD_AUTO_FAR = 0.115; // SHOOTER public static double SHOOTER_CLOSE = 0.70; public static double SHOOTER_MIDDLE = 0.87; public static double SHOOTER_FAR = 1.0; + public static double AUTO_FAR = 1.0; // CAMERA public static double STATIC_DRIVE = 0.05; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java new file mode 100644 index 0000000..00f61ea --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java @@ -0,0 +1,297 @@ +package org.firstinspires.ftc.teamcode; + +import static org.firstinspires.ftc.teamcode.Tuning.draw; +import static org.firstinspires.ftc.teamcode.Tuning.follower; + +import com.acmerobotics.dashboard.config.Config; +import com.bylazar.configurables.PanelsConfigurables; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.constants.Constants; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; + +@Config +@Autonomous(name = "Red Auto - Thanks Angela") +public class RedAuto extends BaseRobot { + private PathChain forwards; + private PathChain forwards_again; + private PathChain intake_1; + private PathChain outtake_1; + private PathChain attack_the_human_move; + private PathChain attack_the_human_go_time; + private PathChain return_to_mama; + + enum AutoState { + MOVING_1 (1.0), + MOVING_2 (2.0), + MOVING_3 (4.0), + MOVING_4 (1.25), + MOVING_5 (3.0), + MOVING_6 (3.0), + MOVING_7 (3.0), + DONE (Double.POSITIVE_INFINITY); + + AutoState(double timer) { + this.timer = timer; + } + + double timer; + } + + AutoState autoState; + long state_start; + long start; + + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = false; + PestoFTCConfig.initializeDrive = false; + super.initialize(); + + follower = Constants.createFollower(hardwareMap); + PanelsConfigurables.INSTANCE.refreshClass(this); + + follower.setStartingPose(new Pose(0, 0)); + + autoState = AutoState.MOVING_1; + + hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); + hoodSubsystem.update(); + + follower.update(); + + follower.activateDrive(); + + follower.setMaxPower(0.7); + + forwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) + .setLinearHeadingInterpolation(0, -0.36) + .build(); + + forwards_again = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(4, 0), new Pose(33, 0))) + .setLinearHeadingInterpolation(-0.38, -Math.PI/2) + .build(); + + intake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(33, 0), new Pose(33, -40))) + .setConstantHeadingInterpolation(-Math.PI/2) + .build(); + + outtake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(33, -40), new Pose(4, 0))) + .setLinearHeadingInterpolation(-Math.PI/2, -0.40) + .build(); + + attack_the_human_move = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, -46.5))) + .setConstantHeadingInterpolation(-Math.PI) + .build(); + + attack_the_human_go_time = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(40, -46.5), new Pose(8, -46.5))) + .setConstantHeadingInterpolation(-Math.PI) + .build(); + + return_to_mama = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(8, -46.5), new Pose(32, 0), new Pose(5, 0))) + .setLinearHeadingInterpolation(-Math.PI, -0.4) + .build(); + + follower.followPath(forwards, true); + + outtakeSubsystem.setPower(PestoFTCConfig.AUTO_FAR); + + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); + telemetry.update(); + + waitForStart(); + + state_start = System.nanoTime(); + + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + + if (autoState != AutoState.DONE) + follower.update(); + + draw(); + + if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { + switch (autoState) { + case MOVING_1: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + autoState = AutoState.MOVING_2; + state_start = System.nanoTime(); + follower.followPath(forwards_again, true); + break; + case MOVING_2: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + autoState = AutoState.MOVING_3; + follower.followPath(intake_1, true); + follower.setMaxPower(0.5); + break; + case MOVING_3: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + autoState = AutoState.MOVING_4; + state_start = System.nanoTime(); + follower.followPath(outtake_1, true); + follower.setMaxPower(1.0); + break; + case MOVING_4: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + follower.followPath(attack_the_human_move, true); + autoState = AutoState.MOVING_5; + break; + case MOVING_5: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + follower.followPath(attack_the_human_go_time, true); + follower.setMaxPower(0.5); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_6; + break; + case MOVING_6: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + follower.followPath(return_to_mama, true); + follower.setMaxPower(1.0); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_7; + break; + case MOVING_7: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + autoState = AutoState.DONE; + break; + } + } + + telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); + telemetry.addData("timer", autoState.timer); + telemetry.addData("state", autoState); + telemetry.update(); + } + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java deleted file mode 100644 index 6f2217b..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TestAuto.java +++ /dev/null @@ -1,150 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.Tuning.draw; -import static org.firstinspires.ftc.teamcode.Tuning.follower; - -import com.acmerobotics.dashboard.config.Config; -import com.bylazar.configurables.PanelsConfigurables; -import com.pedropathing.geometry.BezierLine; -import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.PathChain; -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.constants.Constants; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -@Config -@Autonomous(name = "Hell no") -public class TestAuto extends BaseRobot { - private PathChain forwards; - private PathChain forwards_again; - - enum AutoState { - MOVING_1 (2.0), - MOVING_2 (10.0), - DONE (Double.POSITIVE_INFINITY); - - AutoState(double timer) { - this.timer = timer; - } - - double timer; - } - - AutoState autoState; - long state_start; - - @Override - public void init() { - PestoFTCConfig.initializePinpoint = false; - PestoFTCConfig.initializeDrive = false; - super.init(); - - follower = Constants.createFollower(hardwareMap); - PanelsConfigurables.INSTANCE.refreshClass(this); - - follower.setStartingPose(new Pose(0, 0)); - - autoState = AutoState.MOVING_1; - - hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); - hoodSubsystem.update(); - } - - /** - * This initializes the Follower and creates the forward and backward Paths. Additionally, this - * initializes the Panels telemetry. - */ - @Override - public void init_loop() { - super.init(); - - follower.update(); - } - - @Override - public void start() { - follower.activateDrive(); - - follower.setMaxPower(0.7); - - forwards = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) - .setLinearHeadingInterpolation(0, -0.36) - .build(); - - forwards_again = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(4, 0), new Pose(27, 0))) - .setLinearHeadingInterpolation(-0.36, -Math.PI/2) - .build(); - - follower.followPath(forwards, true); - - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - - state_start = System.nanoTime(); - } - - /** - * 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() { - FrontalLobe.update(); - MotorCortex.update(); - - if (autoState != AutoState.DONE) - follower.update(); - - draw(); - - if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { - switch (autoState) { - case MOVING_1: - FrontalLobe.useMacro("outtake"); - while (FrontalLobe.hasMacro("outtake")) { - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - long start = System.nanoTime(); - while ((System.nanoTime() - start) / 1E9 < 5) {} - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - autoState = AutoState.MOVING_2; - state_start = System.nanoTime(); - follower.followPath(forwards_again); - break; - case MOVING_2: - autoState = AutoState.DONE; - } - } - - telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); - telemetry.addData("timer", autoState.timer); - telemetry.addData("state", autoState); - telemetry.update(); - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java index 65d51c9..4ed319c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java @@ -50,10 +50,11 @@ public static Follower createFollower(HardwareMap hardwareMap) { .headingPIDFSwitch(0.2) .headingPIDFCoefficients(new PIDFCoefficients(0.8, 0, 0, 0)) - .secondaryHeadingPIDFCoefficients(new PIDFCoefficients(1.6, 0, 0, 0)) + .secondaryHeadingPIDFCoefficients(new PIDFCoefficients(2.0, 0, 0, 0)) + .drivePIDFSwitch(2) .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0.01, 0.6, 0.0)) - .secondaryDrivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0.01, 0.6, 0.0)) + .secondaryDrivePIDFCoefficients(new FilteredPIDFCoefficients(0.0, 0, 0.0, 0.0, 0.0)) .mass(7.7); // 7.7kg == 17lbs diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java index 08c6a5f..74c5ea9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java @@ -2,7 +2,7 @@ import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.Limelight3A; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.shprobotics.pestocore.devices.GamepadInterface; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; @@ -11,7 +11,7 @@ import org.firstinspires.ftc.teamcode.PestoFTCConfig; -public class BaseRobot extends OpMode { +public class BaseRobot extends LinearOpMode { public MecanumController mecanumController; public DeterministicTracker tracker; public TeleOpController teleOpController; @@ -35,8 +35,7 @@ public enum RobotState { NEUTRAL } - @Override - public void init() { + public void initialize() { FrontalLobe.initialize(hardwareMap); if (PestoFTCConfig.initializeDrive) @@ -66,6 +65,27 @@ public void init() { // MACRO initialization + FrontalLobe.addMacro("auto_outtake", new FrontalLobe.Macro() { + @Override + public void start() { + FrontalLobe.removeOtherMacros(this); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.OUTTAKE); + } + + @Override + public boolean loop(double v) { + // how long (seconds) before starting to move other components + if (v < 1.2) + return false; + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.OUTTAKE); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.OUTTAKE); + + return true; + } + }); + FrontalLobe.addMacro("outtake", new FrontalLobe.Macro() { @Override public void start() { @@ -117,17 +137,7 @@ public boolean loop(double v) { } @Override - public void init_loop() { - - } - - @Override - public void start() { - - } - - @Override - public void loop() { + public void runOpMode() { } } \ No newline at end of file From 3cfc95e007b9b757bd491214a6d5e623e72184c7 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Sat, 6 Dec 2025 09:00:07 -0800 Subject: [PATCH 04/25] Create BlueAuto.java --- .../firstinspires/ftc/teamcode/BlueAuto.java | 297 ++++++++++++++++++ 1 file changed, 297 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java new file mode 100644 index 0000000..19d6358 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java @@ -0,0 +1,297 @@ +package org.firstinspires.ftc.teamcode; + +import static org.firstinspires.ftc.teamcode.Tuning.draw; +import static org.firstinspires.ftc.teamcode.Tuning.follower; + +import com.acmerobotics.dashboard.config.Config; +import com.bylazar.configurables.PanelsConfigurables; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.constants.Constants; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; + +@Config +@Autonomous(name = "Blue Auto - Thanks Angela") +public class BlueAuto extends BaseRobot { + private PathChain forwards; + private PathChain forwards_again; + private PathChain intake_1; + private PathChain outtake_1; + private PathChain attack_the_human_move; + private PathChain attack_the_human_go_time; + private PathChain return_to_mama; + + enum AutoState { + MOVING_1 (1.0), + MOVING_2 (2.0), + MOVING_3 (4.0), + MOVING_4 (1.25), + MOVING_5 (3.0), + MOVING_6 (3.0), + MOVING_7 (3.0), + DONE (Double.POSITIVE_INFINITY); + + AutoState(double timer) { + this.timer = timer; + } + + double timer; + } + + AutoState autoState; + long state_start; + long start; + + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = false; + PestoFTCConfig.initializeDrive = false; + super.initialize(); + + follower = Constants.createFollower(hardwareMap); + PanelsConfigurables.INSTANCE.refreshClass(this); + + follower.setStartingPose(new Pose(0, 0)); + + autoState = AutoState.MOVING_1; + + hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); + hoodSubsystem.update(); + + follower.update(); + + follower.activateDrive(); + + follower.setMaxPower(0.7); + + forwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) + .setLinearHeadingInterpolation(0, 0.36) + .build(); + + forwards_again = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(4, 0), new Pose(33, 0))) + .setLinearHeadingInterpolation(0.38, -Math.PI/2) + .build(); + + intake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(33, 0), new Pose(33, 40))) + .setConstantHeadingInterpolation(Math.PI/2) + .build(); + + outtake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(33, 40), new Pose(4, 0))) + .setLinearHeadingInterpolation(Math.PI/2, 0.40) + .build(); + + attack_the_human_move = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, 46.5))) + .setConstantHeadingInterpolation(Math.PI) + .build(); + + attack_the_human_go_time = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(40, 46.5), new Pose(8, 46.5))) + .setConstantHeadingInterpolation(Math.PI) + .build(); + + return_to_mama = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(8, 46.5), new Pose(32, 0), new Pose(5, 0))) + .setLinearHeadingInterpolation(Math.PI, 0.4) + .build(); + + follower.followPath(forwards, true); + + outtakeSubsystem.setPower(PestoFTCConfig.AUTO_FAR); + + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); + telemetry.update(); + + waitForStart(); + + state_start = System.nanoTime(); + + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + + if (autoState != AutoState.DONE) + follower.update(); + + draw(); + + if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { + switch (autoState) { + case MOVING_1: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + autoState = AutoState.MOVING_2; + state_start = System.nanoTime(); + follower.followPath(forwards_again, true); + break; + case MOVING_2: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + autoState = AutoState.MOVING_3; + follower.followPath(intake_1, true); + follower.setMaxPower(0.5); + break; + case MOVING_3: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + autoState = AutoState.MOVING_4; + state_start = System.nanoTime(); + follower.followPath(outtake_1, true); + follower.setMaxPower(1.0); + break; + case MOVING_4: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + follower.followPath(attack_the_human_move, true); + autoState = AutoState.MOVING_5; + break; + case MOVING_5: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + follower.followPath(attack_the_human_go_time, true); + follower.setMaxPower(0.5); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_6; + break; + case MOVING_6: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + follower.followPath(return_to_mama, true); + follower.setMaxPower(1.0); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_7; + break; + case MOVING_7: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + autoState = AutoState.DONE; + break; + } + } + + telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); + telemetry.addData("timer", autoState.timer); + telemetry.addData("state", autoState); + telemetry.update(); + } + } +} \ No newline at end of file From 1eebddffdbf1388868d1b5a603986cf6282f2199 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Sat, 6 Dec 2025 19:15:44 -0800 Subject: [PATCH 05/25] changes comp 12-6-25 --- .../firstinspires/ftc/teamcode/BlueAuto.java | 14 +- .../ftc/teamcode/BlueCloseAuto.java | 304 ++++++++++++++++++ .../firstinspires/ftc/teamcode/RedAuto.java | 12 +- .../ftc/teamcode/RedCloseAuto.java | 303 +++++++++++++++++ 4 files changed, 626 insertions(+), 7 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java index 19d6358..fe58bb6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java @@ -22,7 +22,7 @@ import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; @Config -@Autonomous(name = "Blue Auto - Thanks Angela") +@Autonomous(name = "Blue Far Auto - Thanks Angela") public class BlueAuto extends BaseRobot { private PathChain forwards; private PathChain forwards_again; @@ -59,6 +59,9 @@ public void runOpMode() { PestoFTCConfig.initializeDrive = false; super.initialize(); + FrontalLobe.update(); + MotorCortex.update(); + follower = Constants.createFollower(hardwareMap); PanelsConfigurables.INSTANCE.refreshClass(this); @@ -70,9 +73,7 @@ public void runOpMode() { hoodSubsystem.update(); follower.update(); - follower.activateDrive(); - follower.setMaxPower(0.7); forwards = follower.pathBuilder() @@ -84,7 +85,7 @@ public void runOpMode() { forwards_again = follower.pathBuilder() .setGlobalDeceleration() .addPath(new BezierLine(new Pose(4, 0), new Pose(33, 0))) - .setLinearHeadingInterpolation(0.38, -Math.PI/2) + .setLinearHeadingInterpolation(0.38, Math.PI/2) .build(); intake_1 = follower.pathBuilder() @@ -128,6 +129,8 @@ public void runOpMode() { waitForStart(); + follower.setPose(new Pose(0, 0)); + state_start = System.nanoTime(); while (opModeIsActive() && !isStopRequested()) { @@ -291,6 +294,9 @@ public void runOpMode() { telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); telemetry.addData("timer", autoState.timer); telemetry.addData("state", autoState); + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java new file mode 100644 index 0000000..f0d4f74 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java @@ -0,0 +1,304 @@ +package org.firstinspires.ftc.teamcode; + +import static org.firstinspires.ftc.teamcode.Tuning.draw; +import static org.firstinspires.ftc.teamcode.Tuning.follower; + +import com.acmerobotics.dashboard.config.Config; +import com.bylazar.configurables.PanelsConfigurables; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.constants.Constants; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; + +@Config +@Autonomous(name = "Blue Close Auto - Thanks Angela") +public class BlueCloseAuto extends BaseRobot { + private PathChain forwards; + private PathChain forwards_again; + private PathChain intake_1; + private PathChain outtake_1; + private PathChain attack_the_human_move; + private PathChain attack_the_human_go_time; + private PathChain return_to_mama; + + enum AutoState { + MOVING_1 (1.0), + MOVING_2 (4.0), + MOVING_3 (4.0), + MOVING_4 (1.25), + MOVING_5 (3.0), + MOVING_6 (3.0), + MOVING_7 (3.0), + DONE (Double.POSITIVE_INFINITY); + + AutoState(double timer) { + this.timer = timer; + } + + double timer; + } + + AutoState autoState; + long state_start; + long start; + + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = false; + PestoFTCConfig.initializeDrive = false; + super.initialize(); + + FrontalLobe.update(); + MotorCortex.update(); + + follower = Constants.createFollower(hardwareMap); + PanelsConfigurables.INSTANCE.refreshClass(this); + + follower.setStartingPose(new Pose(0, 0)); + + autoState = AutoState.MOVING_1; + + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + hoodSubsystem.update(); + + follower.update(); + follower.activateDrive(); + follower.setMaxPower(0.7); + + forwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) + .setLinearHeadingInterpolation(0, -Math.PI/2) + .build(); + + forwards_again = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(4, 0), new Pose(57, 0))) + .setConstantHeadingInterpolation(-Math.PI/2) + .build(); + + intake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(57, 0), new Pose(57, -40))) + .setConstantHeadingInterpolation(-Math.PI/2) + .build(); + + outtake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(57, -40), new Pose(4, 0))) + .setLinearHeadingInterpolation(-Math.PI/2, -0.40) + .build(); + + attack_the_human_move = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, -46.5))) + .setConstantHeadingInterpolation(-Math.PI) + .build(); + + attack_the_human_go_time = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(40, -46.5), new Pose(8, -46.5))) + .setConstantHeadingInterpolation(-Math.PI) + .build(); + + return_to_mama = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(8, -46.5), new Pose(32, 0), new Pose(5, 0))) + .setLinearHeadingInterpolation(-Math.PI, -0.4) + .build(); + + follower.followPath(forwards, true); + + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); + + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); + telemetry.update(); + + waitForStart(); + + follower.setPose(new Pose(0, 0)); + + state_start = System.nanoTime(); + + + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + + if (autoState != AutoState.DONE) + follower.update(); + + draw(); + + if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { + switch (autoState) { + case MOVING_1: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + autoState = AutoState.MOVING_2; + state_start = System.nanoTime(); + follower.followPath(forwards_again, true); + break; + case MOVING_2: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + autoState = AutoState.MOVING_3; + follower.followPath(intake_1, true); + follower.setMaxPower(0.5); + break; + case MOVING_3: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + autoState = AutoState.MOVING_4; + state_start = System.nanoTime(); + follower.followPath(outtake_1, true); + follower.setMaxPower(1.0); + break; + case MOVING_4: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + follower.followPath(attack_the_human_move, true); + autoState = AutoState.MOVING_5; + break; + case MOVING_5: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + follower.followPath(attack_the_human_go_time, true); + follower.setMaxPower(0.5); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_6; + break; + case MOVING_6: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + follower.followPath(return_to_mama, true); + follower.setMaxPower(1.0); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_7; + break; + case MOVING_7: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + autoState = AutoState.DONE; + break; + } + } + + telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); + telemetry.addData("timer", autoState.timer); + telemetry.addData("state", autoState); + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); + telemetry.update(); + } + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java index 00f61ea..63d3234 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java @@ -22,7 +22,7 @@ import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; @Config -@Autonomous(name = "Red Auto - Thanks Angela") +@Autonomous(name = "Red Far Auto - Thanks Angela") public class RedAuto extends BaseRobot { private PathChain forwards; private PathChain forwards_again; @@ -59,6 +59,9 @@ public void runOpMode() { PestoFTCConfig.initializeDrive = false; super.initialize(); + FrontalLobe.update(); + MotorCortex.update(); + follower = Constants.createFollower(hardwareMap); PanelsConfigurables.INSTANCE.refreshClass(this); @@ -70,9 +73,7 @@ public void runOpMode() { hoodSubsystem.update(); follower.update(); - follower.activateDrive(); - follower.setMaxPower(0.7); forwards = follower.pathBuilder() @@ -128,6 +129,8 @@ public void runOpMode() { waitForStart(); + follower.setPose(new Pose(0, 0)); + state_start = System.nanoTime(); while (opModeIsActive() && !isStopRequested()) { @@ -291,6 +294,9 @@ public void runOpMode() { telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); telemetry.addData("timer", autoState.timer); telemetry.addData("state", autoState); + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java new file mode 100644 index 0000000..72065d2 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java @@ -0,0 +1,303 @@ +package org.firstinspires.ftc.teamcode; + +import static org.firstinspires.ftc.teamcode.Tuning.draw; +import static org.firstinspires.ftc.teamcode.Tuning.follower; + +import com.acmerobotics.dashboard.config.Config; +import com.bylazar.configurables.PanelsConfigurables; +import com.pedropathing.geometry.BezierCurve; +import com.pedropathing.geometry.BezierLine; +import com.pedropathing.geometry.Pose; +import com.pedropathing.paths.PathChain; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.constants.Constants; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; + +@Config +@Autonomous(name = "Red Close Auto - Thanks Angela") +public class RedCloseAuto extends BaseRobot { + private PathChain forwards; + private PathChain forwards_again; + private PathChain intake_1; + private PathChain outtake_1; + private PathChain attack_the_human_move; + private PathChain attack_the_human_go_time; + private PathChain return_to_mama; + + enum AutoState { + MOVING_1 (1.0), + MOVING_2 (4.0), + MOVING_3 (4.0), + MOVING_4 (1.25), + MOVING_5 (3.0), + MOVING_6 (3.0), + MOVING_7 (3.0), + DONE (Double.POSITIVE_INFINITY); + + AutoState(double timer) { + this.timer = timer; + } + + double timer; + } + + AutoState autoState; + long state_start; + long start; + + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = false; + PestoFTCConfig.initializeDrive = false; + super.initialize(); + + FrontalLobe.update(); + MotorCortex.update(); + + follower = Constants.createFollower(hardwareMap); + PanelsConfigurables.INSTANCE.refreshClass(this); + + follower.setStartingPose(new Pose(0, 0)); + + autoState = AutoState.MOVING_1; + + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + hoodSubsystem.update(); + + follower.update(); + follower.activateDrive(); + follower.setMaxPower(0.7); + + forwards = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) + .setLinearHeadingInterpolation(0, Math.PI/2) + .build(); + + forwards_again = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(4, 0), new Pose(57, 0))) + .setConstantHeadingInterpolation(Math.PI/2) + .build(); + + intake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(57, 0), new Pose(57, 40))) + .setConstantHeadingInterpolation(Math.PI/2) + .build(); + + outtake_1 = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(57, -40), new Pose(4, 0))) + .setLinearHeadingInterpolation(Math.PI/2, -0.40) + .build(); + + attack_the_human_move = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, -46.5))) + .setConstantHeadingInterpolation(-Math.PI) + .build(); + + attack_the_human_go_time = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierLine(new Pose(40, -46.5), new Pose(8, -46.5))) + .setConstantHeadingInterpolation(-Math.PI) + .build(); + + return_to_mama = follower.pathBuilder() + .setGlobalDeceleration() + .addPath(new BezierCurve(new Pose(8, -46.5), new Pose(32, 0), new Pose(5, 0))) + .setLinearHeadingInterpolation(-Math.PI, -0.4) + .build(); + + follower.followPath(forwards, true); + + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); + + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); + telemetry.update(); + + waitForStart(); + + follower.setPose(new Pose(0, 0)); + + state_start = System.nanoTime(); + + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + + if (autoState != AutoState.DONE) + follower.update(); + + draw(); + + if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { + switch (autoState) { + case MOVING_1: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + autoState = AutoState.MOVING_2; + state_start = System.nanoTime(); + follower.followPath(forwards_again, true); + break; + case MOVING_2: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + autoState = AutoState.MOVING_3; + follower.followPath(intake_1, true); + follower.setMaxPower(0.5); + break; + case MOVING_3: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + autoState = AutoState.MOVING_4; + state_start = System.nanoTime(); + follower.followPath(outtake_1, true); + follower.setMaxPower(1.0); + break; + case MOVING_4: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + follower.followPath(attack_the_human_move, true); + autoState = AutoState.MOVING_5; + break; + case MOVING_5: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + feederSubsystem.update(); + + follower.followPath(attack_the_human_go_time, true); + follower.setMaxPower(0.5); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_6; + break; + case MOVING_6: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + intakeSubsystem.update(); + + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + feederSubsystem.update(); + + follower.followPath(return_to_mama, true); + follower.setMaxPower(1.0); + + state_start = System.nanoTime(); + autoState = AutoState.MOVING_7; + break; + case MOVING_7: + FrontalLobe.useMacro("auto_outtake"); + while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { + MotorCortex.update(); + follower.update(); + FrontalLobe.update(); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + } + start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { + MotorCortex.update(); + follower.update(); + } + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + outtakeSubsystem.update(); + feederSubsystem.update(); + intakeSubsystem.update(); + indexerSubsystem.update(); + + state_start = System.nanoTime(); + autoState = AutoState.DONE; + break; + } + } + + telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); + telemetry.addData("timer", autoState.timer); + telemetry.addData("state", autoState); + telemetry.addData("x", follower.getPose().getX()); + telemetry.addData("y", follower.getPose().getY()); + telemetry.addData("r", follower.getPose().getHeading()); + telemetry.update(); + } + } +} \ No newline at end of file From a317804ef79930630e644d63005e95f3bbe01165 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Sun, 4 Jan 2026 22:55:20 -0800 Subject: [PATCH 06/25] kinda working maybe some --- .../ftc/teamcode/AngelaDrive.java | 7 +++ .../ftc/teamcode/PestoFTCConfig.java | 24 +++---- .../org/firstinspires/ftc/teamcode/Test.java | 31 +++++++++ .../teamcode/subsystems/HoodSubsystem.java | 63 +++++++++---------- .../teamcode/subsystems/IndexerSubsystem.java | 5 +- .../teamcode/subsystems/IntakeSubsystem.java | 50 ++++++++++++--- 6 files changed, 121 insertions(+), 59 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java index 40b611d..dc24ceb 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java @@ -9,6 +9,7 @@ import com.shprobotics.pestocore.processing.MotorCortex; import com.shprobotics.pestocore.processing.PestoTelemetry; +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; @@ -152,6 +153,12 @@ public void runOpMode() { telemetry.addData("x", tracker.getCurrentPosition().getX()); telemetry.addData("y", tracker.getCurrentPosition().getY()); telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.addData("target", intakeSubsystem.dropdownTarget); + telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); + telemetry.addData("dx", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).xRotationRate); + telemetry.addData("dy", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).yRotationRate); + telemetry.addData("dz", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).zRotationRate); +// telemetry.update(); telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 87ed0bd..bbfc261 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -23,9 +23,9 @@ public class PestoFTCConfig implements ConfigInterface { public static boolean initializeDrive = true; // ODOMETRY - private static String leftName = "fl"; - private static String centerName = "bl"; - private static String rightName = "fr"; + private static String leftName = "left"; + private static String centerName = "backLeft"; + private static String rightName = "right"; private static DcMotorSimple.Direction leftDirection = DcMotorSimple.Direction.REVERSE; private static DcMotorSimple.Direction centerDirection = DcMotorSimple.Direction.REVERSE; @@ -39,10 +39,10 @@ public class PestoFTCConfig implements ConfigInterface { public static double STRAFE_VELOCITY = 61; // DROPDOWN - public static double DROPDOWN_DRIVE = 0.29; - public static double DROPDOWN_INTAKE = 0.47; - public static double DROPDOWN_PUSH = 0.29; - public static double DROPDOWN_PUSH_AUTO = 0.29; + public static double DROPDOWN_DRIVE = 35; // 0.29; + public static double DROPDOWN_INTAKE = 80; // 0.47; + public static double DROPDOWN_PUSH = 35; // 0.29; + public static double DROPDOWN_PUSH_AUTO = 35; // 0.29; // INDEXER public static double INDEXER_OUTTAKE = 0.08; @@ -71,10 +71,10 @@ public static void initialize(HardwareMap hardwareMap) { Cerebrum.initialize(); MecanumController driveController = new MecanumController( - MotorCortex.getMotor("fl"), - MotorCortex.getMotor("fr"), - MotorCortex.getMotor("bl"), - MotorCortex.getMotor("br") + MotorCortex.getMotor("frontLeft"), + MotorCortex.getMotor("frontRight"), + MotorCortex.getMotor("backLeft"), + MotorCortex.getMotor("backRight") ); driveController.configureMotorDirections(new DcMotorSimple.Direction[]{ @@ -121,7 +121,7 @@ public static void initialize(HardwareMap hardwareMap) { .build(); TeleOpController teleOpController = new TeleOpController(driveController, hardwareMap); - teleOpController.useTrackerIMU(tracker); +// teleOpController.useTrackerIMU(tracker); teleOpController.setSpeedController(gamepad -> gamepad.left_bumper ? 0.6 : 1.0); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java new file mode 100644 index 0000000..65700d4 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java @@ -0,0 +1,31 @@ +package org.firstinspires.ftc.teamcode; + +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; + +@TeleOp(name = "Test") +public class Test extends BaseRobot { + @Override + public void runOpMode() { + FrontalLobe.initialize(hardwareMap); + + intakeSubsystem = new IntakeSubsystem(); + + waitForStart(); + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); + + long start = System.nanoTime(); + while (opModeIsActive() && !isStopRequested()) { + intakeSubsystem.update(); + MotorCortex.update(); + + telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); + telemetry.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java index 2dfecc1..12248b9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java @@ -1,13 +1,6 @@ package org.firstinspires.ftc.teamcode.subsystems; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_AUTO_FAR; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_CLOSE; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_FAR; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_MID; -import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.AUTO_FAR; import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.CLOSE; -import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.FAR; -import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.MID; import com.qualcomm.robotcore.hardware.DistanceSensor; import com.shprobotics.pestocore.hardware.CortexLinkedServo; @@ -51,33 +44,33 @@ public double getDistance() { } public void update() { - boolean ledOverride = distanceSensor.getDistance(DistanceUnit.CM) < 10; - - if (ledOverride) - led.setPositionResult(0.39); // YALLOW - - if (state == CLOSE) { - hood.setPositionResult(HOOD_CLOSE); - if (!ledOverride) - led.setPositionResult(0.5); // GREEN - } - - if (state == MID) { - hood.setPositionResult(HOOD_MID); - if (!ledOverride) - led.setPositionResult(0.61); // BLUE - } - - if (state == FAR) { - hood.setPositionResult(HOOD_FAR); - if (!ledOverride) - led.setPositionResult(0.28); // RED - } - - if (state == AUTO_FAR) { - hood.setPositionResult(HOOD_AUTO_FAR); - if (!ledOverride) - led.setPositionResult(0.28); // RED - } +// boolean ledOverride = distanceSensor.getDistance(DistanceUnit.CM) < 10; +// +// if (ledOverride) +// led.setPositionResult(0.39); // YALLOW +// +// if (state == CLOSE) { +// hood.setPositionResult(HOOD_CLOSE); +// if (!ledOverride) +// led.setPositionResult(0.5); // GREEN +// } +// +// if (state == MID) { +// hood.setPositionResult(HOOD_MID); +// if (!ledOverride) +// led.setPositionResult(0.61); // BLUE +// } +// +// if (state == FAR) { +// hood.setPositionResult(HOOD_FAR); +// if (!ledOverride) +// led.setPositionResult(0.28); // RED +// } +// +// if (state == AUTO_FAR) { +// hood.setPositionResult(HOOD_AUTO_FAR); +// if (!ledOverride) +// led.setPositionResult(0.28); // RED +// } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java index f208f3a..f419d32 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java @@ -1,11 +1,8 @@ package org.firstinspires.ftc.teamcode.subsystems; -import static com.qualcomm.robotcore.hardware.DcMotor.RunMode.RUN_USING_ENCODER; import static org.firstinspires.ftc.teamcode.PestoFTCConfig.INDEXER_BLOCK; import static org.firstinspires.ftc.teamcode.PestoFTCConfig.INDEXER_OUTTAKE; -import static org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem.OuttakeState.OUTTAKE; -import com.shprobotics.pestocore.hardware.CortexLinkedMotor; import com.shprobotics.pestocore.hardware.CortexLinkedServo; import com.shprobotics.pestocore.processing.MotorCortex; @@ -20,7 +17,7 @@ public enum IndexerState { } public IndexerSubsystem() { - indexer = MotorCortex.getServo("indexer"); + indexer = MotorCortex.getServo("blocker"); state = IndexerState.NEUTRAL; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java index 83129f9..9749443 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java @@ -11,13 +11,21 @@ import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.OUTTAKE_AUTO; import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.REJECT; +import com.qualcomm.hardware.rev.Rev9AxisImu; +import com.shprobotics.pestocore.hardware.CortexLinkedCRServo; import com.shprobotics.pestocore.hardware.CortexLinkedMotor; -import com.shprobotics.pestocore.hardware.CortexLinkedServo; import com.shprobotics.pestocore.processing.MotorCortex; public class IntakeSubsystem { private final CortexLinkedMotor intake; - private final CortexLinkedServo dropdown; + public final CortexLinkedCRServo dropdown; + + public final Rev9AxisImu imu; + private double pitchVelocity = 0.0; + private double pitch = 0.0; + private double time = 0.0; + private double power = 0.0; + public double dropdownTarget; private IntakeState state; @@ -33,9 +41,12 @@ public IntakeSubsystem() { intake = MotorCortex.getMotor("intake"); intake.setDirection(REVERSE); - dropdown = MotorCortex.getServo("dropdown"); + imu = (Rev9AxisImu) MotorCortex.hardwareMap.get("ext_imu"); + + dropdown = MotorCortex.getCRServo("dropdown"); state = NEUTRAL; + dropdownTarget = DROPDOWN_DRIVE; } public void setState(IntakeState state) { @@ -45,27 +56,50 @@ public void setState(IntakeState state) { public void update() { if (state == INTAKE) { intake.setPowerResult(1.0); - dropdown.setPositionResult(DROPDOWN_INTAKE); +// dropdown.setPositionResult(DROPDOWN_INTAKE); + dropdownTarget = DROPDOWN_INTAKE; } if (state == NEUTRAL) { intake.setPowerResult(0.15); - dropdown.setPositionResult(DROPDOWN_DRIVE); +// dropdown.setPositionResult(DROPDOWN_DRIVE); + dropdownTarget = DROPDOWN_DRIVE; } if (state == REJECT) { intake.setPowerResult(-1.0); - dropdown.setPositionResult(DROPDOWN_INTAKE); +// dropdown.setPositionResult(DROPDOWN_INTAKE); + dropdownTarget = DROPDOWN_INTAKE; } if (state == OUTTAKE) { intake.setPowerResult(1.0); - dropdown.setPositionResult(DROPDOWN_PUSH); +// dropdown.setPositionResult(DROPDOWN_PUSH); + dropdownTarget = DROPDOWN_PUSH; } if (state == OUTTAKE_AUTO) { intake.setPowerResult(1.0); - dropdown.setPositionResult(DROPDOWN_PUSH_AUTO); +// dropdown.setPositionResult(DROPDOWN_PUSH_AUTO); + dropdownTarget = DROPDOWN_PUSH_AUTO; } + + pitchVelocity = (imu.getRobotYawPitchRollAngles().getPitch() - pitch) / ((System.nanoTime() - time) / 1E9); + + // dropdown PID logic + pitch = imu.getRobotYawPitchRollAngles().getPitch(); + time = System.nanoTime(); + + // power save with <10 degrees of error + if (Math.abs(dropdownTarget - pitch) < 10) { + dropdown.setPowerResult(0.0); + return; + } + + double error = 0.01 * (dropdownTarget - pitch) - 0.003 * pitchVelocity; + + power = Math.min(1.0, Math.max(-1.0, error)); + + dropdown.setPowerResult(-power); } } From 057ca8f3a384bf7daab3076a580604fc52d49c21 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 8 Jan 2026 16:19:18 -0800 Subject: [PATCH 07/25] current --- .../{Drive.java => FieldOriented.java} | 68 ++++++++++++++++--- .../ftc/teamcode/PestoFTCConfig.java | 8 +-- .../{AngelaDrive.java => RobotOriented.java} | 4 +- .../teamcode/subsystems/HoodSubsystem.java | 60 ++++++++-------- 4 files changed, 96 insertions(+), 44 deletions(-) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/{Drive.java => FieldOriented.java} (60%) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/{AngelaDrive.java => RobotOriented.java} (98%) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java similarity index 60% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java index b8ed77c..b125942 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java @@ -1,9 +1,15 @@ package org.firstinspires.ftc.teamcode; +import com.acmerobotics.dashboard.config.variable.QualitativeData; +import com.qualcomm.hardware.limelightvision.LLResult; +import com.qualcomm.hardware.limelightvision.LLResultTypes; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.shprobotics.pestocore.devices.GamepadKey; import com.shprobotics.pestocore.processing.FrontalLobe; import com.shprobotics.pestocore.processing.MotorCortex; +import com.shprobotics.pestocore.processing.PestoTelemetry; +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; @@ -11,12 +17,17 @@ import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; -//@TeleOp(name = "Field Oriented") -public class Drive extends BaseRobot { +import java.util.List; + +@TeleOp(name = "Field Oriented") +public class FieldOriented extends BaseRobot { + PestoTelemetry pestoTelemetry; + @Override public void runOpMode() { PestoFTCConfig.initializePinpoint = true; PestoFTCConfig.initializeDrive = true; + pestoTelemetry = FrontalLobe.pestoTelemetry; super.initialize(); @@ -27,19 +38,42 @@ public void runOpMode() { MotorCortex.update(); gamepadInterface1.update(); tracker.update(); + pestoTelemetry.clear(); + teleOpController.updateSpeed(gamepad1); if (gamepad1.b) { tracker.reset(); teleOpController.resetIMU(); } - teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - - boolean intaking = gamepad1.right_trigger > 0.05; + boolean intaking = gamepad1.right_trigger > 0.05 && -gamepad1.left_stick_y >= -0.1; boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; - boolean rejecting = !intaking && !outtaking && gamepad1.a; + boolean rejecting = !intaking && !outtaking && gamepad1.right_bumper; boolean neutralizing = !intaking && !outtaking && !rejecting; + if (outtaking) { + LLResult result = limelight.getLatestResult(); + + List results = result.getFiducialResults(); + + if (result != null && result.isValid() && results.size() > 0 && results.get(0).getFiducialId() != 21) { + double rotate = -result.getTx()*PestoFTCConfig.KP; + rotate = Math.min(1, Math.max(-1, rotate)); + + if (rotate < 0) + rotate -= PestoFTCConfig.STATIC_DRIVE; + else + rotate += PestoFTCConfig.STATIC_DRIVE; + + teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, rotate); + telemetry.addData("tx", result.getTx()); + } else { + telemetry.addLine("No Target :("); + teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + } + } else + teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + if (!outtaking && state == RobotState.OUTTAKE) { FrontalLobe.removeMacros("outtake"); } @@ -91,14 +125,14 @@ public void runOpMode() { // Cycle hood modes if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { - hoodSubsystem.setState(HoodSubsystem.HoodState.MID); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { + hoodSubsystem.setState(HoodSubsystem.HoodState.MID); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); } } @@ -108,9 +142,23 @@ public void runOpMode() { outtakeSubsystem.update(); indexerSubsystem.update(); + double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; + double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; + double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; + + pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); + pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); + pestoTelemetry.update(); + telemetry.addData("x", tracker.getCurrentPosition().getX()); telemetry.addData("y", tracker.getCurrentPosition().getY()); telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.addData("target", intakeSubsystem.dropdownTarget); + telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); + telemetry.addData("dx", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).xRotationRate); + telemetry.addData("dy", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).yRotationRate); + telemetry.addData("dz", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).zRotationRate); +// telemetry.update(); telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index bbfc261..9e32999 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -24,7 +24,7 @@ public class PestoFTCConfig implements ConfigInterface { // ODOMETRY private static String leftName = "left"; - private static String centerName = "backLeft"; + private static String centerName = "frontRight"; private static String rightName = "right"; private static DcMotorSimple.Direction leftDirection = DcMotorSimple.Direction.REVERSE; @@ -33,7 +33,7 @@ public class PestoFTCConfig implements ConfigInterface { private static double ODOMETRY_TICKS_PER_INCH = 505.3169; public static double FORWARD_OFFSET = -1.565; - public static double ODOMETRY_WIDTH = 10.1; + public static double ODOMETRY_WIDTH = 13.567; public static double FORWARD_VELOCITY = 76; public static double STRAFE_VELOCITY = 61; @@ -121,11 +121,11 @@ public static void initialize(HardwareMap hardwareMap) { .build(); TeleOpController teleOpController = new TeleOpController(driveController, hardwareMap); -// teleOpController.useTrackerIMU(tracker); + teleOpController.useTrackerIMU(tracker); teleOpController.setSpeedController(gamepad -> gamepad.left_bumper ? 0.6 : 1.0); - teleOpController.counteractCentripetalForce(tracker, Math.min(STRAFE_VELOCITY, FORWARD_VELOCITY)); +// teleOpController.counteractCentripetalForce(tracker, Math.min(STRAFE_VELOCITY, FORWARD_VELOCITY)); FrontalLobe.teleOpController = teleOpController; FrontalLobe.tracker = tracker; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotOriented.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotOriented.java index dc24ceb..075caff 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/AngelaDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotOriented.java @@ -19,8 +19,8 @@ import java.util.List; -@TeleOp(name = "Angela Drive") -public class AngelaDrive extends BaseRobot { +@TeleOp(name = "Robot Oriented") +public class RobotOriented extends BaseRobot { PestoTelemetry pestoTelemetry; @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java index 12248b9..93b8625 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java @@ -1,5 +1,9 @@ package org.firstinspires.ftc.teamcode.subsystems; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_AUTO_FAR; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_CLOSE; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_FAR; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_MID; import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.CLOSE; import com.qualcomm.robotcore.hardware.DistanceSensor; @@ -44,33 +48,33 @@ public double getDistance() { } public void update() { -// boolean ledOverride = distanceSensor.getDistance(DistanceUnit.CM) < 10; -// -// if (ledOverride) -// led.setPositionResult(0.39); // YALLOW -// -// if (state == CLOSE) { -// hood.setPositionResult(HOOD_CLOSE); -// if (!ledOverride) -// led.setPositionResult(0.5); // GREEN -// } -// -// if (state == MID) { -// hood.setPositionResult(HOOD_MID); -// if (!ledOverride) -// led.setPositionResult(0.61); // BLUE -// } -// -// if (state == FAR) { -// hood.setPositionResult(HOOD_FAR); -// if (!ledOverride) -// led.setPositionResult(0.28); // RED -// } -// -// if (state == AUTO_FAR) { -// hood.setPositionResult(HOOD_AUTO_FAR); -// if (!ledOverride) -// led.setPositionResult(0.28); // RED -// } + boolean ledOverride = distanceSensor.getDistance(DistanceUnit.CM) < 10; + + if (ledOverride) + led.setPositionResult(0.39); // YALLOW + + if (state == CLOSE) { + hood.setPositionResult(HOOD_CLOSE); + if (!ledOverride) + led.setPositionResult(0.5); // GREEN + } + + if (state == HoodState.MID) { + hood.setPositionResult(HOOD_MID); + if (!ledOverride) + led.setPositionResult(0.61); // BLUE + } + + if (state == HoodState.FAR) { + hood.setPositionResult(HOOD_FAR); + if (!ledOverride) + led.setPositionResult(0.28); // RED + } + + if (state == HoodState.AUTO_FAR) { + hood.setPositionResult(HOOD_AUTO_FAR); + if (!ledOverride) + led.setPositionResult(0.28); // RED + } } } From 21b5d33e7519f9e172cd85d2faa530efdd68932c Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Fri, 9 Jan 2026 21:52:57 -0800 Subject: [PATCH 08/25] teleop almost metal --- .../firstinspires/ftc/teamcode/BlueAuto.java | 303 ----------------- .../ftc/teamcode/BlueCloseAuto.java | 304 ------------------ .../ftc/teamcode/FieldOriented.java | 34 +- .../ftc/teamcode/PestoFTCConfig.java | 29 +- .../firstinspires/ftc/teamcode/RedAuto.java | 303 ----------------- .../ftc/teamcode/RedCloseAuto.java | 303 ----------------- .../ftc/teamcode/RobotOriented.java | 165 ---------- .../org/firstinspires/ftc/teamcode/Test.java | 37 ++- .../ftc/teamcode/subsystems/BaseRobot.java | 80 ++--- .../teamcode/subsystems/IntakeSubsystem.java | 5 - 10 files changed, 83 insertions(+), 1480 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotOriented.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java deleted file mode 100644 index fe58bb6..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueAuto.java +++ /dev/null @@ -1,303 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.Tuning.draw; -import static org.firstinspires.ftc.teamcode.Tuning.follower; - -import com.acmerobotics.dashboard.config.Config; -import com.bylazar.configurables.PanelsConfigurables; -import com.pedropathing.geometry.BezierCurve; -import com.pedropathing.geometry.BezierLine; -import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.PathChain; -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.constants.Constants; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -@Config -@Autonomous(name = "Blue Far Auto - Thanks Angela") -public class BlueAuto extends BaseRobot { - private PathChain forwards; - private PathChain forwards_again; - private PathChain intake_1; - private PathChain outtake_1; - private PathChain attack_the_human_move; - private PathChain attack_the_human_go_time; - private PathChain return_to_mama; - - enum AutoState { - MOVING_1 (1.0), - MOVING_2 (2.0), - MOVING_3 (4.0), - MOVING_4 (1.25), - MOVING_5 (3.0), - MOVING_6 (3.0), - MOVING_7 (3.0), - DONE (Double.POSITIVE_INFINITY); - - AutoState(double timer) { - this.timer = timer; - } - - double timer; - } - - AutoState autoState; - long state_start; - long start; - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = false; - PestoFTCConfig.initializeDrive = false; - super.initialize(); - - FrontalLobe.update(); - MotorCortex.update(); - - follower = Constants.createFollower(hardwareMap); - PanelsConfigurables.INSTANCE.refreshClass(this); - - follower.setStartingPose(new Pose(0, 0)); - - autoState = AutoState.MOVING_1; - - hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); - hoodSubsystem.update(); - - follower.update(); - follower.activateDrive(); - follower.setMaxPower(0.7); - - forwards = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) - .setLinearHeadingInterpolation(0, 0.36) - .build(); - - forwards_again = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(4, 0), new Pose(33, 0))) - .setLinearHeadingInterpolation(0.38, Math.PI/2) - .build(); - - intake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(33, 0), new Pose(33, 40))) - .setConstantHeadingInterpolation(Math.PI/2) - .build(); - - outtake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(33, 40), new Pose(4, 0))) - .setLinearHeadingInterpolation(Math.PI/2, 0.40) - .build(); - - attack_the_human_move = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, 46.5))) - .setConstantHeadingInterpolation(Math.PI) - .build(); - - attack_the_human_go_time = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(40, 46.5), new Pose(8, 46.5))) - .setConstantHeadingInterpolation(Math.PI) - .build(); - - return_to_mama = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(8, 46.5), new Pose(32, 0), new Pose(5, 0))) - .setLinearHeadingInterpolation(Math.PI, 0.4) - .build(); - - follower.followPath(forwards, true); - - outtakeSubsystem.setPower(PestoFTCConfig.AUTO_FAR); - - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - - waitForStart(); - - follower.setPose(new Pose(0, 0)); - - state_start = System.nanoTime(); - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - - if (autoState != AutoState.DONE) - follower.update(); - - draw(); - - if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { - switch (autoState) { - case MOVING_1: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - autoState = AutoState.MOVING_2; - state_start = System.nanoTime(); - follower.followPath(forwards_again, true); - break; - case MOVING_2: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - autoState = AutoState.MOVING_3; - follower.followPath(intake_1, true); - follower.setMaxPower(0.5); - break; - case MOVING_3: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - autoState = AutoState.MOVING_4; - state_start = System.nanoTime(); - follower.followPath(outtake_1, true); - follower.setMaxPower(1.0); - break; - case MOVING_4: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - follower.followPath(attack_the_human_move, true); - autoState = AutoState.MOVING_5; - break; - case MOVING_5: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - follower.followPath(attack_the_human_go_time, true); - follower.setMaxPower(0.5); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_6; - break; - case MOVING_6: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - follower.followPath(return_to_mama, true); - follower.setMaxPower(1.0); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_7; - break; - case MOVING_7: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - autoState = AutoState.DONE; - break; - } - } - - telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); - telemetry.addData("timer", autoState.timer); - telemetry.addData("state", autoState); - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - } - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java deleted file mode 100644 index f0d4f74..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BlueCloseAuto.java +++ /dev/null @@ -1,304 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.Tuning.draw; -import static org.firstinspires.ftc.teamcode.Tuning.follower; - -import com.acmerobotics.dashboard.config.Config; -import com.bylazar.configurables.PanelsConfigurables; -import com.pedropathing.geometry.BezierCurve; -import com.pedropathing.geometry.BezierLine; -import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.PathChain; -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.constants.Constants; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -@Config -@Autonomous(name = "Blue Close Auto - Thanks Angela") -public class BlueCloseAuto extends BaseRobot { - private PathChain forwards; - private PathChain forwards_again; - private PathChain intake_1; - private PathChain outtake_1; - private PathChain attack_the_human_move; - private PathChain attack_the_human_go_time; - private PathChain return_to_mama; - - enum AutoState { - MOVING_1 (1.0), - MOVING_2 (4.0), - MOVING_3 (4.0), - MOVING_4 (1.25), - MOVING_5 (3.0), - MOVING_6 (3.0), - MOVING_7 (3.0), - DONE (Double.POSITIVE_INFINITY); - - AutoState(double timer) { - this.timer = timer; - } - - double timer; - } - - AutoState autoState; - long state_start; - long start; - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = false; - PestoFTCConfig.initializeDrive = false; - super.initialize(); - - FrontalLobe.update(); - MotorCortex.update(); - - follower = Constants.createFollower(hardwareMap); - PanelsConfigurables.INSTANCE.refreshClass(this); - - follower.setStartingPose(new Pose(0, 0)); - - autoState = AutoState.MOVING_1; - - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - hoodSubsystem.update(); - - follower.update(); - follower.activateDrive(); - follower.setMaxPower(0.7); - - forwards = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) - .setLinearHeadingInterpolation(0, -Math.PI/2) - .build(); - - forwards_again = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(4, 0), new Pose(57, 0))) - .setConstantHeadingInterpolation(-Math.PI/2) - .build(); - - intake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(57, 0), new Pose(57, -40))) - .setConstantHeadingInterpolation(-Math.PI/2) - .build(); - - outtake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(57, -40), new Pose(4, 0))) - .setLinearHeadingInterpolation(-Math.PI/2, -0.40) - .build(); - - attack_the_human_move = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, -46.5))) - .setConstantHeadingInterpolation(-Math.PI) - .build(); - - attack_the_human_go_time = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(40, -46.5), new Pose(8, -46.5))) - .setConstantHeadingInterpolation(-Math.PI) - .build(); - - return_to_mama = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(8, -46.5), new Pose(32, 0), new Pose(5, 0))) - .setLinearHeadingInterpolation(-Math.PI, -0.4) - .build(); - - follower.followPath(forwards, true); - - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); - - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - - waitForStart(); - - follower.setPose(new Pose(0, 0)); - - state_start = System.nanoTime(); - - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - - if (autoState != AutoState.DONE) - follower.update(); - - draw(); - - if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { - switch (autoState) { - case MOVING_1: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - autoState = AutoState.MOVING_2; - state_start = System.nanoTime(); - follower.followPath(forwards_again, true); - break; - case MOVING_2: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - autoState = AutoState.MOVING_3; - follower.followPath(intake_1, true); - follower.setMaxPower(0.5); - break; - case MOVING_3: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - autoState = AutoState.MOVING_4; - state_start = System.nanoTime(); - follower.followPath(outtake_1, true); - follower.setMaxPower(1.0); - break; - case MOVING_4: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - follower.followPath(attack_the_human_move, true); - autoState = AutoState.MOVING_5; - break; - case MOVING_5: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - follower.followPath(attack_the_human_go_time, true); - follower.setMaxPower(0.5); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_6; - break; - case MOVING_6: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - follower.followPath(return_to_mama, true); - follower.setMaxPower(1.0); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_7; - break; - case MOVING_7: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - autoState = AutoState.DONE; - break; - } - } - - telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); - telemetry.addData("timer", autoState.timer); - telemetry.addData("state", autoState); - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - } - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java index b125942..7caa523 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java @@ -1,6 +1,5 @@ package org.firstinspires.ftc.teamcode; -import com.acmerobotics.dashboard.config.variable.QualitativeData; import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; @@ -9,11 +8,9 @@ import com.shprobotics.pestocore.processing.MotorCortex; import com.shprobotics.pestocore.processing.PestoTelemetry; -import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; @@ -84,7 +81,7 @@ public void runOpMode() { intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); +// indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); } if (outtaking && state != RobotState.OUTTAKE) { @@ -99,7 +96,7 @@ public void runOpMode() { intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); +// indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); } if (neutralizing) { @@ -108,11 +105,11 @@ public void runOpMode() { intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); +// indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); } - // Nice little LED display on the gamepad +// // Nice little LED display on the gamepad if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); @@ -122,7 +119,7 @@ public void runOpMode() { if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); - // Cycle hood modes +// // Cycle hood modes if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); @@ -140,25 +137,24 @@ public void runOpMode() { hoodSubsystem.update(); intakeSubsystem.update(); outtakeSubsystem.update(); - indexerSubsystem.update(); +// indexerSubsystem.update(); - double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; - double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; - double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; +// double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; +// double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; +// double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; - pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); - pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); - pestoTelemetry.update(); +// pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); +// pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); +// pestoTelemetry.update(); telemetry.addData("x", tracker.getCurrentPosition().getX()); telemetry.addData("y", tracker.getCurrentPosition().getY()); telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); telemetry.addData("target", intakeSubsystem.dropdownTarget); telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); - telemetry.addData("dx", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).xRotationRate); - telemetry.addData("dy", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).yRotationRate); - telemetry.addData("dz", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).zRotationRate); -// telemetry.update(); +// telemetry.addData("dx", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).xRotationRate); +// telemetry.addData("dy", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).yRotationRate); +// telemetry.addData("dz", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).zRotationRate); telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 9e32999..7d996ee 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -8,7 +8,6 @@ import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; import com.shprobotics.pestocore.drivebases.trackers.DeterministicTracker; import com.shprobotics.pestocore.drivebases.trackers.ThreeWheelOdometryTracker; -import com.shprobotics.pestocore.geometries.Vector2D; import com.shprobotics.pestocore.processing.Cerebrum; import com.shprobotics.pestocore.processing.ConfigInterface; import com.shprobotics.pestocore.processing.FrontalLobe; @@ -23,9 +22,9 @@ public class PestoFTCConfig implements ConfigInterface { public static boolean initializeDrive = true; // ODOMETRY - private static String leftName = "left"; - private static String centerName = "frontRight"; - private static String rightName = "right"; + private static String leftName = "backLeft"; + private static String centerName = "frontLeft"; + private static String rightName = "backRight"; private static DcMotorSimple.Direction leftDirection = DcMotorSimple.Direction.REVERSE; private static DcMotorSimple.Direction centerDirection = DcMotorSimple.Direction.REVERSE; @@ -33,7 +32,7 @@ public class PestoFTCConfig implements ConfigInterface { private static double ODOMETRY_TICKS_PER_INCH = 505.3169; public static double FORWARD_OFFSET = -1.565; - public static double ODOMETRY_WIDTH = 13.567; + public static double ODOMETRY_WIDTH = 9.1188; public static double FORWARD_VELOCITY = 76; public static double STRAFE_VELOCITY = 61; @@ -49,10 +48,10 @@ public class PestoFTCConfig implements ConfigInterface { public static double INDEXER_BLOCK = 0.24; // HOOD - public static double HOOD_CLOSE = 0.070; - public static double HOOD_MID = 0.1; - public static double HOOD_FAR = 0.1131; - public static double HOOD_AUTO_FAR = 0.115; + public static double HOOD_CLOSE = 0.01; + public static double HOOD_MID = 0.04; + public static double HOOD_FAR = 0.01; + public static double HOOD_AUTO_FAR = 0.01; // SHOOTER public static double SHOOTER_CLOSE = 0.70; @@ -84,12 +83,12 @@ public static void initialize(HardwareMap hardwareMap) { DcMotorSimple.Direction.FORWARD }); - driveController.setPowerVectors(new Vector2D[]{ - new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), - new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), - new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), - new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)) - }); +// driveController.setPowerVectors(new Vector2D[]{ +// new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), +// new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), +// new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), +// new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)) +// }); driveController.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); // driveController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java deleted file mode 100644 index 63d3234..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedAuto.java +++ /dev/null @@ -1,303 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.Tuning.draw; -import static org.firstinspires.ftc.teamcode.Tuning.follower; - -import com.acmerobotics.dashboard.config.Config; -import com.bylazar.configurables.PanelsConfigurables; -import com.pedropathing.geometry.BezierCurve; -import com.pedropathing.geometry.BezierLine; -import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.PathChain; -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.constants.Constants; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -@Config -@Autonomous(name = "Red Far Auto - Thanks Angela") -public class RedAuto extends BaseRobot { - private PathChain forwards; - private PathChain forwards_again; - private PathChain intake_1; - private PathChain outtake_1; - private PathChain attack_the_human_move; - private PathChain attack_the_human_go_time; - private PathChain return_to_mama; - - enum AutoState { - MOVING_1 (1.0), - MOVING_2 (2.0), - MOVING_3 (4.0), - MOVING_4 (1.25), - MOVING_5 (3.0), - MOVING_6 (3.0), - MOVING_7 (3.0), - DONE (Double.POSITIVE_INFINITY); - - AutoState(double timer) { - this.timer = timer; - } - - double timer; - } - - AutoState autoState; - long state_start; - long start; - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = false; - PestoFTCConfig.initializeDrive = false; - super.initialize(); - - FrontalLobe.update(); - MotorCortex.update(); - - follower = Constants.createFollower(hardwareMap); - PanelsConfigurables.INSTANCE.refreshClass(this); - - follower.setStartingPose(new Pose(0, 0)); - - autoState = AutoState.MOVING_1; - - hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); - hoodSubsystem.update(); - - follower.update(); - follower.activateDrive(); - follower.setMaxPower(0.7); - - forwards = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) - .setLinearHeadingInterpolation(0, -0.36) - .build(); - - forwards_again = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(4, 0), new Pose(33, 0))) - .setLinearHeadingInterpolation(-0.38, -Math.PI/2) - .build(); - - intake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(33, 0), new Pose(33, -40))) - .setConstantHeadingInterpolation(-Math.PI/2) - .build(); - - outtake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(33, -40), new Pose(4, 0))) - .setLinearHeadingInterpolation(-Math.PI/2, -0.40) - .build(); - - attack_the_human_move = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, -46.5))) - .setConstantHeadingInterpolation(-Math.PI) - .build(); - - attack_the_human_go_time = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(40, -46.5), new Pose(8, -46.5))) - .setConstantHeadingInterpolation(-Math.PI) - .build(); - - return_to_mama = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(8, -46.5), new Pose(32, 0), new Pose(5, 0))) - .setLinearHeadingInterpolation(-Math.PI, -0.4) - .build(); - - follower.followPath(forwards, true); - - outtakeSubsystem.setPower(PestoFTCConfig.AUTO_FAR); - - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - - waitForStart(); - - follower.setPose(new Pose(0, 0)); - - state_start = System.nanoTime(); - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - - if (autoState != AutoState.DONE) - follower.update(); - - draw(); - - if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { - switch (autoState) { - case MOVING_1: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - autoState = AutoState.MOVING_2; - state_start = System.nanoTime(); - follower.followPath(forwards_again, true); - break; - case MOVING_2: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - autoState = AutoState.MOVING_3; - follower.followPath(intake_1, true); - follower.setMaxPower(0.5); - break; - case MOVING_3: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - autoState = AutoState.MOVING_4; - state_start = System.nanoTime(); - follower.followPath(outtake_1, true); - follower.setMaxPower(1.0); - break; - case MOVING_4: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - follower.followPath(attack_the_human_move, true); - autoState = AutoState.MOVING_5; - break; - case MOVING_5: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - follower.followPath(attack_the_human_go_time, true); - follower.setMaxPower(0.5); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_6; - break; - case MOVING_6: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - follower.followPath(return_to_mama, true); - follower.setMaxPower(1.0); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_7; - break; - case MOVING_7: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - autoState = AutoState.DONE; - break; - } - } - - telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); - telemetry.addData("timer", autoState.timer); - telemetry.addData("state", autoState); - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - } - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java deleted file mode 100644 index 72065d2..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RedCloseAuto.java +++ /dev/null @@ -1,303 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.Tuning.draw; -import static org.firstinspires.ftc.teamcode.Tuning.follower; - -import com.acmerobotics.dashboard.config.Config; -import com.bylazar.configurables.PanelsConfigurables; -import com.pedropathing.geometry.BezierCurve; -import com.pedropathing.geometry.BezierLine; -import com.pedropathing.geometry.Pose; -import com.pedropathing.paths.PathChain; -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.constants.Constants; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -@Config -@Autonomous(name = "Red Close Auto - Thanks Angela") -public class RedCloseAuto extends BaseRobot { - private PathChain forwards; - private PathChain forwards_again; - private PathChain intake_1; - private PathChain outtake_1; - private PathChain attack_the_human_move; - private PathChain attack_the_human_go_time; - private PathChain return_to_mama; - - enum AutoState { - MOVING_1 (1.0), - MOVING_2 (4.0), - MOVING_3 (4.0), - MOVING_4 (1.25), - MOVING_5 (3.0), - MOVING_6 (3.0), - MOVING_7 (3.0), - DONE (Double.POSITIVE_INFINITY); - - AutoState(double timer) { - this.timer = timer; - } - - double timer; - } - - AutoState autoState; - long state_start; - long start; - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = false; - PestoFTCConfig.initializeDrive = false; - super.initialize(); - - FrontalLobe.update(); - MotorCortex.update(); - - follower = Constants.createFollower(hardwareMap); - PanelsConfigurables.INSTANCE.refreshClass(this); - - follower.setStartingPose(new Pose(0, 0)); - - autoState = AutoState.MOVING_1; - - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - hoodSubsystem.update(); - - follower.update(); - follower.activateDrive(); - follower.setMaxPower(0.7); - - forwards = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(0,0), new Pose(4,0))) - .setLinearHeadingInterpolation(0, Math.PI/2) - .build(); - - forwards_again = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(4, 0), new Pose(57, 0))) - .setConstantHeadingInterpolation(Math.PI/2) - .build(); - - intake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(57, 0), new Pose(57, 40))) - .setConstantHeadingInterpolation(Math.PI/2) - .build(); - - outtake_1 = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(57, -40), new Pose(4, 0))) - .setLinearHeadingInterpolation(Math.PI/2, -0.40) - .build(); - - attack_the_human_move = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(4, 0), new Pose(20, 0), new Pose(40, -46.5))) - .setConstantHeadingInterpolation(-Math.PI) - .build(); - - attack_the_human_go_time = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(40, -46.5), new Pose(8, -46.5))) - .setConstantHeadingInterpolation(-Math.PI) - .build(); - - return_to_mama = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierCurve(new Pose(8, -46.5), new Pose(32, 0), new Pose(5, 0))) - .setLinearHeadingInterpolation(-Math.PI, -0.4) - .build(); - - follower.followPath(forwards, true); - - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); - - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - - waitForStart(); - - follower.setPose(new Pose(0, 0)); - - state_start = System.nanoTime(); - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - - if (autoState != AutoState.DONE) - follower.update(); - - draw(); - - if (((System.nanoTime() - state_start) / 1E9) > autoState.timer) { - switch (autoState) { - case MOVING_1: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - autoState = AutoState.MOVING_2; - state_start = System.nanoTime(); - follower.followPath(forwards_again, true); - break; - case MOVING_2: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - autoState = AutoState.MOVING_3; - follower.followPath(intake_1, true); - follower.setMaxPower(0.5); - break; - case MOVING_3: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - autoState = AutoState.MOVING_4; - state_start = System.nanoTime(); - follower.followPath(outtake_1, true); - follower.setMaxPower(1.0); - break; - case MOVING_4: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - follower.followPath(attack_the_human_move, true); - autoState = AutoState.MOVING_5; - break; - case MOVING_5: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - feederSubsystem.update(); - - follower.followPath(attack_the_human_go_time, true); - follower.setMaxPower(0.5); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_6; - break; - case MOVING_6: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - intakeSubsystem.update(); - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - feederSubsystem.update(); - - follower.followPath(return_to_mama, true); - follower.setMaxPower(1.0); - - state_start = System.nanoTime(); - autoState = AutoState.MOVING_7; - break; - case MOVING_7: - FrontalLobe.useMacro("auto_outtake"); - while (opModeIsActive() && !isStopRequested() && FrontalLobe.hasMacro("auto_outtake")) { - MotorCortex.update(); - follower.update(); - FrontalLobe.update(); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - } - start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested() && (System.nanoTime() - start) / 1E9 < 4) { - MotorCortex.update(); - follower.update(); - } - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - outtakeSubsystem.update(); - feederSubsystem.update(); - intakeSubsystem.update(); - indexerSubsystem.update(); - - state_start = System.nanoTime(); - autoState = AutoState.DONE; - break; - } - } - - telemetry.addData("time elapsed", ((System.nanoTime() - state_start) / 1E9)); - telemetry.addData("timer", autoState.timer); - telemetry.addData("state", autoState); - telemetry.addData("x", follower.getPose().getX()); - telemetry.addData("y", follower.getPose().getY()); - telemetry.addData("r", follower.getPose().getHeading()); - telemetry.update(); - } - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotOriented.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotOriented.java deleted file mode 100644 index 075caff..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotOriented.java +++ /dev/null @@ -1,165 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.acmerobotics.dashboard.config.variable.QualitativeData; -import com.qualcomm.hardware.limelightvision.LLResult; -import com.qualcomm.hardware.limelightvision.LLResultTypes; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.shprobotics.pestocore.devices.GamepadKey; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; -import com.shprobotics.pestocore.processing.PestoTelemetry; - -import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -import java.util.List; - -@TeleOp(name = "Robot Oriented") -public class RobotOriented extends BaseRobot { - PestoTelemetry pestoTelemetry; - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = true; - PestoFTCConfig.initializeDrive = true; - pestoTelemetry = FrontalLobe.pestoTelemetry; - - super.initialize(); - - waitForStart(); - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - gamepadInterface1.update(); - tracker.update(); - pestoTelemetry.clear(); - teleOpController.updateSpeed(gamepad1); - - if (gamepad1.b) { - tracker.reset(); - teleOpController.resetIMU(); - } - - boolean intaking = gamepad1.right_trigger > 0.05 && -gamepad1.left_stick_y >= -0.1; - boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; - boolean rejecting = !intaking && !outtaking && gamepad1.right_bumper; - boolean neutralizing = !intaking && !outtaking && !rejecting; - - if (outtaking) { - LLResult result = limelight.getLatestResult(); - - List results = result.getFiducialResults(); - - if (result != null && result.isValid() && results.size() > 0 && results.get(0).getFiducialId() != 21) { - double rotate = -result.getTx()*PestoFTCConfig.KP; - rotate = Math.min(1, Math.max(-1, rotate)); - - if (rotate < 0) - rotate -= PestoFTCConfig.STATIC_DRIVE; - else - rotate += PestoFTCConfig.STATIC_DRIVE; - - teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, rotate); - telemetry.addData("tx", result.getTx()); - } else { - telemetry.addLine("No Target :("); - teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - } - } else - teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - - if (!outtaking && state == RobotState.OUTTAKE) { - FrontalLobe.removeMacros("outtake"); - } - - if (intaking) { - state = RobotState.INTAKE; - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } - - if (outtaking && state != RobotState.OUTTAKE) { - state = RobotState.OUTTAKE; - - FrontalLobe.useMacro("outtake"); - } - - if (rejecting) { - state = RobotState.REJECT; - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); - feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } - - if (neutralizing) { - state = RobotState.NEUTRAL; - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } - - - // Nice little LED display on the gamepad - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) - gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); - - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) - gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); - - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) - gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); - - // Cycle hood modes - if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { - hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { - hoodSubsystem.setState(HoodSubsystem.HoodState.MID); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); - } - } - - feederSubsystem.update(); - hoodSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - indexerSubsystem.update(); - - double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; - double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; - double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; - - pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); - pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); - pestoTelemetry.update(); - - telemetry.addData("x", tracker.getCurrentPosition().getX()); - telemetry.addData("y", tracker.getCurrentPosition().getY()); - telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); - telemetry.addData("target", intakeSubsystem.dropdownTarget); - telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); - telemetry.addData("dx", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).xRotationRate); - telemetry.addData("dy", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).yRotationRate); - telemetry.addData("dz", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).zRotationRate); -// telemetry.update(); - telemetry.update(); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java index 65700d4..a2e8c05 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java @@ -1,31 +1,44 @@ package org.firstinspires.ftc.teamcode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.shprobotics.pestocore.processing.FrontalLobe; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.shprobotics.pestocore.hardware.CortexLinkedMotor; import com.shprobotics.pestocore.processing.MotorCortex; import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; @TeleOp(name = "Test") public class Test extends BaseRobot { @Override public void runOpMode() { - FrontalLobe.initialize(hardwareMap); + MotorCortex.initialize(hardwareMap); - intakeSubsystem = new IntakeSubsystem(); + CortexLinkedMotor frontLeft = MotorCortex.getMotor("frontLeft"); + CortexLinkedMotor frontRight = MotorCortex.getMotor("frontRight"); + CortexLinkedMotor backLeft = MotorCortex.getMotor("backLeft"); + CortexLinkedMotor backRight = MotorCortex.getMotor("backRight"); + + frontLeft.setDirection(DcMotorSimple.Direction.REVERSE); + frontRight.setDirection(DcMotorSimple.Direction.FORWARD); + backLeft.setDirection(DcMotorSimple.Direction.REVERSE); + backRight.setDirection(DcMotorSimple.Direction.FORWARD); waitForStart(); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); + frontLeft.setPowerResult(1.0); + sleep(1000); + frontLeft.setPowerResult(0.0); + + frontRight.setPowerResult(1.0); + sleep(1000); + frontRight.setPowerResult(0.0); - long start = System.nanoTime(); - while (opModeIsActive() && !isStopRequested()) { - intakeSubsystem.update(); - MotorCortex.update(); + backLeft.setPowerResult(1.0); + sleep(1000); + backLeft.setPowerResult(0.0); - telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); - telemetry.update(); - } + backRight.setPowerResult(1.0); + sleep(1000); + backRight.setPowerResult(0.0); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java index 74c5ea9..8608e73 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java @@ -1,6 +1,5 @@ package org.firstinspires.ftc.teamcode.subsystems; -import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.Limelight3A; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.shprobotics.pestocore.devices.GamepadInterface; @@ -51,7 +50,7 @@ public void initialize() { hoodSubsystem = new HoodSubsystem(); intakeSubsystem = new IntakeSubsystem(); outtakeSubsystem = new OuttakeSubsystem(); - indexerSubsystem = new IndexerSubsystem(); +// indexerSubsystem = new IndexerSubsystem(); limelight = hardwareMap.get(Limelight3A.class, "limelight"); @@ -65,27 +64,6 @@ public void initialize() { // MACRO initialization - FrontalLobe.addMacro("auto_outtake", new FrontalLobe.Macro() { - @Override - public void start() { - FrontalLobe.removeOtherMacros(this); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.OUTTAKE); - } - - @Override - public boolean loop(double v) { - // how long (seconds) before starting to move other components - if (v < 1.2) - return false; - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.OUTTAKE); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.OUTTAKE); - - return true; - } - }); - FrontalLobe.addMacro("outtake", new FrontalLobe.Macro() { @Override public void start() { @@ -101,39 +79,39 @@ public boolean loop(double v) { feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); intakeSubsystem.setState(IntakeSubsystem.IntakeState.OUTTAKE); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.OUTTAKE); +// indexerSubsystem.setState(IndexerSubsystem.IndexerState.OUTTAKE); return true; } }); - FrontalLobe.addMacro("limelight - align", new FrontalLobe.Macro() { - @Override - public void start() { - - } - - @Override - public boolean loop(double v) { - LLResult result = limelight.getLatestResult(); - if (result != null && result.isValid()) { - telemetry.addData("tx", result.getTx()); - telemetry.update(); - - double rotate = -result.getTx() * PestoFTCConfig.KP; - rotate = Math.min(1, Math.max(-1, rotate)); - - if (rotate < 0) - rotate -= PestoFTCConfig.STATIC_DRIVE; - else - rotate += PestoFTCConfig.STATIC_DRIVE; - - teleOpController.driveRobotCentric(0, 0, rotate); - } - - return v > 2.0; - } - }); +// FrontalLobe.addMacro("limelight - align", new FrontalLobe.Macro() { +// @Override +// public void start() { +// +// } +// +// @Override +// public boolean loop(double v) { +// LLResult result = limelight.getLatestResult(); +// if (result != null && result.isValid()) { +// telemetry.addData("tx", result.getTx()); +// telemetry.update(); +// +// double rotate = -result.getTx() * PestoFTCConfig.KP; +// rotate = Math.min(1, Math.max(-1, rotate)); +// +// if (rotate < 0) +// rotate -= PestoFTCConfig.STATIC_DRIVE; +// else +// rotate += PestoFTCConfig.STATIC_DRIVE; +// +// teleOpController.driveRobotCentric(0, 0, rotate); +// } +// +// return v > 2.0; +// } +// }); } @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java index 9749443..1db45ec 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java @@ -56,31 +56,26 @@ public void setState(IntakeState state) { public void update() { if (state == INTAKE) { intake.setPowerResult(1.0); -// dropdown.setPositionResult(DROPDOWN_INTAKE); dropdownTarget = DROPDOWN_INTAKE; } if (state == NEUTRAL) { intake.setPowerResult(0.15); -// dropdown.setPositionResult(DROPDOWN_DRIVE); dropdownTarget = DROPDOWN_DRIVE; } if (state == REJECT) { intake.setPowerResult(-1.0); -// dropdown.setPositionResult(DROPDOWN_INTAKE); dropdownTarget = DROPDOWN_INTAKE; } if (state == OUTTAKE) { intake.setPowerResult(1.0); -// dropdown.setPositionResult(DROPDOWN_PUSH); dropdownTarget = DROPDOWN_PUSH; } if (state == OUTTAKE_AUTO) { intake.setPowerResult(1.0); -// dropdown.setPositionResult(DROPDOWN_PUSH_AUTO); dropdownTarget = DROPDOWN_PUSH_AUTO; } From ef4ada6ba52c10f9774804ec4b25eff7bfc56e59 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Sun, 11 Jan 2026 15:17:26 -0800 Subject: [PATCH 09/25] quick save --- .../ftc/teamcode/FieldOriented.java | 66 +- .../ftc/teamcode/PestoFTCConfig.java | 17 +- .../org/firstinspires/ftc/teamcode/Test.java | 44 - .../firstinspires/ftc/teamcode/Tuning.java | 1364 ----------------- .../org/firstinspires/ftc/teamcode/Utils.java | 43 + .../ftc/teamcode/autonomous/RedFar.java | 80 + .../ftc/teamcode/autonomous/RedFarPaths.java | 68 + .../ftc/teamcode/constants/Constants.java | 73 - .../ftc/teamcode/subsystems/BaseRobot.java | 38 +- .../teamcode/subsystems/IntakeSubsystem.java | 2 +- libs/PestoCore-release.aar | Bin 106808 -> 98608 bytes 11 files changed, 248 insertions(+), 1547 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java index 7caa523..3747ebd 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java @@ -3,14 +3,16 @@ import com.qualcomm.hardware.limelightvision.LLResult; import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotor; import com.shprobotics.pestocore.devices.GamepadKey; import com.shprobotics.pestocore.processing.FrontalLobe; import com.shprobotics.pestocore.processing.MotorCortex; -import com.shprobotics.pestocore.processing.PestoTelemetry; +import org.apache.commons.math3.util.MathUtils; import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; @@ -18,13 +20,12 @@ @TeleOp(name = "Field Oriented") public class FieldOriented extends BaseRobot { - PestoTelemetry pestoTelemetry; - @Override public void runOpMode() { PestoFTCConfig.initializePinpoint = true; - PestoFTCConfig.initializeDrive = true; - pestoTelemetry = FrontalLobe.pestoTelemetry; + boolean braking = false; + boolean rotationLocked = false; + double angle = 0.0; super.initialize(); @@ -35,20 +36,46 @@ public void runOpMode() { MotorCortex.update(); gamepadInterface1.update(); tracker.update(); - pestoTelemetry.clear(); teleOpController.updateSpeed(gamepad1); - if (gamepad1.b) { + if (gamepadInterface1.isKeyDown(GamepadKey.B)) { + braking = !braking; + mecanumController.setZeroPowerBehavior(braking ? DcMotor.ZeroPowerBehavior.BRAKE : DcMotor.ZeroPowerBehavior.FLOAT); + } + + if (gamepadInterface1.isKeyDown(GamepadKey.RIGHT_BUMPER)) { + rotationLocked = !rotationLocked; + + double[] angles = new double[]{0.0, Math.PI / 2, Math.PI, 3 * Math.PI / 2}; + double bestDist = Double.POSITIVE_INFINITY; + + for (double x : angles) { + double dist = Math.abs(x - MathUtils.normalizeAngle(tracker.getCurrentPosition().getHeadingRadians(), x)); + + if (dist < bestDist) { + bestDist = dist; + angle = x; + } + } + } + + if (gamepad1.x) { tracker.reset(); teleOpController.resetIMU(); } - boolean intaking = gamepad1.right_trigger > 0.05 && -gamepad1.left_stick_y >= -0.1; + boolean intaking = gamepad1.right_trigger > 0.05; boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; - boolean rejecting = !intaking && !outtaking && gamepad1.right_bumper; + boolean rejecting = !intaking && !outtaking && gamepad1.a; boolean neutralizing = !intaking && !outtaking && !rejecting; - if (outtaking) { + if (rotationLocked) { + double correction = angle - MathUtils.normalizeAngle(tracker.getCurrentPosition().getHeadingRadians(), angle); + correction = correction * -0.6; // 0.6 == headingKP + correction += Math.signum(correction) * PestoFTCConfig.STATIC_DRIVE; + + teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, correction); + } else if (outtaking) { LLResult result = limelight.getLatestResult(); List results = result.getFiducialResults(); @@ -81,7 +108,7 @@ public void runOpMode() { intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); -// indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); } if (outtaking && state != RobotState.OUTTAKE) { @@ -96,7 +123,7 @@ public void runOpMode() { intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); -// indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); } if (neutralizing) { @@ -105,7 +132,7 @@ public void runOpMode() { intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); -// indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); } @@ -137,24 +164,13 @@ public void runOpMode() { hoodSubsystem.update(); intakeSubsystem.update(); outtakeSubsystem.update(); -// indexerSubsystem.update(); - -// double x = Math.round(tracker.getCurrentPosition().getX() * 100) / 100.0; -// double y = Math.round(tracker.getCurrentPosition().getY() * 100) / 100.0; -// double r = Math.round(tracker.getCurrentPosition().getHeadingRadians() * 100) / 100.0; - -// pestoTelemetry.addToDash(new QualitativeData("x, y, r", String.format("%.2f, %.2f, %.2f", x, y, r))); -// pestoTelemetry.addToDash(new QualitativeData("d", String.format("%.2f", hoodSubsystem.getDistance()))); -// pestoTelemetry.update(); + indexerSubsystem.update(); telemetry.addData("x", tracker.getCurrentPosition().getX()); telemetry.addData("y", tracker.getCurrentPosition().getY()); telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); telemetry.addData("target", intakeSubsystem.dropdownTarget); telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); -// telemetry.addData("dx", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).xRotationRate); -// telemetry.addData("dy", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).yRotationRate); -// telemetry.addData("dz", intakeSubsystem.imu.getRobotAngularVelocity(AngleUnit.DEGREES).zRotationRate); telemetry.update(); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 7d996ee..7add005 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -4,6 +4,7 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; +import com.shprobotics.pestocore.algorithms.Constants; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; import com.shprobotics.pestocore.drivebases.trackers.DeterministicTracker; @@ -19,7 +20,10 @@ public class PestoFTCConfig implements ConfigInterface { private static boolean initialized = false; // don't mess with this :O public static boolean initializePinpoint = true; - public static boolean initializeDrive = true; + + public static double mass = 21.7; // lbs + public static double MAX_FORCE = 2220; + public static double DECELERATION = 76; // ODOMETRY private static String leftName = "backLeft"; @@ -32,10 +36,8 @@ public class PestoFTCConfig implements ConfigInterface { private static double ODOMETRY_TICKS_PER_INCH = 505.3169; public static double FORWARD_OFFSET = -1.565; - public static double ODOMETRY_WIDTH = 9.1188; + public static double ODOMETRY_WIDTH = 9.102; - public static double FORWARD_VELOCITY = 76; - public static double STRAFE_VELOCITY = 61; // DROPDOWN public static double DROPDOWN_DRIVE = 35; // 0.29; @@ -44,7 +46,7 @@ public class PestoFTCConfig implements ConfigInterface { public static double DROPDOWN_PUSH_AUTO = 35; // 0.29; // INDEXER - public static double INDEXER_OUTTAKE = 0.08; + public static double INDEXER_OUTTAKE = 0.10; public static double INDEXER_BLOCK = 0.24; // HOOD @@ -63,8 +65,6 @@ public class PestoFTCConfig implements ConfigInterface { public static double STATIC_DRIVE = 0.05; public static double KP = 0.015; - public static double DECELERATION = 45.0; - public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); Cerebrum.initialize(); @@ -124,12 +124,13 @@ public static void initialize(HardwareMap hardwareMap) { teleOpController.setSpeedController(gamepad -> gamepad.left_bumper ? 0.6 : 1.0); -// teleOpController.counteractCentripetalForce(tracker, Math.min(STRAFE_VELOCITY, FORWARD_VELOCITY)); + teleOpController.counteractCentripetalForce(tracker, MAX_FORCE); FrontalLobe.teleOpController = teleOpController; FrontalLobe.tracker = tracker; } FrontalLobe.driveController = driveController; + Constants.mass = mass; } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java deleted file mode 100644 index a2e8c05..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Test.java +++ /dev/null @@ -1,44 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.shprobotics.pestocore.hardware.CortexLinkedMotor; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; - -@TeleOp(name = "Test") -public class Test extends BaseRobot { - @Override - public void runOpMode() { - MotorCortex.initialize(hardwareMap); - - CortexLinkedMotor frontLeft = MotorCortex.getMotor("frontLeft"); - CortexLinkedMotor frontRight = MotorCortex.getMotor("frontRight"); - CortexLinkedMotor backLeft = MotorCortex.getMotor("backLeft"); - CortexLinkedMotor backRight = MotorCortex.getMotor("backRight"); - - frontLeft.setDirection(DcMotorSimple.Direction.REVERSE); - frontRight.setDirection(DcMotorSimple.Direction.FORWARD); - backLeft.setDirection(DcMotorSimple.Direction.REVERSE); - backRight.setDirection(DcMotorSimple.Direction.FORWARD); - - waitForStart(); - - frontLeft.setPowerResult(1.0); - sleep(1000); - frontLeft.setPowerResult(0.0); - - frontRight.setPowerResult(1.0); - sleep(1000); - frontRight.setPowerResult(0.0); - - backLeft.setPowerResult(1.0); - sleep(1000); - backLeft.setPowerResult(0.0); - - backRight.setPowerResult(1.0); - sleep(1000); - backRight.setPowerResult(0.0); - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java deleted file mode 100644 index 00340a5..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Tuning.java +++ /dev/null @@ -1,1364 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.Tuning.changes; -import static org.firstinspires.ftc.teamcode.Tuning.draw; -import static org.firstinspires.ftc.teamcode.Tuning.drawOnlyCurrent; -import static org.firstinspires.ftc.teamcode.Tuning.follower; -import static org.firstinspires.ftc.teamcode.Tuning.stopRobot; -import static org.firstinspires.ftc.teamcode.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.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.PoseHistory; -import com.qualcomm.robotcore.eventloop.opmode.OpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; - -import org.firstinspires.ftc.teamcode.constants.Constants; - -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("Line Tuner", Line::new); - p.add("Centripetal Tuner", CentripetalTuner::new); - }); - s.folder("Tests", p -> { - p.add("Line", Line::new); - p.add("Triangle", Triangle::new); - p.add("Circle", Circle::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(); - - Drawing.init(); - } - - @Override - public void onLog(List lines) {} - - public static void drawOnlyCurrent() { - try { - Drawing.drawRobot(follower.getPose()); - Drawing.sendPacket(); - } catch (Exception e) { - throw new RuntimeException("Drawing failed " + e); - } - } - - public static void draw() { - Drawing.drawDebug(follower); - } - - /** 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() { - follower.setStartingPose(new Pose(72,72)); - } - - /** 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(); - drawOnlyCurrent(); - } - - @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); - - draw(); - } -} - -/** - * 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.setStartingPose(new Pose(72,72)); - follower.update(); - drawOnlyCurrent(); - } - - /** 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); - drawOnlyCurrent(); - } - - /** - * 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() - 72) / follower.getPoseTracker().getLocalizer().getForwardMultiplier()))); - telemetryM.update(telemetry); - - draw(); - } -} - -/** - * 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.setStartingPose(new Pose(72,72)); - follower.update(); - drawOnlyCurrent(); - } - - /** 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); - drawOnlyCurrent(); - } - - /** - * 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() - 72) / follower.getPoseTracker().getLocalizer().getLateralMultiplier()))); - telemetryM.update(telemetry); - - draw(); - } -} - -/** - * 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.setStartingPose(new Pose(72,72)); - follower.update(); - drawOnlyCurrent(); - } - - /** 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); - - drawOnlyCurrent(); - } - - /** - * 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); - - draw(); - } -} - -/** - * 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() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** 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(); - drawOnlyCurrent(); - } - - /** 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(); - draw(); - - - if (!end) { - if (Math.abs(follower.getPose().getX()) > (DISTANCE + 72)) { - 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 left 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() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** - * 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 left."); - 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(); - drawOnlyCurrent(); - } - - /** This starts the OpMode by setting the drive motors to run left 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(); - draw(); - - if (!end) { - if (Math.abs(follower.getPose().getY()) > (DISTANCE + 72)) { - 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 = 60; - - private double previousVelocity; - private long previousTimeNano; - - private boolean stopping; - private boolean end; - - @Override - public void init() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** 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(); - drawOnlyCurrent(); - } - - /** 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(); - draw(); - - 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 left 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 = 60; - private double previousVelocity; - private long previousTimeNano; - private boolean stopping; - private boolean end; - - @Override - public void init() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** This initializes the drive motors as well as the Panels telemetry. */ - @Override - public void init_loop() { - telemetryM.debug("The robot will run to the left 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(); - drawOnlyCurrent(); - } - - /** 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(); - draw(); - - 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() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** 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(); - drawOnlyCurrent(); - } - - @Override - public void start() { - follower.deactivateAllPIDFs(); - follower.activateTranslational(); - forwards = new Path(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))); - forwards.setConstantHeadingInterpolation(0); - backwards = new Path(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))); - 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(); - draw(); - - 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.addData("Zero Line", 0); - telemetryM.addData("Error X", follower.errorCalculator.getTranslationalError().getXComponent()); - telemetryM.addData("Error Y", follower.errorCalculator.getTranslationalError().getYComponent()); - 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() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** - * 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(); - drawOnlyCurrent(); - } - - @Override - public void start() { - follower.deactivateAllPIDFs(); - follower.activateHeading(); - forwards = new Path(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))); - forwards.setConstantHeadingInterpolation(0); - backwards = new Path(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))); - 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(); - draw(); - - 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.addData("Zero Line", 0); - telemetryM.addData("Error", follower.errorCalculator.getHeadingError()); - 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() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** - * 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(); - drawOnlyCurrent(); - } - - @Override - public void start() { - follower.deactivateAllPIDFs(); - follower.activateDrive(); - - forwards = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))) - .setConstantHeadingInterpolation(0) - .build(); - - backwards = follower.pathBuilder() - .setGlobalDeceleration() - .addPath(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))) - .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(); - draw(); - -// if (!follower.isBusy()) { -// if (forward) { -// forward = false; -// follower.followPath(backwards); -// } else { -// forward = true; -// follower.followPath(forwards); -// } -// } - - telemetryM.debug("Driving forward?: " + forward); - telemetryM.addData("Zero Line", 0); - telemetryM.addData("Error", follower.errorCalculator.getDriveErrors()[1]); - 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 Line extends OpMode { - public static double DISTANCE = 40; - private boolean forward = true; - - private Path forwards; - private Path backwards; - - @Override - public void init() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** 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(); - drawOnlyCurrent(); - } - - @Override - public void start() { - follower.activateAllPIDFs(); - forwards = new Path(new BezierLine(new Pose(72,72), new Pose(DISTANCE + 72,72))); - forwards.setConstantHeadingInterpolation(0); - backwards = new Path(new BezierLine(new Pose(DISTANCE + 72,72), new Pose(72,72))); - 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(); - draw(); - - 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() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** - * 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(); - drawOnlyCurrent(); - } - - @Override - public void start() { - follower.activateAllPIDFs(); - forwards = new Path(new BezierCurve(new Pose(72,72), new Pose(Math.abs(DISTANCE) + 72,72), new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72))); - backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72), new Pose(Math.abs(DISTANCE) + 72,72), new Pose(72,72))); - - 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(); - draw(); - 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(72, 72, Math.toRadians(0)); - private final Pose interPose = new Pose(24 + 72, -24 + 72, Math.toRadians(90)); - private final Pose endPose = new Pose(24 + 72, 24 + 72, 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(); - draw(); - - if (follower.atParametricEnd()) { - follower.followPath(triangle, true); - } - } - - @Override - public void init() { - follower.setStartingPose(new Pose(72, 72)); - } - - @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(); - drawOnlyCurrent(); - } - - /** 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(72, 72), new Pose(RADIUS + 72, 72), new Pose(RADIUS + 72, RADIUS + 72))) - .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) - .addPath(new BezierCurve(new Pose(RADIUS + 72, RADIUS + 72), new Pose(RADIUS + 72, (2 * RADIUS) + 72), new Pose(72, (2 * RADIUS) + 72))) - .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) - .addPath(new BezierCurve(new Pose(72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, RADIUS + 72))) - .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) - .addPath(new BezierCurve(new Pose(-RADIUS + 72, RADIUS + 72), new Pose(-RADIUS + 72, 72), new Pose(72, 72))) - .setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72)) - .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(); - drawOnlyCurrent(); - } - - @Override - public void init() { - follower.setStartingPose(new Pose(72, 72)); - } - - /** - * 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(); - draw(); - - 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.75 - ); - private static final Style historyLook = new Style( - "", "#4CAF50", 0.75 - ); - - /** - * 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/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java new file mode 100644 index 0000000..a86c99c --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java @@ -0,0 +1,43 @@ +package org.firstinspires.ftc.teamcode; + +import android.util.Pair; + +import java.util.ArrayList; + +public class Utils { + private static ArrayList> timers; + + public static void clear() { + timers = new ArrayList<>(); + } + + public static boolean hasTimer(String id) { + for (Pair timer: timers) { + if (timer.second.equals(id)) + return true; + } + + return false; + } + + public static double getTime(String id) { + for (Pair timer: timers) { + if (timer.second.equals(id)) + return timer.first; + } + + return -1; + } + + public static boolean timer(double time, String id) { + double currentTime = System.nanoTime() / 1E9; + + for (Pair timer: timers) { + if (timer.second.equals(id)) + return time > (currentTime - timer.first); + } + + timers.add(new Pair<>(currentTime, id)); + return true; + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java new file mode 100644 index 0000000..f5ea0a7 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java @@ -0,0 +1,80 @@ +package org.firstinspires.ftc.teamcode.autonomous; + +import static org.firstinspires.ftc.teamcode.autonomous.RedFarPaths.PathState.DONE; + +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.geometries.PathFollower; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; +import org.firstinspires.ftc.teamcode.Utils; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; + +@Autonomous(name = "Red Far") +public class RedFar extends BaseRobot { + RedFarPaths.PathState state; + PathFollower pathFollower; + double start; + + public void nextState() { + switch (state) { + case FIRST_PATH: + state = RedFarPaths.PathState.SECOND_PATH; + break; + case SECOND_PATH: + state = DONE; + break; + case DONE: + break; + } + } + + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = true; + Utils.clear(); + super.initialize(); + + state = RedFarPaths.PathState.FIRST_PATH; + pathFollower = RedFarPaths.getPathFollower(state); + + hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + + waitForStart(); + + start = System.nanoTime() / 1E9; + + while (opModeIsActive() && !isStopRequested()) { + double currentTime = System.nanoTime() / 1E9; + + FrontalLobe.update(); + MotorCortex.update(); + tracker.update(); + + boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; + mecanumController.setIsStatic(isStatic); + + feederSubsystem.update(); + hoodSubsystem.update(); + indexerSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + + if (state == DONE) { + FrontalLobe.driveController.drive(0, 0, 0); + continue; + } + + if (pathFollower.isFinished(0.2, 0.05) || (currentTime - start) > state.getTimer()) + nextState(); + + if (pathFollower != null) + pathFollower.update(); + + telemetry.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java new file mode 100644 index 0000000..b9e54b3 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java @@ -0,0 +1,68 @@ +package org.firstinspires.ftc.teamcode.autonomous; + +import com.shprobotics.pestocore.algorithms.PID; +import com.shprobotics.pestocore.geometries.BezierCurve; +import com.shprobotics.pestocore.geometries.ParametricHeading; +import com.shprobotics.pestocore.geometries.PathContainer; +import com.shprobotics.pestocore.geometries.PathFollower; +import com.shprobotics.pestocore.geometries.Pose; +import com.shprobotics.pestocore.processing.FrontalLobe; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; + +public class RedFarPaths { + public enum PathState { + FIRST_PATH (FIRST_MOVE, 5.0), + SECOND_PATH (FIRST_ROTATE, 5.0), + DONE (null, Double.POSITIVE_INFINITY); + + PathState(PathContainer pathContainer, double timer) { + this.pathContainer = pathContainer; + this.timer = timer; + } + + PathContainer pathContainer; + double timer; + + PathContainer getPath() { + return this.pathContainer; + } + + double getTimer() { + return this.timer; + } + } + + static PathContainer FIRST_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(0, 0), + new Pose(0, 10) + } + ), new ParametricHeading(v -> 0.0)) + .build(); + + static PathContainer FIRST_ROTATE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .setStartPosition(new Pose(0, 10)) + .addCurve(new ParametricHeading(v -> -Math.PI*v/3)) + .build(); + + public static PathFollower getPathFollower(PathState state) { + // TODO: create secondary + PathFollower pathFollower = new PathFollower.PathFollowerBuilder( + FrontalLobe.driveController, + FrontalLobe.tracker, + state.getPath() + ) + .setDeceleration(PestoFTCConfig.DECELERATION) + .setLookAhead(1.5) + .setSpeed(0.75) + .setHeadingPID(new PID(0.3, 0, 0)) + .setEndpointPID(new PID(0.001, 0, 0)) + .build(); + + return pathFollower; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java deleted file mode 100644 index 4ed319c..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Constants.java +++ /dev/null @@ -1,73 +0,0 @@ -package org.firstinspires.ftc.teamcode.constants; - -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.Encoder; -import com.pedropathing.ftc.localization.constants.ThreeWheelConstants; -import com.pedropathing.paths.PathConstraints; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.qualcomm.robotcore.hardware.HardwareMap; - -public class Constants { - public static FollowerConstants followerConstants; - - public static PathConstraints pathConstraints = new PathConstraints(0.99, 100); - - public static MecanumConstants driveConstants = new MecanumConstants() - .maxPower(1.0) - .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 ThreeWheelConstants localizerConstants = new ThreeWheelConstants() - .forwardTicksToInches(0.001978956176) // TODO: tune - .strafeTicksToInches(0.001978956176) // TODO: tune - .turnTicksToInches(0.001978956176) // TODO: tune - .leftPodY(5.05) // TODO: tune - .rightPodY(-5.05) // TODO: tune - .strafePodX(-1.565) // TODO: tune - .leftEncoder_HardwareMapName("fl") - .rightEncoder_HardwareMapName("fr") - .strafeEncoder_HardwareMapName("bl") - .leftEncoderDirection(Encoder.FORWARD) - .rightEncoderDirection(Encoder.FORWARD) - .strafeEncoderDirection(Encoder.REVERSE); - - public static Follower createFollower(HardwareMap hardwareMap) { - followerConstants = new FollowerConstants() - .useSecondaryHeadingPIDF(true) - .useSecondaryDrivePIDF(true) - .useSecondaryTranslationalPIDF(true) - - .headingPIDFSwitch(0.2) - .headingPIDFCoefficients(new PIDFCoefficients(0.8, 0, 0, 0)) - .secondaryHeadingPIDFCoefficients(new PIDFCoefficients(2.0, 0, 0, 0)) - - .drivePIDFSwitch(2) - .drivePIDFCoefficients(new FilteredPIDFCoefficients(0.1, 0, 0.01, 0.6, 0.0)) - .secondaryDrivePIDFCoefficients(new FilteredPIDFCoefficients(0.0, 0, 0.0, 0.0, 0.0)) - - .mass(7.7); // 7.7kg == 17lbs - - followerConstants.setForwardZeroPowerAcceleration(-40.3); - followerConstants.setLateralZeroPowerAcceleration(-85); - - driveConstants.setXVelocity(79.8); - driveConstants.setYVelocity(64); - - return new FollowerBuilder(followerConstants, hardwareMap) - .threeWheelLocalizer(localizerConstants) - .pathConstraints(pathConstraints) - .mecanumDrivetrain(driveConstants) - .build(); - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java index 8608e73..271b389 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java @@ -2,6 +2,7 @@ import com.qualcomm.hardware.limelightvision.Limelight3A; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.hardware.DcMotor; import com.shprobotics.pestocore.devices.GamepadInterface; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; @@ -37,8 +38,9 @@ public enum RobotState { public void initialize() { FrontalLobe.initialize(hardwareMap); - if (PestoFTCConfig.initializeDrive) - mecanumController = (MecanumController) FrontalLobe.driveController; + mecanumController = (MecanumController) FrontalLobe.driveController; + mecanumController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + if (PestoFTCConfig.initializePinpoint) { tracker = FrontalLobe.tracker; tracker.reset(); @@ -50,7 +52,7 @@ public void initialize() { hoodSubsystem = new HoodSubsystem(); intakeSubsystem = new IntakeSubsystem(); outtakeSubsystem = new OuttakeSubsystem(); -// indexerSubsystem = new IndexerSubsystem(); + indexerSubsystem = new IndexerSubsystem(); limelight = hardwareMap.get(Limelight3A.class, "limelight"); @@ -79,39 +81,11 @@ public boolean loop(double v) { feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); intakeSubsystem.setState(IntakeSubsystem.IntakeState.OUTTAKE); -// indexerSubsystem.setState(IndexerSubsystem.IndexerState.OUTTAKE); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.OUTTAKE); return true; } }); - -// FrontalLobe.addMacro("limelight - align", new FrontalLobe.Macro() { -// @Override -// public void start() { -// -// } -// -// @Override -// public boolean loop(double v) { -// LLResult result = limelight.getLatestResult(); -// if (result != null && result.isValid()) { -// telemetry.addData("tx", result.getTx()); -// telemetry.update(); -// -// double rotate = -result.getTx() * PestoFTCConfig.KP; -// rotate = Math.min(1, Math.max(-1, rotate)); -// -// if (rotate < 0) -// rotate -= PestoFTCConfig.STATIC_DRIVE; -// else -// rotate += PestoFTCConfig.STATIC_DRIVE; -// -// teleOpController.driveRobotCentric(0, 0, rotate); -// } -// -// return v > 2.0; -// } -// }); } @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java index 1db45ec..e6b81cc 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java @@ -91,7 +91,7 @@ public void update() { return; } - double error = 0.01 * (dropdownTarget - pitch) - 0.003 * pitchVelocity; + double error = 0.008 * (dropdownTarget - pitch) - 0.003 * pitchVelocity; power = Math.min(1.0, Math.max(-1.0, error)); diff --git a/libs/PestoCore-release.aar b/libs/PestoCore-release.aar index 44d9c7e6fe551e4aca69b97048e49167667d1e1f..7f162ae85290b010d5f98d9c502c04669a9c01ce 100644 GIT binary patch delta 77902 zcmV(xKKq0f1}2BHVjS{_KtQ&e|FA5V?Gv24NSVwTXzGtr^gq-q_mE$tgO1T)tlrJ>+Y5jwFCsZ?^fiA&;H-7(h9F z3b&|pCf6+CHI)@7f7pIRh-3#nXMQY#!4-feLEB`|@(@fXd)EC6w|p9)s#f)CJP7A{ z&3hu622?y$SHCW)_kepC+nckE{81X2FboxZOdq!(W=Ri8e;X|{afod$44(YpZ`Q?J zhYsx!IlE8u8Yoj39Hf-g+qOU!)yhUycqUL}vQW}E1b3BogqCzLb zs&C#)IJji18O00#BGXG$Z3^FYd^pv&vszWHiqx^1b`?q<4a`bx{+ZK1V>h9Mt|+Sy;4O+m zW7)e}f8<#yu_+Bw`f*_(nf8Hb5Jb9%z2E&(r7PF%9Jy7}eMf-^6T2QvA@I-a>JB_1 zMt=hVk^URw{J+hvteuixQt({FB|CQl{Nd+_^?BU$gmdzGg8!G)`>Vg6r4O6rM zIU`ndq!MbFlJKkz+Ywj8Q`W{GH)s0!eS?(}e}NHX87G?p(mv*zG6R$2-d*=o*B)DL zN6XiC0w7gJ-$TLS(WKz0if|%$u6oYFZF|poZLaMZj3jGceFQp23>MC+X_-eeMzzv@ z4%v^OdC9NfNzP)%Uk6Y942{1DI*7q@4t^-y(mP=t>MOwuLHa|ymtg3b&aNZga}tUm zf8e|hdd*m8gXR%(m+lYs)xcha&KxR*E$urd3^NZ;#ew~x)3KsBs|Dvooq;3Sa~)}z zCV~S;PK`;wLn5*p)kzq~KcEvD+H;T{KcRjgKA^bVJ{ecVc1D-6Bo;dVSh9Vr5aMM+ zpG!3WUtDstk#{Jqf4OhKeD*4;Y4ho)e}Ba+n*e6_T+b5*r1~u)&tTAle)lUmTSWzd z`W1sO5?eeFkS*`*(S(ClJ*gsWHVL<Vu{|G*iZl|h)Oqr}&Tai$l*A1Gu~JUmC8 zuMLAfeijeRh4kqAj*A6+#+4d_ID3Lwp-2l&t3BH85^2$Pe@@Kj3!HYNM}}};L!l>RyM;v1o0sIECWZw5!uvmovY7A zFk;Do8;jA!#*(v`Mg2`BiV9((RJ53c*(6^(6aYU?dSDqPn@f7wG=zhiOF&vA5p>>$ zf~Kdanyg*lo2R)+S5_`FFj4b7e_Dgq^ywfvd2X9hz5;s^(8~O!r8-p?4G^k2-k8vN$m`D`I%0Ix%4aNMRQWRHr zHIFn%=i~j(@K1`nu`^bi|DCTwfq>Be-%?yrO7uU8ovrpm0nZ$n&&rsAf8B~W2su@l zlpf|OVK7Ko8B2J65ZOX5PY`(OQ{QT~Ki+Z9c0i|``vz5@UZGm9knCPgJw#?%-1Au6 zThdE>mOhPVK`mBrxZ63w;pBQWf%9?PsP6~G2u2fw+|SJoFN(Z4pC8 zH?m#H&U{Y8g^+*O0ZB&zvI*%)#;vLse~ts@b7>_n(HnBA;(xRm=u$bW=}6skIplz8 z*vD;09InAiM*Zcz#F+SXo#*uJrNSQ|RWn}x>iWBpI&-ojW?9dGfBKl+jmGt1S6|T& zmEF=nwjZ)`DKMGXantF%=9tIUW?+xn77IZKwN-P-@+C6o*waW3N0P>Bw&rCiMWuO& z8@SV;$up!8#a&~W7T3{Zsf}^97*!#UvG|ZJZB}ozi07)5wcj>pc9P)_?3xO=NR&W0 z{h)F<0=HQD<)S1rf7poE!f-Gh!DY20Hvyc%bM33fz>{X?^5_8?fZE+2$}IELbrpof zsLJPT4cid7!5Z0@FuM3|dNb%RqkUBAO`hZ;uon>MUCe>z1MrfcliOUd?AGUQPH zk}yiRV(e4br%q&7bB;{5_NzW!&diePo_XNyB%eS1K}fVR{cGXMd=Qff7`7ZcTb6Z< zTheXeHN}7Xe44fLP%Z4SSOFC^$gx?XQI}4_kX`js!3s&Lsu1=T;!N842RKf8L-M{o>T17k^MGVuRFRc+^Sv@DeE~-$|b>SCEB5duGxZ4u%B>n7{mi zVD6T)qXP$K<^~sNCP3fBNOJ6;MQ*}$>JqG%j#)A>lE&RX!Eo02+@>cHaL(my@Uzg9 za8tH}D6s8U(FjwNR8EQJ1+6&MF%#`v#)w!I)0hc5f7$@|mP%nyMcB-OR2g(-VjSSR zgLps!|4yVk0!yYp>4rsVjic@HGh`yal*7+m!3bJt{X|ZYo)Auh1mSn50U=mi_BtGI z6aU${+%hgHSNWN}F>bL5D_Fz4OBWqcRhQ_mtoq>R*!up8w6Yt4JG&|zqsbm{D_PSr zL%eYtf7(eS0zPk^q&!-C5D;Jh4n^N$;ZVf;9>C zrENp&qpbo4+&Je)Dd=aALn%?oIY#k%0!rx9(NJR@bIPqjn&YeVw%xEUU8?G@_5;uX8JGf7vNxwyq?uH_f4{TG606$ziK3qv zDseITd~he>NQ`e|Z>#x-Ng^~!q%$(~MKQbtY1>dD+zfqthcw68cNf5aL?u3f&hP)R z$6sJAa7g7py>Kmif)lZ8-xh0-TZ!p&`){5nKCrK%5DWz50qXy+E1Q_Q0*y_b7$gjB ze@yKSO{8r9c4RX{W7Gdtyku0+w9r3o30YyVf+ZCN(S!ZTM72?fjMFA4!^8)SqYCme zWsYI#@_FVrg;u6>(=M$yCd?`rIgOJK*S>bpVjZ{aiJM4P+k9oE|HWD?6 zK7Bw9z>x}|iOT?kDB@ru>P(M!Q}*S#RiGpUfAK{vU?#)>c>e1W{&4%!G&!rJzW zv>;hWz18oW36e~#8AS^2Edw(-f09?wah1F20YI%$r~OqaBY%u zjvrC_&_9xLDul1_W^3)E%8SYX3zZJ<^~E!l_-L?;-VgFxhRa-zuyF6#e;())VlwU+ zp=1g^Hj)zO8C91|zfD+Fo0vK!yP)n%zL!$dz|FPOVM+%L-n9Uv8~d3SuW_+;)B{4! zGEHFj=+d2G#GkI8#mGdQ`p|~&iYVVnST_u@SIoCrH%w>FyFB2rKFx&|`Dz)|9diKM zbu=*m3R$(?m#c5^2NNe>|AtvXF(5?PzR# z`$$ZfQp~$I1aAqWugX^%ut8{y0<{C?D?UoSmeMXQ=p%GPCACmP-UWUc#O)&C=MUh7 zq@HBS&T~{pI4QJjdC%gI1`G0ZP|7pdT=_b`tgVIDMM`r;d--xfS+2qQs{21n%f1nG zP<>(_SyGdas^W|!e?{~md}t0Sptnbi`@J@6fF>L5oVX%?-*sAJ>P2s22m>li-EL;_ zdD$O59d)&2HrgRgd2D}vO8is!w%Sg{3eX@RZs;H&%>NbP%b0rnr{s&(q1;uLF+PbB z9?4$Ue0dqYmciG-gS24Sz7LymLCeMin7pgsY5A=Et4bvmf1<9O%KaMv&uK4~q--7=v*6xmB!ljSm z8HnFdBtM7ev}MkTG`Yw+AIz>IkXrFdbl}0#vO`$Mp{bwcM-G7O6-4-k+q8&_DLyT+ zIdzvOC^^Qne_DZoJlBy`?dcB*e5_|v|7AkcWHx@r_Q%STetqJ?-Cx{nAYpT@+gF5P z9u0y#8d74pCh-E@zkK2>VY4N;{q!44TIFHh=afxmOV#Gs2d)3=1YCM!|1F6>xocE% zfTo?>viRN8)6?ju4l!eFx0#e{NvBwznpyIm9;~+hf0$?fuWzmk$<7!#VZTV8z`eX$ zTx{}USlTrWV5)H*N-ir4*O!JVt&d;je6hzJ;$w=xVHpR9WVnw>t+VD%(#>uz>Cq%K z%mv2h_;0#y6tB2eE!?8|tF;9!nX($#a0|$GuUHk|xlYp~jAzg+=u*+7TGbL8*|Mh- zTGxJjf1`+d)qry@kP$I3WzKfi0H)38RA1PxP8I6Y)FGa;y(EPHY2xchKgVoC#{&)} zw$o|xq&A{8wG_j9aHL0EjFs-&&Phouc_6I$X4Yv*#QwtUQXSyU>7lt(kFe(?p-`II zj7yfgXe`^6BdiWOKiC&(D8Gaz4bdZ5ceibsf3Ly5bSm91vZk3NT~*>TiA~+^)yYHR zu~=>V-3MsR73bo#FsHii`1O6nZl@QI>*Da+AAEA6(t(e!jC$^3=ck`!0T!Av~g&iJ{?I% ze_8`}iXCRWl&Xp82R(nE!af-D+=~%Ve+}kJ0)z9#Z?*ADzAbtbH=aO*x<^QV4(V~& zg5jbD7sVawuHcs1EQ-+58ER5v zS~%Vrb06z;_nz!hB{0`frkS?$f4bv>9?9}%x2=`Avu2Ot#&R^v;L;Z1I5w-EAYUhN zL~RcN>A@XdzHuSgMt&jhDK?z4ph!6Fo+9KyP3EHrZXS>5luwD!yRxv zuA2)_%C?H&p33nScVH4ojhh~Yb4ua&aJ7+XZXK5{Hj-Ml<+vg6RAJK)e~?12MbGG= zXw&gk*kO&qT_b8n})P-r;Yta1)$o^+%h# zs~1x^^(w+Jkip^%*>~n~e=D7LRqrXj$f^luo8T*bTx82P99|VES5FP#Su3-Zh_V*Q|f(>;jeVCW=_vI4FsCmWB$zOV%k0~g0c|)lJW?u*dAcTfJ{+9g! z2Psh*#&Is6E~=kM&@zwD?Up!@Y#%bFbKun$xT5yUOkWSDivB7?IkMS_Hev#dfd9A_ zeZX$X;R-3oForG&f9nLD+g4f9m-bj)mV6tpA&AXh-h|)ugZtoTNUtSXEs8LSE;eaP z{j_2nKAEAshB4hr<DqrK&NV&*zy~wLn2IAmN+uC0XeAJI2U*`#Kd=G2v)QO4948No}a<>XC%0T z$G7g~JZo&le|N=ny_wv`J-?4>_9lNR>G)vtOLb3PGwf-{&V7G;%E%zu+Ep@?>SjTv z+|wmgqbPSf_e8nAr4&)VMu3cT&y|QyTzHTEDKvM^>li>*%i$b2$l-oqBDG}!j*#H@ zi?megj-1paDB>kgVk+riQhWs(>lP53Mfw{FuUXs%e}(9Fv_0XY3;?e*IKtbYl|aOC z7S%z*zZ-x5{Z*=PtBhd}GgikPK9@VHMdYykvM6vIjz5Nd2BHZ@V@5n?&hVrZEV)?3 z1LM`MV9!2`L|!T0GXQo|C9Q1HAb}l1r5U<ERN?SharYk6xPA9O~9j9os+E8*k?AkGYQLex!6Zvh8Yt6wP_Owi%dn zmd)I`i0&6aWcW3!lVPpCCp-1RC`f}SH%sgtBI@Dnwb+RcBr#lu6br%cx= zzLfT6VHbbZc<$t=`uYGCzp{eRajV-+2^C9MCyFDbvRc%Tup3f`naI?^Y_ItDe`^v- zcM%63zRy}Rsmtp*%Dr0AcV~|oht+bkO{0&e;I9itGEM(RF^F=_k6z-5O43nblvP{^ zk$RgYq3SI)oF5ZEkq2L<$|)G7pt%ifpEhVuH@0Y>VM4u=94mYVKt})yBNWa8)%7 zN=sTYvH}v4`k#w~J#ta_e+p?1{hjqYpl>8TkrB6L5z?zc7iYn-e|{gwj6A;`UuXUR zq4U0}6SWAnB%83WQqwneuoz5}D-kZ%66MZu)W>BfQ3aN$CDgH#jP6g--Y62QG90Q# zh?aoecKiJ{6t~bkmf%gZxT=snC0=5WQL}`8{~U7YxmXk>Pa)mKe{{1#ERLxu?uHgF zecYSn+|5q^K!mhs3zI0md@ z-8J~MM6%XsW!{-U5Vo7ZN6C5V^p~6b)3gKiI#6jjwkC&`e*)zXm-+=>oRe`9hqOPq zweW>gqwuPOGA02Wf9pt;G!C5|py@w`=&cAPH@sGA@cHU}kPC1(A?3A3c~8;!+yU#2gF=JbrA(R88REjPx&7-8deswy~o;iX8q>CZmbY~84H z(J%0ic15eL59Ua*quXxHbo(dt!UWf*(6AsN_xKt%th*j4BGk)=D7x4e~H;{R|3xj?}UfSfDVNY8@4Iy7n_AW+du}X;IRONlqg(RE@5@CUIeWqb``V zbrP6^Sz{C?=ybYKWl%Nzx`t7F(52Z*`29Q+>PFSTsSKe!o0UwS_UX z&rIJR^4Y>Dr97m{gR=KO@jA@T-_Zvwrj13Zf1H&EF8w79`5*bhZ;z zZI4$Ue``^tfjSsA!URLD?{^)GK@qyPRqUD{gdSbb^*d8~w>5T&89IYEuoY$4M z4pNu5NK%ldE@58zvpdle7Db3(LRM(A+a_N!+>Aa@^F0$gnqma?O#HkG#!q#a3Ewl?Buw( zc<@biEqT@01j76?+rdz(K9*mll|JvReB)I*K~Cmg&<|knf8m|q zm+H^{wXN@S10vp!H|~ytiwZZtjBmu7(h^S89yoI|WxYJfiN3O{xL~>P;sWF=_@_vuXH}x=$<7tRG6JcE*@zBtihpK|KeSW^zJ*?*% znvt-@jX;V`q^wC*8vdJeUNf@b<4`kk#>JN(o+(`02Uea`5lL8!i@KHX zb`LwR(9cjNKzq)}MRomRe*=4MYL*?O&%D5Ji|nz@{e)M+LNg^R{m8|;Fn8Vn4Iew3 z>HzU&U1)az`&s>cSlr1P#Tezw43pHSCZc`~|MUks<@2pX#fri-i%#CQ!psGc{XBdd zauz6@^tJF=<7RnA1iZM zceYk_Hr@X3TO%zve@(~j-#aZCG#{t6UC^sS%&NKJ)Q?{rH+g$>6zskb+%ehQ1N$$Y z%g}nNe!ukH9TIqhD!}P)^|3T{O1@ljvABEgqHpOE!N<=(J*;*S9ME0sIVQ9wdhcIG zOc7_z57W8Yk@&E~H7%ykW3G9kMejxynL-*P0S8?iA05^ze>q!!=+sq@DGKrOJ+yfx;GYnS_nZ0}yc=GF2%L7|TnLW5Y#) zXR1wrc$>aFe_D-jz86!0h?+B?T~Q2~Gx|*V40D9^`SOC9zYxf+3t_ZPbD^9V($}Sq zT;tmfnJal1%+F~jxVmBjUciFmJxjUo!0brC{%00fpoye+xlT8F911qsHJKS;U3l9s$G( z^dPS;Iw*15zc`LXt;5D-3W|qi1bvcoOKfPc^~k8k=k-V=$tiAAL~JjsIch_8Yb_xD5|XdzG6Us; zP(dMfe>4k(>AwM^S$#QN2U>fgmD2BTy)|g)NjP*LFVax92Y>e9@VdWKk0Cm(z0bh& z`($E8j-8hToWJO6forqv`r}HnO`*C4%@NB38Kui}>&CV{nLiOe6tU+_a5l&~s0U(y zeM#FqOJ}3LZ4SOL`6eheoG`=G5_dl*2AlHoe?Xl{G#)4#upT)LYJZ=qJ6^h2TC=xe zGUs%(is^Ftp0zts&2>MO{MM$LtI!e7sjqX7OZKj|Vv{NkGowL^8F~DJ_9;1RDB%@T z#=F?4-nnN;Ii|#+d`<2|=jSlT9n7C5Pxlb$W@-r^!b?bU_X=pWJ8S@G?uZ3yoEBv4 zfABhJ4M%AgMJPp()P|w%5-sXe=>& ztb4EDdgMw17^%O@twdMBA6W|UHOF!7vngSCw79m&D$;H~V_L(g0Sf|qHU-i!m3Y7c zUJ|mJUoNRR81yiNKaPkZtXn#p5~d5je=g{|wLkaQN0+E*F#Q^h`jz2G?$wc|`d*uqsh#)JfH= z#H%!;HS5=mhAfLQD!-bH9;eN!q=_muT@1CGf+<9|4GTWh-T63fR>zMfdxBNkf7O#u ziNE)=LPZ=Pio8oOLb0u=uopRG@f9&0vIZ|@pq-BlQnxrzfo?k;BN`2qDt`Wx@+;?tI zM`C%dy^phx-@T`wdAeS=Q}saWFuoA;;16-BomC5@^FGs0uzp3$D zHf489R~B8gbU4$*{kqf3ljmp=Ge- zKCL=0QcgJ+L(--?7c8kH2KY`jK0OhkA{U}|t4m}D=>fUhotGRDSk_G)TC?jL#4AP| z2XT|TiFjw4Q zTmMX$QK~A*WsMu$(!hlX79bn(#E*oJ} zq>B=A5KYJ=uZ6`RmbaAnJ&%I%K|ywQ6gwBj$b~UC=nXfZ4#n#xe?FVgTa^~PCX zXFE5I=u-~1p0w$bPe(L|9Bb7ic{!}J3@fV(52*Vey=q?Mtj}I{#NhqHOw!nw_n&-_ z&IA_C%eUA}SjrqLm$#sysdq%G zWPi&{L5^+)3$c=wfA;eL9kh=X?ba}mI2p^&njo;Z!HfXNamNuR{V3xOTU@E$=XZty zHvz1RkNK{kt~7v8Km-}>Dj{rsYh`e+u3K#`DF|FrwX?NmiUrwQA+_JU z?IO6Iu~!}Wf8#EgcRai@4i+3!oJApY!i^KM4~mUFZ*V60Q%r?Nf8&q1Yd|&4IXo`R zx}=Jo7$sp0RQzBNOtYtLE9kPv}BaPps{G;=4OyBJ195tIKWEsXZ zXx}_hfe0}%@Pw$)46kzjhYMR)v!l)p2GkOu+Gl`De?X}*tn*XF_=B0hG-;w#Hmasy z{b!qI(e6Tk7TMLoNn#EM%F0{ys%Z}*@{ryoTz z^USH^awCb)`g6CYF4wET*EJ1iZ?!qCnv*ibLmKFv^OukiyR#R}o=GrIetuo5oYrr0 zFyqGY-(e-rk>8Eza~TS0Qvf{aCBKSWX2-J+e|c)%Suc0VxefXg9SkHifAQH@FT$MG zh+2%!SdipzwYWiDaS9~oTpO^H6yR7`X*mutNr#tVGl!(96s*Mm8lX%YCrfkwT%GYa z6!N5hLRFMGvUC4S0lu8zqXPKrwut>)f6Ebq)HKx}hqGr69#d_Ix>l1eZ+nG7?-X|w zAs4DkWS!EF@+^m60Aj|21Ihf6l=6AawOIDw_(#Ou9N8^8E{vo3w2WVX{9U`OCtF!d zCKm>h#Ty0xE4&09+07y0ru!^fFl52N4;F9@)4M{9Z_{OuZZEmpJC+1NH8mfYe~KEu zz)GuZhV7kko}#WEE#F^vJvo}mFZ6!BBb^dTQ+~hRMzz8uhgh2=Us+ScxJ#6XPOaO3 zkaD#~kF46H&GQxlg*QFZ+v*k{y1}rHReh6XhtDIhRe(nIssXwe(A<{8_*)TPxU%FX z$+AVK7nFFiL>B(Us_CM~0$KW@f4uInzG|J#5Hs!05d0&YCQR)A`BF1TL%O(cnKO=U zV$6vscPe+$qh^S^>zN075|W%VlA`Z+5{P-8!Fiq~Uk7VTUCZz>q?;lPq;{eJ`{s)MKg>PwivsnzNxr#e*%_3`=B{l z(s!PCyw;!HduJ?3cee1wPL|Fhd!SU?5xW!qh{+lvz{(M_>DA$|=85d29}PW5;hA&5 zbelHPz(LGadWnu2!OY#1wgkH>vW6;l%ZFIUsm*Q!bHnOd5yqP`RKML)-|0qR*yX*| zJLcBl&tN#$i)dPd+A(f)$^6J!wCD~UU5!cg3i>i$lj z0g2!36GR3^mg_S2zLu!@J&-XHv@eREGf-)(CG+@Z$4Td5+DK=ZfA3KTpmo>vt|k7i zRR<>4!R@2VP}#kQ39C;tbCp1XvnmUMK*349g%||;@CB(Wjo!^-FG4K${Kal;ECtaAFUtDrZ0%(-@%~ zv8m2o=imL3>aKDbgW*1WLvx7Q{>G+pX!(d&Lw($4cd);Wf7$jG3L>N@L9cY@!o#X| zpR2?s5IAkK%+6|cd^5DaYj!!v#p|-Mp;t(zAQkRyaAj3<8Z9|*cJr`Tf^4Yc4{u6X zj8rexR+L)!0sdn^ioH;UcZaagkWg)IMUPqMlmiBMA=$SQA5c#UVJzWoOls}ayDv?8 zWciU(nE^3Le>S>E6hW;*Ie3V$$nvrVw7{6oEBJu0&QTbq?$wZtlTJGA1Sk4X;`>DV ztjf^k((T6e%P;9|;Q8>;fcxw_?{#hdK>DYhBpul&-ugSU0R1m)UOGD(8e9FxrnRZF zsiO_h7U=Z%W7YqR{_E%PxO#aoCiswSOioH-0Mjj`f9X$J#(JSe7#Q#}FZvH|9miu8 zBkEgAcwP{s;G1#+LxV5^o+%2S&$rJPvI02nDvN^?Zt3%JncQN`Lrw440@UvV0_J-8 zh!8_oh_@K+FF5G!hcS@|0@a-uHeB4=A!;{N&e6S z&N~Yme@{;@x0@j6gjw(|^Zpd}I|JQ~Nd5-})x zVRDdc&Gs#<&DUEv*!Lq`fsEVh2fyPkeYW?)5Pd=ZnZsH@qiLq(viy&cfj`9ID99LYrg<1kId+0fbLe_t0GnpJh3)>V=D?ov%8q%bJRTqN^? z1Z}X+z?CV<5FD&2*xFpfE`EkW#THPON06G5aSd?rf_w$K5thLHjQ9C&w&5KcPFF9 ze;nh9?|pEM#e19qJjc-2+QZjye6z0eeYoWkzq17`DSeMFsTys)>ERc&XHQTNk*}nh zd`X!k$#;O39V-t{vQayoVJZ7X6HS)18q-+$9tnaMec8+ki!$|61s>0kS#!_OXHx{s zll}&6i{<20X!fOe`@pyHWV7Ohs-*OXf2fFZP~~@>IWY_za=Gk;GX%3!1;rdSrtzd( z73oLy%EtK$ECEW`@ab}Q!c?+RxXvN%$^w}g0bE}%<+PDVX8Ll?Uos1T#&hnJpx@Rt zt|OdGu(|_Ww5(58nr4C<Z7BpRx@WjOf4$5* zGhoxMh#HVA_8=%*o5Om+_7(T1FcRv38m8D|QG*~Xpe zg(M|{5Xun2LQ{{ZidQ=Q*@0(>o!rk03ybC%`5;&7ru3Pq2Cj20ee-u zkYrsV7CE#6<@`s!LvTn;UuXcB^MK!0xu^oMMx*-Vd>3-Xq_0r!uK<#XSl+(vyjIUK zVHneT`OxGo{9W>bFeXwz(ZXn}V`e_>69KBJyIOCw=hG0#jTt!O?`=Qi!JQr*=LOx3Myj*}9CWpFJ;2mbs90&)WZ z0;2ujR2jrofjZxuMmMP^a zR)-ZT^yQN@+G7XiBGEhaJH4MXMk5tbT7q{=tC`zFk zoKZmm_1m&uXxDK&=fAwr6SirFqtJ)pTdr+aE<2(NP~Bl~i_qQ4)9fM*<3A6({1u&< z;H*7cF$>6g{#e>@oBG3Zf0?gOj6VRAIk!(E?0`itf0w1q2!CXWY@d!#NqCxOsQHPc z3g3RO6FKi(_I6@iNQYPv3o6K7XAVo7n_Eu~;h!9OENR*4sJ-pK= zFy|smf9cFC$(qO|qML#l7OeVhEA#VPOF4nC6T3?2Om^f4j;vura?64=-lweAYvvl0 zErF0s)_VEitb+Y9^l;xb^Crv{5AK#1dRf-eUi~d&{k(fp7j@w=lNlD2-@kRlHgA^D zq`$n!g9HK5{cqy^zoH5zb~dKYjvk73CQkn!f7B1|6Z{YA<3VE(^!OtW2b%mg2|9ze z6z;giy5@b_eJ#=4HF-*5=gq;&_)k_8EgK{*Z%x5&DHDWY1ixX^?)Hr7;Da%$zZfuuA4*rtA8<)g>ueP!iup4Pc>-;Ckb*I+fAad^?5f<_Ay zf6jqhonmDh2(^{T)_O$Ihpd7k!6Ra~sY{uX0{i1l+`*-|?$g<-x@)jb%TnnQM~OF| zget-<7h~Fv4t+_?bho=eSPUwVSDPv+hv6KaL9Yc~LI_runOoJFbP}1vW_foZ#k!`+ z_yRA(hSTNmGHBOKa7|AqdA78GXc?Q^e-ADt+brB*; zuSE<`@=Se`DWF7xn<}$%<~ED%vh2On&!=!T#l|2e41Lqalibe;=3%0^J~1Fvh>jca zxj%8p2gf61=nG_c#tCNa1D&8w?~Os~9&E1^G)@k7JsE`~nb#pB)+or?&4OK4op%h7 z6nnxeb_OULHI_gckfd#t(Eo2@!CbSuZmBCiV$V&V&+- zQBapZjh@^CAlN@bDYAE@!IVEh+u#pyyrGdZ4||WvcqYV=rV!)BB@A+fe?=OoX7(g9 z^z_~Nw>H4d6@K#mcb)|c0;2riBnM?v^S`e9f7$J7HC;C}HT2E-BjbdPqSk!$ACW`K zjKF#-O>kg2f|RuJe38kVpeS^rGbPw*ky%1S#7U%p(3ig*|0r?)TyZ3pzV|c53!1l! z$JOM|;0AB$26fkG{^Ok5f1LLF5dncONCQNDh?!7d0bY2$7xaU($;%)gtJ1|Pwso^j z`3r2fJy5{x><3;>`t}T$|DkRG)!gg z7_8c&igJfO(1d4RfBV5c5S65%7iW$m56jimqOMy?Ewj2%F|%#hgj>X-WYVFnskg-Z z-OxRCH;PqNkGX5az9y5yqrIXyq1{Aj6b}CQ@Pgj@K)rHEmYHth87C!9btgB;corSK z=E)T)KoW2%kpKuZh1l{e1meJk7~O8z_-H7wI$O~wm2I-0f7#sW3N6JVVXMa%BD_ok zj9psF$8@`AnP53EvSKc|vMoaV&JC+p9G=)d_l5amrp|KW_C>Q6|~W zJqxQ^W#bnnFX|s`L{^>-DSo`CNU1@wI*re*XQ$Z5&ej3TA3ZngE`P7CYB4ozspC#l zpLELjF9v%KY{q=1NqX%U%W0q3?1`Omm9g;$^Y;}C!gv@UFTD#{)Qyu@^H#9o*3w@bBJ_Ytu4s44uj__cB=>ozkd1+9}m@7YYkDft@BlFkgACi zy$7#F>YY9Fir)f05^UVN5`xKSynGVG$T~0XW!NcKF?y+2<4iD;-E@(p-T=?HHTPu) ze;Vz%ZktFlpC}q0f_J0|`um`SNgrhg%N}u|WCHXa$)TKyy!5XKQ|_8~XbI=M6Ql_g zWVN@@L~$QU2QK`-+7C*+9o#F}-vcm-c!~US2)TE-tJRVT8}ZTt zVj9Z~aa^no&>($y+QMt=gY7J$dkV!oe??yDX@oPW|q!Px*(; zQ3Xc$+K-&!_TaqRS>OKc=I>@_#-`z4=MfF@-&blKO$|*%4V?}DRccjr6&3{1`5HHi z6~~qv0*E7E&oGk$`Y515S23j6JJW*Y!jL%E2@LDj6I#XvX14+V;k2J5aIO~$e<%k_ zFUeTay{6NhJiSV{{k%UR4G0xnim;_)wwngJ1Ao=N$2$wZ3kJnszxdbT`SYT?5Jt?z ze7ovG6SAm%oi1MA!JFf`DaOJ;Crg6|w?lUy?EDqS9xntnU{I{HwzaxOS!IpsriZBk zdw$3k;`rkcGs&PdoE{tg&BUg-e@U&1Syiu9W9Vl%Awd8xK+(TQxZVSk3I6gkxCp&n z^3yAzRrl(0E%~j-o}?dAu@DLhID0#|+B2F;DJrUD%g8b|N2nty#c z9A6hdNAD3&wV)^AL9~6bD$*cvSvO*#w%)RNUA*OhXQTR7ka|{>>+-flv7P2EDe{S| z{ioxE8=Qbt<11V+lsoou`94scVnV18^h9Oe zxD=cF4M}%|)Rf>A+xQXh43$irJT4~Mt+Y45#%g4yLL=MF2=;%l_KrciMSn}SXjSbp zciGl1+qP}nwr!hVRqe8E+qP}neCKqWei5f5UccyjJJydC`EzE>9GN*H=SWq-bQ#Dt zy5N~u%aT?XkSkat^4U0FCO9Mz-rTTNO(O1?k-K+LCWgSdT80+xd*pw=&-A{4jVUl@Yepvw4ecfQwF&r%jgpvH%zBspwj}m_aQAw6#tE zyeeyRpZ^Wl%lWxxw=6*RbcE-``^5WZ#N)IL-{;c;Xf?=fNf1n#vwx2;7h09zQo@{R ztK?oXay{cZnzi}}NmKMHN0kxT4CNfujnw=6%vdmHx(Io}6Ww4az?d_GE4X$Cx1AMw z?r_pt@~W-CsTI6DZy2fxO5zN z>|N-t{e(XcXnzZ5o|-@U`)^O(xH*G@f~YNq+`@+>NusnF`&`u!r-e;CZyk>s!Qv4p z-e8-kKk4peZI5f$zkSfOs=-0*0m$$$ko{LE^ee%eb7?c8W-2a${S3P?!~0&Ym+XP| zQm0c2d94>=@&3RV!llG&Xk#y}JJeItdzKi2r|I+Wfq#U5UouA4p+)j(xbvn;+a|TO zdRUnN)Yxv}Ah;>kFYL;?zHbw(rb!3Ed#iZ^G4^Q_QDvaLeB z4(tK5&LxhTXR_o?*WGPdSkuzAkWYE~)M)o3UqRiuY0;ZVn(dLDx2oY>do~~_7-F~7 z$O&)SjDJhG0D#Iz6LUmj%27>#aFm7g1Yqos6QtFa02f~N$OroYIcO=p#GW5n(&U}! zK0Myd1v7kKjQp*S+@_J9N9hZUyEw=6ufWlgKT1d0$1yH|chTZlxfFj>1iM^0(Tncd((K zMSnW$c6V(c6Y3A6QhuGe;(ylr>jmi1ke$fNP8%IbOp8pi3)}?hA>RT4tYmt1U-jA1UfztpzteX{qI`9F?bOj?)@a{pfD!KVRek34)73=KY2Ivrdj_Ob&!qx? zjqE2F1#KhVV9b11`|ljAm51+KB*n);zkgx~S*E7}$Mh0|d;{T;n(x%jB0`B`P}|*= zhm7n7BGW><;~Y}}8xxGb6D{}~5#~)zhmaFXdPe4VWX=nu24T5_jw1NrM3{ zV&ujsl*#&o^6Fme2>-Gj$KjI=nGmFky?~_QvEGe+uk)UPdWCtFa!g5Gc0i1>tj$d?RJL z80=f@2Hu~5XcxTi+e(d!zOV37UxF03?dd*B{`y z`Y5{mrOa8K@xEmD1kaBFcP8Qk$lT=_k(!b!#N`|==W#$C!Mhd&!{)d*Af^5u`+p4gF(IZ-au=Exm#ZyU!SG?+GJs`SuoscqL)9poKj29? zI1SsS{4z|Bm(QSpAHBMeQRL-4>20l_VPAa@OLO_kJH+jS=LY0G0n;JHpVInBsC?$+ zf@EWHA%h*DG|%y->OXt>aN$+EauW4gpa6PVL2{UV80A|I)<~2rU4Ieumf^sHtTg;a zyMdD5plzu>M&e-&gxhvTa&|};Cdkt`pz#+baP2mOS+DsPJ~52Q@DBA!_2pvcxW<*^ zXatJ0gxpDjG^JB2rB5>YJR+gnTRwx(JZghIyx6?vCRQ=Nqy(}hk@k>8BN4=+GkqC# zqjUPFkX#avxZRwfHa-V~0iW^_h&)QCAk zeA_u1xuagBs_j8)9{IjdK`L$Q_K?I!Vwti9Pk6e4Gn_fs@iL1l8q0ix06Er7T$pn~ z0!T)l@V1zoBsV0q2mp)NEsqD5YOTkITW%eA-fxBDaxz&h(tj16xuodf1K?G_d%AR` zJ}cK~)8gEm=LkIgJ2`B&B<*b)8cH&s?novXtHAhaT#`l6S|R%qbH~f>$wDYK?m4q` zu6m{ky{r*)c+pOl#mV#$$cuR`up2idKZ6 zAZNVdY%q)0B7eB=G=C1mWFndQy>yLO-Nqqlp>M#_a`AF5uy{YPf1^B>Me~*vVOV-Z zRs*-=svNDh#XCVthM6NpwN;*|u;y+~^#;$~NvnBDhjK~q5NemFQ&#yGK|oepAq)W`q;u(Z)qmN9FR)*_gR zm}iyP(y<|4D9>a>2O!F zru0J6cyEU5$9h{5!*}($cIg4asl!D#&`ed^0e`}s0#keAFlNEy^CI-i$7j$6-J%Oy zyEd$`Gs3ttqj4Pu*B-{XpLbQ3%1sC%2ISKkUTl}%mSB=qhqV*WZkL!a_;m&&@vnhR zYr><@X7E)g?S@6@3C@H4Z9c^SG!%CHV=%AX>_snp=Ugw(Xk)33u@5iQ*TZfPs2EOM zrhlx0tc3c$ITJ@y#^dbWY8IFI(1n9;V5YwFDs8tbZ5LhA=h-4^ zk~S$Hro|z3EQgS3CmwEHET+#*cG)f2E3>#2_5oLIbofJQ3E+9Sji7m<>-{T#vL<_-Yz!B|4@bym z&_SvKkfEJg4T3OUWUqCC=uQ}|&T0r74Y*G@&J^nV$m$s693v27xk zHxbe=p$X7^!~(@*uvDPScyT%rpvP6iM$Et4K^dmSvTK@DyD-YEIjCFMt=RBoTKpa5 zWBl=@`~}}@$qi|<3ZoT%0)H9SbsD6_pkJq2V^O7h8H8R~+0}RtHgDXrIJjqN{f{8X z+ll|MC8lndnC{`D`+s^gky}tRrv7{Y@y_n01MJ#m?&hagUFzWwFhEEQ61L*S^}9xE z3KngkRAB$QB_&oi@6gzy6lt5aQD*s($^96>3BfEb;m7EhP1f~lWiS5omhMns=gaBS{H&?IVEkKQb3 zewD@kL|EGw+r^c-+tY$k*K$ zt)xl%Z3k+b5Pu;Iyi7er2-Q$Ve*!JG=p(;um*|+c$}5877hv@8*U{S%TA-8)-W_y# z4XVIHt~(>!b0)Una^eSg=}xNfo{@ERmR(5)T!ZCKy^ zZR+z|L(}VX__ZVDrkA7jh0@7N#zUS>*H!CJQ>5`!9_ASsGDZz+KpDl9KAj)h(3_?~o((By(CkK|qxiwFGVuec zV$|)1yMHNmWf90HaD{34x8#|+iB6GgrQ@0W-wB5JnhGn=f7pU>KtLM*w*PjOFn3GYx$k1KYtWDd6?66lH)VYG1K<4`E_x__YG&RwvJGLURwN4B+}YGh_J z!@PNj=Ek#8i<>jaam+e%PV1JGQ-F=odO&8kmSjp%LYKarYNMG$CY?p!Z?2YGe##$g zAb-!#OMO9_2#|oHzKd*6@+w>ykiNAS+sPM)&H}-XC_>23raY_WQq5Dp$626^9$Hw! zj0yQYWC5l_sXKrfTBJ5^y0-EH;aD#nwP|olyEu_)z_|r@63 z-@zSi+et|2ojQ)Wz)X{aNRp*=N49Nv%6~i_J3tdBEi=9&pE2v0cbUlTN^uP#&7yz5Jb%)v zKcCo+t8vfi;jMFmr|v!>QlZW8#2Cy~bt+2@R;VvM^5Qi(E1}5lhOu#2ID6>6H4>1n z&n^VB#1X$oSC?dPVl4laT&!%K&YP@AnnJ@M^H{D0t4S>DhC#83c4C%laD}>7zC&-U zsZgl0*@v@4OSK5gROc?#sW70<&VPz7*3>NVH{fTr>f-4TR>eHhQnZTPM$@~xGvjEw zK8Gfun92s*lcIpDI2~dft;T#_R)+)e9CJM?rDbBaZoWV%?O>z0@8nSi(^sbbn^vdd zN{;XEY@gL+PFWE}GFP}xVWTcUF?q3Ue3%qI+Eo!4%I+a$D&F96mHc=JF@H~xcFkmD zmqN+9&FLu!1MSE}-cAe6?NAJ&BnGpLmw3+75+xm0?MKbHl|MTV3ibhVP7K?pk^l4b zJoVn2-~&XWB_Vl?f8K}qsEI#T(j)R#^A0m6irGtcbc*DLEGLi@ydycv3z8?SK5BZ9 z$+9&l6!_v#A_~X&X>DNiosD|-zoMf zfH-A@0OCx|NA-Z>mp>An#46s7HNI*ex-iz(Ad0F^Z5~!F4T#q(Qh)77ayCM<_%cya z&Y(ZRG1T0L@OT1`w{`$-f~rZqukezucEC2=`PiAEg;ip|(FFxFD zlh3DvXN^W813|f#%&;5i>ldQ2Hhk}?FHEm0q-1g}T{x4#Pae-EWO3Rv{TpnV%X%Wy zQo@hF>}R;{CrNf0Z-4X+HKzb=eLz&9GgKql^X(b1I6!$?wR00ocwHDssom8((X0rSrs8{+~e(4wnLZ3V{F9xy6Y!^3p$$uWzFFqU8q|%i4U+)Fw z)73FH@u*8QDMh$9)6+~$Gm}%_Z!30wK&^4;zK^*pFbHD!@0g*nk7=Iym4G5)PCpW8 zTA`mn1FUNzAv==H2Lm8px=$RnUd(2gWru!_%2m~E$C$vRQpk}e=u{dckqvi>`*z~2 zV5^G|^nO>Qiht#L1=@41P>nj+g{kG45-i6yNl62yV9Apk3#74$jF=1c8ix zf*@DSIVsUl4pI9QgIf6}8-sSORHN2V6UMxqE>$ZyBNQnF6PHKNYkE470@gNmbXMxEcn2Lu zqAX%DG36fdOU8FSx)UWn?x3zc9pVm@*1X1~N@<78VId?j6Tj0Co?mH6j<6AlpZnC#bY&d4`F^OMNsgf#~1 zCKG~(>9vurGiRehHO6Pl0kQAq%n=Fu>M5mPOOgqj69q1@ba%mfk`j$Blg=dTA~WJI z035jlQw;lZk1_bA_YrY)3?1z&*2WrkM$5|dRDU1o#UBE!&(Y5Y94@oBzb12PwaG;l{s_^W22!WT?q>| zLf6<~crUZLqT)J|><^1W*C7sV4?QH3A_eWn>tfPh;#T;Quxe+2B$#GcDf^cuC?;s- z=YO{cJhL%P+bu-KuK9~1c!=ugVwHcIRY>tEgc7;dI5IHbqURtwY%}|1Q(eL!367^r z!U2y>FaCsKzMimW0tHQCvW}!REQf`O1CG{|m@4yPu0HOf7kF2`f^=J;c!S&iL;E#* zRfGgb@^A%;p_UkF_nvSD6gw4r#mP!6n}6RTZ62~0G@1Rqzqt=XlQtCILlFB>z?>is z9(DCbR-BD0uVHs~wfMh2;6G5H2VUIgAt~~n`SmVY`uW&&9xDcF1NWX_;4r|u3hrJ- z4zO`!9%K$OLhDY{25Hx2o7Oxtn_(oWY~)btdT}`5vxpSXUyOQ)yU}66cl1?})_=RP z`C4FFMziEqVtS=eVdkl!kwX}y4+z0lp$)5P!bf5Vmdi4`NPg8RdD9ZN`b5%c_6ihr zO5N=QdADn#LNQYz@dvmYLN~AaZ&@%)oWipDMv@A~4pEe#eL?~U;ZY-)GKkN`Dn`?w z=M_i&25ky=u3Imxk)$j8WrXT@4^=#mdY7yL{m7U-z z&`Jp#B=*m*j{#mR88?PRa)i{96twBgIC+3s6K6?SyS~yDrQ%tgfRXOUI!vw4Hz+pmTnaq8% zp#zm6Aks4cph_~PA~ItZ7Jua(#+5T^mBGx0iNzFYf?%aF-MinfSP)J2ikaylI;O#` zlk7qkycFd@DrCgEzv?P|Y(s;5MoSk1gKS^D6Z0aZbf}K8pMNQ|d`(FZDY*_& zj-I*b4{Xr-Yw(o4JK|qTkw(6&SB@k0*TU#2L4yMM^xYF{hPUKs8pCp`QaC576g`(6$sB4(Lkx`w1OALSd~O(O&HLN@{wFLP-^X3y zm3Nf>cX^!`8c&=d5g#w?ggX>5>=OmUls)(2o49Ievu++`mCO(bIax=WbBenr30lqG zAYeyiB1^*-^M5DKKU*2!MMpG~wq!ZD_@UdIb!f_fG$k*iIXI6p194~(^hS1h4H@f+ z|Go~5S|=HK`{g}F4ECO zQLAK5S8$}Y)LEiaN^-I%d>8S=G|<3#{V%+j3e&FJ$$zF4?YqqCwkorajA~U8l{OO> z;R1zFs<^k`<#{HU-f0CUZqJZzwx4d-)bG3$9ZhWKcMgBk)^1GT-7|u8kK@xgE=^(~ zkMDcx4lH#6i@ryrV)#EUC?zrQm>x<;CCm0EvJ&_9lAOvrszCH5^PUL+B8Vj zOgNgRX@3&0{_rW8y^sI+?C5dSRg>nBm&I!2L(>QgWI7ej+zMqn^|KwKxNKcVVy;`a zby|jT)!K}rxaJ>*G0(^cFfVX<`CVNNle^7;pCKf)%%5v+VFmZ}b$~beU+TP^#cF-A z=5`$DnS%zvtl@Tsmh~5y4XYdbsBFkByk_-MC4Y6#$P#U#S<{MQbkD#OZ6U`+&g$m) z3Fw26!78%{nx^(NPwc1m_<Me*%-+3X)_m8rPd75j|#dIjsr z^M8j(AO4%(XI1zHZ4#RwzH$e?D{thUWJvudWdGXfPr@2!n500FHzcKua*&WiK1mp- zm~w$oj8PyX$)A`%Jwn;!dLfTfqdzTTlHgVn_MeZJ-_bM$CJ@hHM?6%yxLS0e? ztW_2Dk@$_gbw^b&+ZI0GDkSL@totF{91I)?a60q#H-#4e*HK$JyA73pYDViI|9_)} z|G$L&e?0|PdviiQ!SqF|HCg*>Vl5PpoXJn{1UBkVh*k_5FKu%RJnSI2fOD}#R6}Et zvV{t~{s_(7m00|evHc=4Pjo;=(*?+QPWxWP=Un*4&pvzfa9c@~&VZE^=P~NqdAWMg zo$HL*ryAudx7_Z2+xIX7CxEN3@>(U9r!Z=k*X1R-pC6leCR##~r;(7s=(I z1`0sk4((vU@n-6_GM9;wDZ$HPXJzDJ%)pwW?use-`Mv3!6@wDREW}+wXd`EQ+&oR}TX-vs}IeexK z5x%bu&4_BwQ3z)=ZTaCDP5(7W2|+r9pR7V3s@Y$1B}@2^ds7(epqJ97Jj)Bh_v z^=7>?qXBNBBR8+7THB@{F{Ger{{>=y0h*YISG7@RqT#YXSmjTfSAXz9HgrJ~&I<(2 z2&(KS-H7d8x_o-&5e787EM*o_ENj6byJ;U6CL{EOMF=Lhx`~8jd$u3d{MA@u4)GMZ zcSd(dE+UM8C=fBW{bufSfu`=acCs0@!0YW>3J5`TLw{@9E)n~sAZty@`zUC=#Nc)Q14Zk=SQTa-9`sd;bRUtu3ipJVZgWnN zhWNT@MOkutgq0Ll7ty;5=$-g>OM5sTGtpZbII)Y0y~eW)*_?&H6B8+G`>rkR8mb!O zsTO56o0REEMW0z`lc!Ed*Rc+O;hFPT(vMsFY&JWF&wsG(WXu8Y2@kf(zsN014DdlE zVsTkG9^S4bEKDp@!<_iah*oAtU*o~g8}73n*iu8$*A9pklYACTCuhRNoTb6!Ra67w zt#K;gv8buA1I6gDPV3Kql4T^hX8c^$VyZ=%9I5270eVZIZ?~T)N@crDB6P|t^J7XC zI}g@K+<%WMs&Sf36)%n^o=@QmZSBgjYq5k&*)_4#F^SEJBvU0JGx$LDTkd>frdy{FjZI;1msw-D!f2yySvurQ~*Ig#d( z33-kd;4?@*zmU5-(Z=n1Ti!l!ufO}AH0MLQt$$|U(-1RGH|m0y;Z|E)fdOa}r{@P} zJSNu2>pG%;XR}RUA-A-Kee=c`;h}l7MI}$`7>9#n(-=sd+oLt|ZYU4x(tNbKCw6{S z`ph1!)MIZBAilXg zfq(f1<4)C*TYRN=z$AXfXSRH9!aV6Rmqo&j|L;<6dTW_ zUwWa|G1aMGVo5u6x~6G1VZ*p>ecP6oKf;&)%8q782h^p(!!c%kc>lV-g_Bg>l-wr= z6@8Ft!^zyALuq4?52N^EtJ4ohBeCcM)_yVn z{)%Nk;S!wPmGRuJ;VztT!<`vmeRjM6PRuRQJX~OWRi9*&7eW$el61ua{sB3pwSQlA z#~QeZX4jIo2NkQv&=mYIHtl}GxQ%S5f%5+CeqqSk#=vd~7pI99b4ZrJPUa8umtSUI zY8zwcP)fHytb7&6Oag>L_SB-%Y|eELp$f_IEv&Y_=U2>6gW z0nk^GK7@b!`+Ge9n;h?{t}9rzkAH5k8Om=&%D206WapMq&8lpVFfo(;*j8VISqER8aj?LEv>Mvz$XR(eB^o)1C+BgV^uRpdE1h0s^W72Lj^$AJ-KB z`9kMk`zVxkl#nG*cyK`o9R%tBR1UJ_`i~I|>h!R^szfAHDE!I2RS1(vi;C?M>VI|N<_-aUR}|Mg z9r5oqQEQ^?x#r|OQ5C6>L2Z|u7*8z#*x`V?yp%zwppAAX8pt#WRe9?<`V=VZo-@4B zS6QAy&=e*_AgU$9|GjEvg)`JE+Z^o`WDOyN;edsid>WlKzj}?^hK8kfx1sAKx36#x z+{ZeKVZO(Z*ozKnz<)q(wcrn|%Ko$E6f_2a)ospQ!GreO<=0nGh!X}n#$z@?B}ey6Oz0ZB-JY2CZ*evrnypzS zn``P~hJY~?TFusAipX_y-dgl+K?Dch6*_IFn4y;egby{@JYk+# zSIvtotfV$ld%id5bZCR!SCaiCT7&x|#c^ucY2ga}%s$KwBOEV5O$C#4$LDZ6(vCUJ zW9kWFdHKYw7)moVZ z)B_FSANWyJ>{F7--Xly%F@B=0vWavZvv;{UKiDGu;y38OBO0^+n%)v78mT`hlzBMD z%J*x04-+-dv3E?cN|q@Nc2BcM2v3W52LN!JwGg==?S6tVp}CV&BK(IbN`C`u-9_Q* z`~I@;_H5x|vv^WN=dAt$xuQ!n4SbTrb0}ZU zJ0*X^{a#~KHiMsDe3wdlj+h(pIP`CpXO~5-NGDsJMD!AEM-jq}1T9yX2Duj12prlR z2!c52{xABnR0S9j9$-K~&4@ri+W+H_R5o`sF@I4rH!-pP&*1#;h@K&}t^Xi;Y|H^< zTg6592}FU03C!Mw-l+7Y{4GT(&3&xRD2wfD+L<&Gte3XXufTtH0d(E(g|XA@oWIx$ zRVrXP52Bdf$vJYo8f=ebg5OVlNs(oq{^R5}KwsZuA?qhm}lCdlSRW7m$G zj5U^yXO%>F0H(#k@0FHo5&G&);~AGu1eGI zB))g##Mtam5mU^YPbW-YPm>9|eO#H*S6q0Y{oV$nWN8ZtdMDC-LmKB!9)| z3Z)`vX#RK@&zN(1hIuUuJ{Mbx-(hmurwcWebe@bgQT`U8PQ)_CtR=YRz*DnPBdLyV zfqzF#mgnRGfHvfVe|3;AmgJU}&?0-mT$0vPh&Xde2X5kzlB2&DiFj1Q!6~jhCf}bx zn?n+U2F$ady&QxG>&Ssntos{an}7cPu#bi~F@f?TmeU>=7)p6YjOC_1K>a80vleNq z$Su-^_hN0XK7(3cX@iGNx4}brKq9ABH8xt0ud^tXqeT#|bb73Ho_8pUBC=<3rNc`S z1z-qY2)`e}#QegD-)%`ZJzPlrgE$ly9K0ZRW(;Nc+s z8G#6G8QGI+Pd5MEh*p@%CAQQdXtji(W-*XdF|x$zAbC4qeD`SD#PYuLYlFguMMpIA zI=R@FX9hf~4TUMml2Xb}^BqoRDz>zE+T_F}CVQ?-f2K-BVooK^;jf;TS~3$9;6(1$ zSZ^g`@2+7>=)fmPr|Z+UNPoyrekvlHMj|s<{|$-K5AnB~Sccsp{|be(_0rz4Tdn$_ z2@Q#=BS6pNgMCWSOP(c0Lsd&mY$Wr!i>S}7si1!Q8$QkcAH_-4)_z4c93>u}bBEU` z4bE|Y_RrAE&@Z*2GTD|evCV#k7W-(JmgQA9IwA5W`y$%bpaIdjMSu0UX@q#23EI{; zHqxy(pEqu%4s#?jzA`?v_Pr4qC^6MFe_wBD^6|)CXOz}mHxe9O6}$P(vw{eP{y$i= z{p6DGb>@3QCArKg(CtHc8#t0q4Y}Aj?b~@V@I`*V1gt``f3NKXF?i-c6nYgN>3!j5 z3y@${Qy7>rYpeCgo_|t5$6VP~{S_S{b`~|YZw$VggIL{Or;lkZfNO8klIUn^s>_FK zZ8De-)iS9jC0=lk@zWtQkTrF%q(*_B;-@e;04XyGSZw6CBshCqg?*R26&p+T!>UOm z*ebz&vk%BQsf)K4V=(I@XNlDOe=-uH6eqkoOjd`TEYkXPs@F}26! z+o$yHhnw72`V5@8qawshJVx{#v3rfmu}e4tF^S9%Yq^6bXm#k6syoV(ynBXdB%BlRJm2P({G?;zl5{ys|MLVh10Htw!H(-DTlVb2k%xy-Q0!q zMqMfQ|Jv@oQK3N^6H18x_PP56!bjQ?yxJ@9%eqkhV1K(sw9PgzDtKb8UIF_C`*+Ci zb$ZQcfdB%MMg{_s`QL;5|HSw=HRTgb-)hK%-VuUaQn+0Z@%baVQ`L0aXpvA_s#DD5ZYkmAYK6>2Xnt}^@4I<0# z+3(nSwSS!GbjS7ld`y1;t=|f8u;!5jPeB*`S*U%=_mzk%dVI9DHa^a`aK{>t)v%bj zSeBn(Wmbr#fee$cmIp2}=&wC7vUTjMGy5mMvl{pxTf@SJ;g-H<)Vk_q931Qv$0lkhrl}jk*C1gOdzzhGzWt}Q1bKn7?JQX zd0BWleGD84c(>_rI#AAQJ9-_&2|SDr2sBD|O&oOghjl~Z_I%+eO?Z!JZp=?x)iU;f zMt@N8sGooA{a1yc5u(Z^M>1uOU7&;t1eF+sw0djh40`B=VVSNnWEn;TLNGL;al}CP z(SPWE&t&pei1e9RuRJR76xw6h?3ZW#rB`Y;@CbI<;XDinTtUa7bgbb4EtJ_S4~n5# zuiR5}@mLozT@&uH7vGvQj1U8lkfX%KYLw3VOg3_@vn<#(h_@(Nf%8DuQ`D78M=t> zA<-f)ze$fbpeY(>eCw?>wkz*nlz+)7xU1}8-j!yCJ^?)YC1+yqD@xApOYSm$^H$iy zt!U7NY`CbuB!aHjZV?PRaJ+MboE&LKSiKo|DD07TPPXObz6M=52v(n4cqfvh0li`5~hw^sU;vKLZn}5eIu%UEQ z_9-&ks{cJ&AWOQ1x%nqe6JxV^Y7pgE3AV7H6!5G6jV8qIKqhr2@QgbBEZD?YkrOdn zQ%!q0Lu*InHHXBh%<7baDHz|Jy{)@H0?>JN{1)ou!T!U&*2}g8%G5q0OAlNgTG{Bq z$;4;GdGH=xC_EJ}!$;;kl7Hx7>(G$am`?NyKSe~RlG$!4$kDQ3)5K2-oMnbls~aIh z*Z1REZyV}kAs0W@1P!Tuq_21|-rMt#NwN_MHX(;~QeoqOS4p9xpRbuN20r+!7*{-; zM9mq~Ru|J?z0jxlcBx-o(`05GJI&6UVj_hON+S|o4;sr-EmffA3V%a!{$YYth>wJ{ z2xxrd64uR&2I_eGCvsEZ%vacyAe%KCZ`%VjtGjX#8KD-1O<>@KP|lHed~K=X$l+3{ zo7U&uKKAgl!KhTQ#{a)EO>x8MyueSY8|4`+{|pAsWXQQfcvvm26IX5kyLl@I-;!4r#BX3^kyyV&eA-3r;mXu z9#~jRk+Y zhyNv;C0-p{c@4rad5>f0KM3{-+>y}M$DuoL&^F81(wFF(O4+FmqBaEg6GHkK%tAO} z3Qmka+JD^)^t(+4HK*e3m5G%s-GjGvP?qFrxrG-awDf}MIr<}=ZMW}+qay!c<(^g` zdEOIBEvB-_D;mRcX~VWUWb33X#RE}0IOl5l#-lq$DljProvYm0o#NIqsn-}qq?Z}@ znaz@+rN-1@#n{tA_VBhenYLnlyg)g!nKZGLZGU{NK1hYM;7^aLtI>~cSB>;)ozR=@ z5#Tqfm84IYl6Z}(hIS|F_e<&3>RF$@XwZ(8W{(SuiP$$r*XXbs`R2s??B&DC>w#e_ zfbX55YX9cLSDI~4t~;3TAtxT`z(!8OPvrH#Z1To(Q*P`0houDke=^DR-?f0*aue{t z0)M|NpI1$I_K9&?(_tVSgh-Gge(}+BZ5U{90Wx&(Pj-KKC#Me$so=MlcT^~qjXbzQ z(2I_Uh14p)6J0VeaV~mPR*tS7Yg!BtG2W#JS*%5Fio2K^4Sfr}>t&%kAl2O|5I@S^ zQ;HBR1g(aWt8(PwrMmSy({FwrF%g4u>3?7hRj?Zfestic=-O(RPyj@Ts=S`(h@`*k z37!3Zd4LL{nj}Q2hMlN`eRr_UI%DK6f|`3xq5r#&Q26X1KL2420RR8)FZ%!X(Z8G$ zUne_2|2xz#jVv!OdEQK49O4{|j8&76kT3w$&@D^JUgBWX_1*qIH0@f0sbOLD$A7*r zxjy)Ie(v6$;deozK#2pSY~1F1n5U0fF|JI6c-3ui$NDpPj>ePH`Y666rzc8oWCH7Y zy(^w2Rm*9Qe7Z?-L5ak2(jnIFHT1J=I4kQrcA}Dv-B7ajh!B<+R9*;d0fJyi>d7d} zRZhwfvYGnUH1;_(Ke^=byz9#r?SBlYRI*{Vj%6or^;Ns$DJD^}lP&pgp^qk=zxnG-Z6fze{6me#Zb)DpVaMgHCuX+8v ze=OSodEI)T;;0`9XZSlR(+8W->@f{1wWBRbtFU@g4AHY_ETHO1tC1&{8vhBMStNaH z%*XD&)vz(vR@l!=PnDPc@_%NZFmE0qwqU_iatW9t-lf6tmpSVt~&y}WGP+@d%OdaLq3T^LnVI^c(T0_N+fr$$hxraA>4{ctjzLnRP zFc7qFUfSVRN_E*!+keQphrByt8~Uy^AAA@kHO8R#$5S#vCNwh0QjrCp^kgf?fP5X3 zGu5mE#%peGkQeyF!C%(1jNo}SiI+lTd<3Ol#QEhI7AId>JQfUXsuL_w*hDZT#UB|s zG+Qb_xJ{0UWh;c0yFW+>c=bqEF(n2%JjWoGn`D3 z#Z)lvk!<$qS$`L~_FNdmtX*5af!_{k>J>vS%Rn=~Aw%`~DSxxAM$2K*iwd*arnLmHA{@TL710e^xk4n79n87>z5gUhQlvtBRD zm%_lKnc(>`q@f#c4bEk4%Y){;x86wlFNTz3PVLg7d#Se2qH1DsvQCGxXGqN=W~-u; zB*te^rbr!Sm+2K2=~f~&Rp{L1%ZFO+QaEg^(|1<$);D*446>T4h}6+D5^9WYF82-l`(Ns?wct49q&N5i7PWXZ|<}mIoZL;OoExfZBqZn*!-mZj7 zhZvsf<`FEfLbqI&RIQH-i8y?QcQqhZ3GDz?v(5$g(GB&~fB;26y1$VP^@Kk78`yOs z8W|O()dwy-SGfay@QqHk+Nv^7=(x4baqnxieOn7h2U{tjk|9K<)zhk}+=O2xvr}%j z2H<_-Ha34(%(14mu6RrIapeFp733xSjA4FoS-J>E*}XB?RTsvcfRj_dctIfV07h>K zT0fC$-xyJEp@0wgs#iSRSK#bd#IDx}+gQE>l4^zD)x@!S_P}iRP?+A46y8yK4ybGn zQNBhbcc5Sqg24`@{w!P}3n=`&QA+Z-%hC8+87zMX5NZZfNaFePnHJ0wk`jB-E(A=o z7OFCiu<2_D{ODu*^OmDsF*IxrlL3e~O&kz9Xb)^4Tg|XqXTvVv1PakRsx}E% z>LwYQEJ5PIvTtWutmc5#{JEQ4AxUn5j8h) z%lg>>K2ggZj0&w%x?Fo6?JFCn=}Cr(o55`~$OE_JmX5iwQDNXAbs-F=N`xaABS@1R zde@pA+g?^_B)6V}=~kdI@O0UFg)tXwl=J^^_KiWB23wkC+qUic%C_yQF57mOZM)01 zyKLLG?dsz8ot@d3dn0ydX5)>F$mf5@`y-#oJb9kXbMmlKxUM)9<`#~W!i~hlDr}4> zhZ@F^T{i7;VGhF*a)7(|PdA~27Uqk`jli#LEzZs5?}<+ADrYy8vSWyYJrP$aTL>10 zg0384!6$Sl%o+0))~k^E`WizHvs*ATZ{UQqMob+iZ>-M|gLLZUOUcJY4~l<>B1FgK z0$go~IJOz_F3`6F;K^g7G*LAbR1en6!MQm~!Mkyk>J*)oAzmAoxKJ`zJ2Nr4 zEVfQp!?YU0qK?X*u-WLN<&}ReEsHhG4f zevN(;YbJ)ySfMO zCXhqija5Z#shcf7!oF7m(jH`Ky?W;xYZ9?Mbj=H53&3C|@fsF>$L z2(Qo)w#yC*=qSa(dVYw|Qzdx)t_I`#+52HZgw@jf_;AVJ}t|M0P#- zl#{Yf$vs}fPwxoV?ctEZ9*TR!Ys;OZr^VEIq;}>gcJSL_62cy;d(6PAj%xiDZAqwN&M>QG9T6xN^Xt~F_3S?|H<)X4@V6HymdyTJn zDXz{*MzlBdcG)3RDR`O*S}s09d)PhsQ?Hywo_WZ@DLx+s{b{#&N6TB#&utu8EgRZ2 zJbSdSR!}pvKJW%7>@8H&`U?>{aAS37-%s$#AVtT6a^}>)9$Aj!R(5hrzO}Yq6gEcoeC|m)dQF zUjUk^rzwOj^6Q>o=JktIngB!1T>VuXDf%|}{u2o-n9C2XhJH+GW9rGS2OU)dK7p?g zPwNzLiyqYU332fH5=z8nCSu7C?>=ts!DKPo4RF zGW8ay)hK{#W9uMNDPkY{}t?Y=& zPZkrS$%i}s4#hNC?-PA=)en7c-Q3~JYW}L&<(*28v-m;?tqUMon_P6kD7_MwH*0@R zvZWBkzl#4VIOb@~+UBp1hQ{j{PrPPu46XJ!c;O6K7g=;-U(u(WEWzg8>=E>mhb$LN zY-05+Yfoviqghj1+CL0n;|-#edAkwg z^GAG0VINH=EOC{WieFVX|a zsyaLHQ5td=~9*$rSk$ef&$MrzDwGZQ8#W z5e5i||G(?dxc|e6`9E>J|K`&Cd-3HITMb+>w2|+mQu47xq;SQuM`V8)6bltPVPsJY zqvjMrSS&QcuqnI-(?(o(&Y#_P#*e41w|M1z-M65xmLFgQH?l@Q9p*vPF*8cN{a>bY zzNbH)W(fU3(jnrAfBp)Mk7Xi(^JRSHpV8Ueo~pg-L<*fj(qgh*Fff5KYcPf9D~*nn zHy%Mr$omR?6U#5u5D|ZtK=Fk`gfC5fsc>CcbM#rby?5RF6T8<&V&FLCTR*_JcZ66W ztf}8k24}})4w%I9A%N#tNrar`~cE2VDcan)H9?+_L1N9UnM*W7Pq6 z{1wL_!#5VBP+)~ua645wZ})|SjYjxBq;a%HQ|#T;*bOY>*|92%->UxWd;`MbM<2dH zI*ZHqG^b~pVj^OzOxCV4(apXmS(`lE!wH77;W|z=7&a_xOX56&|ltt6WZ2_wFtU}B0F7yZ_nevPsl%$-q?I3=!~Vc0C( z%SI9JYRZ;!k>uIb7>#0wZ-7v;dL~4&92af;YlQ49sGykgamP3 zV{5ClcU~8oM!50=?1RQC2+EWfz6vn$M*Q`*dl+=rbL|#?b=z~I+H&2H!;A2=OE=|a zEA~AmFD`$)0dsWTLWJt9+k5Jv%h^MrbZ*9g-0ud^UyMM+MTb*zGtz?mloj|E%|R7c z#2ri+r{ADB&|sF}SW}+}sWPNq!5$2b!K#gU({gx*ry57ylHa7^v;L9&k0h~Rz)4ub z0(yd=ukq>-Sxj_>T3xnp!z+ag8mD(t;*6CZUFvnsRgj^f0XZvFFeu%ACg`)(S@C}vHFFTWjl*h=Z)1(zI z@I!x4sHWp#%Od$G3)z>od*I?|j2l%@Hlr7PN%Jg`!c-`Ai1WlHrR#se<@`PyoG?(8 zAo$#(KQAf@&|TZ`^|G><3`x;@W-qA;HZWG_9z_eHZ1Nzqluei>P)uAPyTGn8QZLRT zO;LVz`)y5C?m}6mF;DvF)Q2!8c5^}QE7jJ zLw{I_{_ag9LwD+LP%GS*=d<%!tWFP5l=T(vUay@Aeml(F9_@2ut}H#Gh>->{3Ea$c*0?Uht68LuD+RYJbtl?dJ0Cmi;kK?J_7Oe zeEz7pCteWT`H@WeEXWeAfy;lLIyGK)j?1p&Y6e1Y&x_9Q{ETqE6N9v;hH$1|wa{ag z6tVkQ=CXN-?6ZqzBa86Ly znCy5H+3bExaP95tO%KPaw;qkFJwZ`|ahsD-oD1 z?9B#E&W9zPZ}5p5a^9-9XX$g`by2IRE=`uVN z9@9?wKki6)5(8@juXu9xESjR)E7Z1j!(Bq@+E&tvm5vtm9$&BJOku} zMv^DsQ!9q;uQtHu_LCoS z^%}r`3Fd2W;6Kbytqj z_`JPQfuRVFnocf~*{(j2gV2yoBST_8A28xUHGLSIpTU1sgI{wcuLRHX!fd*p3!zzf;fsqia;ZuZ=sit-Pa2dkTrs zJ^ABM5q==a2Rq1SA9{!9_<$+pvRsX#=m+3PloLu|+EgK-8U8@G{)rdCga*JH$@h~Z z6~Z^fcYl9XLEBvwXcz9|-dhpo64Oa0UF=1P*A!M>r~b@fkNJ%WE|y(g+dV#5Cd`O# zEAt5~@piA^@Bxjo^Mi&$&UMVkodd|dV361OJ3pG%wGjI}99_upuF-sQ5RnLm1L+Q~ zhF+aNlmU9<%=-Nm7%uZv8Itfxj4L7%`kT=@q)&fBVXkF%xh3c;<21YkKFo;t?uZy+ zs9E#$>n*$mokZ(9JT`bg^Ho?$6Q9FKT+Wu503#?}sqH2<+)!f@Yjb$aIpJDTH!5s@ z&y{n%m4^RPS&DYkKd|qqJDqrE<5iv)jkW2;f}L#^e{Fa)Rmi;u+hdU`6#E#WY8dIF z9=(6o$t_tyKhFWgQonh+AWo=fxQg6!x|B)c3QJff)Z=c-Vq{C=?iOs#r7t? z22MXvCX3jrOTG&oLo1dxWD+UD+M$v31?Z;YHHD5nC6!+|ge8Vx;+0>5_>I0diKkrM zC4X7OAR@~ytKtJz53j=LwubD?C1;QIslb0)3OcgY@otWlE{~_zNhZjYaOrn|z(P*h zhm=r1CRSF$d#$*f5m5=>&}tx=7%BBZ%-j;bkGuSJe-HoAQ^*YSRvv+(8&hlEGiep! zkK|{@JtoBEgSN@K5$HcCFMDbc*5Tcxn>i$=nSyhYYh)aC)Jh8bzOf+l(|VhQt`dLZ zXs?_k-26YJA`3eFT_@b?p z`0X20Pg+!mpI^**#&rh0gNoVW^f$?lxKan`bq{^;qF4&hd?0n+82yFP&Z75%F&!2P>{7 z0->;<1^$rr`{MHJbBB~L?qs$V+7zfgNK5DrSUMTo znEuCG7;*}@8fbiotOOs-SVpp8Y=lMBg9c3CNhJu>s*x$+Aj&B;Fv#j=zvtnO@X&=Ce*__55&B@?&-1nXCH#{%7-aEeT zx!+z78-zd@b$BB{Bs367ib&{Ko)-KpF~8RwqBoYpT8>~v?c3m23{b*NoZa`agk{Be zBft_txF$B3wKqECYR~`FEU|yMU8UY==`V2LZEVzkmRPq&Gj^rYGo7w}ne{3s&<#ix zk%j1XMQvWXN&DtGpB0?*UjZ(gC_KrVtU@ zZUe1ZAnT#_+Rg0Fttx+~uc0e;+RyYFG!b?2jSW|;QfYsH$IO9*{e}r=<9d092QZ2ytki^PwY-y~|1}z4nJ*6i0s?o=wxjyp%M?%k@|F zIrO=zOP|tnovgejY2v=3cRF;SvzwB*e05%HRjRVj?MBC5c&G!CPyn`_X@7ikvH6HW zm+ACeAERp)@hY%EsLR2VX{ZsIo61Wc=QIHBe0&Mhgu6yH&ny6O&mwpqEW862`$AWJ z#urZy*X>w^UweOC;&n5XS3CqKakF=*6b|8yuSxv=2YC7iys-|zBW+ZP>1d>FWF;P) zQxC^&k<|5pmUlo}^TE!wB4! zhG%ahM6v6GSj;f>`ixE|Ru=;F#5qWfXC}l;RSU>KECYY$fl`O~bc^-CE{x#wl$9L} z==N~P(OnI9S*4kIk&~!Yq<7n~hFqm_UfkM~`dFjgSyoH0NHP}M`hF%UZZ`yfY+%Fq zC+zO+tn~LY+o_d;^G{I>!AyGvQt(ALPrP}0=U#L~|Ef3Ik@ zSY{beA*6qhok5RMDN;9eOXGvURV{E~MJOnkXXmWDO@~%gx04S?j4vSn>9?Pd;5;z7+#(TTx>a2MykfJ zIIM>CpB)X@1%%A*FLPvFb!i)sf`ER2svozw+9udjT<&huWd)g8FXul~v!IaFO$Y)6 zBnS3iB|7~lY7`Bf4F9cf{7>}cByQL(2qJ}k$0W5$;g!l+{8B_XN*)Zs5dxPKa}Wa4 z1&e=Nq(!B-ZMKf|UmQ8k2iZ9+;dzuv3nVgQx+vx^f4b>3? z4vi=XK^cdefc(IBFXhGS=-3XpRSCUE#U6j84w}1yr_~f55?vC8#~2V1fY~&0!jjNW zmKJbC6iXEMLxXjvD-bNIM~iq*9nszRqV0c^V8LTuEaklw=M}I=oGxNZk6Tw_Y6*cz z#l}i#@I#ktlFe?ci{uFUEX`cu%~6B~_McHae}3n?^6u-;bYcU+UUq=KpkUBx3#^2D z`Nj{==f<$~qjGaiC9h)TJ^xY&=pruXjS~;dXO7SJa7ObW**@7$w#y6}Jy{@*E9QST zPaAR}K@A--pKv=jbSvYkmjq*PBoPt72!LA9A`e!^qRx`uTp5@x^?E5NT*YK88sFk4 zZ!La{gSQe2D5(}Cl#6LOow8sIx}Wn8y>M9%$^XQe#$+;oz$!5&Ec{Y}-2BxXK~l|D zWd(KCs5B(^+j6Gg0k##`ww#R(@$`QbP5Of%f;GiSsIkhPzS?+-mjyqR!At8=X54Ic z+X<)T0s1M{KQIL~`#UO`FKlrA5PWuwI&!{ez-0>TjXDq-q_QPn$p|U|7Ip{q43#s2o!BiW&J^tn@&P8oq(ns~ zlRuVp4|nfY@YaD$-(nRP{i!8fj@iq|Rwj zW}T^9!}W39sh>|V6uG$j@HE82$q?xccUMp|+MH-pM&i!srUQRlLCyV3MNj6YWURV< ziPdQAW;TL4;qq4+m1ly6<%NGobzcJ%b}V^I zp)?4xmQtJL^^AX6BV4V!L;3xt9~0R2WXms!2HUYRNgsd5Pr&W>m0dfQb*qaiS&nWG zY!P4S3VcYO`c<>-l5v<=+T4i0b|INTl3daP4(Bd;h;P#hPLZt{l4JcI$bjKE$f#m> zBmImrf!##htiaXRWx89j%XOi56IbB@mFbOO0TduXd-#8PQSLIsU|13KP94iS1SMqP z!Pj?Ub)z?S5h&N@r(R?8$SFWpyI10L7=6$o1#86th!FLJJ69~IWmIr6f6o%Hkad6+ zaLt`TmI9Phtg0PuU^^~;IguCtsbCu+bi%A5EZXH(h$SS?HuU>cAsnA9>SBG1>I#hWDSz)I)K!YlrnKM57S4g-DB#^-@(`Lylf-PT~1i!vtKJ@BQEF z`-tn2K^}AT3|<%`ALw}lo^kv5Uy2*U8Mc=Zi1U#ho7z`t9j0 zPFb+RKtbU#bR(-}i8zltJYn;GEQCRAPD2hqe6Hff7tlx9JTj9ayvRVThgTJA+NjCG zfaOT+2{)_ywA9FgR;BZzbexv_a*I<=haBZxo;+7cPD8_#b6K?~50{ZCJJ_Vh=JdZJ<%?E{wXkju9t~lvUZG z#inXd%1;ofFtQ8N)mP^zQ|>qxXw6^2rm?H#bJ@2Hth2!#W*!~j;i#>s;eVv0Pw2pB zU_fc>rA6eXnHv$(Y)9lv*_!AD<$-@*cJ=Y6AoznY;Hw|_%lmK@%;halq39Q{;{(*| zJ7V|7w96BZ8dl7H;p5}DV0yr7i`Lz+&9d{zUqm{dbJWT27iBpn#3wbwLtGD-WAj`T zq0jIvLzxbOv=L^xJYt;=f#Relk3o7RH!A27>o3V~+Thm=N?m#DwNi!Ogg(sS5y z)`9Yv+h{ZXVRFEIASU4!FyAE>DjJs`YFx&;LotAWhcm>?X~L(q=C(BR7O`+67u$Nu zwc?HD<9^0j4U=G_>rN4y0L)wXd1E)}V9~;A zrMqjLK&7Zjc`5(bnt+?Vcbn4XyUvUvRLJA31CSLEO&#NcYjRM5Uc`ujaGLS&tOh7+ zt6IKHmK>i{Eb)mg#&yN&NM|+Uc#wD98&&o zU^}>@k_+06&$ z;|IYPcQfc|_9%Y%hzcZSq;4XTzL~r(B702oF+&#oC*scZayJjLj~qD?jX(=*0ecsk zEPUituBZT~KhYfQ{7?C9p6!R~ph-a>7V?}Y7gT><^za*sFyZo;{{8{Ic+{jKn9{U*s!b(!M=>F+(!wBiLb|bA?#;ScEJ7Y8Xtcvze^UzH0KxiLqnk!n%=FZJCf4WVA#3V zNULpbq9AYLFJUYD_p(B06Fx|;vVX`|rw+FVSXO1IUReDJik%_ba7hQ_>VFcRIRB}0 zVwW}Nh`&g5iZV-s+3q*3xr_W2+^UI3aP&yxK{+>enI~FIsXE!(dZ*J${E@{1f(L(^ zXiI)#oaN)(w^{`0yP|~p*p8hBbuN64>LES~dZ>HhWFTRI@dTXP6?(!3rB&6ivWMus zB`&GV(HT~|e*r$kGy*Y~fswPbd5HKH`O}Z*)O_S)dV5E)tiq;tF#nM?x>b z?vaIJs;^=VMb~d7qg)_n02Se_*inD4?>u8Yww^_B6SE$=I&kVYS0pgrK_efv0A+fs zWwsCmBk{<+3swkk<#Ckg3)%Jn>MN)}qE9&G9dd5JK>E#hKWjP(R!XN2Lm9-?3AT)$ zqMy^t0gSmCO3YchllpFEiCLPO^n{J@kRLMtFi({(A=g(8Nlj&Vt>_XZ${l}Jkp716 z44Jme?ZrW>S93#HZ3^F}`@Zf|2_@BUY}iCCB#TZ>!T zSvp&onuxpF{ih<{De(gTIAMPo+9C5YpMI^at81vA9TuxYQkLqMBKk$8xq4M?Y+v!AfFezr$lLk*B>I~IOPsy z>kZ6VBkao$|8^N}bAP5h$Xv26uSQ@ONUK&;;>j`&s_TijSH`kD*>8W*u8Ry74ogXK zaOKwFv17}~<}2nwta*x*u}yclU2)hBL5aQA!F3&o<31g~ZEj{5kEKJ3HShUB`@^z? zqrpERQX+V7QTy4LRAe{aILx7*gL?0FXT=0em{3p2Yo4N^=_#RfZ2$v8s_~F2(XNzX z_D|UA6vV%zHfjE<2YP?|ix&R!Ec^e(v#6=Dsg0?V;Xmm87n&9M{z0>E)@csc0p_aa znx@48$!ammfY4u(S8u9~8w~9!FR#!18*d?B3j;fZXZ!o%COfIOC$l*7Dqj$RRsd9U zsAcS}ER$)uxUu4p?L|mhjg(xZcGO-XLfe&q+BI!IQhyE#xzvBo$WXm4uAKV8)ZRVe zE*i^}tg#L=A#NDe8EY2kvWK%_tHQe>fiS=<6*Rxo3H#D8MPK1g7Q=%p2qj`pR7o)< zs;u$ZFjwr3dSLI_<4E6nMguD5SPxas3L@onLQgXd7!3I{SPe%DnZw5lEG%#Uzf<_* zq%B(cMWJkS7(Ra-3Pywy`KFu}@k7`uBgDTv^CO?VRs{UliO0nMuOg=ZZyf(;@J~k& zUFp^ixEkmq-z&Avht1glxBV8fwmvzNp_mWpg?-_3O{XhOIpvL~#f;FpRF3=M2K5wm zOPJ(T4H;_ix1YkEA`^`v-KvNtKM{FDUv5JK3`=}|BHn)n_yO_v!X0H-#*l4jm|a*{ z&0H>Rd(Yftdr!BU-&`YpzdzZ7U=2qix|XfX{whS41DR{gQpkLnhw)sFCK(PK-ZWv69t7m*=OxwVmrdJ|Km(Sb?&L3Lbg zjsoPvxFr;L%s7mOr;;<+@h0RSqHVdkJ;cK@$zdF;4aXV!U1@i{&F-SBxlglXld z;AJ01$+;Ph5(JM%ryh78Y4CYGN7EXvis!@@BprWlDqUR;oB~o8)Ym0rhSwnG@pz20 z+54$UbKn$C7A%d4)pVDvT^@H~GUY#_ZHsdbl8^%wtGw`{Rp+O*r}tTg3|UBsyAhR!}Eu0Mzx{_rN(Gs;Oj+b zl~eN|T0@5RH2dVp^9`BI`x0PE@CV#ABf)>YsZRO?IsoHg{D2bcF^aHMb;8S>hdrng zwn3N8-aZ_UHD=^hf{56-ZL};tb`E6xEN*swPZuXM5*)*OX8aM;ZoPDrh*&Y>xwE;o zF=GjKSy-?xJ1_yeK|02B3T+`Kl!(V^c6=}3dxe3IiWKon-m9Jx9)nIMALSplBiet5 zBlMR&oG_ORpp;|HQtMZ1CVp$OJaf*DtOMmM(cl3!7PH15s>+;ZVA2GvT3)tnxC(jrW|dWwwn&$ImCJtOP#M7@H|c-%aQtcj z545b3YmIGmVWhDhvyQo%M1O%&rMGsOd4)^eAq|%jw+!?lhjbb{WCIR`sH5ePu_3E# zn`;O2Nee8m-mahns+UyQPWZ@_ZcS-VkHKzt=F(Rb<2#7!$=k#;e4X!0Pye&+haxpD z=jia(oivullcgGmS$NEvDp!BEr16)67NZVe62q!<*V;+cWa{BQGYI(!HAFqe_2sD61ukwR_kB zck4E2etIe{)>N}=t>R08`r*l+ZQ0v#q>t0f^52h%bpCVRZ8m4%dF$L?RYV)WaN}+Q zAWlAnnTNhe8lx>EwjB}USMpr7u>!B7Zebg4ZCC28wyvK1ucjMR?OVT&21=|UkW|># z1-lT#)R{2WHG1V^3fv)#pH92mp!n-2L$}L)agLV)+N`>bw&Z2%AN0Z<&TeNyobv3HNm#T!A(-uqzyVZ4H0FyDVGv*#7%;acAOx?d=k zUo7?q2Ai}^9xFlKuspD=;ksq7T=aCemRD$H~;_+v<^ zGN}h(_cXe2BOjh7*(M~C6IvA7h%>F!+M5N%h#w_FHfV&y<4X0I91T@F#Moi*%i=@o zd|N+TeZG3E6X}2P8)Gv+Fl43gOSY~@HNeq{`LeoA1$?6!;aMZ_v-?5&5aS?BqT zyy63f29&ZVdA_W-V{y2pmi2ij_)7uZm`B(6Mtxv?xleyzm^33l)YjGTrOeRR+OQzt zM~vE!cfHk)rMgsCCc?fCwI9_Cm-?L&DfHgUeIQ`gl^_RiLv`> z%*}rknU(e8dS-=fbxS!#xemKkwSi8x2+CErg|$ux<9b)~d&!oL&K1`S{3KGLLAdH4 z{^L&f8?KYw&&>w{|F1m-AWd-*;6vga$hdws4`^~s9G>VOli`REoX-Xpp-Esj*mE9i z?V0fgdJDKe3Bmcn&|vbRstv8lPT|OHDtCXR#Rue>47sIfZPv^jW}Cz(i}2ZVb}2}? z7R`o?mgN^}CVjP%B8N#zdpWuQ5f_jx*A(tXk3mibCp`$42u?)RTNEG@rH5k%f^JNVo%*tuRmV(KX%!R1%*pjO6B>N+Wx$-Y6ZRczuL>Pajdd;f3t_Rk;6^{J$B4!?Kas^hS(M`qsdnSvK z)~;z(bVuvq*n5TfNZcitZ1t08Ftl|n))}To8Myi~6Ty>pV`9Td$dp)SDZ-@FM9E^Y zfkGB}6^(;*mFUx=D$8^eLv$AgQD25Mr3}V&mO>(}X#_G}DO}!t3HY z<;(co2nrNy`?=a-s&$(rHSN_-QI|uEmqPBqKY2qQ>gl7liQe)AT;I%Vx%J9DHc#W) zhps`uK|krH1=;KdGg<5P+}M9y5?Bg;NM~c1b<{0eDH=)|RT7zL4NMua_jM~8dVo9| zVS0-aGpr8T1QE!P5EF2;+Mp)}_lu!QrnZsA3M)%SI!XNwHVW&XhDMXoiZo?M0io4B8Ov+GS_82>&q)sic2UWN@e6sc>jk zd1(#htQWIWvIFQRvlzii1g^KQmzJBbVc5iALyts5)o{FRpl=7b zALErKE#$6m0x%3kbKI#niOye(w))?@PmGy*g6r5ZX(k9fFagR z%ddvt-RV#|`&h7?yx%GbFENYj0wIzZ_}Rfau;C~F;u;iIkE(x!xnm-@+cSnCOsm|_ z)bN`)4v4Rf)$9LJ^&{MtzxW$bgSd9(_%AcAH~P{8bm4iFX?~1mHw)qack+)6v|RuAFVJw z12) zNu}K2fOLPKC^`=`Ib5Axbpt7WF+Un2S%E`bNi$|87 z4p@JG8EjT5g4@|iT-yL>#N4$qY)5j_8>a#EG~WTDh4L2tR3|$LXIYz7n%e%7taG!HwtuR^;J2TFO7d} z@?gUy&c|~-6Z578t6tNc&5|Q^7rX_AGs5UxWibF#+5wg^n-O*ct$FNWWi+_Js+e23UaSmv&C{5ys$u)sF?*_=zXD&AahC2L1mG~*b zu-wODr4FQ#Jv$B@XL(N*KF#bFhh2ZK+^5elosv-b(VNqY?Q%kp;Fuk6-lLes+&X=- zSBCXA60VbbAWlN{(=RC0lcnWs?k6t9l5;tK%!Vl6eKP^16=I;(1wvn%ctS7gLOS`a ztL5a90~%$i5^3C%B^^c^Zwy3$y=0-*4{IEJkd;!$mfk5#8)OeVoDJ~M1uTCgEICq& zS?K|cbm;@50DD>Ev|ic;4;lL6dL8{5nFFr?&XW2QV5OkIkByN~$mRYZH!7E3a2HHr z@R~z35cLGKb;#yMsK(h-3VMJrxpw?4=5T$@j}}xN2d)+)PUqhQC-+6(1T(}Z2Mjia zV(ZoGR88rrr=I6P^u?w&fJA@GA$I({;~}~|(VzKiQ^vHc z`+yD-?P-3JPZw^1Bi0G@CYAv}86rpt^8ud(3md!05s3*F3Oim(+kxc%>0G!e%QTX` zakHttzHRrb^7}6FB>qq}+%&-uK3ogaD7O*E0tl&1I6xwGs6J1Si=lsCca_V0Y9c#@ zGVOR$>+05$G_BtGhGxLmv@Nfl6HzDZHa`xJ*qvsC+Vnu3u23yosfvL;)-wJD%9-A* z_&Mt8x&HxZU@Oj0{EF1W;X;V_(5lHB?MyqA`Kwie`FEP}C-EeA^gytZPhcKnx2HhG zP_Vbs`0ksMPiS9Fmfe3`ZO7J1>!u4WjWr)$#)q=1uC5PO-b+AUs{jo7E>pMYJ^#wl z7yI7Vl#&nS$y53CW*0)ebF=jWp*mr|g81D;4m<&}38DJ$iyp^5Lf(W8M?3tUMZA92 zX0CeyS0sO5r0?COtep|;3QN!$6w3s41k18&{%C*ix^db94G(__==&st>pAZ5wd3Uo zBGAG^y`$>eW&DC(8iSBHN1P9kStP0#4Z?!`y?eo@X%STpJUd0NVp(+)(n+d{K1Ryq z_X*I+EHh?%H@$AR>*n7~`uz+Ys@+?L+zbal*N4C#q!;(6bSY~0FMVmlj+VmrZSjm& zn2wt}z45>G<8*%jNImo_!02d|od z-4z+H$)+76ckR{#ye&Adi!U4quLdApf5H>>vax!O3aIsGKAQ_)@$<@nM(qs7NsK51z-Sn zO$v?x`zIa)?m4-CChrpp?Y5IbN-Vm)8io4DKbYOryi0v|EwUd|l2NV?1uhj5*+s@% z)xM^FAt>UiR1Kj)jGo_wNvTF})(z-IFUwZrgQhG%VRhi{_&XmR>vN}u{1ILz|9Ftf zFGspN&elI3MBdETke3ktadRnR!tJjwnmNW6Z4 zXQa}yi-Sbwk!cE&UpfU*C8c*A(q#(a+>DOAIyhsgK4-;Rjbm24b#;zHpC_#4wud)I z=H%|%ZCj@ooc$RUp-!g9HNdLInb1{BNr% zd*}a%%+}C|?OJjgL=9Z@065Dj7IVm}R4uC&z89mHC?gigru?X+HKoeMf+&*PAb;~(} zrqiu|LeF62g_u+#9#peZhOKr2deLC5(T6pWBK=1h1rL>5Ze9ilek0YN@0Zqa>mG-g z=KiEoPV8L<)pXVU@B}x$y?xc)aAkH8>L`?h%pdga@$=+D-k(|T0fk(i7MWM_(*AX< zB13?#k_F2*{?6?wzzB%HtO8Ej>#0`G^j*7ulL;_ZQpeqp^{Fpp%L zwSgtqQp1wuJe?TIBSv^T2$z0O^#b|tXrySbEvE^bobms~**6A<)}?F4ww)8(wr%Ug zwr$(CZR^CgZQIF-lR166?@aesQ@5w5YX8`4RqY>pz1Fj6E?IIXZZ;Ca9AWO@gp!zl zJs|PAZ}kFd%okl9C|P@*PAfZVLQII8OalvkN)B$-gzJGB&J5LxBS6(i1EDu8FZJ^TV~#4uNeQ6p8P?q z-!XbOVc}yaq)H~&m|gdOt|IJ!rTS32iSm6g7K%lMk66s~$Q7f^pW>YKGB<``m_l`z zP$zr5pXwbA;j^oIKlNcr(uYTkQ1#;b35^@Df>OmZ+l6*EV7-KcZaIrjVP76e73r}h z`DICdh{1z=17K1D%B1@tUxBRR=5JihUQN#e6X@`hqZ8D$67)%bJyITb>gUS;?UAdf zi?)T_fD5$_9cbwc@`ly#iL9$7x_rHX@C=k5^T5@QydVq!HE-$HoL0?I&}SRxPlP5| zjOvA|QPU`s0JhM|ZY|~%g9ao9N9rYv&>jIF%GVMfweF=3-5u~Qq#m-MDD{Phwvjt& z<78`NY-IS&_nswxdqnlZ%Y;|C${n#pQKjAy+Grwn6$2ILdFu>HV}LrZJ+RFw?1lgB zUlp>x%7J>t;qGb>_Y62E4YxZPXJwc&-fQbOHJ)Zj#}3(#I4v;rOCip&-d)scy<#qZ z_pEBIc!P&O24*uGRzA}S&wUMbEo*!w%ZVNs^Fx@Oou74o5VdWIpW?L!Ppu=r_TG~H0W5Mt@b7nTbt?fv&( zBC#X|z{1^6!7Y@49#z#+lkhE`_t0a!uum}oipBze6^ir6wDzg%1!V7L#TcN~NribL zemj!y8sJwQ1>SYJE?UhYl?@yvX>8e7Umo9R>F?SQJjJsbTmn5?s)SjIgfKsJZ^8TU z^?tjTkz0=fLd+@g3+N5pUuAkslAIAH&G*je}&;&3?`A6n4M1s|K|^hCbGP2CuOT9U^!GRDLn)$)y` z<>{8q_mI3%%pqP`Y96+MfyW=!p0Un^h75jxT&oe5cjA&0tQ%mR&Dw3He#Q32l8!c=*4Ae)R9V^<6OO&o8QS^4dwj7>8Xn#DCF>m%0 z3mL54W!VMm6Yp%i7RXBx*33hZCWw>dlf)mF<>`YpdJ*(XMCudho_dlnf2ehT{<^-I zWu5OhSgT#13cD4T}F+Hb?tc!c(il3Jj zQGhnY9Gi~QQ;Z>sRSiAsHU*_`}@+F04Al8{I$ zF8I#=h)P}ioS*UB0X#w>*451XNf;bh^rn^gE>3fXq)NQtBN(NjwHR4{8dnHuH-_4e zuy?BspaNh45)e!_o=^1n^w|$llUm%)&md-4Ch=Va3nOxquip?c_XFf#nV6*mA?FDY z06-Y{-wo#c6B9c)8M{fF+gKVK2`MTWJGj{XV=zZi+Y(s-g=e8i137VVSouP1DL@Z- z2o(j9GB|+{!kj!@nf!%+J{@-|Z7ZFfD^vA5{5zlSP4Tu5e>WEC#!B!!FrW?k`QS3g z^SXE1oRz0p^Hn+aIgjdQnRB6fPSeQTVtN*!5)h?0{Px5sy zj?_k~IT}~U{<6*mIe*~Z+0N3m)|7FFWUO&hTJtJHJh6FzF`ZP%eE0r9TAb(#1RlOa zr57)Fq)m}xi0RgUcjAT#L{K(W>z8{gjO%;43uQdrlX7u{CdY0H*}Oz&WwZSzMPYeu zH0??}3neGyD-gV==yL;m3F8EE50B;ro{;r!8^+DUm{-$yuaW8~`Z(Ezui4k0C-2ef zAZ2!#Z%Xe636XDl1MWQ@UGq(@zxP-V+nB1uqV5RRGI4LXhZC7)be}+=F8&9qfEn`Eo9uj-^_oO)ZFZ7haTCn)#GR5ySj5Z3oxd}GIufi5 z%2>%CX>lZ~Q2fe%_Bih76t|0O27SN0QApJ~J zS&(qe=s2tK#B1j@6Q8fg8=OAYlf;SOL_cO#DIrEy?S{bFtN2y5j3%8p(8SVXvd<``p)PS6IvTGbWK)>!Q;>Mou zc&w$T2DP|dT^Q3F?oAs;FHZ4;EYHxi@ z8pI7DW6_P?U@ZIWysMK>%LwquJQc7M80Ff33(hR^Qxb$NYKYS1O%9xMf+R)vx@Wjt zd{sy*tJz60LOtfTBjV4;n#-&cMtbJAe ze$ab{v^Am0sjbPvyyq}(rq!ZEh$ReU@F;k0EJ2W-pX@wMcAXQGG9&RYc0%u+bR_eC zPH1Ae0EF>a5YxkZ2O8lTY^TF`Gcv5n@Eu*?;8!qC636aEsEIdj!VSM@15`gFErIBg zY!D(T6a@+lHRps~3yiATl|i0i5E#=G3*Y^~?+u2t>npKAu+=9WxUYtD^32`yy5vW# zvY+g4vkrv`+3tqrj31rt373|iOjbgFV(4NXeB5ND4#x534@SZ)SoY?3z1~GAyis^8 ziLra_rCNBUcID^gm|zrT|M7ve*Rj|raJ~*|u?*6Dp4L3CU%ktE9Ciga=I+$qmGW&f z{2d@a<@E;p9cBDn(p}&%sn+s3H81)y$YIJsxxBoycRIr!Wn?j_(SoBM9`(?FA^`o@ zxi$bxAHk?Uf|daB|0QVuthJN1wf>G*HA@XC<=-TtB@k&KA-GYT(w#0j#LvQ_7u14& zwN%FitHjFH)+jM&yYIRy*j2X-jbHmI&zrNR{ez}lzCY2OgX6?i=XmmVrpNaSR1Yr} zYV?Pte(x~FAx4dR!38(;k{qFbnUwFuT^o$A)6Z+0@x10Sp&L;6U?r*F7lfCTA)DHm zqh|j3iWY4ZS0A%`yi?X>%Gi_+sF;^p!=y|12i#!st@3pYAes8pt7lVJtAZWtYiOK` z^%P@2^I6&*Rh5hSGoXm-2k7Tnxw=k88zzYM80yGK(-&Ap>Bs3yL>85QHANLcEd^aa z!u0c+lu3&Tr`6dl53r1(vkAQ0xR#p-~q1-_y7sb2zz(?04IQKL_&y^3!0uq2V++s%KJ4LLm#EugL-DaX7)#1q7Ww zcYb*ZH(|`IMnsVbJTm@Jh(r5#TIl?x(jI>kMY*>PtL!|HN{AAFr+G@cp$=!rS+gv{ zSW6kWb~y>?+#!K&q2&EYi9qMh7U$rX8U)c2H8$ z^%aC-K?r$OrR-^c#QVHi6h7x*<&1l3qB#$Qu=+#$vS6mi?`}G@?$USPfL@xag-9dfE1Ovxe-ok^6%*ZnPsvIcn|bxH;!+7mkXAF69J4*v>%k-( zUa@3xSJ?OtFx}aJbk__~V4n!;Pr#uaz0W8w<71K#S1MnBJ?c)Wd8^B!FhHysgiC5G z2L?$2Ja(#UE-J;e=dgEUt1&B0+WpGKIbfur^W+_dFE&!MH@n}cywm$rR;2VHW3B9E z`jDj2#+!2OD)aixu}^lodx~H^mxhk@{mM~I$VVt+w=CTf0?%&&l<7iu+66$9kHJf^ ze%d@RnIx-!N8NScFTZ`2ex>wXV^d5&0UFPSji6QyqfXAcBJ2>vk}lsOy#5tv*YVm; zC+*Lw8Q|ZgAOE+ED;e83{3;s=)&+1O$3PM!nF{XoX(?fU(UBT4J^B?tOt}s1*&Qj5#lm5T zsn~CVz}6?m;QX-)C+PunkyIOu9@JDN%aZ>RD9VSTub>JpxSdv+Y*9Pn7m;g+t&K@w zg^&pHjfA-mKR}7l&*^aZm)_W(&&rIFKZ-018~}jnfBeZmdxpl2j^;L|bV9}s#s&_~ z*8k9dU@F?K$RZd%q%s}W4WD^I7Lt|%0tu@PsN~Bf%Eb9t;?Nmbr~)%aOr(KhHk;W; zc`ILlbex zs~q?go;%ctBOlx)lp^pUF9d|p#Iz=P4r5p~M$@4&M&Vch)Gw zhQ}otjhC3mZd*<^SqMuYMS!Wo>4JZNXK#wG{T^Q3G$d}dbF={;i++WFBgNN?h(M7M z!QaIgK%+fdc!%K{r5#bMA4%KjS7t@M*lp68zSOG^jO84)CVGWx50v8~x9V|g``mx_ z)IY@9c8{9n6#W5@_zUvw8>eIev16BvLFj@~QGEc#Mjs1K!DpBnCD?=ILw`7|$M51L zK$dBBFqJ%UOJUXNixP%^n;%p+H2m=nw!3)Oc6NmtESI1^=b*^{28I|G$2Y_gtU-?9 z3nU&Qd=A=B5%hPR0%<`iB3VLXqo}9iWHt z#w-lB?hSf@KnSo~jXoeAEb52L+uEYmVk(x9(29GZs=;{y;Dy?M3y~1t3^U?;U-OCK z>)GZ5khV)JAfs34PI6WN&3zv((^T!S`E@TKb(~aVd9dtozBOKDS~I6FB3XJ09mV!2 zJ&%-n@+w*>s;8G_4x{l<0a_#5DEnScGNC@+MgWD5l0rAwcg5OPc>ZQZFq`{EB8O)@ zeD>Zl>Fidt$>^AWnGa^!GOp4|%Pv1Y^zX0oog~D_C5>Mc%N@*RY%I^%g5(aaKG^V)2 znXl$-2wTU3X;zqh9eEwX{rfI2yR%?rp*!ECc`;!~+RL_esh`0DdpFBzbW*?r&$Iao zOJ$J7eQQa7@gHLP4x6nhc)`g86%8!vI#6W+Y2AYT8Gq=?351fz`AbDP1l);GZI-Kz zZb4p0{N3!M4pI@a^7)>vhM?_22_=4$XhEf1kAOs>;e58000p406Y=-XcRm;kBa zmV)H|a{js^6hJ_zY!(BW#O1|cgj?Qh=k{7ZW{rwqIyHLLx_n$Q1IU#S6dB+vdPVFV z$rCVtrL|0Q&9U#KiK|Vmm~1pXf-LQM5*f!Srg*R;_InpX`p*2BDz`@O=SaQq!hwry4z0~xkd?Q9U=(yZs45F$Z7 z99Y6gfFe>P)l1?b3KHN4x8uf20@O+A<#=I#Oy6ZD@=hK6<9=e$Px%+&4T47X`z**} zl_RJcBnK=}F6&uu@1jU{AkQ))Rrao*Ulc49uC@7eG!iK93Sxd(_>Z3lv{suij?rNh z4nK9GE<*ey53C*veH=3*JN3*h*9aeF<=Rg1g~*3{g2GZ3wu|o#pg^dWpb-i?0`9nf z+7y+c$=8~{eLH2Qct+jR4v<3qSz-Xp3T4Gu?JwS=Z)`=BEPmPuj4_@*Yk>@DOSWjGX}4~VmgLW311?T+QO$Z79;GW8a+czy5!C{7ip{7gyH11Qv&M7U3^iW7OIG9L#^mgxbO)#4u|1>h@xjCDiI zs1R5!%6bVjk&y^4ZWoJn;I?YBl?HS*hD9b3vr_^z3r8RcLq@e9``MH=BfJH&91}zN zkE~PNW=LAOy&n|Cn-2s*@$&hFx$nt~4VRO6LZn8^Za2yA2J*rF*pNY7T~gSDsI_S# zE;l%x`opvYr3s~4pswRXs--V~62ug!r1R8Hq9r8BjMiivTnm<$NLsd4Z^;Ho_ zgTWLP$)Mljh$q7$wCt!7%Sn(H3UX>)K|W1^R2H(%7_Y2NSd-285LOm{=IudSp{vpo z&KYsrS-Wtr*Z*#nK=_kd-o)1R|Hp2sSinb%i#QM( z+fzNMWtNK`p!S|&G>@m|RZ3sBSqcxFEY1+N;d3uT@#XIXyuy-w#Ur&yU3UWlt_1o- zDIWDv@%zNgRStM@m!FS+jM1k$u!TPM>6E=T&BtJBGBL=AJxIgeM_t#FU}?-Z3#izM z<+(x^0<9p}EPt(CZ?TVF-1~=?+pWI@DPDSCSwi6&QHduRq$+OJ!Q!5m?ywJVI3WGn>Nu-M48j8re3-ras$dLJR@jbxR|NLK$;CXoY-N~Oq}R& zR~A8bWbh+X){NDEpU=6Ymy4v23>a;YiP~aXQ{`vkQ%!|jt)y{rGGx=3 ziD(6LY0Md9`LPJqsrh~+Q%~x z_KZ`K&VjHaUd#b1Dqn&GrL%_~#J8WX@~t82caSe_PIz{DD5k7AMdL`^R;=}l1t_0B z!qzM6ydkDJ2YgqEufi=8>UTsg`k5J1V^zfDd|k@q`POH{Wh?62Arw6!*{u}E*N4S# z9v@BrZ5pzFFT~fA9hDETo};ul{XR!M*U_Wzq`fb?@O;DNs;pk$$`^bN-BC{Tg|Voh z!}afqm%t)f{!|hsBG4WAJ6}b5@jhz@>g2cYvVECyKD{%cWBLIH!P`}$dk3Dt5S&(B zWL}jQ5sLCuyI(srh6j08&`rNy3Z@IuW~4?$(kTUh4RUbiR!iOW4}T+RO1G$RS>7dH zL}-aEOa^#)ynBMlVP#^2!c8w*WfX{%+j43FH}YrqMVNpO2LuhFk(*jb!PVecv~&k6 zh_%TX9yku$KPO5TRjY$9sjgO;Zk-8sRh!ndnr0wTs#?iHycc)3EG(RiAs0<6ScFw) zlxDeq#db;tUzB76WtOn5m0+wsdy&rk_5^%&lJVM}2! zNiC<`J2BRBh^Ik`T2Au>`c|bAO=&T>QC2a6A}MmFbZj0 z-0~zFcQQDzQH79X93H9FNtB?&ba26cGA~NRhu6u2sY6GO@j)PkzIR6Z7znNv$00%Y zWJju6f>+@Eq7T9v=vQcBH8e+(ezHDG^C^r$eK8}*Z?LSPrG4%%6>UHTiWJUs-kk5Y zL(J`9fIU8-qs%lu|JN=<^;?i6NaaUWkQ~vr6?7epi>FZZ5f7<>lOYe_z2bU*9TG2} zDmDxqL~OAojO8nc+L?S-&X`EY)kO~f;q4Bb8Vn&zHE+0$Vf!aE-{Nm_7bq)=YHA)R zlU;=Cc-I>Q_K@2YKifh@M-(>sAL^KoAgW_ra(PvZ@){{Z9|+?g*vSeYqH-I3CbOY~>7@R?`zdFZ%+7I4igP4;0a2lQ`LIWR_DtP1rcnZn4kZ^dM7svy& zpAOm%=#^Of)owk1O>}M#-`$!{H+pu#_VnIlnLc}9yVxOkAm4=Sgul|L6Zle?NVDYu zspVmA%!XVgbzpfS48flEU!4x)u7-o#!{YVPdSNnf$5^JH^I(i@n7`tGy1}g+c&>`U zu+2JTwIDaG%4M?6p97rKe>PlTMRKble7gUhRwq_??j>KX#1CNQ& zR1ou7a_ovwtO*9wv~vo7gK%!s)e)A}mM*_g(6Nuu0Yx#3XcHD_1e(5GA#aj+Nkh4#NnNCVAK!|9&bPnUoGpY=5eLp+$HYl7hu20u_HGf!!{FO`H z{SLXwGr1zy{Ff-Or&mDJyP2-Z5I+Xh1WmcaZC0gR~S=&^*x~u_w2d^&71Q0 zX7Tc9t~k8I;&Fa);AR9AtMG6jw|k3-GrdmAJGhVzJ>AL^0{Z#ww0-Za8*%0ts zQ(74eI(`TVMrj`)gI+LTQ*dpA{F4^!+QrNb9@&=+*&Bg%d!qHmah_TTU!;ANnAY`j ziPJo#`B=4H!%Clj{Jcx%rrT0)+=y{n=u86ho`QL*Kw1Z89l{PnQ4XBfUYsoo5GjuMNDP25DLqHU* zx$8dfh^iEgo18%hzGDe$L$|eo=Pjh;7q_NWe4vl~-5AfO>lmUoS0FMEOUsIpy9I_1 z!cbjw09~;Jz+AtNPXhv6?Qrlqv|Qp_Imb+2FfELFT5jfaOu@U}TH!$G9L7lDO0$Q1 z`H+NQvU=rzJ^LoNvYBQnqmgHiUOtqsIXrXp-U3a^fc^YRFw^n}m z%4FO&rPz z;$5eIzEa!Y{AQt@I*7S9IWuA>k%C5-#T~HBZcZq4=1^d)lLwhBBs>kgSXNxA-V~Uv z9x2_dh{wg>} z*_6a{(S9%duuVRI((%mRP70GX-9AOyn*K?DP{u><0yh4I|F1D8Ei$7t-=An473e>R z$i@GW#T9WgG`9OcC<@teGqQgo^5LF)Q*>1nk-go%U08a1Ityv~pHagD=K?U#idbc9 zTQ(gc(Y8lpgMsk7LYNx?b0BiR>Ce0#rfk<=U%WiQ?Sf4FfFgJ$S(5e;FSi%Kv4)v{ zvqM@Rlp}+5xfycI36y|tq>BXMAu_U0N7xo6ixzxbl?8(JZXznih*Ul@OswNumC83- zq-NE*AHrk(c7w)%W0S0VmYr&JIkAjdFiQ?}w-5HP1 zV`2;onF+_txCKAYkL4-KeqI99S8k+++ znxa?5mZ;ZrfWow!!!1d%(>Bj_Zgx=*hn6f!!DMN;PCD9~(P*vmuF3IO>y0r|medx!X1G z0wlc_;LvZw;HkzNw4*Eb&)A|dhu&-EPIvoTRoYNXeDQP)k2Kr1`&EYP2EW!8fOalM zUXVk$*q;(8Ad#%2KteQ9s~<1QGn;Ri&GFu`P8-j+m<7g3=w1Gdu$%Odq| z3?qqQ24uxS`5`B5QTVH-88RV%VVfSK+@n|ip)gjTQ^W4MI4P=J)o|M~T8i6f>sYcS z#}UYsGRlWfx?Gz_QQ{$D$O zW5os^s%`$Ee3&OS(4}P?TOCS3_8ZOiBPK$bTs)`QU4Go}9s|Rpl`1!Xo6W5U(a@e| z9+H0EIO-vW%`H{kroj5Os9%7U8zrLySlAnACc2l|V!8iHjXKoYsI5QL0R6Kk{Qpdi zzcmT`y_iY-k9TWpeH$ake_$$w33L2T#*so6 zC;6aION`Bm$lh&cR%BrQ9dtG^NRBBIFg?>XZ8x^pSf3N95>k49lCzPmwMB!DUY8=_ zPL}M>6gi>_^@_DP*V_@vO3T39Oi$4(TlUJ11Vdu0SIuTOG^Dc8@YZR}R*wr;!(^qU z;o%Vn1qFPC4`FRo5p@le?<}s%qE-@>W_#$2^I%jEUQ90QbdL;6nHe*G#=hQB5jkckg}>W*Vfoh)MA+`SI>BpKGbKN1+d9qsDYBaAK zJF3wmx4NsN2#|-GIY`hi*0hWk;UQ#!k!GOIjcaaysl`Q?nao4kSVds;+J5F*2dg&Y zi3Ku|NwSa0FLJ|xw7Pti`)TaTJsnq5bK#6`*Ec8`_c+n<$$qA11xGX?d4_fGygS^vrUPzjv`fL|zy#u&rIBCKK2$ z>v7qP0iG+8L*ne4R=W>C;2s$ibD9Zz?;1+Xpo79uYuZpJU>_r8nP@;W1IWxb)k_Wt z9}H^M!8JmkRA_+O_rWa@qz@-)o1bU=?mk9<5RMONADs}05=y5{Y8{R~ruDSpi<97l|8KhG*ees+8$-Hh1={)a4DG zF@637r&<+gY?$68ga=EwAs^1Z~TvhtPOX*7NbUDxnl%JKct(c&VNaHjMh_h%XKBA9<$o|M*vfZV9z@AWaqN$S{axmvC852E!Dqs4UjtG8( zyX*hUzzEyLW`4X(J~j`$)ah}*i68lM+jeTz+;TRnL3Q0})v+x3=bOFgfClc&-ev;| z4Q*aK^_Y-}Ow&3^y#nkBC>)=fto1b#Iq72`hMqXxXF)3yL~%vG4sg67s`!u(CH zii3msWoHx8!aZcm=O#)a#GeBcu(>}q1TFkvmt!RY%>7@^L6&lgs>YVRx3rM;c0_cI zMFq1ERy#8~B5+qoMkV~GmjvEAz3`>aMhRvzMDV$Dd(1h|X{8^dNJNE=_uIK)H%bU7`cV)DH*Yc2agi<0w(A#W`1)3(6 zD^EeifWBL3_dIDKMxbqJ`(UoIsYVnWHU ztIo@ae^=#yH`^{tj26{!t>dp|gAaT6bHaXC1V|4W0b9opxb^+&D`>Y%Z|*Vab2oei z{|&dKY+8T#*_`vNkuOl3Y^}G}LHSa8?&(N~I$T75?hu-LXa8)sgpkvtXP_MbBrR;j zM~5x+I}&5O0kT))uLV8)d?}$zAt;Cgs+S7*cYFwnRkagD4SrWYQ!z+6xe7->vIFST z&gkgun`xR)OFU~|p#yE0xcT6oO%eF#7JL6Yz#QE{k;1^w36zz3ze+XEZCLifa6GTl zCPTV^-#^Cbbn#Aig$j_x=7JxbdJ%GtrY`;VA3&a)3n6s}R#0;*U%#Hw3XT+mZmDav2H6S(Sjy_5n5d1C2bG8R!~^iNKg<_bUE-zrZX1b ziL4eiwX+sC2EE}>WD^wwDt7Qof>FRCT_aF*)kV#_-gQw*I{f*xI~M;XY5NiRWHtg~ zQv=nX47GCB(^2aCaJ>ygdpgeLn8Ggo3c~OL%J4#Dc!?bD{R3fsP=sP7OJ%zKCWE->_UoaML0RqbR|d zv7izC=xZk`}iyX;HBUpa!+$lrN8($5Q`!wlYOZp58bL^lJWp=ahtNmp}q$p4P`5_qKT<-@&QmoOGk+@p&c= z6OWv9AK-WQPP)Cdp|%ufsie=js#~i{vb$*-wN)?i2KXAAU^n%D|tui#e6P1 zHCk(uVqJ3h52PN&mveRd^}7qDja%&Xeb+_yk>9vM-|+uxpG}C9VHf|b_yPZa1N$uh zx6QxzApG4v2S;_u0t>(djri9gKok@QP?AUqhy^2vi+>2C=j~{v*Ug#WZe5G)FOjw2p= zFO`O6g#>3}b7tk_;ZbIK8QF(_wr3`yEvfhuGU0OQMiN81$eLR>bQJ5J?5U^`39gbg znf~M?P6*fCcq-^%!}oxSHml<*YgV^o)#Bc4>O$S%*4Bc4Y2ou=YHKNse^vfzP6htB z)Yee!ME;e(d17_o_AhN3Vu;o{mVZ2KanS!DT>h_fQZ}|S{;vz({}C>KD{0I9Z8iXy z2704d{!hdrnH(z^ufmIj%EG`*O!~*C5O>S65yNP>V(nZY{i4n_W4;4_DU5P8VS^Sl z4DwFn@^rXqf6nTBzj%Jm1#qb|G=vyHV}xtK&`;w&;kkbM<$aFFIvre!A-X-P6%AaodYt5HMksaJ~UA ziW=v^-JkT#r}!hhI?p&c9siSJOZ(jOkUiMA35=}3=%H458~mda8dL2qL7>-@M+ z|NgNfJqiu^suj_}tA)wWDdl|vW6mHeDbaYi;&`z7^L#gj0d(}y{+n}w8@AbQXi(Z> z|0C}WeC49KY`*sm-Tbq%X#3nSKXyne;+MTq__VR4PP?FCF|!t_=lfqI-Kf^g7zGRf zAQblB0q8q_IolXJIMV$yoT;+&{|3-6Ry}h>5kdK8;UHaOmI%WMacp-Ts2?o{K^?^k zvk@0JKu|Wgu`*>caxr0Az=pfI2UAes?tLFD9H*o~g2ex@I#c@w`i89-Tw%gSiV;U@ zv3Qs1d49wFjPddP@_cm#$h=bmVUjnB zciHmlpE}u$k}jeagQ}(3k;D$U$4xOT2gi^!xVx5A&YR~CDul|?FGM?gJ_6QHIU~ED zSF`z{f{JtY8eYU)Ov95;y>d2B9#X-(XB-11*Al@!(6I<&674|pJEopZR6ZIDxEZHW zexy!+-{3QdsrW`qmUZs3JqF2TTqcnV@hY0c>H@@?b+DvJ`&~DB4abo_HJ|iABd{Ud z$g{@Ua>k{Uw1rGh7FzcW@?jmZBlp6X`5Zc@x_QxYas&uW$i4q^Wj--6QRi?)t+ptY z$kp568miv^!-K|`VFXDS(*kv~+bIv(1j(=t!f@Xq4_4M*UEVwvByH*KO z&itG*W+{w8*#g)>(S3wMM5!iK=1~(b{qn_qf{3MS94EJGWRyZ|)qi+b*$@;9qXj%f zBsk)Du)Zuem9dev;;jgIDiMJ%BZiVKBbhP-Gc|5bKp))*b=e@>{|N`uDlaRi0}_RQ zB!29)LEkL8I3`RWz7Et_r}Um25c^=k&N3KnrObL`v>r0E90B?@N}iE?Q0UE~)xl~Z z$byZ03C%aP{1l1#j5p>gL)q{(dwj}u)E_8V-sExUX15Jrc?MM@KG8kCJ(R#_gK-u4 zUh$`^L8|{2j*K{CRn8#?SV{?B`c@Qw57=*u)NwMcp6VKhF47gH`!v;W`Vk^=1<|zz zwWrg=>zjOpIun`AkvSJ42KMIMLLp=m57m|%ERq0PZi~Fk0{}e3Rp*iL8G5SS%UPt1 zvU-mciTp^C#4$HlR5%I zV(f3teu@iI_$wNj2X?#jDka8rxTfk%pp{LDz&JT6>Qb^`b7v_nmYS4tHSAED9z%MF z8o`C^CcEq-kl7eqH%;|SNuW`GsBR$%j$X*~+q@%p+&Vvi)|M$79tBYu_4COlTnRtS zyHh!I`YN5MFvmec0_!O@`%u&m#vpV?u)$;MCY zlUColgAB*XlTj3`v`LF)`n;41v9G!XX=%D>5!+N#9c1)fp=ajb2^*B3G`fBAOL*^@ z=ZQ{Gv*!FQNO}BC_@^mN?$IC5al(V0o110J5or4bs|)-86oe&>s8$d0R*(5)Hipw9alTMlBvezX zGI+tXw8Ol(1z$d(gL>Ry-WCxTLBU?Lu`;k;Wkl0m)`_|q5vZlvfARnotE}0jUb~Zs zL(Sc13TPgD=eX*=y(8(qzhmhpu)@{vCh??AQrq_o;7d{a0{>S_BZ(?xBnS=wFbntZ zZgTvGr4hAtFf{&W6QlO-s5FB5g|^m_@@rI>Wl$ahia>x7K7CL|5CuXsqHl2+q_d<5 zzN1@n0$s{=XqyVye>|k5mf2ov-aH{>w#odhpm+v>`m#vo&8C#;wfI}W^v$uf$K{lN zX4{gCbub!m=H>e0(sg?6;cBh0N89Is1|a*z5=RQ5eztcmj9jR+nsTj>MWLi6VaY=M zwPl`>YNYrgHMzn>rMV!2apR&*@$}0A9~Pqkp0noQMlY<0e@SRAI~3t#2tlk7bh;h| zG9(&o1G^fmEau9%a{fUD;AZ7#d6!k|dFX8-37`YBR%A^;N=*#^MtW8;XtUM zr0fy1+4yeSf2;I-j5FP#JN+sXGYSjSpU03|l@4odzbakzJ%RT0_ax{ndpd_E(2flc zCk3h*HJ2TV?6?AtEcIhCAN%)bO%EY8-xSqGwPS<82i5?5tNV0k?8&YT)Q=|`E^DWq ziF`k8V01u{PBrjL zJIW@cv-bN`yp|kIhE(s=Q}?C@-?7Ud+G=B9F0jkVuh~N3g>jT77EAKc;eWMu7I0B6 zT?1dFTM22Tk!}P8q`SLe>7^S)LXl4C?i8fEe;Wj(rKDLT4M0lr+k5Z(e!TAM_0@YX z{1%vJ`JMlHX3m_Md3NTU!{h*elq$uj8MAX7%<8wJmCKB^JWEf@ixJny36&M^q60A; z(2QP;j8(^@sy@Q=BM&A}sJ_KaV|)3s59V%n2KQ zf9O4^$yZ*(5=C^Bxq6$7(;$KJ3g}GNkD-dBRjM?)lS{VJYc#H0tCmMH1fMokU$8BL_mp!B$@2Q1 zHhQ3?3i1$*26AxV^s^DyJNSXwyb>m6e~Aw=$okZRY0Dg@vQ&|i>mR&38hJR;V%3*A z>c|hgH76C9;KR}Oltt$ht3PoV^r>ZzQK8{k*7zZAWZ@pCXcg6^m%KIKyUW2`TB$~w zeA6q%GA3!WvN+K}%dot-19h+AF1kpIJ;rF?@rMM2Qs>z##3!=! zu`Ya^e$>-~06bm=aQ3_xVVz1dkYS{c@Nzb=Xtk-*v%PRG79ta=qs+aEcevnMSXW5zC+MG!8Crffmi=UkzFP$|bR{Xab@1+c@@x{0 zjAWZVNfP@yBOOzM1j>M>jgf@MY@;o0tLYV6%BW8&a~RJlKCtAU%#r3Ae_Kd^yo9EZ zUd^*TPdIs6pR~vJieJgu`yJ1^2gZPVW7z>LeRMVn>f(mA)i^6bbSZins{|*arwT`a zsflz6p?auS`#wh+wZ{@zh1RfOPinO59{#81&Y94|l)kP^do)OkJU}n#{KyK=J0@gE zpYpO_t`@&WZ4{nqO8+f$e>Q3Shr>(i2vQ+`Pk?X4KQ!Byjf%9MGhNutC;+VH^v@-S)18EDE%sXqfYu&?nb1vjb%Bd{4UY5*zuUS zjr@|nByEI=>q6!m<@U&rlUq7|&m}Agn+c9~PPb%dC5PKMX63&`f9ZAfj~Jcf2ns(( zU+r1lR|WQGfFu>BR+ZcrIdQsQ8IhcQh@UB76&w%kpUQB!G_7bWppH)J+hp=T;|@Ce zgd(0{T4d6N?|EiMB|1!gFvsAV88DwZr}S=mHng0mv9hkOu8*yDn0+kd@ffX$r2t-E zL+XV@Dp$Z}p(72}e_7_m$YU?}t2daNv(9yq&R;Zr6%K5tXIlpLZjTx~o)BZf>N%vE zo^XfnEs4l!!Wya!^{7hGaw5WYu^v~np#ze%Cb%2j+TADK-%!tUjNI9tsYJFnLA?@w zzxHVSnJ<|1BFG2bps$tj+4&rOG2i6t$_O=GH{*v-@E^_!fAjZPsc9-?g|!BIb>u1- zlR26NN^b74$i*;)R~V4bV3}^4rFDw$aAAFdn|nd_r0`aAZsM3Pa?}N$H3dmxbch&5 z;vUb(Bn+){grz(;0^nteMEm~U-KFC_-HS-`Sk5m`JnvuON31Hoy`m;OhuVZ8UT$r- z09pD~p#QIje-}3cvOCbpRMFhr+05mewcoBgQ7`Uw1huu<<6NFlQLz*Rc#(=PG3h+W z638oBj%yl`ejoYJnes}eq~2-0Q+Jab$vqUlH)u%TVceBD^?Y29klww=8=umX&r_CLov+U_f0wWCbRhXe3*k{9^(FlXmzvXhjjC(3uEcLCiZp|@TsH|H z1tNTsYQ_-4x}>RFVTKX?njlavFo-u@m;2!%YLzKG`)jvj#JLu=3Hz}ZPg5=C7t$ha z+etrhSE6TP&9)4o+}dX7cYfZ2t(D)zh#K6Ff9|ET@-`imR{B*XqeNPpC80G??P@Ag z2lfOhk3|Pnqt1>^!(@nF@vLo=wgNVq)TY0c=2JH_Of@rum9~G!bN8*&gMqY!#`zvt zoehNLm(v>lJMqHUPYz`!XgKrRn{fICvCkcavLpwZK4`J2>|I#Zt(~G35^<7b(lZQR zf06Z-D}`H6RaXxcIys^tFK~E~aeSnc9SAQTknQ6z*vH&H5T@q$JD5&=eN&$ zJT^U%uuJr&>8M$`l(f(f!w*7+7gqRemh*eZpCN{9JV#`=cuey;uBH?-`SmJ(Y~2*& zda}NlQr7QKKF@^FyU6aF8G~s3oid#RtJ7JmQvCtUbZf zu-H#}2Eyjxdro@lznP?-4<{JJ3%lt8XOdY{CHHvnOTU2O00VLwqUsk^nzmqCf4In3 zENpNp>Mv>Zn`vPCT!g2)^ESCQOrmlw3psk&mHmcS?tbZg8CyNM$&!}(W;COK@+*(W z=Xt^j6rDCk>`DIzUwFX{uiBEq$#BI*1P*d~JuO1Z^i*FA!ngv1^(%Imv|l0F5WL2` zE7(F_7(LCp+GU;l(4J0qrOS5ge-cKa(na~5mA6NxT9t5%VN;)U=3HRVWA!ad6<@?-)Xac;XPhse~I2$cLQkw zNGO@Wva!wvj~#u3;lhGh!nJam?&U5+m`HQVfkq;jV-a~YZ+8jO*#gdE(~I;iB_nWC z*(x@_Qn;ms-K*YBXC`L@*LvwH@T9aKX&7Q`0Z64Z9^dqa6l% znt|5RCP+ZI9G6Y|!4&<2ae}+>7B}pc?5^9>G$h^+>pX(J<%|}cjZa3KZ`%hUwso=H zWtaEjBJM^%C2SkfUfF)%9WAJGX?kfsiWN>YTd_%Eb460u_WY2df9^&75zA~_@X{lr z{;%%QUt>2e2<8(jsw+g69@UCqq>(p1h;I#9Wllrg&Mi5V4@Xg%apdPEl#lE?tW5P# zd-^K2d@V6efyFrb!zgohLolAbk=tiiFCWe}#i)==PtM8x8tsq$u}hZh>G&Th;}u2> z4cJy?mn`W?=_3U{vgMF!heh!Ir7dddpR?x<0rO0khyE= z^}1WOW|`wHe^XBdsCM<8NQsZ(V6O6J1XE;rFVo_JiC4ZVeMaT?WodG6AKer%C$n4e zI>!qEd|sWo?n`+6q@gGMk(P96G^;&6SnYz3nWZbZEyQxYUdoqe*i&?Waf=;!6UhKA z(Xb1X_r$S#=)#k_BWe%)RQZ~&kli4QeKsnFKNV)w>eOLmsdKE12o zIkA3pe|aklb~#Wf&4`xJB1B)*UY|jw!2fL$9(TkOH$$OMhM=ErMJxv+`Z#ek{Xa$y$l`dPD^c59( z0xRCot)@l_WYytY_4}s^(&^1nI-xzpLQUdgf5^Yr#!QNyjd4Us$fJ=Ho$U?0tg(<9 z<@gxB^q#Md<&}Rdg}cZgk?NdS*zsOW4a49VWaYCgGB)l;?+F1PbS!7> zf2Hzp=O$-&CMJ9sj&Hi7+e8HW;2E4}ij^a6oz-lgVk8oe}B%rK;=lZzSnVJW09?dtiiB{U*p7Stg*WWhnAEB zxmG=>9IJ(D?)I~lb*{bk6KQ<1O%sC=tahqp;be;&F}^V9Mj!v?%p%BEH734(%)6K=${zQ%Y_{_dan&&g>(6 zl{Bvg9x&crs63MCkM`oGUWB=`Uc=VF6Whf#)zqN98kL+uUzKmztX!=6z<$(V=csS^ zk=8DjPxCI3&0cGHQpbFa09W3u+2CXh~%Nr-`6@`IL zLxG>!84}+zhUId+Kh$2+!PYpen+Dtf5G87J$_14>XH*~ zX*LvPgm>#$ms0~im0^!NqJ`|KJ1a>?%fly0mk1F!&ur})kv_6()LcAOPppW1eI`3A zwtg%-E7Bsb>3}FYgjP2>5sL|)V|x<1G~J?O6(viKO01ZKD~cU@#vO6l?>)Ks0Fo{+U7F|!olR`#hI#}~#vR*5`T zP6(unLeQt=wduuiEZin>!I;Woyz&T$Wx(dO75 zT7A+IbV8@D$`gfYsZpS!E(Z=eR6d~a1=F`4?JK|d8nur+j=*<7S1R~rk9Wj_Cyd3i zKH9A5ddhw{K>VFqUrAuj~{D-OkFI$d5F2KO5Bfo z%{5aoghchif5udNU#1TWHCQ~sW=KLoh>3K51MG>TUNo(gn|s$4El6HjDvgN%BO<_`)=4C#e+!H(IHbRgq%0R~EUd*JU8Qg5 zk!+lD7tK}Db|&F7u*fbdN>V8*IIt)ZVGAuNPU?{%n*Uru=6xr_P@!VR#)U7~1hO~{ zhXzR%Ov$6g0)c@otJ=Wt3p=kPncAxBgB*uej&~;sHL^(u9&+xJYV$a(? zD$oYbQRB5k-?v zuoyjnnb=0|SH62sw$yj@DUZeJf?^T_qYuU7=5T}j26fO}DR|K%sYZ5`)gtb2y;Zt= zEY^~_Q8UY8FNBBa6T*Qz!`COS{C?blr7;ire^pzi!k{G-yCte zC<~ThMYC5@TLNE_?svt9kaA|XKf<0gp#V21o6EBJMwqlR>nX+rAt)p ze@a!5noms({oin*HI$|R#tl~yVv7z(tw7-h3jM4JR^t@e@*?|XZK zQ&|h-Lw42OcPGcAO#D^zbHoGTd0gpbe?BL?Wh-(}%;d1)rD|aVd8m+}?ediI5Q+mF zDSg`M25fh>v`IdzO3K$gq7iqD%VdhSZ_K}VF}+XBj&?LD@eB_=EDf)n!4oa02Iu&5 ze^DSCi8k)x`RC{;EONYF9vV(Bp*d~$@)wDBRXkw3VlUEEyk+_k_sKm`gA@m(f8$R$ zV%PDw^Dq>5lk}e8I}q?W?HGkwC~j&huQJJRxBAAZcA@a;A$8S*m}3{B`;b@X>3558YWtUARtp}#Xyv9OzpIeH z#dtr+n*@tGG~mew)f4HH{R)rpe~B4~OER0-9nhvr8tm5s^6)PPF17S!qtb z(+)EH9K98}0tAYs)JRUJvV3jf<^DX;oOzwBj}g-v%xGgDcFQ;NuH#3yf84h8Ru+B- zAGmZpOsOPbpdq9Jb3B`7>*M4HVO`z8;uI+vD~Rw8B&OxPyzq{J-`J-K{$ zD2?}?@73#Vq$USCKMcLloN#;4XaK8(E5@IycAT%57Hi)v<||A= z@q2URv}s#vk0kGsO_*2}0z9v3)5>Di*fz2*6j07tQh$_fgW@h7ej)f1^&DxlQlQp>`IfG_@#3 zVs%C3t!uY3DSK*sR7GHD)+tBe+i1KYYjtViG78QyPMV7>57TXY8(W(FF{S^(bnZtj zQQ2ktrRchYBF!bMWCsE zys&^Q#DY=(S8(BfjmQ7L-%1Vg&c7F7^Um1n_}3&Urjr$LNbgmIv~jjtb!~tZbhY_- z!FeE%e@NbnZ8L9;?1Lv=p9*R{+QCPi1ou4ldhs&SqIdG>pK}PZf=_d%J2=$~>1$`>i$R=FeLpFM;lerYvV@seeyED5KLPOt2X z_NUXj+tm7Tp*bB#HSZm|NthzWo{~?P@Fpw|e<@AQ#+8fX)S?*EbBmf;Ccap5p#xOQ zDY7_@;=vRfx;5->^V)r(I9dEkT*_*b!M)Ixwt8?Uw`VM&ElO&r`H;icUa{|XzXtrg znvJAiHu!3R)52-AI*rbI7B|v<7Q`l9+>=L>0Mwna92;+7c6<4R*p=SR7*CX+OjkK_ ze^u-3Sr37(Yq(mdaa5@12eVnL$J&N*eP5^8ZPx-iR`75?Sn!ZnqF2Ax>_82CAV4R@ zzlbwpW-XJ+r8ksR)0jaw$vwpRLAd)tjz^s75xRTm`C~iO$%9Qw?^dKMRpm zqS(`99xp2aC_2AI(@IFiPEf-(r_1Am~yp zyFY0njP9p91TR8wwsXl86#!enzmOf8la6Ka_Gh(TommY!>K-(=^3?Z3C zM}IOVG@8mypV>MaMb7V6%_G#femni4-vi4dzLY)QlzsU40~XMxd<~d^{q(_B#|cm9 z!>t}gp1@2;;`TK$qg@W!<5%xIIX(?)5@_po&v+nzSx-0ce+snrNM28c>1Xi3B{wGO zwm!tAX`?bIbcC~?_}X3c74{(x&Zj$-Ib<@KD93bLDh}+Y?Eo9{qWW9??Gf%p%Mvc1 zC$AWz;g?Fr8q>+tX zY?#9deckTRhv{=t;*(91ypMRwa6uHwvF2=F#}WrO7~VYhWK`fJ!#U$iUFxIj%S%jv z#U5ke?Jhz!68+%&!H+nn!)>M<2Io@qgA%qGg7qp$f9Bis$kODPK*97|?yXMKrMi)g z30(T4gCj&fXoOvC#81msvm!|k>G79bN6O-NGpx-~OSOgH>V4TLy3Og-rDaVEyGtaDDad(qUccobHk%++%FB>?MA^a=hQg1Q2G&FVyf zQ7x8tf9MjX6}Ztr5=wmatn%5BgS6dKyGiT&Ngn~$lJR2`+~>H+$!3p9zmv+y>W3|= zs?myLO+6crNjM&+PO7ZrM9MbDrG>t^s-<>-cP2dGD_cwP%Sb=YD#1mV+d~ghWzQUx zG`}W2-&7Ec9ou{97q>lK6@j8p-`Hl$UFBM`+RQFv7RG#*VarujuNPf&D>UbNW6oy4 ze@l=hbf>`2#sb~it=o-6!?SehkjY+}8QEk+-@NnWu5G`L<+MzKd;fj)0bVs1?H<`c zi!j#?wad_9Rz0LHX)1 zwE5M_nUC3W=-QyqB#WUzy3DIieS*(!Dm}wZv0U^9$T_kP-^sUT`yRXS9YwZne}8-( zLOMIKTK=h=S{e^O6~vn%L1yU`-3ro z%nbZFF`Km+TLA&5>)Sb7v;t&DevJEzjCI z`b0dvD5^s|%*&(UdV|KofFPe2|~g0Uk}dDX7k**~u?BPr@TnY$Xkh zUTk3X+RpURcIl_$r+7r3^ap&bs1bPmgO!ZZ+2|jW%X7FX&h!lIW9@8cT zEKk3BS+8_a$@?k2xG>b1XeD@BJfaR8ij-g~V>5T`L{0dk$G0y}0Oyg0YP ztl%aInfwcilhhAgVM)CvD#|-4J$x_mxk!7kRruNp3vfhOlDXxv+tsx6l)6~Nb3dC0 zz@=`86Z)KDD#^m!0>Iw5VsuPNLq!+>-~;5v0J!<8dj|NSV-|4**_i(4IS**T@>-Z< zXb_>vFn>(WZv-d7fBZ-=(8j{v3FKmF>-<|NOJ^6Los0AL3Hsf~7!kJs02#PHK8Lv> z9N+p$f}Fj(5=62D$j0U0&*q>h?%b@U77)T5A^^br4P_4gCn-wOV&9h?{k*d{7g9b% zgua7tlpo19HFE=*m^rgZ0&UG4fTmEvKA|agI?g7FNC1F4e+~e^{tYDn;}61DAX&m6f}B8ZX2w8g2+QP; z>TVtb}qj+uoIQo?{=o@0(5cx z6Hnq+hy!{GvEV&OkJkA{2O#%9ql37eiM^?rlNiX!f6U}2J_@uR4PG2UaS%O-AU#R{ z8$Gmn{~100b@ksLOeoo#{z;Ya@rG=jL;6`7#P(IbQN@z~pHW4{%mQK^e`Xeo%_)mO zNL56@L-Qwv{~5lM8PHS==mPvcU%6@kaE1v0;L`&D(%b# z0BC=Me}z~7o7jK#LaKlL{(S)dGc{@z1wPwD)X0alzRWjj9BcnGYJ8tdZgOic7}DYh zSO9?XH{4-^U*-PG)&9zDE85Si|27uuV?$ct8+?!H-@|{OCsBPD%nK=3BK#2n>xPGK z`>VWvcj@nw7;^DL9z!a&?hXK;_YJAU;a5p&f0j;WW}22}W;Xw3{z@HpIG-lhL+V%# zQpfV&Xp-Ufk7@FKG@-j%V+*9D3IlD`9X`K|{)Jn{d1Q}x0V#FEKu?g?eg7i&`ykPF z$qQnLEg|DTk7K;gei`I$|CigCbw8ic5;C6e;sOA&-*)4me@Kt-gJWf9br>Li3lrkE ze+0iZt`|QEcK;3b|K0a@^!HiMcwSqDKuQ^q*Mo0Z)bYQ@`T=C~q|v+w(xOx7f1JU; zfxssGWUgfqGf$A2lc=kc+n-FUV}|pdctOgu2!EW(x?vEd|0F{cdoUnT# zrDFi}B4;D(C&kMFZH-NVQjh@~WcMe_f6Yn7*tUC+`GPzgv@3$o+|0nweNj{I(XbG&7ZOwfn&YSSza%a0V$&e?ri5 z-=I^g{|fp)&#C{ItdKUB2Lq{EJQ8S^bzSpU$p2aRVVlDG?3{l^0|3a#q1_0m^)G;EDN}zh9VaviIyd7DX?y1HWNL)w zK&Pg=;i%02okVre9O(2|HyrNee_u|P1uYypE!B;1qLsgtqzW1UodD+sfVKX2(&7Bq zoD?cI%nirz{ol(J15JX?vvNc7-uSCoSD+ctadmGP`-guo$}ThsI#BElDfIYngpGy9 zKu18m!Qh|%Gx1QNiO@kaZ-|;_|4azY|C;DQ1w;IgM!Wc{p%I}O&;gxpe;CnlFn=+; z6Ep)l7}5=+5&l;gP@$2aG0+ifZZJ=feuVjP{2FKqbhLsS%6p8Tpg_kifEEvZ_VPx& z+uffN|J{?A|7FZj=T&YnFG+p^^CzcQ{>y-&Hb>u3awva-@@HG6p)t^VzHTt=3_pSS z&JHkW0`%sD8^SK@j|e~58mgcq3y<)d2qDO~D-i(T!VT$xfd2zfO9KR#!Jq*ew~3zt k2>}XlY>J+nEdc=kQJ0*c0Z9U5f0yT=0ZRr3fB^si0P*Ouv;Y7A delta 86155 zcmV(tKX5F_g z8ao{u9XlO#?2c_G9Xokrvt!$~ZS#$7+qQZ7?7h#e`~A+XbNAkLR;@Lw#;Enz^9(#= z&M7Yi4gvD_fdL_gAqGQ464R9f1pzt#`_caO8rlFD9L#L(Z47K2f6WaY7;KFl9BmA3 z?2Q=&oy@I_glw!$%uRn7TIoADM8=NE_6eW|eeKMW_z~&MG~U$ZFxdq&ndhP!iuBR< zBBmyx1SNbs8F;cc-tB|F&W)I}h$&3}dG~RY@$N9`>D}oA($Z%~NL`>}1UD>5Of_`^ zzo308(4zpp*Pz#QA4o5F39%XnnQI#`#X`D!SwP%j z%11uTCSy2FLL>(vLJdXy&`0b{)4LR(0cnms(B9IAYMis#7D|#W{bruaAJqpIH^?mkH0%fk3IkBL_Qx_3)aYbb zwT-)R`xmTL!+4=zWIFN64FSIA19-!higlFvaUpPz#&qxK+aSRs&gBvdGwkyJ;H3gu zJ|gC?%>xSpf5QHMo#E^MO$(&=C zw9$n?{7Ip?kHIQ#0wMGxU~`D1^m_dw&et((L&#^V)G;L=Ep_hFz7Hdjl`_jGu6f*o zx{XWS5|rMLTN~l{ms^!uw0X>XxxYG29Y_24ydw4he>n6Zrb&oPhyqlDCVzj(tI@Wp zsD8J;#3fJ8eW)@|z2pr_Qtz0C!U3T6!Tk`>Kd#TLvp83!Jx#hiJ$;Y66V700nXddds`Nq z-#Z*n7~^bv`^Mu;+OCpOQ+fF_1Hzde^i<*w3@16F19&1h;q$F@oCj#(K-f91h*;Vs ze^?h*+#@C=bfa{GI_4ypl%EQe#a6r2F772nTl)>fhKV~Q{3hNk=^-dZJ(@~2oBK&e zz&G(;sId7lFW~R`(su_g7Jk_cm_1m&#OqYQsh3PH!{blWu(){y(>3QZ)Gj0O&Kvq+ z^#-dmd}0WmZaPe-;e0Y91(Pu9AE=8w#<5iDHNo5shMcyq)CO+R=*D z8ftL}keEur9E>paq>FHydKSjUnHq*QT=}UQklVRU5$LSB*RK$#$?QiQG4n+6XbY`t z2(}eBZ>G1hOUEO_nTvUF24ScY#K}!$0;N$s!M37f#4ZNC{CA! z^k4-)4gmz8Tf`8ViFk%=Y_6}nfP0g*kw2^dc$wHvooo-8LM;U>ZTkGP$Vn%k(!c+;CjT}cf&WgCld%4~nCKfC|3|fp zVUhzfA_q=E#x=-O(V}{^Z3jYP{}RVgPNXvE=Bhdyt|fg_yjjD3e+GT03Lwap4ap_E zJQ+E9s<=9P+d~7X+TjTX_1D_LC1k5~p%v4F*c=s*6^gSyCPBl{R1 ztQ948;4oq=wF_U*QSq!TDFphfI@K&2+ zhZ2ctAS+n5tv3}4e;d(apw0aBl&8pc0xSe$S|s~u$bL!aGe(s^S%>T7W7zpLIA&ro z*M%MK%Gs)gY77!B3UX=eyF%cQWpSc+e$$^nyQ${)wW}_c*c+?ofM$FF{U@@&fsfxJ z!9YMH|N1!ov&c%@xXAxS@&DaF65}T1(0*YLW}h@|G|>U5e{~CK^6~&`#%Mqp0~U0o zA{yAD(2RBKA!q#)mU^x0Q{CL&{&F$@FtW7c4Sq>4Q*|le#F%Ht-Q<TefLy0ZPBjdU_^e$HP9=@ z8UUJG&~2(O^j95Q0XlQA1h%C2s37bd0yR7Ky>{EO{EP;?15Fx^c-K|9eu@wdJOvHr zk8Kj6orreA7(SqOaB$atX6(4?z9>+BsdXZzg7uU>e{E4Dcqsuh1Mnl88i-I> zbiJN)AgOz?r^kHyBCHPh^wGU!mW~6rd8*|OF{d68l4a2ALci@v%v4fBq>~G?{?kRT~3@=H7FJW~33uYb)^fVw~#u@%jG(6b{bPSE{n?W6+7Dk0MQYctRz-*AM9`HjLBi*-%e~`{5J!lxfLCq#0Ef5PhYe7NNkylRC ztnJQG-=Hrkl>&}eJq=f(HGJ9$Pn=mNl`cc#(x!D37$z$Gq$xQykyg54#ZBzyI#-_{ zjh|0RsH-s=5g40GJfA?{5AqXQcOnYptHZxPRG!+EJzzxU$(YaU7_QqwryN*_?@lblq=fv4sDgQF`vp5cIdU0BMBbqAd&`5tcgJC)C<+tYMi4A^1n_j1_~e}$^C zkkNd3E;7b{UFA4{J(u|sOH_@OzBrH6)1*(7MJ?&*(Hyb4&^q7m=*s(`vRUX!_d%5} z`X>_EZ#bM)9dTO&fV(u-ScuxF&FTXd&*51|?glbA;PHIni!W05oNL%3-_6le+@a&VX0agT-4oAOd^FfJ+k}`c1^w|}^#0=st8GBWA zY2w*b9K#c>d@4_t(laDFr|)^%DdtYJ2){2+^~_(I_G2=chb%?Ulw=&?7Im6=O!D14 zon$QER|>igRN#)JIHovuQ&j6-=W>=x9K$O{M&V z#GmQDr0ZtIRrc0LPf+oE5_W%f1j6WGbmKXMx`H_L;soCufWP2y*=le+jeKWjvr9N7 zoMoqXN4Z4CE#dTYe=eM~g_WHmzcOkApQ3B~%2Gb0jNSP28Id)`Jn7_*^t=kArya){0it(kSHTEtUKYHe>#*gt=OeBPG+G{l2aqd z+u=rpcT7$2R3CnnjMt-&;;(VZZQ3YeHZRAoHPF=!lHb~5iBxR=LD7v57CRq)+P@XE zC&CBVTC0CBi3KMJwTA~k%ZC;rZRv}JnxJoOlV&-3?-27HQj3nG^ZCB-^5t3aA5i;F z&0k3$v?^#^{&aE0Y!M*|rX+8z}Vf%CW zbNJzyHZ|`fDmU1Fw%=`zn^k|lcR^g^M}s#^KknS`fAkqH^BrWnDPF52d8TBC%`>_( z97v|AAzZj#aR@;F{{HJb?>$bOa-u|Hbz>SW=^Twl_-Ki;dF(Zbl4e>*MVv-y!icG8 z1~X{Oc+ z>@1nDfBG0KgwN1f-4-4B;2R^s1;(1{1{m%@4kjB+99YN3@!P@8G@Ps-TX#;RgyZw6 zvIANg+&hRbzj%dt3KbfylmHgtMN)6{x2S@m$CqCaZ@)z0f$k7&%Y%T`wBlhB@rj3?`q_=1F`YasXf4G;0cbczkfiexXPK$8hW9r?ZgiX|UMUVRVw|_8i z96iJM8WMS5;s42ftbcD=J~#--J@o&dA~P~}Ha9eOU=Y&>7~AR_{j0`Rky1j_K>xHR ze`JBh3KW+YKo9gK6V^oeZkRGo6(R~WjL6GLmpX!@&*h%m__aKhopNEdK5kOR$YGdx zu==$<`=zImgXpFR$=02_l z^Wh{=Z1x%(S5#)~z7C;R*q+T#RG3AWe>1HICkW9)#3gw&s#DLSXy?@U#Jx$MTajT@ zWiF=5Tc%>Tj_Qz3jteP}7^h)C4q1q~`rW5I1hrGmF?+y82UYf_Hb-cJJAVfRNUW

kORDg#cNd}V?ACy76=Cv)pNO~v`w$bpX-LXt1nF-z#hW%4qvsj}oGf##SK$kR zROj6Qi&Kf9tbP}n`1-OCFMR%->^8bEVZ!Rx^OOK-dz}?>jyQ29mb3yn*Cya}miQ%1 zO!-bKMS-0p5IHz%4x#odZJLe_f7V5^%I(u}f;L(|svbL+Pm^!`G1a3OHF4c73cf{L zrZgeEFTYlj@{w1@B5JRtKem@jge}|>fv&i2%>F$>7e*@~t4#0`Z>HKdqO_odc)r~3 zt+sHw93KsC!Sh~LLw||W9uEEu+YNnOM9LK-m`u(KATD;6R&l{JV)RqFe}So8yaW2K zh`gAF7Jjys9#b-)|F(%(vc8XL;R+X9Th%Y(lht0&g{gs(lu*W({o=F{QN1&hsT0LTS(*#6>yC#TG~< z-DCjyvBxLU>o)KiE+qnIxtRr;k^J_wiBi z1@JUu1ZnH;2`M?1?i+)xlDpl@uiI2{ypUjRiRy#mM}iQ$32j}ta|e>dMrV#K?G>PvXT#)aKcE( z5;J*LzR~eo`BoH*%SBu|#!vv-)*^~dtXB)n{b4{80%Al^f732EST;P0Jc>DwPBm1g z5q;;kOh2C9kKT_q+%9=P9B&~06l!)xG2#A*;0DI7%Tt^oa9A^Eg&Un`ob_i`5J)V0 z#M^OWY1kmH;n3F3@FDv_bqgSZ;WjMbVv0_QZA{+g2#AkzuasdR&$eY$y8A+zKh(0S z_88GNn2epWe|}iH|5zJ8cl8xD0mf~tc6tjj%%MS2L_&!zRmGp9`<9NM#%(kOww{3f zOesIe`J4o#H&twmzSH@xjKina_uY{AQaDE>`l;KvEQ#JeK0XeAY7;R=cbZ5z7qyGz zsF)<~>cDC0j=JaefH}`6I$~sn^pHG4cz8590dk^#f3~XY!B*nj7hRO+uPqKzSslH| zcw>**#YPo^VHpMnrMZqutg&QI(9div>d?m3&HBe?`EEF`7cM(j%-^8;sK3cqIJu4x$ z=!UrJonE6M7Ttr{p$z27>Y}|>4YTDSp;VaMh)I+=uP@n=A*>8I+uswaE4_dr4bmZ4 zbG2@otHQo;DBdfuqMaaJQQ$O+PTuO)&Ozcfe_N>^=_PK?7UkqHGo`+2>meVq+3v>U zJU;;Yz^71rtg=Vvrt<~8?9iA!GTV5%N810rBvH>ztXJ<*F`s!tfR1fYO%)1#3rtm9 z+yL`fR-iS`f3FcpbL0Kxe>G*AG6tjFt1WI%r^iOQ&5V~+F+O##!}DzIor&vYFy9vJBycFuO9?OuL{^ zqCKm48bbZ}P{utTw8n@^iUqztNQzTzf2`D!p^WTgcB8U4{CSW|VO! zos)#zsENFkfsJEf?XpQ>Iv2Ku53UC*x59-;RyDJs37M8*T$5RzqIOLD$uU#I@D53Q zZq5Ly#^y1}LIa5Xz{aTs}ITTga&Wmq75Wr(&E+1tACHs>?^6352~xYrjPzvH5iik*_G9Y z(6+bvM|hGZ zMjg8%k^=vNDv&FFR^iwmU?|ic50a^Tz}E3ZT_s@lG4}NJ7NLdWpOfdA3=Vl1k$#5&DN-85aV(uGs2z{fFpbUb6x$bX9WbP~ ze}S29;tM!sLatgU)U#E$T|Ttt^SZ zj#UvvXD)3ZZ1}*xfAcYTZTkB|q^Uxa#I& zUqKwW%F#U71$HTvcI%dI6;4Mhoqm@;jfd+jo#!u^FGhD4D)kXBbwPiHD*V(hEuQDko4-;!woH5#OMF$MzSl4OWGeh@g!2+Ff90>7*DalfPJGoGQ@NDX zko!|GW6RLMrwiJpp4|Q zn@^&1;)-Ece=~ZP{NXVzjbw92L0_WtCo!O zx5z)gX3u!+{m81>9sT>+UH6S7Hq9Uq<9vEZizRL;NR0x*o^!+|6ZR)WmtnAOh@&$| zN09IuMFA+^Z-!gr-b;uP6#9pF>NMiMv!6z^k?`%rf8LS5NaSypFzjMRYr7(3b44@> z9kgB)_>aN!MX^moHo&S)i$=}r9~Xls77Dpxyx8RJ+J=zGD#W_`!EGp|lq~4Qu|X;| z!c>k8L*77oD(og-8~2?_d|;F{Z4J8I6fC`Zw?5?CpA{c0GK^O0CTn%mHfPZ^e`;HQ zRIb08f3`kk+n@Q6(gUPhRs1O%b9k)NFlQ|qxum_J{wYrmfdikDf9Fv)C=d|t|Drtk zm(iq9c}*5g0sVKdPEZo{G}r-!-=AqrqmCRiNmqG)rgGi*b&hf!Ea6 z;9buKB)DFTeCf|pr+meb2Iep`!C79Z^^ZE1e=d*j&kqlHf82ON@)3y<^$AdfaoSv- z3E64ZH<@)3oC9zeg|X<@;F7QfQ_tNIE<(&h&W`^~+AcYk1$AGz%Z|X(&9Q6mKu4Xp z_EClNj-hwm1gHg$jnVFImlD9(#Hafao4hda?!4uVGb+mSTKcLmu~|0Zs7C?l*fTn; zf0j%0;WrRgt2kWG&({#FgbtOs+>Q8z-Ef{x#K$-UZ_?I$K@lvlXPF{s5r9~Z#4s)! zqo6?LqG=vq&qq&5pi0ob#%u1LGDPzpc5h0QCAR6b)WbSg^?U&CCe(>eW0Mu(JkKaP z!)&K|OuU!Y9!8yt(1co~Q@Y22m#nN|f7MGLC+15b4^aKEuhwJf9n+b zSQ7r4KseLX2#Q{Wb8h4!cSM4=5~H;Ie2~QJ3<-62vHsks=&>xs5_MMIFeUAcf9sT9 zYpS7H>ogPUt@vpE6F4t|e%d6l@QJj1xom%lD`n!@uQ*kPKm=ZiC3xa+{G1N1T%6m& zN>d6s>d814a0f?868_Tgek_O9e`s++{g4Q@JID{fb5yJxHg5o?cW{jXWi@_Qx4ol# zA^XyM#C?W@L@Z2BbVxyMgtt{p$WPb-C0G&c76}NOSpM*9Jj9D`a+f+>YuYi_ax(ox zrp*|WKh!TMy9ut<4N|BIiTJ9KXLq42xN}2I(EbmtX&K zpduSqIG79y0%HHyC;ER*6MJ)KV*`DMznNlaW9?{fV`XJ*@4z7ZKixwAkK^AnW+8q; zc1-|Xv|CCD!CWw&tpOJDHCVYmr#@6!1%t|hj*KjigrxS*LVuS`1ioB~U0-|cHs~vf zS9sV>NtonH!1-xl^vB3if7H;^>(N!Z76`rPb&arDum#z;ZH0=iv7K3eicFDUp@uM5 zmc1@68;P=ckxE<*8_DqAB;B<oHyRf3N6%&*H3|igFT) zhQrOf$rG{(0<|1#_>6j0%G0z5cEVBf3YHzcPYWa~wPxn+aYR9zaeS1l=XPJ2iI0YD z=oetQ#ptRGTJABlFMRSBL}6CiaSYO4|K|J`PLQwbwXkcrb#N!jd`$X>@T#MA6a6LT z#uI*-Y540jq zI-)pST!=@yv5^y|x$%}yUW#rom_3~lAe8T96L|;j&+{E~f5B*Dtns_fll2zPb<>&7 zs^dS7Ht|t!(`53j20yQL90JN4TwwjB-U>;qXKFRl5UAoQXY&mqOFu)R=oNo+8WjwZ z$0#?Qe}vGumMROe_Cq>XQIH^BfGKd^ok)-Z+0y0jj%1~Z=C_58z{T~_gD$w7x4nIz z-(+}pVY~(*o~}wH@|>F=k{(^<28WN@N6|ml5nE@f%&y*fj^T)cqDK$b$fp&wyNp}c z$>U9?GRA5Aly|!%t*ZKyB!$5XoVr=O1#*r)e4Ai# ztbrlT6G-fF;PI*5I3OyNW+BuoT{weR-MqfoGB%2t~- z(RQyzMq-yAYer|GBN-WcDW`LG=+SWVbMw@5O;IBV{AN)&O6K7>-99hQSmVyjr!7%v zf5((+mFq}F^uS@tIX6S9eCDr&plJ92DPevN?$a26mNN+DPHF!h7`;TZ9*Z&MU0@M$ z{1^OOQL5$YqS1a(dec~M@xEd%pS6xcNTXeRVppQGu8lHOJ6=(Y8b23dzxXi0OVloQEMy8@NJejIl;6qLWr%B}e zb$7d9i_-hEh?b1+%Ukk7+zJ zAE3XkmB4H&n_+n{)N7Yv|;{Q>qw#He1xpj>Qzho9K$3($Pz5p zSeE4NvH`DxzkE_X=?^3q%N>{os4un7^y&Us1j8EFONQbFW^rU$lVF#l$`~|74F%m* z=KDAME~KLu4_{p$u|K*!e~wmABt@O@fN6(#{@!hbvRCL%#j0SP_uGk=+vLIDLI65f z#E05+7^FedX;(zN#155_2}x@;`|>!vj#E;570zb_A1(Qjt;XxwUTY{jm4B*ikWon{dB>TZB zHyM2S=Y33ow}~n5!ck8Q$8kO|YS*n}TfnE+x2vCNRxsSpfB8={SIxyYGk+J9@!tq8 z?7$76EjP~MW}UQ|9h26zh^IuQDSVf7X$zrl?!LmT8uf_uw${o)cb<6a-VBO}NG-r= zHN@(OyCM4G&2`dZ`Ap+h$kjG^qfVr2s$yVVm(*WI#}fA4JN@dvxeFdpZIeno z*t7_E7vjqkx!e5#C%G<5x0+2+v)*R6J7>NOo$tDbe=8&DP1Y59kjcQ$=0-9Zpu)A8F0f1T>b@(f*_+5X8VO~esNKHak zn`8@!gb}Owib5V8=Pf-Vmd<{SCW%Ym9hR+Ff0p-gWE-f+dV#oSnqU#)1hbd0@6==e zl5LPA@p<)L{etwP738atl`5uMf|*q$s%T^q^6*uJ`Gu}3_Kg4L@>(rRtB|#2ud0{8 z1@W@Q(st;#|5m%@bz3`B@;WQF!{WAx3nI;pL*gKoawald?ho{isL-+L4z=xvjzB~5 zf1_|5-Ad+>V7N}Lnmw$tx8&zUNkt^@NOs%Cc2JvLfVL?&@X=)h@#|maRi;^B|HWU+ z;jb7M`|qeRB^P7+|6Pd}%Gb&Q8IirLXCVZ0F;KtvKq0v5gA?b9OQR5kwXI!-wn;i9 zUIbkk2pVjIKT|1F5 z?@AD}aad%GRaQcBYmF376^;anb77HXN24oIUt#9znhf%)9=cr^R3;rxL4<&(f4dbQ zpi?r)WbBY$8)~f~3knixJTG*R+7+^m9d=Gg%7cMlen|dzA7}gyAJc zP|RfPTODw!zBy1nP3BOXBwc!>e^=F3Zv0&+K*^h!Hl))p-!?z-K1$`b91fWgw*AKD zhK5>?vOFf=I=9@rfRyJLW~ca8Vpg%i8@_1Yz4U#_74&z7^~6FQ6b?^`l;v{C4$lA zN5Hz?59{y$!)Myi2qvb%f2_;3#AC3?Yo0VSBCs6`4!wC0F!z^nYTKs=wwbV5mU74W zTn)Vmr$SpH>B|#cR zk=?XCsrbwLMI9R?Yu%@+e8pb5+mITrcv-0UE9Pnm6}Xnh)K&AAe_Ltq2FHyrlpV>E z+3K6(qnuyCA>FH^BALCDs@Qm@><>Dynt2U5jLBK7FwIizhN@052&&FnK&=GLA)DZ= za`e+=NHd-5CV;9AT*;EG+1QP<69{Q2+^G)6JwbgFO+zYVNikZ@Bj~F?I_UR(fQnA?5mXDY18bMZf55bCf&g^7G*4$7MDdh8 zn!93M_k(9n_`=^U@o57z`OGqo8|x2`e+9k#NcGR^>5^|*vx}cWSu@@(=tMYipNXx| z*rz-r+lXURoM~XPro`|)_M|%;&}RgTKF03J=>ca4FVFe*(_I~Im%!tjv!lFkuyvR| zC=F&0-nA&Af0z?bgct;uO>`HJl9~GC9V5&J3DA}Y1RRJfO#sViUS<;4J~SK!r)-kx zFWSd8o1ldm7QFY1jH#@5(GFoqVrQ|uP=Fr8Vyg8Auwv=PNe@L9p{b2oOLejW)ZDKxpR8Ja5FN_0+Y+)w+O zTwQZbilH4{hv$3MU{l8&^pKDyyTT@urcR!+MKYx)uD2g|TwOVvyxjE7UJ^seT5s)abZ)#vQ*IIoX4mu*R4 zbF6IAA99lG<>mQe7A0BaWk)we8iZJ%u5`(Ow}x5KxV6gVU(1BRD8Fo)Tl`#Kt~nr# zqyI)L(kxVbk5@&%^)XU+ULpf**y5OJ{or~)jKXwjJ+lsJ>#6+;ZZtBat(}(84^n)~}JL}S< zlxAPxx^u_%onW7Xt&L!2n%Hyfu3n#=e^-s_YWpoiJaTmS;0oqptyC}WXg0n{yYPf75jKbUxRW{6~}di^TSW`{o$+7>CJL7kg%twiCxNAtR%M&CE4BTXHjH2X>cQ%EGmrZ`2y99>Ug3yxES1e+C%Q zAI+Cwq$tUK0vxa{c~|Bdr5Z8UGH3yUrl>@N2-Q zcd(6IUc%QO50WEd5@WP!l0r0feDh2JnS#p4D2e%QKMXXpFlCvXgN#0psBW3*=XQMK zef3aog@Ln4#R{@|ii%#EjDw{^e;(#8_*S{70#U)ptRZ;eIBA{xR3k4688st&Rw#NA zgv;GyYZm#n#C=9!PHE5od?hp#m`er&ru0I}#|i=q9LZf}$XI-@BgQo!c!d}B-KqLI zD@E)r;Os3DE&_2S&ZIcwsh$q3RIdbD6>Xt-b9lP5juisSj?`XCz>e&Ee`(1C8M4XY ze96}Kmu5)QM@*X|X8%-XtWB=G z&4d8%m%gnBL&K?B6@0_Gf8ibQkn(-P^!(0%c7-~GK~=d{sjnnpcX8YLsAxLUNMnz3 z)4SMocbw6`+1j)bI z`!^YbkZSrvNFMhj|19c=VQlG4dI+g37o<5eezc}$an*E&vp7v!Rl8ezU+4CWxU9%= z6c+EZdldt;feGkt88IT9FugC)XwSVJ(`QVf4bYr7ETpCKZA6su&ijTrII zqvmGDQ+XBlkX9+MgZAC3;xQsrGcIu6&-t(Klc&F5?MmpbWjBlsl1^l zsCTE2e?Bv^s`3KRNW=iygz)1_Ocy*+HGcdxlT+mJmk#3j&B(orrp$UwK~4krq@#{b zB@wxZT^a=JI&K7OTdpcJH!2oo1`kfg2L|s_JBJrg?CCvkEFKxd_C7voZZm|75!(V# zc9-i;QxmzlG}#tiQ_c_N@%pXi3-X_URuhM-e-?p*fH1;|DI@dVCL4)KU{I1diRT0e0I*IW6sgD% z?W`zSTbx7A{{%xv=TVi0ks6b60@-;$zWiMXOW+&8!RJi9(Setdn%Z$YBMbhjrdO@) zf2L|4SGqo5kCcCmS>i*8Xh@4lq5=W{bG$Uq&C$FrQ;1e`4ES2!+i6v%7>~Sf{i{Dc z#~2{8^u4Xzy!FR6YTDlhn=bI%o6r(ccj*%<(bgL7dtltV0s_8!i>t^Mm57s&6KmM8 zaC0Xbw9@Mrvz<54W=N_qjh60`AbR{Lf0VpZil#K8pje;de2 z$MSfoZX&QgHat39I=mMaQ0oJWQS2ftDHmZqWq~i=l0>ll`xLjUn|XU0e9HNo8q`l) z5R@+!3^j!ueT_x}ZuR_6fH5FO&g- z`GziGC6Ck}r~B?fHZp(C&CD97WdodP8d9ex>qOG7oCMN$v;uAYb}M$E$U20~vgr6r z`3}7Y;E|ZV(1>Br{6;LZQTd|{hIJ`;&t(cpU!YxIh)Kqyd3v{Un%zeQVU25LgA+IL zcPR2gm`Ht$ANh1frar(zm9m{2615?UAx$Snbw;UHp-{t6C3 z&xJ%20wHxAjB+?j|88g?5VCF2XViIKCR@PR^qpUB^qosO}w~M#pY7moaVKHc6 z8y4HSnW*jSVl4W=i4KS&oazb{_M|fMAk9L8&O_z;h|mg)q|zkIgEFNbr4zIi z(vB#->VVSQx^qUW4htkdU&4Jy$JAqyEaHn7{T`gxFjeEF4Hv)`V$((A>yHtMwO~uG zR~dwDE}^IIf4?}**g~AQ9@0H8Sb+G+_|8HudLq-~95rXkW{5MM z-WS(hCO^3EE^>8=@PV-DvwO6Hc33}TG87pR4lR&vQ}L+?Pg3;NKarFXTJN;O=NwC3 zj}7zbzm-LU3b2)1RpnGsh|KOs>nAw6jNlQMdk+#vL?82sOhMmbU(T$i_HV{{gFI=y z;y9AEe~V^CW^bQTr_8#%7c$IRd@A?$xuO=2{VFeGM2sX9_@0f;HMrf&KkFn-<;Ww> z63;30I|(x+P#J79{S&OIlt9pdO(}RfGyEM#TE8x_X?*GFpXJi8~cC>esw=r_~{|NoSUV(oLeLNTpf-Ya=L4TtWqkvNw3&FNaF1X)P zt5N+nx!$P0!XctSOa6qLbxriZ=h4Oy-qxr0Db8*WcbjgnuX_vu!f4|LCaV-{p}XcM zf1c)3sH781k98#NxrY|jy9zHIR?kaIU(=NK^}9w4m)<(d!L)<()+97K*id%d$|Or` zf9TD0*5*UXUSuT{F>WE7jo(yBNpM=PqIOP&HJ^@_l^y*x8Wsu{I0`(uB-CLp*%(tc z^yrHs#yg#Pf+EoVJet%ASqx_g3_48+e`3Gjelv3^JCaTyvjdiP=98?d8Vt|z(f}Mz zmD(FSCIYKE+KDs8dEb|?xqRT0GEMydJR!D^j8)?l)gR?y0f0}Ylk~^FrkoF{cNoHc zj6R|RP6*5mQ<_m2<4pI)45FA0i4ePR4>a)tip#_pKx`CVcpT3lwH58NHc?Mgeqy)r8jWwd0JgGq4-;j8rnxp)mL;)5+kRTmZzdk8`Dh}8sG03P7tlb@-X;+|@l(|e zCch#vF6#91>6;AJi;}l?AFuqCB!FI22>J%Vox;Ze_I|vuHr_Az7d_Xvr@r_BFC4d^ zfiIB3X$RQVcXWapomU2lJMi6Nf6y2ixV1zS_Cx?RK+3-!yR>M707n-yHfdF!QR0N? zV;+%H@Coe8*=54l&A6`bPb6N1fSs~96GO^lPDr%ZCjNU3+=XnKeMZdJle}pvX6avf zSTRF`(9uk`*U`2(dtd}lLKDKtBtK*!;)LiRuA+QE*Al)FpQP6c4Zn(fLQpWF1b<@W z)#Og0Cw37N>>Z*M*xJ)#%I>4B^ZD6d)5@5JyhWuw5#mTvitykP1~|hZ0V|o^zw5hu zZ~sdh;NlEDe*0@@z=41${$EN5MPt*y68wK@?@E>5E@&#~8*_(-aq9)mx#(Kq1B#61 zwbbem=B0=dl7@2yMzaFKF!7F5;D09tCUIe5$Km|HzI<)?hKc%S3&XK=J)bC_(L9~p zE+_s3)_F?SsX9OL9c5K#wcZW!^M66O|$=Cf4*4{Bz*yqU>-L`Gpwr$(C?fq`sw(WP@wr$(C&Tr=Y&rN2MJ2!LBeCbXl z&xa?~-K$owbX5_>Odtp-2omH_nk#2mvDFalE(Sjm!5TwEu^_U`aw;$V4e4TlWpFTr z>Lja4rm?jcKr-d1e^scAr+-I<<}~CQW1yLwL4~?pR&t{yURuQv3+8et$s8|(I+tnC zk~?85zIF{|w5+;n?e1rwv+1W^ehy5fZBOYQXCOSDfPNquWYoNqYF3ysdr+yf_KYGt z8KE?H3Q=iML3}_NY{E9L`(hi6PFB~8H^-EN;%sVB(=DTtUSF!5+kZ7|!YXD~H0jXN z&|6_5HS|c^k7iNPW9k}psLf*cY_BXyY&TIHgN8XhzM``^QmY!4VWM4n#Y~M?*~?2d zo<~8ceQ|>ilpwqoPb3U71>Nx~vc!Z6HM-xj^;MT=aj~XWEZ=6kuzk=KT#19nP)jI+ zeVZjTc5SJc(CwaQgnwd3&5ph1%&|Ia;q4Wl+n`{Ko3FR5c=p<^zaC#-*JS*= zqlPt0b=D~zupHtwxE=eGF5!JxBCB;~dmwtjSo4 z6nZ`C3tEAvB7dyQUuABY%H|THCnYRRe83Bc5UP7bhv(q9HjIcqs)OV1I52EXH=>j6 z<~TB(L^sp!F*58-mx~@=?!gY^qoSid|MuFwXFpGW=~WPcYkygW9pEP#jQTW4%u`xAif3$l zaYsx6pF0{Jk6KTuhE3>VQf>G*A{>9xZ%Dte$gk;$G7EfocyHykCK`6@bY6d6{oH+T zl?o4>u;#!OVV;T)JVGejq4yvEk<;N?8_i+zwoTsZ zEn-y>{Lhe$D7}kU9Sb<|#}^>`E16n9;C$q&NU z``X9yBlY$?_icFTA4GLefd}G5{X;;!kf3(xNTs*Elt{T-8 zyhiNwz}UueLrhm217t8??zV`!h7fy;n4Th0FOj&>Tb4_H$^reRH~&GUE(HG{OXo)}GVR$oDc>3{4~ zUfu~?b#JaWQa*Ydhz8&Ys*LAE;Mg&|egPu&swC;)+c%L?T481%($=cz;0Hsb1FTRa z?A`bO267Sb`L7MhMl-n3NXd&y!wA1uO}SRBL_`aMVyP|KBD*uxR-#}-VCo&$u&qYm z=;Gw+J!7jB_9Q-uv@cgj86>UhMt?5VHCQ!oinSbZZ`IrjP|b^QUf-80v{Qd1N4=1= z-&9WM#);SbanRbSRCK20vQs)@|MiI+e(BI7!WLV$2aWY0Oxc~chGd=q32MLbBnt2R zCk~ils%`Ft?z|4nKH#uU1AJ2`O%h)S0e=@=IMomxXAj51x&+Dr<8E zx`r_(pNsQjhD8G6%MV-AB7fqE8NL4iVP*`RuV-xKc|iV;8@i-PI^q)^0Dy=J06_A8 zW<&prHgj4VXsdhfHXKW|#MutJWsB#mL~M(sCXIPESssuy+epS>tvivtFM|v4uf?u!YW1C*$h4hb5)PK8za%rrufdTj2 zZdFxTzjMiQ72v;aJ?1=iL1?kr+&6UA(GNABX!eR zvt=Wupn$|FFE(?mDoB-~DmSjIBsb&vph@W{G;_k!S^+FY zMHxeJ9$i`d$hVPb+Lwe?)s;+tgi%l6Xn8azLW4u8Iz5!knenHJlLfhcKbk*BA<4;2 zMhbOEiaLzd$h61Dls3$@K3DKM1Ch1t2$eO42B^siH_WYpNq=95@a!4Kj({Q$)*O{H zM(7+mi^FCGB4(VDwczL!a$|U3EG8VYBPB>$z>0BZ?#9vCu7Sc-&!s?*Ec8xzM>HQ7s_J+%cgy=f2^C$`@aY}#F_j6_~b zkr(*UlYcW?HW320z<>trVf1^jCm%g#3rnj9y8F&7d~=@`ha}x-PmhoY+LQD+V%q#j zkTs_8NaWpGWZsBs{=uwqfhXv>HXk+a#uzyHUJ{N;#`rC7hRTymLZ{ytc-y#%Wl}JJ zn{lZuKRNB4}WQ+0j|kjG45X+r$5-*sWw;?GV)1| zHf4=UVnqwMf7j;4RpcBwV9gbbR2wbgCKC@M-`pKNsJmd{^DsH_B`T1ll&>$~mJDJ2 zxx@7TxHC9pJ}tCXmuvp9=t&yv+`}u50F{!JFd1`I@m5dVPvhtU_rrWOp1XuuX$PXd z^?#=id+q;JG?#p=m=4J;5Bc0vzjojcgYTQ)42rNnOC6UL&S&tJQ&>9*gB1S z2RHV^xBXxUi%Vyd)w27*2m`lN&T6sbkbmhcly3QA3)?NAt!k$2FPQf*aarTO$thmm zJ-+j9(n7xX_62%ygv%q4puJxxK=cS6#P2JDz{P;YMKk~#Orh0ty~D_E9R!7o8w4Wz z10kZQFM_2&L$WmGg zg_d`6hv@-!sHP&v8%2!DrvkKeEV3uh>7xe0Xo(bv_LDt$YEdwMiVqF*`g3nZTw?Lo z$s>iOChIA7w8*2>lNjU&FYFeY!PJdK0#YBmt{?vDE)VAi+Aq9jcmip5Y#U z2iAZ=WO@4BA>DlXL-;XF2EfbVUC6$S;mZK-!O2ZLI_X)7jf|F&c8$}7S0_rwN@@k| za81YNs7vGekRcy;(ain~5GMm=i!R$n?)f|zh|=^GtsQ#5eEubul)kxra=PQxN>c68 zX#J7VSn&xhz8aar7JpUJ_M*xj8{UN&C+C<$H6zrVQl$n2vMETN7i)ju=IS_D%UFU| z5u$tE_nrgy$7T(#@5eo9+KUPE^qFi0%E;tkBr&%qs-QB8Es7OIo=R<@)>Ub&VjA`1 z`O)5Ul=S+U3#DVBPNtAj_F5iho>PfB>M^qj)Sz0$L1P zzB2{|&#H?Bn1Zj(hEZkoDSqLF)jf_>Np^>4D=ULu=kw`dK3C7s>{mu}(A(1Oszx@0%^XR2+EP4G>h_LkflzM zF`AnNpOZ(k2QR0@a>4SDm61iWZ_Vj!D141n8p@*ZN+n4Sb~Bs3devG4q}b>mC}XRd zEg+%FfSp@^`BZh|c^KpS!WU4uDmKTP?SV6f0QZw)rrqVHG4)M{;J0ClPaMYvC|f%}kXT zEx?G@ue74NirAAJ>kw6$u-L=tPMZ(Hp|5PkmS@jYtj7ujD3usv>ASl|&rUc^2%L?~ z!ImyMxqmT`9y35*!8lutHs_Q}7@ZefQTUR$Cik#Dlvtiq=vw7W-m=r8fx@#Ha_fe` zN&)j-1{`Xme%lg_nEC1y#a$Y7V{AU(gZXY%$FW}&Nk?Pf2{qzjXj2>L557~EzPB3k zYL7;9ZvN4T{>c#by0QiNzAAYSEB$MNy4}y!qnqajc z$=DKNyDVwDI$UlCmnO|p0Yta>2eAW&kzKL$|h17M*%y zUMOG9wZ3`YE586IS-D9kv`;j}uO?>OPeR9D?s#IxYn0Py>!1@JrH&I+E9+qIOrPYA zctdx3mn^x%79^ZSNUs;{+A-MCCHG1CCYsp#NYwR7^d;3k%V(XqZmHn%_d411Kz}wZ z<7R^Ey2wk76;*V{?7aV!k+;W!XxAj(o{48|$SvP7{L6d~Gv`Zk%XZKaIU?3gV84@P zKP(ESHI2~*1x9a3>ygyt#k7B^29Yt{jw#*F2yZEtDrp1{IJ7np%eyN>4N~U01GMcG z$>;7G{txah-QJTh3oo?W=4ii~FMk4{`Sc&*Yx4rXL(PrvdFX4SuQ^a#ztnnsrf^=7 z#ju$3L3FgeEzks(;weI!902{%#0R7vUu4t|v@4Or+n_YY1bsmIR9=1`bmDJSjKJG| z5FdQqC#w#9Q7VK5+g4&9Pynk;DS|RzF ztCtZmmN7iHBs(vll4Bnq94gCG|K3So_tAQvPGX^W;n zwv-{WbdD_FD4C30Y|LPtnt!Nonyk^x*jwXPdv?|Iugu&$Q#cNYz(e0qN69xU3%95P^ttHKErusiBt4j8-h$nv%AG z(&8c8>#)|$e6~klE_KM~e_1(N+R*ouwQu!<`TNt%JI_mKtQkP85P#bO{XScIdN#jRtc&`&&nSb)NrGUz;T(DO!&w}lN5?b@$_yDr5)3P*hW@S?3_)OJJ`nKYs z;Uz!b&O-A0E^mLaB0~RmLF|g$O@h5`g0+#DVZW!r7NieS96;#I#ty)tv4%vBB1{ef z-J$ZT+_hMf6(*^?zHrX^21?3rhdpZAV(y zB&n(vcyY_QLPT2_?@?vf!B6~lcb^q~i$gL6`DPFBYXWh}5a6c_@RBk&U`~;Ik&C`| z??-ckzcRjMgIq9&SQrhRnKb;cq5llhXFBQ2i0PVs z{ScpB#C8MBC#dulyQYyl-Jst*(&u#Qn)W}REhBN;Wq{}X9ScgMdEBE-eVf(V>$QoX zZ=l58jdIu5(*8v0Vx#0C&!+FHAJdv_yii4MZw6~0iag@FMa4rbZ6J6hhIV30Md>tQ zqaDGdX@3yFrB_Bcl#{7N=EN|pz{xT`$5GYA;+T1@`^Ef^3Im9Y;-}}oCDg(K0BHW-Dh&U65k&H@`QOWx z|38X@n(aR^9mS8%elwV~SYxiGrztRzCPc+1N`Jx@nuc--B|Z(HMvFa5`Y+4X!A@I=M3j8=j+z@M#YQ;O(2IH z^_kK=)C>bnj|!V~Ko5N~vgyVVov?d>-hT>=at2sDducxTQ8k}Z0C!e41VORq=;5Fj z%C?8>(i;sbOTncV6SW0L-GOUY|D0v2ZrUavrgqQq8cfhHk~wTg@e?g7I*6KhZko>_ zXX2WtwrJf}f`+D^lg#99#2#)}RldF`kYs2H*xdrVX%^gkoi-h+)=5F}DVo{{x_?Wk z4RLziJ%KX5f}`XS!nc(^{gN=1l2W&`#CL9_Vb`ofCb$Olmb26`fleuOR25Y%WK^u{ zXi4epY)zf_7CJY6IYtV%oZgCo`S8T&Fa=6Y*DOK%A;>tQ7)-~&8;0s067A=(P#Nmj z=*Z6Wl8xiwOhc{&n{ak4tjE!lgYtVeM20(ja<}gG>=GzhrD=;d6Pm2qRCebrT_z{e z1s7ACMG8~cRisOW^#gR;i=|`ag4}{`4bMRsJZfGpSI-{X44;*?nFQ}JM^_OoQ&q%zuh zr_)PtMv{ri{Fya2_v0w=vXN-jyaW$cRw$a#s$Xg*o#OF1kWfyMv*8#$9RfZVPiarW zw{saYmAo1NzZJmpNgP{hE`wi?H7JC zNin|*JC;p+#Q*H#3xAF{K#09+L$t^!6b5%2W@Gt+zd8`>=`seWLLa7TVq%vv*vl6Q~(OXWuBjvR3HvR zR|O8#G%jU|R=0}&{HIKtb6-icpnq&KXaE4I{~^5l7r?3h%70;tBmAJjjLfWq1VREX zq$abpygLeHq6r}Z@!?1SDjUn>^PjEjO$D?!-pmMk{`pxfv#d&2sYwPO6IRX9#UCL+ z*-xEVh;cVJKgqH;Gw1*MKJ^CBFGLZ6*80Aqv=HVVoCf}Gu1$4mEH8Be=ecES;%Af@ z^c|VQiZKN~6MyK7%MZj>z+ih=Nw~O5v!ym~7u!*s+;XhxGIee?z^?O@b8jo^XvyV2 zYANceM~hYx)MuaiYnpCX+QNS|9s)(#K8-+`%U=em-qhRnkTjezF}^In z4e45^@JfvlZ*|T(DXq5SunXbZtKeU_r|ctk!8^&faxG+KKfA9YSsFq7isD1pv~NPy z&6>C3raXQ$VkCyKqkb2{(gcOHkwsgycLQBi9+=J|Wm&O2EaTjPZC>I0P%*i_H;MS1@BeTY{+abb8?7 zqBQ(IC9qBuK~lEomYSGc^Gvh z_kVC9-`GV9;mS_w>^6J(*|>E8vo!6EUV4AluXN#4pMvf}jB-^=3F{1JsCH9IzMvJh z>CHt+vFR!0`FNF^jjs~J+pG0!uwh}l7%J;I#VVpJv}A|!c1^lgR#P#9e-0V?ek3{JXA`1Zzq8XI>z3TXh}?hPPVSX zTeccMG3p!;yy4w|Vey>-eNlX~DD9_eNLc*{rkGm|GM&VuWC!BBu zKA?j9Fh4|?LiEA2L5iEXqw7(3m%>&wnB7BgfuB#rPLPm&@@mg`m3FX=1AE3dYkyvm z&aE!$ZHi{#Tx_s!rNf@65#cnf)A-luQC{QS+i?A+?p=e+s?8b6ntI;UAs}WH4wt}) zOb?V_=*7)_hc{e2Xd!HM-&3_9bCZ|J%8@q8k_1h3wwO zCvX&$d^6O=o^kmprR&7OcvmeeSy%3OC1v4x{S&ROnJq8s4W(QR1b=p9AlMrwR&%xG zLo~06Mn?@cX6Vb>!MwZ!@wBaS*%@RXchSO%6{vME?QgPivHq+{O^#5rT7O4KrCh;A z{vKa}RlMH;kEulmFEI-sXqE%Nux=m{W3{}@2Fzz#c%_OQcoNeBCgvV66dnqgbx1!3 zzhzW^7>W&IP)|~6LVrUEHse=)AlkVO+^nphNWU8hW^%#~u`uu9eeTVCzhS6@XM3dc zG@HysDm-D6=Y4sg+m(TauT+lOASEj^BA!fkp(G3|_;a)!zL^H9O^o+^f4#dY^lJff zXV+Sd0sIS76Ri^mnJTlV8fodO;m0zi6JI}Nss)1@j6-m0Vt+^i6eJqRIKdwFk&Fi7-*7+PQug4$|=9u=g=cvIuDxTN!~8!!isbD?6;JjQ*Ed!&Lr41^oNKYXnA=LFd$VE0f z?!^@!9~1uq6Ym!L?4|^}&Y>Bm+_F6%G)pF?(1Z5aoYFZ>UC)L>CpI=AP*MGoyZ!*z zKtmg*&(v{R2c@>5REWZE6*cWeM|Lr#+6t?+IyDxqV}1=DIy^oncv>!MZodR!3Zaf-v;4 z2hR=82_n5A4ubZye5F{>wEQk_5^}c|DSsy{&+=3p@>($`@`y(%yTCTBaao}KpLx<>>r;4f&lqHGbStcD)eoFkC3t|(3YYYfv z)Q*ce*ytTdzDpo=?maCN0~!GR(Uy{aWwkR> z?#QdCKVUY{>+(z^WMi5TB*i-b5r4Rb`C#K9*x1}7=`^xq9xSP&sjM?o;R0F3+6%>& zi3=e&=RNi$v`lsjrP3S4vi|3B-vy^lzv8p!=kDS`B*=2Hq7s+R)t@_A?ya{w?z_JB z-=`_709QlWF&Y6WgiDl5MS_DDnBUQOv*+(NJ|<2hEIhEVpEX^_xJ&ha8-J|}5vvg3 z3KR<8E1S zPO^Z!+6<1FN{b2<*{Q!eFIlhr*)c4_i@`>e$iw2E;-2y4pRMN>kosVuupPxgZ*2o#7k|0C>PT%#4vRc$ z)dALu9ng2m2zidzJnhG_jj(RI^#TqY%Y@XMM>mln=NF6WHJ?~MynjZjubRj^Td9Vs z+;1tacS`GZ-Rd%np%|rJZdBG(yWPz#Z}CF9d%*v;(s<+v(Z8s(-6HMbfA*4mlwW7c zI5#}!4}8v#n%r}eO=a6^>~Nm=$R-Z;4nkE}{ko;~ovCvWK@~o>SbL`C;I}-0x_3I@ zsA80#tSKLGlrlWI#edokIO-S{XByi_9O8vA?pv@y#TuV<&;L=>7(taYDjY~eS)1)a zujf~qb1rsv)Gwv4+|z9L@R!STpPp)CHUEg;t#ZJ>S)DUcR|N>+LnrHho?SMicvduSw#lMYPX;;5vaPvU1aqXxa3;YMSmtVVSQSPXOBq_Bu$%z zvCo`w;i7eyfpaE2Lbajn#+?Ka6&_=S<<4`&zK6(0&;gYPx$5Z|C@_SLdK1`5XVWco z8ksttk`dm$P|88;oTbVh1c#i|Aw1Q5(hmx!M zhLT(KXlJNYZw$txot2%*wyV#rL{H&^b!u5~lS*d>yUAsJ3(OZa8*=9v0{u4Nq|9x~ zDHaQfX%seHhX%xrn(+4w}X)%m$b_hbw*3Z)WUA%uoNl z)PF+8&E%XH8Y0%sPS+m^?3I}o!)+VH>usIx?r`o9H(P$`M#UaW9cofGE)7@13J9m6*GzaJl2Wouh)&ksCu=7NL&{`@|=xfhnpAJwsCd}O*iU@D46V%tOpr`NO5Ho^+GUZuUbRFM1Qoa zBGB$81Aagb1yjL78$lp?#+0GJv`L2>=slI~?KB4~z(#2yZJ_43akp|P6;-fjboC<( z`?(~y+V3c%8=bx{#Ra-S*(j(@2L zFD4=HKbanL2^xq7X!=%Y4}X%>p))FxkSL+w2U%%399SQxSZNK6(HY8spf|>|_4*!- zL?Rd{bM=SJ>GVh$^hxWxY3^LJ;X&jYhQ=*7307$KqQtqm%rXx3|AI?HC%-S(iux28 zSuD}Bz!jY%dDc~K*;0&hhVp+n+8HMQ9F2N{?%a`fMeu)`$FuX$Cx7=6eChv3sv*{h zcE||~0MGyi0KoI#rW*ez)8}6uH&k?$ktI=hae)XOg%~KRhgkFfj1vs$_OidJMkG@z zQsmz$hDoMH%PiQ;{`ojr?77}u^WAcicC&sJ-2GNeEi)I&KOz+^S@8Aty5W4y?%~z% z`T2$HbLHU)0r^mp(0@7`{nKZv-b~ed!^L;1CR!zn+95SLky?~xj|1lVS^<@UHrA79 zDBCPt87Tco0Q!T8QlV|4~jTbvMqsGba$ciqAUYouSXHP$D@7D5Qk2?IU#JT_-> z{T8*)tmx zy3S$0FRp_i!Oly&J*RAYLsQBaFpff})fP+{d7-$FDb9VQ@{K^%+}8E+wQr@nCs)_w z1Ft0O=Lc`1aerwFP3r9Dxro@QHOUsocxP1Fo*PrQGKmc|o@pf&u$8!)>PTG8oyC`T zl$Lz?h8_Dd)$z!HY3CWxcU_W{Bb_400*}>k`eK?Yns{v>dLg#CeZUmIkLZr>wc<0S zVl3!JYmy_MlM_4UM;n2^9Tu}@I!G1ddVM9yX2ra5pnrL?b-Rs!IC)9s@@0&f!P;D< z+kS=_dKEzUSeL^a=7n|Lvc$?pYAe0(cZ*JsHq>)1H9(?0bTC>Pr=F7*t~kKr%hEW? z`5M$*G&O&60lO>Xl-pwd8-%czj`W6JcD2PPx9R(d(OBb)a)p$JPn511dx)`TVTeJw z0OOP+hJUCjV+f(%#w@52Xax5tfTHSbe8*QCKr00~g$HVo>9_b&y$?y}= zl#^$6N0?}=@u*ng=@hFlp!qXG)H2V}Imsqfp*++x!x14eBheF(h1;Ty$PHot8-xkP zlbjOqXN0mG0Z{us3fI67*r5~n0C7!%1}hr$lYe;RW&_lCMH~g{G^@A!CuiRBSsk6L z_8aJ$KG7`jSsu@^a;@Nu{2ljaok_(UZf5C2I_)K5e$eyiPm2PF9BNfM+1eDMw^#>? zFm5DBrQ!_GjhJTO@YY}u_-W67QiLk))^z+p0RXxX0RVLV+ecEx!pYQB-NMw==Kmbd z|9?sx8vd6!WNVQ{wq0EEAb}{@Ac2KP2?~XwlE1kiwP}E@4P~`$LpPmDg6+l*>H`pY zM&A3jY=3cfb`~zB4LZCUjh{WwKYqWJW!qRnX~V5T&g?z2-q`Cr%Nyq{|MPYFq6_eO zZwJ6veP1LdMteaLZ6U^IXBt(Sz-FV{cz+;jwjOGhPLs>{Oqr@iYc_1Fygb9a7+Ln0 z%(zH%#A!S_!Mw$jQ&p{*>&ZiM)-;{6fUiu;O=^}IGI0RCCJj+QK?r!VLNv;BqNBy{ zrY|HhlQ=UDntkYkRC{)~lRA&A4OUYO!Voe>Yn(;1pU?E)BqC7A&d;=+F%ab1i+?6W zpn5pbHLJvi)J-UKTw-9a0+Z|GN^z5F?dprYN?0Z~Csm1R<^iYB(#^E?Qqd7I9w~wt z9ODxm9}=97IO}C2o-hOqH@F4>?+yp`>%k z(siVZ*fY>=Ked5Oi_LI+N5~xNO%(+1`TbG846FM;!8y_<{8gD5QB;iGaLoB=miLfi zJrwglkwJsWs{>HQoqlf2F@EG136;t zdMfaw>{S#|a@TfBf}HGy!5o1Ye>fd%q-g?IT}(G^ZfR|;v)ZLb@=4pEzPz?|hs4!+ zGk8YRKX*~McgWk^{3(JMQbJd!3gYIl zNtTIuKKp`L|9ceZ?SG-Y(7mfp!O$3WV)&56Wm16cr<3I15JG!4y6I9%11%F40PQC{ z5P<4RKAp>#iA5S+2srIiS=@_0?Q@5cOr|Wz&gl{*Z0Uyf&%dv7u^cIUgb`TO)FYF9 zb~1>~GXHT&YWk|`HEs+aA!1!z!;4yyHP*g@dx^fbsmK%jq<=q)o;jFfX&JFIw3Z%( zL5gKNTd^a%K1o#&#dfeJE{c4Mr;NXEa#kxe7n1(JM0aXH) zBp)%GXNUEVmU%b7`(i1!w-D#cE;+@t$v+h@?;k}8k)I2eN9;FWi>0^N_(aNigVJr2 z99(IY*yk=!?|&!h83q0NBi$BL^@ezRNbVEf`G&)9jMjU={_!2Mdyk|^r&LPe<$+lT z5Qsfmg`z!EfnuMx=Rsx-GU}{J-p0bR1WhNbBj6C-mcKV+IM9$yDunTL4N!oZc3gNn-Cy5Du0kovAR5B#^6K$77DF%`RCFR zuidkL7I1gqrS2AbhI>y)^^VQnAgIu{Zc|12)!iG;r+~_%k-c6M73UtT#Xudf?iGwq z6_ni@SpJ{U3s}Dz%I*%VCwNk|&(D5uwGu7js6ayEx5J|+fIY&l@a1m4H=A1JQ~e&T z7T>m@=zkekrvm!xKQ%u4xatf&0tW!#Mgahj{h!1A|0Dp_ha8z>ZVC)xC34-P#oNL( z1aN>r+pnc#4Udr09L^iSrm{{wfjz{(3B6H;4y@?x#9vBrtlT;M{gw0%fIFe*J%0j+Snt>_1-dK97Bm1EZ3&@+;%0#(1k1!8A=&~K!@(;T! z%YO=07oY7v5y4Pg3a%H-M{~vc;3pErD)cQfMvjXior!sQ&f&>i$|p6sV}r6uOwe|y z@2-)}bchp>xrmD;6BCam8zq~Sg&|7>PBgCSW3!=mbQz29>hU7fEZ75e1TVqn2E7@k zgC#Q7yF+thaoMhsIsg3z!l!=qufuNu2YE<>xak33J?kKUB;1nC?8!HY9w>v&h#~BOplz-~% z@{S`8`avQdli-eH@K z)mR$&Q{M*>YhBJHjg6H`FU;j3w0FpKTP5XL7wDu!K#A<{E9TDo?iL(%2!za0QZT@% zn?&lNt6b>G6D)6Gp$oW!D02X*xqmuaAI?sSluXE)i_B3sqckz);RP8iDFcZip}5_2 zo}=`vH{M3T&|S}i84wahI0a#Hq;<$-oKJX^8JZ*8j%Z>S7LV+q1hwYxo+2oWTZ1`; zWw}V&k~SqXBBP2I`kSP73QD)n1k9Z^>!C&`oXY%r$+Mk77m;#Yq2i^wM}K*)N*jaC z@SL2IgLkMryKr50UxC0!dk0g?Xf5@66@F8KX*1~Nn~(gkd{X)Ax=43sx24HJG7`)JhaDc;OZyC|9`$oUS{gD_A9RJR{B$s609YHZ>G zG7udJBc7Yv(;|Z&nW_Hj`hQ#8OL#{LnU`Nc{K2xB>mx;aqz=+U#m?qblvXm?;8a>> z?qg2mfvgX|Pa9yrmsLGZy)eZyl_57XRZ2sgHxD`So+4&;jL{Qe5A6fKYZ~GRt1DDg zr*iI;R5XS#@XCs#so6p`+;b5*U@fQw@e^|C<;R&2I5k$*Y**r;5Zv{Ysi zei3RrVx{9w!wHYJ>S-BO=6P52_l!U~$X%P>$EtbDR8j6zG*Z=YAM5m7y>+H;XO=ngv1U2>;dcsUS6|{Cw(`0bc zs`LSMX=BY@Z*+Djtbc<^S`ESDL-3et&ZsQ1_GF6QPnIS6nM=M+Mw9ML-EzPu9kNK7 z*)d7(*=;`Qf!@d75wAF!yXa#BHfyf#t}RH!ZvAM08)I8dVA$QDub(}12>Lp$chYrh+$7y~f50TMp)C?z+ySo>Z>aO77lJ^aBtA3%AtgVdImpf}0F7@c zp81cQ`77VIVqMn+h24yZb=T!yu^srgt@8Wf_YiPp^AQJac9Sgnku8Sf#+ujJQTRvX zm#+Q5_=jiDLVridDwrI~l5Q-DQ)uTodGr>r6}!C8Jaop9ezXHbAxrO0ebxblM}Zc8R}Tx{?=Fyi^x4oF`=qHdlK zPlqPmZ@mn*pjqU4mYr8en&}J|0XJOY*>DSGr z5bABElqWkSrUYLjJjD?%!g(BmX}Z@0l3N$16ANucMK>d7b}5X!3HsEU6h0a_i_vpv z@b?K-_BAjE3d8TFK{+>It$M?(e+$!bozrm%Yzc9RYzeMwEuvLr?1PQn!!nHtYt?3D z+{4-}%72Hc_>2oOCb!mX+||KH;-h8VSCiLE4-lb8D~*<6gk`Hoa>K~yl^WU?bg`>) zM#+u$F(vb2R23z=dsR?rLd>IYWR;BKf>j@A0kEp#Y?X{iOLb0vuWM4HQOD4+AQX*W0D((5^sp zHXTz(N%(&?kUV+W%;+Y~@b4vgT;I&7qZyylV>Gydow-3{a-ZH8ji`|KK+(${on*H| zesjs_qZJMC?~@MbgO(|VTF_lc;q2m@TjLlM{xbC*)6bu(W1T(JCKWEClCDGSG{-zW zP5#ogvQcz3U%K8Swwl z8>;{6(wHMZ2?r>MQ2nxI%6mYJ)0Pem?kG%x6amc7z`bdx$(@yxfl48pC8FHhpQ2}{Q%0F3 zN>t;$epV@ z>GAp6BSnLrST`&GRg)#Xjbc3~K;V2B+L}zA1v;d;bx7U*)+;9JEZBoV_pHyId8~iB zk=(MAMwKv7RMcpmQAFmj4Qz<{GnMMEgd%}&d&#n$p2=D!j9j+;`|h#Ha-`P$uw@z8 zF7QJyF9)XAT1qz#Ipqgt1jq)q9lq8L!8pf^*|zJie-X~qOr)}G| zZQHhO+qUhV_DtKhZG76cF>T!0J-dH5_VFwf=P&-PxTV2Q(W{A9v`{d4oxDl0 z?E&{lp+dQPGRw-Bm0%_kqdCJd)A^wHt2FIl+IC=e7Ap z32CWR>6_UN-}B~<*Otr7_WSA%$2U+NPQg-NxSG2vjsW8DivqZ1+y(1OXbJZs_oULUCK$z`jJ5^GW-;_@bk73 z93nCz7RIE?Ds)8T}~=cmJ#w{}<|LArCy z^I|Kxl$4Rg3YzdDa;)_?3=b1wb~&{%IN&k7BC1NEK5P0)dNU|2#bhf#42vxiLph?# zkj51#%~`GHvV0}38gaA(+!Iz9K;MB@G3i1`MS9}CuUkssbX$fIS~Y*Ot-;iWlvGS! zk|i=Gr?s|6LEw9RnrvipP6IoJUAUizV-vt@nn><99dL`w@8)b~CabA>PK$CNjMg4{ zN^l5o;laJT`asO{1KNZ@^^|2CTzno@+IR>b9|><^_@=@w_*x(WcP7@{)G|^BU1@pG zkfapnCBt9bKS|LJjGTYBkMNs|QwnXoT6pRp^xQAe>JZ+sv@@WM3)rv{l}mhu$#q0E z0%rPq*>|4gUAe)p9x>V7E3r}xO(&}JNC?6I7&Ve6OA#P z0uz^a9+j#lw>*8J-8FWsKb=S_Wz2AbrT0A(Zxqw}TAIR@F!o^csvL8mhPkr2>H7SH z%XqLYu$*ZARrG&_S)}i%hv%GfzF3vnY(o1`;`U@=G)be@eGGcDIKZUe$xV=R=o7(R|!>a3p!1#R9Lc`tC@4)S4qmNUrlutBTH4m z&10e9b5hb>VgBA-pP>hVn#xlF3niKCEVQx0H|N85(w2W>!B*aC$rA(5$YTl<*$I@6 zTy?|*n`9iBmE>CUx*v>nk^e~$W;|X zxm^ZB!s+hNa+-4YW~Ka0&y25$hs*ve8k_s?O1+s(zSnd&r~QR*#F2qYrSNQ)pBDH4Z4Jm}Z#78zO7&*YI zyD)$4ft#K4$P@?@ed;Rl?r-?zIp-IdqLlNf&YBTzm6B!1@$i>)D^*9 zb;1`oVD|5qXbY-klB;BCi!xvmLQYUgq!i5z1K$ z%O)+TdGaru<7c@pu>*B#Pn_mt8dXk*1L|!aKd8P)SfDyeQ*^JxqUIk@I!qD-(eTt zO`}uEiGER&iw$EYV^+d2SH!XbD_NU1Cnz1M!SK|*`0>`_w@ac$xsuT;*)ood3C#HL z5W6dp^t@>Ktd@gpE((W*LTCGcNs!N^|-5bwO74Obz3k` zT4C>wz2WBj@R;5UQ>7y>l_$8h@4LAWch`j5#kYyFHhRWi$qPi6*eW4ZZ^%Th2 zT$jx&T*J8ei*L1jN&rJ|yip+2r`uX#}|WYj44L?S3Cs%{HN6l^IDwBcXKcenjwJOVcpiJT8ELbPRBqnoweMSCzN1 zz)02p43OE|xHqB`c)UAoobK8?&q`)7;*Eh3;w``B)!$9hU!1Uox)0CeaF$|G8asuZ z_^qAwn=gEJUo4FH*i)DbN>8|Wwc}Ko!%~YV(hGlmVx3xk%5Z+_{%g1)o6>+W{YrcY zy|89hIyt_Kh{YlnwIL-OZ35q@w|}Xt`4Yyx)Yj2pv}wUdUF+h^t$fP94E^CS2u{@ChC&n>&G24nteELAI+u7*CVb zYt^*nAJWaIaJ(iz6HCj{v!>D<#_x{%_27Tr9z{}U$lzRb6FeVtD6#}*yu35-_{XJv z0Au1|6uP<2kZ6h)kFkkWp|tlzwnldqM#>TE#GImH(G}?&+KD|zb`?i<6Te5FVsL2= zC63J#kBH$@?E@b2v1)HUFz~?fDvM>JuWQqEXxQ%@SnSJ+H|E3-HjqRh!sntm^Z0+| zTT>$UeU@}Jn6Y<8EA_t(cOhPg^cDcZtM4^-#WvVxeiEke6x22md|UR(b<2awrCR*y zgt_-f`GS#{eUhUza|zhi?i#df zeQH5hhsF@yJ5mNdFP%7pkKOx6l52mHNFR|zv|g_z4hLTAl#Srlb@dO>Wo|QjQ)yKj zA{S2!9s1g>374aeff$3)ZXjkC;I}60bSvHJ@%{7y;L_W$MU8le4w4tGs*_J!yYDv$n9#9L%TpHI0pG2ZK6L!-0Jk_PG|7 zYazaeInJY0Q1Kp?rJEyo!6#^Z^rFap;O&b!WqJunyCX0$+>oCf;6@$b+i&s4@6tLX zCG2DJ)E{_)Q#c0Q1;DA`Td04SCUw2!R__B8x^UN~)&!0grHlCE3+|`{FGp`(_`%u- zxITgvh-z43I9`_e)UF2@UYEw2-S;(ot%*m>(<7H@xv~92cHWfYyp_O#_qSclJkGoO z7u5=3Q$=1oX{euR)o1jSUZ2g5@cjANCME{lws`rwF^6h^t!P8)&>nw;-h31PfC6|T z%0bIXG0)47?}lMwfGjG2Rx^Hl2bTNwQLWSi9f>eB1=065|rP*oVh@p;tr<9Y8CnH8G{(3}` zLAF$(6-E-ZG;U54guz55h?vH0Fl)r|;0WxwGkH91y~X{_*K-Tm{;)siBzE%_k3RfDbe2}`sZY-|#YDsaj5cmEvCV!bIh#D(BT0WobCEjE)TqvHn`8BV!s-09 zf91wQ$ugHfHPh*yWVsM-N)$~z%eD6pKe)_#wi0hHCXM=qgNi9$TnyM~`ZvmMFm=U1 zV3)adMPM;=uNX(Yt0`N_MU&-Hp*MJ0J@E{Tb*DIe$_I~R?oQ(Xj8 zdnO+bTNi(~kZj7y@4$+DN1HfSPU)${>!c9%T6@FZ^b&372;i+76*!3-%}>;4AJfy3 zBPVX4f~4IIyctP;da5%%e2XxsiY$ydpU4$*oTFXGz!kj1)s}*BN7hl}HoHL?MWzsc zb@CrZ65uCzkFNn}?z}HFjdA1$*@jG1;FT#Z{1ktn6OH-n?e@@Vujkt>Ut*1(lGRq~ zh8>@UXIy(IHe0doF?ey{447gI7Nb<>+~3m=UC$nhrSr1}VNQR-r^}FdhkDXGg{n3d%*f#yooXEQNPd$<&ILpd zJQ9D$gZ@at6c*4E1bInR2hU-oHPY&~E2hTsjyMFFgKn243c25!{0uL=(`fUKO`v)f zns7P=rC%QryNeW-#@%|c)BR~h=7dt~*oeX*+*YaQ2!@IlPya^W=E3c>3hB`eb4|jl z&e?I0r#MeSN~Zo7 zY+lFN(4>K?1pen1-FZn#knY-spSQK;R9Kqc6I)qLsDX((_ZVsjMUy9im2A=szG8p! zBIyNIm9cth4oRBwi+hI+BN(pW*8_>EZvJt#M@bfT0Ks1cV9pKc}JpHDgfD!PL#x>_76TDLM|wLVsy! zQ0>&2YFOI_`vTAMO1oH<^=?WK z+nN^Yaxix-i>sIAWa|6l>)`<-kis)p6mpM~7`!Nw$uyxV$jn>4)vU(`-${pgNWV=_ zqsJ5yBRUSWh7d_&p$`}~{G{bHQ>gPKrYx}rFOv^n(g>y?C;kTBa}nCp5Pp9n*C$Ae zz&W4~A$0MXQ>2NcVTpI8ilQbg} zaD#Bun91_+3#M+h@)5u-uc35{iaKjIn+{83V& z+gHnumGgJ^vg%EKCDg_}cKS`l_non5%T}O~g>=`McLgIUu8zUmAE@z6Ypvdws@ z5g~dw!1* zKMgcfC+2p#<rS}-! z@zfkUi5%9ufBfNsuzHG2!E3~dri|lK_~WI`^Ev7y#zUXLKFc8X877DQTdJNd z2=W`D-W_USh$IfMaxxk4k0d}4=a_ZWzYW&;dvN>@zt#WZEAeD`;0G8{A80-WDdK;? zC`jV|sAneZ&kd!>u1KV&IYJ1@5}Sq`z}>y1}Vz=3HPkm&W64n=5LSnyE9dm zACbpN0~>{dMoWNA94d;hIeLn|WKA zIg7ac-G~1n1k``!Tu?O7`4qO)C#zeI5JW|T^MK&f&2WN@VBs-QX;FAhauASEM9AfJ ztS?8Bwa?P?5?{w8l!lEf%yX#Of0rnWnSn`x=U`LMn5#DyTzv$;f~jOp|!li&= zqg!`-ym!0Yv_Ee?ztswSdg1gj{Z(V2(}DJda7IBjIZuD#dGzZ?X^&w?Ir2T!i2O(C zTjy3k=(w8Z;vv`JGSQ3bK;ciimAN&mU$z@G+#ZBF_CeJcZeHcRhwr52mp$?b{Z?M* z+&+H01q>pcj`ZYT*OLem=dF$jj&!R)8p0`=+~b3GsLXl)7` zeF+d#n4U&x-e7Fc7>;yj&g1*PpBMA!IT$dV#vjs6a=k;EzosXkD@k! zm(k@8;s8_V#JSEu0s9QMJ68?>Yg&}oPRknTXL~=~4>a{1Ub_6O-^ZGgB>Gg|jX87? zn!bOwU_!-XvSjDcML(;YJ3YGCQr*LMG)VfGEm*GkCiRHQKA zIA2!FfFI4DR$BC$Ft>cj>oY2D={)MXNyS}jDim&BA)88ZTqB}mCbTYH`I^69fYZ^| z>m1A4;Ju(@xa-nINdKB#?|(d6J-(FA(}5Vwq;K=}Q_AbsNSP&`E>uS&HJR}do6Ucq z`Xb;g8!B}zLaV8&H|;2p_y%7Ab5H9E_BmML+M!`%;azb)Ss_(X>P+|`n2L*|$R#en zAAa+*JMMB5xXE=fL+i*Eb&)KKpjee{myNLnmbmsEh_kZhmaI#F!`dGWj>q>pb6KKe zF!+i%OoMSHGi`O=hF<}?xosa>BW8bXX2@R;mV^@sO~T&xkBnD65pfMDZt0yovA6#r zJ0Jl?c=HE7*nL3#1{Ekh31UeSTu`bw&~aEWLbU52^2SW#iLiK z0Q=iVrG93qV2&>{AoPW#>ybr~PmbshyYTriTsV!0cKJbRSqH&uV8r;4au zT%_m43VY0~;V)7LICp<{400k^yUTvV*p$rN+tosh5qw_pZ)1xSbp5OZxzjgKPW*I- z9#IeBgov9exzpCc{q5dwq#Q^J*Vpi}NOt>?>Gg(TQBnAP^SyWuq6qO#+>N22)gqrF zC_W^4(UmU1ZnSUxw3zqa3<-a14cv&_pWY}{VqA_t9#Po%TPRyYg&X8ser#`ng*MUG zye=UA0bzH{9UmcFIKGaQzO=4Dy%zKTw63 zr16Dr20kG+nl5)o%13|T4~R5Vuv9Ylv}pm+6|6}95NHE+jmab4Fi{$_p7^}vnpYQu zftVlu4+)}uQ^jHK`N?RdQ-ersfT6T0Lia535~km58Zr$}SCqlDUkr>#y^X03^BeB` z=op>--ZVkeq94hIfpIVC5(OIXf`mHExmTL@%+|`-)y)no;F5o$B2^iOUQsxMGHWtb zH2(Pw?Y?~op}jI%DZ1yK3VdAh$)%;AGDhb`5l`0Q7Uv$43ZKbRz?i}715$_@#Pwlg zB*|HpEbv5E!4$<|E39xQq{c4-Mu7mz4!RPKh-MH5yjP_*AR%GN3duMT%NO>wIjf%{ zi|_j%?m1wQ9VmYQ1PJKyuM=bXKXqUtR?a5>sUDlvWE@a5P`~VR?}ifkq2kX%?;#UP z{KKsF=T<_=)9N}RlL?cksg;%3@?*(E@Dy0_HH2t8gex@Fw3?JVFN*Yv?4hkeZH5R8 z`w32&0|@7CW&q$aw8>y3v)w0~H@P>tKG#_n7`5Mi;D&$rGE%TaWyYLvU`|2voyQ1e z^Q=1YPL2MnEx^SWW) z^_sUGP{S-7FpA9iyo!h zdbsc{o9qaOmRVv<=%C0|A9OB@S98xN2)bb=7;%4b4O&?!h^a&LJ3h{4=`?qEvvy#O zz#~jjJ~e*v&@vP_F;kt%T<#3G9yEozQKsP0I_@-een0H^7^_Dr+8613owqJt(m$JN z(o|IeG!1xbMj0=xt$-Qq@+Vc8(-fq(jV! zdI8BvH31~p^p;h6zrfva%L)E?{>pGG%|45`vN%v{^j23m#VRkPs5%E2c&=|qpO)ZF zpOr6k%12q3wGx$co|c5lOP@A<=^sCP9Y24j!UF1Cm*-tN794*aLz9Mk-TUu3ef_`- zFb00-j5~Ssiem8$YvkjGP&%+66ZZFu6;W-LNJ4cE09h_>ZCMznlqyn?TO{XTR$>o zVSdWBb(KbwCQd!3f-{oxji_vjF_Np=XOV`!jui8iml9LKdln#HI!e3-@qP?0gx3zZuUx*x3P`+6H#xehtqdO)( z+IWBQ@Bg;9?7!@0MI&dUe?K>oG&3@_vbXrp-m(pQ95qzE(Sz|9=K4HN`7QFo)buyx zNSk$VSz*g4A2nb}xTI{t0aM-~6$A3@EJrWV3haIa!Xv0ZrTe9O>Fm_XZ=rwGcXYl# z5U4I<^(a8|Ju|s{Zq_XFnpd}7z5oFY5WB$kLx{meL{%bU1%l`CckN2n*jLR95S1RZ zix{UlEgLNYBtH*fVw6M?mk}3{BIp^dxT}*j3_SAGMqA}-o9w-MOt@>*v>S8Nk2+h9 z()d|*N$RFA(v=!FY=F;L!cTv+Y8-g%YOQ@ntQRYwBFW&Of-ZkVO)@mpwACDp%pr&= zW6m)}HVKw&|9Auyo>Y4!D>lI#ggVdai$fISJXSH4zq( z8s$m_ONOABX4mTKbDX}nU9I?I-F1ZX6^;SfP0B^90TTn7<7SQiJiBIh@fo*LaYQfK z4hnvPyJ$&|T|@V2&v?0NC)~yM{LRfmHm87XZnCY3fXGJGc&?o<_FCk=;aZ)({KUhS ztoMuD4!sxgwno_`=f{7d)_3ZBmK$OcUTR@qIWRZ6}eK&DlL@+!RbKEcv--PV1S z-hFb-QSPFGZW8AU;{fV6jeI>Ck-TfBOaJ&!Hp-Jg8%cKpNwcG&g;ha)&ybsk$7>;| zC$#7UBLDD~u%J7>Km7Z>h2Kvmqy^}s9*NZPH&=$gG66zQ6y$$2A5MY*{vHxuW@spW z@s~y1IbP(pF@`}rL)m>f!a7o>mT-6EeJ+kLR#8?}OhnHdM?Cox&%oXFRUSrETmXis z%8$0~@zY=!S)-25ckDAt-Nj+kq8FM5E*FgAPR}EOpWq00vd^Ancko~)1WX|woj=Kr z$M7mdH~E26xQ2fuubB1?=GSQPl}kWPW}TyMS`bM@rKucFl3kM*_E=DB(ppQq%l#8f z79cZR;^fVlTUQucQ8-f2*m!@Nv1a)bfM~H5+p$xh>&fwYepxgWnUS>>W*RRteHalPYAKsA}XkN7~#)Ju(2CLH~Oq!z8>hsVr#Dw zV+3|zONGZ0oxa3v>o~_S{TPOZjQ5bWc0w=$f|{>j>+?pcz{=FZZ)99PtHHCY-{AjB zJL7fVBN~5k9m0RtNAWMT<7z45VDD;VWpCz8`Y(UzUkc8qGd3JHTv11Rds(A$Xze#7s0&G3Z8ga@3emQ<_}HnI$ZDZYU9JrBtfTOh7s&~Sux z@eO@;$?qa=;}K6RI;GY-s&#;c)vjFppI-fEUiCiSkFE_`d%zuGk060hkq~2vLKz3O zvYjmI^D&BR(?8!Hoga?cIMd(W+|A+2c6RLyTiMgU*9(6`4w~d-y+| zM;r;REimgIDrB_fa;tU8nY^8ZmsM?&3n{XwVLStk5+v@GE)Td7m}Bi|<|)M;0|yC= zA<1HfRk?WGDxAMs1?)e@$q1tM7?X$6E7ZtcU)z0AsH0LT+mAgd23@mBYP!Es;MiME{8dMo%!YBM%nJnol$ZrDe-RPzj zRO*j4YGZBqBWjvimG!15#9ybHR(*e{v@XlM8K%8`Zn5+qw9HOo&&;Wb*2YO%KUp#L zpSwF&oL&S_zenWnpI)F{S<34g37BEMlQ6G8BK$rbRW*VrE|TL#CSMsGA$HNZFC{ab%oux?~8 zFg-fj6ELKF^c^r8oW+};+th0D_O`@v`eMc93+c1UgnhPtW}w2)wcA9-=Mj;zODDW7dC%%1)fU&ZyR6()q?%+ep(ezd#P(HwC^iE6=e z$N|nGf%*KL1ndmeJQCvD2m60n+axTyg*FAYA`Wdt9^e^w#fW$&aNZm^`3g#y6CTgq zQpPXl?J?y#vSbmb0d0l3hQ|afB*(2!uTp*Dv|J9Anvuh46rU#Rq?Hxz;$&AlEMi z;aU|3J%Ll`ttVibg(EH4CH$m*>6k8Z?p4AmmOHMC$#wq1{{GWYQ!ziSw1arA)6h$@ z^vrJEOY(OK&9W~Xojt6j!+8ni4MZq_^c`O4#vY1pUkbx}B&CvJg zfatWAo%JfxR{0FNCqjRFc0V_Upw*Ai8Rs{cws{siwXMKQw~3i3?rV_#)Gn2VV3S1r z3jb_?-E9tDKN0U0cm{9C!B_C?L9oOveL#O>zG=U~EpEOQ7=(8J&t*#h)}9YQqa#R=uB+) zA(ex9TjD$^xN=>J{J65Ks+{O@W_Q;m`M3@Hk^07Yz4V+@c{068sr4+ihmvY83)`U? zOGxdzw!G;YYdgDTN5)N$9QJF=bCpQv8W!}efKje1D6U+i^&Aw12ZLchJ0 zF&W+rE^`YuS{f_i%nGJ@Su(q?$8Qe!VkmGtClhql$3iholEsKDoY7>Ha7n0I9@y z8w*&2BbEbp>#Yr0P-Ki{}JaM&`A68a>={huoIU1)mwU#00 zi?TyJBci^7rzG|kz%ljIVwu2_-L$D2-ZdhfN0!IYdY0RCb9z2k_YeTM2w&3RsiA-B zK8UN=SZ{6Qf@7BHR3S0_)sa8|?tC!lZeE*deEl~tSpob^a}uSOKerz++OO&b!#MSp z>o_DMbKd}BdR_h#^l7-)zg%~xUOd+5n_x4X@ThY}tb|te$8J2ywU7ra@6uiWxdDo6 zYy!bcWX9nEp0k%NU0(Ch6X5=OUy6TX>y+017J{VSbdYsX~q9i12Qcbw27briY3>qewkSlX`wUR_i>~nTgGTw$s&l+bw@ePnN%J z^KlR+I{m=k-%8#JNhVPBNW*zBdg0q6bcXkm`ni?lQ7E>e8=NFj+LdvvM02BvPeYs( zqsbKIbFYc_dxC`c!REm-=H*_Kfq;gho+*JosdZx1&TD8}{mVCJ);)8gC%zPS`SzQ6 zGfcZ`ByUJ@w19{x|M%pX1)qPhWZHsJP7 zr)XEqU?+PLP?}WZ4G&=39#sr@xIxU!{QBvIT#%jlMS*4`LyezVY#FtWy9E8~CyFY6 zm^BIs#7J#E#pqUB!mOI*Ay{kFEWYuDSY|AT5e4z1FWeK#1tSS#bTfbSmh`pCtfeo3 z0AVVG8qpO^#i8!yL+#RD(OqeCVMyxrG-pzsp_l3bI zHBp&A@}NeYtGT3d1%=b;0F|A$@!JjXLoh^T`glLwsXWi`nm3N48!JxYJ}_lrew6AvLd;`N0a z!0n%Ybj#QF*RwbblxUVG$oCnP7d-cYscpJDF6tvhnyxCSO;4QSN|+@YqzW8JY6wm! zv4?^0px=F-aB8uB6UD`N=_uy~=%|e$z&7djZ=+AtOW~f-2)7iFuA#BG5XTf$GVD>k z(%)!o_uWh8%@ltX)Uq*st`0of3ZYJP5iHBTmI8(kx2Kr_BGeFB0trZ){Qh{v!wHRn z1-o!>KZCJ}GU1lEYYpe^YIp5)cX1UUu5a062FnE*!ui7}8v~&I4cZbNZgw$-!*3z3 zmE@}{lkMnb}`O-q2LTAB{)Ig#D2|Q(n3v-+zCtsW0^e-{PM6@%muRS|Qde znpr5}&&R|i7WvL0=nrJvOB>}Q7`qeze4SJXOE4fmtttEBUl%GFEi6*Qk(gihn%;c1 z_Ys+oYp73UWxwf=p(SHFB9|N0c*j_OVChe}HzLE+95TK+hCcscdd2I9mD@vI@Wj$W zFOunTsY-uPNEtnNA7@gTg8&K&mwSk#D==% zLuwz*EK4Ib>0uS^2!dsvrNuNKM?q*4Dw}Z=fb(X=Y+0Ze?%fVrgb7?q+Y|YUN=6 zzr;^kqJRvD5aRF-skg<PfAU|Rkexz!L~hMYw^Z>58_rN z%13`}Zh#zw#UXmMi{RnU=N;58vJaPcD9#Z!(s`*zT8uVW{UKtWbN+Cy-r&3q{J#81 zhwDh2#}mat_Oi|IYIrt*jA}I{o*a{qy52+wWlXD+{TA)I=uqK^v@}OIZXF(b)~sB< zQXYhwKhZLFnU1%sj@x0#@z**yZi5NjrxSm-&CT=^@wABX7QKcvhE`?l4FO5f5}|ub z+D|4VBD;wu5svljRC~8OtEQmB1bRx|3*-$=f0D}A2GPN#8V@Ox?aS%sULye0;Qwd^ zjCC24`2LGl|Jqsh|H{syW+rB~X3j?cX5N38S&{GG% z>$Riw&>b)4Vn&vufQ_W4o(exJGcbfWl{-i%C^(>TWN~ zEGYf-)J~BKoGHhtjGKu0hMP{tf4_flP8B6+|C3E^l5#qKW0$cN226oa9aC1A1y$DK zdVxFYz$3Kl`Zo}{l3$C8IV?ykYx3uGivIvqAW|LzP}3w$w4pX3@Z>Pc~5%wf9 zdIVk-e3yoaj54vrd-fB+cma{0wzvN%g;{FQ(Cdc)0^-O0?|KaWcZUA2;9q|d58ayY zE;t%!Uo{3clQvxLm#lJ@`@Gqb6C%?4O;Au|@npmHx)jZNt@2Pt-RomHW1SUE(kMSs zp_>Gu=I$v|pWoFijpj@VK|Tf)J|K9(!$)t;PZ>c3`e2W8E5(uzXd2yEn=PJB`DZ+O zd}i7$Zng-%PkaP`7-KOy=7N9K;q18A=ZO-Tw}w5PhzuN0^k&&(?z+?-brNTNB+~xSowF>$-cKx=c@))rEe>INozjHZlY6!{VGR&4(olTI3(k0%Fny zU4yInRGFPgF%A~WSk>+?b$QcR?!{;ZRT3BjYl7kJcSYDe!Zb=tW+Wx&jP?(WtPn z_duHzQ&U=9{fy^vq!>;{v0HNE9dzd;iwM#AZ7tO|$gLko0-S%X!8jEIo2L7NTBVLb z>p?u}=f~@?XEM96QPTLrVU~1lsDE61=dE^-{_kOPm?lAXC*Dk`#tLEebYom7BhXQ{ z*mFr@vbwVLjPhd!%`%EPr&LZa52z;bqDDQ=ASSp2?(1X2E1xwcB+U%jQi%@OFLDZs?2|-0fJRv=i>H$~`+n_I~RaWOl@&4nMowZ{+fLIWUoHHSq%{s}~Gp3i7Ac(_9&T}~U z`o_CKj|6{Z3YAxCn%eH!a!Fi=v_#HvuMX#08be*Vx`@UrxDEbBUD9~T#VoW1NyVV> z1FSn{Poe(3O2su0iDNRfh08&ra&C3oI_o@a`AO_~qK4MqLcaYumlhwjvleb;eimpn z&Cw_vL@l|w;IKmTfdPfvOISzu>7-Xay(41-bfsrsWH+2AMvfWwgoOQN3AIjjJY=_O zKN)}R_lzcZS}QmPtMN9B?2AD{0@`!RF;FPE&eCA3QagU}r)85HGmbehzs*89fozs& z)iTf(>M5I-4#5sCoe&1&XnVMwk^{SxbC4~s)K7pg#|~0Q`k%sr+TO>?0tbNd!g8J| zOaNn|GsC{}wXkNq#2nE^t4U?5j;|LEyHtO>(2ULAESEC;OT%miAHO_?uyTt`m)uVo zKKi)_V#4@&OPoLYae9OGfEwob5%&xy%9irjJwR&`J&Dl1DORURx0$F(wb^B)-sqt& zCvH#pqM5DE!a6RBnQd&?q~>gbkpJT-xT679H`=`1!%abFcsnzzI73mDyJ#$mjH5rn_o^&1@gL96T4 zJ0AJ1&t{B3;x@q@;g=}KjKJWC!R}sdTX63lQ&;5k{*5N-lBU_7b(tV9CR00g8F}W%fu`8 z!Sjx!dMIQ^=a01?P&BvdY??RBb^5?Mi$GPg5I#BBv>mXvfqmdOfmiqa_$nc83?Q9p zeeA427kB;J@gBc`yX>$4Ar)EnZjvcHoU|Aln#(Cr`I5seml*tH)xV zUYKIENko!Vs(J3AH(9R%gNuL8TYG}Lz$uKM7u@nwN_!J4yWF0Fmr07=X3AjJaunMk z6n=pd*Ffu83vd%JN_oyab}!NQYF!G2zLc5w?{`1K?j0GA%5R&5xsYUELtYYvy*wC? z5DrMxj?ycfA72G0W_OFBCwcN=N^6! z3d~cod|^VH7)3qq(8K)-CLV|ntiT%ZhUO)X4_e^vIw<32R)S=}^E7Ui^rhV)33MkweVrvuc?Uuc67F zUo->JjYy{=Z0Mejg~D*wP?O{g!HT?w(W!VJ}XB9q>KoZoalT8cPowRMOX zNL}XYiiXL?LuN5(z?#V}YtBw<7vBitRf=S$a*2>ZERRDWW?&SIbE_wT&t3* z;qtAabNptVP|P%F>PBwxS!lsiSKkVz!RBL!#wL-`D1lnVbCEKTXnTuQgiUhG`oNRg zVKVcnAxFkRM-5beA!L+KRT`G!i9heJh!ho3E!6;lExEun#3{ zIT~nNWk4()7nph!@XP}ernqZg14&fBQTk#&JxCt3-l@46xE#rp^gVCk*OXbL5FfP0 zF;0{BI5JYVUZI94MuG;WKEtFzi6dLhIGqFHdu=}VyNgDD{){QD`JE z*W76Z(LLXP`T-eo#~MkO9@RbZy+?SlqIvt{^zjU;F5Fr|)HsFvy%hMmEh&--SI(bX zrQNBrqD4XJzmPnp>Z+C*dzAOcyQm#_@@}4%#NV?hNsha;_t2R}X&~CCqQh&IJgb*N zs={d&1H0t++{gEb({U5-)5vsVIdt7Ju3$`Zrulpq_!a2+8qHHEm8olaCK7# zl$7qlHi8elM*$C&Y+==agaMyB{+1mmEG6~9%qr~u@$L6Et0U8~eYnl*QR35QDPozDW?W}F|R?Ya|3|lCvjW=z#Y}yl=FGO|@hp@p0jhgMNXJgH_R$0KO#I;qKDSU|3i~RdWhd+M zOeNk#qa-3YRToqv7PpZQ1!^z3rV_7JwqL?`WZ8BXl}Bffl2DitUdQR)w{$XGskuLau+7Lh%jGste~>uku=? zp6OD4T6lRR7OmK#_(bm3AAf};LO5oBWedAVw~&I6NPp+uik1r-+i${%3WPtkFc`Uz zRJkEqKA8shieVp~Tc2%dMfL9A;C%}2=ei}#ak8wcJWD=fjk;x+D(8}Es({>;qI}cn z6VR@WAPYr6jgY;L$V<}-FBWY{qm!kt9)q4E-jm-eAbw1WKZ~d9`EEb=KCc>oMHd+; z;8DseNi1?WIhs=dPS;~JWI0`f7@u)OOc-nDBkxOnVJMSVBzediT`^c^-x|C~3HyXA zrVf>LmYePHbp}R$2Aqhyd-n`5XJm^<;-#lknT{AX^m_@TkAcyewq}!qn*oXB4kBq@WU z>@5bq(mKDXpFKxuGtwv)b^gIT#Aa)4X4dT~Z1z_4RMnKUqx3As3+Y%-NYwWbB{s2< zfO|=IaqYlKbyf2UdcklJ8c7#dHJ~3rtpB8DjI*=(bjqbj{-dL+2$xZls9>Grt&J|l zpnqXiQ$>I}!j>61P-QLsy5x%YyttD4kx*C_nJweN(U}Bk(-1b@AFi9k5#uX_d^8Rn z{v?)Hb@Pt7`y6f(OJW53A;sCgXb21|H@yC%qs`rag>F%km&LG1r?S)ZT;P_zpJT&-RB&jzl;)x1z|-V!}Dfyxr?! zwF#<`IXm<%gLX)NI3uRka>?uH{w~bi-)nIGkk-j^BQqcDof&uOVxqWnl{r3t)$}wP zlVeNp;*KT*O-y&Z3BwC&9*XuA{Xw1yK6oQ$@ToBGJ=pNJNRIGv3&jM=n;*)N8Mhyl zVrl%a03`*gn>`pTpH50YdoBfKBiKf2A1Yr{agFq`0>uS?0=9ULjyXXPPnF6 zk|_Y#gGdhxy5~yCpKb+6*@Iu?m;9o6`lhUL&z;lMLXBx!t$yRt_SU<=UGB&a#&Oi1 z45@0=-n3K;!#IaN+CzY$1s0s$%ZEhFL+0LSB|SKQ+sPFRTcfJKRw0vTbAKU!joxTa zG0;s}AD8-j2Z1Hb&G#OK$8N?+QUrAbYEw*O=ydVZAsR|l!;%8)d7hptL`|X8i!W62 z6Pf+Zv%J?Y>-lfQE!Ekk+@AuX*FA!m8^bhr9DKs4J$AlL*B;DfpnZZQrgnD_c*geU zJ$;^ktz5iou2(dr)lPOwcR2+O4G$c6&%RkMUPzKZ?7Y&9If*IXWnw=E5IqTOUR^{# z+MRn^nIoT>&4#Zt5I$|K{Ui}v!OLfFxkcl2TKk@M%K~^y(fg}U?(clO5xcvwe0P`G zu8t}eI=UNSA3~bzMfp9??BC}DSgmC`M|k~zy|1BruIAVvEgaC6qGfi`ofF-5QCpVW z%6LAzd&U92EU%wC8w~fbZ{E$Gqh(g)OL>n{=~H8o2z2tWI`P*p@7~m@Gsf+gEdp0- zsuw`7oGz9)3w?34E;AW)Pg%5T~(05-=Xrt_OB4>;?C0zCaEr-NcL!x8HaK}e( zaW(^jkEGmHftC2Y$Lal7Kf*{0PV~qoH^a5%>Y?l8IeEXxECFv`AewIzBS~zFRQC1W zXqx-ML~3Wl0|`Z`oNMP`2sl?H_5RWSU+tWihXXdtC^sw6aupMxUUB1qY@Q(rQjinth8?%8M891(GE{j*L z3(Y9s`x(?Roe>3BGqyH$rE2GY{4~;L6LvSXEoo<#_N0P0ry0uOV)F3GCk!um4w=_y z4@1VwuD-^UC~uqC2M3|ap%!a(LUcwy{j^bAUlChNmq+@{2z1=;*5MLyWuU0NNM+~vo6VMhpIEf)!jbJ~I3 zG`P-4auIu(<%%DGfA#P5i>8|bzyJWK5&j32>~gk_#*9M$QM+NSh^&gjYZ(Tq4~!^} z0#dK>5YP~ix12|Vp_|u#r8ZCA)I&Y#qAu<-Xd<{QlLG)qtew6!@t4^H!#3&O_EomM7ZJ_seW=m|0Sf^c-NsP?>NsIj$1sCyA4;1uXer|sisvid-Di+z5;eR6fBmFdS#6Yx9j?UlXYQ*@>InQR*k7e z%2|r^ZsT-?%W8E75omA{`YQ@Xfp#(6v#QShd7MOcS44Hjd&HF* zViN!Fbs}%2+4JG|SGjv4|5J+M`;30KlUeRqMs5i;{CJ5kuxc z&X7=P``Or(sHdbTb5y8{>ii1n>DvHrmpL@y>84?uF!rMP$a-JB;D^lBbN-IN_8I({ zM(egR#qJ%Ia$Bx}jZn_U&xC*4i?7R@e!s*YZ++sd<>ZqGq zO5gPKOu;UHa~xuMl$Uw3)*hKe_F6b%pHa;nen=_SXK-d&Ge(<%uGD$OkUQmb*sK$t zYsII&jKasSy412|t9uE0P!_RZO614CNEOe(2@F*>8}BZ<6Mo+UN_H((A(h)5kDmoz zG!)4>^sh!Yt9KK6I<;}kNESTjTwL&G;j^7+nX!g{hUwP)(sJ%D@q~CO8fUfc08BVA znx}3Lx$0FC8}`awrs+Di@VYwmU}2wXV2Rx^XhZe0xVg}XgHr};9yVw z@}Qeq(6aAXaefOQ<%0#rSFwq z9jP-*fiTs^S2EOfED3>y9WopYWJ11PCTM{;2nNbWw}>SC1($LZ2=18m?DZG#h*F4u z>5jY?qNn%T1(P039|k?6rqg>Xy&k+6ayHm4rqUs`lZ+zY*s&gyKOnzzTu%}R*cp|7 zni(-OjG{g++F5;3L&Q>=9cgP=0?dJ-ouFR)5TUu9Aw){t^jcBl(-4<1l;9~GY!6{@JerJ)jd|Ho^`v2rn-)d zDq2laZ`ce-tw$Mq@anw&pZppK8H_UL-%E*CTD9%VYL1ol$1A)nxxvhiaVB_wEWMj^ zj-Hk?Dt#5nRvxs6KOiw#XBg0o(*|1M4ZLTq%t_jVFQ@gV8N;&mSOXGGLK|!IDE?Z| zV#mBAvhq2e!&BO05JV`2~EY=(8<=}KPavHpOhxKqmPWh4+7Hsm(dXNl`G4h zNO}n9P^~CcG*hRsR){bDXBdgnF9EOsQWhtHzw+v969t|9010tq`7OaHl34-03(2lBD8q z!2iC;IJM({aa%_d3+Xat{o{;nnNw(QI^!h4tSMw{6@mCZ5DYicYvwO-0yxC>Mf7XJ zhNX0UZV$PZr6NbY)+bQGraA*|jj7AHFrOpuz3tGC%Os-;8_qSRoDF2M?HH|CZ~r(x zzRs$&M0whl-;8syJyfXL8R!?|=rc3Ch}HI-M1iS)fKD}>ZijX#p*(QB>h{lmmWSV* zDz|hkwVCreO5r5zB$MTcwdJCdw3K!|b&2H$8b+C*K(L`?JHdT065o< zE4@a4F@lItcl&D5pM_fTl*yigKhX91csD*!huMFvGvx20vRE{FM-c4#XtZGDmbGX? zY8RA%Xit%jao}j*$Ui=%Yqh*?N>bP8e$&&4kY%^lOD2vEFUR>UnX<2$wM{GaraqKW z1G2)tg5I6`BEWWnNVNQtkLf|0NglCX#jh5BHj!{rd-M8HeHin)i)*%>2=LHDz|-1J zsuL^%lXY^_O$}@=?ZMhMf!agn0>#<^3>{!=MoanFVKTu~r6c zvse?fgz;(ts}TI~o<2_MWnEMh*2ugQ-#>(6sH~T%?huHzrz-PH==eq zf)gb(`VNyv&(9!Rf*>M75e6V#^S?dwAKNEwp;(c|Bd7B3+!S#qgN8%+oFRt#z~iEi z@}bWm_jdLG)ASgZthbhtx$JTWoj5F@B^HcP9=&V}T83$sLPB^z-P!I6F8aJkOG*GU zi(K5}F@Aw$rBYm2n$KQuDD8TG8bi!#LXY}_1sg2a62t$xhw=%cCXWW04wwQ&K+s>zdJ4$nn zKT}`QbhL3LMgJzp#FUW!w%Ere+qC_RB>WLFq?V-w)z?`-ZSnLB_SSZP7jM-GTQul= zDg=n#uQ^dHqs_AY{I}k~{vHuIM<4)zlfQe+|5rLO(|0g()&KkQkK%R*TPr1ZyMH$O zCM({^F3O?s*j}wvqp^*`8wU^;Smi}QzFG#+>tQ8Qk_M*_%W9X)Ei@Nh(0{8kA`xK0 z=6)4Mz3@~>nM$p|-#l-Bd0w}dveoYTdVPcGA|~fr6TQ+c6TtWNhIG$yiM zXUb%)eUi%4Xgi6kP1?WoFj<2OBRhg->G(aFf^BVeRohMba$y+^RvxkoNBxmLh-=(Y z;i%=+EVMZ@uZygUd*q6rmljcgHq0EGj?-J1CH~}@R^0P{5kyLHFM9Rs0aDNu<6A83 zo0k*0fE3XeXE>}kEN!epoz*d7o{4@Y_Nza)RFTUxKM1@)#x-1~MvgEP5b;e4nfa3tIIze~EAd^N#w8EhaQ#mpc5pIwlQOrlG&T}cP&9UMvHfR*tAe&A zGCvB>Vv#y>;?juHh3ImC9`Z0M3L<520wIJsdAJgP`73=o?sVFAIy+aU%1`)DKHa;* zZ9o2AEYgjYzpmRG%~W$Vu8@NjoeT2cf%|8>%QKqO#vKx|#!YF>YYg$k z<^jfZk|7H{2ZL#GBC8O1_zsm`yx@^GMG7H*rrSS>nVv_FEK%<+ahYtMM$9oRDuo@SY+s4eTY1lgPb18W(ti)_ZLjHxJ`p zO%r`aDr4vqWEZ|>-}|1tM{7fr*5s5|t^svR^z-{_Qq`6h%OF#J^DD00RKv{GY=~ z+V<~R`#&t>w#;8JeTSsb(pbKU3ils>;9n6|k-G&l5afl6lYl{x?xg9v1|?s~WM>n; zlk)nxYLUx}cijSdksqd?X($O0t{WX^HU6WaCljBq*BhKZ)|14E;N;g$0XAqzu-xSv zU9uNhf(XjZJ3;J{Cf{DaOp?`Ki`KI*@j7YkP2xt_tOWmp3H4G)ya113Qu*|MoAq;* z25)iuHhC+7GY(}b{5ptcg*Eb&f1ZC_m`*Fi9Xa!w*;)yu$VahA;~Te!IvMTbiF_S3 zAJl-Hb*g&;J3zngJL1Nk?|8hWw+6MiT}=qn8}3~jMlVj`lP*Ds3e&dB8p+6}T*tIc zn@@AApxkASeoBIn zMGaB9oXMecPLPDie$OnIi?1?iWi>k~MySX9PDK3qcypO`!sxSY?7qcS5wu|VuZDca zt?C?Sa2Qe7#i+pJrU5$}?FYRVNLv${oZ6Z!%zF;wW?D^3gjm8r29JW5#u5ang{jWd zWY>97Niz};V<+^!DMvDY?}R3n3qTl;MNvJx51>)5p>{fqcO%1^4BxRuj^FaeNn+T2 z2sQD>O}OC~ZGdWLq$LpD5)FbRg(5(Kq2`>h>w!^Kd(z0W4E*C7qTzd=_$1D7=w>EQzsu>!VtHqjvqx%Q49)!v5E9%* z$scJTF0fgg(vvPR{F{YEFQ^6mYPpUJR*{vftx3KNvOc1sB|Z(95!fW|F>>cWp4fPFmMC z6M4!HSa47lfCTAzRv*V`l#O3Kne@SD$nHywlcXO4yVRsF;_UBc#jshumQC zt#Wk?Aes6zYiH9}YXTh`>u8(`^%Ub;`7G^@DoRBI8Bj#^gY*lmT-~Q44U5Hr)^b_=dCBjQe8X^jymIAJyVfuMZN~FbvGivOXhgsup``X&FqZ~`*{CI8|{m(_m z*gavxpk1LaG+C|ofcW%Ny|_MdQ)wG<{VBH#5pbXBY`P;ZHg86 zm=xxvc%?5e z2xNLZ_t2sBlz#XI^wCr;MtXS(a<1|yO3f3+`M;^@9peLE+05Dan-I+^o9G67NmRnv zEU1MQmx?=rw3@NxnC-J(4<+I7iYAM>!p3)i>COeDyJm<0`$SNG0S@o#eMNa0ACrWC zxKjD*QFlr%SX~x{0b=MM1uG}KL{d)q&@!C!&?eD7j??dqluiU7ennZ*E-x7jg_F0g~z9PM?;45*8iF zQPZQY_z}t-XwRNVIV=_qLrjGM69l$?Q3mJFH8=?mpo^s1VDzA-DjAmi*FX_I6n%LW zaDkn)%4Cb$QNM^>J8W%C0xN_>kRK$>1NcEogaJ;6KmS%m*!xwPQS#T2Wr6=!LAk$s zhQ^ML<~F8ug2oQU1`f{F|FmF#%G$2T!WcfJ(jC?fUwJ_m5|;e@32P0g2{${If<(q=Dl$TiHi>tKWcho)^-!?csf(rCaZj>^N|*Go->6&17{ams6J?Z(X{L zzC6CK5Pck<2%;dsUHdNQ*{Eb2ef75mrZtZ6|btTUZPXPz+&2 zw96Rh1?YsQIgAW|LdE^rQ!@)la0VO*w5O8ZZ_mOt>{b_O-J2;qARNGA=&2v8b=L{#(Fq`6uWiFRDW{fTtL-O*urNc)kP{L+TXf3_gTDa>*MS9E zwNFIVTd(b8&y&1XR6u_CYm!^Jb%I@>1)80-DuJAI0y`RHVHEBD>qZ zL_SE~TW*srJ9Fy7OcdwGJDs(W*@A6Yj=l!yr!1SLTYvkXdt8ZX&MhMJlOVg}?!-BC z!d!heJa>)Qo%20^J}WY!0_QSKy?`>&amzmipe=LVtdQ^3Cpdu^cT;vrYXhEVCP=>3 zK2k0ai6{%cGuIcd-X|Dhm?MiVXA(5jC0)-B?RY7~1^JWu`O)Dq5B#i#1r6Q0mflGH zr2e*zX!eNhulqc9g?I{nFBL`GB}avkTF@-oNhw2_ zWGTPkY0w;4?ASfcc#XhOB(TR&HD~DrBG>0B zBGIA57kmld3C(v_FT;k%B^iqsU%+l#Nj6ywOCUvnslw@oe}HFiimv?`S=%xsZnbl? z0UwWkgCoU%*Nccikru|^!x%)PJzM;M;ToeIRj40L+Z<40MZMT-(wVu`s}GFj9J3~R zgK7_yJ?k5XD9x3r^l= zgc>E-gXL3yB&^r(;x#~qX>BN#JaJoo&FPyGhWj^vsBUQZ;~i{I@t*D6Dm7Rx!9dPo zk^c=0F)WU6h$C2oEW~`Oj)^Yhz+=DsJOs z>|mmA_#Yt@*?yTpdKhoa!eHyZpjQZl0K2v5L*k*L0l2*FZE8)XVsUZJxL2wgoL2x| zsQnOsaj~s1BfgJypBTR09Xr?(UwwBAD?^q-9pU+-IMx%Uw# z1u|c_u1gz95D=F+9)IskLVYO?u2`5&>`uJrHL`fIHdu@=6ox+f19BH!uYZd~^<^cV z4gFnV1O8V|{D1nHA`btUv|uG=YhX+)t#9b?&*NZnOt%dX147W~=T<)`5?%mMMjFt6 z5hxOYFkwNM5dTS|irrW{k9#(^Rs{ENJj#iTh!h%=qWR0ykFSq!z`7B^@SOg{6L_jp zT8HWKI|HtSp&TOhY3^|5t9cv3*70DPRc2pDUWai1{>#grELa)n&UYzZOc;{(vK?LO z7qGy-t#TTj6!5_FY`(%$X=E|qT2lOfhnW69&DIpW;A8>{1{QT4s4{@GZo&SHzjS5! zL&@X(C8Hby?u4nf%2mg9W$w}6hpaAM|H8&E>+B%{{J&{f#^IHqk^lVhLqBy^QL@+S{ zJn1q5cmaWA1c7>S6~=@8q9EoXkb65pvqjE)a~n>8b#qmCpO%ME7ADu3 ztcPsJe{`{3pznCyV*;dxTMCf-%lhjIQvd;>vRMpj5SJH&5pH|4o!e{vnlmbb=~VAi z?e=lS3?NrTP+)+s=o7YgBu~J9l+rZGHOIb_BCa;IVzSZj2(q;2Nn|K9&onNvqQPYO zaPq%zOFw4=Ye+G{HlY+ulpi%&VNHlHi?7E0Q@L80>Do0Q;NDf%0T+y@M*+Y@&K%Qens_ff1zbIHNTyOK~Xe3bD z6Ttkm@SivjXstG39H+x59C_+QU4qae53C*zeH=F34h$Y3j-b-?}%@3rYa^ON{^4Kh8NaYII}#11(wRhEsv@$J|N~Ng3T$W1YbC! zWHpSufLu)!+0sw!W2Agez?ok-6YH0}uMpRh7m$R*{&CwfW)0__KQEUVUMMDdoHOA9tEs!Q{$rh_eoK_^*|65FPC4K`;olVa5;r1NNTj=c9Z;J zAQ$Y94H?AMEs0HtTAL>9a)Z;UKSE1Tnoz0<>N+v3Qu-=?PE3JHx0Q7)(Kd4EjBecq%MH(~c^!oCImHAg9(9J(3;0-Z5eGtJd#We3^h(hK)cy;M#_{xma_Q?1OW~oD#Tmj5eC}l^zT6$Z zS6H&ISfnPY>s~;>6@R}7#iKqde!r->@*ywo%FB^|G5T}|w&3Rhos!p<`8Z5XCI%U? z2Wi;HnCp5HERFeA0Tny399QUKpcMq0W!L)kHv8DctzU%ffg+GGwOMutj~S!C>P!P_ zP3HJu0IK9oYB1S>#jnfRJ$}$!rE|c^8DDO>Ph7NPkMbt<>AH0J_RH*%I=5 zv~2gVkTsgqc1P>wgTSdZU1%+jcjZD+*>k}T>*%1{w8?fN%A7t`wbDi58&FoESpn<9 zrA$Qz(rn0)#14~Y;zWnLvIw#xgI}34W~}~ye9j$xTqONuz-U8E)D|-u%36s}H5Ib8 z62`^JkWJ$f-z=!QsnLQAj8}r@p2T4%ui}ymbBv3;>7gfg(xAST2bvA73$w%=G63^C0);JZV7Qbi8x4#-L zTT$QtK+zMD-AZzNe_A~A_-Od=(2#w9Bfg#NDu06Y9;L*8hPAOo2kb^V7 zR_d<*=NU;uszsU0@-FcrLQ`~cD!|L*!xKyvD-#UamQxeB@ppEAgbDaa zK+rH6xv7ODTn&yzOHZ)8Xq&9zq2q}COQKX!wHo-c%377__L)F;wP{VOX$BIdij@q+ zM{!Tf;^N6Ta?y;uMObx4X_i}mY^Ox=3$8sUZ zCLNBkp~Uryo7Pcd>uD=EYz#_jmOYp`MV!eZ6P(yI)BS16(kH-xy4i@-FScW!z$CPU zS$oqV#}Z4DeY`ril870Pdy6E|t1fP5Xm1BnO1yic0Ir(z^PT0L7F$z)$%~kj$_>Ne zLNr+rxTS%_s{{^G_mkI~>@&(jN1PY(<~H^jqBE~5^qCaKnH<}Ab-D}%D`$pFj-q3( zLyAd1Lq){YV|eeyZTX>)Pa`ev?)x@5T%N%3I1<&F`klBIr)%+8d%Uc7sl4x~D)Iob zJ7>iS*Y=5a-;Tu{24}{9o2n)pzicF;IgZI7kCrEi4vmWOalcgp)t@8N$|&+i%x%H5 z9O0LBnNU<~uTjI=7a5GtQQ#jA8_}~CaOcWJE@)$H<^O;K6*{Z=I z45mgEE!P(lVgC^@3MpLN@+2E~GB~g?`H*BB9?7*Sl%PN9-~wfTUX+LrZ&QcUe;hd` zhJfVzKN#&}Ah=c?hXve|9jR&w-hdB^J_&1}-=K+A(Huzz$oehKr!j`~MU5bTz_Nyy z54gXTwE^WRQaI0fbAHJcXi< zdPokQ40{0Y7uV~5ka+o2v0>;SVv8~!GNU>*soyWSwMhuo(4*%m4|qOi&RQp0=%Q5olw&8uRRQ%@26 zM40%*PL>A|k?rmf;~=gLr2_8Ru!k9=8~kv@;0$`}>Kt!>Km3RdVoL7EX?U3o4SZCr z;E@a9DJ0)U!r^gVBoEMjI&3?nS7h;5z4h#x?A#f-yEUC@^z4T1?Yqe`eeu9{u|x1c zz6se4f1^<&@TD-3V#@GhCLm)Ivv4X3kSD{#p|c_!ero%u}nYb z!5G~%f5UZugIhiHToZ+1n{&u&L2g=;&173R2RNz!YRW7)B9_q?d)4D~zc!`C7YbG* zogov?5fq|ErxF|FqNk=sP=35|i3&^h!p>`+jZ`*Z@oKvBQxlANEuW-YiE!4k9CV#9}l9kBQKb7xh_o?2b^V2?o=!a|(lhaBkDp5t7lCD!-7|v5(LJMKOzL z6XI_Knz>yiZ<2jgh8hTXvE2O~?tpYcRYoN*Yo7))layM35Ycw&9LAStR2ksTH7&W7ZNp%H!#t0OZF*S z7*q9sGpPpm;<^mYoAUT>@%m`4FtW?yaei^=W&{)~|8OX~cZ-NKvtK#0dp8I(QM?xE zdhoFGRNHld&K<#Q2>7ERr33~YKa2#UcmR+=FA%ULu)azDMGJQAV&(>q>`R91jljAy z*?Qx+KrM(b+`dLk>w3A&X`a%2tWvLTrB8l;-YtF8W2rY`#5f~(CXRW}Lsp+2zf%!5 z!UhnMgL(orf4Q7Et5CYMtaE`96uxu2Xz2F5o^gU$F}}Y>V0&l#=KyhQ(E1}9>5r=J zSS@3d@5vyZdaPH>VdWUo9<9l#P0}H7nUTC!w5NIxZ`3q(sP${w;g-Q_n;W(|)XBAf z#JqqRIv2~dE*_;JAd2Svb-#B+Rf_se&X5D&u{gD%+xp-BEu(Ps4hByu4n>auHWaE0RgUdICvdeF7d6bW2P^dCPqCiH*-3s zz+GRhP#|;;W28`}*~7hDNJ21Kz0$saeUns^<7!9FmiTP(%~MZ_aZu7=FHewimwL*e zFV0{%j?bvX7|Q22g2Y!W9!dbq+{-EPOfd}nExmFS(gixk79G+_s$AqK6p-ePJ{18| zOL%2hAJ{&ZxLu_Lq*>?bEx`5>U<3+)h9<=6Q%0!#HEq@wlgIfeTnWBRunnkxBQQ>W zLM_6AYCR5z0G1$2ju3DTr5`GyDw7Mvh8^_hScwB6r4Iitd_Xs)x+YhkvsCN3OkT=R*3Z2T_=ZTSGV zKf6e`E#lu2bKCsO@i_S!kyZWA07PjMzyeq0wb<2Q9Ok6AGO<_!CWF4TMLs^Z^!fDG*=N2Vpgv||*Bo_d z?5qPtm%*wClnZ6fJ#kjIB=B6cKMFr>lMkVEJhOL_!emT$PLZ}}vy4uV{SQ2Hv42K!h20E|?f$>pGJietk=}b#bQKig{k{G@SbBRp z3n_Z7sFA^QewY^ptg`iOn-1Y<+oSQJK=?gD%*}v#5ZPz?Gp~nf+l{wZFHdm0AQL~J z2wn-6qCF{<-bj1^34{>IW_Kw@L0dSpmE|U)AR(xa?r`as1pswayK*Pk%ujSLEE`n z@T8feAmk;Y`1?$E#^dvt7{fwl!f`Y10*N&*ij+sGKOm*^KO;|nke@>+XG^eZZ}j~2 zi@1m&f*h(*x=>t=%>f)u(QBg1)EhZKVcN~%mZaEeTjx4Ad#Hbgmn})bWN5ffI@+7j zXsz2CkXN*ij5EuD_z zk!IWWyh(H2;Mdv$(9Xxm32+D%`%?l1B$9O$h>Jw3-`7z`jlE50+yx^x{DPt>)IlXlPF}4+%eS9JLU`=9a1+Q(*mC)NjDb&62S}EbL7*6Wz;f(cFKP zMjdKx)b?L#fd1VR`fp3)A4LNHCz(n7&v$EUeH$ake+Ft4ByAUeBYd;cv4t-NE!_Gj zmLXF{fn)_x7Bz{*4+sJs_1LRKQ*CZu+epOiiP{T)9Qm=oh$>HQh`1h=LNd%*D6oI~dRTap|H18kBQKB+XwpA@|6Z$E7OcENd?t zG+u)-y2PJx6XJMI#*su8Bl)CIO^nTo$lhyaR$yR$4mz70BF7XCn3?UKu^ZoStj`Hl z4kf6Kv=9=&}#nya8)0w7YIwTjT1JGiRk4>=`NCH6j1N)i|(EABo=ND?e6_onS*s#-2r1bAsVYN48 zez5;lWIfRTNBI2jH2A;4M@iFmksgERdLy{yY$ZAQBRg6LV{&A#+)RK{FhfbtpzOxn zqB=dnZSAZ@6a-1^SHJB(WHk5?6Cc!n9mlvDS;U69dmZjc)&nm7=G)W92Ry)EnhixE zg(;FYq92#rYH_umYz(Bi5H`)^A{hKb#AY|B91?C(ojrBW zZbAW(fT)tC)mRrwV-)%-9q<`cVOt&J#CLX-yamA7xL z2BF>7z#2kd>3NdOMH;rfy8)el;Soui{WYDnvx~;-=sP?DqR+8oq{0ek_X%QSWH0w^=eJ5uB}4g~ zo$H4EtI(ck06IX$zY2m@0{tdSOsR&G{ZT`T6H8=-V~=7o+eFw@_%P|cP0PFae{Ip8 zq-Ixo{k@C%Bl5y{fo<&~HJHHmSdYtQ4e(r%91`c=HQRjv0{6+FnA1$y`_@rnh8*ON zTGNI*0s9##%R~a289-)#s9tkG_+U`04zCgVB|`&Le-3YnAbmJV+x$G^_YN=u1aW*w z`{@Kh6j3^DQtNQ^F|B93-z!c2e?4`3!kX(U1r7j!gZw{;IsYeQ{vRw>t6C~zuVVVd z#H$mdN!3YP;EdWEj3)dVyW2)v8_^qGqY{gXHasWQE`qH>MB35T&njAd^pQ-|+5X5b z$wlG@mgZSJmMmrZn#-L#D|LBCXG~u>!KqdO8XuuI3E@G{e(0Hf*qPz*fBo6b{f625 z^^MREwqy=*wif2$pK@^=l|Giyem69?=1g@3x#YUZvB^ashaMemW`?jVROK510kjcv?PkOp+NK0wfq{^P)QuVht9d)oi72WIX zoK14&ut*v!I{bmMVzD3>f0qD_JvB>SxX_+VAMbRqh>WRrs35q40Z)uQf5m8lWR^*j zIW9R?k8S*p|4n{B}D@3^eqvKrVUOP)n(Pyyk( zZ41ff%;}@`k6|ezNVT85m^J~;iNG?3e>9d}l^&s_&X1Z4E3MNUf5gL;HLU&paGz@q zy4i@6Xo6xEsd9~XdqP1F(iQ@To9!l&*X$AQ$Ex2ExKdU6$xG=<>~uNU2$Y|dv7?Zn zjY#7(2Z*y|CpM~&gUJ5)yJXY5BQE=rX%QI)d`7KFw8Hh)p_agING&zU2;_>r2u8PCMg%xKL(!zaY%abCBhnqN?!~?`=(FyPA`0^voV6%3}Jlk z++K4Ibeh&Ue`D_8g0Fh{^d>eZ_WNHJGNv?(6ePJM&>f|PewhB!!%PKiSL;kArp6#3 zt*izrqcrW!6o#G0YAX_NqT+6Ac(ds`{rTw%%`wR~hCJ?B-0@y&_YtHC_aS%@T?zBW zLvpzlu9>fqENW?3jaiZl?9`DWyw)b7Qllw`zKnmQf7h7Tzdy{Xyqy#kg?5mwm@IoG z_&-$OqbCAcSqo--)a@}N;8ilp8_d_3786nS25t5174kr4b{hq%*XMz-OCto}YgK=f zmr}}DvXl^-9o2?{bewtyxI_x9!gLV-643J@hs1yf)}WwQ5B{pm=$n6nHrI21-u9;M z;9VW-f3y6AmD8_&H_!7%9Rlt0Q69etE(>OtamLEj^6PNUG{@_XK2G=cQ-~-?N-Ox%q+|@bh ze}E@4j1Pl|qw5Fa#zE~BoY$p4|G50Q7m-TPrdLWXV-V6@-g(aG7bJeJ-do#{ayc{q zOf+;o0SZ5m;odzc*DDEldi(;m3xcYLhw|vMjde$1PB=*Q*ZgbIn5a-r>{1LC`jGCm z3hA8)nr2Pw1Vu;K^QWa0jFM87D=5_=f81$TY;5k$48x}_p?#p(p#gltLRjCH1ky{Z zbI=`Vp3#s*ameQ+`f9_^YAxO!1n!|oLcj86Q>JI)2__@L(><{wG^zQp2e;qIdB@Y2 zKMx)tURsJ_j0RUR@~dB=ddHvn4QNh6O;$qZq~^x#PQusb#2t1AvIX1v-nJO0e~U{g z+ia6IWOYbDsN}4-3OPfO9@M&_%N4n6|GBx7;v*ARXhvW>>rxkCBNks+$?|Iaz2MR&|_DH;+lN5Iv4pCVuSlDnQ zvWkhJD7axAH3C3Fw^e9FsVb~_37u7vujCt%?Q#og3T&-@~fPFEnf8DXH)oWZ{ zQtAP$QR`3Ims+cA6YCY7ncxg93(9H23hhZk6=GHu;%4PzdC&q^g(|JU?*tmGTH%+p zq-&255_W;M$6fFC1+l=P>D0VTvzCbkHXaL~yvzXbckeEy{q^DYG0?C0@{LxYOm-C@Qe@JOp%C7WFg?vt0jP?|zM$||jsC}xh=i1I2cNc1#w|E-| zo=e=L&jg|0|FQ~55^!9%`;Vmx`rn-=_)qw(WNK>dWc^>d!l_Cuir_5BISP!PP7tVf z;JgLDQDuJ=i4^gQfXX`JMccXYk^0K-qYr{d%5)T)e%5RZM2PY(sQp3yfRrwa ze`%!C<&#L%gM)y?LH&1vZ~w_@$^aK@^Z)8I^<76aDdeve!S|2DV6+f$U_zGBa5!2v zhysZs7z_!;6-BKR286oJ>WRHyWk>Y&3d0rKw>Z%zR*7H>e=$m_dh_fj_}i#D#@Xct z3DE*lR5 zJd?;wo7I%6@IRi4>mGSqI+%}kc@4?gm{F9-;3kKDhJlZ<$hY@@>Mrd-hgc8`a8=ny zNJBXwN8z67f1^kc{{0&oo|n*l2%*q#EIAM#%xpr<{oY&Oj*K!7Udp)eL^ke-5g z^+*6mkyBvBPb12>Jh`&3A9+0%?(=?tf_1YJl(p_6ju3r9(bO}Sfv%Jm-V$nP`^d;}8;i-u#x88tBU+Ao74tmQp-^x1xJaX$teYv3t6BX5vY1hr3-DO=iZiV4 z+G5M_K7BTY*KBnP zf8CGvSB8_Gho;%9mn68>c~(hf5BHv~t>Qry?2_MVa%)p;@5@y51Ag!ipH94DDzf^; zL&2B>g_Ltxqed`Cu**<~htwN0`~sMNyL`#(@TSahTn^kw3ar;xC{fDfMcSe(vh zFB4;lkG0_}&&kRpn~?>n7ua^6r1TLsLwr7Xkp#+>tFPtEyz<5f0q8S zghBr=G8^T8d-%VmxBgcQ2#e`a1Q&r19Sy2ShAt`%rlpV*kqSeWmi`dOD%jP_te>|a z*uIuHSf=&@A%xv8CPtTTU~hd|XUjLbAp)7Hcbp^3@yXo$=(H+HL-lKgn~~^dw@dY& z;VG#k@Vr%BkjuceLq)W3IJ0x}fAOiXyo~P0+_#c2kX6-(NxB@qk;RrTvFA4mAH%(; zdMar`MXcsbWj;Ac5F_w5pAJ3T3_PS`%;~(!nKSBKv$?mLzR)(gb+ln#Ui>_q-d>In zUQ>RW*FgGH?r17?qWo95WpZus_Fo3vq)_Y)ZNWf5q#^$=3XT8nCv|f>fAfFaKKK5Q zLZh02(!Xt0fiu8umMSN}!pf$`izaFaqGE8cu#;2%lZ{Dx&*1ZQx#@Vx>3Y9-dC3Rys5do*9>iotY{Uj+@Sg}=zjgbc6LQXk zm19fpjJ2xYU;`&@M=>RFe++#^CXWr}LPf}w7oxW)<7aR|k+SQsn)}Ao+D663@p_$v zJUf^$v>K_Z^quiA?Y8Mg>vii4Jor=#?eed;#aH6&W5^r<1O4Q%@W+8}-{hni>Syjk z(2ya++0#g}&De%%wr$wDN>vxn&3o2Wy%JZWjHNR1?+sftQ&t@kf4~Efj%Drbnh>6= zfRzVGB#!&J{%%Q0g!`Qrj@Pk%Q-qCe#bmldcboR3y-1)dOU;jXdU_VSi-zJRMP7HQ z&BH_vMnGN!X%@+I4Wr*YD(%Na!a7pc(YClkD`cc~M15Tti~KTJl6wxc!tWT~WRyXN zE5x2>>=7$5_a>H&f3#6PSt$GMGoYH8V*IGGMpo_hj&*@$eO44EPK?NXKn`&DGic|0D_K^ zS7aP`HT-YTi;_m?pa#JlIn+(J=15}42+YHyQ0ZOTHRhv3e=o^45-~&h@g{M{v2sP) zW4J9mVMF5k%x~gd`7t<{zj{%ff_gZ@ymJ00@YXDfvNBCatFDJ@`saITERbW5&fmO? z{0J>h!$a~m2OkA*KUObVDi(gfVOf7xm+YLI7RC?DMRhxyMb4PZ8g_`9ma^+n`o8}Q zN3xFO_m%wTe=jEj`@evDb#r?sN0ztXS@O5`6FxIg&uUPZ*^N0SSQ5I*J6pMq4kZgQyd+Kw?3EY>63Jn;e*C}fj=JbZvi=~Pss?-oo^;;Z2;R1@u z5o*wMjS$v;Q%Vr%?Z&@U(#CzlUiG(L@x)kaH@R%ZN6EAs(BAm{OBaJ+Y|4T79~Sn8 z@ZZr_H+Khf7gwhLeEdM&{eNHAD%CvmM3+GRe|Cq?#8>zU9h!Z-6KXnG3xP6*E6fRz zgpH1InR{gioKj?B>)F5Uy%k1x{QW+Z{PHM5?sway)c3X?82U1Fo{0cs92(~D*i~L# zby0Wzc9<{M2dW+Gx=cNY4R?%hs?uM-q1iFiAM9j3OW~KQxuMxBKNfIitySqKdhAL| ze}+agnmph*+cqCmXcBVB<3l!>;U(sYL91e3m{kmw11JUHJpK{0h$A4sXPu)xs)EaV z3=vn|SV--ii@WcHk0>nDdd(CYNVg}Qt*7UR(iKyWv>!a0UalDSfj$T@#brv%4Ux?rZ*(lCNj=bD13e{h#ng7#vC*Is@P{oveWBgV7i{R zbov%LWQ{UL3^3{u{pv`QYI43MCo{(#b(=D-Z)Um_92D@j-HLu3dD4C3VdWw|sDsA6 z&$oD;{gV-bJqV$2XFVIwUR>(N)>&tYI+1ChFzFWuN%{UtvVW?1>}j)a8)7ije}L@_ zq%9U!wE2cEwUYh2E*^iFJYksN>4&;le3dxvlM!5iU^H)f@>qTtw*1vr$3P{h;-?6!=RQWO=dA4oWoQi zK>j4%hn?tFyix<>R-{=4Hzz6)qC92`n$9CWfO969IX3}eib zr^M^DtzXsthIWtQV=^y(GsSZ3N>6pmF5J@mOI9X)kN-miSG~j>NhKLhR(5wKlJp1~Q0Dz5$s(FA@6_zM4%YDWZe|K^RMk3wDnOORx zAtCZjw$TKwD8JA*^AMw3Hg8<{fF;5!GJraCg(*ax{AF+XJ3c9nkcvJ&MMJ zBMVfu7Cw5P!CdU4vBl}D*TpPlV;!Ap7=C)KynmRFft!=DzSw2%==@hlW^HKPZuU(l zGz6%LstUy|nRt{F6>>?U$Alb&tnMZ4+Rlvl*-sill%lyVUp=fcXxU++u5zeuFdv$OX z<@V>0QziB*e~?r5_`mrFm}+dXhmu$?S$0DTMgx!lD>=Zjt82C~ljbq}Szx zThR4A-{Oz+np>W^*uqr)Gx$S;@M59hUd=3Ef-}rNr$7+(f6@jA1C+nl=|*9+jr8>R zBFHdF2^7V7@uSI&j=Srxt##jj++LD*OB>mgghq3(f0Q#Gw20*3qv>e8I3&L5p1v3B z_X26}$JXh3Bl|O$q2861Yz64$i+Q|x!(5>(OfVsx5joPaS4;>!Oawg^jeU{fDqWcd zK7!G%(isFw>$-;c`G&Bv7G zfAb+#chu1h6mKICLih56{z;cHpb}gO&#_Rjo$aD&s4u ziK&u^oc8CmY@Vi%S$@8V%$0L6HPJa{MK)xSN7flqtRS5|k#oMN6dO~Da?Re5wmCq& zdnKNZMXjGcj&;gHo3-JP9Sfti7Vl0uf7u*2E-fNs8=ayLKBiWPfD|C|VPbMD$Rve@t2v zTv$WuD+?3*appwtQq75vIQgkzk{C=IH(X&+ksYcBn4ZrfNThcx^tW-Ix1y9EkOH{c zs^N)=9l2;MPax3mYe$*G8|rcMfZNhB8oAd`%6U^apj=_J;;PzPU;4zQwg-ujm}bLp zKwLW?U|!yvVw_@Yxo$zr_FXW7e?r0wGGJb?4<2z3BBVE$=1{rgKQ%_7m#eW%qo6j# z;sa{TGjN+81veV^wJk_Vn%egH6WqhPIP}&Q%p4*KVDoDS6|N+$%>|^`IF;M+<)W{X zHU_cE1*nv&!pLgKDJm2Oa@TdVzI}*v=c)=~P0OQxuIe|P%n1rB6*ZvU8fPvi<-cQPLUj|V>WEQ-k!yj>Rj$#sVdj>fJ3exs zx}@bTh-&DB{()%+i718Z4?jssq#=tX>*t-w)*RDyGk!szer^@we~aT#G{{_KHniOo zQAWT)!BX_BZK3LZTB83`73v&Vg~Ot8pyDpCp$5}mX~Xo)GUYh$0kf>ACwj%TNLwgZ zF~GcdXNby`OzuWE823gf1(m2-I(A2^<^8qwg2L$vlv;#r8JNpyE~Qvnqc%aAdfQOw zJ@cR~e2T`-^x_yCe^6-l)w8#Ayf{@>kgL^_kQu4rZv&f%M zJ)Rw4n;L;LnN)qPlcS>bQ7-;XlBAq`dJ@OxlS;VRQTdD0e-?$1!txd3eS^WJqFO96 zi_lIqFXW3peY&%2&wMj}gBDnz&?snk{znR+fSTSM+OXcFW^zLHk00_2?JM$V_#F!D zjYM5B`{L<0r%tla#2t%HLNxBi1y@}v-Y3MU2+rx5rbo1n2ki^~@A4zfn{vIA`(Kci zmu&b*dm_ACe+L3rsv3D8%%QZwCmp^A11XV3$%zVO3~6DJdi*hBuu$BD{Q#guvbJ0X z={tjN4z?(78l0V(@ z;U4Nhu=;x3VKi*-(4D#8F?~I7n*9!>irin9lwre%e_V;D`raJUhT`cPcNE4imtAd{ zCw#Wq{f3-Zhwee59}QpWAp5BMdaOCcbAHMX(yhba)gjMjZ}BxP*pj=K0o0IJGnD^g z`BIZsUG=#Oe|PXD5*wG@*}-7?FY(KpSRB!K6ZDY&P1n&*iRG-z2ZT`RQ>)xQ&BnCh zM^4;FfAH|18qy|N%}67c57@q$6=RuVYzLfjsCcwuxylJfsbb%DvG^`?r7?YiavfcP z=cARm&H>4`$!ywaz7~+}f%By;Q>NIAC3v^vQ)7q5xwGXf{_&2I6~#_jPtV@2qheE< z*f?iZU_(5_!NR1~Mq`B@!T4CF~hkj~PRUBvaAKlBMcJs2xSf@72v6&=}9lN;#mcn&)1`N%F ze+z!fb&iC*`PzhmD8>WIF=xf9dsFT5fo^y@ro?7t{v$C!klbS8wsN5#G6{UaPa8Xw z&opCN>;N%G$X5nf^L)`m(RGaZMXK@Q_tvh_pfAMf8t6&p%ZuSKgqQ;>`!LL0C~KD7*Kr-9-z0L z+%k@~GAsD8l#{*OGDt8^XqD`*N#o(7DtH@Ab0@W95L~Ev@p$);HR+3NC}bQ-Ur;N* z2NpZ3HbX-nIj9W~aj2fsE~^X?7wj&$dWngYYaEViB94ILio0sbkwGtnVil-ge@yGl zpe9vrQgg1h}nM1qI4&Mm59O6X=af|7-C8AAnqYN5KEt z)R^-a@5r?s#+AN+euh87#9w^qdb{Kru0JJBjxWLSIa8=-!&vAj7^|)?b_%=T$T86X zzgh$Zry|9MLN5xd(T)-A{KLNoj^qF!=OiQ}5OFLnt*LCMdEl&jhyL_5e_Mb#Yr?VK zf$~kMo+mCqCrp+tnfpo4&Vq5V#-TkMY-O>$Hl|53kTpNzVS*-yD%CXK|28*%J!0WO z_T!XQ*R5A{a-tzD|>mmy5H|j5C|B}qyC&QDv^Tee=?c&k@vF7~OlUei` zpYvznUVaKBQj_;9*0^^9f5806Jm>yYh`bAV!g@nGG5BY&2J9bi{@+hb1=A0tnqKJq zpZu6PLjz!5ce`wnT)PT%!i8I25C;j_a;y`>4gu4obh8~iUZ}HOe@AYGe0=*yqPfiv zo6!frCMIM@GRhq|b+t+8>awTNwWqW$O#^)HO?JQkW!US!dOD)_e;>OY=D#bb{#W*? zWMScI?)G1b9^0O166oIweXR=VttloVy_kPxqs`=Kf}yHQNmLbN6lDLZIw$3pz>OPrmXt*Ln9w9r<~#y=5`uVLCS^Mspp(phP|pVVTPRS zz_w;uRqS|=+y#omLKt}A9S6Kf-RJvnU3~NX1;cdz;It5|Woc(0DgQQjAIl8p; zz$AmshB2RoAfJ7AlmR@r?vl8Hm3w+rdUDmdrk@0^$l5JNX7#CyCC*L4^v~6;WA|D& zp=ahxzC0ILe^plo{2tmI?S7sBpNTth4Hy(e6C!-Lcl&N2IQ$~hO?bjyo@FNxz>?Y3 zpS@MQNoxD<*4};7#1*VH^04+A7%qp_TMz-P#{>vgiOe@p1do3)5ONkf2;vhR*FUAk5o zB&#{_=*udwY3D4PdTMZVHB#fl;?VLzUgQPPfwA{vx7v1#jL`zhbW~IwU^HCPA2jrL= zr%wx-e;(pD!WU~4o{*J7uTkJE3@3tyWaoH^3~Gh3Q#{g`s-i67bT*$f81MVz5fP6% zJyN*g_)rH=I`go?=nL-*B*h}B7-M^HSmWTN+NiTvkJ~1WX<@fgv7vPY!j>qMrrYZe z$yQsl>AM0iz89JaQvA+<)ECn&cfpwMHm0&ae+^ie^;?{$jg1>S7vke14VfP=I0ZQ# zYsH0_+NDU)PbWhX%uWtP`0eV3!YT|=Z8AsK&Q}Z4zMhwVh0)um@}KM=|q5Ctqw;Ky_IlbL0Eh!pD1gq zf8kAUo*0sZ0D47Go*=pvzeYB`a?-@gKQkURQ)5nX8q(!`7-;`CV1aE+t$Imw&4R(? zZ5$yNflQf@Y~&y;f|?D|uPJf0M-y6Bb$W|htxE9u-UoUKN4=;gcHLir+2MUNyR2%!C_1%Tc>RUjAy6e*zHHer{`wW0A`e-;7i zvlF((q_4w5LuM=GjTTH_F%b9k@CV2i-Vmg2`I272lL<7u7V1P(1Ju_>+h4I?#@}u9 zd5E~I2uQ}W-KxSW$e_o?LMn>IJ0zN@FY$hswXAd9{)^sPFyyD`I3x(j2K@i95G?O# z3b3>G`TykNS~^puxhJs*7sy3xBd0M6sj0rWB+U4m+{FMds8)Tez*t@b>PvtELw(JTr`rpDS`6f0mTwG27E@ z&Dj00$CiD`ZapJ1riPXBnN$I~Adtiz@4-*YmT=`Dgk}QEElW@Mg4Bg95b?W!DFZJQx6CsL$@gWSHiXt(rtw=U zOe^k7DfpV$wj&sJV)HISA$&NQMyJ=x0DPkiRUk+^?Vs=zb&n-Pf24PSxCqoqCD=tr z*DVL5_I?rYQAKuEb#4)uHs4yH(m@C;p)v%oR5ED=dym8JxW_mePosF5sMQD|0t0>< zZ9iOf9pb3xR>tAmJ-R`fJ|~4=W%ur+GvBo_wOn+}RMe6KaO_)ivyh)5j4A39_xgzY zXBV~yeL{RNV4NgSe_6uL?3NweRxL@F2a%SA4N0jognLxr+&Ij(EWBJvlsj|~cZ278 z*dM-@OCJHA4t#=sZRa1yR}NhN>rWq;eh?O@Ce&x?YVI? zzuhR~ldRfcv4}Z+2(U!8rjV|5E@(R*R zMA4rW{i+u@zWcX4sj~a{{LU-_m~NJ8LRpCTCOk~ea)V^`6482BcM4Oi%LA0wp6W z%4&FN3spFa37WAOV>M%78nP8J zhV8K$9NqZ)+PgqZ57De9U8y4YwB4BH_rAmfTw@ADG{KkS+2!}z ze|YXLz=*}BIL1R~O=2IP6NtRr=@A+agBS8L);Y7Eb+z-JZ2AN3eettyKMy2uCE|ORh`ByVeA3oLb8TO zj{1c{6x?WLU-W{M+7k5nbJuD}`TMT%==o%J9Dv>u&S!UPo?a5K-sX>g5!Xsg7*yf= z0RqyC^graxN@o8qeDAGgZRTe6U-02f4SyBoTcB>;K$1AfjEpWy3pP!=P9ofXe|-!l z0yMPgLcYlo)va`; zW0h6o{*~6-5gx%xyPOAYNiJ98FE}J|*$XcaSD>^FIE241zu|`Kwm{(x6wRCt?^R9hBHy)#>*?LQdue>^c8fMGAq%-(k1J1YR_i2J3}o7dDK!{j3?@*}gAWfHh; znr44aMPGiZ8&|PbRuBzvGEHi9y%x`N_2miB5~sica#7RXI0sk)eqig)oHqF^tkB56 zr|$yh9`u=jgzA&wyfp_Z{3FPzh%m1->1uUcxjBveE`^6!4DslSe=vtDHG)!#9&UWM z!oQdC`cb01W-&VV?!X034hCqQgdEx_!mYaCH#sc+(C2%ONaXR|k-|J3cKGl|8bV5G z@I#6Qh2Uw)H&kVpiDLlW^lX;*SoT%k9w|8i^3~|8bT=#IMMR^}<+2jV@NiD&>M=VC zYAn>wO1X;+EJr@3f1)p;{Mee#`Y!D4phK~*pFrZa@#1m~KV?D=-LDL%=;9B%NWV#i zv+(99%LG7#`~{@pl7frjLER|}{(|aSAapV8h`O2i+)ba9plql<{9%UjEx_7xyGPV; z1EY>>&nGxPxk{<>6*`cDGJF7DsZ+POX z_l*2-fA{S$tdcbx*KxpT%V;}MTLm^ozK(;L0mPw@$x)%IKMz)eHZ%O2?grCrV%?e}n{wO^+w2D6$^?6j1N4I`tG`$hcIs z9x)@riCMaVBy(^1y@I)(KHr(;aT*Tp-zQg19xH#}X7r;=HksBhzSq6~kEUOKuZ{Fi zqP_5-b|MBgtsW=|T1&^)S+R~FhARX(D~CSd53KrV;0rym;$R*mzYD_qgfz0w2a^@k zf8oBI1imAPWC;m^I1UiDXSXdxRlhzL7 zqMeqQ*dXc*9dv3h2JNR*#koTfB8NY)e|MVewu7QuxyNo~Rhv0^#HcRgZ<78u&h|q) zHI7B=p~j0Q<6kpdE54Jv*e9#a)wzY2Y|oNf{`1r}yef-ea8zjvLX9p`6Pe*zC! zKH#Ko9r=T@y^@yqsBM3%*)OA_&kT6w{PPlb-)!#74_o0!8l2^oieVkkBBsr;ZS zW>I|c1!s6=2>_EsbqHm{2}_0kr1`uNKB8QBcO*6XHsUYevy&PP9E*Xjs}cX&C$0&y zS4fo5XB4aK2+lfRZE&>5WQRhve^n`cR-qZ44L;02#1aW+{z%g7yT7yj7#X!Se$a~r)Y!fb_Rohnvkp(Qw?YLp5JCbSs+*_qjyt25nP{&E{je+Vcd{TPoI ztF+q6^hHHWlnND^TNp3?T3cTaj(tdim3a>qCS~MjlD$l>>7Lg-Cwa%7GyY$fO_m^b z140ATV$xzAaj@#JcCs5CrvXM5)>9G$zC+JRt;Iz)@;Zhqtq&@E`AurHSb5 ze}z*r-HN@BeLRR49~h3?=S5}{i)rhUXshwhGFv%@h#=|`#@7Y3jGavgGaDvm5FrBT zUu6jpwCR;EWTyu<{{R1aXQe-xO^6Yv^t@ATgE zG3MHJ`z^eh#-+bI!)~N}WsW<`QsbVvTaU->1_((^f$M2yQ(56w4Ryy!B~rj@nJ-#` z>O0<`&J@$QN{551wRQSUJ3SMCKiC1v87)`V$2STWu28yE3_?p(seZ93f-VHRi?R!m zYrGNu3#mYZW}b_Sf15#iL^y00=(lZ^GsB8ayP_0c5ttsMS%_ET?6Y0Dcf8A`!87Qw zof;00#YTy`gi=wTtu(QRh#2D-xn{`IS^=O~k;b)0_@tVnNI0ar+dJi|y}k=;B`Mb^ z1kY_Nf&pxqkU~n)8!_yqEcB|RxVTIV*t*qymf%xt*vQ_Gf0RT=pBaldofBmp0Yi`A zLQ6*@O@l(C+4k3hvowc!1EmVA^y95Ch80Y51e7hC1Amv5fAiLBRo;?+u#K7wVUZ1= zA{plx*RNGg3ab^xWz5e|hi0NNZHP`{nAEj3YQc1hbcWsmMSBO;D5D;>4HX-w3`2T` zZqx~bhjMuYf8WRb^0z&hMxFt;M1XbXWc1c{YqmjI2O78?3k++c5z%ToIc7B1x21U&VnosKJb#lT6yo!X4NfJ zP^!O6KCAw&%1HYa9=iI3a@tino4CVCgjL&b0)t{gf4oG+W0|`aP*<*>R)@$EW-1Oe z?05`mkA6}XvFb1pQm|EV2{vWfvlGs#q%du8HR}@Tp0U?KU;QG39x;p|+9l?SINq78 zD@`jwGnXk`XYJsQWz_c%G-s6sUzadys9U9n4EnQ=;0upFc9sbs`RB9HNw})K=#r3_ zsa}Ase<$@gu>Pbp0kc1_IUY_MmTnnqa?GgO3F0k7hj(MlaO3A=4Uf8f)FC|%S_@>j zUuG9$59Pdz1mxyFmICsLMN0>q_H1soZziH^5k-1EH{;3?U4rA!xPOL}(Bp;KH5wAT zh%B|Y2+N)NKszqqauPU>@{O%wdB@R~lza=se@uE_cwvRO47Uc=Z9434_UeuH_~ov0 zhxuY|fc1JITpzygD5ah(r$bph3lbphiMSA^-hf(g=nWP#Bt9(VH#hRw%A+<;dMpFE z0b@UIMG%MG%?YSjNR%DsN9aUaE5LW3QsQWyB@}4q z0y1t!vIMFR*?UD#whL%TZC^C^V}v)u5>D`ktS!g96h~L@V!;SUOQlr&SNXm8<0Bb= z6prKa&=xI+Sn&Q999JLEmp_x7AKSY?^Jd2}V4z)1>Py+HF&wFoaYf4%Q) z*SR*Aw+Y#tO@=setkhAf+F?`ZF|?6Q!kzmQpb~=z6eY z8M!8}DP_zn;OU6>Sv_DF2x+|`*N7jFK8CZ}7^#A0M{sgXR2wX_UD#)wZ0yNg{U?wS zJI|;Ax0mxRUGmX-w+3nc$-2_VATN z>u#w6X769W$#?ongEf%|hM!{jD}_F&^K5FUqv-R0i@~w*6W+pcY1YWFIg@YyjOW<9 zMUPv1Mi=CXr1F@(t=ukRIU^U`G~8Afh-HGt?{~?|MfO4*-58A3e?{}plXsYp`+f-< zA$@xM^l)-={nWzaFyV>)6($?&`f(|Dxu?9hHyTo5O)709>0qeH(iB`YC5-fms7${t zGvACgjXk*Bo^5hzC|+^eb|6wS4Df*y45H2(;>{_TxrFCbX0{uOZ@}p*`dcLM)Z7l<+Ut#?CIH2DBI4jgWbPZRuf!Q8_Ywp0wRb z<;As>UlQmouqL#eV&+!q2|I2yAWia0OwO}dpjAd5f9)4%JPr?}FWZ0dYnkoxIJX9J z_U}=Ohvw3HY z0D7xdbMx(t9+kfM?zA2zSYrIddMa`I+HXNaIC}0e>QN@~Q9hUEYc}3GMkynIms#x( z!hY{ze_>o&a+5S5G>vKfh68d5&`9%dqtBSz%I0(EPi8cCh!h8s&_@G<~YW{H$7dCm~2GHE@Rq~HnLckFz{0CtjGq; z>N4VzQ;jPyH1bsath2u1&6riW)$85YYx2wFixPxdUVt62zHPygnxf$zuD{ydQh}eC ze>-Tc#pvL)^fK%~A7-BB8CZ>a$m)gxYY&w0K|fK+0T}19SYNyFWTuAl0D(V9^+ji^y(oo=@TSYi zJA+|Ry-g(zIz!T_Ek3L#7wMUzPN<7v@@#Gn#68SQxM8A-@JSUZ;+$?QNvyrF?L{V%D+$sa>dbzO51J}rWaUddgZJTK z*`@4Jf4o+qO%3tzQP!$-6Eo$x^GPu^KX|*cl=(c48otVA2UP6BQSrI)|;Y*vSFv z3_hID8XDGce`j+FWwkg0>FFlw#=~oWi&V>RG5$gn`}A7Bt0kS)%af3LBj|h$rOv_l zB`{_xMjD?c{WHN7J(9Lpw3I;rXF#ovdVkSW1R+>&5>l`nFi{u}nvII|g6^l^LwW)4 zIPll<&!|Y$u7b$GyrIaby&FUA(0_%K z9|{$#eZNhkLf!M$h>WfRKSoE$S7g?Zum@=h_Jm?6T6t5nw0rou7@V{gv+g!mYsB4k zeGWg7ykUm4zC3?d#7P&~QzB%ya=)3JEu@89w%xgy2p-}_gdJVIv`Kcr0hEc0*Tc@u z0wPBcL7g#E%cjgEgaG_S#dajY8h-+U@0{>#HYaU<&ssbQe{d7GaK{mHE?+R0)e~>l zEl<`RWa>SW^@&3BAsy>0*Xi#U?kK*~Ati2LzB7K`fw=Jno7{8Fh7a5IgcgpD-r%Yi z%)?Qxp&!uJEAuEDbd=5ugTw@H(Do67vX|Vj+!?}g;qPF@UvNHj^lOxcB7b7peAs82 zQ&lI{*FF$Cl8QF4(Y{#Eid{*!n}t&Wq?^OeaHLy+ay?GJf2h*i`S-spr8pSV&~pD1 zxIg|0+#LVEf!o8{^`AVJNzBpS$=%J|Mf2ay|ByVobb#FSaJn^JZ#>8C>~nFlZ0|q@OC1rAO{-P;B{2(r?_&-BGE5u zA@ex$wFat)aA)eSAZyIs_#Efxwc)!8Sa#;6>M?&{vxk~;gBT2o5Pt}qYA|=(<{Qwh z3an0H=oSZ8bX?DNX{@R-C(^gxac^qsNHdJig^T@@*}(7B2M6_R{_$2TSf61i6FJ)v z+-Ay@T)ut&g{25Vc9V!Aqqo>r-65A}X@`CVg@a?q!dhbrQ4IU2v8j{kNw910g8=DD zV0_h%YRFqpY(3{BK7Xp>Y?o!J!B7l{bTZ|QI|PTcsoWs%c(@V1&aT{yuhl_02N7Iw z2BX5M`m;hmY6(`p;j4(TiT^G-X~hXdU%+MM9Z9q|B7xKUYH2*){iUEVF);}@nG+`i zSkcYQLGQFCDEBxk3%xcau=H?SOiomqdy5!$<+bp{EHCMYB!9s2#%l4L3!leq@Qe){v}D_Fg%i;TG0c1VWNr0VZ-;&pT`-x`do zuA4;lTI$7aDYO9;*xJCNiomhf9LD_wnI_JG!TOd&7aoHi1S>wZJC6*GI*Kr6I|hL9 z7fkz6UAq<8G=I-cYK=-BbvK=nNuXu4cY*q6ltNK?)D5;}+OS>cOy{wEi&LvV1G=jH zGHj<^_!m0@fK43LCP0s#rs7FKz+LaktnMQBCT z>QSm|QGY1P0TqxH1s7zy6p`9hX|1xT6%_Y|V28O(!XzNaBR9u$zdQFecP2CUzm``M zDf!mtlIPpQM?aGO$)vBM`+nN+g|b5H5#PF@x-I&74c|273)*Zh#6CZ;B6>()#A`UB z^Y?}C#iE~gz55<>B<8o9x((KsPc?Vf{mx}I<$sqwD?M;`!@6a)9k%5!Hm}NVPu=5( zE&DFD8!WuDe^^%g*rj;x0G9pyZhgu1hjs4HJa$MqM%9mF&b}OOe&U())xn{i!;<4z zmhGcTP2(%(Qtv&%nHLV*G%b<*%{B*hzq|O}{8;P5jsrb`O{dedEV*vk+updk@_zA+ zlz&1uY1XJik()H&&8FU7hv@wS^BS``HC4>8RM#QHtT#&5@~etX84_MB_l3)k?K!tl z)AYj8bEQ9i;!wo)vfmY4pCK{aWcYrLP@rpN-;|r`Z56LIe6}n6&3#z-qTCh(yO+&N zELykh#O*JN-wBM{eX}U|E3**Y^|gz;bbmLxwPf$LT;shH*BumJ?QwQur>=ayxWlZn z&@#kbzth>K;#h6Df&Y9+QwV8*&TuBj)M zv_{6K*9`jaFj`^a*k1ILQ@=^-!B0C1TKmr!?``?V5R-$%xs>9#;e)6&o>gm0+J8~M zBOZ=MOD{%Se34@ri%E=1y0V8m9mR~>|88fcx0$|NqbK2hc|GR#h(YI-+{2gdo0{}R zI&4}!hTfj@D%N`F;hpnskBk5F%(A(9J|k_T{`Q*z52b(ke84VkYt^BS%-q4ilzy$Y z{)LrmGXmew3Mp95xMRP@ystApx(2dzCm|WyY9LU=5Pw+P+W6Gq z<2eYjSyTQH4WV`G(A1a$2@B+`?3g6Zb|>P1&;#N&b>K?E7b+t-SPIU@M7F*t4@*Kh(=-J? zO2iJDhaeJT1aTlKv5Qnt0)MbH>imChyfk(VRFX63My{m%HI}QE|1<~kPG05Z63`+- z(BeKMXzePckPuJ7Vo?#W*z#b(iR16@%0Bk|;{$3_s+U)?77WWGQv~rNnX6Z;VFqGs zl%LF-PPOl7Z2A?XMBr$BNouvV8fvHn6Hb4qS4XyKYJp)>Yzm`uZGY52Ww#K5lBPqq zm)|)%2vTJlaQ*T&&_u;Tl${`dAscib9?r)_;6I1SKc!YruF4OW1xT|4!y=rd*1M>x z`U*V2^p3J{ev$y^i^qGF(9&zXbBBsiak7ZI3@KH{_)aiv9)ab36sZiiHqA~My!mVa z2NQbXLX1spvJ01^Mt|zK`!i6ErC|7OC6(j4`|Ols;?vj9!LS4z1y!=qCHLMa7~BUy zFAO0SrO$JAiV}jwf!?90TlCg`(Tjqr_*e_}H~Y_yFT_xe7b-@n{mL@|xuf9ZVzCZE z{7L>&=B)VCtR^#fG)*?A>LW-biOq*sTRT+{9)NbP*p51pi7)PZh2ogXlN5h_3DhD;ZH{e#(dN6M> z^yH795b)mpG+~Jh`(yZy)6~{o?0<_{;0(1y3%1O@RDaEquL%PMoa96W%k2+0G{=J$ zM9L8Os`TxP%X`8-lknJNDxZV_-5|$&iP-CbCC*X=Wb|u8sskMLXZ{nWiAy-kyo`6EKcv$awq(YNBXS`~ zyMJiQ0|XNi`<}|u_|E#&4w8`RQ2^4i34`pk4XW%YIUYEeJK>!AP36$;aOQ9jbt3b9 zkJJjO4g+wwW&$V}o=Na#*nuM%6Hd>QnZ-4RB{(WDAw7GlZj4~qfTKVWMuL{cjABB; z5**fukTi8@N>o9PU{k-v>z~mc$?8h;N5{?1KvxQFnCKx7`S5Eob4tn&55Mn}<2}&LWVg+bv%d+qTKR1>m$b$$lGLg4oe*q~03j9)yP@_!& a0MT}rlz;(A0&Aa_-+%#21`ePB0001mo=<21 From 33418490ce224b85044342ba9fc782e19e07ae33 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Mon, 12 Jan 2026 21:28:16 -0800 Subject: [PATCH 10/25] Jan 11 comp --- .../ftc/teamcode/PestoFTCConfig.java | 4 +- .../ftc/teamcode/autonomous/BlueFar.java | 97 +++++++++++++++++++ .../ftc/teamcode/autonomous/BlueFarPaths.java | 61 ++++++++++++ .../ftc/teamcode/autonomous/RedFar.java | 23 ++++- .../ftc/teamcode/autonomous/RedFarPaths.java | 11 +-- 5 files changed, 182 insertions(+), 14 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 7add005..fa85e09 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -53,7 +53,7 @@ public class PestoFTCConfig implements ConfigInterface { public static double HOOD_CLOSE = 0.01; public static double HOOD_MID = 0.04; public static double HOOD_FAR = 0.01; - public static double HOOD_AUTO_FAR = 0.01; + public static double HOOD_AUTO_FAR = 0.04; // SHOOTER public static double SHOOTER_CLOSE = 0.70; @@ -62,7 +62,7 @@ public class PestoFTCConfig implements ConfigInterface { public static double AUTO_FAR = 1.0; // CAMERA - public static double STATIC_DRIVE = 0.05; + public static double STATIC_DRIVE = 0.1; public static double KP = 0.015; public static void initialize(HardwareMap hardwareMap) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java new file mode 100644 index 0000000..58b19dc --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java @@ -0,0 +1,97 @@ +package org.firstinspires.ftc.teamcode.autonomous; + +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.DONE; + +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.geometries.PathFollower; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; +import org.firstinspires.ftc.teamcode.Utils; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; + +@Autonomous(name = "Blue Far") +public class BlueFar extends BaseRobot { + BlueFarPaths.PathState state; + PathFollower pathFollower; + double start; + + public void nextState() { + switch (state) { + case FIRST_PATH: + mecanumController.drive(0, 0, 0); + FrontalLobe.useMacro("outtake"); + while (Utils.timer(7.0, "outtake")) { + FrontalLobe.update(); + MotorCortex.update(); + + feederSubsystem.update(); + hoodSubsystem.update(); + indexerSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + } + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + + state = DONE; + break; + case DONE: + break; + } + } + + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = true; + Utils.clear(); + super.initialize(); + + state = BlueFarPaths.PathState.FIRST_PATH; + pathFollower = BlueFarPaths.getPathFollower(state); + + hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + + waitForStart(); + + start = System.nanoTime() / 1E9; + + while (opModeIsActive() && !isStopRequested()) { + double currentTime = System.nanoTime() / 1E9; + + FrontalLobe.update(); + MotorCortex.update(); + tracker.update(); + + boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; + mecanumController.setIsStatic(isStatic); + + feederSubsystem.update(); + hoodSubsystem.update(); + indexerSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + + if (state == DONE) { + FrontalLobe.driveController.drive(0, 0, 0); + continue; + } + + if (pathFollower.isFinished(0.2, 0.05) || (currentTime - start) > state.getTimer()) + nextState(); + + if (pathFollower != null) + pathFollower.update(); + + telemetry.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java new file mode 100644 index 0000000..da85018 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java @@ -0,0 +1,61 @@ +package org.firstinspires.ftc.teamcode.autonomous; + +import com.shprobotics.pestocore.algorithms.PID; +import com.shprobotics.pestocore.geometries.BezierCurve; +import com.shprobotics.pestocore.geometries.ParametricHeading; +import com.shprobotics.pestocore.geometries.PathContainer; +import com.shprobotics.pestocore.geometries.PathFollower; +import com.shprobotics.pestocore.geometries.Pose; +import com.shprobotics.pestocore.processing.FrontalLobe; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; + +public class BlueFarPaths { + public enum PathState { + FIRST_PATH (FIRST_MOVE, 5.0), + DONE (null, Double.POSITIVE_INFINITY); + + PathState(PathContainer pathContainer, double timer) { + this.pathContainer = pathContainer; + this.timer = timer; + } + + PathContainer pathContainer; + double timer; + + PathContainer getPath() { + return this.pathContainer; + } + + double getTimer() { + return this.timer; + } + } + + static PathContainer FIRST_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(0, 0), + new Pose(0, 9) + } + ), new ParametricHeading(v -> .4)) + .build(); + + public static PathFollower getPathFollower(PathState state) { + // TODO: create secondary + PathFollower pathFollower = new PathFollower.PathFollowerBuilder( + FrontalLobe.driveController, + FrontalLobe.tracker, + state.getPath() + ) + .setDeceleration(PestoFTCConfig.DECELERATION) + .setLookAhead(1.5) + .setSpeed(0.75) + .setHeadingPID(new PID(0.3, 0, 0)) + .setEndpointPID(new PID(0.001, 0, 0)) + .build(); + + return pathFollower; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java index f5ea0a7..1a23d3b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java @@ -10,7 +10,10 @@ import org.firstinspires.ftc.teamcode.PestoFTCConfig; import org.firstinspires.ftc.teamcode.Utils; import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; @Autonomous(name = "Red Far") public class RedFar extends BaseRobot { @@ -21,9 +24,23 @@ public class RedFar extends BaseRobot { public void nextState() { switch (state) { case FIRST_PATH: - state = RedFarPaths.PathState.SECOND_PATH; - break; - case SECOND_PATH: + mecanumController.drive(0, 0, 0); + FrontalLobe.useMacro("outtake"); + while (Utils.timer(7.0, "outtake")) { + FrontalLobe.update(); + MotorCortex.update(); + + feederSubsystem.update(); + hoodSubsystem.update(); + indexerSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + } + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + state = DONE; break; case DONE: diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java index b9e54b3..5c5a54d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java @@ -13,7 +13,6 @@ public class RedFarPaths { public enum PathState { FIRST_PATH (FIRST_MOVE, 5.0), - SECOND_PATH (FIRST_ROTATE, 5.0), DONE (null, Double.POSITIVE_INFINITY); PathState(PathContainer pathContainer, double timer) { @@ -38,15 +37,9 @@ PathContainer getPath() { .addCurve(new BezierCurve( new Pose[]{ new Pose(0, 0), - new Pose(0, 10) + new Pose(0, 9) } - ), new ParametricHeading(v -> 0.0)) - .build(); - - static PathContainer FIRST_ROTATE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) - .setStartPosition(new Pose(0, 10)) - .addCurve(new ParametricHeading(v -> -Math.PI*v/3)) + ), new ParametricHeading(v -> -.4)) .build(); public static PathFollower getPathFollower(PathState state) { From 6c8243b95337e6095069c8e99f7796c9347cfc68 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 15 Jan 2026 08:10:07 -0800 Subject: [PATCH 11/25] sloth load, progress w/ auto --- TeamCode/build.gradle | 8 ++ .../ftc/teamcode/FieldOriented.java | 3 + .../ftc/teamcode/PestoFTCConfig.java | 8 +- .../ftc/teamcode/autonomous/BlueFar.java | 35 ++++++-- .../ftc/teamcode/autonomous/BlueFarPaths.java | 53 +++++++++--- .../ftc/teamcode/autonomous/RedFar.java | 2 +- .../ftc/teamcode/autonomous/RedFarPaths.java | 13 +-- .../ftc/teamcode/autonomous/Test.java | 31 +++++++ .../ftc/teamcode/autonomous/TuningAuto.java | 76 ++++++++++++++++++ build.dependencies.gradle | 2 + libs/PestoCore-release.aar | Bin 98608 -> 95861 bytes 11 files changed, 206 insertions(+), 25 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index c988850..bf43315 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -15,11 +15,19 @@ buildscript { repositories { mavenCentral() + maven { + url "https://repo.dairy.foundation/releases" + } + } + dependencies { + classpath "dev.frozenmilk:Load:0.2.4" } } + apply from: '../build.common.gradle' apply from: '../build.dependencies.gradle' +apply plugin: 'dev.frozenmilk.sinister.sloth.load' android { namespace = 'org.firstinspires.ftc.teamcode' diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java index 3747ebd..be79dd2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java @@ -38,6 +38,9 @@ public void runOpMode() { tracker.update(); teleOpController.updateSpeed(gamepad1); + boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; + mecanumController.setIsStatic(isStatic); + if (gamepadInterface1.isKeyDown(GamepadKey.B)) { braking = !braking; mecanumController.setZeroPowerBehavior(braking ? DcMotor.ZeroPowerBehavior.BRAKE : DcMotor.ZeroPowerBehavior.FLOAT); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index fa85e09..bd6b344 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -23,7 +23,7 @@ public class PestoFTCConfig implements ConfigInterface { public static double mass = 21.7; // lbs public static double MAX_FORCE = 2220; - public static double DECELERATION = 76; + public static double DECELERATION = 35; // ODOMETRY private static String leftName = "backLeft"; @@ -41,7 +41,7 @@ public class PestoFTCConfig implements ConfigInterface { // DROPDOWN public static double DROPDOWN_DRIVE = 35; // 0.29; - public static double DROPDOWN_INTAKE = 80; // 0.47; + public static double DROPDOWN_INTAKE = 85; // 0.47; public static double DROPDOWN_PUSH = 35; // 0.29; public static double DROPDOWN_PUSH_AUTO = 35; // 0.29; @@ -65,6 +65,10 @@ public class PestoFTCConfig implements ConfigInterface { public static double STATIC_DRIVE = 0.1; public static double KP = 0.015; + // AUTO + public static double HEADING_KP = 4; + public static double ENDPOINT_KP = 0.7; + public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); Cerebrum.initialize(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java index 58b19dc..9c905fe 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java @@ -1,6 +1,10 @@ package org.firstinspires.ftc.teamcode.autonomous; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.DONE; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FIRST_PATH; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FOURTH_PATH; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SECOND_PATH; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.THIRD_PATH; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.shprobotics.pestocore.geometries.PathFollower; @@ -26,7 +30,7 @@ public void nextState() { case FIRST_PATH: mecanumController.drive(0, 0, 0); FrontalLobe.useMacro("outtake"); - while (Utils.timer(7.0, "outtake")) { + while (Utils.timer(15, "outtake")) { FrontalLobe.update(); MotorCortex.update(); @@ -41,11 +45,30 @@ public void nextState() { outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + state = SECOND_PATH; + start = System.nanoTime() / 1E9; + break; + case SECOND_PATH: + state = THIRD_PATH; + start = System.nanoTime() / 1E9; + break; + case THIRD_PATH: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + + state = FOURTH_PATH; + start = System.nanoTime() / 1E9; + break; + case FOURTH_PATH: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + state = DONE; + start = System.nanoTime() / 1E9; break; case DONE: break; } + + pathFollower = BlueFarPaths.getPathFollower(state); } @Override @@ -54,11 +77,11 @@ public void runOpMode() { Utils.clear(); super.initialize(); - state = BlueFarPaths.PathState.FIRST_PATH; + state = FIRST_PATH; pathFollower = BlueFarPaths.getPathFollower(state); - hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); waitForStart(); @@ -85,13 +108,11 @@ public void runOpMode() { continue; } - if (pathFollower.isFinished(0.2, 0.05) || (currentTime - start) > state.getTimer()) + if (pathFollower.isFinished() || (currentTime - start) > state.getTimer()) nextState(); if (pathFollower != null) pathFollower.update(); - - telemetry.update(); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java index da85018..2afcfaf 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java @@ -2,7 +2,6 @@ import com.shprobotics.pestocore.algorithms.PID; import com.shprobotics.pestocore.geometries.BezierCurve; -import com.shprobotics.pestocore.geometries.ParametricHeading; import com.shprobotics.pestocore.geometries.PathContainer; import com.shprobotics.pestocore.geometries.PathFollower; import com.shprobotics.pestocore.geometries.Pose; @@ -12,7 +11,10 @@ public class BlueFarPaths { public enum PathState { - FIRST_PATH (FIRST_MOVE, 5.0), + FIRST_PATH (FIRST_MOVE, 2.0), + SECOND_PATH (SECOND_MOVE, 5.0), + THIRD_PATH (THIRD_MOVE, 5.0), + FOURTH_PATH (FOURTH_MOVE, 5.0), DONE (null, Double.POSITIVE_INFINITY); PathState(PathContainer pathContainer, double timer) { @@ -36,10 +38,40 @@ PathContainer getPath() { .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ - new Pose(0, 0), - new Pose(0, 9) + new Pose(0, 0, Math.toRadians(0)), + new Pose(-8.5, -0.3, Math.toRadians(-45)) } - ), new ParametricHeading(v -> .4)) + )) + .build(); + + static PathContainer SECOND_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-8.5, -0.3, Math.toRadians(0)), + new Pose(-8.5, -0.3, Math.toRadians(0)) + } + )) + .build(); + + static PathContainer THIRD_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-8.5, -0.3, Math.toRadians(0)), + new Pose(-67.45, -30, Math.toRadians(0)) + } + )) + .build(); + + static PathContainer FOURTH_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-67.45, -30, Math.toRadians(0)), + new Pose(-64, 15, Math.toRadians(0)) + } + )) .build(); public static PathFollower getPathFollower(PathState state) { @@ -47,13 +79,16 @@ public static PathFollower getPathFollower(PathState state) { PathFollower pathFollower = new PathFollower.PathFollowerBuilder( FrontalLobe.driveController, FrontalLobe.tracker, - state.getPath() + state.getPath(), + 0.2, + 0.0, + 0.2 ) .setDeceleration(PestoFTCConfig.DECELERATION) .setLookAhead(1.5) - .setSpeed(0.75) - .setHeadingPID(new PID(0.3, 0, 0)) - .setEndpointPID(new PID(0.001, 0, 0)) + .setSpeed(0.4) + .setHeadingPID(new PID(PestoFTCConfig.HEADING_KP, 0, 0)) + .setEndpointPID(new PID(PestoFTCConfig.ENDPOINT_KP, 0, 0)) .build(); return pathFollower; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java index 1a23d3b..2729807 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java @@ -85,7 +85,7 @@ public void runOpMode() { continue; } - if (pathFollower.isFinished(0.2, 0.05) || (currentTime - start) > state.getTimer()) + if (pathFollower.isFinished() || (currentTime - start) > state.getTimer()) nextState(); if (pathFollower != null) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java index 5c5a54d..a0714d6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java @@ -2,7 +2,6 @@ import com.shprobotics.pestocore.algorithms.PID; import com.shprobotics.pestocore.geometries.BezierCurve; -import com.shprobotics.pestocore.geometries.ParametricHeading; import com.shprobotics.pestocore.geometries.PathContainer; import com.shprobotics.pestocore.geometries.PathFollower; import com.shprobotics.pestocore.geometries.Pose; @@ -36,18 +35,20 @@ PathContainer getPath() { .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ - new Pose(0, 0), - new Pose(0, 9) + new Pose(0, 0, -0.4), + new Pose(0, 9, -0.4) } - ), new ParametricHeading(v -> -.4)) + )) .build(); public static PathFollower getPathFollower(PathState state) { - // TODO: create secondary PathFollower pathFollower = new PathFollower.PathFollowerBuilder( FrontalLobe.driveController, FrontalLobe.tracker, - state.getPath() + state.getPath(), + 0.2, + 0.05, + 0.2 ) .setDeceleration(PestoFTCConfig.DECELERATION) .setLookAhead(1.5) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java new file mode 100644 index 0000000..76b7252 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java @@ -0,0 +1,31 @@ +package org.firstinspires.ftc.teamcode.autonomous; + +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SECOND_PATH; + +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; +import org.firstinspires.ftc.teamcode.Utils; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; + +@Autonomous(name = "Test") +public class Test extends BaseRobot { + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = true; + Utils.clear(); + super.initialize(); + + BlueFarPaths.PathState state = SECOND_PATH; + + telemetry.addData("endpoint", state.getPath().getEndpoint()); + telemetry.addData("point 1", state.getPath().curves.get(0).getPose(1.0)); + telemetry.update(); + + waitForStart(); + + while (opModeIsActive() && !isStopRequested()) { + + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java new file mode 100644 index 0000000..c1d2da3 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java @@ -0,0 +1,76 @@ +package org.firstinspires.ftc.teamcode.autonomous; + +import com.acmerobotics.dashboard.config.Config; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.algorithms.PID; +import com.shprobotics.pestocore.geometries.BezierCurve; +import com.shprobotics.pestocore.geometries.PathContainer; +import com.shprobotics.pestocore.geometries.PathFollower; +import com.shprobotics.pestocore.geometries.Pose; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; + +@Config +@Autonomous(name = "Tuning Auto") +public class TuningAuto extends BaseRobot { + public static double endpoint_kp = 0; + public static double heading_kp = 0; + public static double deceleration = 0.01; + public static double speed = 0.5; + public static double look_ahead = 1; + + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = true; + super.initialize(); + + mecanumController.setStaticPower(PestoFTCConfig.STATIC_DRIVE); + + PathContainer MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(0, 0, 0.0), + new Pose(0, 30, 0.0) + } + )) + .build(); + + PathFollower pathFollower = new PathFollower.PathFollowerBuilder( + FrontalLobe.driveController, + FrontalLobe.tracker, + MOVE, + 0.2, + 0.05, + 0.2 + ) + .setDeceleration(deceleration) + .setLookAhead(look_ahead) + .setSpeed(speed) + .setHeadingPID(new PID(heading_kp, 0, 0)) + .setEndpointPID(new PID(endpoint_kp, 0, 0)) + .build(); + + waitForStart(); + + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + tracker.update(); + +// boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; +// mecanumController.setIsStatic(isStatic); + + pathFollower.update(); + + telemetry.addData("decelerating", pathFollower.isDecelerating()); + telemetry.addData("X", tracker.getCurrentPosition().getX()); + telemetry.addData("Y", tracker.getCurrentPosition().getY()); + telemetry.addData("R", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.update(); + } + } +} diff --git a/build.dependencies.gradle b/build.dependencies.gradle index fa68f63..b9793d3 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -31,5 +31,7 @@ dependencies { implementation 'com.pedropathing:ftc:2.0.4' implementation 'com.pedropathing:telemetry:1.0.0' implementation 'com.bylazar:fullpanels:1.0.9' + + implementation "dev.frozenmilk.sinister:Sloth:0.2.4" } diff --git a/libs/PestoCore-release.aar b/libs/PestoCore-release.aar index 7f162ae85290b010d5f98d9c502c04669a9c01ce..5236f62e94b0ce9d280cc14bb1464f84f013ee3d 100644 GIT binary patch delta 41662 zcmV(qK<~e>f(G^M1+cAA3Wc57@Zcf=09Zz|w^74^e~vM_b zhZseZT{i7;V~)TQa)7(|&orTg6y{6Bj>4~QEzQs8?}<(BDrYs6vSUbqJrP$aTL=|~ zfUX{4f5FH1#Lt`X7uKtg`udtcj<8!WGjHGow}ww2CvB|H6N7Z=~+wGmjP*v;2b#ogKWz!g0~IgQIcI@mSOEj|D8(T&wd6zU5#z zQ!D+w`wcVE?cy6r97zwbXYe8&ny8uzs)y?3f8g94rQqE-N_C3P$`G$jN?a(JtDTvc zT$WmAs$p7<5L zzsG)vH4{Q+tx%rBu5fz5-DofS@lgmH{0HhT+s>E;)@l2Y$zNzLX*Hb8`$_m=KEMSM zf133cS+Azz(#PAg2ar{`6ldxy`y3VXf2Q$tf)C;b_MBpBKt|&R>Kv9vonr>acu|;O zCXs{PO;kl~shcf7Lw{BSQXgb#z4{g!YvQpu7r_@}Y4L`^0Ibr4Y;**okGwSwA|Ul; z28x~6>Ri6rQIA*?OS((CrCSR<1I1 z5<%Kz@i6_WT!GZ^oQx#lY*h+4+hsny`3i*0-5yp;Emb+P3oN?uq1xJzwv^cXwmdcF zW}8(~;f1B$9@trqIph?DI`dI}GqUIVx2Ku)7N=}1#A`5GS<4P5&3*5RlAg;}e^AlS zLl9meqimO*6wr~1k2$c6L0JRbveu`a0`CjdY;>#am-cUrgY(7wxS0Fl@0@8e+UOc(^1Z{j?%R*26Wh%U@LX25*D-rV|NRQePs7g z1ZIrYt+qp47{w=tZCm4hGyi>u4px}xIjTuV*2-0WMawzXRUl)tDHoGH19SC}*lT>n zOLlcmG^V|wx62BqO2*TS*K+X@-ox(ApMK>m^2|jJO7{6I7)ZUvJ6hR-e|~P`$ZXlr zrs3VAeYJv`rS*X~IAL$0n$cej*MS?aLnEI^D6}WgBXL$U))EBnEx)Cgf)n2hc_d?H zO}(9bb4O#C3}yeEoAjP#ZVV~a0S6Cy5D&iD_wL$g3`t~Xfo9EVbkTnF5WiE+_kMt3 zO)yil(`}7HGSdpDkvU82f3HY7UJP-i)xX?Iy{zxY^$@Sk&ilB4oQ`77l2O2!X%nCZ zp69YqiGu89=IF2CNYS^!51dG1!CZc7H4I=%f16NGbwB8^n*D5k z8CY=xs3~5H^<2Z>9+n?Ovs2A<7dZG+F;s;HHO(3gm-&!olE=o5-Hl^Idz*V;-n|UzZH@!D|X1p)G3% zX4VBL^vHd7qGy(Cvj*D>N5yssHyLGBQkHxCsqoLuvW68oe}MFu?)8KJL=r5J#`%~% z7izXul_RaTi=5i!FK)E<*{)_2DUB_L=>(w@ZsQd4fH5)#8nmqy5kw9bt07`IPnqpF znSTGH)hLK-W9~Nn>%Mt zvZW9yu!jFCH124^+UBp1hQ{X@NBq~|7+URd=)#$6U3AHbeN~@wssx*FvscJV98&7CJ%^Q9JEle>EM7B>Vi5iV{VYG>HoPie~dW z;Cd6_w#u4vJB(OPH92VC0&20__W@-p&5Dc&cXlY_TrAz!p(Qc_CtsDoSiV3?nfDuU zet*P=WcIN%!V*_WtVBtR8>NvxtQgkoM%isxJpLK;HP$xVSyn`b1A_InTU)mb^&&lx z%<9ASf7ws0zf)U+Cl=gFxkHRx2_F6+y@ymos04$xTrdw=mRf|T^dCi2f@8bz zbO~-P8~#WIL>3pp9et6AS8neVDg^a@+Q{V*e;}p1CP9e$2?)x*Yj|ThlsDQxL?iD;*gwsvps>hr#Zc^2>Kzt?@<1OJ6}cnTQWudM4$gn=_yfWO`G-~ ze;W}72uR@n6wtW;3&i~Yyx#u-Y5qfeIoVbNR~&8hC$W@#JOL?8vFs692E{^!P6S!Z z!niqE2o?*CFmxKP0nmu+&iT9N&gAj5^%k$3zvmY8)$$XJ;6~Q?x5ENx8fJQ_xBtsb z_Rq}c(=4GsNE$>e@$bBlxELl9IA6wBe}P$@&F$&ht1hIFStKnc+eHIYD6<9tJb!6a zguKZpN__5j$h&xcp@yi4B#JK_B7AAeONHy|Uq_$C+k4l&x0t;)5(CF+-}*uRy(7d5 z5l#IbGB`U{ImrE2uQ$um7n^k6_d8xv^j)CXN0VlY{AK{wre_|8G z8gbfz`?nG;RHx^N7^5hrAnTZ$HaJ$=t;PzcR;Rvl6$f1dyqdJ z{8h(5qjwgh5MYH@a645wZ}-LcjYjx>qzSY}0QPQ5%m$Xp+<28mhpPWN|DcG((Wh^q z&eF;~&FPt@xTyFVleMc%RI~3%f957H&q%z{T$qj%4Vu&Y=2-nx2)(a%Syl|REK3n| zGrjIfx--$HWWmIXTzmiUgY&FME6L_!{HSjTn7HD_#elV@U!&{>b5|rJPKj$*C^iev zigEadnzE%_1bG%UMx(gphvH}!8{CSl&LH35lDODkWe=#e;x_P!&ZeY zq?>Z`J8+^u5hf0mQ+g^fI*G)+R$g#7y~Nv@g81u3xsDP>^Aq(M#|-ooC~+HTpviXw z??%7AJk*&Uenc5nMHj}LPUP}A&(W_V;d4LWYm32o!s=-7nq8rd!V*coI|UBI2nk}n z#{aI--g#YU8so|jvJaW4e;_DRUid1E|J+wNh|UC*~${8P6*C#bE|4LiJu%((PW zZnk3IWAfp`8!$)ZE{3blxqYM@x|}@}O6Q~x%5^k=<}m^h7adN^%}NUiP*&huGzV5( z5qC0Soc@5~K!aI=V@-b{q{xtZ1$i(y2B|jY&dA{zooXEQ{Q4mcf1C4<7vtPy(Z;T=jyoZ+-=Bi z(+TR_0)Jr^P->&Re_E$+vBDgWUKDn1xSs2e$u$&TuL?s6H02*IrC)I-2`-P8QKv~Q zUKD_!P))I_rS%`m@uxOY(_8omgZe1g{e^Ll;Dj`Ow<2{%kDTEnlw38*KQAf@(EYpN>t$sz6`ZX1%wAFxWMHDsGlmvO+2lcJe<>S3L!g+jNOpl;WvpJD zNt&$u>egXRRqjGrzFkSP1-{;g^EBWgaX}2Wz~A(BQUP_brpWwfO$1f1-&VQmF1}adVWQv z4G#TjCDzfGN`~$<(4bbhFVAo1vs9fHpeXAr(z9MW8}xpdvpv@D##~u?L=i0wViW=v zAqhTls3<mogXMqHd9 zr|IWhdJo4zYE$}*X$d2_CA=(uKBMo1xBds_Bjah2-K<_vo*hAz7u$Nb_sjOfNA?5n z%l6m%f1QCFa8~~)j|h~tA{?7Ax<$8nO?rF68Qsygc9%JN1;}~b)!MQ%$eyZK4K^~H z^&GsI5mXjK+fi1p?%k$%s}<&_?(lu3UH?6K^tEV~8*%<8EeXqJWW zf1r{2D-+0FVX--2h>{JXZ6oMnxWr;{weIlOngA6lpTagzOj}}Mj2S8n@=&X~LKe7T%Ci_hH(bd4ZxMcR& zd#Y`?es*0=&Of%c6&uMDc?z8je3wDbI`iXmBBiKfC#52v6)54~?1tiOv)BFRe+9V< zY(F3$LE_SG^4VyNa4q{=p{4f(O1fPztQ>u*U|CWc)hQlbE#1`uOd9d3R$W(PS5VmmY(q4h3`y5P zie(3Pme57oro5UG`kgyqv?A9%c9x#nbqACUA*((H#gY<$GHlc#J0Rhr%g9W2c2il4vFKcEh#g@3O5eTS+=&lBispl*R zA+3wDv3({VfqU4F4-&8)#&RMf35TXpixZb%8e;{Tce6?4K_{xl(V<(IpZn^6| zd(A6=D}z?+d55!=BG2D8z*gl@y?g8ZK_*m9jPMz(`Q;&`aOypHf1HT?_t)w0$90~K z6?C^hEMsmoK_o?TQASi%+g%R%n{jGj(*76zW7Q+s<8Du|tg_tc1b#uqUz2(Ito1qU z>zBWB#{>wk@+x?@lQP2(RcDR@uKVKOEKRByluTi%jsY(+pJHC9l$QBu*SFTCQTkO6 zv?r}x!GelYa?kepe}Z#Y_$wD|IfF2?l}<|+Svm!@c1{YZz8$JH`dQh1d4G`o<(5z$ zCiXQP)=HTQKvU_H9V5%?(EGi!5`)$kp0TQNItKQ0x!$qv>TJ4jRnJVThiX@JSF_^T z&D=5-l00`6(=#ss&%3KY-y;qSuc-j!o`F6W4yeSP0KuVaNPS_FhIGjo z-FbqZ1bU_LN^1RxdKg!s2O%NSSNCtFQ-d%o%~CQaWZy8tWh~#}cof>5&fxNLM#m@M zn8zz=iCmI*e<;r5R>z0hJ?CuS&fL8qvL$Nz%~dINdq@q0Hug?riq>9#C3ELLWqoK5 z*(JedbJ3M-eeCDFGIp$ote8v_Om3LdMA+lt*|n?_2cxf2b*$N=3ge_`w_&88^f8H} ztw==+(@cVuH`L}Jz-{x*k}VD&z-&j(RC|JZ=ZW4Te=5J1gW{McP$2{n^?yKm;aVb* z67dEl<8m`h*0A`W3I9E%B}^B2`+x!gt^JeMnEy{xny96di4EXC$5_ZI;A)`pBeD{F zGGiIbhO!YBQ4bj~fhU$AP^(5HgM%n1)4(VfSnx%KghxaEJqV+Uw81H#NDwD&?qpa8 zEXf5%f2_MM3(kpu3#EPnCuDJ&bT%h})A8JQx!>@<~#}bhh=L-i*0O6k8VAkH~l&d{| zt664oyGpsy(qH7j+t{f8DzR>jV(d<#XF6T`e>Uq=j;9-xDk2Nk?ZF+TnkoB5$s7{Z zciXE~mHy4)Y|$=X*e!ZtL#`3-7jUb@JfG?`Y^`zO_IRcQHOX{xG{OKy^;eo))}JL@ z<~2-J$1ZYXW2z>{12wXgXO#2Xp--Lip_#;v7p6eS*jMf;uHe$;aIG5yo@p@JSESFe_ViIg-%urule zh@qX=o3(v)raPd9>a^qkL6ITH4Xg4_V87?WdXWy$g#kc>Yr74$W`eAT*lRblJGZKw zzJ{#YX+P6z(1h2;H8xzWNu|C4kDCLDfB1>um6l;=ft!>6!0e|2H# zN9}a#KxZ{2a{KDM)~Zxxo!gC#zwlBAB%*NHcBQ`g=3w&^gRao&xjshKEa6pPgHV@) zC(%$NGB=f%KF(`!x%2bK&k*h!*F3XuNq82)`(WW6u-F&6>NCE0dbn=KDCF&NOVrI) zUhxu~#LnHJQaFS)z9tIzAK>X9fAGaP0FSm&C8VK|wvm;1a85rQw?$Cb|FOIS(y9;5 z@(3wd8`YiT`H8!U`xKudl3SskQkIVA9GJ;88Y(1s?+7JuR~nhS4Hv_%4`eaJ)ay4s zom^WC(39XGHJP21C{-;W1F;NP07@C=*DclqyD)~&RaSN|pxeVCM|U;ae`S?s=0i@T zQjy+m#~OB(#(8mTPwZ!na%Wj9y&_3pZ0rA>sJPt_^tpiz;~&4fx3fAhz-*_2^2+x* zl(PNbSpPmz4Vqs6gt9Kw|BeFsUqV^Y$i?Dc^3FzK#)jnKb_M8 zR<2m$k7Utzpt+mb4gbkzY`5Rz>fjD=)^MokFCt6gBSRp|5H-O~ z$K~f5I9ww#pQCFh^k6@#_Rir!d;+QdT1^g*$&68A~xjd+XpNoB8{rQnDO4m>y=EJvmY<`8C+#rr?> zFNGs=*QmN)N?;_~#=nkXFECi(BoTodm}B-HgKu64YQM9-)M2@f4N(~5pQ1|9QsbdO z)zBxbn>-T5>@>Ohf0_Os>G&DDN=+!PbHy0JzefZndL*xPQ?$z+Ui_$QGT2yjuHt14 zz==wS^V~crrcbOe`K1@)7E`UKy9$?*~8?(3p^b7ZcSqwX{(S{aRpDP+N)zH2(Vw@ZF?hRN z%w3<7jxlqQ?or0@g2uA7q>=E-Z|wmy$n5Q-bMI1;0}k6B^>q9_p-xjPL?*TZfHjGe zpUb^>_?1tA5&`d!8(0|YM2BvIo^pg8G>kjHR7TNQnKq;cy;xLE+gA#fe;TM7Xx|9!a6th;ASm_Xw8=Lj+P-rwdEHg(=08$DBAAuWyp+gs z$G{z@gHu_P0^a`SH}*IDFW=us?m!=RT2O#n%i9YmA}U2z6J54_EmBT&K>==)68-?g zf7;~6E&*VJCSSfFCshlmv$7xtrmPn8gX_nve|0C5-42{fF8*3>FdwLt@LPMu06Oka zLpb>jPxuBW(&aBi8%aHBGnw%N;^O5qYc|%Gm&qL%GS__4c6z|rdpYc=cb=e<7!oY(-!h>Pb(6aX3zR8_;`LKFW8F_>>L_K)(`I zU@&j^LsW3|=a^$K!7DUeqUM5=(wniWh1k+<6r|D3$rdTVo+UU%7(MR+XD=ESSyQHJ z+>y>WaQKP8V4G@n&>QEv;y4?o23RiuA!2pF^Uu)XGfQ_kB~YA&_s{;UeT_^zobcJ#VX0oeJQ&UcgqkMyt&V|NP8554DbF|~iNaYo zwjVw}O_p^tr^6#miVnYXyrGimXvPQ3lh~U$v+2LZgGMg95;q3c!baNF&C!Zdm3XU1;=!ce?oGJbU9h6&Xhoz zH{3G6$s*DAm!1Pv@$ekE-7!UM$q7iNkc^@ea zegQX<`FDEazRPpS60lYly%>%*{lL%Yp`Fp-Iu3ilR!O7cB*+a*n8?2J@B)6Q;E@W& zJbn_fee6rlw^2aMf6 zy2^DZ;+m;%ss%RCM>r_{^=7bBCIw;FOz5zFxJ8x%w%@Y-ereD447{XeLE1_9-41zW zdb`m8fTOD`k&rmOHR6r7D_5P*t6Y~F7aap~$K&f3A(Ib&fAjn~twG_v1|F|7E~$Iu zDG$t=*C+B1iNv5rjfr~|khb0X>{kB+OA2|A!V4IQAA=j?e(|s0{eDk4kICrd$WdVJ z@k$%%l{#xdD*k{MB;92dCQJ{FBy;rVs2K0 z9NJ8w1gSjRY_IlA$PrRm4G0g%{hC3SR^s0mSM%TOfBSAekOx~=s9?%Az!XbZy(ezt z*T1oHZ*dERxF4QWR6qaQKSvPftc~w~tZLx@OH?OeZ)0Qc{tu`VwE&n{OZ-cB*#clH z;cE9^gg}$y1Z6;lk%o83yv%1_YwPM7>gPtp>*7@t4#c;z~GWVHpMtyw!eL&iV^kWG2B-+)3%=YxI3e<(^xWr1c%$ZGAogOm+ z+Y;-`vzV{5zsB2)p0q71MF(e>7b?oKr|X5+awj>dqncP9b!N51Me+wHq}zD1Yw$T~ zChsq)@x2^mYTFhzk?cS6ifAw&CT2{pW=7SI1J*L`-(@hUaJTofa zg)wDmPWsuHLg6`GA~CE;kmG%SWJU>{7Sc)^tc#_z2;8%IuMH4crr?P$TrGj~{2+Dy z{qMSantAm=@Bdhf|2SIq|H;u}026=>z{%)e{{3%$R^5u&%non1ea(zhqlO=Fpy zIo@d|%mbr3Ys~^(_HZ_0Rd_cn7|JzAe+4bzbi%$oLeXEilgaSl3POpP9a&OLi7IPy zHo_gVqyDGw>~XYzJ-q=HbG(--dliv#Ccd|s1`LM$8LWn*h0Nh|6&4maK)@;Namp60 z{Gw2{ITRlb1tVOEd{a(~_#t$S5#qni3V4yITQP`YWMqWRPPf1A?&pQ+b%@^0E8HTjsv~FOV9xdt~N` z7&IAkDPkRf{30TJ4D_2roOw+xJJ}8)Yue~&!d_3$+VZ}B%iiIB*=&5-{yrH&1nRhp zhXgoCQKc#YbBZdmj{2s1(AdUgf28CCe5mZ5ec^(40Z5ow@r=@dLf4y=ABO^RI z!~s}vxWiHlamKNtANDA)5e>lu@s`=Mo$G%|GUFXgKmw``T_Tdq5@-n$=Km}w1sIE4 zkd!-)&v7C)x3l2Y38M@Vrqn~kGSMyWcW_{^BuG%yNW#txz&aea2BK`Qj9ZBE((6PV ze@qt@<4Em&mV|mc97e|*Q0M>oy%90sv3yMjrf2T zQo2qXJKT`TuP{Jp=zP>c^4^vO5n%Ja8M|&jWH7No{K?-Yjn6;$f9}cq>AO>G6XaXN zgmXC5V{wc0>SQHHdW0nHAM6(03-E*PhO?FD48-)_JrSPAaB2ky33xVox$Y(YCVOOV z!XSZHp)j^8;Ka|wT1`~HjVdYiC{{HV6jgB?Zn3apvDBt7^pXk1{6N|xKv14<5r=UI zL~~_XSrpI>2F6Rce{G8z#4=rLTpKQMnm$dz!jnDoO3Lqw-oIBqj&UFvg!|aQsFSnl zAgDKQV<$`-e5VYJ_qm_rg&r~{JZbrtr%*7&HUKBmI_#<&nT2ew0vfR|a;~aRT zzB$HpNvnil*$qJtvzM2Ff%HR1K^h*(&W5-*$EUnzne_HYI>`({|^tj^lp)VKrl@ksCyf59XRnYq6!Zg`bvW((q>XI33e z3r|5g=Wp=8esyTa(;Z;)5TBt?lWnmC=hPJJXWLbXtelwI$}^r6QBu+d*?<*_UZXyG zqZw{UT@)+Hqz{<^d@(YU;I*hGM(9>(R_pj9)lp&r_0r|j1zL`PdfoJaocN5445`cM zg1wqnf1YCCe!7a}l6$%?=|o;wDa(qfKh&%9x)0-}WjO;q@$a`}2%BBfetKB>J4h*W zH|A8MCqpN&OS>`=N3;<)))8;GRl}{Cu`(_qKQT41sq?Y4SOaQ!gX~#-u2^Fvfl^+O z@2AEhce_%2<06S+#vjFFTNr)I4%%015;d zAL(Aur~fT6#1tW$cLkC7HhwP@Mtp zme^-E4Lm{{6v!W`NiapepOob4qhzAS6KkJiWfx}n*8Rh|BvWBfEKsxE5tPTqd ze^Vh^hP_B@wa&lq{+t+^JR7<;_W6<4?VJEr&IXX*8$mc3O{g|zuK33KVVV(t3*XO@ zh;heKnebs+qnIJoN8WmXdzI9g1i7s%0?*K+`9o8AdM&W2>X9pZFhK62{uTl+Wm|kT zj&}rK;68v`zOykIPQL?_|BF@YYUYDue{K_{lZ~A_{J=3%nT6f^8}nfV;CXO7851?T zM~*u?$;i#(hh4jd#mQCpRZ;Dj&3dqEV^ZUW@o>>HqHjK8zlI|-6SdRCZiWyg^^@}I zi+dBNE9_kv)dP34Fya||_+f|05cfHE^@jNGscaD@Ou+{h2xtWVf7j{$pQN(?e_#u1 zLhEJ?qyHdY-uJU)5gSRdQO48OkuitkD#OUt2g-@ZMS z2_*z_XwbYC!DwLTBFh>>rrOSre?7~IBOti9!P_)?Ed=4d__JsDs2Xs2o&k*M6kpm; z9*;;pcg!it|Lict0y%9lXYWlCg3ta{0`Lfdb6yJ579M=gDwho1m{uIywA4&a7t}WH zSL~|;)9u)?UvmSPm=yM*FYB?Aw3HvSAA(iwrZJaokd4}h6k^!2(`_7>f4Esk%qNA4 zpjlF-Pzjg!-CN>PD59m&spK6!Z47%-C8kAlpY770?CL#1Kr&jLeIo<%k=d)1{zS+{ zexT~23$%)XAH!IT7lZVqBTXZ73Ga(dDM%WEOYRPEl7L8#?M86)!*+08T%P{e4>xe1%e4NNU@6p3ZJai(4nW59cDsLc}KqVFLj5 zBIDSfY67-i1Nw*t3L(H@sWx=+NIGQ6*;7iku9jCe`mqZD5$f4l@4`Fkz$|7m717>$ub>p#u18%DE;c`==aW|S_vP1 z)zuLf^pc6UU$?W?72FCZ14e19m9xe|g1k=;p04BNDXBS-)np=WJnD&paYI#z4=OSC z2wB*v!uxOX9Aj6~wudKIeHu4Muo`bLw)~8hV1ZL9nmb>i7X@!z% zZF7>mrZ4%h@oH7H$ZyhR>7%4Dw^@(g5q?{SGP`Eq&NqzbT(eJ+znPJ6b3vMY@M zP&Oh;;pG^<)K$O8_y8j!kqV`!Q*@L#Blu+f4JGRtJE`F^#tz66TsJ-=l`vR}Iy{(s zjR>igfA)b#gl(Fg0+(y1bTv{MdpxM%U*s1yNcBicoJHQAiW(&&$ThSv8fhi#iM~O~ zxm+X4MTGh2`O#P_1$?5u=7dm^_rww+?Jp?Uj1UWt*`pxgFT=Pg?1rK!JapLbVjZiz zn}p}yB2Tl9!pUSa>p!uE=T@q{=S}wr4kEr9e^Bi4_GKA3`+mrY+zL^nckeJm`OWfA zMR5fC$GsL>!T8!e+6fTS*`jXf}gnu?Hp;!IdHAHxwcRCwu%a^7&X7TXp#Jd~P z<%xUIcGIV*|9)uz$H(& zwA;NGp|)b4rs^a-<0u$3>tmQecGfe_;Sxrrlx8-dL(TN1@vDyq!^K zuJfc=#)!q95pl;P4q(>HGY&_4tilF)({l@fF0CfsDuD=#IZpEL$@-$f z_xh_Uu7dgmA`?p;k#P$(<$qNie{?@&OjnSRChppUg{~WKsoD>oU_t%!q&yEZrRIW+ zL8~1Kh^UdRu~z<&e$$d=i!>-b=j{GM+sY_9sd!WN)1k(ZR+dr1RP&|$mf!i=^@jXA zQKQ!kNn~|_AQD;l`>cvb_DLsa1=`ca!7c4ID*_Z6OAPOMitoPP)d$=e$);rbg!UT_+~&NPXs*)jFc#G*nToOf z64vs45{n`Pi@ZDo-4K~c2W%-j0%pX0{)4uP#+aTi1mk4Ff#%0Le-~bld`(ha@90)i=WuFFd+S~6CVXxow^o{+2=lS;zeo>zMsV}( zm69)HPNHnJ+hI<=Baf5ZG^!1GQN87{R`-|8V_~55T-4)Qf7ge~kAr()b|=*I4TCLo zx1px)GU!HdF${iraCY-Dj3#ad>`U`SR-Ogv7LxR4R}8{~HRwHA-z{4@i+xj@zShTitwdsaXt7lIvNEF+}SYIhKzV#-lNSA6;rO zCVt6FmxpvefBJLeS5>SHH}gZMd_eKpj0%}Kp+akmSe6%%RZULWIYmf_1}AL?zFNZ5 zmyeBYtJzUHvW?n0nC`?!0QNPP6I&qYh{9U(;%5N95Oa`0vLL=fXmN-l(J;wBd^E;C z$p$zL`eHv`!ZCBz$zaz^!fBD8S8!!X!$A=_@1*s^e~ON(Tv#;n6tN!ct&P&c;+4`O z9 zKQ*NUfs9I}Jcb&ScMWlUHl$5;BM$U^ZdL5b^1kU|PgVD4rS=|z2S?hJT@E_6{z#(S zZh7zZUK^9YARD&joT#3A2;BniBCSTxftGX4^x!gz$Cqxj2MeX^lLVI8TGOVcizSLef8Zifs;9?EvoIq%viRy{*}^1LyFmUO z(2FUM>dr#~0ePVU0Wtm`1A2Ss|K!1F=sBaVV*9No&}miK{2g0c1I9zCKnz5OA!DWh z3nNNfgMe#mu~b>9yz+`~qAg19ms)I+D`lM)XIQsnO^nokEaZ_4Girlzp}zPcTWf@F zJ6WmaH&~xBtfRlU@XPy;LO3vlD~_?Xe{H75AW!ryO^+ouV6-_gDSw^|f59?pgnhyb zzSCj}-g%McPxW#8wDI&U=Pa5|j|x45u@_=ui9}${Y8kfL3Ft+GwMIYIWU};|G726l zkKBR`4*W)nKYyOqNb4SlxaR(pQg+N;I@L_o{m3K_zP)|b-9Hsv5$YI}gUlQHfA++A zQX${(%#VOVZcmGhD|u=EI#$tPuI`dW%XfjU?P;!25Pw+(oYdD-t?Ze*_Fs#Ro?jvI z_V+yNK1;U;F8YP_dO^Iu+N=#MxtAN3e=X37qda1SwS#c$_f{{GcSIpYd2KmO;$%N{a`dWvif-7~E^#jC#*RxEP`$HOM{mx-AYZd?T1C$a9ShA76lc` z&L6C>OK;u5H#S%-71w>xe+La_Km1b*Kj|mJ1vXh7G~^E`EjszaIu@O)2Y#fOv;@Tz zlxRp2qc*EAyPvDcHq%E_r0Ue%ELC~BPg?RoJvCf3Y~#gl+{c3t(sS~aeim7jeeEZl zFf>=F$!~x+(in6d;@2)SRa+yNTmR2sX`6>X0S|A(&V)J_; z4gMe+FQ5GqqYf5G8?%Ye#8_@BjfcccmH>5$lKct6&uD3i;Jlw<3fm#-&l^(O=qXV& z>@jsfw$c>#a8~>je~w^TLM@coH@*5RHi=_8}2=!WqFB!C8-pwwTP?V>vy z@IGQew>-tC@UM>)%1pS@Lh|H9l89hGK-e_Ea_PTOufW#u^Ea;Mu4d*yiS>o3Fo|ng ziTh<9X^uOMe{vQ7^(a)-McYGfAcWe64z_d#`NA9ZM%LAmUcTKxc?Zgld*K^JUXc6& zw`>{Eo>9+HGUA*NN`xg|it2-@(aMvu&e!=hX4^*> zx;yAwNH=UnUFwerYo~D1#>3gh(#ZTQ_>m=lMEfehe@alf#uu?nU8UI(+Gr+u6$2CJ zed`KNZ;Za6H@M9s=0o@sP!+Pi#*Kc(?dfhD_X0dGi?BNtXJe8w(P#gAdLqq)kqdeN zc}94+ODWE|-c!P6y<$Fp_pIt~@dm$84BTcmyke#cf#+ZJzgZKjSuRYV*q>rtTtXZ} z=xxhFf7EX^1R5PV8Us1e$4<$2ryfnl0;Q|Hn=0hE+&g0I1R)DfS$N}Kcpm{xqva$; z{4m_=%#p^cBY_R6x$FeDjeWhDJK!ylOOp7X7ZE@Guy2rt7gFCShcn7K7L$6a0eVPk zrzG#{WylJ@uq}ixQ^O()ZarvVU}~z}fd7i$e{MKjf&TWz`jex|-%~>nHn|X7{}tnA zM#c5qh_spZ$2%ws(&6N&-G%B|H8sp1dq9ddi{gzYROxO5saGd3*I)SV)PM@-4Y!4a zIL#o`FoaAt@|FEUMsNS4OFWjm0935!DY%6O*sH2qW(u*z`yO^&0RAcFk1{~GLV4ks zf59y6o2uY z7O!ycmO4pRA_*Lk!7XGzq2aS<8I|oAFx0$?kg(z4{Z*#d6!{rR0;7n~;JLO>+0Y7f zP?o?knLF^i38bQqt)Q9^=27%?klLh@e_PW%(1ikVRaC?^>60BDF>3tnmA#-_0a7wU zm_I_Yp$I<+YMZq%^!8xk8fD!MroRSC_E(76YR>%TSTKIa7#^<+;LwUmA^6xbr#JEq zVfqH}Wla^+$PyEKR4X`|mS<45&`bVKJ&$~4t$o-A0U3W(d&V&v8Zz{GtwB=We~C{; zyl#whHs`RF{+amm-_SvSkA$K#2oTW8KWl9NOLSmi5)H75$1{8#fNcw0G%cwuTT!c?8SeAvBqSYin~=+s*KDVI2%n9n+TZdh$*y?)eC!puU&9eO9xh*_ND?BZl%9^y+dp0S z(?qMeyJAUoLI+Uwt0Whu_9ABXWr!;y755 zn}P!-$hn_j|9*(sJCJgofPsL-K>v56+W*TTc5(rD$XeQ2158DgRRB(I_Wv>8N?Feu zRTzzbu}BLwacM;LLUQ?!A?h$X8Zu3A0tu7=H9*S0B~`d8)hkmv{(p4ZRyr4Nrut9# zPd?+j@@+riZY;`;jmUZ6pElT+gUcN6>uy#-Kfe!zU1$zkO%YiBQCx(?cfaE%_HQ3JiO>x`@+N(6W`i7Okxlr3qhiSh;_&a zv}ls^byU+958VOC1b;A%nyy&#Uc7lpq122L2|Oi>D+MJgg=t2DX`6jkJ-$gcpOL1N zPs%k+Y02hzSOET8z`0u0E{Z6B@^v4c%topu25-pziv9(aP~hI#&hm`TG@wH|7SNQ| zyv7_)X88xeC=;^Kvp<*?C$S1eK1GKt#DuYExvYP;Kp zb@MRp(=^d%sy>D}L3!bC@xA9QaI`i=lO5)t()USD`u}nEj?tNSUz%`iRcza~ZQHhO z+cqk;&5G}s6@S}yQgQNDcmHRm=UMNXo}O>_Icxns+-LLJXYcC-WHsU4<1@706a@K= z|Kb=|cm8bvz+R^8Vt$YLSn836zUUB7t5d;MwCE55emId^#_$gT=@opS37(~FzsW0f zU$0B?)8i!TNt|R=B<+?y!X{lN?f#Ra>q4|LEN82Dq<_PeqDIw|_w0T04`Q!$6=1C& ze^rSK0tkrvzpqYm4z3Q)|HCtG$^TWRukdtwI-6Gsv4MSpE8-eT&k!b}pHWg|5K!dX znMNL=X;<=jdBktz{DB_2luA-Px4^!X2U%y@s=~x;rpLL>C%!wcIRpZ~{2&<j>-)$fw%=^=N&2(l3*Ceq^4+t*VI6STN7U zqzj0c=G9Mv>>n$1_={V&X`9L1iKxG$u0!dT*<((H=7q+^7<9wEP;#zW?Nm`q{8dV{ zzwr8K)6n0aDA&*m!Hp@|r+O!Ff{hx!qHml8j(^A7e$}Csc4~@Z`60aN!5Jnhe=sDA z(qK9C*dd$RSL$1I=n3d-7FF72LjAB%XAk`sUNWFiyOS@{q zdb6$li-(K(>cqzS^K*#eyEFUI!kwufRbIs_*pk|erxWYzevcJH9*{CjCc>N-Uq>ye zn}5hu!1tkT)QtxMa&*PSXJfs3QA**Szv^!T%9qxQ`%@5r2L#4&{`eu3D1JuZ?YdOg=BfRIgqm$0ZTPy660e>74 z_N=c;U`3(`n+lmXYxCV8;Uqj3V?&Nx27evx^&SkLp&iWW^6TqzvF^FdTIqGDkrIeQ zn7oUgo6C@77pA&T(>&%SWGu$3%oeY?7rY3dS z0b`3?f=Xtok~sZHbxCF|cu^M}z?x^|Wl+7+O(JB);vgXrR^0GwA+a^PawxM*LVx4h z5>dM!1pQ$Mjss=(NDfBiL-(}^u092OzL$b%HBM859d;3L;oE)i+(~0|zoKLnr_xlA znR;1=A2*q4!*Kls!;rCxmi+`hu6L1&Z^MM#Vm~3BmsQ2U`)4jlXd0UqefV`hPOC|LnEX^mP7X zuz!vgS|+GPOh+ijSW0-KG`%lNdPIUQ>5z!$h7ege!Gp^Z`hDAgfmombHXFYJ;6v87DF zdR(^sp)UF&P;+{%qq8B#lFi3+z0- zr{YbMBzsH^6y#Zp?Ba|QjAdfKRkg*H!EJ;+J|c~Nwy2Vq63=LI+8pGLd+zD!DFC>B zQwrgGW)J)+ImYRW90Bi%c&5v3cLFA0oce|5uQ-*to;Z+xyAX}gE`O@3B7{o4gF!U( zr2Oic#>ZHtomq0=D^Y!fm(nl6PH#*NT`V%NXd9&1~vOE3t=-^diFfF)iz%=GiM zsCP6Z-LONYiU5nssvN)k8LpB9&T~{8+6<%}A;=-)Tw>)X!J4Cmo$hE_3B{j|$sjJ) zMU11McG}qNfWe1|#0W$}(Q!_&KfU5_3cpf{}3N&hN~K zg-ew^!4|4YKYMoh1roJz6>h8aEE9e1@UvEVr17>2NWDrj@cBa`hZxDw7@?oU_H{5~ ztZP3<5z-#rar+oN)YTf+@B9Yg?8{f8>o$?y#=VEPYSH@gj(^!q>Gfwj^BM>!2N;Dm zIe!F!SUo{FUtoGv2ms`f*KIJnz)?3HiDhv@Q%kO|pp=WkDQl|bPov)#EMp0{hpT73 zGE%JgphPtvI+ulWy#Mqup!b!(2L$)i)hx#N`igL`@TtholOzVcY8oCBfL__p*$0`E z%&M6i1b<3b!++T?XhxQnOSyoxTe9U_?y+AFr{eNUq)B?fCv`y>%mrt8WQ&9PN7H@+ zkL(zJ#`>BalZAWG1Q^nG%PiPlmP7($&mvvY+B!2y3*mFpT=UQrl z%oDKLTqFRkW)y8|&I4(OD1m(W7U}h$jASm?j{2E@SFJ$*Rr&FM+PI3Dz03cIpmcFe z2*He)VShUbl4$4&z%hEfAWTlqhOX4DLC7T~wb`Dmkchj5v38Gg37 z$iigPVcq_1Wo-H~0E?rZq*3Z^Sf9QaMQk=M6D;LHb0m%d2`0CXRRn2okc-s%FpSWa z8hN(Dmk@CQR3jyINa5|w>NM+mKwxx%BaR*xk$){x3fMO?);{78HPRrr^Wi`G|9*W| zXP5nTWVw()KrH{qKlyjh#LUIT%HD!O#LU^u*xAkQUmi?N&jUpa)1O?f%dYA3XQ;Kb zjgV0CY7-jea+xY=A+{uJHa42jtSJk5$hiGx-qFvMFJK0r3%UBvsDAMB&9@j%T!fby za(^-FR*Hs`%c;xv*B*oB0KR}1sD7>wBndE3h$3=hOjFEX(>IRQ<9S_fwca|b(MFD9 z+{(4ga3w5hoZ*bNg!aURBXk>fTATLJv$b8)>wRhm{>A6c_2#XiHxFG6%iTWt8}I{2 zE2E?i69!>zY{tf@CUD|<70mO(3}Vwjw=iF zUaeH#P|gtXjI@un`sh{tXbB`y?Xo>_su*QuOtK{`rHmRu$#T`CerYnhlx6T!nVyi% zaK%1ra3adk2{bDvnVZFWm-FL;PCYied?*x-$-b8uL{RY84w2o|Q@`PBohC%Fv46rV zP?A%++YBm+!@hur)Q-qoi^;x;rNanHvKU zyThg)+LG%Y91_irq{{Ob7cAt?rD4n?OK5tqpg>QaTg(RF$K-HhG@0+1(y@?R6H%oj zw5Wy~gJB`m<$Qx|=C@z3mk{$1P5X_C@pH3H`|BNXymWJi$M(4U)fHvD&m1N>is`2Td6;?Dmz{$(rcU~EPzXJq31uXHdizSkav z2`Lotu{i*aj2{e=oe6RTj!Yy*TofrPbkeNuIM&JMmB*_a%`1pcJ&_%qPG?>+e|h@; z`ThmmFe(z2Kag^QNK;PlJY9Kb%#%EvPog!=8^wAxZ+}nRJ|0H5!W!Vh?;I60aCzC6 z3oj4b{U*zg1xMCdv28&63=z`5SxKj#4jFQuCs152hawqJPfqXl}P1MzdL|F}4ML9dq{&mh(qxfqOy(ARtz}|B9mJ z|NnIUMSszv<>QOH?PT@muW zm8E5+f#~1%5W&XcF_Zg{=hEjh(|Lih?R$>}lz$OrBTN~j5M&@m1p+gXTOsRsT%!F9gFXrSznT#c?V_sl|b0SsZjNJ4Es~-HFkfa*PO3<1#6e4i&E;ubHP%{> z^nXPe^o@GL4RR^lwqIcmVcJr6wEyvzX*chR6a)6*%oa%o5}husS(XGUtc!_%1&~AGdRk{mhjv2YS zfBpQTXt8*$!@sMUNOe~j>%%%|;yk#$)_47RGMV^V)G6;iDfok-*nXxG)IxEx)f&cf~6DJ#`8+MZsp44Q74 zF(^BXEpu&<ob>#t$Bny4(6RBZq$W3-QZkaPq}W=lO{0{4X6ir5xbq8Vk^?gLRZ@mZ!ZHXr?+?-& zkDwc|CHTTD+hx1bXmqR84W#wKx~)&C)26rHfl}~`yYh5>1~_v%)1iGT&5+>e=wY*F z_(tqSa^!7!;?)*?2ETNqbxVzTxPK+ZwHx91R1#q$z^^K4AFlQhjUbC)xYb+>bEGW} zV9;Jt5I(W1P83xt{GDysW`@{SO9{)0AXk_hMp)6Hu-jA(lj&k&klZ~lem6imXv|d` zGt`-sm`Be|3(+kefhCWa)_?5hQP%5e!jFMrMPQXJ->4aSjoMFGOX)|zw8ijGA*PgN#b=%oDYGn? zo3`|ot--UsBO|3sUwkxK`1Lzz`iAtPDMuRIMSq4k|8e^ z<=17$fw#lfWG0_8<8`w4?xZ!-E-K&V`x-D#NlH8) z0*E%FLSVM5_x)a6g4kR{#|o$EUoqJr$4X1MkeWL)d}!sCOCDhMo`2!AkEa*Z%3rqG ziVs|^&ycne3oauF6z_z5BhvyTV|2(pc7ubjga*W^9*xil1|+Q14*2nwpO4Hirn_)N zKK2<@eK)Pf;p%cQDM-D^Bj3k7)>7f=tTu~iI7tfW$1ZLIqZRg5 zK+I?@^SbyfnS(TDnt#yha>j>((PVBi!YKBw2`^`Ng}@8c?vVHakuzjtnpl-aE&|1U zUg!%`TO6<%sJyg}LPTc9YcD@-egY1Kf>bgv2eZt(Bb99Mdb7p^ zQ5$Y%+*SlLRCg$pQQo8Hc}0e=(w%m?*e&gcOsyKg>UzJa6@N=8oQrhX#f9ExPIi(| z=l5%9mM@CkfU}Fv3fmR`&QW0^&x0OK=`wF6O>w@fh^9C)Cd`qyWDgQ>>+0tr8=wG1 zA7-Jop3zp*O?j%TQmB_UD@}uL8JGTILo>*T6JcV$60!0jjXZggl3AEzUgXb;IJuJp z52)VPX?mMtSbw*hp#?alsEi=wN%u{MA5qUIr`M5*SFx7IpFvk1i=pid$kZ5~(N-TG zH7DM+bWrBqO8M=m-1&V3zKx*=xizZ|uVsEbgW$}%rs^Mvy5PqjprHvQOHsRd8$x{t z2B_YepnZo1(C0_xWkq1gTTwLw61NiUUaY|djF7fo*?$*Iu&lTcd&2{iZduU2qYE(3 zELoasqNf%b(x=Y1KASGv(cTVW7>OxvWw^dRtpD)&YX@!9QGES)J=szFfcSNknP@cN zV(2k;^qso*#Sm3!vRsqfA5i^5z-2JTjj=c$8+y3@UG)-DA}^Rh#zF$Vqj(pf%qTfv z=S-XS_J3WmFIOpGcqVepIOHsRyGnBJ%oh@l+irluul6EFRhi+~vqNWc@Y5EyrRSw+ zrWk!z1|XJ2Eo_{RJHJ})WpwxlSzESEjmPFLxW zOt`n!qORQ{8<|?&RvzlTw6AS(@njsOWJbw4vNpRs*E6A8I_#n>4L9TGksH6zyv!ip-A-H2wDn z(0`zo<)|zn$FYA%Dthv)lf|%0nGM+S7n%XUf(N&KZ(3-x`dWbmp0S zha@eAY-L+Frc17pW1a)5$v_j89~sApet(NwO2gqFrn&SpZ!UX@vo=V#>O~${R`qYHK7Y!$ zAWvqR$*}YDnQHjinxSD#mS%Nbk7skSpiu}aSv_DS?SA^ma*dk=94hfcC9B!HqEty}Mv?hraf7k9Qut zCxo)34d6CCPez11s#NhQ2J;nDZXx6Hxh+x#>pdNG95AY|1!>&+^h|bdkKWx{%ryJ- z!vE^O$+dX)#&LH<@i-|YhChMFJ6R=_Risy;2a^SNn0mm`toZE)dvZ|27v2YG_()ihuQ*=Zs zZzTC*$nAA)K~EqWrb#|SA(by8N{c}wImE+AOOK@Xc;g-$ndXc0vww9qM$MSbx8*KS zQzZVSa*|;=+D+GH^kH9ENiNThlYBV_o7oaFK3ZEz!hgx7H(I$a3_{z{H4@6L!$4nD zUQf32LP_5#S|1$MGP*-ls2ODDc7?J<;YAH*F!P1k0cP_-6g`Xr(;5!{&W{ao}kRlA!c(ps;)U z19xVxdS>Tt2yUWuHO6EAVf(4R=K_N_n$-mOTU%BY0yb#`8GlY?A1IqqICxWdZG-ZY z9^%^F(i0ISfC9x2iG6#r{l;a1R)j#TbCs0d<8q1HD!uhsy-~~7i1NHw?xxSiaKe;% zM&wKi>zl<{P&Xn1!`#2_U)pH=byFglOI*%d#gka zcMga9KQ@Q#-hbne4>b(N>X};tPKNNc5`5zis>hIb>CI2=Qx8BZOqF!we6;%bW2b2& z>|QbtHjP(0JaM#OPOhcrg)K37*rpBesZD@Ub>^=J{Gw~pwQllO zk6%1nRtZ2p3U}jup049bIy^uqylrf%0C$T_AH)#`7=J(p63M^?fghj7M0k2pkPYYs zq_+w#IROwln2q$jtXWvXcm4IEA+Y((F{0I$5BG}U$zc?Ys(Vf?vMnwvUHO|*v!ypr zePw2$sYAc`Le+Y-(uV?YhoW%(0n%frA74n)p9%P=!EAHSr=&BbaEP~zYO%-{7?_(3 z$R`)D$7*S4%kI-#psgd|XjC9=9jMc%>q=SOF zI~O|7d`cjP(DQyrA4W%t^D|RUG8tG5 zdAuQ;yw>DmH!daS21T%`V&c<~i)H1N+D)OkT0r?`RT3WF4pB?S>GEXgr=Ixx`=*hA z;eQ(E%+~|V`%J>Bi$0yBU5LaIL=BNzvHZCY?#iY#zPsLg@rOg&0gS#+-gauFyv6n@ z^45$lQ3W5RJH*7-KRDFrQJ7@~{-SX-kpBiEm;6^1SIpDI%<+FsisvQH%Kt^=qrdJg zFw{}S_I3w$;TfG6tYsN>V@HS1h2Wl*v41Ppw(Psa;v9~~heHr|MX)x4=fM>IFrN87 zOgpTPwaWD0>K2KL0)X z1pP6LdiEP$^OaGkaS`tamFm3(A5DZ%b)rO5i9ffbe)*CVi!$N30@!}j?#45dnPfv(9aJ82)0afOYFnZZ6L%Og zD?IuZ9*SZQxHj#sOOm50)Qom4qo;e0wU4LSa2)A*x2e)0dd-B zbpn`+cZ6L%$?gpUF_pC#0$ z*2Uq2MW~%Kv$m#u5ohyr{l9^CvD&ODf1dt4EQ*B@u_+*M64)Ql|9021Y}=lov&s7fTF49p)AL_k4d>3_Cp&YbzsF zzkJ0jCo&wFgJCU)l8=p z5nXqtzQwR&d~;*zid3vy5-rm5_GA{!aP{1}H65j&Edj|H4r!F)XQT~XO9=f?%7b@V z>GvMChf^GW-+w3Cz~y4OXNWw%nRw^sC&Zt$Xb^klnvx8O4zc-ZY)2dqN)709eg4gI z`*(wGAGnA;3T#zYtazu!K$ZsW30?pe|Dd<)Y|44({A6^Y7Q-|4<)Q9e;;KMohlz^{}?H<+QZ-yf}T# z$0f#;4ILKiZ0hl|kaZQTobt|t1yp!Aq zJc5nar}uY6pub@@0+k%DM9!3PTye9_!)~%UgziGjB8P`)=#YfNaY!vZ%DOfWfMp7Q zD0^tcJb%SA*slLEY*?0SyXC0!}k}mMuofIU6=0S(ffhbN88DskLw}7W8lsM+#yb4`N>p=2X&FJIFjA8B z#IaO&J=TI4wMlCE^-H%&bf-O}jyOPWo-AjPj$`+3P=91phHh_FeD-fNy`mM1nVMW}^pNq;i&4>*x-ze1yn(UHJ2>tfCtfzPcy^B{ zA%9-sa?fFYv+PtRLcqI(7TRwl67Z-1JXd@unxw3>r!qyd?TV2$sCTM}r0Zt{*m zpQPP=%wQ2*fARqa5ik|hZu^V|Tq7*I8Nat`^M795p0F2q$U*`E;iCLEYR>;jGylb~ zs9~dmvx4OxpQJ^KF54hyjSFxx1|$=X-EE<-jv4}1X(VIgOwP&mO5kgLAaCm#<$so} zJo?L|=x@E}l@%cKg39qN9?O)oe9jfjot3-4VK8ScoZ!}~gN%w{sR4_b!S6@N-eu&_g4%AAxVUk|sW5KQ{Gugl5m)MY4~;L!|p zwj6b_Kb73;Z=X%_|`sW>0P*s@tuN=bt!oLZ(WTyqGoz&yU77Lwq!oTag>3rY($}i!5)@8N$a? zFsT=OxG%5*-)P27F-NtGQNPB&J)t5B?+8c0%kvcf+3Fn?$ZpgXvRqUC!B6c$>UufU z3{sezy{(+A_k+%L4jA{hqkkm82=@o)qhQ&FUsqz@CCefT9OR5j!yqk1<+?ZndXVwqM8@%119%EA+cl(8j3dMwl6>Jssa(@oClwVRazU;T9gJQTNW?&{RoQt&Do!u3Uw?Z~16*RLX^w#Z5 zAbU1OG@C6(z+3RkiVK6TJ<*Ietmv~*DXWFUmGhp^THb(7=SZ5RK_Sij97H-K6yS=i5VoDG&PgC{#7804WA&p=Dj&xm_SSR#Qtokn3N z{MvQ-SE@w#12~0UUaQ$lyDF(^#$$RQf8wN8e3z8A?0=;kO&triKaHbt?RcM#(S?a~ zc4sWjVuN$d-t$G$*)wR?mo_}`7#pT`1(0$tA+XaXm=)ol}g#FqS zLws&?3c3T%Hy9Qx4*8r!U18m=xc>n5+*%B6FtmbJQ2heYH~xoLkLo1UcsX=VVs6a#Bw}?=)P83$hrj*T+a~>V zaepa!yG`8;Atd6Qva%N$o+&lAJbQE|*kCx#N%W45c^r zZRJ#Y@Kj>!Yy8yhQI9GryE-W<5~^Nj0qHE}(mS!$l9o>P(&o@NT&g^hQefpSL1_po zc;ss&s@{g!1&_O4YH8=cpY|mXyrgbFqJNysMMG_Bp#@Q(RnPgj$b28JcYx{5B)T6{ zIc8l!nOwk_T!@V>Q6k*`(VvKS7oS1=wB#-^uE@mWK94?i|A9BKHJae-D8ZSIMNpOo z5;oF=q-3lw460v832!8(-6k-qP!-nl89qVT)7FUv7A|w|{49Uacdu@Sy|s~!bT^sQ&-t2L z+iHrR1>k|Ed?^7{yfM-Dm-C?lh=1uowf1NWm%Gr?Ar!ABi6%eo8~pcRZ@xPajU!_lZkDMj9_kmX6x$hU14zdax02KtrF~b(K43 z(6wrPZ#jLTX?*Ko&A7Dqd4DjywG=71s`xaohIm}=U?Op%_$t^sxjJu;Gh-~+B13lv6@b}x#Y%gO2Ch+T9@+mZhZq^-# zyHVjTOf`@Rw6sjN7mdZu^4x9`8wW{j^hWuS#MwlDYUq9Ek$2K$6{Zq2&5wxl?`&*IJPrr_RxbO_w^x}BM9yCzC?bHB{U&jxU(At7QktqW2=ptS zL{dM+W!j}wKYw%G2TN@fPcp*mEO|k~f>Xi$2EHh1atdnX&y_*maBYbqbcjShI1H8C zp;q zA`{)?WEwSNCavEoY*NaqL+ z)z4f|#ZbT5xX9O7r6O^|T{=C68pkTZ(8jPM?Ik6RkyMRuY%N$!-OX7RaS(3qA(WJO z``?F)Cx58vkf8}aY|k{lLB8RuhF4f{kmDth+pOQ^em%e8ea8C-eEGb30Oj1NfUzhV z|4c20JA%uRaNqJBoIcr%l`Wx_fT^e3k;VzX$4fV< zgv69KzPpxI{kb3*S`3qGRE&Q1d<1HgenxS>pnqXcsD_4n_8L{fT1v-PNV{^jKp9@e zzh@Q?qtF)3JJj_X%skGS>`#0nhqz)KHfSquvm&6u$oMmqrSwKeo_+qZGalJ}LN0~p z$5kAe?FE<}`*2x_-n&8E8mi#y2obNr%aw(clob8L6^;6m3=$7N<7=44pbu}l044ykD3&$aNI9Lr zc3fFy_q7{8A*7sx_#yvKN3#Or+;2Gl7y{y0=J+BFh(V@8Z^4AY66ap*?$HZE*2JjJlt4Okip!{UiDUjGM$1XkR4CW zk)1}Jjg^r&FJy#aineT=7xaV+ZTmAfzY7|bENT3-$;dLUG(J)&sR7(fzxZ+~Li zV=M?HOws&tnKy?;PD=Eb*sWXDee}j1yo3s+8(xhDUR3nINtAZsg@ z58{t?#sr1Vui852Uh)-{`%Lw3MgWPVlK5Ja#?$HH^-UpCgSp%$VBVdCiL7=wq zE+F}U(YvBFymG#BG2iIws(am%QzQpW0^8Ia4^2{K;9>02eWl$sN--pU1Au7M9~IIg7d94P%|@F#v5pf)+k3?DhgMiIr}-`?06Gto=cc8RB^5jt%`-gN z#TR8^n;&q;t4|2BwoKjhD2&EzR7f%DLHuFWm%*h!Q0+>CH31eL(nz&AfU0>g4y6yk zfsl939n5jHFrlM6LtkKDGk*u`ZLZBQlBdN|*cwA}t!wAp9_2CekcA<`^tPYJ0~oC@ zNKk^7tuW}MPR;Aw(r*>{gNTD_1vRIxzV(HgOi-qwD%t9hm&y(Jsubf~^$F9{_0s?7 zP|t9dGxC6)U3e#MQhn0u^Divpzh_+_IYG;v53(lb3o;j&MiCoNl7DaC&1za($m!(B z)32|ODC{fVrKF+grrRkp>Ba@90i$5G8Wnl}vTA|dK*Lf!SA- z9$c-rBFSib#)uHewcS#!!21Fk?6POED_8pa5f@VmMdX-S`<1JTiLHt~nz_ z_xGM8k@y~n@p|GPlktk?loA!0-MYTaYlmKyN6bqVz)CnK8h@oaVJfhOj+JAECt-!N zfptetBouzYYAF10)^~Gzf`Wh#WzU7Sd;#gLH-A z$)jsE!~HblKYv-x5DdxOF4TS#YpB#1zhK!oVqM%qE*~(!Jnpb=i%E*1;;h-*8r!Wh zqZ=&i$KC*h>gl$;!6mBec4^n{q!Q5z_E~~khu^ub`fl&Y`tI-8`iN}tjQYrY=uVk!&?1T=^6U%i|2uSg^A;A~>{pMOJ)#=DCO0PPEXtt-7}Oq6X{ z5ekM#h#4_!SWXxfN<4bt_b6C*SqWlSpY|k%jK|0}4X9OkSv{+h%z{;N_*{$CTT$sO z676M)+?#zl%WLVkkj0xz`7ifV!P#va3ijbR;Mte!i%XB0wTG*<;$M3H2XsJrFE+R` zNR4y-^M8?)BIUKzYsG9zWo^kz)|#(v3(Pct(u<6=Ds#2gqG;xgiw@<}FKYsL%pyeY zx`P|T$PyNj`Me0Ej}at^X7HItROs+Hhz*=th>G|tv+9KhHK3an-O66u_JuZFR=@DF zqJ!7LR_Hu5xCQ2TokUYhe6%i4S<5wwD!3dUjDH4Cb?WXDzB^sqT1|T+a6ql4$*JZl zadva*370+9Ms3*-LLiZS2r`ma~ zqo>-#$OmN4Xitj4=2!Q~B>J(*;gnD$WYcB+j2lV7r#+lLIP$3$LAgSB@fK1F0ZP2W2j*?qpXqb* z`03R_Bo+wOl6nOsAD=XOGYMQd@^1a5`4aQt_LKV;POhV9=bucgY0Yy3ju$_e=$p)h z_V91n#QZd-sW3|8Nn#{Xu8IDrLr=@Vmw)@F!SqPRQOYIJm4z0pug^PKOjJv2u{KjR zUy$HF@AG$I7ip*2CuL?|_i9VgyG;L%-OdeKH7CS3)Xbx&rCkk$q?(`tv`Um(xL@sh zLh+n|yi%u{TFM!83#`QIjp5^d4y><&JeOe=0e=uwpfuaHXr0HZF+%jn;+2{kRC!A0Jv8HaKzfehL&$bgJ#tLvUMTKSHkpYxAs@#VLyB2A>9zH&C)>z@}3@-VDQZEZ_#nwIMJ%7!EBHffv61d5elNLq7j^~|yPplmT7a5_K;Jw@T!*ni| z&moDDs~yd@vqD7`7{4$hF)>ANj~-NT^I@tb)+6V=Qe#iFo#tD=c!Er9^U1*o@(Hq1 zynvQ{Gpf`w_d7mrF3^oo0wpjD*lg50A6@02G33Mo$1hRPjw!d{V}J0a(}xON{^rKR zXPfV$QPT0+O6+?WkDG4gZROO#{GoY>(e>yl%+E{IL&}KJyO}Ay6X-`og?KFaS+=(l zcn)ob+NN0PBw=00GwEJTvps!#c@3vZus)4NwC}{145iO&_{GK+;#R(bOHef%Od;vd zf$f>MOf|fUE`IBrhku?3;~t%L_n_2Cg?O-A$2QjUj95vv@O6yhtdQQyEMcZ5Qq|aM z(Z0X#SaQicw-1yl49adLX9o!|ue%3Uq93zI2MZkF{z`-czHH!%5u9sI(11F-5+K`( z*`hiNPPe4@o4yb~?eg)HEDm2V)Emg*7u51Lj16+*3P`2FJb%Zqu5<--rWXFhKCeC^ z62sI!Ef;jmgnPr{6~-KM7-DMyU_z><@VHH?ruaBs%GR=;MD7A-NA%B}n62Elo&-gl ziQ8tul+v&GtHo38;1F?3>~5^5^OsYZRf*|7mQ}fj1l@kXjNv;fzfcJL-tgX?iV+~+ zNHTI#Dl$!UzeW>K5Vn!CrntVm8eNam+1NJPHp13`z3U=FEAezaDe|2 z;SaAr+DjYszD8Zey*Snwr>f&_%;ST}vns?pY^|yx|1+jH(zm}@-k8wIEL`H`mO(a| zF1A6RXnzIS^vo=GKWF} zmpR!+>ad_Lf!FbMUe6HJ145v!1fy>uH<80cq(5w(@r(gzi&Lcux(2riPAnkWP=7l9{JrRF0A{ zaMsg`nI@2HWpJq&(rR=XZ$j>a4-7i~otl+k%G1{Qf(~)G&PSx=kO}7(lfpCax$!-KeO5 zK+b3YE+IWAnx$Q|u#o_GU+vxBc~-f#ugdw=Qd$h@z2T}~OYz#E&rl@{+OX_(Z+#~e4WLQ*wt!yp>mhpJW_lWHtKAJ%RAFL32Jtat^~G!tKhqxFihHcQRTljY7% zaL}79zJx4SR5IhSRpYXrgf6FJihpIa)o_|~F(I6$hQq`EcHiT9;thpTt-DM`#>l3q z3I7;-A2q$X%Wb<;Ix-&w8Fd^2$!y_8K9<^2i5v0uPH?y!la`Vt$&}*dWY59 zG7oK@x{{lop{+_b`4$XIUgjuHsNag+WR(^H4k5rUrO^6}tO0om~;s zbro73Dmh_0Hc2S@EN2;JRtlcpMSp)7sZ42JJYmSqnVQWnBYEZYyxG8BfYI)wMOh5x zc;GtdsOif($O5aXz;cw;9qtj_p(cIMk6{as)N44W)2e~8#Tr9I=kFmZPg-W&8?-6r zaiEgf9kiSK1eR}fRa&?9^DIzp66!JNsx{D;3G=sNogFCzdvn-w&^{z;FnnmW?@-&w%KAZ!ynUp zSkQ~RH7-+CUeLq{cW2+LXB>a9Y(dYKTx|a}wy^hIMj>K(L#9Th3{Vi7xWHio=-~?yAh;Vv*+EZbF5Clip|~y&Ir&HGX)OjieP+9n93mk52AR;A<$T$2hu~kZ`)0Iu z&yI$Y_?16RKh0;6V{uj+PVj8M@Y?!99*Nr$+n*R#`y#gm3<0kmNv|o#A6Oe14b2V0 z+XAh^2)RU^9BI8#d-Q*~uxG{9k8-gv$}3L1T-b8)qmPX_o~nU0DfRmqx$+FgNtd(q zg&mO?4ut+!)o9tBT@?s9f&M5DaA zwX*<=a_JuUqS7TLOG-*hr+{>KBjwUdH%KbN(%s#NAR%4SAs``*NG?jLgc5?lf4%p9 ze=hrZ{frCG!ZR;C=XYl2%)B%2JLjDJ7^{a->SS_DNsWNFtD;pIRAM?@7=XY(YPvZ(nC6&@mGXx``%j|+wnTtXKK)fjj zF~K0m9pc?(7KMPd<7+%B!()d?HeyGZlT-Gwaw-;K);xbN8@dSBX7gjmjoLZ$k1V^n zGHDY=*WOXM>*#m8TRzJ+CtRSN2vqOrIgpVY!N*?W&kUx@_F14KfRZkLR@p)q^kZ#w zZyjD0GN-Ux^gbpG0c_p0y8xUC~w8pCD}glc>dxXIcP+!A8BQYYibH|Qz8 zGq=Wpx{7~dh>>K}fz5y5*g5dUleR5t8+u>$jG=+S$pL*9$g$2Du@t6RMb3H1UWbtBNx;o;v&Wt zB95D+Gp3%xwZ2Z?=p`16{=w@tuft^{?`>3Ui4lKi?=fV*2d$!69{Z%9w1#OgRwUxK zM_fxb=8rzSs@piQzI}2j`|<)r1>%HBK$=iwyvCOP#FvVdIahbiRV~tS@vdc)=woL?^U> zs&aqQ%wnLd%m=A>!LXDTDU@9cwCW8=6K2q#p?1Q!g^Qld%~Wu`#|daM;=i#8bhfc0d!95hu8GuH}Uq*P7N{aYldQn?bxJ5jj>X47XrAx!1IzKCvchPqlH6EAYXU`B73J zuYTy){iRL2lWQKkMCU-I9NCSM%tuWo758#=023Y$CdFwtlYm--cj%t*Lpa_LOsKdO zUH`xxIkkiIS=zh`w99<$_0v7M-WYEl+BpQAm1_2SzPJwViN<=}rKo?DOvcIrqbAj2 zbzb{n!;QV3!P`2UxW46^s}^U-R+Qtu5srjArZSH`Q4thpH?d6$2rdKKEvM zt2n@(H^?@t-y2`)8{7|UeAA39pR*9HOTe?&KC?(L!A+P&mOwPsrw-o9>o4!P30|7x zQ8Z56E(!x5hJv;@n38|SnR1t2@3Nsu-pN6!Rq*SiD;&{@6JZn)_lt=`2;Bf|ADPt1Il|2t?DoL zHIphLpC8FjORVh6Pm47xYC9l{4`9@eO*tWHhrAOEyUl7s=$L=dB}Dkt-nfzNUWJUw z80Q*ey3)w{-O*0Ahtha~lCe2K=Hd~`wL^DTIKr9O1{|5Eoh&!IBJ_MwySgx+Fl7rc zqX$`8u;Y;Q+3`g7C{>PsYnU4~NO zkK6o19(-Y}mUS_1E%}L`Ts1LUC_P(>-@=9ASX}|l^CN!)0QJ~ExK~m({UhS>J#Db5 zi{*ufnCt4Ky##06QxyX!G|@Juk~?xexah%>i8cdLN+Qe@=?3MOtb^kvOx+4W(l3YWsPXq}J`TP8M!cng(NE;mUn4&Bqo+9nD!P1jZgR`~ z%kl-U)`Nfjh_jOqQ2;EcC%$IUq)J}iHCK!vMOB$}79y;OzyLZYvD6MIs_=lpI*O`7 zu(7C)U`(Zfokxms>NN~kY1^s9El`nNRFt$zR4}9{5@`)1C|>5a5k|mFVHUlUQK(2U zbHnS8ctrB}^`8urD_By7i-jPN<|SQcNbi_b%#weIRfZRfI&EZm?19wF;2W5Ft~TPF z;=@OT*+Oy0E$@}+Ac9MBow6aMGkBVBry(X;k0h0kA=N?H6$ZUnf^FGv8bC4LNQvPi z&+fRs>k`LMOtcu@MHpR2?Nz;YUB1+B_&%S-;cMk&CT3r%drjen1@)TXnNsMSM{>3N zFq?lx{HK*?vgIRjmNy%;vn{qm_((n=?Yc94_Hq^U=Yf>Q-V#)Ao(O*skrrb>O*2xZ z?X$mWDV?5EFu3jWK~}HccXU4@y_3cBr8==dUv-2o4|C*9q*;2!TyBMd?o-811W0>? zZ2wS5h~Vmw)0eVfIW`P?6^(i5m!S?Uj_Q9*cJqh;6P4tB*4EDKRaDkca*dK8fhSN$ z!S<`FSg3~#N$MSGN(wXN4I_JDwbE#h^6yz|Wl_^LLGU~%7B@(Uwm7&jeV@;QAOI=#A_Vx`)$M`Ik82g5TFVT}bq#PJ~V^R+YF~iac zTbVpDf~xWNw|a{p>}0wGpN_X;qHupH3A_1jaCwW&=(?9jCtXwXxZDxKN$EuVZ>pmu49^i|~JIdKVCu z3hzZf<6)q@rc|)TOdsS!hD#e7==GMyOZH%=!Xtci%Hf2XLr>b0KB;>QgFh zk7?Hfu^LjVjX~kiDDYu@q%uAB-kkjos0b5fbB6&9A~z8xdkL2=ba=6fSojh2MZ8@(_%(NM!ll-DEaxP?pMB$=g?34_Ebbs_6J?!iZ{$MuHAGKPHy zc6fC!)uqYIG99Ca!a5$juUw;n5DSh}XXI+kStrrWMs$;T&HKoTze~ zt&^2#-7FS(l#1s6V$XkR)wa|gMbRaPIH@uObX?h@lg*~Je%JbukZSI{=ItCCGbmxVG#W8wEwYavw)$-12@sxkLe|<6NLH%_WPVHxC ziVPO^E-%EJ9@FE(##x8Oup41KoGC;X93f?;AhQGrUR1TBw zjEJiu?C1+(f=YkiWbV+AOS;P$fEPqL;pjxpk`YFq+7CfHqcSgV)-0SU>*?vCO`p2T z=)wvw>Tz$XuMZRWMtN^K;+k8{8rxT#KL75nroaq6ImXn*DxMe zn)5!jmv=Jny^gs2g8h6jTHBY^Q}0=Q(iRU^Y?=?yzUx% zf+Vd=oe64^apgUl#_8xV0p7h9`=XnoDVS2Lhwb>X)U?qK^D)Vu9V4-cOY79j(CbjT zyEIEueCmIyIw2!jqi0y-3lg4ZiYp|iVT4@i@85mFPEn0wVv6zOL$SWA=X^qSGbv|6 zUsQ3=db*AWJ@ryZP0{FaQ8d(|eP?(lj6xLXD_dgp`Hxw z)7|*|49>Mdmdz{L0=5wgM*m;Ih5x!A|NnU_4cLEQ{<8_2b;i>Ko{^=Rj#XSid7~zx zi@)|v&jwV%P*Xq{oDT+zqdWBGJXq#e%VLe4~Ml^X$|5-bKCZ+-#B!Vu|$mAryMomPh1#K8JmtTm&C6@GiKxw zH?vHNo_ApYR4FL4It~*e6dSqKZ?5y(eWW^=`%GHOW|PVDx+8sQ7bmZ4B(Wt*W}xX4 zr=PuY&(&Tn#90j+Y5yGP>1!?vr{St}2A_Xvf=K&mFuQDVSN@GeklvK#$jkbhZjZf4 zT^Zes3B?5|^i(64bdDZ$5$U;xYlIp{g?hd-o3^^AYZTw}d4j`sIk0V!kl>vKALUcb zs^{8m=n!5Z1{uLQ{2?=Ixh!t|f#m9jOolO@0j_tVoxHgo@uqv2?xDx`?9j({SE+w} zo}ru?PY3my+6WF+l(74BCv&^ZQcza4$XDJ#F6a+(ln{LwD#gYAsZ<~@o}eJRe(4 zD*{CLRJW8LbX7QGmTyb{laTijQ)}3+ERiB9t#h{ z2K;WeLH>@Z(2uFjsQ9a@>7ctA?CD)&YH?K1n@&3$W;1b!zCU!M6Qzz7Sc5OqvGB(kuqp}m_%>> z1w1gu%o@5%pGTak$iM?Ze=gTgs0oZ!>%+(xjyQPq<`RE3plq=+ltF>h#g5_`+c8QM?3?3wta_3tD}yvDANLv`m8roA=F+TB?E6kH+~scY^}c3b>#Hfw7?_968;R zDxzwJtqiuJ?tT>X^m=AKImuZoc1lj{G^75xw~gMEDM9l4=oQbDjSWhAXk@MH-Z5*J z8{L(+SFjo|}kMMJ3AIk2b*% zVQdjAU=bqfP%on&GZDq~*Bd|-egx{zi9$%j#Xi9I)_+E|iDBRI+2U=lXy}5X=*HZY z8(E6uja;LTEyjb=2-|<{5C_O>V(xNaW!-TFU+zyX$OPGaW@`$&L(g@f_pwf;r85!n zoeZyb#W9jtot?>o#Bz)PsZLjW%p@XdadrduOGD9KTNjqnu1yDT96Ao$cB@Lovi;XR zvUd~(2^t=rhNO0hxKYIe`;`Ll9#w_OxCU*AqswTs-I?R94c>qGP?0WpUBNI}Mqfd& zDR{MsdM^gCS*6`n-Wt(dKFwxBT$BXsRj>_Hg^Y2U?=q6HlgG#Ttx+uQ2V`Y;S!-rx z2d)TVY!=OhkWFJ^dX0z-r|~dmJ)4fA6!fp+6KPnvnsLjY*K$uFb(=qR2Qgun6}+lg z4Q1ju(VADde)y_8HdH95@bJ0XCFH zb(eZuBixG?q+GT}*MzXQpp8M;+aQ$+qIRDE<)aPwsPKQf1)iEbu!;K+HgR)*cj9&f zJA>`*SjFva9b8?^oV5NZ{^j_iW&1UAu`kbz`B+6Y0}Hng4m~3cc&z$9TaHK|QnJjQ zXk!9I$Evv-@^N$ZGx(v;TOE3^eGf`}bI4M5kPn%@kVJAWJKNW?#$V|VZ<_HM7COju z&iq)LcKd(q5*s;JoWlS;A(fwK;mJuIRY_$JN)x zn+(Yc*Jdr#!2`_siN7m{9%|p8}Yx?B(0Bh-lkx@!C4h-VR zH9p4C!h2d19K?xiyoFFcVU_H}VnrnP4`lwwjhp*;)>6p=_oH0W+hkLV8@LB{*4x(i zQ`LXFdB9orsDoY6Vs|?0BT-FXX+Qsx=v!*@8QW@1y>fR~jHARvF1W_6u<*)OeB@Y@ z$C&@Y)5xk@&Fbng$|H?kZ|{+D-bx!&Tg;7=Z;DS3eQ{bt>wxG?yem+)oa&#Mv7cQ+ zfHbp>8KlmU)h}&+Mt;1iBpf%g{n$T#eX@Tt0?mN2p~aS`(zRr%i9^mT?B-FXEq7&| zeoXbH(A=}PGd6wR!mObih5j}cnAUEcZe&`XrSqRy>}7AFnhY73w;x=y?Y(0;DVONp zORw3-ui>KGB@eL(b8XW&2_0lpCR}(qgdsoUlEFPNYqh9wEJvUJs*=EE25XOj?=^qO zh`Zpr+=IvN-R+l|+!FRLJ0F~8K|TcB)OWqkAmf5d-5hFQ{z2KT_)Lh5dERx_;JTkr zU6Zk1=2A+6E8@fQ8&=O+5}x!4IT5~^X=!j8s3G%v8#~fynMBrUAL_m|aYE@+GNchC zNcigT$)qV3^^;GbO-~k&e9aa@m-~Nx$5@RFGvuDM8xU=|sdWuD#&I(mqUOrqdZqX* z$8X<7U@x*|{r&S;zZZ1FK{eSxZ#nP7ns>WQiNkyCk_&9ws}Y_m*PcoyCV&m9x^vGa zgfs9RyMfmZLkN?QB)wPo=a(4=beCQy%-`Q73Ari^1;)JKvvVHTL#_zEmEM1}!=HF* zi8kQg$JgkV?z|&HS((5Y37h39TOlE*v#YslbV3w+WY&F)=-vzn-HwDtswVLVQ!9a% zQ1TDRJQzjI4_exK#5}#JszN->%VVx|2aSY*z%+BXuXsj-?6*Y(U_WI8JsR~=(VfY2 zQlhyI!Xwdar48>!zs2pgo$7y~>o7}UnS=suf{;Eewi6kWj((l{V9GWZLq!Y7c#LW;u^K8< z72zZ*qp)mH9EMydU<`LMC9(4TNcd7tcx$$nY@jIx;y9Zb6t}n$eItK5fEX)V3w4jr zDuc<`8?V=}Bv^K%FE(>S1qbVOHr0lxq&IT8nK-|+9k#NNqWyB`@}V=$XN5+@$g$Y| z$LT{d94Y!Nt5lcydNs?sWs6GQOz6jlp~uFkAkq<%wAoOl2Gbaux#J~iBkqk2uaURy z8D;M$^PeE1xie&p@H&5((2e$n6cUV8F}FB}yC{8WYLh&Drn9)V4EeNED|o=Q{S-Ya zIRi;(!|a_m*E*C9+9)Mg@P+Ci?OjJ$a<_?^>PBjpz+)gcc^96VK+B^-d@TQoeGjo!Z`vCCWiTRHt z@_+a9fETQ&gFS))6PkkX=i>Zaa5BR81cPiW?47_ambT7cLs>ezfb3kHzfCac+{cQz z1OUig`SU%@Ibr|O4-ypY-BnLPqwL<8`#9mnN=EOYvuqlg$woxPqDk>Y@&<;0J!4=02~)6 zfmlC5kvF^dZTW9IyHAH;EzW}k0NlDDpN8<~!0_%*AqyT?_%mtFM(@V}tcy-c*duF=p8E2$&ETXmc7PosaL%J{eKk-xx7oe1y?q!qtk z7Y%Z;{JMGtf$d-xc%k%NJDfBIlBdCDJrYd#{S_qtSJ2<4 zTyjpIJ%yD@5#TH6Ui=djDcI87-W^syaZ583YpJhmXG=3vDObDiEEsjNp8}3xr7;*< z;R1TGz$p#>{@qXPgvWbnfdyZRTv z--f^^HUC??w*GXAb9mwKIZ@ArpZ5M*hE#Y0e8S3eLTCT)rLTl1!RInOC*cnMPG&=R z4ty%NbB@=@?<97E=fJ0vI_DUT|8#OGc;WDAoc=auCVnZY6FdMuVaz$;*35tJq>uTp zH5^8l7~*mnUj0Fc218-alT15ir?1PTBE2nYZG0718Ke*qc+3Wc57 e@Zcf=09Zzslz;(A0;qJC-+%#221|7T0000<Zw>;F$mhrVBcI4Td7jL3@~~34t~eCt7LJs{jl{$% zY>X&}8pe=aHtlg?4#N_1fV=olH=%?U=8MOTz^`mA&dufTiB9Y)XE&6xV~B%25mzZ& z2o{Edf36&1!6$Sl%o+0))~k^E`WizHvs*ATZ{UQqMob+iZ>-M|gLLZUOUcJY4~mB( zM91XxMJ*)oAzmAoxKJ`z zJ2Nr4EVfQp!?YU0qK?X*u-WLN<&`bu*ERDRwP3SjeZkrCWg*fp*)9Q;dFz$(O&l9qYyUu_t#yvoiX#T)Ak~hztCLLYB-tqk?_I1 ze}nTUHtQ|0UQNbljJ4}+4KF|)2w=nQ#KajRT!=8C5Myd-Zw=Ff6pZ= zsF>$L2(Qo)w#yC*=qSa(dVYw|Qzdx)t_I`#+52HZc*6j8vOpFIE;r zc0Ku&ld?|9Jzm34?+DlJ;gG@}ihIOs%blaA#ngJFcIGH{@Y`V$!XB!7%)qOTwl9gH z;xK^th*G#TEzjvXI#Q*rn0^7Jf5RXc!v3%fl(X!k46TcP9X2M|O5Li&dF`OM-9lm? z**z5gX(M&3?NAp+v56tu*7%>yYj4mY3gg{JH5tfSdCIS7xyQN+WNbF&qOxaTu0G;> zjjwnquFgqDv^Vs2*&$RZc$x`XE@8H&`U?>{aAS37C}xxAanQVtb*F zWUQ=dw-bNd(HJJe*gs|`yl0pjLrZnQ!Gj;fLT>iGJ2x6blh|3HS#uj*v>!dh?o{)= zA7EG$&D894TceT8v?6F^f6mhTDw2;ELS1R~FSpVz>-%s$#A5i5gQcT?Ew*(w^2OJK@}!LqDtv7Y>R6sg9S z+HHhi0Gg?%DTFQZ>z-fc^@~)R07K1O{Z$+(`ZoCf6A3Js%MY!Fe|}79W9rGS2OUuz+y-J~TTEvi!0!o;qLMkKgF4}T$4^oe?4hX$(TXxV!6eh9yss8M zfv*rx>lAQ{As%bwQrUVF`99;kg?m-P3-YYH8q zEold3)deVY%YAg9XO(NShS&>5$Nd&+GR&@|EcXbk@XyP(e})x4fb^K^@q_9=t@b#0;S5+8S#)Aw(Wjg&!RFoU5%iLW zEEh~{V)ZO*PieBFSyNluMAr^_X_c3AHmu%4M<^m{f2Unj)1gSV&o8McQB+A6uduIZ zHopU|HwJF2tSPs{h~rd~gZ3?;7QKDzSEkae$c%Jnhce2;(tRCVB;$ATRSAmY4Wg8J zyAk8_M|?Jr%ZNr^mMPxW2SYN%hb<0#Q z(gVq=e?DBF`M_G6+!8pk;8MyPWCSF7_=EHuQVpUK4AcT(9oq-L`kD!LwEMtdn=W8CInN;UWAo$to-NboK4l{QhIu5oL7X8AJsCx6-@|^ z?IJS7xwLHfq7)EWTm*LXg(F|Nyi=(V)ca_of0l-Ul$B$-uh zf7-to5e5i||G(?dxc|e6`9E>J|K`&Cd-3HITMb+>w2|+mQu47xq;SQuM`Rfk3l%zH zWKj#F<`h9#EHuKfDZB>LMqGE!pWS!HkEgA-c;$TEx1g_n6QA>xRC{tAtcWg>y|e`S2-pV8Ueo~pg-L<*fj(qgh*Fff5KYcPf9 zD~*nnHy%Mr$omR?6U#5u5D}I@@r6T#FHL=^a9vq*^jWyQcisCFyVpiy;5g-5Kft$l zgjgZ0sozZoXUA!!<1`q57)ngH=d|N;i6UU~Lrm&sg_&qhs&Maj|MNt@6WqeLe^5)4w%I9A%N#tNrar`~cE2VDcan)K(~vgD#2A2@qs z)d6<=6~`dMHx{H&V1-w3J5@Pv_l1OwM)*FYakNHL?A_GZ4J_l?u_}w-s{ZSI1H$4* zAHG34i_7;kr)QdCB4Vpd)~+(qf6cxpS(`lE!wH77;W|z-Mr?R`TJ&NCjZB%2EfBfgP!#cB8;jc^P^5Da`~L+=+{y3dGGMG#o*lGbu@U*uF!_zNhDt#{D-Sxj_>T3xn%(Gq;lk2*Td%gdzbwfeQEMFWV-Wb~4xgA%a+`C|}NqN-)zb`v> z8*wm%J{5~6; zFi@2s_}rpDFDeSqUEA>Wva*;ANzr>|FR2MOFjnUtMGK;AfAS!-luei>P)uAPyTGn8 zQZLRTO;LVz`)y5C?m}6m<%1u0{JVHG6tfa_U^ z`m%#5Gb`e0f2fb_;P8Hm5GQ)o(N8?TynF$z8Y&T!+Qf7?TX@|x;Z{L!%3x(X>c5^} zQE7uie^`nB?oA^@cj|9YE8Lgov-4T3P7hF&^%d@3ubl~gJIvi4?Q>(UEIp!#kp?jg z1&fpbA3szSn`Zh3{pZo0ytJDQLI43R!2aVJxfJ8klY##!B`qHrpc_qJU+{m6JqID1wk)#FVL=KAnsiFN+E%Y26K zgy)3ke`WJMt@f)8_6HOp4wT?heg+gt(XY?gW=qpZbx-z(<9mD_12v@IyU97{WgzSc zlg&iY82F(PP_p2q_jc3=wQ9WXYt`JI0xI>N6U210Moi_Y)-jBvgagS4lHaHe0i z&|{SpvHMu&vU!Q@x3-Vx0KnCy5H+3bExaP95tO%ErVf6>Lo;Or-G685D~SDpu9A%^3ZnTv@QiYhTC zcjfRKDYpCJ!B4WpxNYCNo2_PcDw*z%k0OSwQ8`nG?YBqesM-KeAj_kVu9H#w?d7{G z5tuCO%?3@*hb5hF@QE98-m9c%AGTU{D~=O`8=7TmGF=9`vSbFmb-&nY36dbXf5Y5e z=`uVN9@9?wKki6)5(8@juXu9xESjR)E7Z1j!(Bq@+C^M8~7TPv|GA7 z1LTB8k|*F(D~+pRgHqPJPwo3*eN|WR0&#u1#UQnrR$5q^KHi$t5};h>z=LwHHo)fg zlOJ;R8o+-E=4)@@KiC+@21iyJlov%aFT5ACXz3Yf|{>nvRzQ@|_vJquIe>zp0Q8AX> zbytqj_`JPQfuRVFnocf~*{(j2gV2yoBST_8A28xUHGLSIpTSjwUvnj|1kdv1Z(=J3 zv}G?m!%@%DIXoC%xgH@;FA?ktpMXge=GyCmR`XiejuvXaQ_uaQYgE6ljXSfgyrW5b z3W?D@`QuO#ejv#QJIH1qe|m@K_<$+pvRsX#=m+3PloLu|+EgK-8U8@G{)rdCga*JH z$@h~Z6~Z^fcYjqu+g%lC7w+TUTM_0G(@7>>>_v&!6jolR{>)&H`HcxKmR()jJw8|_ z%!qC)^9d~RcCX;@0gbZrgN8!RbTG`s{p%!v5z zh!|n0S@ZPkExZMtMC&^|Hh4etRai+ApTkI8&X$+}BPd;|?It$dP-7Bnb9l@-;aXBR zDr|qxm2cu5^K=j5h73N3u}PI z_9ngtPCrm4i`c45z6%{gE0#875-Gykp^@|j=%(T|g^oQXf0bW2ge8Vx;+0>5_>I0d ziKkrMC4X7OAR@~ytKtJz53j=LwubD?C1;QIslZwaI34v@ zLQdI-lu$n=R#w7$t+<>KQ3>DBY9N^yDfL0j+!DTzyZm*35C70p$PDvV9)Y48Q)}Kc zX%*p*i$=nSyhYYh)aC)Jh8bzOf+l(|VhQ zt`g#Cubd>@{6C~2%3eS}>gJUD=ha*Maoa7|1Q1Hy#YFQiIgwnOD7)T~M#Kd93IZ4S zqOFwp?Hf~1T2zOhU(9*Nbq2kIirM1yH_48;QU~aDe-C}|qF4&hds*x$+Aj&B;Fvo^$>4O{_nq!HJTJN4 zJHGC@-(C+Jgg_W|cq2e0G!RLONa$Fe7W^zRf4|opqBoYpT8>~v?c3m23{b*NoZa`a zgk{BeBft_txF$B3wKqECYR~`FEU~yMQviOs&<&OY8H8-g1%ZdP|~@y)D5G>0BjxJVGBJ^o2MKmYoJ?bB=k#W5e_x&H4yd6z?D)P>WXN&DtGpB0?*UjZ(gC_K zrVtU@ZUe1ZAnT#_+Rg0FttzLlp(}RU&-5BJ5q0s64OgpDX@7vn%z=dcgz-wtu(QF< z$-iOt(|~f1vEVUC+xnTYafqVuPO$E&f~S##a^8W7{6@cFnnzoESMm#%$}AVze@2q5 z)e-3)gJPY3CZzaCv<@>}r=<9d092QZ2ytki^PwY-y~|1}z4nJ*6h|DMP1C}>lr+Z6 z^;h*d^tq}_pVD)kth^>^;=ZDHI&`43o07PEbzW;#sGWJ5qiYuNDzHJQ%fXXrf2a|eo61Wc=QIHBe0&Mhgu6yH&ny6O&mwpqEW862 z`$AWJ#urZy*X>w^Uwd5Qbu*P$JOn3kvv;Tz4&jZjN&Nl?c=`vtu@1l^ZB&WrXrygq zB_5np565kh)b)XucR*V8Vc8y`1*;>vv)teDH}M~0lSFdM)RW5637q}Ye_4iug#>TE z!wB4!hG%ahM6v6GSj;f>`ixE|Ru=;F#5qWfXC}l;RSU>KECc3&Qiu3-i}k=RjNtQ> zl^qP|_HfA2T@80xrI~q=lc-drciXXsT%~bd+}e}+SfkxpR!gr)G8WqUekLhyHw1rd zV8i$)?C$NX^!GE{si3^_f4&Z;ZvRW_!0n(D>d;^G{I>!AyGvQt(ALPrP}0=U#L~|E zf3Ik@SY{beA*7IZN5tcLZU9Szt8gv{}cByQL(2qJ}k$0W5$;g!l+{8B_XN*)Zs5dxPK za}Wa41&dsyd9gN6u|eNRxgyzyAy%T&y#?Y$GjcPQO?Fa>FWy>vniSZXoQ})e=>}a5 z)e!>@jVK5~8HbyI{J?iF<;Cmh*bcZ=3B56|hH~E@DfMTUTOg z34ut(#!6`LLziok&2FrVU`5fQ)$fLhQZ4_3ya&XV3-8JI2gdMPMe#bhiR z-{L24Eq;rGw-O2{sTL%Zi)lHXvS19lpYspBa9Iz@fB(dp#$+;oz$!5&Ec{Y}-2BxX zK~l|DWd(KCs5B(^+j6Gg0k##`ww#R(@$?i;`hy^XHN{D&vC5vl+IWhW1wWL*OY2c) z+-!E+38&=&`YF~wFax=!`PfztY<7|e+<`l+~=n$dA*E#(VQR%`81@MftbHA zBQd*mU!C?KZ?_$Nrms1qHf%c}5-#g#gjpj3BT|N9A;JZ}PhG4Vg`8<(C z!f@tjzRbo9x*U%UcIA;7?UQmc8ZJTR6}kq8srgQU|7Ip{q43#s2o!BiW&J^tn@&P8o zq(ns~lRuVpm75~Ca{U-uX7}>AFXUhGQ#wL*kooZ(qep6^+2;4e`#qy zq|RwjW}T^9!}W39sh>|V6uG$j@HE82$q?xccUMp|+MH-pM&i!srUP3+&HYP7Pv)j% zth#-P)oAQyHiA0g@>d#_XNKL>ol(K8)DwZ%!Bv2{$BH@Z#!jldHZ)Ca+#F8&IVT4f49iN&Q7d-9HSs5Ur084ykT$Dpu>y6<%NGobzcJ% zb}V^Ip)?4xmQtJL^^92~T&=r9`TeFJ6WI1-%P)xr+p#i9AAiSB!0q>yT|1U_tBWdG zj&2WZ5nt&Fd`O=9RkQ7qahO=z+=#z+A(=svT+#v#=Pr4OZ_^4+k*yh$e`Ea~$bjKE z$f#m>BmImrf!##htiaXRWx89j%XOi56IbB@mFbOO0TduXd-!@$?lQw*SP}G29m_fd zC1l{i*LPxdqc?UDDA(qvUSspfDL_`cSK@RSeb6BVYsCSG5cPyRS1hPyRB$nW&l0bY zb$}Ic&7DD(0+ds%svT}%e>*OIIguCtsbCu+bi%A5EZXH(h$SS?HuU>cAsnA9>SBIv`FZuoCs7xm%wL5E5y-INoe+gfaGJEQ7g|Zu) zMSTeqy-M|8z_^(^XzQ2b$O@+~V4nf|gwSsbsk0!t?)jy9r?|=P_M7t}xwCoDZ?Ho> zD36@DnNFe{mS-^CQ8l@JT9^W6CxWjOi4Sa3^Yp5t-FMy_lTbYOpM2@Vur-3i1YDW# z{om{Ri0hF-9&_{ze_j|PALw}lo^kv5Uye^*1xL+jSY9zCG78TDuHwZP&_~%kGLs^_$Uv-zR~2j8 zsL8^Bbc8wA9FgR;BZzbexv_a*I<=haBZxo;+7cPD8_#b6K?~50{ZCJJ_Vh z=J-)&$M4^4cnI*D6n%WvpyP#|#*{p*CXL7Cz&t09s`(hM+!)wxpi%5DjJmjv5hsn5 zRoS7%rfN{iPY|gvvJ2DISLY~G?l=}`&0oQ$v8&~Cf7!PTth2!#W*!~j;i#>s;eVv0 zPw2pBU_fc>rA6eXnHv$(Y)9lv*_!AD<$+#y_3@`5_=7Ous~`Bw`*0P^7>o3V~+Thm=N?m#DwNi!Mge zbJ%j$f%2H!Xfys{a=?8cCgBz^-z63*8kZkxT*kUXF@S)FGsMhk!l$+7wlwn=v2Y_7 z+j`2i;*I9xe#Ti1lVGFkP7#~sa28pXlK4ZAe}tOHc}s~M524kl1J>AJ%3bKS+fX_HGU9lFF)BAhTY5(2OEC`-lQ*8g{ROr zf4+}Aj%(7C(N)YROMw^u&&h^Q5dfJ}Uh0_)QC%V210{!H)Wo5#(-2M&dh!#L^nm9cf+6L^!LsH%v<<*V>jtw z(ZXt_yK9|5rKm}HDgW1+fSbK{o6_aGf6j~|RLJA31CSLEO&#NcYjRM5Uc`ujaGLS& ztOh7+t6IKHmK>i{Eb)mg1-t+qQ^!Zfh+HOhxq&W zmbvm10Icp!6dy$*dopQL05dn0McbhgXFI5VklJlmG>;%wCc4UkLD796f2m;u8g)J( z?wEDlx;lcI%PVMg9GBETx@?wZe;5P%3frel*@BDiC_jIM@7Q5U_h8BZDo?(P+hE}} zV|dO)Nd1k$JOdaCbL7H}xa_~t+j>#q#U^fX^fl5J2|lm{^0zW|x5eJs=l1sW3oM3u z1vl6)m!ULJDQ)lxi8xljePqscg?A8s(u5@0 z%?IY=2f-J2Gw5mdD1P{e3M6HuZX%MtnY=C{dra~%Ll*oe;?DGPe>V@Yj~qD?jX(=* z0ecskEPUituBZT~KhYfQ{7?C9p6!R~ph-a>7V?}Y7gS#K@EeLS;qsW|`D{b%#uh*X z+9lPm=_l+TAaQLJU1N3LTy~Gozlm{d+!O3A^AP3~C6NEbLgQ8Qyu-NM06KHG@5+1F z^ysu&0)O|3mJ>Zrf6R%TdPDyKZK{u>{{8{Ic+{jKn9{U*s!b(!M=>F+(!wBiLB1j;1y?5}qN;!sXh20gY%9p+Q zxh-zbC!gH~6l7B9?t+&Rvn@k@0zzZQL*-&VhCEhdP@b8xeb|bA?#;ScEJ7Y8XqgaOBTj7=NI@xL!lO$-mRuPlG4;* z*tyn7t8H$gAaCL?VJrLhvO;JRK1i;zf5=y-4z~wbR%NJOSp5l#ogv$BNeAQVe-fTJ z|EY6gmo?{zf4@j{iZV-s+3q*3xr_W2+^UI3aP&yxK{+>enI~FIsXE!(dZ*J${E@{1 zf(M#tOMYUU<>TD9S_J94qJ;X`j-3W|E_{yaAwCLvsC(gLAYp;=1f1Iydcp>!Rn@Sv zhv>Z}E~(7X8CJW00Y1bu0x_3?k+ZXTi1-%y(~sxWe|+R)dV5E)tiq;tF#n zM?x>b?vaIJs;^=VMb~d7qg)_n02Se_*io_XZ${kja z{)X=inYPRA#X+m(5_}5KN4|2!W~A~_DC3rD`^kiAO=#sMNo(roa@NFGb3<5d3g4#t z!ye~2UQKVu`8$DMsW#A#UZ<*GT*WuYzubndf3@L%{zX;5|3l#>Zf|2_@BUY}iCCB# zTZ>!TSvp&onuxpF{ih<{De(gTIAIyuA@eeyeyy#mYp9kZ6VBkao$|8^N}bAP5h$Xv26uSQ@ONUK&;;>j`&s_TijSH`kD*>BOViwqVH zOG$BX<<{Y`W6Q|qE9OD0d5V;=O?S9mao7$)iM`grbsdP~J{`YpZe|#dr9+A}@A*Od z!?J{o(O4DBf|uh0A&Zy{d`13QFg`}^T0JE^xPvpDlAe_s%R zRsd9UsAcS}ER$)uxUu4p?L|mhjg(xZcGO-XLfe&q+BI!IQhyE#xzx_cP`xd#och7k z-aX+i8q1Wdu?{mKZWz@WYZmCThqGa;!n+}XFu*JoG{4gc`_eE)U*S#`!-FdbC1Org zNiij=tnt|}SL}{@VDH)ENZ)!!e*-G!SPxas3L@onLQgXd7!3I{SPe%DnZw5lEG%#U zzf<_*q%B(cMWJkS7(N^dMuZairkob>L)a=K#J@cABcHui1pL>D$Hf1yBBuXu9RFwV zPe%}4>DCUo8t5b6E49ss&Dj9A{T8yeJ~@-2m=EcNec^LWrz=f4<&CGse~i$&RF3=M z2K5wmOPJ(T4H;_ix1YkEA`^`v-KvNtKM{FDUv5JK3`=}|BHjl00rB_39c5R>kZov~ zU07JnTrO>U&)j5tPq&-jTqAzJKiPv|4M!rnmaWYGDnyn8nQQC9o2EBwcn-YMywe33 zALH@ZnNK;)H>Jr@T4%K1e>x6m;kBwzzjLr|sCYU9?2A#%)O#heWyf76gMR}0q%&P# zcQGxdXFs&8*U(O5>RWUk#3R>_>K3Whj__&GV@slCr)6&!ks(gGwULQ>6H}zofl2y7 zbzE$Y0_4NEB@}qfIE;p;k~7%xCgdNYZMnHU#KSV=Co`yd?6_KIf7W?P@i{&F-SBxl zglXld;AJ01$+;Ph5(JM%ryh78Y4CYGN7EXvis!@@Bpq%lU0n{G0#X;$*Ck_y*C6Kc zc#N~z`>9ED;1o_4ERBiPbeF7M9(Q3fXi*^KE2964z^%9pUw5kdGg68y8{?i@B7- zx~!?Cq;{LR^}|+RE##NO8JTGsfN2t%r!!&2V->GIbOFK}f219g!}Eu0Mzx{_rN(Gs z;Oj+bl~eN|T0@5RH2dVp^9`BI`x0PE@CV#ABf-6?PWl8o0OMi&fD-F5im+65!poe8 zJ*X14L6^|Zh}gJov@AY$4rKf+Zgzf87bi0k9K(BN{1MY`y>yg_STWsMhv(cEdL&+Om*hJ06A7_9d@_-8lj<@7*f3Agu99Hb4C})v)yrWV@x<=xr zt5`73`Wv(vpa%V2T--ih3LAR2B{L4LjU6U4N-BUY^Ep?hfj(1Xqi#F+y0P1)7PH15s>+;ZVA2GvT3)tnxC(jrW|dWwwn&$ImCJtOP#M7@H|h0o z{AvIXw5*bAjcs&cq_G~ej=7pde}Ph^w|1F%g-hKb4VMzP4D=y~bQ(Kk0}h3#qvesY zA**YfYX|d53oNhRuAl>|msHqJ_{fxQO=(Y$f5C2d=F(Rb<2#7!$=k#;e4X!0Pye&+ zhaxpD=jia(oivullcgGmS$NEvDp$9p@t1-YqYhva!>$5kWn9>loDtXKCw$eG5S228 zftt>J1j`?yB+e?8W~cK^FAa{p^RGyFZ}^?;svN#ZN@BGuC)d;3He5|t&bD(qi>0mG ze~J#!%4?IVhUTZTv^acpiqT(h=9fMkcCk7>!<*V;+cWa{BQGYI(!HAFqe^oqt0juH zd)NVY>o#b9dMYl~RI_WX;!A=0;mMzE+1qiXkJHQY-;arO{&U`KHfP{@>)c;eL>s_x z<8A^VPCkU0hrUP}qb(!09TDSK@?5pCe*&+gZebg4ZCC28wyvK1ucjMR?OVT&21=|U zkW|>#1-lT#)R{2WHG1y#?G`2q+#!sgPP^Nn`0FP_x66HTj+X-3th$Z1Z<&TeNyobv3HNm#T!A(-uqzyVZ4H0FyAY)=N0AQTHgG+ zUnrJeEcOQo=Rq1E!oU!?Cp2VdHqt+e^T53gwr8a46_lW#FoE2u>=g8Hca-xg%ycsN zV@RnosRv;9G`esjAD$-JCM1#*e_9mUh%>F!+M5N%h#w_FHfV&y<4X0I91T@F#Moi* z%i=@od|N+TeZG3E6Y23AV>3T6WTo#*wysAtz|o2Mvbs$Le4`oRStIbX`tO3g=NQ-y zZB6^}^f*)3g?HCn*MoXFM8hO+9NGnX<6^iFY*nOguBlO$##$;1Cn@&*e+&DY?5&5a zS?BqTyy63f29&ZVdA_W-V{y2pmi2ij_)7uZm`B(6Mtxv?xldo1G$TLM*46N(%+S}` zupr<^jM|TPz15DTx>Q#t!oCl+AJq((`kfLf^xn&TAYj&&AO~+lb?=LHTNghzpq7=u zmk;{4b+pX}^-AQ64`#P(fA?JYmXSMlG1F9$XjzZ^+^cT}-u3q5Coy~72_%loiAu)X zCEKHJ?p$^7i_QZKlVFW}&OuKHwIrk9vMPT-Vwu1@# z!qEFgwu1!%CD8i~?fVIbMx^^)$@jWzy->aY{Q0w+@4=LN3i~QBe|vn}lV45B9<7{v zGrNs2dwPF=R^h&6u}ARMrQSS}dv%uHleh2B(|~F9M*Rv@Zkx)w#Z2j^-wy5xW~3D^ z_JmzR9e+e4m`@tcOJ1q{dDWR5se~W9OI^XHpz>~$ggB%0?vr%m|IeNVsNebfA2=W& zBI5rlhVcL5Y5aR0f0ib+rtT8@7ox0L=$>%*_;;mG$C!W`%8aOF2ck4!c#gfljpu%2l_8wN3})dROy%$(D}J71s;=BvPS4 zxauGN<4*S*u9Mu)%?ASiuRR4IO>q(6L*gCCxPCSdXmU&(f1cA zDM+~%&4!GYXk3mibCp`$42u?)RTNEG@rH5k%f^JNVo%*UzD z0^>Y}!-rXMW>nJSz=I1!uQ3eQ?wH_yp}_hA#PVU5e}c)A%!R1%*pjO6B>N+Wx$-Y6 zZRczuL>Q)e&8oVt2iCh4j{Ni@W*%*F1y-ZcO~w0r zCX12Qu4zbTpZv%_g8Id6#$oD&!5s8sdYO!ZQt{;wVwmz`*71*%lO;~3KVPmx!Pf>b(gl7liQe)AT;I%Vx%J9D zHc#W)hps`uK|krH1=;KdGg<5P+}Kn8cG^f5}9cYOc}BFbt@Wr zfIJ&vdW#Y>tPa@(5y+4b6L7TJpeF|Ri=j%UwvojOD@#T?N&OBs3hSSSMw8KtltE)a ze~)A-Ib}Ci2V{1dWGh4M6gjMc^_w#69l>Zo?M0io4B8Ov+GS_82>&q)siaV3aHrm> zaA;P13oESGL{ypB-$1MBYqrU(7qe5c1L!BS7{N&duD7q3mYc9)*u-E%k3>V&aJ+4x zZwI&^hSeb+X+X(YUyB>mET^sRn-@O|!6j=SJJJMv2ryVh|18ghsgMOaaIuVO*eZV;F;pBixq1{Fd4$a|6S^h7-b*S5{1xk0?~MX@W$bg2BLt52TsqA8=dDLf3uQUK6`M| zK$?z}fc}iO#iwsCzs*TR1kUg_(>Sd9(_%AcAH~P{8bm4iFX_FN{;HpGYw6My%2He( ztuQ?UH(H|lSF`-*@katQAC@+rL6Top{dsqo`r!^hvMigFN$JE98$Hw?dN4v#{T!ro z4o)$)a9LYYv`W2+A1ZqWe=N2hZ`vIk82elwBVpe(ym6RNwkpm8CI-)Nu}K2fOMZIIuA5CT%BEY11WwnKN=!g%+hqsI7o_od*vnb`2utrjGFL)WvM3_ zpf3zD>t|h`^Coyzo z2be1Sl4{z}*76@;&V2cAPD*c2Fbk(evJg_w^StGM6jDK&ejdcgr@nuwA}BT~&QW{) zglTSJx4*tzBe1fyyt28nx;|TN%SRJk(w!|2by#-Hc~2yzU!vw#6JO6ThHPzWZOLx# zsx}spaQC*hpn=TNe}9&YBLDp1WzJ@2CmHjY%E`bN zi$|874p@H~Y*s0P+u2E6+W=_9+_f@nM{?5}rvdad-vOe9@)rG6Cp!seS({axC4E~W zGAVL)JF}XEckAlPg=Me7kBl4nSyFNA^)#;#bl#wtuR^;J2T zFO6*SV8bQO$8$Xs^QHx>Uele;k|T8&yak3c!suLOF#uEA0hTeF5q1NudHnDf_rBwT zT?975P9A_Y_N~}=SOyN(RH9Oge}7inLstE94rs3^e@)_u$u)sF?*_=zXD&AahC2L1 zmG~*bu-wODr4FQ#Jv$B@XL(N*KF#bFhh4ASr_V5*l2G~4o70Q!azc>cm>qB4qnO3q zI(@QNhV?cQu9JHpPD1t5FDTTLrR8kyCoaU2b2)#^hA7{CGXbO(VxZLpLSLGALNDq< zI{B@uf92$o0~%$i5^3C%B^^c^Zwy3$y=0-*4{IEJkd;!$mfk5#8)OeVoDJ~M1uP^i zIZ}#Q=>d#%=>wwxds*YOUfKl@8T#US9sL@a1FrzilKK;1rJ%r%jge5u<^CWyDwkhy z7ffOBnnN@Y^#rta$mT|<#@SN}dVnywcKj^ne{g-xj}}xN2d)+)PUqhQC-+6(1T(}Z z2MjiaV(ZoGR88rrr=I6P^u?w&fJDn7cKp2KA+}JlX2g2F3M+&IGsbH|%(;otpZRN3 z#9T4akHttzHRrb^7}6FB>qq}+%&-uK3ogaD7O*E0tl&1I6xwGs6J1Si=kh4mCJl; zB0GgL?RZk_>eiApt={>DX2939Ew7yuQ77y+KMs%Boo0mE^gx}iP%T@jih(`WGX4e1 zncl4UIqK@U{{d)VE6z~-iqym5LWuX!f2zqF?MyqA`Kwie`FEP}C-EeA^gytZPhcKn zx2HhGP_Vbs`0ksMPiS9Fmfc)!$JR>grVA~NH6LEahq9`!t`An;OF&+$01WvqQ@7|n z|H{!9``*`-k`Lv{Q~C5}7ec*rv-Ja^I$^(p_}xSfJOQ!^q5AKO9>+dH-h>TDe>?o1 zMZA92X0CeyS0sO5r0?COtep|;3QN!$6w3s41k18&{%C*ix^db94G#(E`y_+wIqvYa zq^5mgR6J4LTzS#=ZANveuI zM#|*(3DC(bGiG}?y>7Sb=HE>EfBg&{s@+?L+zbal*N4C#q!;(6bSY~0FMVmlj+Vmr zZSjm&n2wt}z45>G<8<1Zw!&~7k#2@H>cU`d^=bO#*kCyq@Gc8+E=!j-HKzx!ntCIC;;<25=)h99HyRu`2PvS9(u?f zVIV{}Ji$~;0V{$xn>R*W;V5U2Yp>t;`Z9U8LGO4@-W(kpocw`3bzE1zXPb9I;BkLL z*y={@48}=}C7B z(z1(#MCOrc3X)$s1yLoXcOBAY3gO(0j=VZJW2ru8#afMHR=jm}jzXU&tmU?cH%I2= z?%Qo!rx)bUpKTXlf0(+o{5|?!XSnw+a5Rb}2&KD!IU5&MAl03N1OoCx1p;FHZ>uSL z=l_Vz*3ffCUBUKSNu<-NvRNBlT?NKNsXz=uhaqF801GEdUxk2cYq3;WuDtR}Xre7j z>62P$k}GAM5@T4mWKD|Fe=O*-FrSx=G|bHS069R$zxw%ACZG3mIe&LIjv?hb2Ycpo z+Bx&!$9ux}-1Ge~Y3dNuXU)tMm;%;`$MV zBj)rc1z37kFguYOpGdE;^K2<{YRYS1wI zJ5V747{V3D$l5kbV}F1<=9Z@065Dj7IVm}R4uC&z89mHC?gigru?X+HKoeMf+&*PA zb;~(}rqiuL&tT+*m{cMjRI^fst#$%>(O|97hc%HR{YM!E50zVPUIqt#Bh{bpm)3CW z9*3Cb{-jb)>|F-cbk+Uv1UJ6DebwD?Wp)wjD3pWDAN1|<^MB+*-k(|T0fk(i7MWM_ z(*AX#0`G^j*8;f}`hWsJ#6>_qxyG?SYGaVZB~3 zk7S#*fhE^c!;<7Yofyg^MtD02mwr$60{QP~q-d`#rwN>#@&CoyHwK5+rEA8vofF%( zZR^CgZQHhO>wmpz1Fj6E?IIXZZ;Ca9AWO@ zgp!y&Ao03y^#W?l7hN4F1y&SJxHqXKOr2e!b!4i=4n9MogB|9 zL>HjH8>fR_8)RLBUf-6EGJo02m7><$+nRsThPeJ>e1BwU+HG4_tZdO|xyHh-N{a`b zVXmMO9oTE$jC#w2yBH)V(#<{exGfGXe8rnC$a9V=J%V7EeB4*@0cBVk%9du1 zwZyX|bg-&^0#Z4jy7D=u$4X=7-ns2VyR&q5Q*z1hiCydhfocA|B=>;su%zbGue;G@ zQa$*^XMceS+t#(7Xe`GuKWB{wi%ruyge8M9h1#TF+o#sdRuohyJ$JCoBDr-3+t^^X zSX}o`6Eu+h@SXDVq>~5}*kp0gkl(Mc;NT5yUv#b-_?}|e5)@NVq9#Uw+^o9fdafef zOcPC-s#SBdSmo|IVa^Hh)Ns+TjT5_Z9}hY}!+*wI`cY(7_PL*MLfc%SBD(?FNU8hl z5Vv-TzSf;8`I`$N>lOfMNaxw(l9f zu0kPbA43d!Mx4qhSMgVzuVi_@+a*PD50Xjc3oi(Afj|V1mEU|C>_Ie6KFcLq9W;O@ zdVdqQp@Ga~8YiKNG#>II8OalvkN)B$-gzJGB&JO$g;bGjUo2tl^1ojgRz?7v##M5LxBS6(i1EDu8FZJ^TV~#4uNeQ6 zp8P?q-!XbOVc}yaq)H~&m|gd-BJ6;r`cS)x@_jHCibaKwSj_au6{F0b;+*s{H-=!C zLUor=Cwsh~>KzT?v#WbQ^ zk*lbSwuRh)3$+d%Xz2{{hSl$htg9uue7%A243r-8z}1huAPfLCZ|T>ZR?Sh+XB+2F zgeF*w>V>LN(jIF%GVMfweF=3-5u~Qq#m-MDD{Ph zwvjt&<78`NY-IS&_nswtMD@bUgjc!B9kE1FrQQ+RXd-qM0~P0a>kLX`fI6=|u+1s# zh5zke6|%m{fqKQ^?rISC3^*qZw>ueUWtcMFYwI^Po@PkL4%v@5Eim*;A%D)X-d)sc zy<#qZ_pEBIc!P&O24*uGRzA}S&wUMbEo*!w%ZVNs^Fx@Oou73OwQY%?;< z1@E@8w$&l@8kN13O)1}|)4KDhof#>Ir3{dXh6W?Fz}P!_n| z$x*u#`ETXaFkj4m392m8SISU@yA6aMt-xGgfxA;(a;#VE7D9qF-G5NM5Mt@b7nTbt z?fv&(BC#X|z{1^6!7Y@49#z#+lkhE`_t0a!uum}oipByJiu1>`_NnUyWbbCh7@*Zj zg?S==JCg4j;8z_5-gUVyTFoJq4ICwDY}r>|9^Yu`@7fSN#j_e*0zF%*gjtD%Fh6u} z!Ta#_e!G{ETaN-l%zr8I3+N5pUuAkslAIAH&{8q_mI3%%pqP`Y96+MfyW=!p0Un^h75jOs}YuW;*t}r8(^Ky+HIwOB>uHS zp|4w1-Vq1@;N;I9^Z)1_nCUwhx$6IU`CC(_gRPaayWKxrgk+@~xdnL?9^0$sYBaVH zc;f)V0;{|z$bT2hAbLHlL`u@&^dULza{2k@q6_*jHAW-?EZE%7!l-AS3Tad6W%!%l zo1WM0rEIl3zFuEodWdqUgBZuuJsMV5xF9|Q@VJ#K+;v*{wy*x$n@oY(&!k;d?>ZPS z*UO>6T%ceYLO76M{>g zZ}t-l8Go$ZW!VMm6Yp%i7RXBx*33hZCWw>dlf)mF<>`YpdJ*(XMCudho_dlnf2ei- zy1toZo$okUt6iT8!L>?eZH^^1}hKQfq$cZPanWF?x=A5>D4T}F+Hb?tc!c( zil3JjQGhnY9Gi~QQ*451XNf;bh^rn^gE>3fXq)NQtBN(NjwHR3%R|si0 zhT4y?cdHGc0$>3W5KK0nPxSco*$+{ZTHMahAZA!5@m&N9BXX0k-w-kP1LR+sn56?D z=Lrx1Kp6Pn4d(n46FWE=yGfhdSQ;A%DSs*%JGj{XV=zZi+Y(s-g=e8i137VVSouP1 zDL@Z-2o(j9GB|+{!kj!@nf!%59d{~iE1jJyQ}sLiJD=`N@wN|tHx}u}O7J`|pbh%@ z;4;Vax{Ha=$LAex7m}4qU66pkKEgN&15eBWtGoF)aWOn%M1L^(69bA?RI&%#9)BCx zk!oO?`sNXQUKUp9tbKm`ik^G*94avgpAj!nPS7%B7*Z(7@j9w$i<9~QXdIAI<)?7+ zUc6~Zp~SQTAuJiAGbtG|sZmCPQJZa6J+5Ikx4ycBSIRY1Y02hTm_P2T|G7%lE|L&W z@^vqc)JCc~8du2vvd#rLf8gHP&VSOh)|7FFWUO&hTJtJHJh6FzF`ZP%eE0r9TAb(# z1RlOar57)Fq)m}xi0RgM;)V%CP&QTTmwPLW>wCHjWjx)Ja&d$v$8HMQyhLYZv;8JT zVR>yd?MgfgB`4%75WJ`8a|3$`;{Vf?0lE?nnZ7Hc9LIl6U_3&osvgb#LL8;zcYV2 z608i$Sjiu0aU`lx{K|gzIDh#IUTumJpa$X}R^k8y0O0)3*-6IM$=2b&HRG1-A7=Ur zNui~&d=(Sv+sD5mtRi;{WFW{3mmmRyAl**WcMVFulFiO0d?V%cbNxxKAo1%K(2M*a z{Y+C?kZ{fDIIHo*Yv(l+pRdOooIci*#EIbK$4vn?Xh^X9-4K*LsfSh%*YaBa3zwRsI z#-8tZtfi+0wYXhf7=P0n?oAs;FHZ4;EvJQ0Il$;Y+H9Qf08+s2eq7et#pGKSe}mqTIWXi(#I> zYHxi@8pI7DW6_P?U@ZIWysMK>%LwquJQc7M80Fdv&Mfj%5`-;kh|=Xv4xDp>Bt`eS zXSiH^RY)tV*-0@%J?6F};?KvL%d8Vde%r?GSzHxC3x)q^$YX_i8pS-4ZmmuR6ipv zf#{NK5F#lQ1quu`=Y(AgjH=p|L7rg{7}FFB-~GVv4S$BS>npKAu+=9WxUYtD^32`y zy5vW#vY+g4vkrv`+3tqrj31rt373|iOjbf-=wcpx++?H<#_{G4M#3yu_U3oJ-bE<9 zQFttgv3u>MT6m>)<>%#?U=(Hl@qx70vDheZz7A@!4AOj_);zCYy~}zWb_F-)?$q9u z@@+Hx9e*G{<@E;p9cBDn(p}&%sn+s3H81)y$YIJsxxBoycRIr!Wn?j_(SoBM9`(>7 z0R7jwHULW>!KgoimH_epC20SwwUf2A{*G5QOARUI-z1_X5NRMGxKW(aoh~`V&%&Y? z)PjDsRL2FY#LCsyC^2Wd@4744RksX{U;8P~n}4&W{ez}lzCY2OgX6?i=XmmVrpNaS zR1Yr}YV?Pte(x~FAx4dR!38(;k{qF#l<&k{8;q~h&ug3Uyyh{X8&LRQC8^&RgqM^d zo7$M8X8!q#7Ht(*AG3SBQ`Th4*pv>an3r0^q)Yb)++gvo@^uU#nflYKXH!?Jf*tE? zXn&lF^%P@2^I6&*Rh5hSGoXm-2k7Tnxw=k88zzYM80yGK(-&Ap>Bs3yL>84bMHN9U z1zkVF^z)jONs9@m)!8i%vc}x@w6*0%I2OqT@Z2)`eit2McZUsu{tA7j$!fI+#HXL^ z!S#`!Ok0oZOSzqofNK?2RuVv=+(9Q8cz;rSbxY=kMY*>PtL!|HN{AAtc}lvW4rj<& zvn;|`OBuL!ISJ_8A%ShAcu=H39-&PQlnC=$-Y{J9qYF+qovW%!-TIw(Ka5T3N<_^j zlJl6y;8rziclI%h5v|Tldv+Z@d4C_hz$QDQKalwon8O8zYZ>2&EYi9qMh7U$rX8U) zc2H8$^%aC-K?r$OrR-_M`@C5cKIdTNjC*RLIS+)e`a}D&V5Z0KZaTE?(s$p0UYe?f zNG~rT&J`Xd={ce}|5tUrV|?H%n^_xw6QUUv6WxGM$x0ZTdG)a3QVB%k-(Ua@3xSJ?OtFx}aJbk__~V4n!;Pr#uaz0W8w<71K#S1MmU>Q1S7tIMJ=K&%;r zOKK|z21x-tcB*SGD#f(tuy=49~F5e=&{uOA~ z@!C!&?a!(i;NPVm|F?`Q8QVDiw*{q%W`GNz#|Yku6-Pyj1&q|@27h9(chGa9Z1zVg zDyq(KV+M!c&5yEvl%dnr>3;s=)&+1O$3PM!nF{XoX(?gRks2{Q`V~J+xee{v9Vw5+ z!eNN1*l&Ws)+ff`{ILor=>c?+R2z&Q)Kn$QlK&DY%7>z_pb9RyomQD_Q9I%nk!y#o zjY(jIkO=aPgt-qtK!1tQ&*^aZm)_W(&&rIFKZ-018~}jnfBeZmdxpl2j^;L|bV9}s z#s&_~*8k98D%!5dA{aiTG9A_ppLszRl9mDj39AjL#Q9j_&>2{$0y9QTq=92L zo7qQsD_?+go)^N{Q)1)F6&17{amy?(8uYbRE8-00vUm$upJ`lt} zfWZn#4KR!_dZupdD#x-roU1*wRwMN7L^u_z8DWZ;lG#J(t$x@L<`2<=4`7&+m7o7x3Cx(pcul4YL_w23DSv7aTpl@ zg-ZCdr)CzA;D7Wx5NJ;(z1^OLYuc^M)4DfPctALS#n4kfR_mZu^rFTRg||xoidIH1 zDPfQ>$m@9xyyr0 zW|!b~iB13kdu`a@ z3ljqPre^vNNYH z%tUE!tbfy48<{QGhUMt9pMKJ^S*DfW|J>tBOlx)lp^pUF9d|pXNQ!2DiNw4JZNXK#wG{T^Q3G$d}dbF={;i++V8#n+37 zK#>u_-^Ca}qdi-Ahv6Ef9Z{?wN!#dGW<|Z&ZPJ;()TTzrP z+<*4eKg8O0kDBEa{Q-~o3-aw7r(^-KV}F;7LFj@~QGEc#Mjs1K!DpBnCD?=ILw`7| z$M51LK$dBBFqJ%UOJUXNixP&LA5=Fq{P7O9yLi`jc7+-&m!LoApveCQh8PydH^dRF zL5|@IBpxDs3o5z$8~b0ye!f|t{^`%k9q`}zFaIp|wl*f_rV=(z#ttU>hX0*Hk$>xx z9iWHt#w-lB?hSf@KnSo~jXoeAEb52L+uEYmVk(x9(29GZs=;{y;Dy=?kr3YuGva$+ z^NHc>+2#X~wo5A@qgUuoa#jG%eIG8iS$YZ` z#r7yYkCb}yDq1P3rZQZFq`{E zB8O)@eD>Zl>Fidt$>^BnF5)84=k%I_gVu8Zg#Nug?CX7NE&n#`q)6rq_v_L|3IxPu zmdD@wl2BiogDVzh1G^LN_bOSucpEInCkjI^{XV%1uGe2MgnF|Q&j$ajuzvynT@e3I zhbijtw+Ue@X^k{<#P)l1?b3KHN4x8uf20@O+A<#=IC-(@E9P96N?eqzv1`4{00f=2cG zEXZP&Bd8iA2P{!8>sfE_qDXci&oUxa_O72_6f6|3wfS^35-9HqVt!cokDmv$R+})6 z(P0!0KXsxmLVx@u53C*veH=3*JN3*h*9aeF<=Rg1g~*3{g2GZ3wu|o#pg^dWpb-i? z0`9ol6qTXL*P6e5J7uPLM%~j6kV5@gVgSqvWyM(SFW#eXY(KfpQX@Dh8d~s-F`hnafedL&wrHhkw{DM?3Y#&3YIf zr8wwN(0{9P>W8a+czy5!C{7ip{7gyH11Qv&M7U3^iW7OIG9L#^mgxbO)#4u|1>h@; zbwkXk5LhkBdI>a@%Qq@| z?!z|Y77{w4P%V+XlkkZp=`m?%1d2@aCPq!&MLF{P-l^GW!syzen{J<)KU3*LRW_;h zReupkgTWLP$)Mljh$q7$wCt!7%Sn(H3UX>)K|W1^R2H(%7_Y2NSd-285LOoE?Lk|i ztI`tA8FAZLyLOTrsTUM)bG&rvC&k5{4@U?#!vmqVEBC!$9Q|1wg-7$JXkRf{z(~=?+pWI@DPDSCSwi6&QHduSfv&{2TD-^lB z(96e}O`x%tcm*n_V+>%Lb3rKD;PzmS^rzI@Oua1&psQ??DYX7;TV=+G1K$iD(6LY0Md9`LPJCC!hbCj>UTsg`k5J1V^zfDd|k@q`POH{Wh?62Arw6!*{u}E z*N4S#9v@BrZ5pyK#MhG@l@G9`xR1zj4&>i_ZUqyQHK5GZ+`hNij!P`}$dk3Dt z5S&(BWL}jQ5sLCuyI(srh6j08&`rNy3Z@IuW~4?$(kTTEa&YEWOWpMkeCmawgrV6iFsxR1sG2glEMHVAolEERHW(BT*xN?tF!{XA-H zJ#7VtjX_DxvIjG#h%;GWf)k%&x<5@>`~c|JFdLTs!FKEun16(pFk^2z=vZP&vWHja zRuVDoac_|%cJ+(f8QR-{loIdWD1fWx{Cs<9yT#U2>LMnka@}yK5KRsQZm~b{DuIL4 z{p95)`;4;C5$Bn_xs83A=*+7MeL974I>$C%gDykS%9-Jkqv)9HfMUYWPzf>h7~Xqf zOJOkN!{{e>*MEJRJT6b*SR9Gkbp3W*i_^74tUX@Vn{?h+R26vu*`2e}xNG}(yKl$B zHiI+cO;r<)Up5laEXPEUN6V9Bhi1jtnBNM4+V_!ZWfXZM=9bV|j>z+xY$&R=*N9>5 zvn`c|bAO=&T>QC2a6A}Mm zFbZj0-0~zFcQQDzQH79X93H9FNtB?&ba25kFG|FR*U5vaLr0GBK_G>`cSidd2(A^! zAwl52G)IztvOY`mDU3mVF(b%tu&kk_eeN$6Z9oNz6wY(r zobR?n%zy1*fIU8-qs%lu|JN=<^;?i6NaaUWkQ~vr6?7epi>FZZ5f7<>lOYe_z2bTu z5-*=BHVhp^Y_TPbX?rps()i#a(PvZ@){{Z9|+?g*vSeYqH-I3CbOY~>7@R?`zdFa-58h*gn3DT&8lERY10R(tc;o|k3dy&SaCn>- z$OE*W4%!arm00}MZasfZbZ!sd-I`7}dUnC~^xkBdK6_xh*dcfz--PUhztX4^_)?fi zvw!6QspVmA%!XVgbzpfS48flEU!4x)u7-o#!{YVPdSNnf$5^JH^I(i@n7`t>!L1y4 zu8P61%{pYYAUCbbWwOnm1Dw=`LVdpi^M5-9Dcs1SmsecQ_yp&JSEk`*2v>ble7gUhRwq_??j>KX# z1CNQ&R1ou7a_ovwtO*9wv~voBaBkDp5th}KF27LFv5(LJMKOzL6BcL$n!a5jZ<2da zf$9%r1zy{Ff-Or&mDJyP2-Z5I+Xh1WmcaZC0gR~S?EJ)sWw?79Ta zoAUT(@$zV{IK0E+aei^&W&{+g@Ngivdy9xOy;nKCb2k7pUc4IVy8p2KRQu}!ojZcr z5b#@5S{V#Feh3LhX&)eiUNB%&aDQ!s{F4^!+QrNb9@&=+*&Bg%d!qHmah_TTU!;AN znAY`jiPJo#`B=4H!%Cn0yi4Y$+fr}bh;drzOak+shpaw5e!C)Um<=E#2lWJM?s6${ zMzM5pN#_D3D17^N!O-pZTE+=t#n|2|f$g2`;XdN#fc1Mc(xIB}Xf0!t?|;bvo<^)! z%t7TS(k`vZsZG)WaG8<9&uCALZr-RV>QL*Kw1Z89l{PnQ4XBfA$vHtYbS{=DT|7!d zKoqUH>pt&@suYczoIwY^V+m?Qx3z)iEu`ZYx29EmppX3B7|*Bc7@{^;ATke2%Zib^ z1%?m8P+fEYU9kkfT)&S`1AhWs?Qrlqv|Qp_Imb+2FfELFT5jfaOu@U}TH!$G9L7lD zO0$Q1`H+NQvU=q``zGlo$CZwpO^KP}o2Tv)}ayce|K*8fO%@ zR(|-(YfJ~UpzZMUF zO&rPz;$5e{QrqABW}%%rh`Bd8Gh!!^f<~9c9k9%9PAGKdP++W+2bnA+JPo{9R$Qsx z6qv0ZDc!7y$Hm>}*_6a{(S9%duuVRI((%mRP70GX-9AOyn*K>p#zXD`HvWbGuQ4YrGNUx#pJ*Hv z=s$?a#s87T6>&2(w);OQ3fXZpvVS7-;huX_bX63Qz1_ZDSbBRp3u*eFQNsi00x-{t zSY>NlHXS0-wtq)sgMsk7LYNx?b0BiR>Ce0#rfk<=U%WiQ?Sf4FfFgJ$S(5e;FSi%K zv4)wmLs}n{BZG9g8FI`Clz?ueiv-~zGO|xc*cK&=7JOWl1%mZ%A}Yp+R6a6Htm9ji z$~Ri1X4SbL!ejk*gT{y_P16$$%RwgwqE0j!%iYYFhkqY70S0VmYr&JIkAjdFiQ?}w z-5HP1V`2;onF+_txC%7;(7T$@Kx;v{9YGGj(`ITGzo1S%7HMqcih;j-V4N$cQg?#~rA$nos! zw0|F1W5os^s%`$Ee3&OS(4}P?TOCS3_8ZOiBPK$bTs)`QU4Go}9s|Rpl`1!z&8-K~ z(4J-LG^BEmhs7!1}eQUx1YxC8Gma*c)gjx|i8vx&KOyI@H>ztv}QN{j(?h z|4fa)H3|H^m`VJPcWY~X8zaYmBx)3;Y=0N{5x!XI*uocr=5KwJ%8)6eK(YcTi<-pa z`-Omxy6sh?sWvvQZ6xD%#q0%-{MetxR3_I&VFQFH9n#XbCcWTiaXZ8x^pSf3N95>k4SvyrW}MT3rB zmm=X#mh8?HIid>ninTb`+Y!l1%fQ@BPthw|_R5X~Lt?8}&1N?=q_WZQ)@jUEj|*4B zWTmCy;SmP~1$>1MVQo|qbq$p7EPt-cqE-@>W_#$2^I%jEUQ9*3Nz)WaJCOL`QBwT9hvjM?jo1B&+IP87>J})=Ykw@-zWE9E zJ2?W#MzN|WRjf^9ZVJl|+m&1m@?3{^v()BYx6>0QbdL;6nHe+2zTS_iPIH`lgp-#B zpv4{^n_@SR1c2@v_9Y#l=L5LTFVuW9DD^jE!*(B$vhQC2m)jdM-`W2NvL5LFC;R+Y z8T>EoqpW4SK##$5y&l|hwtt+Q{GJ`HgE29@TW%&uDU_kCXHa%yZc&|{;I?|!A_jsa z{-e)!4>B5jkckiKj$=%nEMncj4*kTlI~wvP4KNq;CH5)>1+d9qsD zYBaAKJF3wmx4NsN2#|-GIY`hi*0hWk;UQ#!k!GOIjcabH#YLBy%tP5&MPT&We&$*S zt2X0_1u~IIvX99xa>IbMx_p)UY3#~99amFx;f!wAHz*RFfyrMDij_2CoIQ>jGEVM0 zm5Qjs6aiMlRAmuzet#vbzM`-Urk>4N?Y$^60c**Gi4q)nE5!_d>Y8`pYSGbSS?smkyn z{h>R(ycK16cF|ZJeTPRt^f`8nbXeic9zkr3+~uC_+-AwCRDUR+vvb{$e-+vjO+nCd zpx;D^Db-N2KWa#EVu`Fs>`_c+n<$$qA11xGX?d4`E!vax%yN&vcdn zXh!?p;Owe1)fMET>juXL7lAx_bhMcn!fF*7DmPc==^qu7qTi_lf_2_+7F3fjA;!cC zc`0>Lihp!H*p!Gr;pwt2Bdt}FDtCfQ)z{v1)WP~xbg#30Ho=v{B4w=Pa0q3^VnHq; z2^xE9mOOu0l8VQ|(Yea0LUN7<>ML(E`aVn!^BfZNw`S-ol1ze|=pgMZSX3c_{U7Lv`G(@X0g!%{|&YCmx? zWdfQLfn^N;Xe_fLGfYXHA2l0RTBkLDhbw1T%l~knYYw{6h?8i7Viu`-jdy!OK@idw z0*9OJCYsmm5$?yT-x0W6RrWdl z;eXu`mwm~!fD8jZt==S7;d<*(OJFyso*HBXa>ZV9z@AWaqN$S{axmvC852D!U;3Gj z2!4aR>;KEZ2;0SGe!NURHV?ei>2be_ANh0Jc52n!ayF|$b=_&zu`K!Lo4x3O2JXz> zW&;WhZC*R|n2?D~(>h7L0_+JW9G^U6N`Jxqq}6)H?@KS*0KmnuRoOF)L4-p8IMBDk zC3ZvjEKQN|$r^MJgG%djIjY9&^yCoi6zB5aMhRvzMDV$Dd(1h|XlM>h?Qc@D$Mz&(I?2#0BSA~xr4`gL6nD)`I$Bcki z%_wg$Uu9ZIMA;p%)w5U31DW1w6s%sG1Hvwi5QMK)<0mhrl(l3jAv8Ox4SxmcIQ0y0 zi4{8^dNJNE=_uIK)H%bU7`cV)EK@{n_cQX)an+iZ*l znkJPiBQ^l&p&D0LL*84Tb3jlmmNSJ)ZYSj0X}Kp!EaU-{%sRW-_@z~u*eLZe#g8{` zLL;U_LR0!uhN^}M%ZJL&pnrO-TTB1K&>^EeifWBL3_dIDKMxbqJ`(UoIsY zVnWHUtIo@ae^=!<+b&Ct7S(XA&pNv8fErO$Abb@UqDZT;Q zt_&}b+$T2iq1=I!Y%Z|*Va zb2oei{|&dKY+8T#*_`vNkuOl3Y^}G}LHSa8?&(N~I$T8V5Sn{u|7^E}kkg}QpdA1t zEo{U`hb{Cw5@WmpvRC7;1wH(HDWOXtD2M~9mkRiId#Hw3XT+mZmDav2H6S(SjxsT3q8LZ4bLvP*~SUP!LgcIq*rQ zGZx>8tQIx3vlcf7z2Q(~6BPq0cJNDrQNSWyBT#hJMa{e3bx}$>{Q0yy7XKw_`w{tM zHUeT(1J$1lwSRKf(^2aCaJ>ygdpgeLn8Ggo3c~OL%J4#Dc!?bD{Bqjv%m34LPj7h-M4luv|rO(;^C^ zD8ZSrpb`D(Z&mrM;W4F}Ep6t7;5OTm7Pm2JQLzW027k5VlrN8($5Q`!wlYOZp58bL^lJX+l!R-SKmul-*2f+9ws|4n!Kvh&bff0+ zc_t1MkDPQL;CJ^9vM-|+uxpG}C9VHf|b_yPX| z`z-&r&A;~`{M|kWM|H^p3%~@8_}3vo6ch(gl1K@N1tW-ye+Z-J?P#Uf&6(hCU5o55 zk-GulLG2a(KoPHJZh2Z`%GJHW2biw2oh8chNPpk>=rAivLGo&Wo)-DVY?bUj%~4d2 z>w2p=FO`O6g#>3}b7tk_;ZbIK8QF)nXC|U8srVBz;d1Ck5<|Mknp-z?6ziVssi+YN zu97vG{^TT12-n?sD(GOt_kfBvtK%wbR<~o-;@)iPLfzoj)`EU%;qzc>YblI>RsLyC z1%Ljy)Yee!ME;e(d17_o_AhN3Vu;o{mVZ2KanS!DT>h_fQZ}|S{;vz({}C=LY0Ld> zHUO9gdZSqWPsAdb94i>F!i$8;!oW;S`p2gbcgwO7!)Ul-?OY)JqRusAz5{cz(_WaH%signt-7V}xtK&`;w&;kkbM<$aFFIvre!A-X-< zqI`o9GGRG_CW@)!DKK%QBNZe-BtIXyNg6wi1qh#6gWl9Ls?<6nG=|-6$LHEkhpN^< zR`Jsw8_jBqYNSrHM%#r;G2bfpdP{gY#yX0~R=>ZG7z*ad*Xf&>5LNlinGXUqaDOOs z3SP1aLnpBMdS5x+kcB*5HMks zaJ~UAiW=v^-JkT#r}!hhI?p&c9siSJOZ(jOkUiMA35=}3sj~C`2GB27J#$16LHTCkAYEgY2*U|+Y5f?W=P&T-+GG#JyF=1N3hP$~3Q&8aUeIG0wr=&rG#Q(55Q-Avg`i89-Tw%gS ziV;U@v3Qs1d49wFjPddP@_cm#$h=bmVUjnd2B9#X-(XB-11*Al@!(6I<&674|pJEopZR6ZID zxEZHWexy#{;4_G+_(n^Xb?&k~2FYbyCXoyADw@RV0>qkiu%t-)T{n6S$B{lYpY%W@ zup!*Yv&PzT#-)_Bg-lNtTK5g|VI8p}_rjR@96G1EdC_rl1b+xj$i4q^Wj--6QRi?) zt+ptY$kp568miv^!-K|`VFXDS(*kv~w&N(oSe`X(oW`aZY^zuL~xHv<* zRtZwh{G2joDU3nc0@y*(eS|_psU}tCQ4=ry^2L3Eh^1>BC%0;3ltOIPe|T5f5EKie z1w2F~IO2G)zJDw?m9dev;;jgIDiMJ%BZiVKBbhP-Gc|5bKp))*b=e@>{|N`uDlaRi z0}_QKe(bbC-z>T~CQKl{4%Aqu^qw3L`(VM&G8k>8%z9(A9x}5W0s1vco{@Y|=*^KcbG(iNrqG}UkV5h8H~ z(X|G(r_;mhn|y>i6PeACITs=Z_U7C|A!HK|)s`D9k^ow6i@eMO06fE0=aKLkdaB*a zS)`1zdVh};iTp^C#4$HlR5v|3Ld&zTA~2dc%O4YSr6j{--U;^#FI)3P z@|Kul>~GC}iVIWtD;k*xcDwT`CB}5Prs_Qb^`b7v_nmYS4tHSAED z9z%MF8o`C^CcEq-kl7eqH%;|SNuW`vZXpSdUdZ#?yd!tqIzNEcmMI$^1yLFG^T{S$ z2|vucQ#o|{DxIh>$3a2@>nS$-P}C2`Aaq8s!DJn>`ZJwO4QXi3(B@g!OhCFCt5fx5 zsedu$wnh=0YFgR1hq?4!rJ+bLJZ$E0NA%a{#mIq6R_L^nCg-$nX}1b|fJA{c{2P;2 z-@1bg$H|jX6s)vKi)H$}lnSx0x&>)zx@ZyGR8t*f^j)E6=HCe$l%F)Zeez3q@0sU` zPEfPv{4Gd%{7v|#kVVGgWm|XC8`kDC+ke@zb!uxv^ScXo$*IUXX?6+>J8?!-0Fg19 z^$R?D%$uM$P%)Ly<-vcbjZ{XWfj2c&ouHX9A6%_BBS>kwMGE1|wA@mxz0?ZUbvMxR2Cy*M@%zU5>1+WDuQ|X)^md)Z6L}qoaJ%6hlW+@X784X0-#Wd_ zX$D=DhR#XkLW|kO=_lD^$T0_vmVaV|#AAlAfOLk9$L4=PtH~ic=r}t+L4d&qv1UP9 zvtwFxle!ykEi}CixV1pMnI4F|HH}zy1f{-hNx4~rlu8NSoKK^y)sA$#MkcP<2emrv zRTLh`BMt7+AJ1{ZgPoh3Wy=w0`vt2D`~MV#C5@<75Ajxy`D8YR(<5=dP=8q@R8y)l zc)_%^!@Rf!Up}CNdfZ{&77-Ug!CtemGO%7{MAKc?iMkmPsHNHR02Kj2ExyvLtl6br zyOW4R&E01TXdZm$xaz*WBk8`sW9cTa!qx94@uW>s+xHCMOHum*|5r;Ri7I3y2o3-+ z3-|ACa{Py-5w&$NH2!B3qxSBoG=hKng|^m_@@rI>Wl$ahia>x7K7CL|5CuXsqHl2+ zq_d<5zN1@n0$s{=XqyVyJfx(S*YNYrgHMzn>rMV!2apR&*@$}0A9~Pqkp0noQMlY<0NoX!R6yakCL97vU zx*i2GBpPf3yBe%4=E}Ho{y_!cX60vjmsRV03l6h)NJ+uLYkxCjHY&_KV~kdukr^Ip zhnuw78d(KQrYCxxn<{1J3D1AsPn>FX8-37`YBR%A^;N=*#^MtW8;XtUMr0fy1+4yeStMq(~Gu@#({VEeP3JcSp$B= z;mDA7>MYF_nGCj`+`q7M97QkR0XGReqHMz@o1B}#i# zi`*+PHeg>jT77EAKc;eWMu z7I0B6T?1dFTM22Tk!}P8q`SLe>7^S)LXl4C?i8fE8w8}Kq*){lKuYr4d++;xyzcAu z)q5}e7MN%Go&R}e&YYQfcIKSJbIkn%Z#-=OHa#-5!c5Fl@;%z z12G)Xj9!f7Q_+7{(TD01u;26Wb`PrR=_ej8(^@sy@Q=BM&A}sJ_KaV|)3s59V z%n2KQ=sl>(S6;&sMRb(8dYg>XAc67<=uFp-p^Btcug&Q6x&-gJK6RvWb%ol){Bd{9 zH6A}URLDd{FR(1NtpcqcE(Q@zBx4EX<19{-OSaN$G_HSKtCmMH1fMokU$8BL_mp!B z$@2Q1HhQ3?3i1$*26AxV^s^DyJNSXwyb>m6i4QW!`qYAH%N(Y%RFRYGAG|vnc{tHx z)t5Tz$Pc_VCl#0A!_oGXMduW&KXDlJsb!8)q2XE9_#tj&;U1@G71gDeyfxpu%fVb) zsYaT7(<^_)GA3!WvN+K}%dot-19h+AF1kpIJ;rF?@rMM2Qs>z##39!7_%ktnjJd z>fZT!0x!p9w`AVOWv#mHY$a6`?*O2KoTA`_{j%)N?txZqk?S4i(C=%0=mT7EZ{{bY*1TLm+8B`LOb@a}u^ zY!ZKtjAWZVNfP@yBOOzM1j>M>jgf@MY@;o0tLYV6%BW8&a~RJlKCtAU%#r3ATS$Ps zgr<;Q&9gmEIC)y1w8!>}U&-0~9nZQ4#(;Zc*#RtlbT$d<;)b==I4ePPDS8>J1Sg`W z3P*sciF65}dZ<_XK1Uk0#}ZhD*05ktYP5gr9{#81&Y94|l)kP^do)OkJU}n#{KyK= zJ0@gEpYpO_t`@&WZ4{nqO8+f$Hfj8a!%ON2QXzj&fPFjC^b(3SR^`mCmxkjHdh}$9 zkdw4Y2iN!wFmJQGS!3iy4jXiq6!m<@U&rlUq7|&m}Agn+c9~PPb%dC5PKMX63&`>2>sv7@gw? z3O`3*?OEMd1@>ovBo(GsmE0FOak^g_k(_;qpDAD!91rcE%5b^Wb!}b z4m$gUBA#JdWYUH2d1gi>I!t~r$KZdP88DwZr}S=mHng0mv9hkOu8*yDn0+kd@ffX$ zr2t-EL+XV@Dp$Z}p(72}S?0yaV=wosH<+8V&UKN_Uo?Fc4s54qTL$)Sj~YCl5M#mW zIi#ANaEI?LiO6Zf8mbKSs7ldtBEogC9#^!X1Cq2RxEtNt-6!7PP|tIW+}VGgsYJFn zLA?@wzxHVSnJ<|1BFG2bps$tj+4&rOG2i6t$_O=GH{*v-@E^_!^Y>V(X)0uewFY~2 zy4RFYa{&wYAyfT%J%-u@nS&k%})d z={(31$SYcoYZ{S$ANkOk@=B(p-f6v4cat2+Jruq-mLQTnhR9q~n7@DNu=SvbDCRg# zu)u%TVceBD^?Y29klww=8=umX&r_CLov+U_m#^=1Ao)ZK;ZY#u&@|n_ z#;^k*O-jg)&3rrI67|Z2^z#&~EjYn$voXs%x~a#BV8zG=sHV zHwhmFB7Bl+#t_1~q^VnBh7tXmAW$wah&NrA`{5yKl_@;?Yqx)6#JLu=3Hz}ZPg5=C z7t$ha+etrhSE6TP&9)4o+}dX7cYfZ2t(D)zh#K6F?xnNxHXW2!`c);PL|U6Ap*2wL zYAR9(_5>-9MF&-*&W=sPWQbnztZkFF0ydh|roWZuQ#UhAH8X>iwtvTS_pQ@|fwY9i z`5suE4TR;F(;9#NJMqHUPYz`!XgKrRn{fICvCkcavLpwZK4`J2>|I#Zt(~G35^<7b z(lZQRk@b};g0)R`_g|^LxjiA%=f!JV#`=cuey;uBH?-`SmJ( zY~2*&;z@`F<$EHyL z>BbmnNz*)M(^U>NNa5TkXssDXHjkT0OGwmFqaHf*L!~KjkRUUtC9DF)2f-se;+9sd zJ;Bnj*iV0Y2Eyjxdro@lznP?-4<{JJ3%lt8XOdY{CHHvnOTU2O00VLwqUsk^nzmqC zxX4#5Y;Y>-FKP6fX<++Ygr~dnHn}!TqH-<^IeOTY{f1ZWe(8M~TRpkSl9u{rG^2p> zE04$LdBO=4oi;}7N&g35c)<;?+LFP^aK%Lg4sw5bJuO1Z^i*FA!ngv1^(%Imv|l0F z5WL2`E7(F_7(LCp+GU;l(4J0qrOS5g5=NoYMfshTw@0R0m2it;Q>meWY=94lbF?=b z?#zDCg&(`$ucJWbTwu^+^*N3N7^RG`!F+9qoI(?ww7mKPWkEdwrj)T9N1`Co%8{Ip zv@L&%$dx?<#3eJ4S=+UjkCI_KwaK_VzD#1SHbqRzcX0>ad6<@?-)Xac;XPhsiQZUu z18D(BD4D>rvCamM9eso0!h%`CwQ`#7+XsIk zwso=HWtaEjBJM^%C2SkfUfF)%9WAJGX?kfsiWN>YTd_%Eb460u_WY2d?nV6(%WPZl z(j%k(ukO)bV>d1c<`XNbD@2wa)rw%GkvBewZw*;xPD9G&Th z;}u2>4cJy?mn`W?MEjYhk6tG2fg^R#r=l5*5iJ*Vi&d(HI z*AWdQ*f4)M6ol$UL40h7ZaPMlcgxLQ5r}8dd3lQ5TsA`oMn_v?`p}DYyo!)o+eh!Ir7dddpR?x<0rO0 zkhyE=^}1WOW|`wHQ%?n`cJ-Y|iI3r6uJUFCQ)GEB)8c}OSH3EJM&xBL-4rk< zvs>{x#|r^`UY)t_OL+aHp(p*3mUL+}t35tg?ShY)r7O5C#B#k}%9np<*i&?Waf=;! z6UhKA(Xb1X_r$S#=)#k_BWe%)RQZ~&kKPECn(U4^3FuJVppHI0r2U*eB#7!Wtrqm8dnT zn#{SqP1^KCBpCJ6lZAf=4zPw^d&rn#W6oZah`!I-g)=>li4QeKsnFKNV)w>eOLmsd zKE12oIkA3pc`FNcIZ!Fk2_2U>zQ}lsHSLuT1q)-2_M)pwq&-jB+xPx8-b0Q~O|e6K zpqI3Ax+wJzW<*f~i!Tdo&k*qkyQ59fiYP~E@m@>~!}V@OiV6BO``bc&XOTXnc~?f+$8M~Z z6#~y3WIQG&BN~4xGf3O-P!`{6(E-hMI1+KQTedNTI|h&%5_>9VWaYCgGB)l;?+F1P zbS!7>rSfp+CTDjhCVUuxW`3wTvK}dpc z?kHDW%MX*@LkoX-i}<5V*3#jbH|-3q;`#tq zG6wL$vE|lEgDwn9S(7L6vZG1l?vV7E_CaIKUjBg(OMh!aR5l-F6+7)jGd{(&u5A!X z6;9jzW9x=YFo4u(w(Yeu4w`J_86~|jn6eOGD^X-;ou|l1COJ0r&ZdVHn?{4VxlJT? z7di3t*zkWoD=BcR<-L`W7J<|;oj<-S(G2H(ja3hRQt4ufx!gcX;#Qu)v7~4p#?MVu z?r-GZo~WuB`P%klNG6#)oe z=XIRs)ev_dD!zonbmotw#kYEUFHh+H5(#qu@K%3rfoyh7YnpU#anzXvs6IWfxGn$} zj*bVnv`;nerLfuIB=Ie}Kok`od>k8of6lx>z5pFVRI!ct+>qMx#?TnaZcI8YYo& zC%AufvF(it=az<%C_N!_&;z1~Y^!y;hme)r0(Gc&jEPF6Cf0cc4yY6`N^V8>K5<3P z>?3@YG_M98Fy39LJd){;_Tr{qgt@a`!`6Sm6Whf#)zqN98kL+uUzKmztX!=6z<$(V z=csS^k=8DjPx2w}Lyxg_lVZPcSo}3fj*dEbn3ltuAuQ8z+D4 z6@`ILLxG>!84}+zhUId+Kh$2+!PYpen+Dt!QnYQeo9m7 zk`r!eHWX!qck5V}Qv*JgVUIhah3u(2D@jMo!zW3X2oX5XZ0#D6KC)}nTs&1ztcZMl zCOa#(ek?mH(ju?vfG9eIRyR50grI*J@_|3>5sL|)V|i=&u;E_!yA{X1FnT zT;}_!y>GCAhRGpokkhLN)vlQS~_Njjx#}~#v zR*5`TP6(unLeQt=wduuiEZin>!I5ddhw{K>VFqUrAuj~{D-OkFI$d5F2K zO5Bfo%{5aoghchi##DS?rVk4>SUkaINJ2q~kt|KW{FZfaoS3Ow0Z{UdLb3K51MG>TUNo(gn|s$4El6HjDvgN%BO<_`)=4C#3ydr{q`!@%EEjAnti>N) zrElkvY@Biz%~jHNCgC%%$Sx{MQYk7puqYB?3oR&4>X9Lu|6D=leJ8_Ep<>3yg)i6y zvN#Qg21yl6$)m*rfq{Q5tJ=Wt3p=kPncAxBgB*uej&~;sHL^(u9&+xJY zV$a(?D$oYUQpGBlb>r+yVRcm@5?^;Tx zW#_?svt9kaA|XKf<0gp#V21o6EBJMwqlR>nX+ zrAt)pN>z}XBW)Zz3agVuDa?Cpt&vGd+Z>4PLAJ6}+J7h1Ls3ffV74>EnGJ;3aF0WL zfchP50p*)y-uX>^w&YE_S5hLET4gYbxtiU|B%@E2Rw{oZ7z(tw7-h3jM4JR^t@e@* z?|XZKQ&|h-Lw42OcPGcAO#D^zbHoGTd0gpbJ}10oD{@fGTS6D_C) z=lFAfQ6PUCi8k)x`RC{;EONYF9vV(Bp*d~$@)wDBRXkw3VlUEEyk+_k_sKm`gA@m( z<4-tZ*YUXXFcf!_^q$~55b!ze7=>9VZfYvzRCI93Z6`@&WM8+jJp<|r@fK5|DX|^c z#9qv0$kBko=sdZvGRbeZ`o^htq44P;b=8BIV;6s-`;b@X>3558YWtUARtp}#Xyv9O zzpIeH#dtr+n*@tGG~mew)f4HH{R)rpi5Z7WGMm^P(56co?AHSF@XbmJO^;dE6OmeC ztDRxN&?wMpL!{z;%%es7eP9tf((XPTN}$YCnDi|y+R)LJYC^$6@R!qD0y|btwBjLI zX-(+)EH9K98}0tAYs)JRUJvV3jf<^DX;oOzwBj}g-v%xGgDcFQ;NuH#3y+_v;q z7JdgGxO6;BsU%>aA*2FxJey|aOtIBRO;TP&n#~sbCJ(VXmzI`RB4!Ru*e3C$#4Qg! zxqNphjrX4K)$47fCI>n{4872taC^{cUF3gfILn$r))l2%Q;&`{!Nmz3Is!PmDltSZ zSmDX(JmwR_G(q-leNU*6#*G22z`R;u@+0uyWu5gYk#-FNooUfM_Yu|q@ z<||A=@q2URv}s#vk0kGsO_*2}0z9v3)5>Di*fz2*6j07tQh$_fgW@h7CAc<0<#6YO zOV7l^Db`UOPw9DJ!0><)n*#gWrvhrt#anp7Oi4S6pguK3g7CN7@RUc@9n%_9(c?`i zZdt^43rhiUb`NQY^CiSEzi&If#? z=aV1PTzrbY4p8%}2Ox79c0C~&zRMj)qfVQ-P4CU2b{3^H zwJ1hnbw%Z^Yqv5fdun`CMPO*wDM#SjXuKh7b!p);3eGW3nu{zC(`|ekTblhbrT@Wn z?nfX<%_Xa5Lb!k6(5ISyD|6DMOX7Dbh?sCRFqMryX18-5s}xR3==Td+ zVIQl$4A1pf&?5_P4u(Bt0)Cp4 z)RbExwM7%>MK8b>o%^HvVPwMiKGG$IUr)Jwz+iQD63c@05;Z@Ak}#u;zTT$S*HA|r zq*HlhaN&P{jmQ7L-%1Vg&c7F7^Um1n_}3&Urjr$LNbgmIv~jjtb!~tZ zbhY_-!FeE%NZyKVGjEOTgC|{|3Ti#t!AG40_dND`@iNk)ck<|;a|p76Pjjxr?ITaq zZFNfT1|=vsk7Ue$K3N<&NjJQ@Sd|3mpK=Du7b)LXxg+79J%oQFerYvV@seeyED5KL zPOt2X_NUXj+tm7Tp*bB#HSZm|NthzWo{~?P@Fpw|DNWACm5bxlq8QV2i<(&`zF2ah z160c?vN(?7!4w<1HSBKl+I^uoS^P>|%4(Crz0j4mdT=MVXDp#DN@}S2ki*wrvF~=j z2K>C5jig^T_-cQF)52-AI*rbI7B|v<7Q`l9+>=L>0Mwna92;+7c6<4R*p=SR7*CX+ zOjkK_RqO0o4}q?0xLT-jRH)|%vstUh+JIhozzz(wPU3_s5W4+R5$108tak z;|9^9*wbVlF{-JAF6ZRn+M+2(ovZt0_XP#n4N7Jst{N*iD^7AL#*nD*!|@T|P&`z8 z)>Gk(Uc!I%9+%i;Yc6=G3J1S{WkJf&d`?{7L#3%G6*#KHOh`pLAkS3ATl};P^qDVd zRC!OgZB@70EBRrlAi~rHN*8FamO%0i9Zzq?$K?fOw862px>DRmZVL~CMx0*OVcxEp z&@U-1$T*wIX+WcNwzQr}mDp;uMQh80kg*<{Na!~`PrPq_0UDZQWC`88 zpG%k`PsbgI`dVfXPaQu-WdJRGG~%T2{Vm=aK-o%FD4iUKiyc`j>s!JA5e2lEqBt>b z7q)*G_BND;9Ak;;7gCLCtX|AtG?W7<3*Yi~9|Q%Y=5vCF0%Af-*t2`Zm4sCc+UabC z-F?aK-`6$s&Q8i)w^MLpqnhx`d1Uy$Od&9D;J*B|qOpESAC*cT5o`5yMo+^N7iTqcjT;E}+qy87_Ut-%-JxZ-?X;?rFFRi7lh%>v$8CIm z6_U~;G1Ir`6ls(>*efanT7SN`A4VZs{{q(_B z#|cm9!>t}gp1@2;;`TK$qg@W!<5%xIIX(?)5@_po&v+nzSx-0c3bgh}UQdPTXYjx! zHzw+~KE$PIqcSLTgtMRc+FkS&_8|_=r#qE7WHOm3$8=jN4(zAx02}h6`dj_&5$;9H z5-y)7wgfOggPVdd_kc2p%zlTDJmk9f*(K@`cc=4@Zb5(hUJ-aPkYRN#Lk!#U$iUFxIj z%S%jv#U5ke?Jhz!68+%&!H+nn!)>M<2Io@qgA%qGg7qp$=G*hg(&U&x!Sq}1txnUW zx{-|uT>7JfBSb!Egk5aJPs>)bB1sSF@t0gj%Hnr3tj$qNwT0j6ec4DyE|{0 z1{z|_OEBK*CP%;ILvVl4>g-rDaVEyGtaDDad(qUccobHk%++%FB>?MA^a=hQg1Q2G z&FVyfQ7x8t=n|$CxY0loN__RK^4XDtwB1v?N$dMb9|6{q@naL@DC}s2ky||U69tbo zrq~G+SRWLCc?6ZR5{l&!+&_`{oj2_sV_Qok@jZ=lN$ZeKDQs;uNh$~MQPg}%9}rFMXKCOqIPTTAiFNI%Xh!9|$cLl07A z&m5FAza~B3R1klR9ou{97q>lK6@j8p-`Hl$UFBM`+RQFv7RG#*VarujuNPf&D>UbN zW6oy4OOPdWr@+s~0^QoJ+l@rSvvlc@$zGZn*LOMIKTK=h=S{e^O6~vn%L1yU z`-3ro%nbZFF`Km+TLA&5>)Sb7v;t&DB-R5fs9tn1y^eT>$|i9qGwT7CVA4;B+-OBD z&)PcrL_EDHszW@?%cJ3XgT}&uAgV>Icia;}_IpBnke|{49!$uBrh!Xr^^ zB@KU!UTk3X+RpURcIl_$r+7r3^ap&bs1bPmg{wM^;ND3K5{Z<@MYSF6nnBB z(&?> zKbr@@rEZ85`kZ1a$->+Mz}~oGbWDFqLq!+>-~;5v0J!<8dj|NSV-|4**_i(4IS**T z@>-ZvFn>(WZv-d7{75j+#=_nS-V)*T{=>K2%K2v{$d z8S>9+e_Z`OwVXUmtPl&;_=YOU{;O0;dl86N0xE&*9PB}MF28>_uoIQo?{=o@ z0(5cx6Hnq+hy!{GvEV&OkJkA{2O#%9ql37eiM^?rlNiX!%;Y9M3bY;#UK~Mj5Iu+> zJxTu?J+yiM89n}W_1_;%DA}9-NtN*NhHRZf`dJ#p_Eo-7#ghM@QANef0%9G1W)_Rh zDT_czRYbr;^CyM>8NPp$8PHS==mPvcU%6@kaE1v0;L`&D(%b#0BC=Mg;)QZ*njmxs(=0deE|P6HEIp7D+Rv;1HWuq+Lt5Y)e2?kh!+(FDCsBPD%nK=3BK#2n z>xPGK`>VWvcj@nw7;^DL9z!a&?hXK;_YJAU;a5p&mQH47nwDl}HveY+N*#ANpC;Es z>R1j^$MWB3lHvA`Y4UwEp}SgR3#6n918vnEKEI6qg)5Qk7K;gei`I$|CigCbw8ic5;C6e;sOA&-*)4me@Kt-gJWf9br>Li z3lrkE1iv+|7e5Jh{|)y4-S>C&_gT+)UR#AgN*R#XgKt>W@xR9U0c7)}(Yy!JqEqO9 zoWZ|=z$W};u4NH3Pmr0DsH>CPpG>P`hV!0yLCUiTf1H2Gx?vEd|0F{cd zoUnT#rDFi}B4;D(C&kMFZH-NVQjh@~WcMe_%}K@BwtJBIf;=3wD}~AV*`(A!C*bdY zoBWUjFRoLe4xwaWLOU?eyq_kySpGH}2ZHP%J?fj%5Bt?R5rtJQq+fYsLsuo=%fEvD z6T_ZsAh~~plwQF=-ylcTFHj^POAUK>$o+|0nweNj{I(XbG&7ZOwfn&YSSza%a0V$& zLeO&Gpi`^=3i?0KssEU)kT#bG1F2d(5@?roUGrDS|5^B9o5K3+oPR|F0LaLp-3X}l zFMz)fflktX1F0YU<&^Ev!l84#-Uy$X_-h$op$UJ`2{>;EDN}zh9VaviIyd7DX?y1H zWNL)wK&Pg=;i%02okVre9O(2|HyrNeUrv?5&4ae~P-^&yOO@hv|azpao_^Vl0pc&9{b#EB^hkq~1E;I=`Q0xsU^!RUt zjfH>4Ku18m!Qh|%Gx1QNiO@kaZ-|;_|4azY|C;DQ1w;IgM!Wc{p%I}O&;gxp7}0Pr ze=)ohGy^&q(hZ{#{#O`Kp^>05&=G5HFi((vg!ys&8fXf1w1OMTdyJo;K*uhC77u;) z@y-&Hb>u3awva-@@HG6p)t^VzHTt= z3_pSS&JHkW0`%sD8^SK@j|e~5s-PqbkMNraA;`BY5dh%A4e5b^{{v7<0|b};bpaZ; n#&iJ*0Sa(zik_P-0RaC|m)UgzNdjYkmn3!pO9lpj0RR91Qz3im From 526c0d2c19e1f50c37304eb8162d2bd1ad13a1a0 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 15 Jan 2026 17:16:18 -0800 Subject: [PATCH 12/25] blue far --- .../ftc/teamcode/PestoFTCConfig.java | 16 ++++--- .../ftc/teamcode/autonomous/BlueFar.java | 22 +++++++--- .../ftc/teamcode/autonomous/BlueFarPaths.java | 40 +++++++++++++----- .../ftc/teamcode/autonomous/Test.java | 31 ++++++++++---- libs/PestoCore-release.aar | Bin 95861 -> 96021 bytes 5 files changed, 79 insertions(+), 30 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index bd6b344..ad3dbc8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -34,9 +34,11 @@ public class PestoFTCConfig implements ConfigInterface { private static DcMotorSimple.Direction centerDirection = DcMotorSimple.Direction.REVERSE; private static DcMotorSimple.Direction rightDirection = DcMotorSimple.Direction.REVERSE; - private static double ODOMETRY_TICKS_PER_INCH = 505.3169; + private static double ODOMETRY_TICKS_PER_INCH_CENTER = 505.3169; + private static double ODOMETRY_TICKS_PER_INCH_LEFT = 505.3169; + private static double ODOMETRY_TICKS_PER_INCH_RIGHT = 505.3169; public static double FORWARD_OFFSET = -1.565; - public static double ODOMETRY_WIDTH = 9.102; + public static double ODOMETRY_WIDTH = 9.1474; // DROPDOWN @@ -66,13 +68,15 @@ public class PestoFTCConfig implements ConfigInterface { public static double KP = 0.015; // AUTO - public static double HEADING_KP = 4; - public static double ENDPOINT_KP = 0.7; + public static double HEADING_KP = 8; + public static double ENDPOINT_KP = 0.5; public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); Cerebrum.initialize(); + MotorCortex.getMotor("3"); + MecanumController driveController = new MecanumController( MotorCortex.getMotor("frontLeft"), MotorCortex.getMotor("frontRight"), @@ -111,7 +115,9 @@ public static void initialize(HardwareMap hardwareMap) { if (initializePinpoint) { DeterministicTracker tracker = new ThreeWheelOdometryTracker.TrackerBuilder( hardwareMap, - ODOMETRY_TICKS_PER_INCH, + ODOMETRY_TICKS_PER_INCH_LEFT, + ODOMETRY_TICKS_PER_INCH_RIGHT, + ODOMETRY_TICKS_PER_INCH_CENTER, FORWARD_OFFSET, ODOMETRY_WIDTH, leftName, diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java index 9c905fe..883a5c7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java @@ -16,6 +16,7 @@ import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; @@ -30,7 +31,7 @@ public void nextState() { case FIRST_PATH: mecanumController.drive(0, 0, 0); FrontalLobe.useMacro("outtake"); - while (Utils.timer(15, "outtake")) { + while (Utils.timer(9, "outtake")) { FrontalLobe.update(); MotorCortex.update(); @@ -47,19 +48,25 @@ public void nextState() { state = SECOND_PATH; start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state); break; case SECOND_PATH: state = THIRD_PATH; start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state); break; case THIRD_PATH: intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); state = FOURTH_PATH; start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state, 0.2); break; case FOURTH_PATH: intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); state = DONE; start = System.nanoTime() / 1E9; @@ -67,8 +74,6 @@ public void nextState() { case DONE: break; } - - pathFollower = BlueFarPaths.getPathFollower(state); } @Override @@ -108,11 +113,16 @@ public void runOpMode() { continue; } + if (pathFollower == null) + continue; + + pathFollower.update(); + + telemetry.addData("target", pathFollower.getPathContainer().getCurrentPosition()); + telemetry.update(); + if (pathFollower.isFinished() || (currentTime - start) > state.getTimer()) nextState(); - - if (pathFollower != null) - pathFollower.update(); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java index 2afcfaf..7933ae4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java @@ -12,7 +12,7 @@ public class BlueFarPaths { public enum PathState { FIRST_PATH (FIRST_MOVE, 2.0), - SECOND_PATH (SECOND_MOVE, 5.0), + SECOND_PATH (SECOND_MOVE, 4.0), THIRD_PATH (THIRD_MOVE, 5.0), FOURTH_PATH (FOURTH_MOVE, 5.0), DONE (null, Double.POSITIVE_INFINITY); @@ -39,7 +39,7 @@ PathContainer getPath() { .addCurve(new BezierCurve( new Pose[]{ new Pose(0, 0, Math.toRadians(0)), - new Pose(-8.5, -0.3, Math.toRadians(-45)) + new Pose(-14.711, -7.6111, -0.7068) } )) .build(); @@ -48,8 +48,8 @@ PathContainer getPath() { .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ - new Pose(-8.5, -0.3, Math.toRadians(0)), - new Pose(-8.5, -0.3, Math.toRadians(0)) + new Pose(-14.711, -7.6111, Math.toRadians(0)), + new Pose(-9.37, -18.48, Math.toRadians(0)) } )) .build(); @@ -58,8 +58,8 @@ PathContainer getPath() { .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ - new Pose(-8.5, -0.3, Math.toRadians(0)), - new Pose(-67.45, -30, Math.toRadians(0)) + new Pose(-9.37, -18.48, Math.toRadians(0)), + new Pose(-66.21, -7.83, -0.23) } )) .build(); @@ -68,8 +68,8 @@ PathContainer getPath() { .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ - new Pose(-67.45, -30, Math.toRadians(0)), - new Pose(-64, 15, Math.toRadians(0)) + new Pose(-66.21, -7.83, -0.23), + new Pose(-58.21, 19.41, -0.23) } )) .build(); @@ -85,8 +85,28 @@ public static PathFollower getPathFollower(PathState state) { 0.2 ) .setDeceleration(PestoFTCConfig.DECELERATION) - .setLookAhead(1.5) - .setSpeed(0.4) + .setLookAhead(2.0) + .setSpeed(0.6) + .setHeadingPID(new PID(PestoFTCConfig.HEADING_KP, 0, 0)) + .setEndpointPID(new PID(PestoFTCConfig.ENDPOINT_KP, 0, 0)) + .build(); + + return pathFollower; + } + + public static PathFollower getPathFollower(PathState state, double driveSpeed) { + // TODO: create secondary + PathFollower pathFollower = new PathFollower.PathFollowerBuilder( + FrontalLobe.driveController, + FrontalLobe.tracker, + state.getPath(), + 0.2, + 0.0, + 0.2 + ) + .setDeceleration(PestoFTCConfig.DECELERATION) + .setLookAhead(2.0) + .setSpeed(driveSpeed) .setHeadingPID(new PID(PestoFTCConfig.HEADING_KP, 0, 0)) .setEndpointPID(new PID(PestoFTCConfig.ENDPOINT_KP, 0, 0)) .build(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java index 76b7252..205148f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java @@ -1,8 +1,8 @@ package org.firstinspires.ftc.teamcode.autonomous; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SECOND_PATH; - import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.drivebases.trackers.ThreeWheelOdometryTracker; +import com.shprobotics.pestocore.processing.MotorCortex; import org.firstinspires.ftc.teamcode.PestoFTCConfig; import org.firstinspires.ftc.teamcode.Utils; @@ -16,16 +16,29 @@ public void runOpMode() { Utils.clear(); super.initialize(); - BlueFarPaths.PathState state = SECOND_PATH; - - telemetry.addData("endpoint", state.getPath().getEndpoint()); - telemetry.addData("point 1", state.getPath().curves.get(0).getPose(1.0)); - telemetry.update(); - waitForStart(); - while (opModeIsActive() && !isStopRequested()) { + double dL = 0.0; + double dC = 0.0; + double dR = 0.0; + while (opModeIsActive() && !isStopRequested()) { + MotorCortex.update(); + + if (gamepad1.b) { + dL = 0.0; + dC = 0.0; + dR = 0.0; + } + + dL += ((ThreeWheelOdometryTracker) tracker).leftOdometry.getInchesTravelled(); + dC += ((ThreeWheelOdometryTracker) tracker).centerOdometry.getInchesTravelled(); + dR += ((ThreeWheelOdometryTracker) tracker).rightOdometry.getInchesTravelled(); + + telemetry.addData("dL", dL); + telemetry.addData("dC", dC); + telemetry.addData("dR", dR); + telemetry.update(); } } } diff --git a/libs/PestoCore-release.aar b/libs/PestoCore-release.aar index 5236f62e94b0ce9d280cc14bb1464f84f013ee3d..a8607363ff02b6f7578818595a0e38b240ee4984 100644 GIT binary patch delta 58561 zcmV(!K;^&n>;;wX1+cAA2@$&ooPZ+%0PnN5QSd;2PBEf|Th?e*?J{@Swr$(CZQHhO z+qP}nwr$;WI;U@PI=Ow*|KC{;EAw&9d{bkMZ%h?|G->d5+MwAOi_$h{plfJD(z#e4 zMi>Mjp1jaC4Fay{(fbczM*4vHI{H?w2gH9r(DDuA03UDw0B95d0OJ2U2l`)aGrOgp zrmFjYuIXev?r4hv=S-pa<&X`*q&1mek4&b_ z*(mp^*QwX-sQXzvuJ@NYz*?Z|vH*w@M?Zdl9;6E1mADz>cIkse#76o}6idx9f`-U- zjtT>!DbfY7E3wzbxsgEhOfll32de(CzY#||XHeZPb_WaO{Lz$^#C3b2V;g8i{s=@f z&;=jf6Jz$(Q&mx%lu@VYvXx9?5edWi;ze76a^rS;R03PMNyB!lx%c=|5JQsGti`y0 z)6A$O1Gs^JX|kfjI~5RUx@4fAh>3jmLesjMgNX5-1fVo@74M}iX%hr9V^z_ELy2%7 z1v{fEN25j`hFYYYql?%iiK95RG!+n+W47P3gGmkD;M^t1R-YU__6*T76NIsp6;hoz zDN|KRlMn;z=o~B{>xEF&95v7u0*7^fum`YHzl!4i57MG&+xv8TAxev2E20bd8bs&c zmM%boop6W-S8IYo3U=pPw}doXXE4rPa9@$@@<498L_`~uI#iqX6TYQm5?tfuEPnZE z6ZIfgD!x;?(*YkqZaaYejwp`gsgtEBR>njrS$lx;ZwU%!nfs7EyGcK8;8u=*d{sZx zkG~!|vGe+cg^}Czc}0(j5(KHUc6lnnj*DA3UfS-p0wtpmJVDlxWNB{Y?N94Bf4xyO zYe0eQG7({+zz438=vITa=2K@yOqHDj2I%*qM-Dt)uGj+XB+sVh^V=>%0`PNxU(-i7AcYI4x$>vW+NZQMds!GWNljM;fD2^8AlN_$ z!SflG@?yf^#gecj2>9jK>kUU?g9>jN6mHLp7FZw+W!eP$?AiS1oJt)u&SglOZ+hCZ zFlMCcz@PK=s8Ak8zXN;nQlqvIG&&->?o`4!_pO1D&_wU35aZvq7?!brGc%Pxo0-BB zl8l*R5*?x` zCW5jc5D+F)5a|9)S$6f2lz_BvR6FC|HX5T;1*@|i2Sxc&%?+FgM}9mcCR$;QrbjVU zDxO2HSDoool!9dWHxkukDT9k+MD)!Cx zb^g^t>5d|vv_R3zxJ9|cX$v(|@LxcH#B_jJ-8nXTV+Xtq%q@LJdIAk(zUh0o+@;<7 zbH~4+KJR^Dmq=={$MYskx<$Jucqa)icpPT3Td>_xvx^D&BHUGfzqe-%9^Y^jnf&M6 z1^27LPuE|Un&ebQX2$SXd`5VRjsG@K7x4}t(^9(6lL{#^b|iG5=S`0d<@Me0=O=A< zG}1@A&sGg3dY$Hj8W8TGK*f7rFHKb#mHOQpuy;^Ww8kOyRMeyie03r>f8`cRqpb_50 z2f?DBA%6b!OfV^-ghxa{XT}15N+5$08F(8y(yA(*~Wwh)#xf01hV1E5uJ$^3h zNh~hOurXeW=qpev4$J*02-h%44KEg)XuwZD+OU^foav8$THhiU;gc8y7?8YgROB!z zh!hcDG(2JFj^ycKcX+q9wXQM-Xk2?=lA{3ogNheY`xbk z#2eI`q(gF&Y|5#FB&yMQPUtM>el749bC=&=N-*!kq+3aor68XYSI~iYc-x=@pEfFt zB!@G7<{y=RzTJA*W%%DZUW8+4ANZcVAX>;bus4JOF?Kf0xq*IDvCOcwqy8}r%fOo zV`mDkJNlUf({<538XQc_28;^Z#LqO8R;x6ITIMl+Ob)gF+-+su^p!<#Lfoc>h?#;1;mFU zdCAo6yCWiR@fC_z9HE&;jxeS?hpQ~gC=9brJj57NF(HmcaR6yK{JRoTqP*ac;!J4x z9yuJ46f0d`>0gifRclNfz65-W{o>yxDlyQ8FlQ=>k5>*RQ0v~7>?AR&ov6x4*}~;vRFQf%^2$h6_0x!>LO%JBnzASg8(Y)7R z>sRhT9NL_;gDsSGoj_cF$xwB-_T%Q<-mijxyuF94QO&zCwdz8fy26dR(wjD*uC z?h42UAt5m1o`QI6=PvtTyXO12$C}Eljl6jvz908`fkm-mGmI>Mia!aC`pSZp3i%=J z8ExprtQm*OtRPb*=q>oGndB(ncx>}x`~)q!B8tyCphZ__2gi)vCXvOI1`dfExWK9J z;)bOvr5LLPSh*Cr)Uxjpjz!y#&hr)cjI6- zM5C)LsKUCIR|01hJ-l`Vdgh6C%{=PhTNCZmzDoDd1HZ_BHLmkq2qR@&@b)>K_Q9Z_ zTa)Rm;-GbkG#)_=UWCV&3K8kkZJ5$+hHMsMC=+LLfI@2hI6OPzRm7yOJKWn|8NA-I z;rtRkP|e@qadQ5Y9v1GEaf$gks`TYQpXS*Nvg>?jqOMN95TZWcvyb?U5xx9{!(|DD z)6EKfL^WQ2sAC8%a{}^8mY9%S`s5&gf>{$E*#)CjBjQ+IP_8%Z%J_ zl(doN4Izn$kq)cFr0k1LrVD^=L#*7hsi1u=M8p}fXcGc_P_JqxI&ch0&fH_zp;FAg zZdna~J24-$xz>KX6FuGch!thsOHNQCmBwKe7=7Yg!)$b%$&XlH^UJC>>T46fm zzkny@QUZtESf)7Ef|37a90l@f5z|URrSKkqrp_PPlD26kl`|I9E2Z|=dBOn3p|_By zO@DPf<)_0|#e^@o-$fds!LV(fQoS_Hs6DJ-+^gL5VO;tf>237+t@I7sXTb$-y#}Qj zb_#nH+I<$NNv~J0QfpqVa}|hMRMp+|0J31zx-_(JVfBw7$ls0ov>~MG5TEJgrTu(hw-#M5@I6b4N_5WY(#^ zO(EPqy+vPHgh5H%_>XTlFd;v4%et~37|<&o*CWPBkq36c><3*C-2bG2d6>Mx)HTi*zzWW`31LrAi9SwdB3j- zrKahi(g(MBAWCmiq7xkNp%f?P7m`p2$YYl2F)9Vp5uK=qyuX?%;ky%{WlR8nH~2dJ z7%o^#5%mSI)T)R0x>Krc)+VO_id%@*%U4fli*JrpCUAe)?Kz}Er&_M3Y6XJXENnv~ z?6ZO5KDA^Ks=tUFwB>OdjBsU2y+$c@#c5T)O5OhxMg3y0c?Ba`$7>qtJ%G|_4e`7D2u8bp(!XhSpWEE;yN;sUZ~tdk(p5J{ z^Bbv)g@l_lo3^{okGfd>xgvPWB2mjg-QoIGB35j1E$-7Fh8;|1OqoJv!X-k2>Mk5L zG02{jcy*i#TAw14F>R(Gq_HnmoirOrST3g|hes%H}T-mV46?;p6^x8atm;V~w zBDeH~s+m@SbG7q@^xpx7xY|lfkAK(#FaQAR|F;0czc@fd|9bz2Z0i3DIH*`FVk#r~ z(AaJU5f`b=Dd=kOiwod4w+I)d07**FgB%g_Rjy2*kf>w0oZp0`po{XJfj#%K^+@G2 zx{REg`X(K=ySDyK&>IeanL5hpKF#r-VV`Y(-TJ<~<^2J+1Hsg1%2(%)j8JK!7h-*~ z=2l;*7I5I{?1zcXzwR(k-+>7^QR6DyLmEudw{~Drbe%qdZTlN~92y zYBl)eBH#vhONk~2FPNp@4w&^Ms~IA_WLY98oT5%v{yw}ME*y=&2)<&;HMRt%tcAoL zgnN4#?4c&CP~i$&&MRk+j?0jB!m~o)dabYymufz6P!VB&IZ!}o%h|N=`1sy6$zA^t zA0gjvaB2kNqB5PO3N6^57IFC&loelWd&|%?B9uM+&=!%IrpG1-wagy3Pg|d;e`+N6 zom8S^md2B$K%7iXFa1=Z39UgWq_|qJNFNUa?DOq#<9Vyw#7jOhdT@%~RqwD%#v4p6ma+R(<(=1g&fqVIfjYYOUc_)0KWa(~v_QUqWe(=|Nt|S&{}e zfl_O>AfwF=e}TRcncO-#SHDoGn0mNb(tr9SjqW4e@k66sc`eJEJJ)YHl~Z0!p2QiZ zUDTwLsgSf(J~2WJ8|9(^2x0q}JRPV1v_^U|44*H5K(lTjb010Xm zUnupcCIWa#mVm@QaaI=)HMLKpQZG^;S?c@&<#Gd`lRM2eohe2U&JRCZ`&l!n@a=~{ zE53%aYlW-Qk1B+*J%ps9U6+qhM-AlphEVr^nUoFJBDO-1m^0*ucLFj0DKrt!?WN_9 z9j{{C;3Kr`qvgNb7`sbINpbi5@kU5H_?uDHi~nUC+lLEt*X;de?@_CsK#y0UDLvu} z{PqoRqy^h|<^$EI0xpqMM;pe-|C`Uf1zwW+LiY|`?!1w}xE%lMC-W7i^F@?h&J%Ti zOU1!Y)8HRjks*Av zDe(JW$O+A|+_$#>u!|u903`mG65hWuoU*knrs!WE6zGwejV@qBAe+phrhCag>5L>f zGKe?2IX1cJ6i8ISq^ zJhWd}s(t7!P%HKW>{V+jI}XtSiDlrU&5$Y72*R6g znjz}-(2LV6v!xgg?Gh6Dj6o8ox8?{DGpZ~f&s^xe?e@Sc2p5l%HL-9dtm%?xu4s&#zMUwVyAzT_ zaP7USpsNcYua;}%o#2Y)g9t047BoB@i8I$XcePg=EP00PMZjs^M(DHutu34ID*%&OU(o(#CrIvp2FuumV8nHM{-*cVoQ9Ge0x0wS-wDfTo;~dT$4l9k^ zUT7eHp6xPXPs;AZE5*3E+Vs;7%%9n4uc~rr7stm!guCMxtp#r|Lvdc`@FO5Rj4M&Llz0k?zEThAanb zE>b7f)QIOaw9ydQ4N)k-Xd261<__C9bX3zT(AoN;2Ku+7?eWJgq?or&jduNm0}W3%)Z8*4jkyH~ytkZn1M&RMIOwnC}Q<#nm4DM&({kbR(+2ziRA~)@)i`+Pd z-J2|g1vOYw_pynsq>A>~n#GrwuSe;Bvyd>)3Y0<)>>s3%1Y4sN3&#K0oIcqROV20G zHQHI>*zohp5K{4&8WF`A#ZlE@cx*UW5Yy!6wtSFK@51|lWtYV>kZWh4|!)Z>&3l&ZtD82F|1p9pw3BLD*Kgj4EV`IZ~dW#PUe!&@t7#? zuQO63u#x`wR|lj=&wDB06&-FdZ_#?fmTbI|}bv18i?zer%p%GcS?(H>~S7AbhWIvYrCb zi&dmr+q3p(>gr!ubFWxvpFSj?0q3oO(KhMI+da{*D9<;L-h4lQu(Xlfw0_H?cSz%y zg0R(l&^wQE)Z9g{_EAn{Y1W_?>&)~Og2R? zck+q4g&V$bw}*p={2Wfa1I-~N|CMShYrCoZPt9m;#D9!`@c)--|6fWtTOjjaUZ5HtAjo!++9}_q|%`!#JCN+cVDkxb!I)UI(^?~DOUlZ51LJ? z`ZvH=$eHqg1uOWFtl7ey&nF~Lrp1Jq zY|}}tZu8L5Q-U;bs#`0q9u{4v8 zmM+D~Vq;<8W=O}F&nqUj(?n`H*rAx|1UWVR^<~?Y+E5x1y&I?lsMFr(>CzT_sxn0F zvVWw1TC_cjhD3_>MDnoY-eIJ}^Y}n^3Cl6joo!0aem#1j2^PA(?(VXqJ8mSB2}K*-*GmXVH5 zY5Vd195*n?R+v9r#iQrF+W>uk0UzvoC_hn#0>91Sp1Ca%*&a*Dg+HA~UfP+1Ha9hY z$PV%c9R?=mJfkYsncLial0GXLCC9k;M!fW!5DE&OisGm!+upP(+&B5V>LTYZ=OasU7iF*$v~?@RG%fm5-Hr6j$yo&-Y3L1pXmv zfLQB9XO<4F^MalYe6bOfCKQOZGiMkKTnU-o!eBKNigkb z{}D2G2&zfb)s!7~&1>`Os$6!k^gbP&r}B>7D`)y9g-tQV@F*=yencuj*}#f_rd!x< zInYW&;vo`JHz8<)?@+-iAV!&qn;UhFJk48pztSx}y2p$|xG}CiN#aZP3 z5^^`L!@>@R+f?L^8bmDb7b}+hWPW&E}PYs{ws8UCkcJfYto%{Di^VJnI1Nc$?va*EfS@$_7%grh8ow3>2ItSwdl?AB3uVH# zul4;C`{t+rSz{r%$8zp}BNaaVY_mRS1!k?S4KNdB^6cX9oZHw6aYI`qcP`r)8hl%G z#3z580Tz;5OGM(Vo?#>?CY7GpsUu1~|CZvgKGj>ZXL9#XmG|7Cb6cb?a^}47XUhQ& z?0{xnW+hR}K6r~^6nIuat?AsKY+353eb1vU1htskL$DuC4?y03q1ZFkq*foPT@dj< z(fOr;UDfd{FT*K$s?~9~5_+WeYsZqx{nc_6Vq-xFIVDE(X;+@e^^EmuR~Sa?kZ2w==&&}{gK1fYrw7n zR95EeZXgi-WaK_SSnnk>*+h6KEb=ZI6$cYbgweW66)xi3iMwV#h`$15b78o!ZM+Y| z-*jWjv^qao1SRAWZy6~xx^76c&JQMvHBP){2K@vd);y?xzGn$oLa}X4-G_)#rEd;; z9G`JJW!OQqRY&^xal15NX{TqifQi*Wi9RBUXCv{0%H@+jklaDrJ(AQJ2(4JdG8G3R zmpL=9GM#tXN4q&zov|VDh>$H+?~Bz7Fy|R(leHgU9|k;PiqGt?OdH0%`};Fd@I#98 zT;Cm}(oZ{o)B@o z!}<~GAuYh9gmAEmd?LP+a&-RJ1keQ?7w1-YVDzJZGQq$HJ0r;<#b#!e$Xb+4UVihL z&fM2gaS(RLOzoy5#9jw7T~U9;HJ-gW=ya&Xk4`m5bELFp3$IR%u&$Eet`*sGrr}W> z-Ui-s%}KPg6E*!qw=Nb8Eb0At$Jpyyq?a4CeaJ7X@;pG3Vn6oK)#q&!y=(V#Uw1GG z9>RBjDEDjO$TC|yHTYHc-+Ky?MwCPLKL7yrpa1|||KpzGKX2&#YafM@wj!c95;ryw zzP$h)S=A78p5Hj$kajQYn{s#(xjb3koqVWxYLwK1)vVvg$zsp-?wa?OgQSb)EC24d zd`hXQK;99taPfk-r^gNZYgP}pZqLszM4vN%7gsRwhk}^K*{ENiv1&6#?+pjfsfuu= zG;)W;an z3ygto`PNvU0821F6gxE3)brS!+4WoO4kR>{n>B40sa>U0zyZc_G}8l`_k-VbvD_yW8g##v;guxQ*$dRYc?NfvK;44%M!nFd$|U~(k*bv3T88@C9Mihb&nZW zB{#}n=Rep(IM+>w)>)5f5lk2ski48t#7DG=>5l$Xf)b_$RjS~ z7cxXSkCeXuQZ%=9eSGa(Xz$6?_ISa6DMj__oY;GSg#O=eoqI#@&O(_}jyHFct%VuZCjQLQ9<8FsWuNeEpKRT3;~q|4QaF7XqNg)AS8BJPp@&@g<3HABbBB6hT(>MSvk+TL?)%)L(xMFY zTuTfPX$~EXmc*)Nr-sQ7FnKdIjcQ;#`B+cVRDMX~5+7n%|4@z2C=(S+v&xBU%7hvZ614)+@&FZ&Cqc^`?b=kv#|^Unc){F)dQMij^= z;mFMfh~bJT669%SZ}(63y!o>#Do4#X&^2v>Nx-u#j(x>i{u${z_Rl(lk}2%W(uZW~ zOZfbt`;lLZ9GeVsWg5xa6uhTM2a+Im1aO7?4A6~;dcg43U?A9O&wtUE<>}9yECc}n zKtccj(E1;Tq>`C~v9YRunX$3ee+K7&2lNc9UjFk(-S0LMcn~p{m1S9yMKMcJ>>R4K z^s)jAmlYl|L6XX_v7=;*bc2(tAa0MwX2ovSeP`~{Jo>2UD3Bq#r6_jxedLdD%;^pl zQPLb}i5bt9&?33O!w>2tnbavAG^P}%YA_`I!a_^Ldb)EVKycME*29Eq*9}E z*LO&**ov&wI5HX|Ou2JbHlf&(i?nu=u%rqor-kG*i}yw8`!UYM@u3@9?gXYqiCYF` zGL|igbPQSkAk264OAk#f#*aogma!0EG$&0=<5FrJ_^Pw)A{Y;G5RLxF2gE6apE-E%x8jOaji>vdGcxxvh5_GQC2fMq_#DupI0tIw;IwqbshY@5kd@9U^yv;L zc>Y|~d+7dT<~}wMcU1u_@oK(W(QrbDf`*5M-xdY3e6!?#YvlPkZ*yj=aU3|e=jbsc zUS^_Wk=l?hhH!#|?$#PmrOj7HY&`Zkm#~7%^n{jdvO_VMb&YiNhZX!=0#8K6Mihhk+KdC!Z0I{u&|0MjfwHdk!I=m$+DOnv2ONh`lp3r z6+C(zCC7t*I#|g4?m7Chckz<#Rbd-E1Zks4T>y~T29Bc4R1u|BtA@sy7%U8m<~uE8 z(MQ)fs&m8(%I5YBSHi5<#SN`~aHM~cbC(3iVJa#p7B*TP#BjEvc%BG|LJ}bj(Dd#$ zv{)O(HB-VagtPKr>9eVLpbwDuFaHj%?@_oawx1?{Lsx)7fYcfU1#sZwFlIrw@YaBo zpU5aa*DPq94<=jtI6Wg-XNOVvOtwm^%dTh?|8m!7BdE?>lboxR$D*tAq)kfMQRYh* zor^0@Ej2%dnV=io@Ko6;fF@s^KT}Y2Tqz8buH`5jN9P;gL(4w7=3?RSB4cCR;$Gcg z#tM6XB0y`Z284cieuCR-L)^x|k`xFY#FR`L%1w^FQAu(K()y+!@0P{8%IVZ14izk3 zon<7F+&Hw0#WVM6m9KqWwB~o7pJ6g-pSEnT%+J@?oQ6*9wQtF*+3JeU8}+7nHTXo< zHjk3Ix#g{G2M#9+8aQ0~-hcOxRPQO7)`y0FMv{s~kcti;jc|PG$UI7r^5@e81rD0b zEV#$w$K%kRj_d~E~LEF691(ys!DSCGV*1A z9WmqjQ@0CYT~O*9dh!<ByJQFV+&el?H>Q21BJT zLuIl0?HbmH=^jix`7M=B4q&JB?oq#gI>xLXV{~plP_80Y58t02Apl){u%42fdrYST z&9b&=z%Rb+8SJw(K@8r35pAtuu9`zquPDzqBwoZr9{k=t)~|?OGp}f>-6A%{uRD$% zfFhO{R`L#kMY02&a_Kk~eCF&Xit_L;6-jBMHPU7xHl*@wLTX$01g7341v)u@+UCb1 zX0dA^^XMiVXY=>00|1t>XUh|MHW7F3=WheL3ZlDEC#~_`B-gI|Na!N%Kl%wkmC(}$ zZ~PC_1P;ZLH6ozv!VROuyZte@I1(({4@%+>FArm=`qYk@7nl1sv~kx7M=1|uGU5(- zTn?~{#ABHggt`>sHWaa5?L_T=JzNjT2}c_bW2*Nm5Dl$d51Yi1LCNw&LA`{duJ<_O z)J@!6PjD9)%RkOrebtB4PJ2Fnmdeb(K>uDG`W)ZVTfqPTq!0lBr2qGd!+%zTcU7fR zbe|gV!@g0xJQJj5alwHDhCDGoXl3+uAOrt~p|bX^cKsS?$MJ4gt%R0;3=```ChM!5 z8|#Jc43@y9rt^ekrhO8rnGY z*PH$m30e#IkNsjMRQqawsZ;3N%-dh8cf-a-*fLLQO|_F{PM zhKG3SrF+Kq+6N;#!Lj>3Fcii-$JDoGXKkwK2fw4pI8-mcc7AJukZ_R|5~CT?C(aOp zg#wE7f|`AGviiMrLePxY=`!@A{K04%kXWL?2dKZae`hmzDuw$^tyZ7pxr^-3tPd)( za_JOX^xcD;cR7xK!ZNQRW05-7aR3&}?UaT@QLI)Us5rT;iWzV4_t{GB%;-l60Y^!Z zVtmsImDyw{o{$`!fU!!EJc0`+#@Jx*c@qthQhb5|p;6R0K)z2|(Y{L=JtCZVP9k56 zO}HqLIg=MqwHWDbroq++4ag*qS?a4o=$+w@6 zoY+xGkx1x^^Oxwg6R%wz4ZF+3T^`i5`A!pr;HCdrbh|sN2RHvS zv%iUG9Ce67`h!b?10)o}(^H3Y$a-QHx5$drL(#9mWTTdQyhxIG2X*^TKquOI>r6k= zp$cSiQPKa;z&mxY?V)taY`{5H+If(%kpc&NwuY+KO1kE*@>>p(W4YxSIb#s68C!eL zKzL?<*Y(MJh@(5(FV}h>>oPE7$EXY)U`0q(lRF0^uOY|bM^ur}beuFViPLC;yN!Kg zYEv4)AKYYN?J6eQ&H>&Q+GyCI?-Fc(u`nW4Cv+Pfbp4GY?~=Ra0W}Td*$K>4 zTQBm-WLgOI2vl823=7p1{@QCag@wmSVnJRa;$nb_(JN?IPilyho!^Kp{&OE86TEDe zY@8i;;H;jiAw;-3Bv$^xSA1Cqo{9D4%47R0#U2{(54)I~*K-ng-1jH57@XO8Qpcu$ z)lz1M)XztI-JF6Pg|E0>T>BT)Bs(y+RWD49#~$LKhB73L%wgDk&c-#uCx5DoU>2i! zswX~_YJpgzdHg2INSl1phA^n>$piX)LiMPg!^&U!-s`fXR@lt?%#f>o7LL};nPZwIkCjdJK&6aM2BmCaOh!8x6R&{nf=l?^zFGf7qZFrMG;q~g@%(c z0v_c#&6`J@yhAW=bqcoRL}G*z2Lv6_GzPz(lUF)!>~JBQ!>Tq7u1hugOC5U7+)U=T zMz{VTZ6&a#iNzEe+!96Wvp#r{^6s(jo-R-CH}*s1wpWLlwp6pMtcxDg!G+dzkka#eexMQN0 zhxx9^8&ss_W8~%I>|bS`7E#A~<>{oKHG%|62FkEIfL~!;s))J?(YMt}ho;OWAKcX+ zVR}y#`d!%#DGo6W*$wrLztq`(+n}R2(9FVuTGd&Z*U*mhcc_$a(IF=^j)tMz>gkLj zMouk_6=N*8v1V)<@YO`n%JUSS5II7VqbCxk&P^T=vm%3z0=bbYa^lu?O7WVIv*_8I z!UnBD%5N!uFsh?%UWX;5+GlznBi-@=M)Pzp2fe~_N#+RG##i40(TqQTV(AACgS-QF z#kKUXXbp?Z(Wq_S-fT(Okp9xdHc3neakL#RZRmv}^?nXjx_*M@Bzl_a^r z>W1cBEZ(_wriuBdWFhl^l)8G7U0bJgn<5ExGh)B8nbS2@89OZ*dRs{z-p%vF^+E1o1xR#33A7 z%ZmF7zx|h;-x#h+?Op${6aoKFI8XoGu$V172@A;ox9VlhnEQYbt1S%*%wCWPA^Z<7 z9p|RLI%j6OHty-(AFrge;bCRmj*8Ao#q!Zd7ce@JQPJQ!r4NEDdPa^V_o}L~wG$2V zK>~*RWI^-wh%GUHXA{HWAHfgZEL3}h`g?i8Cz%HdVS>fLwGdJj_I#Wa*8wNGt*>K7 zLSRm9wBbrNeSyzT++-aaty1z#VS;MUmw5uIp9Xv<-#_la0?5Ykkt(65Y9K$ItaDCi zc}u`%p3|uR?js~#Td=QxSc8E7znhN!zkT#Cr^MCE4AT974e?DS$i>5}G)r zlMz<$IqtFBjmc&aQ?Yn4NBVg8Y0f8St>?_T=kLeoiZy`eojWp?+Obf&pMw%zkTLZ> zt$CvcVen8jh0Gti2oN_4TYTDWC{Mb2p!2_U8$Q{|FShwdVxLRPH}LLK@mV^x82 z$aUm92hDkXBZ72*_bAmR&fhz{mIMd}_VTmFdXqI@R92|$6{>}V4Jtj(RE@$)!^0DQ zsz^r{NIS<%OF@IOT1qZ7bZm%-eVmyGNV9si?fm}u!N3EvvQE!3%BumICXRi?y-}Nx z55sS9Q_zBqCL78I`9yKhzgneri3rO`GAlmA&MHNS^Ymb`w~_z1(Eui@Zw|EZd!bB zyc-VM_>@_00TIn-7>@X1IyXMJ!~vQ}!Z|?s!-KA-&7E_xDnG1bdf@t?rTJrj8Vn|C z=R_)kLv?=eT*G?@<|PvL&p^$IFU5pHH_UKi9YQAxDIi><*=#d&&axeOQ1DrMHoSv> z?Nik%hn-gdX8(eTfN(*D%aBf_q6gT_cFT*J(Z0etX7gF|2PqURGjIPW0WR`=t!p=3?|e#Z0Jxijw(y6>?e-{eniBa zy0&W*2dC?QYvsa$amK<%!#cslfPQj%mSr^PX8DloySL!IJOwxQ;H<+quW!3kU-UH? zO68(SI^@(XFS(Uz2`;H5lq6|)DtQFgE}^$6I7*;>6=w+7Q*@hLV-RnDCs0v_%wN5J zs@5%sLB}}$WVLMna1}%&s;WplJJ52le{MWRZx4o}sxGY+)3~r3zMN>T^oK|O3ZmV1 zp`1!>q}uNOcpU(cRyeNnEgkt{FM-eoaz!>ka1<3gtDmd56YeyHb*SuYoP{7uksx;` z;!qk9Hs`&Iu-)?v_87Z=Fp=`)&1fN{by(tj8HTJZWI(>>5N5qa>EAYBKzH+CIrW={ z3Gn^#1(;i`_wR+Tir*nwY1_s*k2Z|PwBqTGudE7cd)mS6f7NvXIwk0p3aN^Q#v>8dZ!QCFJ^6h%@ku&=Yq3L7h91js*Jddn?Aw^ zDnlFYAhSOXz2?lY>wkLY8z%tZ<)eZvPD}vlBQr8}t)jrb4kmw#5BwQfKzRZuAGk6h+k0(-54tpgE zS2LaY5KL8n8bPdJA;X+$QbK$`${CMw&Rj*>0Xl8{kPmhIV8LRnJDQr+e##&IwwWDF z8|9G|XuAbkGj*HGR1Ib!4NpF5SH(L1TFp3JgE>$vNap>2JOD*Ny1%OpGV(r@SYpg( zBBFv<3TS2n$SZ{}Z;LZH(KUedvG16r4dK+z2llG2pLMU@L-h^>^UI6>F6N+*c5fKO zMDb>O`%3*z5~N=<;!kgsDx@DP3Rn)+nWLdSPj5sd2vaS!%%depKg_VdE-iQsCG3|7 zzn!!F9&5Q8YC!g|fB!B8nzf2hQ}}Po^Dpd9u{|YnSD?nYF-6v^9SAOt#enFO+E36K zS#!c9vhsf=fYaRODv!W7z`<(=67O*CL(AHamC^u9YxgAnM~S=e=OFE*+tP&iB0DzHs?L9 zz9pr**wMu6`J^br)I4WBuP58L+uz%-BfUEAFnugvji8ftTtUc?%4I8c7g0Vku^JvE z=-B@cXYUxC+xKM)$F`lE*tVS$+r|^y&dEvg#I|kQwrx8(F;0y4*SEUg>i$>V+kNkc zUA5=>wq~t4f7h6Mjy*>@zv++w;<85??&4;pv6t+HIHCqAfoQZSLlW?=Ejy;8yvkH@ zBL~-`PQQ-V_{C=Xeq*Ibd2KWs0z?Hn*6e9p9gyco|qHTHDIO* z4Oo~j89R!&y1g_%pT93Yxu=rVP|ATN3Gw$wm5QZse<2Wj^%w^+z9)X(RG_e4mCVo2 z6nccil7(dxFQhem`Xp&{WBvzNmwvvqLTuEKBoHYoHiz5ImV|SMiQocrClHY$MuBCt zxR~`HTAu@e%F_lJNj{r*JIYR#=Wui#4_jw`h?z^C6R6VpDvk<^Lo5O;Lc`fH8Ax- zj?TMpp|K_&hiegXF_w;C7y`g1L(EQ3B=*Qx<0uMNUuLM(d9A@s6W_M5ps(n@>Uc*K zf1=u^DVA*726YpQ$xy!%jzZ~mR*?z0^{bBe%e+hZw4(18qlzD`3Z4V`08kB^_Q^+U<#(<&;A~S*SZ7 zf18q&*RnNC^wSWOH*l2wvXc@vQt2@Vo+&tM zfJe^etW)r9frg!amE+Rkm5IVOI=qpIdMotV+LFY+H=k-s&N->qd*tss(sg?nw5X@j z{*U#QuCcRX8htW*3p9Jgolq%JPqlp(&^0H!=LDc69CuuJDMG5Y*GwHfneuk@e}Itk zQ4k#QKxjJJdDd~d_QilMJ2QNxURA<^PEhP#;SXQAeKf%t6AkMfpevKa-u&qot|G5o)Zk>_kAi{Je_Mj%m2KFkHqOkJO&wakeYzKGm{~esM8i{#7U~&; z#c*AO@j48OiG)H2B7IU9brWqN(BAS}25AI|ec&TG8(Zq_ zR2LF5_(3A%=D??Gvk{oc!3xWk)99-6=qYihmhbZb$ChBOZm-uGg<`H9e@-iVp4MNH zbg~F^qcgbNPQ9$}$M=+|&CYwjfS!(G$&yvXn`slI0iEZzRE>n)W&se<*W9X5f*D<6T#w5i4U>(8e|J+a(wEBef>m2#F$+@i4I^<`1NM6Jbb ztd(Q1h9}L?hB$C4g#&l_f1%wlfGuN6Gu8c|%Vz$)^=W9$1E8UNDb{xje|=bf5X(+A z*IVEeNX1eU9#Ht*Wj-}?XOm0AxOq!V-z4#eRn>+hktNIENv1|GKmOHyFj}q!Fy{z) zPjnoa#3d8dh3GeNnylymOHGVXl+gw8GgaE>YVi~F3i+%~5x*GvfAN&+^RxM=YGCri zFQjqTgr^roaud_i?y3>ySeeSzjmRdXX7Vsw)M3graqfhFBSiAy45LFJmNDPsWS*gk zD^@Tc+zSDYaNJbxte*ecdmj5x{p-49pbt??;s=UQfehaJ>>uG~J2iQ-YWv8kJ%Qpz8{eI3 zcG1$T2Ud?aPb-v#y=^u9jDW8zqK2M@NI2;V6T`Cn?_iz zru(c;Oe~}m{_Y zG3Pfd9KWm=u8LjXsr9*vFGMi9xqsFs61#PRWDYwUpBEU(yKa=*fhQ1{u~=hk!=GhCW;`U?Si7}z&(J8+e+SE~KH8Z5z*(Q#7CN=$QO+G= z;!f}k0P8)X9zrJ?tmTG#$g=9{S7uP;i86Fi8*Oyo=OS1}H)WF*CyR^$?(VnuRVwdJ z3MZF6iz;VZ2h7vE0MzG`dwXeJRz*)9)ziO~%!p3x!_y^sv~2|<6_Ht8g?0@@BVKrX zQmBzMfBNYnmq$R9@0x_5>L;M6`mPa8+z6dIEpDs&uwlsd*0p_K@4<{`Q(-%6s4sIP z26D{3DoMAgGiLViKc}Zv?bu#g{L1Qtr?7P_?iNJnZ%Xl*7LJf#UhqGgqa~oZ_Gf#7 z@XvC3Uyuxdy>Bo9gS($a2ivkm0VE&)q6w8Kf4inb_m7PX2LdAaKLs=%{{~|Ie+KaX zf;9gw)0}Lli7$aM`kh!xF`j@Drd0NbDvM^RN-v5kZfVk-EDVo>K^!_w&;V$}_u%@~ zb7%T^)_O}&F3@ue{$lk3L3AT$^2>1nJPkX&)Fi2uz!qPA*yB2Lyln2Wv%Nx6n6ytLBH?3 z>w1YMWM(8GeY46!GA~`Y-!bqsIpB=2fA}p@(_L(;R3kw*aQ|AOjqdyu5n~+19BdPF z(}uuCx7}Fb-0Iv{uIi{~NKljZlv9>ewCjuDV5&CALAdG^Wco!9)I`+=`O9@)1IAcNr*|TG26Jwe?~R? zon~(F@s7kB&xPqa(_%QkZH?9c1v2>Qlx4-h%CQ!~HZ$m*rn``ANfk^y%eVIrKe)_# zwvuiw#*g{|AtaP8E(UD0{2S#qS-K*j@k-pfLUCDnS4_g+)m5zIBPg>`MLN0>TRPU)-0=qCQ? zwf081>HV>jDMYwooa-cMJU>yNal*(zi59ns0iJv}@Miq;(^G@_;aiMJO>AMz`BXli z>ksC2Bx3G6Vr?-bZ&)2IL9-jIaabbhSEt}n7%@?-_xSo6-JSP^mI=PXe;~(@sVb5R z)rFrTT%3tuz1=<*{q=mi>5a9!?Fwme zy+e<{=iu7qegxfbPksXP?=;)Iqhe{EMJAliAQ(4BB<{jQWeB!k?DX=iD4fu19UIZP zMB6I$9U(C=V;J8U+dO!kR$)B4;jhW~HMl!2JNFv0+jN6Fw;`Wde*~4=sIE2`TCB0h zqZdWo8m{O1V{(loHmbtVg3JVlOBq&NNJGk_Wi@D1ix&l1uKJ0mG4y2ZbNSL z;r$)(l)U%>u^`a&d0GK;v8KfGdrcfSmkIF@-Z#9q{1dowlLGvP{I6*!kbBHJ{2wdl zpNH%JG7bHw{6i?mhcv*9@j&+}OcetPulSPyw4RluKP#9jf1@Ifmgd+Vf#8?ej|A^J zhRLVr=P!^oW91)Yw$Ys~mfkl__*Jl5vN%~z1}}fEsC6J=Kdi+&`cla;od+7!3l9_o z?0uK2(*l*`{6u>;YG;Grj&gR!`rTP7OOGj|Wx$Mq5D`+46GuuCGtA%M|8;kUb_hY? zP#_@gh#(-GfB(nbSpfc5WoY%!?nD9JRsd%)H)nUizb99XZB_hLLIF*kCX?o$zFIL^ zI1AiEKf$z-oPIJJnWAti1R9wh8kP1(HeuNm=>s(5;%fcp@5C(LHew7n%y|>jdxFV1 znD2sn9%*j8t_KSacspT+s8V z)7=2*N;KW>V{FVLOH?^4YXIKsEDzw5uA`dU9IAN~H*4yvG}F8(`hOwb?BxYe$Eps~ z#aMmSf20tq!3Ivg8!oL@=L5-nOv}%QJGUSQuVia4F;q^DQ?tOAX&%Nz%c+a(u6cZ z#SsrV5SPpIp$L_S$I%I1gB6U58It`Ckx}tge~{CExT8~fMyW9%6e#dvXg~)%B}$16 zFqI~b@cy`88r{98q?=vv*0CmS2?menZ+@~EGOv}y8Ewp2=y)vep z-dz#~^I{rtNNGxLQyjQ^eZ)uGKd&JX!Eur^49hT`42Ii;Tl(9k)A}SZQ(ff_8v2w9 zf2|ZVb1X2XZ7wk3ieu%sy7-;koIc)`Utt5|%S(j|K}T*)r5$DVV#iB=XYk&B5x@hm z1M*Ha22r2rI9(@OcW}&IyTY{tnJ-jzkIBZDR6!;s{M1JYYG7Sm@pCLX)Fk?Gz0sMBA#LRRsn~5OVRp{Z#*PN$sePuB4-DCh3&H0qduB&k?sObZDpc+nxB6^|4FNgVnfAo=n zq!%+n|37uu?G`oOk>AUkqRaPmi;~5Xl_9ut81y|kf1h{p$EoT870S;)QSTMTor*iY z!KFCpHz-y1#{@E!&r9!m;D|`2CKUQR8vW`%2y8RAf-Qn>Js{DmPMWIKvfw3)dSSMrv~8-eTSx#f-fZ6^#bf2NO>wRt@i zhi%M9iWf`%8`4hTm2k-8b_-d!nOLU0Fh>QNzJyM-BQhV)GR5>LiZcA=)s*>843}e> z?O?ofE})TWBs9%;uUCTR(LqprRg@iXdnDG}Bq)LvB_i~w zQgJ>-=^)>SE@(pXr|;8Ef4~rw7_3B(u_iZn-f(lbF?@KP?NIZ8fQ1t0a@$I82==UG zj0BntX%b8=cYRKQZ~df*%>E9Nw}$sYM!>EpFKUF%gk1rUb(B<>yE&g_E0;BMO5p4v zJD+<`N(*MTp=9)RDg5+Rc2Na4tB=HB2y%z%&gL93t0*L)Z5lb3f7QEw202G)593RY zg=@Vx#NV*BRl9c46N;|NHmuO#a0^Y}Dafbea~t97Yz?4{0PoBlcW4& z$Hepu*G8gyp=RBluKXj=6O>Au91W?oyN?Zd_D;4WxOB(kSr3&0kqJb+jk5?nQN zAe!Yj1ntuavt6^)(`)+dL1yIGt~E2%p|Q91y=>W|R7a?{UPCA!M5E(}J}@fh=4rVr z&q-`OAX{e}e}lShZp0P$xJi4OZTBxZb4R8eKk{PlgZpPcR)t2HKCVdn$VYEw#}ubo zY@>+Y|3wBYVY@) zKcs=_v={hBlcm59tMW5@13-oAxDU2wf^7gDbecI_T2;?pfUEX8PYjy0 zf8lj;jSW|8(y6bY;}#&I{-Ok>Ww=?878Kub2dN-ACpd^$WNia1xOgOy1gALn)WI{T zLD}!1B>rRHaLr?_eXIEe%Vkze?4yY`8p!mIK`}1B;*)))T1S|#laqZ%xz(0Ui1Fy2 z@?pbIe9B5Hy$^<;l|~((0I8wg%9<19e+Fv?oCZAArGL|MoUOg5Xk)*kb~|-pvziil z{B&PxRjac8*pH1r^U(w*qH)`GrM~**;0pWzU!m7`dyJ}CBB;OxqbY|>qNPD*X(}&$ zoY&;`5DK2od1B?3^eRI1#UVIkbtrT*V0!lQblZth%-iRYtedU8;v+hZf1SHS zr*sT!d`T1xI3zGQ&k%{LTn8`FADkOUA2qp4R9+|rh7sss+Vl~Is?>9M{Tw4s(m*gZf zot=~{RVyF|vkF`QNf{Q}QMeU|lP{B28ax>;ILgw9^p$v55;85Wly-yE-tyVy}w!!v8Xqvhy#03iw7f zXnFq=%6c&W9U1gLg|d>dtL48*LK|Dz1DwhKi}hcc?A7Y}4)_un0;YUBe`cMp&V*b| z!DtyMn}Id>GWpy^@|T=A?U33M9oz-Y8V(ivNn-Wm*a*Z5s4leSwER?qfNxCh zdwlJT8RAdf-Z?x-NF?2#fBasLZKpXvaxdO@Jf&Ki++xYmZia&v$n=VYObVs3%pQaU zG-50IZ0Q=t92Ea7@tAbkjJIr`RPo+j3W=EDBtX!`abk{O0kW7b-v4HJE*z1+M%VLJ zh9K23`FR3=fyIg-g$&xj60`ppa`Q}7`<3;n0ndG6gvJ#AH>wmPe>ENkTpe@5rpYr= z++K^jpLzXQ*WbiVdO~S~JH{CCEg~qvR(e@;#)(D(blqal^|;XK};rGz9|6-1fS;a#l8CsMs%?f zqBjGZ?L^Vs!%4L!h9s=H+977{2&ra!=+%d1QR4Yfn#eCr&8}_kUn15N==_5ov)Vg5 zQGZo8etpNrgkYzN%pgV&Ix>C-kfZ*(dKJ{PE>WXpv3;sve?%taKnSmu)n8!CXv)pi zOs4HTYdx?6)P~rdKTHlh-l-CmHuG9{=mO8eVVrnM{Sd%>czTAI9T=@_z z5%dAxz{A-jI(8HFlq2n8VBPtrGKs~?wxK-e$D(uDf4xw$j|!Ifkn;CkBFg;HOI_rA z$@+5(Q2bM3+LH!wwnf3NCunSIvMB_O4k%TPYHIJ=2x9$(87(@4sm3=G9>ey2+?&l3 zCYwFNZLxk8LW1%d2}rZ?z$sPo)!6cyw~8>9f2&@_hyd8f$)j=UxR$b z1cxXSe-Z=)|DR%%`~NA(|6?Yft|q!B#urjMLU14m7+SpqT{21%N%Jz=5Gjc~V%e}t zF*acW4FV8hMy_h%z1#0XHZ|3N=h=PLgj$Kse^ihCK%0yUQ%I1Lt_)}7c@=jyJo&P8cV=4WrtXdwPF(L=A zf3-5zT(^_Wqb%=@9=m=ZFo9CEOezQ{NvJzdURNB9pwA1q-$s$gGOls<6&>UZta1Cn zXELK(!bWlzjMDE;7`vwo8oi;oRzov~OK59YDoazl)hITqz)y*C!a>MJg{hqbIECQl z%#-%cS06oGW7zYk_EMdvra=^UYa*j0e<@QbOBUdLs=$<8psy)}f7eK>S7aq?4xhqF z;>?{(hg5`9(`s)row+Y)5~4OHo^wJ`giq4VImgMFj^mQlT%^&~Q&b}jG(Ze>ecZ1T z-tLvaiL@FdUIdY$k@Qz64$qlj6LufRSLM!$kjgOuP!-Q$ zjwJ>gvO?1}YAz%xy&0!km_6NAQ3lh3e3263Ns>#H$?G0){;X-4HD#vG6X}A7K$!Rw zzNuChvvIB~j;mp6fb9YR6t4rFe}94vpIN%YD}muEynhN{8-dYEn|Cyj(r~8fLJJI} zFO)|zms@q7nsQbei+&G01=JaXBU$Qi3cdxGrMteTLLk-(#Xu?_I4W;*tI zDzW}*2N7|1d~$@Da@GJ6e-J-0#9Wy9>}!sd6r9jM3d<+b=VYb2P=RFL@XQDX8=mvw zbRwc&w1L}!s@Jb6mfbU$OcIBwF%@`$GFV%oc4Ez8Juu{nMYuEOy{9zz2i{2K-|0*E zEzhA!!dqMRVmaCNgFaz~c1A<$I_`s7Cyh#wqBbmHqxvZz3i_i%e?}@6^ZHB1_Hit^ z+(v=0L|W&Uev4KgSY5j5snnrKXr;cY z71+Wam(6&JLZ+???nRuPHt`_ z!V(NN$TvD}+;zS$fAU@G-1Lm79gi>D#LT{g&GUcg3=8iy3HV&_$vh&@c;VK(KTy9( zB?mQYOg*YVbnM?|xBDMhQz(KJpCL&78Qqx;LaBt!XW}+~;|nME7QaB4 z=i#ra+Q+|qeFSsK+Wh**ss{bPM0Ju5wzdu)|A0C%OMt133Wg1+(|B)s3tZi-C1o3(fq*)nKs_+8bU7G$@@zhLT^Xe z+O`ECe=KwW;i*3D{+Yj3q5Z2ev_5`M%ZkK$KIFjNW2&tL{q&IJ6O+na7;~1^q`$2h z41x0{3ge0-1;N*QW|Z(*A)SojhImSg;61y~+5m}F3W3DJ)e@);Rqm797Vy^N!kbt*LnKSmO| zy$D6Sk&1`Rp2k~DWT%q5c3sDxEP#_zKBX%HsK3pVT|bo4w=ddFYn7Zi-f1qv3#T?~ zf5Qq}_HaI8U3fPv6v{nE4J+t;%CS5`*MdqK31D-0@=-9v(DM&^hdJ$_}IaqEN0mln?<8 zD_ogkOJ4iOL+Bb4)W6IZc$TbNF@XXBe_6u%?+94`J0JgNN%1B0W0B0a)>P!cq(I z#&Mz__9=0ZjUa;vmN~Lr>VHbH5FAcG1FDW(Ba+M$=!g>Le=jEmnn+lZmOG8laUnOi zvl7&apbZhH)I-HG(=Q%$aAL70NK)2F!Osl9JD#)#q3x`UTZ-{9=ti8pe@_<`<4O0d zY|nHbRYUA~}$aE|1IJqSxIj?nn2O{1vU`;TDHF$f6Ej4vGJpDTl2CC&#b z0CkLqw@YY*uT5&%uyuBVySAd|4<)cWC~V{FF*kAkC{&cH8H&n}_<|QwxlNlm-jFM- zFhXhSzSlwX-IfIt;qtwjf4J>DWH7Ts{m$PZi_bs&>dE`=yHjct;$Oo?a6Hmyb&vG! zWTQZNgeL1B>=xS(^oQ+6uv6d)!uHua6`99!ZiNI3d@_E%?)~va{>ajVMT)3OX<}W# zMVN`Rny7IbRZ{9%tY#u4rs_1@Vrk84rNdC@EgOpcjC|+S^b% zT8MKO>XXCmj%Kj4Z-#}>>ufB{OggY1kA?0L(qCCw4~vv|4LF8KwR{cAivsmLD#nhE zsB>rPitRxC$3r!j*##1{7w6~u9ed0O?eC_e^DpJ30u8B7e?9gEA2NI0u*U38j%K!z zon4-ez|t8N%tZ(-;?2HFT`+OnU4Zb`ti>jln^kZSt&YEo-?yOQ#&l&PeXD+TMU%~L zmdYeA;eOT#8~aGj1GoDPE8sd?U#cH!xaxhnf=5W_+rC0{<8vW4+!)R0bqF7lr zeaIZ(hn1Oxs7*aFLcc=0S|<>xfffs>mnokv&~^gUf9s_Wk z(^n*y+|zf-B=W&aTUAW`rdgfWdl)Y*%Ngj2f4e0|+Uk<=*T>1hj;osUKK*+k?HQ=25@`(4ffq$@YUMhZ%4s z^W`n#Yjgo%ng_VH>NR12y+E(wTSTxdv?ILI(&KSy6DQnHsr=2r>I_Kt#6J6J&=I=e zAc06NqA7}lq$D?AZS&usKaGU`S)U9G8ouh!f3OJrlrw5Q1<_3hXLDR&oC0ba^`flR zy8OEPeQIR-WaQS^=TBC*dkRuH8%S|)4CQP*q1KqW;uq_WZT{m+95>Hg4|l1LsI(7H;n^?1vG6*Wt-zOw{Z?1^(%V+BUxW)&fAob10U06u?|R<elEAYo9|9_JqS7M+@8sX5`#E4e`sBc zVl{AZlV^>gQt#x)p6A375#8GoY#F~4g7IAZ-Zy$w3%vZ30gCM$U)oO*k4!Un!X+i} zbWHk{`syI`I(8k_ z+ySPhg?*UI`fQ{v?4#cMvrHmk@_6E2}!KB9ar_TBv7Y;+vBI~sBND_D`e;n`cU|jRj zWI3|Pl|!rpF&D9a#0i;+Zw>^8;UX*s*3=4W%*t&lAuY=+8K(=^#G|QjA);ngK*1v8 zEtczymv>yt|5TSzxTxDFwz5z|#1DMZS|dixFh0J93r|+VXW0~5Mhl$5T^xzmW~hfM zEh2Mal{(qrVq+B?bWn<)e_tPx4%DWb4|W3s1kz~0xK1T8B2AW~l^Xl;(pPfRa;405b!Y>YG3jp^f=RBBd0<~EK zd5;DG65+8{8@YNW9l5@#{qdoAn^PP?!1w+YMcyNPRX=GI3Prw?e{nuX6CF+O9XX_d zl`W*KZz;eeq?|Hi6Ti5Py>)e#r`oJnv{ zx4YIA(uyDpL1m|%v&Kq_dcXjguIue3r8SV%WGZ1Y>V<}NLtRJ+E;;rHUD&D0_kb!P zH<&i0aEZq42egJBf2OchWQOb-4UDABoz-kiW=a!4J9T+KZ9>=#>u~(>WZCvJ?@jCB zV!)tFY>)!&{Z=6`!?cH>thZ@4@*E41leiMzw^Z&FZqn3O`@mJ?kz)YFHeDB z&eCJUFIeslm=a<$n4P>N`{_~nmpEW1g?)c0OOwvIamWp5{t_Jw!ay1$;AXR2O zV)ImEH+FlR=Bsyr&YxYm3I4dm%m6$nCAU9p!kEt?GF>e~%#Cl$4$=~JAq?kT zlHK)QbKghWe=6T+44>V%52RhhyFWwCW^`orc3nc)%uyEol2N3`L-6XbY72+rTn?$T zivE+oM^wneKg8^q@X8@52$q}L78-IK-x6JKNsa}0KR`R=CfOsgFO2|DH6lwBtb{r+-()}jR*a{A2#AFRZ*tgy8- zdpx;5xi!6-H)!MMF}Gys)kSukNiU=06S7zNfBVJ3OIoE$V~_o^hkW%&I1fXDrYWb3 zJv4%uije!um9S_rhAV0`_ay&^%Vjj76=E9E`FyM`UxxC8)zi0=;BH7yAp5Aqu+>$6 zh!j*^0&b}%+*y$ez+LzTZ#h1a=&oh1c14Y^+A7(*&gOOOzPM4Y3u@0$hG46C&MZk* ze^kIE^K9BmByC+M!f$vjmN~ZBMHArY`3P-4KgMZb_#Ulof+Ol0ld9R1lzHgYFVsn+wflTm1)`&X%q35O#i z;*MDYz@ndL5{~g$iPIV8gvM4;Gf>k`&OB^+`+Uy{;yqe~SJW zOg5G#BI6cjD&VR(_6)vL8FrcOrjVe|lYYAHn%S zo;3yu#*5Xtl%0I3_Yx5c*dSf>muwwqop{gsuF5)UpW4 zGB3|i4=6k7h%0SR#DaVve{k4V(HPUyg=CUUJkb1D=gQ}Ka-Fmy3IW%y z*PKM1kOt=h{w3>(*;GRCUC3@eKY`X&ghqSY(1%g4D zd+f?u44YVTgt9HuTgzM!g7b z#=%cdu5LcY(ZsF50~!9v%JX2oLek#sia|t(23_i8yiuO?pb$?Tv+~E4L#KH8Li&Y= zI7cP#M(NG$0ckR-aR+oB>zhw*b<3ei3Vj=K#%R4Fr}DAFe|QW=$m2_Gro>MLnQ~zF zV*qDQ> z`>36x*=~FU;6Q6Ru?32rB&;Pbeg@zNH3uCm2j(Y?5r-@q4VV1QPiyj>Y>3xjApY$w z5;Iqw3~|jYf07pYafMKpG#ng}^F~%btmLG|jYF$I8SBZ>+9)F;Q7I!zq3D!jq5wvl z!58c3%P!OXN&}Fl_JMCJYkSy+gz$%pYdsUZ+&*ycXa;{7-bjc*^O)!MS65CD%&1h( zW2`}Y)08k^N7>Ra=EOYUQNx`q@0%X>QuBCHZto#_e{iBp+2f>F?~f$O?N)%iafihH z6X94${UgsTamcSANs{0V9>Xk)T%d%cFdnJ*w;YkxZAC|dqIbm*JsxIUi?gz1A?d=o zN*;qqO^+tTyObqLJJ*!B)fNz0+m8u~rGx{U)My6C^%{i4Z=g*f6*Q z28_tFf5AeT`Xs?+_SUqi>0-$uAVMTs_4GJd7Is8O7Jt1QdzhqJ*T2kCnjT&Wfr0@6 z(ZK)#Vfr5fdIy*P;K69#xS+3McH2m&&}+2Vn%Q3dLWFH5M~6rI$xI0mMv}G$g}}XL zg}zc5-Su+=vl6p6gWWE1s)_A$4tct0(aItre|@Hjn03)i1z~aO5&4XG`MljBH%GH2 zOKtHS+Gba<+ha!HIol`qqc-6CFjw65x1hWVvcv(#GL2+6UhxgybF}EP<3vd1g$Kjp zYT0wt)!LVKH0k=53^7F+lY(^iQ(TSmjH^w^h~&1*s{Sq~en`jit^VTQD$#Xko0OY% ze~m)NX*(@EE95&(vtRz%P@b(%VY^Uncn7U7KtPghX;u*e;;2=w0vUV7e9}cSyyP}B zR~6WrbmdxeHtBQKTF9Xw?OH< z(fU0TH2dTWdloQ`VufJI>i4R6{RyWcf5F1Jqm4;2mBAi4p@`%!-Kpx^r6dLI3DCBB zbnXny$dYr*EQ2L0AY7OeT`vL8n!F|>!~Mb`Z}-pzDdOh-Gdgef(X-`Y&MDh|CBYy~ zxgCW0c8@idBac9}a$6X)6TUN*2LahmGOpY19lycyHv9Aq7z;w`UmXJ?>ppnH znqlt@0{*-d`vASLs_H#P9NQsp7EiHlgGV&bv%Nf1vrtk9%76!O-KX5-e>7&-m`m4> zt!(8h3a)M`xT>~F>e$CO2h5kr);{aR4NgD)QyVwiCq^M!Ew8s;n&`whh)7k~du>hF zHqumKa%}S=u`1hW_;nf#D|Ob+zc?@6U1f0GY_;NZ7Ug&lJY`-vmkQPyaZ}7T%Ob-A zGnnYxXH*(>j+?SsD(}(ce|8)*bFB0mcy#>;_7Oaod4m}jgXo%5pIj~mEQOv)?(|S+ ziF#OvU4#WghaOO@e5>~!?7EhzMV-+N=8E5Rs=T7X#mCIhcdK)Nz%4PM>iuOS!41r-$Ly2Z|Bag^ z9f-8R;%P+bO1k)nj@!rH9f@j-u<1md73y&&fI9(Ik;Ni9)JTB7>1-!d; zlqZzR%z$3);P2Bj$f#B`V&#Td>h(jJmOFulN#ph7x=Uy1^;D8~`LP~^^#>smpKQ7D z4v=+%<1!TZg>pC_ZQqj3B&Z%em>;ol{Ah&A~rU|2d&!lu2>06i0p(M{Jh|20jVZ?jd%Z_@?rzv(&kjdk<@tRVpW?o?^%~ zj)d2_tefma7$gL*gpZwWOZnmLXtWCh0a_RNIld}Ze?m0)A_&bLQm!KcT5Kdf_wTgC zy-=K+zA=S+Nnyg=WS9>!1~J1&EG*g@`aa1n0C&r6kN8qJJQ2(#4qkbMGLsXvo)fcQ zxSk#KV3%UqYpnFh(38=pb+ij!>cx%owk@o9gwYyP7LWHD9*CFj$UM(RbV5lfgJCpA z0#ReXe|ZTdeDz8P%c}7tm8a}UR<1tu>Oh4wFOVOEAfCwbzM7%~orLkBZ5Y|Q#BnKZs5m|lHXZG-yw{0fqA3L zA#RG>?xz44GCpv-S*5y5%^z*3kf-_b(2k|Ye;uwreJX+uc7q)k;6_VJCXCg5x%$+% zzh8-|i9X>a$PA5X(SE<$!I%pVY*F=O_^6z=HU38p#$Zezo!`S(Z!ys zG3$l@8`I?sFz8TOFrRgr^#;MWD@``XXj+K*jRn@5`t)qqWE1f;qp&er!J(H_t zhmLYT{-veZ-y^By0tNzd`p+8s{}EDH8atbL82|I~Z!{fe2U|5S$A8Ba$*MPse~U^O z0uEOz)mU7k$bjFZ1-5xnurD^j%tm;Lw3H#~!;1RlN(;?J7tCLptY|;*5OY5Zqn-sS zvZ!SUIX>F*n+a3 zDZ8uQ4RBtrS3<%0AfdFy2w;(2~s-u3Z-T0E_58O*KSM$32oC6Q(5u99o5eQlr)|h7OT?(2LWVu>ui~v zwSVREblOhiYLoUaz0KE4SuTjtUn& z-)8a6nR!EWL&9SZ;=Hto0<2;7*mQ#4!Yt{(K54~0@4=Kb_fl6R53phuIA1@*z65#E z3n)zjignxYf(}mwn zbXt2WR@A5T05$(gQZm`NkUOViIxYP_!mNLsp(B)IJuI#MibI1--n5e6#p%paRQ)XY z2*GG*Ek>6k6hqsKq5nnNx7`L(0kQ}S3Z)P)Bzbc7{0miw{-@(Flb8|t#CHiioX9Pq z0aMi64~YMIh&eh?a{hvXfPaXC|93Ot|I;CMb_ICKS=rkF%*0ew0nY9Y|2`f|Mc)Qp z1Vdo4NE zP20TmhhP(+wCZ}|$@}pZC56&6%A|-?tZtN4=#*v|31)2$S@ndb+5E;@(!MFzaHS<% z<6(h>uYrHmtM<^u1b>pR`v_z=Q?0Q0fCnoE7u3Q*`{%pMGrH4&4w+a$Q(E&HOFX&N zZvc}laG~d5FfC5<|Ksc(qciWmG~rb2q+;8)ZQHhO+qO}$Z98|&ifucoIC-nP|1;C` ztanXM&$s)WwSFJ&vw7{k&vjNH@$j9heE1-u?TVGc%(uRiH-F3^LvpFxzC7Dt-QP3a zs1oU)R7#?>ICs;?7bLr?S{yeiiz@13=~fb1skoqCff2mLo*OwznI@6@c(pF@gl%`* zF>W5leVQlwP1MHFC&(}SExz`=`HohHsd6Ly)A~P1iTyJhaqscyTW<0LeaHLQ$JLyE z>jSWsDLR?nqklh^x}~5l+Qm|9m2niz+Xa6-oX9St`vn8{2s}^+%~G`8OtL7DbV(gykt~yR{mIsGCR`bowNW_I=1f+l?9P4mI{61LSeo(=&7Xf&i4z}7G&)-AS8>sSef%q;YJUokU`E1Uk&>j~kYw8#hVCJ$ zS8}P| z(cYgZ)=&$;j40TqdM2=g4C}w5ZXEfK$6NbqQA;{BL@<5f-*jOO5|lpZlSHU7?YnJ} zOzbN3%-ePOwKoeZY*$Aj_FRJg#1qXN1O-Rajej~sGRTLMXcH`?+&|lw+Ej?~M8S++h0jf; zh%yUPU8kw;^WxGLq+X^j=>1d9Vx9uY*}F zgSMP!v@96b?6Mt4T)~ffx^(oUecO$G2PsVZyup3Pm_C>G7CKF-x4up>I= z9oQ_YEf{SiDYQ|N)|)9cBEZUO5Ymc%wN%dyr_9FP-XuA1zwf>))Kk9e=+ws!-?p8XA{U1Le3*0c(e|no99t7Bq3g5W@l+ch9L<<0SDO zV?8-p<|3OI!vsUA=x-G*F@Gg6Ya#cK2*Y2^Dr6-@Ga4M$2RY*&d%C*v0M6eOf_NTT z1AmH-v3ny%z`DbqX>-~ff8aAr_2K#{Ol7Pm45ZyIM8UU-s3;4fQ0<@-4m~NodZh9) zRBB}uANYt@9pNVTi?h)gQ9%_+&eyoDW0S?$ROsLjg7P&m#>!)gReuaK{(3F!84XS| zXjiVp$E36@!z+7+tssW=7!`vu1#W{6v`;@5U-^Z<=3s8CGn!gV{-=F1kdtK*`DwVr z*m#Bl)jK6Esfd-|-|T?vIFj(`0+Qa4r=X&ghbV4NGpg7O0U3WJ%&Fr$BYfdfc~793 zvclJnO>Ti$HB6byGJh@8SdT00tVIrSytN!cw}KRG{*cfp4)ZW}nlj5!Z3>JD!J3B_kRV87<{hbs#(wUWJ_L1 z5sinAWua`ZKfUy5y=CwILH)GVi_tzl!dxr7$};oB34yN~2FLgyS9WuDfo84)iD z1OT;q6m@FO9dU;+o^1IR@%5jCX3p0RdKrILEkOTO&GLWRxU#98^Z$sTw6TovK@1q7 zJMj{zXz@Ryb$Ngp9i0qZs9FM%ii>NqJXjzQb_-%`A7$zF^?IMbc=UnXC@_$ONT)-) z{8~#{^?#%R=11L$qg2~4-o4QZSgf4Jm`a0Yi0lL6jIJN6@KRpD7b$h2=poJ3a;ya} z!D9RfT(;2Y+X!38^mPLZzRlpgdr-#K`y7me+&)weO6_a{&i$I z5I{i8|HnW1chA_=+1b+0oL<<}$<)Zn)%IT=On+6^9a$8^k4(1Hw(;{B z^(U88m+!CL`c3}4{x6XIoF9ndpdjFdWJVY!7=6<>4prm1ovt-r+N)894x(I2HB7L@ z%zvpIVGK3|c0>guv>UdXn|4sMHJwuHy{ZR(Mdwa+W-TE%51sYPUEX;ca07@dqa^kd z`k}3?Mn)*cuwuI9O!GqYqSKrvM!?~cfgI`Cg`_xxPK3HsDQ~xDky;Kb3v`|>lwOcd z;BgEzk2QK|mHnvk#F1?>-LWd@rKOBA#ed8t4C;YNvQ;F$snWX?rEpUj9uQ5iMc!+$ z!b(u_)GNjrn?<^p^W%e#-PXIj$m9-5K9}f(kZ{-b5nWVMzu{^eCq%F?!^)A9lDk^< zD~LkBehjUF2({^+h-XmUw8turyq)<0rJVgHDf%x3TEm>gtk2teoxoqu|0 zO{#scPcS`_EX!M5Fqb`-f;NjNrtZds1UY$bHXVQ)lf{YFV7g;W!$fLHK#>a9q#SMt zf&o{P^$CjZY5x>^Cw*(ZO||aItB){Ko*(aW)kS6xwPQW{9AucXZjo&h2t4wSR_Qc&zaO#4+`e^*qJ?e1I|9|*LnF$pnpLyyTjG3NC@hJ#xiTh@mVz(j51=O^M zs#{j~$9Z;=^lRNC)dI1Ys_+|2L&?g0k}-xQvcyt0VPk#D_3ZGrk5WQNAXz{FJs!*8 z_ew;_@U45E|_o5mz<4$gKEsTZ*eLUsSL>0)Jro;gOGbaJ?nF z_H!#V;Q54uc?ZRTH?SmdIR0VI;EnQ(U!aMQkz3HIz2EtA)z|});o?E~Ut3!=+RP=A zlG+I`)U`M-Kzz`9VSkbmn-M1b?`wW>{C(T}Kr#*)h2#v1y(zAWVEON(*xQq>~yG z?S#!bd@x3&szqb^G1{_x$GcG94rZgaeWzL!LXGMwD;up8K2cz;&O6D8W=Fg{Tj`x*8r z+;DyVaf_foC;4pn?+W|Je+Age@_4p1jK^-UopJ=|DVpk z7+y5JeQ=gsziQoDnzZ6g8(so!Y!1mA^(H6TT0??p#x*=hG3)AylMTeWh%Ile%rkRQ z(TWoSl7GP^gz#j`2@!;ZQW1q3B-NPq_liSUib3xkge?}i3M}<(7uamE%7fpxGBqvL z5&T*o!daQ!XL25LoqN4!Ixf(+eeN-V(j%>fC<5gJ^+hRxfl=A5hO|g3O2CP>eA&+( zwF%}-iebAn`_+5=+%bbFlo6E}5i0vd9i1tXFn?vV&GId=?_@}7%x#$Mw7f#B9eI-( z%Pq4_OKoT|S>Ig(@7pua*})sr%&^UWBS?Xx(xfy>6Cn$e5QeuC#!G`V$Qb1L zV1LcuWhZ}~It3=^U@%Mv7UKfPaF<^+utdXP@jyMA8ynoshlcg=tUbuZbWubgV-O~+{M%5`b0%3!; zVX6s~=rc66Ax@RVPRomY+_;MX85{3RY;>hAAtlaCjHy8o)mk{SK7#|1$;PdSsVUhf z5hRAoE1`l|IHF=Rj=q3eNfz5QOzvl*`jdn+zi=ioAbnpcX`m=14Uhf)Ahq!bvVRd% zj3>mrUAilUO1nx`Pf{18)AE!uZF1`sAPKj)D@WU_k3FY79n!1Z1ObMI7CLK+XUJA4 zOV*kzR%PC+-={65Q)0x;B_XEO0L!bK022;&RYCJ`wU1y3Q3%bY>Qay`WqtsS`jQO) ziB)-`pj__fWX(D=#JXBSP+ADF!hcjh!h#Bk)v98UL>nEA=;m?pyB@+`eXh!gzSg+d zENX6AkaqD1G-<@7?qfffsusXkD91TDQt-$&&0~S2o!|dKS+e;+7?P+^P?Z0k`n&OR z3Qw5KWZB~;_1#DzG!Ppqgu6!?n+UZoL)7gCr^|4Zj<77LOdHI7VnnU%MSqfn5|wO$ z#zm}@G?mGgoRhl)ZVVJN9J6%!M%BP`)NaB`QZF33HJWbmA z99VTR=Zxvf){HIHf*)~Zaeu)PtPQ3*Bk7z8w}Y)`C$))YQRz0%N1tIzLj3sMs$kP3FEE6m%sxAV&FUh>AZTZmD{}hr9fIWPgf2-H9#yu}`n! zvuQaFTbqqRPU1xt@jm9hmI6m>xmiffL88DNz8Gu+$!^`fcD=Y)WI1 z+sSLe6sSJah+3OHJ`{v1eUlzazHdcvIlC(emalq;$Onj+Asy4etT1%uFY5I~TbSBn zhe=1_p>Yr-G&Nd#`F~~oD?q(S^zy=>0B0_V)=}~mxPqQ3hUb$LmeCNL>D0xYIT^UtObY zQS=6kO=MQcw&-`ZG9y_o)M#?2Sqn+B(_MKK`H>Mpwwwi9Ab-DWXFoUT067TSFf)zS zjFzfS@>6Z4e4UhONh(zHxYQRbs(yN`FeB5Iu%$Oi#L0`K^uip|B41|s$(<~if7QNr zhP#3;jX!z zBKKC(cSrfo_kSbcZ452YwMlh&E#u=E7<<+wMejhw887Yt6_r0plFHS~0P;J)U**;q z^*h9$E-x}SGaOUSlClYquoZ9nVg<%;h`9C2wqT5D$%)Vt=C63mjQSmwkA7ys+*BPk zwNRfnb-wl4c-e;fb_mTtM1CvH`SoG-hu2RlaGRF=>wo9#$&Ts=c;8V*g5iL(f&19e zcgo%uePn_0a&=C>f7J^#@$l>~Tapd9|MXQLKtg;-B_tfl_%?1I-g_ zUqRQyxOfUj2Y5*jos4*a?3Fa=k$?L5RkLI0{lpeu!dSk7teY)hUNkKDB_ycj`13Og_R7}37Q-YJEE}R;qcij3z+|@`3M>xCz zIv-3%o;d5wb6yOv^f%mF7Ec={OPAhWrs(d#4!a2}M!)J4L;Sq_Pp~Q;; zm*=%P9ll7Y2H6a`WS+1H4LY^N5H|x29ir;vjay7ast@+Bmf2`kBUYd0y8sR0xR;7a z`sFBB9qZADeIZ5JTw4yZ3y8QVEk$v^CFhfc_@W)FBy{eVOI(&|EyrpNnl^?M=YKu2H@(&d6DCYE!e^40 z_q^l{nTgw#5u@xtVR@)0(DRo|$+JpjznAnbP(mWNZx@X{{;Xx4{Hz?`TP3u=vp?Mb zxjAI}9*cCSu0K}C)a-vUgr^zr6L(NGhO|p(c50V$08(zEs1xh0*~=F*O%rbWl5wzU zw9@W@tqFZ{Eq^sHWP#4jI<1dKW&8t0d;WUBH>x^K^CoZDiT_xV#@J(R=y?n2_{F1n z6(9JcU^mYD={kaGWNwYD>h1^M*qhU>2jhl?=FY?8XQ%QB=!rL^fw6#Luub?>-)QYwvz?%mUeL-`dg;|ZTmp60cMB|=M z4qz92-fu4ex&=nRm3;M=+GAfWo;;Kn!n;m?rGIg}`NK*#eGqqVc4opsDh-1!hdX4Q z+mck|%BjdyuK+q#M06T_v8=RGvne=N11Q_9OvJ_AA#6@RU7ig2)D?Sw-!$YmSmT)a zdVqePiC=Zrqjj(i7GDCdCR8nwJNL#}*_6U_(|s@cuunaJ*7MHYPKl5+-#$g!n$aOF z=YOSe1E2W9|KBku9Ws*)|6eqY3jE(dzfj>*cu#vvPkC`Dow0Il3B( z=-%$YE*yg+y_F1uPR!`gxghMb5?1-zmR+Z4to_mWa4^EIFy=;3z&R)|9=Um)naFSfebtVSjB8D$ybOJdAmkgv!7-GQ~m&kXgB>0QTQf z#fyIKDuST~H&K=2#Ht@zX10lK$`u=}(sLR-50UW!yCLHwQ|6gT#uZ?bLop{>Ocfp$ zETa#bKtuL(br2~tMr(OU!qyh1CG#biL@re&e%NHyV*rO99gm^ z1DB)aKI!aeL8G(zbxncC)?kW}wxrP*hl_pd4flwCvibUtIp6>) z@j&*!f`R-i7|#D&!Tfu90D>vo&>5c36?UkJ-0KVitnm_~54HBdaDL2_T9~r(jjc{)V8@LXM}V1d zHaG8SZchNuyVua@Se5F{W`9fDK`e~7g_l%-FOEi-aZ77;uQ`Ze9qQMQs*TdIAuQ|- zG&B9nT=D$>T^jYMbun9ir2+PLPvrkv8viyV@E^@gl7IcSwKcReasF4KMoHR!Q2_Ca zjh;PnF=XM^Pq`eKDh4zsh^n|*B5_a{_^8)WEtYy?VNEXaXFNnW|D@tbBTJBeP^u@#=S1c1wy-EMviu1-n;fRV6b+i0 z?U`{H-)m~f3swy)JAcXB$kpDWMMtkslk_A{^<<6)s6oGC{hsgdjAo-_WNBfb?3XKl z8coZ4RazN`CMvE&1NV za(9fy>-|I>xLhpr2$thB73Jr<$&!@p$>Jf$G2H#_paaN z4I92kj-|qa8Gq;45WrloHNgYm;-dv>b;QS}+zloLqW^|_$pq^A0I3fMx7-X#|HIU{ zJwUAD{|`>Qj>hbFj=zR%0QUc=KL6eZ|A+dhXxlF`VDMhAhqj(Ar>4H=#_C~Aj_y`i z2vG@VsTdfQ-&k7JWF~p6p0$dDB1sSo*zZBbLJTwWLx10Kj%$!dty_B5yJYOg`Js-0R>q7QFGmX0j=caRtR57*IBsukt#k?mROIwY3+n z=nezJqOn<+0ySV*DFD;l3DmF&3jgW!pQ_AJ;I+)vR$=E?A{r}-%kb(25fUsX4kbG4 zG3G=ljgrf+UpkE*Xz&OjKm5qlXNKo(u{$R28|!FOB_(1F(qP3X8ciE21XN~aOk(`p}-n2XXfP(kPp;Uux_%5WQI(4YwJ?ItepA2Xf%3zmRv%m=4oHUwsed2b5<~fMk+lbSC+_ZJ z1PSB#kqyubgDRtR*`?Rx7-HJa_`X${{eQD{d%~9QE&~AsgoFIws5$>9&HNWFqq?;+ z_6nw7T%slknoPZ{6%N4B2#`cDcDIGLI%)t|rIv_^H9jZPErzT9iL|Y2m{Yv+=qH`5 zxAmS|nvcW-BFnpYEM3O@IhQ|oR_6AG&Xl=uf>WagJU+@`7RHO7`_Mc4usy@+|9`!c z{{_2C@P#-4{@W7rY&F6wFzwbLs_=LR>S0(xw$g$3ejH5w`p zclPOD7n5e#r3Z?2K4=kATOcXU%m#HSeNu*WJ=~m(Kk4nZE-Ry5n=XHXOFhuheALPI zRD7?ueKyIR$0}{A>~sii!)iq#DSrhPe`=AsaG^VyIo{=D6&+XOR7rRR3y~au{({j8 z#Uhs>cU*d=LFufuizyt`smRb|Q-%bcC8VO2%Au~8_q$%#V73u=p!2e3(`Im&JarbO zQ4N&)wmmGDE3cm}FpjmHFx_$TV%iKWFAB>P;n7rfMRt^mrXXf6qO4wf2!9V(-ndTS z;XdCIY@-P$*$l-ZTJ0L|_Joo!tUU}KH`hb#SBqC<0GnZF@N#w82OpI?iOc0s6L3LJ z*0xfT?oV2mxgR*c9V7sTI6pZa1xh!3I}>s*nHP~^A!an1#Vg%!o$3f3hBeYdOhB(V zN)I@aichrkQo|1BU8Uk;$A1*cJ~Mwp+~Dp8b{m;syV)&FlqG%P43ErgN0>RGqR#RWb5Z{n~d zrRJufplxhMY5>}f7E0r;V~u60S8+*?RlM0uy@7&ErIxrLhM8^8(ZOwpQa;b6oOh-MWf{^^I|f}?vTBKqtY+XnVlw~nzeag?6N2! zggSKriZUuWYt~XCi=(=5(9TouAh&3t71&M^0wDuG3MdQ&5G_gu&Ct)Ptp52Y7)t}s zKU=;uoqQ`}{eRYnTmUM`Bq3jmaaI`GbndM9AmE1@TzyRiUqh}TA@O*wG-~;suxpp) zz7+AW2QYHm+!oW9HWd<+^vARSzJy85xK2qenM+yfT4pRiY6qj5@m_7i3uC9Oju`62 zdZ+5W=ZnO%XOPUv(bW;)zCii3Sjb7`fS!6E6MREk+-daj!TA z`X@L$TpxZ}MWEV*N2BP3+se}XL-svcKA`ze>=GmSLno>0?6+Y458U^6!^`b3SLZ~7 z?ubxcw1W1|AMoq@HCHemm%cpXGUp!nih&y*DYtLJbz)d_pX7t9!X)RN6)}JKuFryKOdd8(CO}`cm@C&4cFNL8Y52#-% z5#I43DOc4`ergK12bhaP$;($d{~$krIqiy#&ApkS{j|oj^%p+Sg-uup?b{SZcy4tJ zy!(--KP*}l{5grT(hyLk&b1B4F&v5KQ`T%u|9^*If?gl*bXT|#S$sb9!KEKD?`Zlm zVE+O1xupn7e`p0Yzv>0Ncl-~JF6Bvx(Q?R~_}rMyN%-oVh~3U$HeXxc+a}#~Q3+X_ zb<&3P^MPB<)YXw_1~_R=@e_+HusGxsg(WU=%|Y>!tQKz$r(}DX!_TsG#W%KXr4%}_ z6n`SCYrK^0QTIwp+geFVV#*#TeyL2Rk~`7W;^q#vlBSS19Likck{?Q)0#e|Va7fpP zls)w^3+{J4R8mfVKkbdje@WSXL_V2|g51 z@dw~W_2aZJsf436$tH0)NkG zN!M<{ge<&mk2{|23&Q@x)2VrxCM^>S%$#Okd6|A7@19-sdut=@X|B>KpYzqXHdW-m z^1%X3c$57rd7`84FXuz}5z?*{oN0a+a672e*^-v%Qy_dG^(noaYdEgoT_|tdVz2MJ z|Kp-puaI#>LC4-25_n0Do=ILR42u zNe3$Fa^yw|L#Ei4M?ZWF>z@3nxCsfqiY=AlwDMDaX;b~qK;keA+So}ocRiI^Zb?EjVV;bT=ZS}1GX4n#7 z{|&hO@8_gqYGeBE4{81jE`KZQ%KzKl01#T3jS_{wh(#(jUMNwO4+)i(k%ffpZ%!fM zkz*&0(RjtywMh0wlW)Ot2k}xA<8Hk3=T81IEJ=UsngAq1q4L}pa)bkdcJkpa65q~6BScu*vi=V;z zfskE`-rP5)+y)RH$L@9DckiG_Rc|D()N#Z{v)Q5s)N9r1x^XKN*yLYti7dz2#t_>Z z4i1n&!yfs&e3KBNs+_s=nHN(3MEWzc*}B zPFZw_hV27&ENN_22Y+*3`7J+yA+X-h4Rni%!QF2^v%ZWC7{je^$t6=4xLUOz?nZ_= zGgd>y)6g*5Tr?Cl$#J=gZyY4D(i!GO5M>emsiyOpN22Mi*tLmqJq^Gu1#Y`_7JsH}A{YOzdp=hATQ#fZ zdfT$%Q4%1Rm@F>H{x}@?TdDLr&rW$Z04Z+)zYrfr=9}1sZZTUrQE{qPKft$W5>f3G zhjEue?aXB#G^If-(Ga(z_yrLYRvG8}$3=0YV_*Ycjx^GSOLHWFeFWOUVTi;I)hff` zfrnTdp|GCJcz=_K{aBeC)e+1lwtybNedag8j?5Sg)T?$>C!aQ^0GG7y39KcfoRnnK z;fnLYs?Pat8Y9@)qvJQ%A`e`P!^p6V)&9q?H;9#smhy%EH+0L-s^aZ)8Nf; zlgJrUDZLIM;}RBaGVgyrfnZW+VTu9{1Qh;XQYyQ++JF7qL$Lpu=TXJ=e^M%!sGT{Z zh@yP6a+0mFNJij}3}+i+>I?z?{M8jdqVdI8yiW^iMqiFd87^{iVNSu44L9E|=O)WiDE&io5gmUEcA znwHIY-vT; zynkzOg23!PB<&=p+UezicxXwMZk;leyyZDn+)@OiiWP{Hk|%&tRJk@?_E8Hj^YX=W zl9;t;0w=#3Fh(i98aTSEVho0b(FzeJ8X9#x+)$pM&eX(K`BscPos7tz6-ULMl}eR` znVv8&Xozltx@?pi_=E#x^D8H>6AFbiaew@@(a<8cBrZZQu^!A+uk4=U2lm0DgLNp{ zO1bUESOZjc1tQFAi~hFSRiny zg4yH9&2Brs$}Fm8VzOsqM>wJ12Gc6?y^@Z*QF`DOj;sVzb>1N-cv>lc=2i?Z_j1^}^yqS#ua`qSy*^-Td{y_xJLVBU?Gk)tKQNEq47ORe<= zi!_Li$Ld%10T702ZKcg6QXx2QF7mIGSLYsBEEW@r(I*)9hFDi?$Mrn!MR1uO>DBY!N(*#~)H zn-6fuqelR|woKLdD1^#nSU^7MPV`~fo6e~>P~}36IRP3L+(5ZGfTD3Q4ygyg2A6Zn z8O(MuH>RaMLt9{5GXw2us!2DLqrsHl8bfrcZR6M;R7_KjfQ-GAN z&}*km&1>J%Z58?fi-BkcHh-n8zV(I}Pf(LR0^$O9^_R#%oS4(%2 zHFSrWU3e#IRC&_u^(!dlyJuM-K0(cy540lV4K(AQMiw1Ulxy3~Y+PH&?qJW=tE&qy z=q=i%peFC4-6=Hg!U3rMK*nq_EcEKLY=+rD#Z)<0fFMu@R7ImfG=Dc%pP*T=99*rp zAWCa_L<{4~w%$^%!1(~`ZL?;vDpvaY5f+mRgk_mn`jslTF;(zPo0Wop)nRs~Kr!)_ zf+c`g04?+*&t>98So-F>K?TX=+rPkFrU!ids5$!KM8;Q~8V>scc>>IMB974HFTpvl z;XNdZk&(-w_5*#jsEeFb$1JkOP%+qvhvH5MtqZRVa{C`07tr=k58Iu0CCGBAg zS|%-Yb3TKzRtM;Hk4|233~6)Pt1LQDKpNg-IG*Q106(|1$dxD54G7f`3DgmSBa5oh z2=mp5`(!bNHz0MrQ2kA$u3T;Of@$r5d2tJ|d_WKVxWlq7Dj|x3y=G@)WV_0QroXHg za{~~pquufX6MwI&-KAN(lT1L(-)9bL8Gh%y>b<=q?Y+Na?IpCqHS8tzrb|)Z_YUGu zQ~&zMePAh6VG|(;AfP$;|LU=we?=NGdnaSl{~Th}-<_2Ks9$JnooU@;BCNv-kkEvJ zObD67vO*}3Vo?LXM?t$vixE0|wIwj1rr57xd!sePS-wI1+5os=q zW#8<|m|si21hzF6Z(BR0(S z&qq)Qm(@_M6|pLowk9oEX}q>BFi`_aF49vg%~V?oqnI`>+LcbftnlG53K6(!4{i)1 zikXGybAQ7TKSmJ6o4{roP@uwM!8fpLz{}&VOsf_iRDo_*bSipm+7?=ISbW1u3lClg zTcC1LVHcR%Oj$Nwj0*!zsZUCaq=`HS7QH9J6Jt1q*G1&GWoEgEyQGew`(lwe2?&00C ziu$TgQ=*r|5l2fPUlaaOgPN9xEAvT(?v{w9kWHj54ar|$pLaB$sFKoTX`*bpAjWy# z=j+5O)JnBW%*eX#(UPQdp8g%PofEifMt^{3ppi>QL$ewJK{-JQXb~?lce~p4faE>{ zex*t=v5?j8;$Ml;9n+?8;EAyd>#F-cm8hdYlO;1a_13?s#dq!rgt6Henh)-A323oW zd|?`+jmMIDbb8DT4S{Zyk6$r;M?q-%J=?HD)55VGP*(|YIFF?$j|OK5?*MC%Fn?1* zLe)qWrH#pi@8Rnn-Z%^(#A&{Dj1%@qF&rX#R=mb4^=Eoden|{xWo?1i&jpYP4z6IE_`I2kVl?DK^!saF@)xtM79JF~a;!RCK~> zvwQ1d+dz{bV1@Fwp|4g^I$a7B#(!X0i>$i&r7*9Ll@l1Z4sI2T$_R=_13Ellv-vo% zXTzA8Q2>lMZ4N;Pj6P`#t2p<01fwbuTV++|1~E_oFfXN{ z=$vu~C7$M53N3p~dm0CYI?12Ju#+bz%?bqV&pZ1bm^<*!(tAWD}$%xc<%i zrj#kAZg;#~oFE$^_==$BFj**f-a1OZqREK(k6$989FlLt#^6e(59K-i%#4Q5Hs3`e zrQ);{+4j&MH(kqG%cz3*LUIwJ>d=yzo|mYGln|nJGm?8I(2fWTaDSQeGHq_faqU|T zv`jG5h(kM%XVN?wXS;j%a_dhOVZ0j(Y2Jx0=}Vs1@QRGg#VmaUmLRJ)7=zQE1KKif z8LN2|oPF0h4n5$<-8*XUL8uZ7aACHNt*z!6FcWLwY8k{>AiR{ALrsh&tFTm~eERN~ zb4We550uFDOK&A+2Y>M~uDb?Sq8_tG2lMS=|4M`%u5{pv0gQ7_K%XkB0wB|Z(X28H zM!Tf@o2~#a_44tPG!{=F#0$v24{~`M+8U{01-L?go_$zHsvIgq6K`UlM-Ks!erlhF z6DoSbt$y(eeU2#0WAKi`Cm0O3H@tVJYzWA+6qj4t zQ*hs6K^dwxzCT5JD(1yIRg}+@xi{_b>8xLZ5y_u2- zPZQp+QTykIZhvI2DXcHAM%7_=G_;Pkjxx4PGtEVM&XEgQ@S=~lXMc!gvxc6OIg%m0 z<$uh0`nZ2hA)Kr_x5ha?sQb&^+b*wmkKZEB>Ul1R&?5~$k}NN{gN;{Hbi+e zW@$KKqq9|w-`@?7@~F7cAI~pUp?G^RlN9L0omQq z$wc1F%-PiCf5Uzk?${%!-?60Drk+I{QNkiw;9x@a4@tQkP-0NK8jkyFaY0vHaJ0o$ zOA_lE>#AyiHyR4-s+;7|+U_=q8qaT-eLAQ25~HLZ|g z41cj!3Y&s1rAn**Cg?W!K(FoBp-};}R)bd<7$vZ}8!RC}bmwpg{{3`No~ zFOVN8D***tV+-Wj3JVOVF(dbxRaNWRO+A$t>N?PHJ;CA+1HYE&f)_ygBx~KJ`yu?A z##_fbfxg^Ybjc0VXadGG=Jp3-ty^Wmet#|@AlrOnGbhfr5AT|-0WKc_7bNK0X|;P2 z8u*MF;2hkItWnZQ0}}y&^U>P^Qx3rC8i3B|hGHslljp`(f3({{mZv&4QaxMLqFFFj}V&W4+YWG+E~4 z2n)5z>_fnOMJYWVQ#mf#1*V{cbGlR z^H63fD>-TDS}LTIZ$U6*r4C{QdM#LumZ{-j;QVZo@-5FuYUXztftJY3T)}uRAt!$s zswJR&;hZ2RE}+Kw&5bgi6Au7h{c&oj90=tH7_#07a?rSHdPYzs)e17*E;5i&7s2JB z;uF?m#h~e3w1<(3tx~324P1Up?H8gc7Vx@6bj)Yuzz46$tOnH{9QVaPlgSUSr(0R5? zCp0_rJGf>lOE`F3A3wpIr^%TCPA6@fN9Y|@I&(wqc%_yCnV1$Gtv2XPaL3di=5%7N z4a<}j7u3;0U0L^P=?BbPP_xAs+kcHM^gTJZT-QQ87B!o({^XU&Ehiek=^~eokny0! zM_Y~~tM5roAN~{wW|MczDRqA_!C7usVL0Q$O@&EJ*t+DMHaAL4qG9}2M3;<-zPE^e zQ7z+)1!qfj$GTyOVfI|3t>d?Gm|ge^4G2gyu=t8*v}HgZYP zyWlAs$f@*&TR;vZ=j9;>-$)&e`9O#FY!{+^I7IItBN~&e4=c_P+zWqJ?~LZ|+0jrU zpVFtvr`ar04EAdM39ii-ZfkGwBT;KY+Y|k2Z^Smg0pQg=@iqDQ19Kz2zNublo4-W} zK8LV_J+&utk1hx1tf=ZyHU?U0#gT^-OEzxwvElz~?JU5eYPtu$pdd&|NeD>8k}KUx zw{(}wvcS>}l7ch}(%pY42qGX-(v36{QUWR|C5^~`edFU}|Gs|43(vxHENp@4e_ayr1e0<7ncH_vkezwf2U?ST)E*s9C-dy!c5g{k;T*F%xIv+ctXUsWL zi9gcB-tIFpyfG&~W6ngbn7=k?E)cg~F3xS46vLFC&8u7;;+}ugVx9*%Z85)g^5Iyi z#A2WuD7exa(LR}1Ydu`VRrQhJ*0Sq@HMj4}NDdI-%<-oMQ)hp8%`y-!ki9)r-oOy@VXtv* z=wB2zrL=kLc}x@n*q9qTZIA2psA^5UsV!R^39=<#Q2#8z#@-xUA7cLQg^Ukhue@dn%{EYM_H5)YIqcYLjJ(55?*sJHn2d{Rf`e zDDd?w<_~{9Emg3EfURKe|Nm*Jjw^vA!51byhG=SZFcGGxsA<%#OTk%~S>X0tPGX=C zalCl#VYNiA=ZYPc<5$;f;E3a=h} zhnnaf0oY>(1-;8Jc*n#s0t-*_tdA}cceg~EU=^xlQ?;sK^p)y~x3=aR#PGb)KKI{cGGfcg_O4w!;?7zy0Wx!3F2D6lfIcS%Y4G_xWz zy}*Ab6=pL1oF5;|yceisf8rla?JCxNO>IIVY;QBFg86i{Gzo$=$}y5};3(FPHtEbF zf7b={tW?<7PR?y;_+d3o8bt#xO(AlfE^MOF{u&R5c|G$3`v3|fGIy1Mq(nDe|sc|QpwTFbS_Q)RTY*$xo=5Bklcf72M$P}O{<6s!7C8mEq z)w2$|Tt-mOxMx|Fz5t-OGhW~6NPsCHeni7$yg-vrtQ{}5@{X_Ij$C4NDDI-0%ni*d zQ&X#O{AMb$(ShDA5CwRt?!CnwZ4#M1pg*zmwJ|P6%{ezA3fV&HiR?fcvX^|_0|}Ad zEE_ent|MCtulWlU{b^2BVo8=w=rVt!$ekoqlb6IB0+GTy2#iez8Gr`O@^bf83l#*~ zZxjGXJ98Qjaw^DLc9b4p#Bme~XCSs1xt?>2afTedqjxDgPd>BaWr}QDVZ@OX>_uu$ zVPyc}MIawxal2Z~V^QeNFc~s1@Uki&F@cqkKUYqmN;qbFXUu}J*iu|ZcbI?RVT>fb zC4O^v&x}eS_naH8efh15s~tB=n&vzG#Hu}(>7%eCZ+8T+6H7JIksbk^Twro}s;Abce^MHlK71yOybg?C&^04vLhkOF&j zFMM5JS~WR1XWx)$=_!*Vr!Rj>%ddr$-p$emyms>)6{lN`C)VuMWq86L$nl==wX#dW z^>yy>u`Sd?Y14A>Hp|tiXS;G8k)Aws(@41QDsEKqMK^Q5uBpGLPJTMayTym;%@@*8?xDNgs% z!2|kYr>qC&(4L4pM96=8dR&?)$;_KP59=uJxq`?W>jXU#PEa2b_*&akqkZJitoVFS zBfd1e^GJSN;@zJ7xLBQ{mfa=s9?Z(&F$YwwkTs#Oo9qxG``A`tqGz_oHK4ntGLT`; zC8m_y1Iu@YT0r-u@dG5IGJ{OTA1YP$-Fe6HfEm=FQQit~eOB_)$T!X)3-f|)p( zpL>X@qfFL8@+HaAB_5Y@!1oEGE>J-GmafydL!ATinnQnEt&}gfgaZqQ;AAO{shK9{ zOG;o6`C@6Rc4hRq9E^FNj-i{5eWmdU1~FGv5bU^8;K}XEG)jE zS+)7c4adi)U-lzTJwCkvgwOL*sb{E)#)evqfXH5d^xUyh;e_=`lM6yHrd`}(lNwWsQuaL`Gvmdt4CEZ6^`x>BVU;_$K9pNj`T_eg$%i?>iF0`ZrA zsD#%BI|rWCAXVf$j&VN;F@Flt6XT3_3H*#M>xzHb%f&VzE!~q;af~#cW6W6zV&pG@ z%8Fc&zt~k`N;tU*5ce9rk>{4;Bv1*Hi>Qq*nq0;;=bt7u%i8V;?0IVSfEp)Rg6cqlcglu5Q^ma;EEUX2zspyUp8&h&@1ZeWM<=2QNe$- zT6nD%krHxE3rwi?esh~|vTqAiSn*_{KLkI4CI*7H8u8mUP9ZX4&&KjV$hD=$pdxtgp3R%1cNKHnd!?QB%=(mFHheT*3Po zB6R#KRvWCOcC}8T!7QQ*M@_1t|kXtN#RLPjB3!oYT21{Bys?aKPe zON8|`!v!+}g+dV2`HfG6XN-2@6_)YKmxub3JiL-sD@#+WKB9TwE_6|^xrP#cq+70)mKzSiNnL!E@87w>)-#j{IW>?JWQx%z*sGEjFQhY=g}IWfK4U(ttdvVxlfDXA(H2Vi@vtm(aZ_j)Ac7W%p|5$oS9`N1 zY@deE3&ludGb=P~sJQRgOP7D7P`DXjn1>cOyHlFM!a--%K(Ds2iuo*Vx8>$NExOR2 z_cw)DlQSu?=c7VxyKiUNfNmtL$l|1uT_cytIVRN4d#Se^KO|9-=eYSQpc5Y_9XpFW z-p{-(_ey=(2JoOh^t#()yD%!7q2%sTx*mfvj@q44Wz!I9a`m>Cqa}Zar2B3+(&ujL zep&%ThDNy^B^)si4Q8I;@!wCN@Ju(Zw|GI6?b-v>4eNauxaM#RR8c(VOKDSPl%6B? z#7g^Zl}%jo@Ia}7lhcf4=SlI#^Mwpd?3PL@rT}#UY0NQ7T!T2euv{x)MkB43w;rS> zH`zNgn8K91N?|HS<7$7zZ2Q%(@xu*ru(gD#ytZ9sBLwaYHrGT(!a>oH#dJ=pV!ZM5N1XaRm@;EFd~)Yylj~0gKbo^Z4;t7xw^7)b<+>oXxYds z*Y>z@oqk1TL7t0e`oj>iA$Ufv{k;P}^6aD8hK?qZI(ia%-b@qr#i&7j(Mgf}w#8DD zHGXmJwzH9yWFyQQ>(w8?(tZngdqY(Z*?a_jA(xWS>~Vjtd~g{wx?CGcKP4REmC)=h zBwyeWSvbS2{>88ZNk4b{kU?yElF#4Oj`%dksO~gN>Ts5?y>Qttc@u5Yk9aafTE{;v zJ7}N_b)YQ}*Gx&}{vnt9IK~oGYp}y~u>Xq~`TXoA@v&g6C;BL8;s85oOYJk}1KL-| z%;-ZL_nv+b!Z-C64Jzx=&qn{W+^_C97(n~!n za4GP4E>Um}3?`QI*1DFzLY~*7c|GsBTf@R`6UlYA%{HR6l*pAFru&>CpoN31(+9TU z2dUP&#aDykZaem+O>XQ@_wA<|efc~m4KO(13REmmxuS|I<)7I@AbDajQTmvDr6hr% z9;km`@=0g?pz;cxK}={?<8H-!yB2cRhXePhh9LZLvpveg<1tSq37%gzX5tZtn#Vty zaRLI$6_nWR`-zYWja;f$m-%fzQSVP5k`;rj(s-ttQ|7jDvs(w^>LX-&YIit&Y?a!t zbZDYXs#{6>WiEV~;xcpSFHZq_jT463j>CU$$QHKd(8q!G#>@u>tJqu~dyqLZxfm0P z3sLH+gwJUo`L>eiIX_SjHI4{%UxSWY+|@CPX+M0;VLczv_?C!p&5V!g8CH3xRwG6r zuP{(XXquo8YAKh_t>2SSQJn@H=IP;D6K&zma*Hw9#c~ZjzH5UqyuC={^%Cui@pykw zhl!O?Uun?|ueJnkr%6hx@_P9)`b)XpLG}`&_d}()ZtN6`W6P#*-`yHOdu*eyg#^Zk zr;6#ujNnL-yUC)i8akVmMQDww5^=2Im)RZ^WYaC3d1=o0wxiN8w^9_j#@0mv5&~*L zCEwOkN30_5_k?7SrHSC4G6Lc}_9=fEBhv{<12@&0f@E;NE*mK=Lzg0J8Gqru64-`7 zLchwUUj3Y2xo4tas0ixoq07y%&F3W2uYi1Qr5|UfR4}^-<|~T{t9i`a466y+K)w9U zW1*jt>d*-mRZ_rrQg5WR4y#6&V@_L|Z_g&mTTW=Az6%b0@Sxq?bjitwE%twU)Hth3 z3Qa_BbzJ{**t!FMVyr)ZVBjTceX;%`H~L%Gul459*7%|0-GxXQ)ZC9}H2nN~dw)xQPLx*VStfJ`3^hNq~#gQ7W zp~q$;LCHi-HYhz5&m({DaA2qFI>Rn>C*-DqZ4N=TVY-Z5`+A>VDA%{dp{&X9YLyseH24in!=C>^H$y%%w8M$=>s*#tv?uW;TYfxqZn??yx_flQsoHTIGytrq3SJ<0G(2=I zn3Zzc7+Mm>*;uFv!r25Xmy$Gj`70f*oFW`Y)yZ|&;DLV++z0T1oBO*1w+qY>W^2PP zZfkAl>;!et{6qZfn2@IR*W}3FJQJqFr4>L{ZZBL$CR*5V#XV5wtpL;n8Qn+5gedmq z)AaJu(^V4$p`8tO?Ks~1Mc$d@iCdQrm_J_&=bU%6tz?h6*!`e(!lPe!Kg}`iQ)Tka z(~}b%fZ2a0OW>7eQgw2JV8-B^T%!-HUfXp~B0wmRw&t zj27#KSI2Q1^mq4N^Ts4?zCm`cWG*9|Vuy)%#<{N~b~Vk?6r)&2bVUEt;#A=(FhSw! zqqG$6PP?gb2I5FYU|#8%Z1aDpra@^pEKh~I?&MPd9&Y45F)m4E zo~>4Syl}rZ`x`7NlTyM+FgXpeM#j_ezU`FN1Djz>#)OXmOX=8wA*#z9n55xLd`v@m zcQs#gkj8;{^A`9-lr!QA6;WN+$^DLNR`>8Nr4j`0ML4B2$|e<7bN6g5H!klbskQOI z(rtgyds`og>9$mbqno_Z>iit%U2JuTV==5&w!JOJQ3R0-e(sW&cX1;oe7M$a*l+(? zc)4Jmnp&jNKuzn1yX2gL$-}B|v%=+TV^Tt2eR)o2hvG=OEl@I_GZmr+EBIvx9w@@)J&}+&z;PZxxQ^7<1l~5jss^?*jRzz((A;*X4hF zAG@|SU0`;J-Miqp|0O+e-Jeb0`8rU>36G{O)WCFI$))gAn4D$CdD7szkJpP@W4*Mw z#8_vP`%mdDUe?Dx=@NDzdNWa9?a=d_+~-5oK#h4kd5dkR>)h)TDzBnG^&lalHwRBf zO|WU6?1a`nd3)pyoeiDu_8w+8GE9G!d(vb;vf-lI+FKLN&18t4B`^3!@nxpZo|C|C zc>VIn&M2Q(4E;gRGl)IqJP)3)Z8OL9?>0%!g0vPNx+`COCK(qCGbnG%I(;pYN?_kc zeDxrNC>~YP^Bw=pJX4R(+*It$z3pouS40+wBVX~^IF9IDDh(D)somm_L!N)5^S}FP z3d7u$cR)Bjjd()BYJSXGSlHq8O4bsCFy$_}W!GB_Pasm8J&}4 z%z`@K`o?xKcTei_5I57Okr&&72ExEF+G)HuJVQaYo3{kuKV<{lYV?vY94RsrA93wJ z2)}GCZFuL=2fQ}xv37=LgJgf=B)9PWj)0G)6~djLgcPl%mpgA{5w|cl)Cq=Dpo1jt zR$h!Io|mX&A%E_-S-Gbv6Pv3=7}A9eI+3~7+^u~NM%CzKsAv{A5~-3!s*28BPBeU zE6_DhuH^;LLXDJM?q}-#F zh>8`paRxBqN)wU(oSdI2PC)veVz8B&tpm)-+}iPL;7dm*u#J=Bw+RL_mezCiYpJO*bGjXxC8*Oouf>k{2)bHR^r>bBkwmA zX2a#3ONb?SaQT0Gx=o-iFbLFV*yuV!l+XYGR{{Wl;~XUb`zI*! z(7WH(|DmPrOCP+(c~AiW!E^d)iGEK1|0u}q(A@TTxbrx`n?vdxNS^e&AP1NW)EMjt zXF>iz*K}nz&6g-|BD*nUEsNb z4gk=S007eGs1@|TK>fPzRkHhEP@0Yf${Dz1j)Yj$3paic>f`{1SpIpO1m2R?FdLX7 z{GZkTy!vhGQ>rk{uaU4pa1YfyN0sLIS*oAWIt;8RGrsf28 za{h;r#3g^90Co@V!JF_Nt$WS}FwehZgQN|_)&%Mx0ds&t&Z4Ox+EL}n859Gz;~Kmt z8Jx32hyUNP0|ej(>8C>Dr`e zFuW=rq9F2zMgJYX0~Bl`0d@j^o3B#V1vtV10EmB?007x@{2YmYh5v2rqo+ld?(k|C z!vX+w&S6nBeiQpwFQonJ_a8U#e=_5_lJJHt+>Bg!>&u-pV^8PbG2`1@DhTpsFucW4 z@c;mobKG9TpXL5F)c#Ddm24+9zTS%s@Zl|R4&Q3>d-!kjq{^=@@WbV2sDH-GI^z*r z|15v+?=Jmql1Ni>&(|F;1n`R0KSwIE`&p8@xdRlcWe$Z}{muNDI&O44NPGdWV+D8} zE1t8Y)8${Yx>`GNDX!}|2lgG!))LlcuxARAC4LmQzXMjy=z#A>#LfaUqOGHg6x>8oI?{l`4#kk zp923rd0(n@)EMqCBUcf-xLfhBkpF*M_->mHUk+CC!~g)=$q~Dqc*QS(zYRgmoBm(* z+W6C1)De{7s-Zr1s0`BV`Ji0LiQ2rNCnm+TUegqZp8jO5Y#J9!WhIf#kh&N%M| zekTnaA_p<~)ETF9gESP)5wSxnAII8(ox(*%)$7`66{aew9aV%Q>*5W}#Zk;vA5BPc5(1~I%*5fk@7s(G${%IpJA_j4f)EQ=*@&_>A*fE7jKzx~hMku2H9^pH$ z_Lb#PP`|1Wfq&Z=1PTBE2nYZG06_pzT0GoL005T{b^!^u#&iJ* i0SOVi2b_Q-0RZop*mVI)0!Ve2Bz6Hy2J3YJ0002$Uo_?b delta 58383 zcmV(wKrz2j!=zBZXj}`fIX3QL!IU?ssRl#%_$Tqs*nOMt`Ru_;f zSR?Y;IA10>BoN-*uvJYW?wFCgcTgsVz`0t67VdlGf4|TQ^lt4fd|2r4@ zUu83Yhn2pTn#YdWL<0Uuvmw`XfyBk2EzyKTmKuOeR&gSAu{423O!3nkWM8wpd1T1xN??%24oY7(=4-<9Bl>Fwu4dRK1%GQ2`}~%Z+Lgg*~x z3um61Kl=M`Pu;jVgMxynEr#5}ha^d&v>E$c)extJO+0TMj~c<^5h&hZo2WnO?qzL{ zYuCSh(6p+-LF@s@@Gy}5S19x=!JBhwGoofHE`j|FyD`K2Uaptyf%a0TQwn*l7h&=K zz!<`%#A;|`FReS&Q`38v7=ovN>GSV_gnwT$M%JN4@@cs9rb^o;wY7R!nE>QwD}tc; zvf)td-~*6(jElLk;fUhNIFdvH3Tt&nBk;im*Y%1wXNB{u&_=SYLcI>`0kh5}j+$q( z-l zd{_JL9ITax?_4B*#m7OvVhCBLrvb;@v!Lc8M} zQve$ijK32t_!|-CO-+Z86H9tV=67Vy3#0~Nxr5|5_mcv{*tbc80WM8DoXC@BF-Lzzg z6}>x!1Z!nu?9~;;po*$y#W5NEDe(8(pDn{CaQznNM!V$Oza4(|jtM%c0MQMsQ6Nk| zY^CLp15M?Squ*x({e=0X0xOK>gwbrAtQ#poah>gdfpQP&YN*#A;JM?q3x+$rpc_cth+=OLvz{Ih8>Y zaTX|nIwvp^q2Q5x%W(IDc-zA{BQogsXZI(au?EkmH||V#!aoI+T^co_niKJz@{C%c z4>}-!rT!lK4EHf1rcQDfnirR=Em*`N})Q?StnAS2<7bbA+HiKEO`4&DgjL7f~^-1;RV&}NVmE&jxinD~=NrE(` zQ!1rTGWt9sq1#(NgU~!`gFU?1yyhlWF}|b(vL%uBkVGR9#G*5O8Fl0X*59G8jI#=V zyED?@b6+S8rcgDjX#7CQN!eaQh@r(?T~1ae3rF4*j;dyKMt0PQIYNBfIU2d6UZkq+ zL24fPzED9bZR_@s#7AP8vIS3gx`8vCIoI(riz*t+e1iZv)=XTOb3p<~MxOAtn4Bax zB(w+si`XrX2bOBB$A?>P9eCbvh2wI6GFdIs6`r}I=-~t4Rls|?bfrEk*J#t?+??kK zJpDU4Y_=rrZ5kR%GN0~9CK;>1_-R~{MbTOz`x0}<%kIfSC^hamvvjU{rU|{Q5p#Ia zPL{>V^byF5c`dN+BC~40r%6|gR<>eZ{Rd?&{i8(Q$mLFOn5v3agrFd2yy9$sFpJkB zxbHN74#Q+3nfbkRjac2rA!(s+z|wN@axSoVKd^tJJeEcCmK0%FdPG(Ox8tfDt+vHG zK}v?1BSp1Uo~W?qZcgK|N<8bTMXW2dNyQqx#}nb(qOkjV>* zaSpG}4U*vTx!{+t3H+f>ut}P$W?W~fRc*eAc?K`oGHztUs?ut{IK^r}`>iIms%HKf zY4Rzf9%VI)bHLdz_$?Pnu!4AKQ3}dSAHuD3feyrzA{Us%_w?y-SF)z`Leh9|hU>?A zTN1-}^|^NG0m7-nMK{oYOjX+f!kq$Bd*d)>!Q=BH^vlO*&<5S23tPK3tg$n~xHF@1 z9R}AP#<`z&RhG(42q6aK(;8lEm)@3Ol2wPb6VGm!m@xQt1|#vWflX_|qtIsXRVeL- zMd%66gZ*tj#Q-!EcKl;7uiflLFMQ`*FVARWsg1D@FVxq=ZV#w`7*1TKv1QQ*(P3|C zh;o4dv;&hZgSZXTV5v29nk0jzKozq*)hn-EZmhqMWoKm3X*;ag%FMv1iTebqxN`pi zX+1Y2&29XUbcHlil^`28WkzMctf88KyK@tLI;e$9NJ_*5w6sd#q4WJ5QUo6vX5%@e z6o&HcK)JxP>-R{1QWJ6F`m$7f52#aIiaektoJ!gfglCoX1k5%BSy8)vJ>3~M(W}BN zq7%m6jUuds`o1|6M^nb*?A>Y>m-*0zgKl7^zVj+=w<~QIUDD^-B5IO0DIccAA$2T= zkZC6#Ze1*<(vmv7b7?tfM#5gOAca-G$ zHv&Fu7=m7ZR@ei&$$TwiSgA9JcZ%e=)Zzyx#UtFR#PALTof1(Gh%Tj*GGc7||!{ zsWU5cyukCWOsEF8vg%sJOdZ1U-pd#aZ40alWp&DbVL9KTQZ$uy+JcG=@S<0{_7bf@ zKr1AXHZ4rynh-%+g$RVgsgnwse3VrTSYxb!mG%WqE*z}pjb(%XI>zGhd9D9C=Hi~C z7C#_ruR+RIhA)&XGFB$M7MrR!E`>f2z7@G**S4JQr2rXk*s@g^_+F#3iDcg?GzGBB zxJ|8plzr8_5`JtkV0)$Wa4UAQ=NTu)wwscuOfG}RCd5C?#2SRGC7!Da)8M*Lbmb1C zO-6RvE!iuxxE1yRS8a6oLum=%dAN-juOzB9}K2(l4P2(0#-L z#bdBkpv!o1IuW49Rl`QizuQ3>rp2;rnpC?m%B(r4TiC7G@MT*39pz*E@umC)-)qSY zX|oEW6@CJL8P;_gq{X0Lr&?oCrF$8KURc@Hcn>yj+_E^hXKDS9AjsQ^|F9*dZkL#U z?%|{RdNh$+P&20fd;syz?xh3l+GXzMr&nF-;SexDNDLCT;>Gp5Mr#TdZJ<c>n* zw{7Ej0ttgIH{b@Iey{nxIO_!d{81!-oAqNlg^1!;!+0zpDy?XRV0FkCbW^hKfnYu0 zsYTeaLM$9XDTII+oun2|m#%`TpI}!~@j6CCpH*;d?nTffYFUroENFg}#r{NC+ZWr# zmAc#0f>GCURP9CB*cW3kE!GW5@KlZ$_YX}h0OmCZc#cSewZ|msqwcMwN&0Pn2Wp!T zAq>1sJwyoAP)2_OEw<<*zigN2n77I+g5wup^zhfw+YwrzlnUM*ba@S`(yNu}t676# zH;LHNiukUhc}y-^h8ZlN25)-agdkm-(X3KQUvgR3tvQrYdp@l+nNX_=&LsNs0^A{i&Xup0jn0LK9#JE}q{JMJ1O zNqrlEo)qjrPP#Hi4QoId#gsmsAKK8Hra_(!DQD2^Mx&$n!LTy%1F2$v)a{15DRyNM z$R}`xY5BM0nYxKik!z*nnf%`ghWMHaE6;z}f^a}U8vnNh!@p*LNdEQz582fJmvB(E zQNmV1@ujuf2qrC5pHM_WzMN{KnL{R>Mc;3(mRo**${%bX&(BMJL7E7V zfTF&OY)|qkTo{nPwHMpT7l+OQ!Hy_G$j_!ctL9S8Q@_Vqpo|_`Si+16`8{L-rbDSa zfEik(Hg3AM@&e&lFCDdMa7w#4k!irW1#~}*@<=}zCrWAWm4pl&+^FBd9c|l5Na>wA zj=8{0lY>Z-rF2JswrzOIJRUnh6DKV*(?~-((j%-9LUZOVHsleom~cQU=NCY%x~(!t zu12C5nr1!l=ql)ra6^S5k0_L7&<33KD5n)FvuIT;B$BG}r|fNLDMBQMZ~=1JihFbs zLPZ;eBN+eYBE(Z&M6uirzKl=a0TZ7w>zH?$$n8pT4I#~cqJO_U(yBk7*p91l&*|Z< zbAqStJ|R+}&G5t+%vE(NOAS`2FFo?&H8?Aw$nJ)*aacHe=)N@)kgm@z1hd2uzeiV> zWN>0E|CL;mkJZ>*_MsIu9IvqVd^ z2+LIGF4U=iFrd!PiZ0gFEb%wsXSM3$=@3@MJknCMirhxiySg*uXu3X!CZU+h2HTUO zfU7tiVjQi;d|p8Dqqy(nQ3lgjru~~%r{YSE@9%7%)nrat z5k)drxK3fCEw3(f6N45B0kvy7K`&e9Sk9ail}&A636I}Zx>0dh_Z+ozHL^YlFR-kab9M4}}j zd5nMFhxn+8KUUHs@>cT>GbW1JOLlaMz{4@4jhs2v9`E+xrNZ1%%ZIJ#RJCDsEV%VT@!5x9-6-Vbaalc2dz2+2r z!VntVG@(HHL0uI1;!h$9$M|V&VD#i3t!kZUT~vw7JB;f!V$R;A)Jbh9JbhRUo_a^>Ge)fWDr|GVdI@t zuS{mL{2!=S`dNPI7zRS0JTor_vB_+I7dLpx9@Q^C8`PxIl=oln1?AJ#F*fn2OEf7( zxHr?&OiVMAQ{QhZc78yuap=B}xhpUTV)*Zvp|Ou?p81u4B4JKH5@=eXpFjhwYa$^# zlFSDKAYQsp9JOA|W|(D%evZmj)osU^z@$>hktXO=8YGbocZ&OV;;dk+ixBjGepjT5 z<$49$bFEN~I@pD&<(U#J$2Lhx1EyfflN$@9$Z0j!@1zdS$xZ};jDCV3SIjvn(NGRi z`xJv(`6e5KcCA#S)=(41!5u_L3H6cwCb)Y6a6vFu>b+t1YKc~Ug=C#CSn2YSLeD@W z#WGY=+2pFgz3#+ws50Nb2fsFd37!H>{+_xr_}K44mJ=@=rfA{dOWM$x$*DFhRjN6%||I*|g_HgaBPO9Y&%oVlgr09`Q@Y zcRjijB|h$;u00*%4wTls#-vJVhskd$hMuNy&kle`%;tg1pgq@rMmO52k||@u z>Tga;$A~kFMVx#kU2}{Cwy%}==Y10n5b>Do*Kf|qH$d}~$mN7J2J0phf`{p~k*+gm zqe3;tXUhSx@8--A3H$0PrC&>u37ZoIF0piX!F!StjV_bUB+; zI+E-Ui$m8T4s8!TB$6Tp?Z)e3(qH0M_>!<{XMZG^W>_ivmnJBGCTQj7w+B44F-_Yo zM8>Z9iz0Z4>gZyXf0|WD@hOB7xz;!`FyEr*AUbR_`(;yI!XOEbr%S>Ck4-QBgkip( zuxA1VO=7Z+q%|yug^2@>)|8kk^J1<(?xGiXSH6ODTcCJ@+x|oQHG5Tr1V{341&X1T z7-{#Oa0V1R6??^h$x1An-y&@uvKKU&{k^}r4?~kS6y8G+`%%E0APydN^+r~ljViBU zcXqY-zdqnUP@o51+~*-F@}BwiE?N5d*mNE%25JNMo?zfGz`F|WUPTVDabq524l+XP zPSgfz*JYd5JTseNB&lrVQ0jVdIN-C06wqIcdWgHxVZnEQ^i`48yRrFNU|L4As&T#_2#r8)!@+=nz>$D}6#mDs_Ad>J z|E_*pQoC?MRzdmMnswc91_*k9CqSb~3=r?ZfgjC(p=e61uPkKG%u z9+1^IfXuByNH8bnles>70oGbLO9E3&vVm1O>X^d>tMb5MLSvcCeX^kgl_4O~GXS7U zGNvMbGGi7N+B@P4Nx5ddX5wGBBXSGsE)CpDYSe|Nf0Ty4pEMtx#$mU(E4le zl)XFRUrLcizN=S`Blg$A=qW*i0{Qga6KjUIkmyTp`0XTjvFDtGg#|Eqo^f?+NAql4kIFFnPIwyq%t4n8{SPL25?gzaLAt;M{PJv z6}oc{c{Eyz2x+pW?ctJIOBe34H%TmiEnST;WT9Z6<|~KpJKRg72(?5j<&XWcJ$bYz zm6=PPZLqh-vlZZzC8p*zGbV{Qj;F51@?3YcB&E&!+x-3~EF9m*UE!5?l>T>lofjHU zoFNe(FYJUn6fx`*1;dm*_u`wlYH71>9%Yrx5C}P0N1JnsyCw-*&E6njM`R*@OT!lP zC(b`x8Q(=mG?TVuIk@Ac6kjM>xuuq4vktT8F~Ac zgPP1xUoF|1+{o9ez1>PiUR}U-U)^>$?fFycJnCGDaW>qP6eBLu(M3_KWKLIbq_xyp zqEkw8vL}2O@x(OHzIyqF4q)2`derWEbF%<8r(vyY5wRS}go6BpqEg;1)vx8LP? zCYau71txCKkZ!i0Zr9ZByc8WxZ0C0lf78}(OyJ!!f^?7L(>N|oVj++3d+H7>bpeaM zN26l+KQ1UGG4PlkN=GHk4xyDf9lkB6lII<|Iwz*+JVg?0PeG|M=|aanx0l=8%`gYUD%H2n%F770%oWWjgh<9iq5wT}NWBTeo#uhH=%}jH0;a zABHi{$OkYlaC!M%T@91F&48aFB(%(*Yi?l$_w;puH~L@dyqv{qeX-_t9O#*Y2EeT0 zc7~Sq7nlvJ8~dni$Su5oX7y4fb`{ z_B2oIr}p@P9Wpt2ID@u93h6CKAawuuZ{=mb-BS9@7~=Zy3E=V;nR|=Qz2aQGf)IK~ z{OQgYJ6}Pmu{&*hqN)0UxA2aG_3cIR?RVMiA8D1TxY-r^jP`ne1?$Q4he#j(o8D(t z_y%nfn;*V%2fizBDq+UZZi8fTcKK#?~jrHpcrkV8I67^j$Wfl!Q5AS212 zm_I#2+2rMGd9=StlTbbTQ6D0F)c4eF+T*$v#?N}M6d|#2`glfk+FDCbug8%K2@WX3 zXa5*K?ODL`z~L7OJ zaoTqq_AaYJo+`2+tQU$D474?z$jl6Y7 zRWREYKHn-N=@qQ|A>14c90+ha^Yu4{7XQ~#TRFQ8m49k~M(ZH|qlN#!g#CX#1y_4> zLO#LtMXNPg`)gt?6px(APw)gb>Q9JP3>q(Oa|=A|Ah>{Yu|!luW0A6j3cUUZ&D@n( z{F1T#A~H{OKt|IA$aqfsUd88J_{PsZd-QNyNtDijl@#YO>e_j^deNQny6o_Ko1t0( zhTU&6t?XNWhg_y$&Q%zA2m8v(89fWJHngeE^%wdlnED|t(*lZ z+6y)~LB95$t2?otVcZm+bN*-h&XnL#>2#cRooUaL zWGSz)0GMq6txRU{8J$P8p8Z|1&za}-5EE9Q^~002jcLany-OF#<)8)%K-~`QV8QWb z>b5eMiIFM6%VK9`szvOidV?hrb?OwWk zdgT!YG`lQi7E&y0!6Cb89~UMg^n^tSCbznYgk*cRAJzQTSYi(G6uEascWI*85fU*+ z*J)-3CY9a$+f#i10DD2+P$jRv&rUt;-8o{2+kwJ(DH`Gyrw3q5GO8_(ikomMm!hP9 zBL`!4a)1Nu7bYBB>{(`IoC}YI#RNlE3R;dy&$UF!7cmSBA~oek z^hPwuC1fPDT%`Y(T_r4wb1i8sYP82fQPRnz_Vgq(o-V#KPhCf$J-po9gg3>B#t@Fi zbSGXWn<{_%_Oh?QUcURH?0~2Yj}dBr{le!GjB^|Ejfy+gjnM_GH5)%0%?Q5yYp&m= zCK%#8#*?EFuTt6r9duu=Wr$Mehmj{oT z4zp1D;obxE-$9s0EjKd`{8jIb%gZvkfs(rnNZyKD4)2_)>r{57RHMW6EQMiz=|B}j zYuYXm`=uajP09NxXuZVXb^ZfI>%dqQW*#2&Rf=>Uk-ZA{gqUt~PLYQAx@bjNa(jf8 z6jm3}y9?-@_;yQsI36?6TN*gAi;BI*vkcjsg})OMDQo+#E$ter8sn)JWj33X=}ASO zS!a`{PDt0W4uIjA^H|c4Tl;K(HamvTu zEK|dr_{xY@W=CJ+!Ot7+vmV$|L($g`h!vB37EC8+!o{4W!Q@p`1LCc5D&VoGsjvgZ z=&(-f&wr9-B)Mk%T-9Q#MVTC_ONR3zm@TgFv$%j@* z4urx~#R7$HvOmY?Ze@HMokzW=*yK8-GkLcV=XnTm@6WI>r@T3l=8*|`juzlENIt)i zyF1aw?Rs0@K5(zU`<^s^=R>-!X5Z5gGfp?^f|ub|TU&tvXcMRB2WLDc*2wERqJL+z zO<*Cnw1$22#u(wDd9+0(PwN7fGV zL_V7L@!zRNa)^CkGXMkZHro+@C{f zW04P|_+qQm4@V<^vFHQVq@T2l3}QipRi?)1m4hl#zioidf)Hd^(c4j(q&4tWG5;lx zuV0T_4XmQV-&Ic}_QAw+w!hZ%$8-bfzM#;ja6|$^JPA(wGEJnAYdijmWk2B(oZXf2 z+^*p+oN&XP8DM>OyZ}zjEzvw&V0=}dWRn*{5@(Wh#RC3+0Xd|#UvW9Lvxw?C|W z6~{~hghKYzqS9>6br0kENNw7d%rjE1M58xOKhT1Aj9t#5pJNF4kU0U+SCKx1fBXA; zJpY><@2ReTD_FIUZm=23Z$!$syK-dbmQl^BY>(wLs{;JIEmqGSHLsbfbzCKxQ%^Xf z0?pDFPfEK<@yA5_pgcyEJH(`V-C_XhGqFPU9J8NF+oq7`P>=Lb>i9zqT3c! ztLgd&2}D~&t5s*Qjt=yUcfHy;2#DmjqiqxKE72Yv@U}t!tctThEy}&P12^B-4b0A+ zk3GGAfn-D|zrnws^M_X1I%y#Hky?vgG=Y5e(||u)V58BvUB-$-PwwlSqq}p0}Rye?MO6zS>#!*>se0 zwR#cQ`BF$NF%!%^Bo!%|_wn+)=6K2K=F#ha{{DgLb>Zd?0ex2#*E}8Z?=?|tqU^cm zpA)qDC?dxywO)#om;|Ya1PwZI*MVw$B@{6 ziwt9t$goy2sqqLe7@W51t~=b=|xuVA58m$+&m}8oG?#L~cc= zidWTb&RxNS_S@yxS5Sx(20F%LHbEsv_e@Oa8oS+|nD%dRHXfR-StXlm>SBg~F%(+O z)?kXrbA|a#F|I@9uiunSt)1_mdzLzXyRtRi-Ux~^zP<>?>K7(3q)xsb3y2+>6RdFz zw}!=SIWaZM6WAbQnU<0Pn~5u_4#bsQ0N%fcX~`F_*s;%(?GN;rwjKe!S4BzLQYo^` z2w3eW&nBrNiC6j}=b{^1`;75>h;Hbf%ifd9Mgp!h#@TY&*|DR(G!gh)VKJ+JCIgf~ zE?1Wltd>mc`x?iaH(U4z6Bm@upGKG&EKL*7Si!7|9Hd1@O zH|TU|gWXq>{Uln0`y<71YT0Sw3jNGJ%nc(PFF{QOlXJ)Ca68hDIn8E2LBDs?kzUbD zE;o5)H+()Y8mfFyE|JpkiPANHVh=EO%?&Up=3yPPMG-Zm4ItH8nFQ1W4dEa7QB>?x zlF8m9Oh_?)qOG!tbRDyIxj8@BBK_hw=)WTxv;Ugj5+)j{KPZ%WIL6BNYkUtAHP5kk zOt4CpDGhc{vquO|i+2YAaGSLdxghO+f-s@ElT#x6hbc;b18dzy;p+Q;{<81*wU4+e zPK^}}_CY*+y$)uyEQSJo0_f@b&YrV)QbXsg{sOt8OEe99lEZT-U(Guuf5ZJ=V^lVS zpI&^IN_&o&8}K;vZnBK`b za=aRBnr)yr;Fr>PPA=DW+D>xfyk@@NW@Zq8ar()DUu&o1urQl{N|WgGG27BpDAGm8 zYh9)yQPWMZGY#t1*B49FC7aSw8)Q^E2BoP|C)1;2Ofe?N=0#)Ij+=}%mX2qYM0fzE z#li2DmTM9`BP8O`dX2iGKmt&3)D>vdsk9gCA8o(VqAXL*X~{N!SD@SQU|&>wW1X-X zW5z&An9oNRkKI3iYYfcWY>i5-ZuNYMlBL_Ll*IhbwJy^b_Ozu?wwH!Ieamn9TalAc zXHa$yq-K*?mr;Q=L`h6-W!~-+W2I?g-PZs*KT2adEh5%GH^Qz;)9)m{cjUy_>`)O? z%$rbmqOASU8I9g5I$a+HgF-iMeh>jinmoww=4fv1-6$u2@$9%H#pnv9B4=p+co@%^ zb9#n(Eek#uTZ-Rda@nT~HI;Opj5SgI7NJhWGRCYWxaGi8vr!|dj&6Z}M@*LIWd%;|i)>DW$b4dqo;*XM}zZZ#kRKvk3t~@5+pFo>K5`qTIv!J~k zga_-$fl#b}`x{`J{{FC!hBz^S@*k z|J{gIn8_u!)FEiKgrH_IkW?|U#OWY;J70YFXxhZ`zVmB?!iGghH1j&S*q3JpJgN(jPK$WMMMBAZ4cGg$u(iP8`8x0_go-68)9g|qe2-mzP)`k)C7iK-(&&*OuA zO3+K5B}PM4OH6De^SO(t&#kGTe)}6f&Hf+7N!8YVMK&BI9-ecD*C-9naewyD(96&- zwV^WEmN2o+euWnMXqcAeRW~{z@+bQu+SZ_d0nxcd^|)z-c$*2@);KoOtv8=HZl(@% zBr?7-KD73|5g8~k)ir-#Z)x)J$X;iZ)?GIe99e|*f{Omc`@)se!m2)Lb89a?F2D+=0FsB6&~q*;bsevU{zBXm@#XA ztM$j8Qa{IB*;f4(9U*oWHMMUHzM6wr-Cn1UX)S0FgO4yGYMF10m^zDb6+*kSx zoVlYS#7jIz^c}H#jmoi0I07+=%nxh1gC}Tp=#;8E%96Z$hKe<-7q#b3a|x6Z5bD~U z9|Qv(35S8cCL+U`z}z?PI~!z4w8<TA*2)r8QFlNy~4@_~N^cHQ=&W6HMP~$b;Syf?QLSCJCYbea2jIepnUEH4wvq`oYq+%{GH-Sf{Zr zH|@mcOjDZ$W}C~LYn%D5OxB>q#Pc&T{5(E-+~Asm3wjMA%kJ5K@7Q^@oal7N z_56HHe*mrD3UILIkpxdc7yVhNeaiQhh%0)0w6-=r&bM&K8jsbmn7CM$pI>EGh^2uH zldqNsE;8t^Ju$L%?5i{TC%>~A_#a!tOsV(O(0 z>2Nww&TBh*9mEMdj1CAiN_I^gboPgJL*n*);V4abk7#bpPg~W0GWLH)Q1Pgrf9(BN zg`g3l$|XlKWsY5-gbDYoS znOUzqD)1EAW7zDMXZ@vDYBul)cG=-P3H9jE}Oz-|;0Gp``kT0K=lGbAo-H zuwi_aFnLBg^BzaN6q#~Up>n0nqiZuU*iJ#LB2d5{G=@Sq)aLD7n}i3Mq3}|$=qZ$X z;3qSLI8eOPP;5ONI&+|tqmVHaZ~n7mPhtQ{SlIjXl}^k)f5E@NFI0mBil zFkd?N(}-cYLc&1HMfpE_T|i-3nosesi)YdjdyPpKO$x6$fbto-i0&cLA}_y5k2jzx z8fSd#tu?lPEAL;F$tk$2>|x%OW`;fiJo_bQV(%+T&hAU@GJf+`*u$-8(1mQcsJ|qF zuGel63_5VUbA+56X-8PS8F(n{k#bBwT{s9zGTW;EJz5}3 zx`nyQbtdqPI{hrz#8{CNFg2)x!@btawgk%5J|asGTpn84=)uXvXT*8%9$hFr z6)(eoN9H_|=wa*7kk*(^^b0>lM5mJ3ZYjvovS8E1PYRr6hEb~q<63VU>SG}n zKh*>csePoccrf1E^N>lh5eYUShjmh6O zr}%cMUtQB=W*j@s&YNN)g$_z15?v1(%Tg_WRiNeyLvj9Lf>el)gtQ1~eB=_=&5H)= zc>5=EQ{c>3*pwifH5+f+12n62gFDE}o@iTr0-{BcO*&c#@#T#4mp_??gz7$0hFa)1} z$JMY({1`xe9>QuoNBzi;RwWo`JV)3_6=j=8ULOu~HL=f-N30RueNgek&~sIK*a8oz z1B71ov2wNmt{0I5zr6389h_ki2xZN}X2p{Lx1gDK$c|T#utQqz8$Hj{dnK=!TeGjO zeyJl?cvWV#t{?Dn4TVEWfThq+5 zvd+8B4xXzFl*ny3B?0Z`3k>UzfBZV4tk0)67Gv~gE$hzGJbI^(fhrzYSbCy=UWp$4 z)A2#_LK7fl$BuF+AJj!>75vVT-~o5h^!RHl-@SBVm-7^%Wq?92)_PzW6KOA`D(=3_Eh`(wyR&a_buFziG0!z(=lOSww`itFi!BuugNg=v1#U zp~tjNMqyhT8BC$Z&dm+wqpbLUapvrrh*c!8Dsz-xP&vXABgc|vE{&d0Gok}df`6k_ zBb{xx?}noy|6t{wRv>xa6G|aJ4GrmDF>aa+}WMt)-tKr7)7L)8TXmZlA)!>)M3Tg z(?a&}wltZxVtl+nIkK65G_jR!e62o6g|y&LkE*NDk8W3u^lF{Zo9z+cH>#DSPneQ; zjjD!rC+hc0>DB64pT20&j+JJQ3yg`_H%8a!up0U1#QW^!!^-P{VJm>|ouO*~=EGN- zZBMQ{nC~Gc9_heFPQp**^}lTL#&T0`>->kM1pI$8$@Jf~fZ1|?6Y#(Szbl_tO?dW+ zaaz-1ARL59kRpEZ(Q|DWXm9~Cbns7he|aaT4-Ki{x0iQRD3y&oxI)m2j);ZSD!&t5 zGB9y2dQ?`9t{!Vz3=lEir3hK9MQ)0_m>Laz3%%=Qp*tYe-6;@1%HC6o5G@3)hLWpt z>xh>VGRKP|L!mP|Mt9{y#MBT7#*7VPW;hzAw2x_;!Bo-k#xi zL83s31Eg%+=6jf@k6AIUOoVvVZE(l>GkA{1lhXPqz9gq7N^WEV>w3K_o+VYwX^(um zNpV4m#B$Oh*6ua*vurpk>pOO$l8xO^vi67&mKRiB2y6j@U`Xo8D9cq&$`G=d`qnh| zIW#}H&q7H45(DHVc@D;J8$k z?TB?wh=#dljJLHX#^ELG`v79;k0%T!({X5WZn=Z8|Ke1k9ZZ5D`hvk z{{a{ApF=0CHtjz09*x|>dHjiz$eMrj6jpdZ6N{ z9|>ppJ1Wx$o6zhr4J);yElI1edQ%M1vuG@!>Pf4SCzl%k37uIaeQV6e?!MKqG1gYt z&r45#m6!hVW}h%`9wD}1!BcV$9d9*GH(<%5r%$M;M3DzW7ivOEQw&9#xaaQD{>o@X zDPh=ah^}=mkzu*M7`K75#|-qxT4Y=tv(QmXJoYy&EiNa;)bvDmGm@^8RvCi>F(zGt zQJ*4RDz--Sv1GKlJg)ozt<)H`Jg9U5S$0x?jVUrwkFct@%sI&-1IBh|u2>Xq*IPhV z%&M_Ps>OU^s?1jjy^4C{q&=%^K#~dc8KJ(w`+ZB$oCw9pQFhu;XS(W#&IXgcOg*2t zPOZU%&?{r}$WLR25#f^c93l+JCH+>InUZ=j5*OxF5v~OP8;Z;h1 zb=gnb$hn8SJ7OF9t~4Kf7$r5vp!dg9GC?LZGRRVq1)ua}E60F*9g{QFtOLetZf}qm z_`|_p*0YS@c{PcbLS%ddrC!AO20A>)AeNhCmp+z%9x~K0vRwAAG4WG>E--Xan6jFA#^6`Zo}{&F zew2Y0qQt0;yEZ=p-@2m?Ayt-pU}V!NmJ?yP?zJyIX`mL0NDfHe(14p+Q^#za>NndT zeMkfFlDtt(MpN}O5>=tWT7N|Dq1}CpVo8T5kfx;PB4Xid76kEj;bX;AFz%6mZ1(9{ z7rFLa7{shyTfTwc4r%HYLoUleGru83!MI@}WXZ?VFavF8x)j7LXqEbs|5zo&_5PK@ z7t?J5|09RCY!Q%hgx1$niWgchOCyS@x>7-w^6gAieriC0Rgw~_E0elEkXY@wu1n1{ zq9VDxmof(Y9vOS$)}})ml409FR`b?3cYX}AnyTcJBONEl$NEFe)<6V*y4vDu5v?nS z(ets^a$iK$j}XR9C)$bhdYawNxA#5}dAZXX|Kgz^?jjgn5O-8P6lY2{vlycoY-`@Ggi41Pp6cciEU!Yh zT$WU=j|+)7e1>;5AXW+O09CWj1^3Yn_0)io4fTXR_#4=DA{rSLrPT*6JXg5`eejJ= zw%V#PPw2R{&2jH*w0&C(M+aLep^_m)rq$D`soaELC9_j*w+7&Ued0DYSIn`dwXS$e z^l{|?F%{$`{ET6Ka9O$tN7=nG*i{$Coq&^5zj#3)?*K+`30gmqYTp=9Z=rw>_^MYt z+*jc2SH!N@2-{e`1CnZm-_^vidiKC<_E4DKkrduhdJd>;4pF{FBzK@-5rV-ErT#2j zAqyz{yirQ>xXaOh_*xk(2M}roQ%K_Z^O+XR6Os~p(Jll`vlgl{j!VVJE}GbSL!Aink+%$!Ln~>S*_4f zcVVQGqqgIb<$Tg0)9WDKsrwrf#eUpN35+#Cjc-&&%gG*fAE*JeQdjJo@%#X z*q`14x3T-Zbh|@frb^daTbCNQQeb^rk-vJP)u8>^&>(WCPo0b$czYtFz?f@jWFM@+ z`rw8F^yna~so+0F1?*iMcG=3*(F3!G0(K}dY*d9CBYv8ne&Dx@9H>w`gEYrXD6?Md z!SL}c`^6sBzk^Tze>5ddpsM`Wv2OaiB5HF;AfO9WARwv#t(^3qNeIdfc?I-tu82Z{U>nI8hgArK6>S)tZjlun35zim+~QW8*i;l_KE6o8v%Qc;2EeS7#A>sU zT^JLc)OeO^d)D3JS6s4#8$-I5M~*f`!+YBOa=dl3^|kdff83+%0oTj=*#JIK%N>jg ztx~#Ndmim88>i_>hKZZOZ8XROx8#F}iil)^OXlZQJH<+s4(l-Me?&wr$(C-Meku?(cry zob%;8CwZByf0eA7|7K;@tWm2*YOqqct~wOv6pog{jYh{PY>X<07)6s^Htlg^j=&Of zfV=q5G@*nP=1atm!mn;E&CloWiB0Y*XEl_vV@QBK5mzZ&2o;8at{!2*$M?j~oA4Lb ztC0Honm~@QTQDzetDTQK1qI*s>Pj0b{nTe6$%#*gt~chJVQ^v$9{-46GCRKP@coC zaC*SqXfONmQ3xCS2kI`{&X@((Y5S1LUuZ6AHJr@*N%&ztzy%VT^%hyLrsC4a+p`Cd zRk##q>MQ#k74v_l@pOU@;s*AdVroD};|A&+f0jm_V+O}~QJ7#Rk%Qe$R7Gv6n=L;> ze^vuhA7p90`W6~%;;}dv!53p`@rJn88luT2Z4fuH==Aj~;Ybvorv=%1p!m@32~<|DGISC_+GO!C{iNKn^jWbg{9pd*jbJ_ zdWU?aWc^;I~61MLbmZn1RM`M@_W&fO; z^qysI3@OzC2M>A>55C#=?%HS!Nn~e%X3c4I(SGz0zf;Zket=<3FjKSBZH+=Q(+a1N zIZNxWNIG5&ai!J2+)BNy@5l8Jug%W;xPY9FV$PCLz?o?ipa!1jvQUYHf8JsS5YW}! zDpPvsE-4m%x;dfMr_OVmx7&!kaA~HTCKI;EuX}!* z*Dq0Nav5pn=&#{O(YL`5oJeB9Tz+ab3}8x|P)~I~=&+joYe%QZsDa64Et^pR=e~6D2Zd=|4-?=;p`2xeZ3k zwgBcF!0!o;B9l0!1H0gTCr*+T?4hX$(TXyr6X3SWnsPggSWY!L zXx{>AvD^0ne`PAoii`+%b|~XqEZx_kB{BggUzNaEzCcQu_ZxA3f5eAm_OUd=5?4vA zL`jPqrI9|Y7}o1X*=<-n{u%Q%);8Q(Rz!vag7vjqTel4LB0Z4I>cjQfPprRFTY@JR z+)BAaj9dvG{vf@FR70o)gSA{R4_TI7{Yvx-+))P3f2yO6ZhM?~%cv%-GGe5WF(Es9 z?R}L>JCj1mWiKL1*;fAZbj|>^`Q+YS8s}A!<43jhA4OAwW4rKl32rSL{zwHx78k)C zeUXS)ZtoN-1oeK}$mJ0rrMo6Ui24Z#%D!uOV^@5~PV?KUK1?Xm-M?BsZ}%WZv#HRX zHB^_me-Q&YW}cNKTT~e{ySQJ|(<-*CuPwf1bwX2^+U9o)BJ($;xQq*jh_A1>U(M0t zkeqw7J%PBVIlZq4`XRmVQ2v8EUq$;{GDZGGpZ`tiDN$xkoAw_Y5e5iI;QtiRxc>{p z{Qtb({{d7$y=pU&dE~S)I-8>DsFx!8EhgJV15+ro1^_&NX;g%~$tX&E?sv$$cz&UV zf2fEgiZ2`@d}+!{h3o2HN1w&pd)K|Un7uX<1IKCK`a%A^Bg6_3P5mA+I6F=&9jBqV z!w_P+J*OR)OB6vF+JXDG5-n7x=ZF}i zD5fCmn42~@R@$w`3a3`5zH$`@T?4$Df3)YEvZSINA2@px)j@XrRmVW1cNU}&V1-w3 zJ5@Pv_r>^)M)-cD3A9E4_HIhd2A0X(c$Gzms{cCwpoqlLr*ELn(#k!}>6xausQ4O_ zwW~~2v+qgfCNIxOywO~kjuQ=<)BEOF{Zk0NuXb5h474mu5p*-X?n$~c(WYdw7GsBZ|ExZ=gdfVHMyqwEHAS0p4(iECFVHVe;+arlRtvZY)Ec@{NB zqqyaV;%F8d+={HuAm8AUxY%Fi1Kne%g7FmUi$63T3CF`$g)O9;a`HQHqCXKP4wX}S zDls~V#JyHta5ufg+nIv+>qfbbe-cLX6ZIL#4D=KzaT{o$$#(W~@ z7si}US*wqU7?M_5=p*01rEaq31Yp*|E|&Ad0l84>AQt<()Wyok)W^iXcLV&7x(f8oL#Fh}Js zhO5rGeWV<^oIMmu=cEtHbu@tHF#-`69Zt*5N(%{4R^VGS2Uc7WcQRp|{(#~@gIR)O zO@ASz$dGykc`!HzsW#@$$l)2CY8>_a`XLRQ^N$#KB#8k7PQ(%s)Dr@IjZ=rnWTG?D z>b5PU!S)J01f7Fvmn9Cof8Uz?3dz6IX!DASrG62fa6AQLSRWC;3lovX+j_Ot&9fwT zM6GpbMCBA|tJHGbUIOZOCrZ3F_Pee_<9-YNNbb zr*E;s9FJZUc5S$x>yODb6ko3jLkTqHA1MMea;Ehd8)BlFc?l>EoG*Fc!_}ZdBFDeSq{k!4o zWo0oHoUHfEUQ!ceV4}`5h89TK=0K+Q$!UL{nA?nWxqRgm>qoF>sgTwnR zN}S+TM?d-e^70L|W~4++Y7^b*Y~gj&gj)r@DT9^esQ-F?e?_GY4*h8**3p+rhVC@b zpjNmq&u{0mRGk)}DC;ZIvtBzJ^nRGLJ=X8WTv>WV5iJd36ap3@2|jVCC_cmV1N!f~ z`?a2n=nnw|WDO4l#PPq}ojKrtREC!S>`nyWWeIQ+b#-$4Pi1@cEfw5Ve0~jWw_&UJ z*E&3I<|4E~Q}563}jQ~Hc) z2_v~Byexk{qwj>b{s-nG<7tuItX@!_9YK{B+j_V6%l5-Z_5<(B_SgHJfg5mE|0s_L zl(ixpn=raXw|Px^d%_vr(YAJ%IeG=idEM38vNOn@f2vmvHZq&_9K4tjR2D`j67O|*mtCmbwCb@7u80#hGI+ef2atMD2^BNfbhe3OND#Sl z9|8O*e}20>6$H3cTgkylkh9VmNl8rogo*4tS+J?n6H|@WfSZG&-^vcO7a)ICJAflt zijx9d;*^Jd4M3i8PDN9sKENBr;FDG9m1p`ay9NTx>Zu%PmWA-3k@_nk(!bQ&UOPaUq`|CSl zu{mIfk`1G6Bj{qd#A0!^?(o-|02L~q!ZuG#TVi33v17GjqqddpB?L^ikuWV;tgEEl zWXh~OJ;4OCj8NF=rMI;(`5mlp2K9{{vgXyFo4f{)aZ%rPF0l&B5n%bH1Usel6rQ*Z zekr6QjdDB<7ihT?3q*Zt-NxeIJRARj^E(r)tEXpC?z z`&*%<_XJA1T`;U1eW_qsQX17M9)X#*nnI4 zaS=wiD$>P~%Q@27e8{jZ-PHn28u6-DT~}jQP}u}*Lo}QWN!LM&We0bb&_&v&yqXgF zojYK(Db>8g{w!~ZEW^;Mm=#M@24l;j+4kf>b8Kanm(~M1lwN)z!`O{K6?Oc8e@e33 ztW#+3jqztHotfYDK;+;_PT0-&bo$LZPljUWSb8j9w-=*K`5pZj)>L0PN5El9H;ZcL zx@vU)ah*?5v*15WRZ%9m*4Dra1}+S^PlKE^&V$)@G>>wfG=O)8BofDh1-%D+G&! z^nw*Op@O&p0n%)P1*1;~+KM7CYi26Nmbk4E2&jbUt_F^&=PU>zt&6g;eI_4)d)ST- zA7$~E&`~gg49D-f#aFxvRX#5(T>{QLn@GAgDuc*4z~U~HBKf|9P8-UPf66$=zB}B? zq!Y;BR6fkkS+ge)q71^g-nk5aAZ8$ZwO5Mx%8Z?3CyX3!x$8cA%`1Q_gI4Q#hqIL; z&)+t{R^?E=d+Yr{CR9y~@ENT6OFXzi2V20>F~#Oo{bfBw?8anZZtt8MRHL_ zR8`wu4*8pLYGBg-7ye__e9$Ftn9UOBY!>1+;cf3aP#wsx|sq*?oC`kp1PBP#z}se>EJ|N|_2kQ|Xf( zBg^X0`@ORggVqRY)8&idxCrCiQXbAzn6pJm?uyn1QGRrKziX?B9RjD1|{QiGfdX7_@4>? zJ*6c~7kT@De*yum{gc+1|4&nzsHKyM4d6e=SjZ{hYM}8WvJ!kUV;ReavJnkt41V)gD5A{z$h13@I{4$M??NS2&0O$!6~0e5GQT!WLO6*$puENyDkgPiGK^F zegY?Cahh~CCxO%P+;_R(@V?}D@A$gs{CGWV5CUP;f8mV+k3kOR8;hx-J*52rpt37|KS!Qv&O1aU}U*y2s z*r@+1v2KlG>`tL)I$irV>r;-W884zvfrIV#xX*Z~Ef1`SJylSQfVy@0VS+&EQS+m3&8Tj3@ zfs)3prEU}@9)Lyro!oxZa`rL()AXT&9wAq+f0luXlr%)JGwKA0p`F*8wS9G_JD`T@ zwB!Flks-$otMX1@zvsewkq*#>0YHRnyA8Hxf~<$wYd5nyx2l}JhOF9YKhtZ_gxAG2 zHe9VqrM>}=n*)jXiQtu%VP}DxlmEc%rvl|1W5HvPwhb_2;}AvSonYNl1v5h8Lt0U4q2F5u5j!*WHY#m{`PEPh2^ z_AV=_^x7YOQ5#yl^=yO+>KBeV2S$R#-#C}KZbm~B7H6?QU>b%yf zRArspjg7zXQU@fWaM^aHzWL^0^Am%vf6(cID|F6 zCJOi;;OQUm#W((cm3VMYKODD3P}l#lyaUpz56$ujDOelTo#Xk5f4hnM z6rUoJTcMs(mX7Bfn8`F6DkOOC2qkb=8kxHd7sIX(WHH0k>o-1~Tw4s#li(mVnVpm< zRV^R`u?$!MN*U(YE!G3OFow@nR(3F;+ruG8cQx8&m1gEcPNY(i-fhPkc9q6?acfWP zXN_`aSu4FFNndR1|DC9~-4OJ-e}N6-AHTb|vpO)qY^Q?q%J({yvi;v!|2|O-nqL2e zvM$vBjsp5$LRrzs#o}M`&PJAY04K74v;M8MUah8Qk1LMGZ^FB6+WF>$&)F1&l7X}l zP=hO-&s8LM$$`}l9*?qqE3|S!oW6f4!FmDn$KybdNNqoz(*jnmSmKXlf6;g3H}X)n zk##2<3jKYcxtrMy|H)=-x8LLH;0|!saH!}nB1_^ULmwkWTq81{qiZMh zU_Yw%&f!6P0;&Gwk9tg7jRB&2vA&}zmD1!E3-)$XER+DoHv~iy2=!&QK!gxO)}pVL zu3_{+v9A*MN#~7ti}p!nf3KaT;D`whJUAUJN2Uno5N4Cb`# z?sK;=M|R2o3dql?eJTHSG|&<4*=4jR2U)tu66GdZ-b5t@*G{1!a&Jb7X&sN*oD6Lq zSkXn%0@4wOW_VTS#2}EnhTcQjR&_c;#h6TOo?IstSLmAH-Q2ynd!NC8Dq2GDu5Z1S zD3W_HsoF%JgfUk;f5gNUA=zvPx%#jyLO35v9r>-H(Y3|(TiA*mm2c2}R%?4Z>Pcn& z_fKq0FlMUo41DyU1H+F$8S?L|HvtW+5>*;zo9FsPM0|F*@LCzY1=ftF++2-hn$FYK zeM>-XuLI3CWnf0XGXAGm0^Jakq*;k1LH zjdCn^N8>5}w4yfVsY@^)*41bPqC=6#?>k&Xhev@bV~oEahVJlVI!$JA1y88jt7Bg{ zPOnMd)Ivog`1S{QS8zAGTUcI+Hi=ESZK0dCQM1vXx1=$6yIjm&pOTI-bCK>*#_)p1 zvbCg<@XBxPe*rVd?Cqm-?^2Qj4%;5}bo@P`PE#vHCbj~AHHnj-%e{B_l}~{Z0q>9- zSQzU>hi-zNa)cc;j61(nM$uTAHlzo=SX55iR|>XKff8>LzP?L%>2uxGMUL03^IL$z zd5K9+8oHxn|0YD%q_2RV2NJ&J^%P2!6L~`(D!^*{&_zBc- zA#gLYe^m<~-M$wxsj2z|@B8Q4zH=>k-Bs)6KTKp%HnP=H&@+Y2ZnDn(WkUABEKQciS10dA8L{s6<;O6gW*RP%6*;MsYslql!A z9jzZ_cy4sr^a4T>C`8I614AV6b>_+Hii6?D(vd=vp~|6EGf*JSney zwb6q$`d#;GPnCHpYIrf%CQ=HbGUc*lexBzFbeRRZnnKtQ^|X2g7SiVMDXb)p+_`jc z1sGM$_9l~=`+_DxDkH)JRK*ib^+}_pez}pJTVhXa9kzUUMLTZJP95#Syt@2t1hOh zo5GXq6pdyfr<80(U>WL3Pl9ncPIw#8dssfocaHd!4hcZN5>;R@Z}>x0aP;Sxe`7Gg zD>Pi9=7N*bo3W~e*wSqjq|wdE7Ae4JR%kI2)!0ST6t}Vs*gt&(PsBOLsUWP@IML&;G0o>PKu*^gOkpM##0#+j;C|9f8)yJgb7L2FA`Rc3A{?b*y4o@{T5Kg1nYI zrDTrj9MrtFrlatq2@m@PJDDvWtzSRDAo;7a$(QWoa-B%d!mhwAanZaQc@gz8xrEHe z5v|px6bMHw&MoAViumTB){*vUkqt3bRW@OfxK^NGWku>XYNoayK0i&Ce|0mb!y`A%H;MlQP&IbyYGjuAbZRT5G%61e5jwgBGMj7Of&C05_< zK*DYg&kj&iPU<0egwOOb7pC5O8e=5|$8?WEa*1>~S*gyHK$$n(GXg;dXS`UQ@W>Z! zptitj^=k@c_w>e-gkh?Te+8bv^j4P0ofvZ%5A=DW5pE25A1Muf0XLHQcY5N!%X7#Q zuvQkm7>+jmz|ZKRozdVr4tu~>Nu%N<$PG)F$iDLM0)D9AkqX5;eiE^L>`TtKQ9#Vm zms&%+(I5UP1JwOeiUQyj@fzSiVj1&dCpLwo8S{ZxlZF|Vm#(_Xe|0G0nyGK91vbz} zI4J)0X0THx1!31r=&*jcMV11#-?IIFY0vfyyrgA8+DZ7`4tZsIyU_rEqpK^CkT|_H z;*GW|SDnwRT$dUb9RqU5b;k^bPuQM*Gd*mq(%$nCH@(+o`phk^} zdlitj-TUlT{{u@3e|eC?3mAzXgB#<1@vq`+BQDE)yN*n2wJ9!;UvHD*y z)$zMl;No{AVIMDceVCD8ST(aH>Wvn z|Jy%D5a+CofA4>+YT*A%R3~9?V`K0B52zEh0GL=y{7ZM)0$?iPYWH7+K$GJHWk7|I zhIh!k%x7L}>*^Zn=SIZq;#Ct4$dDA#=q{gEm|Gp~IWO%VJGEYcKNa`&k(=tq`=&DY znQumYeEoeu+J^LF2=*k})q~9T^sWljh3UA&O0&$Fe@#}M9y0>l66?#en6IxI{HCpoF3nphomX0^mc@&_lR+jz2T@HuHF?=PwGy&Pm}+ZIBg zA^q`B^l0`@{VWUZ-jpEqaC=%-#Q)}l58OSb+KAIl4@o>TD&K`MWob_O*_cA%Ib9+# ztVodKe|>*sMhTr3(n=ewi>0&(+_QPF4G>wT;E69>ErIj=Aa(xz@49=MdG$c=|5%Iv zI9m4q$?AH{cnC&GqxKRN-mc`T{j2Rq>d!$Tm(mpxqPNAJT|bo4wrHa za5iF9csDE<$~8v?E#P#*zC1$FU$~RW@ZbtUiI^Q(QcQ^|YjQTi9kZkUr|;}>w0}Ll ze*qP9yq79_6_Ii#zPFhM42Jv}tcIh7%;9qt78W=_z$xr;$`-BsqENOu6dw)+BV37m zQ%;NcA#{xq;=j!bc#)`EF@^vFTEh6>(XReyKK`%9zZEFm|H=I=ndUfq7N#y%?pH=$ zKZ;LDNfpmK6b8)~*QObUwBfXFV4EH>f1MN^e!*3`i)8hCWafz&G#PU#VjY0|A|iYY z^qWJRc}*=l*$yFV+URJ)UQf^3^1gn{-r;`PY<$`NJ{ds->bQ%C1UN`hr78h)iYl^> z`lfr(*v4d} zL?K*2tFTrzikgWiR7%O28viqwlsk^kaUwRiv*6VU zqYM$I)I-EF(Jk(GaA2?`NKn*B!p;o9IvlqKqHM2>TZr<~>qH!XOcxd7NcF62&2%4D zgY9}@e^_<$Btx=tHA+>ptyFhFSN zeAGem-j)RsVDr8iyKX;ZFtI`W$=@c8&p-I?$@}TMQ*0CDTf>BNIMicti}dPbB}aOM zB<&yU7TpW*gYJg2mFEn^fArox5uV3zY6S-gcs6>u?j`;vdt`3HAc0q*Ft#e-#LvW9 zO;o>)Dk=3SRy7tBRdF0{v9MyX)TS@=k_pB9K-wcfP@ZoQhj9o*b7fgs6wnO@#!I+u ziyFi-U29w$E^wMYO~JyGJ@ZP+?~2~PS3Zt$AQ^=F*ubchv*{qHe>ZPqCrlfBrx~Wu z9LqtYm5091R61X7M#j0!#Ufl@6g{{2BXLezQbG~3+|8?ru6d|58>mz<~0^eNW&av)2`4%=Y+jW((2D`S}ne zok8AA7~eeJ^t;p<9m~x*1lEeB*w|vD3I?pz;ZO0$CM3+5e~wI~Pu1_PXwun@Qt9L+ z?5`RjBX7z1kga}$3YgB;*XoBF&U){zz+*A(MNtSrS~}{IrtsYFQ&1#%3p-_`;f3XDT)D-Mz+f|6HoS53mGoBPtQql(5fE9{fqdt108E!~j6f4Q3519dc zF*1|jwWuaW=vHV}>-ZzpQDOo0(&f_yT8@Bv-SmN+_>7DUsmtkty_!~@V&HzdisX`e zx-RKNURWv1im5-;tMj@KyXJGA<%NF*UHM^Rcv818R7K>{)%TSYsrCQeKenr^X_8yHb4QHPk6% zw5SSvjez~|lNItDkCcgF)Y(KGzB^g9eM>JpkdM?na%cbw1Q{RcUeM$)J+?%?oOyhW z4gf@Be;?aMttJex8{j#73lEZoa)?t}dNeL&?1=p(nZFTGodNEa*k?BlJVF~3$RDXm zFh#zfl;rB8W%lRmm!aT4>yu%D!&m(o<^f-_hOH++I_aRS4hsxZAzFsLNNcsuzwiE> z7@9mAx;FOtk=E^;09DQgkl!0YI2lc-HfFB)f5!S@nh}2s-_MeWamP}b@L^h`m?6|h z-gWSJ3Gn9&Ekh$yN1Qd ze^vNZQSF$`da!C^Qsaj4aM3cNZ$4tbh9ff*wbR6Ih7cw7lk)0|dlRQC>|Ghv19!79 z;u(ARVTZ^N_c?d4*Aa;k!30s1v-@58e+9r#`dz$SB@EKCH@D=dd6zA(#wY=Z)`s|gz`73?PTh?rGkA0|5|SQFx#2xdJweVzCD!*B?NM4(7YDGXkh0e z%Nj$b+Rl$X%ZVc(xVOREGL!mkiyQRvg>3)J#qn)Hd!{?5hLQ?bxwja|4)| z6!xJn>#>rwlpnJnf>rINF_&$SjoOD4V%W0NZ5)`mSx3w#g^HkAQl(G{m-pRU;!-H0 zrO~P69X)Lfdr~E)MRT9+(x2?=e?37!GFqK|BLni0*{hWPM94*cpz5Lvw2FZr!&r!z~8X)C#E2%5EqkEK4sLr3=->qbPI2BWG1We?TMRES77J zmv>yt{Zf;bzo^?Iv@}gnkB&Z1fgAAZ%WPAJLsf_mDlzs5S=gz<`+zJiJD4^k ze~H578)5}HOm3mT1l~0o5J{0ctI?Run8uHC;{0*a1h)~^;XwRs(e^9vUGw2$K)*|L zkR0XXRz4uZqzA98f46Bi@(cr>gRm0Tr&RU?X43PPyX?nlg_3G*bCSHKFZr9OHA zG*<^y385*}c3zU*^r+lxTu3IlU4JO}O7C_|(ta6+vOp!ae>&*pay1GeAXR!iVbGso^rl4#*Q+H$EekFj$H@JeYiq2&t9!fk%XGnwHHQW|?asNi4Z7dA-sNJ^YV-kypYB_qf+v@sfKe9jm;Xgy-HOPqU7~$z(I@ zKe2}AR;s<{P4@^6BEA|>?D6(x894iX$cfwvQKNV7Fhlvx@=rx^1pCLm7Fxmh+Fng( zcD%Q~f30h8bgX-2e(-WWCyDIN>biZCIE*-+`95)c)uQ+xaQMyy?XSeNtgyB;yFa@; zyEeUFoc?l zkbUAzSTrBQ7BQTAmOJNk9!+Qkn}&Bf8*9s#f2KHQ@$l)yyBpHw&ps?MXm!yWA^}zt zhgs?gcT(U4a23A8T8xh*x@nrJUQywyv`X~;W%WFATU;;K0k)$rgR{{%W0D{(Dqxg; zF=-``GApMliba5Ul+HW^|4N>evNSs_pN}ljk)ZJ^H|S0mgor^A^YzjSiuo2==y}}O zf8a-+E-aOPD=_p-mrdolHK(W=*E>NZ|G_vpXEjOLu|RCVB~Q1s+r1Z|wql;9>Lfhl zC>S*BW0*j8)-%rG5=NzzW;UQh(#)z6>%UFoHumU9!fg`WscG~D3;Ud(GKf`k$8V<2 z&l5$26baG$E3W5Bw~$m{6^lYhVCB^ufBn@-I&vpRq1yAjol$76^Q2hDh{c`}amOSM zVAjhs4o7>e#Oe%lL}9Hc8ar{*a|?kkttQ?ofe4E^PV(=``l7-2`l~9gg8Bp^6H6VD zaSJu&e^nfGKV(c-kdY?t+Jl9z8*i!F51wE_{qv+e4>P6af{a0{9SVr3k*%>-fBuku z(~@P2G$=ji?EXUA$|yRicvJS%p~jI`mQlh~^QHWj-}%|~hWtBGqt^^cWOacc5?T2B ztcq(QeJ0W*px{6gMG_wI;y`o8MGa5C#6G+*-BJfHTekCnEAp&_i-Xly2k(Sw`2dOu zKf(lZah{9hBbjn`(H(Xe!ZaV$e>ToS61)3WK?t&94jPfe5Z==prz3nrRN*H2QJWuj zV=j{Teur$<-5B*-3gwvWv%mM&{wZrM_-7aVUfsbz`>`W^JMxc(=T-M1j4$|UW1v91 zXq|JpUN#erB>hGe*yK=3kzoL)%08bo-!2(+wxpc^uSp|o^P3O*WG3gle^pMVM&|Tg zCnoGjedd_fLEG;!GmNbYRP1il^sy4q~f%$&jb?lifE%TsYKdh|a4W!~}e^%BDqpx!j?A6-0 zWluDGO;TO&=vGqaaB56@>s{+6d~PAPR+^m%^Re&0NDq5PaP#ezk}qUVqHML>VNSjy zkCWUqsttKjz2&i1_m|9LVW9L})Z<#$hsuwGdti1a)btI5Ep)e`rtUK6MsP6MkZU*d2^F>yke+B6llJsU*48nso=ujo&jB=+32773mmOri>IL6Br(k(p1IVgHH zN^N8hNRd*G+oN(@-F$JWSqx2*>sgC2MC%qgmX8(2qcMOVU1~8Ve#uLhhjc&sbL3Z5 ztPMBwL#KQ|@!5}?) zVAo8-X_22-aAiruK@mCcr1is!j;dT(H1ZU&9_+1+(!%1E(jw#vjycBiAT$}gu?{|L z(%o;=04XYOf7rINwudcnFh7{M)>DDYt$nwSX3*E+^@Io%_jxWqHKhcBj7p_Eh8mQ2 z4RL)oq)l}r4)lF)RqV;~zUg64RrhD5_8x)--09wymweM(=0On5~9L*gx){01eUiI9SI6ve-%S?IOuULPD&DmBnxNCdGx|H zY1uT@Pc(8u<3^ttZIH7BBe`h;tp>}xC(E{Dt>VagO$2|95qRk*f_WWd!(jI5(IQU= z3#IFm1eV!a)2612C5l4eB2lWR$4Rp=BRaD9>Sfu&BviXV{vFVZDUj;ULjnPLp#lLh z{vQK+e|zWuiI>X;s<$9a~!i#zUz<3`B<^W2OKLBT8F?fNN{9R9UIK z@``VwElTc}T5OUlWt|phShr+NjMRTD=(aFlkc}|PNdNx*T_&IVayfrDfg$BO4}0cw z+BN&&$9Ka2-23w|>yJFI^{$riPK8ohCeM7ne@gW=x5g5oHrO1=$w{DHQmga>KI-}z zi6idxmJBRCCzO@IgHNPa*mbrXF+J@yxN++*eJar?CK zfAlTqESgS_3O$3d7h+mDf1cJz z>mG-==KhpYcFbKm)lAj>$RrQGy?xc)KNVaN>KK%R%p3al#CcL7-|x(ifI@Chi;OFI zY5zJ_(P6Icl10mRfv)Xou2B$wSp}Tbf7es3?3ugvUyF{OUm^1L_dM%9OScCu`i1p+ zLA<}(tPL!=mm8LUEzpUhJYs~kgK+EjRxgrwL?K0aZ8=TiWKYmvvgc0TY$Sv^!`&f> zCb4-z6ZG5~{;9ECa(AK;UR65b+t`{r}+Vk$$ie_p5f^x13C(pK9pa*Mre{nvm zkXVHMX`BgqYmj#jdV60!%ItDfC`GS#w72|b2yyRXd1P+dZCg>UY%yZL#=)&hiwB=& ztDuz_+-u&9de20-7@{II$UXGBEeu8mSxky^&8x^ zCa@-PvZ;OoQ9GZ$@;he2Nn_*Nf4S|)xU+WkP;txfi(TplgKK_XR(Qa4TGsFzFxcoe zs~-9mw8DmO>t0U;C~z;#+hV}u(zg!d$YD*RHyPFTYcz8f1r^H9AFQxTZ{5K+Hdrhb z*L~0j4Q4<5Qwu-oC&C3bSsgUw4=61<`NBFDovR0aq?oh>#T1liND`wqf2%LMpR36> z(??UJ>eSpURe8EkTJk_WHC!}oi?I)ZtG*_s}Z-6(_7<3)t z*DfsEM?-If|rbl0CkCy{0YL(XlaVzyq{qT+ac=D8&cZnDN!`+F?B$;(iHY^R{Ru> zU|B*fl-M`D`YYscuPWG=v9mG|#0WEV+1HtER@mc+JRJfA>hO3;ReSLv*cS z>Yyw}L*VS0p`=rS2&fhr1*IZFxT`Wb8TA6f-kk4y{?G^1#NHn{Ot;fpHi2WGn1GYs z{2`p@7{i;e@NqN>6|-yX?t6D}F5prlnB7FhemE=TqQXZUHYU`HF}AN?JWO&oCJ@-7 zb(b(FdjemY9Sz}ge`|ZXM)2h6BcrD1hVcU=fCikP)L)tHqB|S#K4L+)JjJK*ua6YU zOt{iQ^5jI4h+scJ*fhX$>Az90z}E2dH?HQcX68VN^@XS~iECPk`(++!jysKV760`p zRMbV=LvJ92+J+9cbO!mt8}&xk)skMm-9UK<%8q;C8%17_fBXTrY#Gp=QO{8_;+zml zge6{z>Vv7#&?=JxwbIFME#{Gg1tx<;=_85I8-*Os*ZDPO+ea6=JLp?TH*7^+>W>I( zr*P87!`a5t$owq$ktKgb`zpXnP`Snzu}od1*%8`kCV3SD6X$*F3Qli~zMwa_%_HVR z_!CeSvcATRe}2X7>24hN0z5B^usaoJW0Eq_Xa9S8BF%)63wi)~MtHbODbBgxQ^IDw zVm^QOtm<#^2ER}Y+-5esVx|j$=U?={Sre;SE=-`X$#;$)seZ84G;4P3#lK7t&5kLK~Z;*x;Qr{?tGs-y@lX|KFdPr)gB=72F$O^x(Erc#p z!y*fAJ!oKHYO39U|BBykI9!4L_Qm>>qsre?Ll8E(5M2Ki<7P(1_1uWGnfAv!C=1fz z23q5S0^ynU-<6SfC}dgw}pf_%^=h;giJQ_mHk3S zZ~vo9JeIrwRIKMIxP=DTtEyUN3bDoe9(G&+{wd~%f7cI2`iCAAfAO3auW;{{I!RU{2^^8Z zEo48T;j?EMmF*ZX)Vzw2u;JkSRi@Vz`58$9qlnPpxwcQ)&+N6?O(>>6I0&!JT#5L)Y9UU=h{Oy&!pj!b_GDDa@Lb9OC~5)*q= zD>#~#XHd4#Oa4whk9=jVeb@#88GlrJ#xWZjGW2<^K~mm{Per_LjB_^Uu$BIq`19Y; zL4S{gqB95((8)h*Z2wDiU}5BB>TdMUf5*QVH%|68s-6!20TGf_ZWI<3(fIAJR;n>L zM-c&kND6H7qM%=`gP06)5@{%c(}xxG$`u!yi!PYHHCRxHao}^m3Zq{5D`d@OR}gQW zH@&ahOF3(I{C&P543QPkhp>+6dbMn>@WK2B5%DY4`08}>?cW0QHdzC+Unsh(e?IiF zUawa|L3zO;v_$csA<7Fb;2ymEVE_#AOK~VD_7&E61`BzPbQ&$K9G?3PA#4g%v$Twr zwY0c=?&6{tfk~MaYL8bH{fb^2HxB57SV~M~do(r7L-eaJHX->w!aJOZ(*@REox{^3 zJ+{F^(|a9%nBfoFgi{!x)M~fLe+WZMHd;7$nCXr>J681?mucL|qnI4JwwzwT7>FJz z*)|8rM2-L6WjO>Jk?m}}6)4J()GWYIB>W=JCyzfa%QJ##^dTOQiZmiNIQ1rH`_$;{ zy1tp?Sm-$TTf06Tf^U-!pUQ&!n+TZdh$*y?)eC!puU&9B6@%pHOKn?74|K_gIYj=?2k7b z)*F^KR-wh=95K(zG!y&PpIfTJYk!^}1X&>O9xh*_ND?BZl%9^y+dp0S(?qMeyJAUo zLI+Uwt0Wv56+W*TTc5(rD$XeQ2158DgRRB(I_Wv>8N?FeuRTzzbu}BLw zacM;LLUQ?!A?h$X8Zu3A0tu8QRk$kED^oiDblO%r7jLHePxwzh0KjCgH%8iZ4 zdElQm*q4LL9PjIHRzW|%4}XMRXbxIU5n`eG2tX1Rfus{oPxEo&Qh3Cu(NOXi77T-g zbT6(WF1|DE;0)c(BjkcSyy#i`!o(F5-`Y7$Vh|ww-i0RCIR zxmwjOiYR~bbswJ0Mye$SZ^-_N{som#;NIEJ@{G?^1{IV|+xqR<3g`Zj?nV>O_@r7Kq0POULb)K- zS=sEkNnKc88_lp9&wozC1N{bq=q>Tmz*WLBiQ3DreL)~YN+qP}nHY&Ewitm^e+jdfM z@>X~MXQt;_@0y;TZ}&NC{XX1h^V(jY#q;oajiwB8g1`G1Z7;uu$V{%rujUZ(6~ zevkQB>XC-N=nzkGj7TMRez?h@N{}Qn^y_3fqjB2;u=cN5GJCZQBq_OP~_X0MjoMQSMqsz#Bb#M zfgZY)N>V+yz`m3RS!dd+!o+K)$GOcXzB{iu1OmVOAQ=;U$Xtm|2ycpTz{A57FJBqb zd?}K}QE%Re5`OCl><-AM+Wz%ueS6X`lXiY&p2V%Hh=0#mFwe!L3y7HJ)lY)#A1ieD zi(9v8o5|dXsK2AGL+O^;V@`$Ug~r7gbi=(+a;{nJR8dR(RZ6tK@cL-e(BGdZ*U$>V zjValudM9v#jT*k9Z=3{<$J>6@p_O)OiemX8yy?LiCMth0B#Y8uIrP{eo7z|ETXg6N z=xi2M+JCK%MDDo;|4AU8IS3Akp&xaOVpNDA)gfF+y??e#yK2IEv#tG$hl}~@#K!vb zbBN-*GyBoPov9yHUd1celG==?6YJ}Kj}=26kTOgr!kiahM=hzF$W*}hp>5QS2Lf_* z#l&Z0y?Rkf;hw+hZv)DjBu$_bFihXzYz7?tYJbyCD~RwZe3Y=2m=!vU&a4a5lSQrT zNU{{o58U!YrN#I9W_jEL)X1xAImt02yyv&0lg`ImE9{a1e;g9_tglL7MWP6s3Yj-+ z^W7lfBs>;lLylVp9qsiV44vFN~xy)MWb*PaNh(nmXi=LaykYpF8x=+(Q z=6@w*EXlmhTrv8mTqyjKTi7mu;k*|m4DsJV06fE;447}GCUw~XV~bpZN@l5&IQ>X< zNoFm0Q5PM+nrGx?P`%PkB4owlAR!S}-0*85u{FDLD6>pL-rqGT1P(o~R{dRd1bH<@X}aQy_s zkgo znp#h3wc%<;#XhtN!T$OOTM>|rzi{kdLraGGe=@ZH?6uSMbpB(oe~uPfCa6VBM<~Wv zN_e9*y)R38M39ZmFtiQhYN>$-UWJ{fqgiU+Vc%m{xVK>$mZ1Jqkw1S;kC3iXaWKV; zi|fQg|9I+l_E*3cxFLQ5%ow4KQGfp^)gfk`SJ4G8?2-bprA)x&T?br%tM0Y^#Lw1o zksENtFcq0U7sQv;;hTC`W0paM%GMoKS08hG{L^+6syNinXjqpzqvT8X2fPqT?TQUd zU^zxJt7p?!tHNFDYv|m{ja1{hg>0QJ>Z&D!*)SxHLyQaTJiVvlO_L;hOn(g&Y2vJSf!m=a^Ndb zeT0|NFTqZ4ObuNuHDBw#j(_YSL==LNaOckN%!q|cm47|K7OF}=dv^H+ z618v@ZmaYx6MgRRvsQVe@wN&`y-G6h`9mUy7|GBWp`XO|buePAYd=R3(jMJ$`xrdb z)f(3C{08Cd%U7c7Hj&-Ny@$7I(faa^*-Yv6XFKy62q*^_g*G{V1c6vRK{#JvdQ=Di zqu&=SV+pv2t7pA3Qmpu(L^U5emxXh@ z|MW4S_m#f~1ozX`EXMfyig2&+smRWgBnG`|8XgmXUfIvt2bq)1s+k)Ee@a)w*)M2D zmX=GofVEq)==H=`kEb+g?rEh z7}9pjEZAO_L;_>aB3;tjIx|TN;d9bl^Ux?~K1aTr*^b+4)9+XRo(Dx9IZxYR`r;tB zd~^JR#y_(^ZA;D=KHkn*VFXPcXSS)(skUImn(*Xku%`_1>(a!faZok31?32J{Fbdx zO6d75m^w@3PJgcmWa=?&DIrjg4=#sn^{B4_^5su}N>BR0H4fFx6R_D_Bmk{u6m4qG z18IjSfqeNE>GhwCWG>f^`k8-Mtw8@(`SE|+xQdy*%m0X=ba6}w!Hk$;I|-6#=n23v zdb}V^PR@p|)U83tB_*}lo~)3FyM?iKk8%tK`hCw|ynhBj?v$9w!erB7-TrN5Z2B?) zi=&>TQR;12pS~DHY&I?vEagFSB#r?ICby4O1Zi)Oi`4osjL?=EdA7or5OD!iBPDf6 z;qA=oH0ydmV03{ajvf|~Em8{DH!{{f;t(~`Ah+}3Kl=ZEeO70e{dHuykU&5z|HnW1 zchAJk#ec=h-hx5I%-PJ?+0E`>9!yQo14RtepIolXuIckkWlh!6B^}mnJQ@^ zwj^veHk#0^DGPbXxcz3{(a)7HU_mw-`=bgqIm|G3!=}hLg*w%lFqF zgXRFffETEKt`8&$Fi?mha$`(W%wN+tj@9FNU4L%1-a4z%Mvh|K%C*dJB`j&2;f%I~ z_QZuFbQ^YBoA%JNwO!KdeQF2(#pllT=B=SO4_yt*-9Gsn@B>IIqofWK24QV%#>S{7 zaN>Fu%=5wwV$)ov#vl<=L7W*mMP#^x&O~}ssc*MuQQD3x3-n&CRNhd|5b=z(kG1;f zRe$|x2_#YNvORIC7-eNlvL!5~j2c17a@C}MX)?Q%W$;s(o{-IO#Xf6rBFfMSG%F^V zo5gyU^W%d~JvO_1C=`y#zLyw8Q1I6dk=@i&zu{}0CPcBZ!YfdcQ@Yy>Dv86sfQQyV zh1>N`B(&PE9Tm<~wYa67*O?h-8y>NvaesiLq;fdAJ0}O38v_x$!=@hElItEE63vdJ z%JUZ&Eac9mVay{-XnL@qKu?}q%m(1cMZVIkDze1l_p zJ3htV$==#-(`>r)8zRkB=Eu9;^iVj$?AeY!2N|bqTIJdWgU-FLBy{E$kp{?6ynpbv z6P>%^u0ERn^o%;53q1Z&VMYTjV3~RbXJOz~dJ0Bg;<;I-+-*#D1vBfV?vc|2KF>*( zd98n>ULX-y6M188EM2)zHo>$)kzC3lYHCQmo*mxyRZa{IA`c8?z-Jx&UWp7HzV#@- zk^RmPbck;CP8ewTIQD>g3VSP;K!4w%M1zxE&?(tWM{5tzKDla;gs{iwwSg2ahNkHb zvWQ`;yx?on8C>kzIn92F%~lftHGHcpZnrZ$Ag2~)$0ts8{W zh_8f9pPE4AIchti&`qlX2N92KEJ2j z-O>cdQtt_PM zUCo@$jZFSW2}NN*euxpy534xLu0Qkz3MtreHSU0PxMUFF=hhaj4u4Cjl$1{53r!vF z3lKldUbvLxW~8aW`$u(D)2h_X8HF@vPsQ}4k8!~)O3d7 zfh+co;`29KqPc=MGJgepv(dBnwkbEyl1*lpTrV+qp#j&|bX@db2Ot>V>!SgFw|0te zqpr#n0SG;p_A+2#?sI%WewV~XvRpg~a2q(?_(ZU3q8BlRTVHqBYGM#dp*_R7158M4F%Z~*|)>*M_ zK>G|4(!W_rr+=Rg8FHQ{P+TsDA{kImPVf*vaM)@`#Scj#tZZ!E(1j)sOz#;M#7t7b!N%e- zllze8(&sbNd4aL*dyfT_5oIGx8Ke+oAVviOg2rJzq)l2`3PHT($8qkYLpWzz0@tn8 zuhHx8fqxZDse+`;gjm%t=Hx<|j3ujMUSNfDCresuVasB#?Hy|4#FxTUVU=T6W=n^~ z_U;;V-;s6B0nwChj$=+OlA;7KUuI8Esz_?YK}&_r@DBMH%#sdcqBIDciPR zVGd#1Qg^if@s?>f?}`)y_TkJHNd^*~F0EOX1b;vL8VsI7(35)dH_@*!V?U( zs(+|sQhzWNQmqu7NaPV{*VU%D99^N#!tL8BE7ddFo?fsFnr@jfC_9WTb8V31FC#Ns zk~Art^!%vDjk`$DvGJ~?CO4W=GLo#M*jhv}?S(U&Gk8$h9K6cd+R}YeArkofQfkPB zBWiY&m<#BY6!A@?lzwLFKgqcB3ulr8GJp3~Qie*xG6*>D57HZtpc}Cz_`)pPWxLX7 zbgR@2r1inNtxu`brnlaKQt*qr@^pO$ICDDFp?xaNkl^U(VY6oVM(jm$GNUQ!S~v8zrLRevh{ zoo(1=hS*k13CoHgSC|_{Ska)c+f)sc>0)A#+&wRTH$XaQ%vBpR)R~l+N6$?Q(JdZ< zC6Acaf9&T`*8%v8~&N;e;fLX#8=iwoYdj zy&Efr1>r!4^7P8!5Tn&+in-t5c7Gd<(i4>@m+OFgOpK_Pzetf%p^-1px{8;Pr7_!4 zaPf4)kAY!DV3jT3s2O^V+D}+Z=|{k{#qdudrj%vHXPyx$vn-gKw)BB$M(a4zq*Rh2FBaw3dw_jffPbhh=AJQM z*_pGaSqdPnEG{^Kx5L(CCZ99ob+Y&Fq&3qnD&OY&8Zb^tN<1F|h&H1_V79CG{a##x z*jz-%3a9B`G1(x;N=vwqnmaRmXyukm9$@yK;k1vZ7u3pMw%LjgT&>TLwh;?1BM21l zgnT2@0wiN}$USz0gRg`J#DA$CjnD`NB&^g9`0T)nC zNWIA;-^V=GQsL>WHj8LDNfmh_7DH^IIBa^>uD3YHE^Y&(74}s?%xEq1y7(-agEVHE z(CTu=hl0^$ZZg6s_N@soXLp6b3)JqA_yLhKWMi6Gl}0WC#eH7r3x88v9IzRvytIx& zL}tcoFF$R525JoZ+|6CalWgFrZ_St%#pWb4-#gORFpa4Z5W}&s7(N@zK}-@;Kv`Jp$Q~QQM-8?LVX7YsNR~OeTN3n=SSsb zMPSKWQ8fb+w-W4Ltic70khWgg7fi6MxDb281C(xA(7vM!FwQJlnrot`78=s0&bL0B zF5A)G4q+IHDSvKdxV}ED|M2;12W`_)eEoPm*-`s|_;r+-Xf)tr=rMNmox1nM5LIZh zT$9@$Q2j!{WiZB#u{a(Zdbs{w^%7DdFPK5bLIS>{co(3|C^=x~Oq=%hU9m4$DPVXe za?Cj7EPT64a_`I+5{}z$fWoi#B1To2;n=f7XL9h<7Js&-=cQ<-7=2a-AeKcfY@Clf zzgq5Pbod8ZTeeM&$L22OB3egcaVpr?``rgZ0Xqi=9AReJHoHiy(t%qCv{^83Ale*q zG&pnwozlWu2B8kux~(rvNuoo+bq5WF!h%~;BEUIHEo3XY; z&ho{c*W@G6?0f+x_0RH{9{|vAE_;cyHb}SXMIKmI^>3;^%C{g-W}3;c^YfW%_}QAF zVN8~0bzP5VbFrXN2r5}TyvkI2FA4;RF@L4-G+aKJ)hX1_!z@VQ3Sa6U53f@P(}ylx z6T=`%1MkdE@lZS~E+fKTX)ZMNM6aOxB_G6fu&=PB8t5)$gA@ZcR@0cnMiQpb-w?SY zOZ&WEYI?v*RO#I3{Q2J&}SL9e|gnzvx7(5jE>VEN)5D;WBi7k^I? z7yxgXp_37B(7n<|eKKGF8V*eTA2o7%ZH2e@Y zMxCC}14_Rs-C=C0YH9gk%y*HllRR#aIKyw#109N$T~Ij`2{o}E!PLij6n@q)D{7^S zd>~DH;G`*mi7WJWNpg|aN6>)wt$#bgjWGvFcOJYagtDX!;5I!^Mua@7 zRPiYW^A%HWA>;D7Em8*SJsor$FsiTxY25nsOm=UN-rZWvH2d_z|LVWVwRrZ%ad$-W zM!5;!iF&2eBnqH1m*w~gqVW@JV=nwEwF}z^X$1as@al9FZ#4?i2_Aod-hUU1i8tOR z>zof0uwnIz=ZUa#;Ik?L$1&%e+lJDzs*uC6a1M0R_}P+EbVMp|B>7^Ke>{-tt~VL94O*Jku# zUsy>l&yJIPIR=~A5;8toTYpKyf61jcTDdL^Lfg?b63VT^Kwnf|Pqy+xN#7}29~{*( zxmg|bEAMGa;!_}OMhFv=PEgr--ZYDLO2r0Vb(k)Wpr)hPt$NSll zpKd$(REAl zp->!O^F67F@a(Y!%b))EX8rPLr98UB=6!x~;Askyp!9H{uzULhcV@48X6J4QZlZKG z#$*3s`>DR?0)sc2)dcukTUHeUHfaPIPGuh`n^8D;Q+REI@{=Co+TGF<5hZ{E#Se*n zd$Rq;Wr0?NK&*3>lz-mia*5k2z4chVQOnkd^1N5>rq9N3!jySNfu9x2CaX=uyt(_5geBj9LMAZ;C})2HkRrGIPs+)Wnma{xjafqa-fxC}sTgg1I{vI?sGcAcxTNen%nD zEeOV~)PHM$^d84*$>gDeF#dJME3MPbA2#~wgZO*%GgD478CVQ?ydj&s*5qP0E+ys$ zMX;%2;?t0eW#yIHO`*A3K>21>5+2?TQA@_@@?_|zp7{IwrjdZ*8t2T{1I+tO!m5it zougfd#1cdeky^3*xexBjrZm30-h1(fL)rn1zJE{Nc50-&#r7%k){HJu1s|n5#KhM> zIMnD-m}Le2qH#2k{{|wL{8trM%+tio@qbN<=Oxa{|3&1ZzwRwC)KSIub_aIh8J!rc zWf^s2M~BXZ;GUJSE7rE`yTsxgj>d;W5O+neHiGBD6#g)t`94fLtiQha`an8{ng@bJ z^M6aTrSAQ>++Kvl9%ao7Z+}pY2{qtl%C{m?0lASa5k`c{&N~Hg{FW|R^!HE|3NyTk zt{Nv%`^Yx8OKMlC+-Q@T)8u`KN(kHy9VeZ#$VxV;1fLv=J<(>a^t5Cheb@vVa+s@! zOr1FjMfpvVbf4qJe0&}sZ&J)kJZ{NbB!9i?OO^g8dk9uO|2_Hy{V|Ms_8VUFl~Jg1 z5$^|>2$x2z0Sr%bYcN+!+^WP9?Rq{)q+V;34LMHc=DGgOF52P9k_|b8JRQ$TS7$3a zz3tCyN__T4GtBfQ&8B!foLe9GZ$!-{R&WG$oz-;4V7rse*MBta1X4=`ar_kw)PG;W zaQ)v3=HJUB|7WS(?OOE$lV1yQ8FgUt)#493GL!~oZ_!!7?zQq}dH&n2w26-7@6&O7 z@;ryWS2>;=f_eua`uTW8VJ^|qAZn1{6pF4QDe)Ms`v%(BvDfMByRaWkgiv*&L{o`B zx1@ggk`#+F;kW|We$(#8Gn1KQLw{EtR338Emqfj4TcQvXcNj7&Jo*+MieeAAHtnuU zlA|fqjCL%er+bdIkEhvi9f3`&qJH>iDRg+3q)buQsxoKCRU*^xM5D1_WdAJqGFc8J zoU#j>;r(3UfS$;^&LqShFE##9?+A(zz&fdeEw9+v>QVu5+GuqGn2Y4_@PD1=^#=03 zdk>9{Rjb`>wzeO{!TMNwO9%SlYKEJ%w$=1mfEv}KeF0Z*l#LBx<7}Xt8(ii|6#Vbf zXh5rv-TEsH@V|Sa|JTy^wcRsGT#jwx)a$ zXY+IYzkzqL+N>#mp8h;6iiHueDIjnX*dNdTcJE;T8B+B6L0-6KPU)Seghx}sUC~)F zWVQ-tdPy+jDa!RH4Oa$5lI(*@BPAg>I&Zg?RhfzPPw3g?FeR2)@PEu~?~LR4UUOr9 zh+260N&ZHj&K4a8Mnk%k7e$&EOAJ6A<`w(*e1BIAJ3SL?D zRIFPPEznpXgLhf!_a3%~QyhNZC)&W} zV!3CCJinQE=jJEGpR{NYd*zyv42cf0`DtuN91ltj=yQGk&3|(HcY|&pxQIOpY*kjQ zc&EldmImz!UH~^g9Z;JS0S?t}2pJH=H~dQ$(60~BhQJ7`&CrZL%uU+^B&q@bpttL6 z%6aGfYsiM+|BveP@7Lh}P#;wthebwAzU%d{wzK85wD-I?eay+x-AYSgYLRSJL*t4Y zE9=^>X$q7{ponp|!4knzxqQPGyVGOuL3fw9XwIPM%LUN*9Lc8@3_Ug2`jVScmhR3<{e z&8=Z1s0RIst|)XlByh6Kf@UNw2raxcrA%Hd;eRMTr$d}WT>y*G&!Vzd$N~LHc6Rw! zkYA}#^v_6sPzT2tZ5D`K_T!3KV|))}=ajiOolbwCkUa_*)=YEG{x#J2VP~bI_RNuP z-~ndp3i04pCa~FWnwNYq0XVdpgKMM#nTTMG?}J+sXn$_|HZJVVWWbxg5@8dq(zD@ z+aPC+3ve<9BomI^ZK1D@8Uj{nBxB=D&dK#k;A?&$Z|fQ5maIJb%cSUUz2}t`AoGIC z@hu+9l(T%!70jKLyT4&DXDyuI)~bVykAE_nhx1|NJ@m~!Y|n57eD4%|!R-=$Aq_zM zwt_lajr0ymzc`M~8q4my8=hNrqq&0q?XkhN!9%2o5f^7^iL_dSj>gNAbNbiCq#JeX zgJGW!T87pYN=dM=Lto0Alp|jcx1r=uKvgcRO3h#Me4k5naJSrX-xdV75WC%4f2jjWz2+!lr z@23xnXR9E}aGJcBHV4m-#x_HIG=Gy@ksGC^EsULuEN{>m!pBoEsTX{>FR%jNXvR%3 zN41PmzsA2kp&|KzrxZqyaBTvPtRPwheKdO6e#Qka{)t(>g)gU)ph z827iMB)|yw2j`<;*@j7)(^-VyxpK4V^bV=`-O=L#e|=b<*twWErKYY+YZyKRyK3FP3r5e zt1cC3x^GV6Lt1#Vdz($Dbo4(vX~#v(ciC~9qACNA9MsX91VSavffFWy73d2XQ=`Jp>R1z(`6C2SoCznmZyY!&o! z4z`qEQZv5nx21z(xFcp@CN7+dwA!8B6^*w-HYOD`vn2G^?MongHh)Gmn=MAbTky+@ z3xlpb(Tq2&=(ABNtA)dr^PbRJ-hytCimZSPwyV525GzP-gr$h%YK^7L!VCKbxgLP?)9M8lPrw!snICo8+r`A5EToAC4d0lRRHKtXNRx zk@FJ6rkRP|oGY`yNq-w7&TnTfAqz-131B{yTV-AQdbh0cb5&6h-A1uxvH2w}^sbH= zHxa_lUNqyc<%AWDsGeQfWVOn&n1Z@H(nRMJw|v1u8WjV*wCL68WRyzn~G5@?6W$%e}Dc7*2>W9&z2u;7yrsw zzs(^xfLbb9*w1pD4VEs0Cp#e+IlfMAb*AQIH*aLz}^O5Q^8%eKODPk@j5i4^)5ZF#vfGiuegQ=C%8M@AO6|J zU^+xcqZmZnDl!5?4!zmFU(x8MN}Jok6Q%N?*+=fr~^NYLJNLJlq; z2|Jb#_H_F=_xM&6kis0O?ryy0~B zZb5mT$>FC*&mcQM$T~Pb9-X%^?#RsWhbUgnz7`D$3S~qtMPQ%~XkMxi-wB|oRy9t3 zXbE}*T1Y@EC{(!sQyjpacE`o#-OSK^+Thy-h#cs_B`$>h+7v^4ZgUE{1I{-X7Ap?< zoJ3t|41cWF;NFJk9FD^GEpIVl_(M3sV1R$RD^i3aF(3Be+K-ffG<_Mk{{Z&fS`2M4 zw1QSp{Q}W9{)bnO>Lk>7Ido29Zp`*1Vs%c`erGU;zx~(SCjE4ADS5k1@`lXwfqU)L z)sa{x1X*p#6RR7D1k@9y6&^|LLCKPwHeW86RDVagj=s$ORS=`7~bJF(T0mQME4=Fm4>syvcXVC61BX$UHKCGg%A5%GIT|t>#z?fW!jV@6l z+<*VkpNMxCpF#Yzta}kLs^^WxU9Iu14xs`ar&1^ zn{+et6^$wX3^mh_)5K-!lf){7>?(wf%74f5paqT!Woo|uL@JD0!RPekYxfW$R=)Pf z9j}fBk$~apwEQg7)`iRW>vydaZ_ZGVf5U~YeA>+0=YVR0EVfWBubrYEhe3!Qv9awCl? zTVls+5HW^*Pw`aJjEqptp2m1`k|=`bWi}mpun}-TL!aAql{;t9wQ7BDIenpNeCuG% zxU~3rFuk=DDY&ZmG_QtuT<%~ZaiaJt*gCm7bo-As4T&Fi`Zj+vY)SC{27g@s_j6J; zvo-tomoWbYmsRu>{%tk@ln!>IRPirjkxokxPEzAXMq^`QB_;oxQ%HK|+Dl+IU9opB zl7G<_ShC(hz7)rLm~+4in}qsh^7uI4bUx>Hzh68*7XZ08n3zBfp)(^iVH#!fp7342 z_4u9Rv(JQ;V~TH&wW;1b7nEL59?U>pMRTqC+cCD)V#I6AJrBVs+jena|Quf<_uJ2GFJl8H@atRhDKv#{)*XktQQ~$& zNCN}d z0v~&H`sQBbg>Q8n8J4x)|M>X^xpL83vC#j9Vf9&EvVCq+m@py}-Q#2$HDe~N-zjWT z%Bn-|^ZpM@H-D|SG(&{|0*d%A*^yn{?Emd0*Z)k}sOt7V*^x`t&sN;;j4yMSa6WzC6U{#-{pQizu|qx`v-jaym|oT+<&Qnu_zk$K9ys-r-0R^*;=-|`)tKG}?wEuocwsi)hK#tFa2OE;;6#FRF^yOvh{xgZ!? z43leAjDGff1ZtFiMsdHOVNa-rhI{rJRl-_I$5%+Za<)JjUd6v>77wG)7R@`<^&8AQ z&YA2_e19W{xMCbOXe(~BBA~&@_%oEH^hQUXeg3jD9@%|DE`{gERUDb^1(+TCa9N4o zyFuIE(e$SZTIiy$ZB~)j4(iQY4eAHK?<)7l2Akr7lD6Q5!$&^2KYCgspc1x1a_v zMkTQtG`g#50*;N@1{p3E7JWS2SW%F{+{|9}R)R8}f+Ua~PtB2?MxBk7kvK18gkg%d zY=4{=^n?p-`!hGc3mTOyY5cUw$TF@pK2j*D0o+W#{GJjR=U~y%CJcS0!fs=%5jv+5 z3HCKsk(qK>*>*A1nuBr)Js_j<6q)smKmICP)#NpAV%lRY2qa9={Bh)Fw}U`+ z7ELQD#Ve^Zg2;b^c@^beS=YljBWMd(PJfcQCjXENBE3u?Yb%xy;*WL41clD8+B)Z6 z@)ec)O!aR@0EwiM_*#?3)9K;$O(9Z)x!fjT-kpSrv$ddD1jXE2z3m2@ESR3x`e)7o z5WdN(8z5?yk!JUD4mrD`(K}tLForB;+|vUM!Rm&fT;A!Vv_>u<`GC>8qBOj6zJGEt z-{|V9d)<;#BnM0a+teHnO;TmxVeHadd2yOxMJwmPad$zj%!~ogLX!o&x+Mh^H$PodMjm4R zEWOP}n>w+M6Gq#6#PEk!STU#hE`KKgIuDcQrlpZ36+9NrGd$VF7iD3aA8^O3PYANM zOx^S-jK*wKNHOU_{9)CX!KFV??Mj0+0Tv$8NVPeDs(CODr4PV?kax}<%yG3ap`$xP zUtnJ|2kULF%`lRu#ZuTBLvpQa=iDCUG4hawA;a{xpT`3jtuIJWf|ji?=zpY6&FkFK zZx#82h=XbcHK(q=^@W;DP^O_O+3Jy($_@Cc6ysd=3DeW{(*NjC&v2GA@_?OPcqeXB zebValFD&D~XI&sULCc*FvL@#XG8dRe5gSjEZ{N*oT3g8J!Cqh&LE%c+z zW#LC!`4zZB2g?>Xyue>(1bzV59sxU(^OvMWz`a17fH0j%AT|d`a(~Th`V5I-W-vDI zX>78EdVyWz4+?|Cgg3MpVNOQ&HPQ12v#~e|1|$UPZ-I)gIU_{(_nst?_#TMydg33G z@rve@5*3-VTg|mTmM@}RZe!yxd{BYKH zb9;h9)MV zC93OoY1i(g6446wS%O=K-?^^(ZtuwY?(f+8h-~qU`pA6fQ#JN|f(6nwzW%`$ER7~& zDhvq(G>7nCy_@r|NF(mxY-0AGLyX3|iwXek3w^CCy=P36ZCDWshDeARF>6>(7!^u9 zdf@jcSa(?oVt-ek_9TXk$H+Dfs8x7bJ*$(m<(T#MCPQRyra?PZDFn|(RUYw5R; z#hXj{FZWZy*=-vN_Tf0-*_Z2!OOKhghpV;XUwZxrbU=A8Hn=iKjdT6;k(46kwbX0H zY)WNq$xGInuWbv=G=S2JjI=6qwbr6&=8cOE<$b=V*e2pqmxl%3j;{g*IGPzwol6gV(`U=sYyI1?G62 zL{m$Av@TCs%QcEBxEvph22XYB?i0Q{UEEqtdn0f_t)FL~0(uaxSTl{wk{w^UPr6&Zx%RlFHgb_ZV8I+Ig*`r`p5F2V~D^Pm00j zSNF&y`mxF3lu#|R_Of${BTvYYjZp&DB!c?SR3o6UDW$ z=J90HW&MmBNx-K)oIW`6sTM)GLU{2OQVIb|ynn(6=55%Y>2vb<>D56b76{dndIcmO zpEPQ1&2s~e7eAQjo6Lmv@Ne0~{4}PiFiPV| zVkA+niT|(O#hDE&J9{MC&V|@%%i8JT@8h#nxF!-N|ai-U+sEA@tlFYQm2|)${BPE zti*MFZ%)>ER(ksF@+7~Iqmxbz0W+HMTZhxEDzwpuH_FptqCU`szb zKW2r6!Zax)teCx{A~ye?ZQP-4<=hUeuYZC(oX1vDK!-O%aD+2VoGB%xZlaFX!D1%x z^z(>l8U_&Iw%j_!i+H9Q4G}*pU1OI8Fu$j~q=qTrWE90r^Y~3@aM!mmB;Y(1>>&}d z>Zg-@8M#ma5LBQv+qGz&$EqeGPE!V1LPw zaKic9FjuRnU9N?SV{mN6);$8!Sl7oYiA-Auw@St3ge9Yaot|(x{G2$m;Vdku04Cga z$KV4d-}Hr5-1~gOQPoI_I>)7-D$rT&9P3XrJPSS6qdBuqyhb2vlBwzbEPa6t+Aqj} zjA^Uuo;6zej-a3Ok7)7bx2z&fq<^2jayH!SpA*FtlAYwGre6wmbW&z@sUj1WF(s+@ zYQEEhRPh$Kv`GQ;JXqM0?}fX#F!OnP2l3>*622&Ha;kHKn5Y2Qm$EPnF8PB}FAHtO z);;Du&4VJ{lur`4$&-^7MZ%8foqbQN9RwE{p_kyj+xNqCE|$+BiIS@w&40GDLPZrA zzc3>)F-32W9#nAiVX7t8Bj>$RV^6f5=3Bpbf=q1l$-xNn39?eWfR=qTs?;*~J3ekM z(2Y<6B`^!vY}7j+UFDxKV=qb$4OMlcu%81dsnJK*!=to3_cr5u@wzm>^4sC|orda7DVO_^F z>0V5;J$-w54W~-5K8;1R@5Gl3rO#{l#l{xmR=$EuP&FG&A?eS7?U}bsHN1*0e(Riv zo(SU}optx1)JcVSuv^DA*7J;5Nwx5GjN+`2-pVXtrY2I=*lN+fzklvna>+cm50ohk z%5EiR2MI8*y9ZXHAG1dX3moA7N`wQxY~YF!oNG?dfI7PpAlr)BqB;vsx1{%*z7Rj{ z^6`@_4qq_T8_3}o)bcir4RYfONTtC%$FQz+1$3qs{=`17J|Yss)IKd2bj*Z%!{Qaj z9CH|AYXM+Fs;2O`O@FGU_&8q5*0P>N?gD2=^v|4_t=zVr1Vx;Q+h)O((y#cd#Z&Fz z5OGWFZmg&Cms6QliRnI;Rk?=*-G0D~;X5k7Pze0q@ZOz@5g^}6LVjsa(PN7hb*RP= z@9i>erHqk(J{qu;@Azrj&{sy5lsS4r7y8B?@pcU(mTy{NGJlBa{boigGEH>9MiWpF zwvn@@xW2p^U60e**f!cW%G5f|JQw9PM+v;( zc(Ur!7Vq+)5g>nWx4hajev34#@3kPxfIR$2y1d{4K2jZ5)P+3R8131Vt?7(|=4vyq zU`u6$*PHHP2!C>MhkJLdR^k+YezwvG?O+1?C3LheFdr0ffd3KU53fJkOB?jQMqS0d zIMx`as^f0VEO$Wc zoDKOJY%P({ryQiaIAbmVI^hGuh8Qm+DN2+$x8sPt{;>G_8$R0+{rV8ffE@rO( z8}_^Kz!^dNjw7=%^D5?y77@*c02gj}NY3Mg7Kh%|blO*s55D4trz@#ml3dqZS96z` zDSi|pn14$bE}Vm;Zz(T5aXjUyz)Aj-%is6sQRmka;wiyg{bTBvIoU?)u%Ir1*YR~; z)_e9&ugmva!Or)OeklJWK@4JuBJ!>uD431C;(wGUt6c0&{pt^?HXh8>=_NIm`0BHs zvf=A#o52BT=?1p)cOr!DQ%-nK4T7eIj&+bukAIkwnWte?j*>BO*3*iaCXj1oaH$y5 zYIGWJLhgeP3_AXunw4P6)7JTd4sp27N2yDws|K1wbw_$@i`5%0(4>v?f(21>lF)Fq zc0gWja3FwMa|+*CHTB-zv{MD)?gLG?6KsKSh-=Ai1VQ9a^0r-iV3F5!zIwh1jODiC zOMf2NCR1?cG50@^Ydxw94s(ftITjn6x$$KAJ%RAFL32Jtat^~G!tKhqxFihHcQRTljY7%aL}79zJx4S zR5IhSRpYXrgf6FJie5v0uPH?y!la`Vt)I<$ht=CM4{e^hlAE5P ztx7ie77R;X<|t06--_L2l@I_RkB%R0yctEzv% za+K8_?h)LfCVkM4VGEDcYdELVs)4e_8bd_q?;$ErT4vlEv?=Csppw}gw43_`mTz=b zTDSJ|EKqF{>M`i5HPDv{^S5H19VrBRbJ%j_MF9l&mr1|#O?d8wpo$;B)M0m+?@tmD zYrx~zH-Ervs-*+h($=Gjm&IE<5pjRx_a)%CG3Q&cNiP(%4&Ii+l%r(8LIL zXWy%59I$Lb&z4+l|24L-_msQ}Jxhr=v>c{}lUHK*+!%u9i#&QFrh`^r9eIDw>|amn z1_-A>u$z2a&S{H@F7msI!rm>X~P(xLayF zHjPV+v*()aoxe@O?ITubK|y0cBv!OytOE1ldiwaWuy;}mDK1UnFOAbZgihH(Ph~FL z19PFcE)O~RN9t)U20DFayODn!A|U$)nb4W#eA#e^;9s!&X0&$Cj)s!>l|M~C&1aEg zaaJ2n@NB>E+WJBsiQ5v}pBPsABDVz$0k0lOuPMhLSQ{A)%?-la09v-E`>kr;mthVD0RzW%Iz z3JFo4-mHsvEm~KAlx<7qJj^SSH2E0=eWpE`ZA)rAx$?_-OYZdRW)U`<>{ROVVh+X5 zDDRRX%QBPiAxoUk<9CHR>$wRkp7ZI1(T%chyTxkOjw{s0|F5;P0E=?z9{8ftB_&Hr zN=v7Jbax}=(n~i;D#Cx#-Q9>FAzjiTAR&!NE=s9{5`w^gz4v~9F8g`?j0?}gGcP>n zcV_0yyfg1R=bZf*tA|nQX;uZ$x*BLfoj72P*hQ}(fPDi&eZJTDu%2-jxwW5-2rk=vJzE0lg zB^HeS!Rs}z!(}7yZB%TD5ohl)WWNWkqFEmMq@T2gX)snK;+nowlC#+LrXmx`4+S9i`;Ez+K^Z2V0?waN65y``fYAOlO-FsV10{9OI7+oW*)jW?h-(@42x(tq^+PAm=eU z7STYRN#2S>U3{te4tS=`k%WiCvV|$!F_7Gd)KfJxyMT3$xnVPATLi@0wvfG@#>bPF zlGA^ll=yBip%F)~k>oP(gDak?R*rPFR?|I>NsMg|>+Eie7cdE}2cZbRz)`LElFxQ> zv-kZ$APL(Y{#O+bbB0jm>Ss5(y#28mJ#mjg~HF}aRIGRLm4#*zq?lx3!7wr17_C9~BkIE6CuH>K_Z30rA>DdOMRpPhM?_1Yr zK>_4FF*GeYw%jX5sMY0)EmeOl=-2(FO}l@SYaY8q z=Rl<#*^QFSM@=Rb_i}Xr6CMvH#c4N_fLeoh=$`OHINlIUsJInf|G*tNwS)9o+Pn(1 z%Y5zi(>=M~7;hfhIRu=QYW8}*xDM`##(LeQsFX~`$^xS%)navC`(eY4y`I6_I-9t@ z<(sP(XUJBRoW60Ci=TG*u83}*9Dk8G}>c$-@PS44ghc|ypU2?-M%?6_G z5?M!>-lPV&gAIVQktnABA zi#021J0Ob>VAPIHIU#9>yb}z&&1ypEn9wCe_|)FGk?mfEjL8`18e_WB$ok#UPPT{A zc!83!IYH*)5z4hgcUONn!kO3x9GRz`EH}F%^n6jfx-g$GWeYH)2u<-|Z@A0~77@rwRPtj>4bXj;JWBLe{S*gv>eQa1e~;_*Fgu&ImXg@>5y>ZH8{XWUa2 z11L1nHl~t0ay@^z=)sbSHUm;hBFq%&2IZHmgX1Mk-3md{FO%X99P=(C1~Uh z`Y_f}6Gh9Y@%L*!4!!+GyrqHBPvq2JBR=$_r#S*Dx_owSa?AY7@&&KfgZ+rJlMhh< zET|{GX3?ZdUfwlVj37l-nRFH+tcbt>Iw!Hz4k)VdfWdz{imF1ev8awPNUgowDM!-yA7QK^Es7Nt$!|RWDMDqCcpA3^L zSWgTC0%Do@0e7~l89A?7mGS=WO?j?)XU%-n0l@@;+*2cM}*lzamOw1mFOUX zOLCpEA*6pZc$#mgAtqUmB$baL)j`-52EAB4t+ z7+pv0RlRmyzSM8{KA*+mYvp7nW?!m%P2q+G^_t+BQs|sVa<%+0n??Mmm1nZ$BXO2D z8?>`6wnO+xJ|OM7Gkx}Q74+wUl*Zl?RBxULe-M9>7Gpq7Gg77Pv%hI6ot{%Lxb5>n zRZiRvFQ^igMNPC2A|4>MX;Odamm$G0v zHVk_ejd|#op$;sL>P&X?hyW9n_n#wK{-#mQTE1-X(CL_SwWxvj);_9A}=u!kBM#wK4GAF(9Bk=nPF zq0e?>O_yv-U0SjB_6a48A9`EGD|i_GY{mq#aEQ}ejo5%(os%}1^md56*yJxIAvHsOFXZiRo4 zCm&0BGg;pY=s+akv~f4gLU~nNDYv4HTVXv}Dl_M-h5Z3YPlUgi21A8?*Cy`EOs2vO zC=`<~?@1Qr)n|V3>K$kT`Y0WB;G1!;V|q}RW*Ik&@N0S(5S9w>ML*+VpuDD3u*OUu z8d9r`LE+FS z@L_$VGClU*oc#`{2oq&lLY_*Z~2%~vgbR7HPZAwuT& z2dPzr47Ehm5ca3jt(>XWdT7bYi^y}><6h(=SLM;s(MiS5K#5zVyh_~iF;mJn2h#bk z`<*^tM`?6m@W;{*%?-B)AJ#^0U9qh0XIoUMG4*I$7M>fu!$5S!u2KS-`?BcRWd6+q z{m0Qz!%39aBk8z>OW`D$rIUXNgTyIyA?rKt!AGvg^@hbVhJ6Nhcy&5;t7@xA93l1V zr*AQ8bP~cQu5)L|%@UE}(GIVO*S_-Get)p071dec9A6BasB)aGla*-QEEaf_ist`f z&uP`R)E-6AC5JevG6Zy7*`kxprnP?8`jL=o?!4yh92+!u*(l-VQ5t^-oC9us6A!02 zM@d4JhmgR*J{5K)j`90K8coG(grY3T8_M7w4P>J5@pVM%y{fiJt%;bIjj3*HbeDZv zG3Y`4brw$TXK0EH7WOVL#G4+lkVT+d zuGd452`j=N?kp5iotb}#f}WVi{lR#;?^xI9p-T>vnmv&YlLk_qTQ8k=1;~%b-lx0x z7Jcrc71RtwZ@A{xBLE^;QG)D8wRK)Ess-a6)nzrz$%4wLSTh^r#(=nG7h-Zy2^j(!>Mr;r7|%mL1uMI zFdkQ$^FFngcQWt2j=21S z{d`RAZjtu9RTJ@*;L!Wp{);oRF6*4-n|z4qMM>Am{O~U?fA0Pw9yXpG0C1CBe97~>(tB8>rlG8G)q!^>Z&>+BUz(o zSmO&4o@a_HB&T77TfXMD&h%mzKoJqx#wJj}4YQ+h2Z zQOS8Ib9U=sZs;Jx==95yG{E4H3!+%0dQ}ZaDj;V7U-HCirs6T{Mp-g`3xj^yN8JyH zwO45k;zM)W_Nw1Fbds?|jNGRjHQ`TO7*H9TjxT?g#IHd!X5%l;z0F`kQW#y+~ad-HZvv1u67YBbRiJ z9&~>Z>A8k$gc?VMdcHH8wz{Wl6yNiCg2Q$>ux*i$;GG2@d8pGR>VU0z~*!x0D}rRXAgo zaK9lSHCdYp9;n0z7P7vUF*2W#H1JSsEJ_0n-?>RlL)WLsQpsO@zYM%3kUXrqt=E6D zq*vvgaw}9AX<`(u1H4^BB>jScue;*?!fREG{*mR{Qi28^3lGBv{BE{E{*I~8kEzY5 z_^Ybvpt~9D>0M)Laa9;|)|R^qDe~4cT1YFwq2b{@mgZ|Nem4`Y$4;}Trc*}^HY5($ zfIm3#rz8aMLmlF4s?}35-?i!^jwpIC%8t5`Q(IY_T$wL4ni7j^Y{HIB}qu5=LxMyabO6dn`u_ zT79mu)MT_wg9e-T&5v5Dfz*%2`8#)m0@Dh(paX%ip(PwS-I6MzYKE;0wxWOTeiZcd zdS*U3$yqCQN>1!FqyD+Kjoy?gLGt_P70;B74N7`wWUcGoF>99_l*BDK#m7lcnM7#H zCIFK~4{XE%1D9l?W&4XZ5pvc90wHqjD= z*Eh?t#7{hCc1o#+^)e-;kH~)-4+H4a3Ce|@n}}0ICCc27Ho*^JY!NG95hChPFQXqb z5ykY^8$c9(1nSR;LP*2KKEU_Ze@3;5Vc+rD;%%>J=z^l?#@v+~S&HM0T%(UI#)Hxb z+wBks$ZKNma$sfMaRp!QPcFy=*?nef3cEwkb)fgLPNk(Y5%HZ2uXcaMF_KuFoymg4 za*P0}PFH)(BqC{Xb_4fIL(yJa7nahlO$TorIu6@*t4hVP{ntIRcN7H)8Xlg8q;`q8 zQN;uMl>+b{RfWm825pF=%V@LRnd7Yu-uY0GE_hwRFj+=lL9i)!wTXH!2C-SC-BjKh z(Of>wW4O4%GjB%RpGLo^A$H)1tQ7rBUWMy|*Yi4B!t_Wdl7R`l_O=Dtu zjff1V@i1mRn~tIs^snL*X;`_Mam%0Aa!(+2n?H32F=3Y#ysB6YW#TyGU28kw3%#}0 zrOXG(awKhCmbkmgDZl^Zl_%$ier+OMz0N5Q)Q>9}hTafskCcCvG=yFz4+2VKl1}SS z1UFh}3?DgOu^;{1S@ikxEqweBI8Spa>a+{8*cI`|RWd8(^`` z47u7ttU+cFOdoukYckws!l8dAtsp3Iohewqf^4=mpCW%M4WK)Y9xCeID+t&9})w_AXS@x)dUD0B9 zI_o1*OgqAd zBaK~e?~!rdN*hyK%#D<9icb%Haau#`fapxTD^Rwa>YtghpIt(LG_#Evq|TAmFKvEC ze!QwA95=H4*gt-KvN8hAfU%*)mZ#FSWT}Zm&MfTaQKl_-Wu1OZ^`+3lcWA6&ETy<<5km+0P0ui3}1;iB6m53vYy zZPPdj9b{7`TzENzAwT1i!96f*wWx3`N1y+ylE7sKYmb5NHOPp&;JVy{$L`(jmzmrW z_AfghoMu5j1l-hjz0M%xf=k^TYGD3B*{y&0Oo)tm-gVaCx}Q&7ld)drQc8j=;=}SA zR?k`zp7aSh5x$yfX>b~-A@h41JJM*GMAm5^>b^8_Lg`a7q!A=Y`0DVd zPZp1S%@#tJ`+dh)jSMs7p0pbfZMms+4K~JcGa91i%HMjW_$a|f!7X02$PT` zy;u0>ml+3imtH5#-`^z(xhf0=#=PLOa~{`2t_Z%B-n7G?cxj0?;NHjA=$7uhBSKl3 zz!?dfY?i}NCT#NL>}}8zOSejdj3&R(N=o>IeRX!lfJe2RwOwpo5a1^D{+6oWr=2H zvKs&G+I=mVgaU1XkUlK76B&|@ex3VZ$~G56MGMGyjA|~i8Y)v2;Up@fuxwBqhFmCM z40kdmvGV;$_)<=IYqpkbpeY67IGY(1x402~BRYT>D_aY7kIyQD$=DmO*RUj5cB3yg zb3+9O>vcBOhNz@Ba=Do}zqEfHwz80-{c`8>p)<{Ag+|24vDp5{=|eIcDf%p{RG0aB zHOsnXi%Q;1=*Nel$Hu52(h-uh*-)hh(-@n%<0WY$?u`wvk+SGh~eL zI+)On_J$M^j8!qWIET9^eQ9cwJbk9KxV8-Wv{Ng1z_tApJt{c^Noaq=?438)I+P9C zC?!|$h3X*fT}N1Qw~3nSMrxP9V<0zq7oM6x%cDYkG1e3wMZ8uG9etG!R>{0A^S~=< zZzYL+53yC`5iS8PpHIb@*wRMI2mru4*oO&l{#E+`@ZE{|k0kPc_w#@ktf+%Mf&mkn zg7D|!{9JG{!uJG&Y%G85oxm=Zw$5KeSvtFb>|C6`O)%)($BMWF0LWeW^F7QtVgJ$( z5)|y+RbY~(z&0-bc{T@6apz$xwSW<3kO6?37br7`KS)uLmH4*on1}7fd9d;)WcV6{ zqkT`dshJzt#LSsh8f0tc05XLO_6bk1yW?!4i~<0-;{yO37bt&$SU*9LH@o+3`ENVB zPlsSF&VvL1+`1s2hVbX)|Bs3&g%x_@20D#N|rWENfFcr;AKz6RS|BD*vTjafg3INa$0RYk$ zsMR-qf%Ok2$r1s+s+ZY+5bELtGO_;CK?K&5wqQH3Gwh!={=E8a zYB^Kq8x6cLE< z{4vpghwo$tGL-|tsYzGI1(-Zpn8Ej zX!x_-zoy!sskXBHtmfByu>l^e2QJ{dOn(pmZJt!sH7Gx<{1oZW2w3MlpzY7{{xhV% zO=8LehTMZSY%LA|pnri>;_$O14NE68Gi^&VGn;?^Fn^|v+nf(m>R@fG0Bd8#3z}rQ z{cD)U>10x^j$lgGzOBV!DfFw5={906(s*x(BGz9a!#K;g_TMX;4A1} z{1X%@*wWnI9acYaOEVK|sjq8iOEXg`SG(^l7;69Z zK&oQW7-lfz*Wib^MCq@P|6cfRpN^pgD|@2@06k>z!w$Rp7r@_!z$Z2TTf4UYbc%m- zc;WClQO|{+_WoLiRCoe>!pd_(XaDb|uY@PT=Q2De;ST;zWk7ip`})I+hxb)H7oUaxW8%N*x%gkk4Cmi*ju}nG{Q=BB zczgVp0mB_8KBo)-e}M8&M~mSx@MomXF?tj~fceIWDR=_>%lvZ!{*CVuzVm8dMII69 zs|aD(cL6Z~kii5Sfq?%5P)h>@m!5V38nbeF_- M0ZRr;bpZeX084ucYybcN From deb0000c848a6ad45ec86b428d143efb7bfa7174 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 15 Jan 2026 17:20:22 -0800 Subject: [PATCH 13/25] Update PestoFTCConfig.java --- .../java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index ad3dbc8..921c044 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -68,8 +68,8 @@ public class PestoFTCConfig implements ConfigInterface { public static double KP = 0.015; // AUTO - public static double HEADING_KP = 8; - public static double ENDPOINT_KP = 0.5; + public static double HEADING_KP = 4; + public static double ENDPOINT_KP = 0.3; public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); From 9dadf5b0bd1fd04cf18bfb3ab35eb1474438ef18 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 15 Jan 2026 19:43:38 -0800 Subject: [PATCH 14/25] almost 6 --- .../ftc/teamcode/PestoFTCConfig.java | 3 +- .../ftc/teamcode/autonomous/BlueFar.java | 50 +++++++++++++++---- .../ftc/teamcode/autonomous/BlueFarPaths.java | 35 +++++++++---- .../ftc/teamcode/autonomous/TuningAuto.java | 6 +-- 4 files changed, 72 insertions(+), 22 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 921c044..9ffc481 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -68,7 +68,8 @@ public class PestoFTCConfig implements ConfigInterface { public static double KP = 0.015; // AUTO - public static double HEADING_KP = 4; + public static double DRIVE_STATIC = 0.25; + public static double HEADING_KP = 0.5; public static double ENDPOINT_KP = 0.3; public static void initialize(HardwareMap hardwareMap) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java index 883a5c7..f11c887 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java @@ -1,6 +1,7 @@ package org.firstinspires.ftc.teamcode.autonomous; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.DONE; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FIFTH_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FIRST_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FOURTH_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SECOND_PATH; @@ -8,6 +9,7 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.shprobotics.pestocore.geometries.PathFollower; +import com.shprobotics.pestocore.geometries.Pose; import com.shprobotics.pestocore.processing.FrontalLobe; import com.shprobotics.pestocore.processing.MotorCortex; @@ -29,11 +31,14 @@ public class BlueFar extends BaseRobot { public void nextState() { switch (state) { case FIRST_PATH: - mecanumController.drive(0, 0, 0); FrontalLobe.useMacro("outtake"); - while (Utils.timer(9, "outtake")) { + while (Utils.timer(7, "outtake") && opModeIsActive() && !isStopRequested()) { FrontalLobe.update(); MotorCortex.update(); + tracker.update(); + pathFollower.update(); + + mecanumController.setIsStatic(tracker.getRobotVelocity().getMagnitude() < 1.0); feederSubsystem.update(); hoodSubsystem.update(); @@ -51,21 +56,46 @@ public void nextState() { pathFollower = BlueFarPaths.getPathFollower(state); break; case SECOND_PATH: + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + state = THIRD_PATH; start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); + pathFollower = BlueFarPaths.getPathFollower(state, 0.2); break; case THIRD_PATH: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); state = FOURTH_PATH; start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state, 0.2); + pathFollower = BlueFarPaths.getPathFollower(state); break; case FOURTH_PATH: + state = FIFTH_PATH; + start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state); + break; + case FIFTH_PATH: + FrontalLobe.useMacro("outtake"); + while (Utils.timer(7, "outtake") && opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + tracker.update(); + pathFollower.update(); + + mecanumController.setIsStatic(tracker.getRobotVelocity().getMagnitude() < 1.0); + + feederSubsystem.update(); + hoodSubsystem.update(); + indexerSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + } + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); state = DONE; @@ -82,6 +112,8 @@ public void runOpMode() { Utils.clear(); super.initialize(); + mecanumController.setStaticPower(PestoFTCConfig.DRIVE_STATIC); + state = FIRST_PATH; pathFollower = BlueFarPaths.getPathFollower(state); @@ -99,8 +131,8 @@ public void runOpMode() { MotorCortex.update(); tracker.update(); - boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; - mecanumController.setIsStatic(isStatic); + double distanceToEndpoint = Pose.dist(tracker.getCurrentPosition(), pathFollower.getPathContainer().getEndpoint()); + mecanumController.setIsStatic(distanceToEndpoint > 0.3 && tracker.getRobotVelocity().getMagnitude() < 0.5); feederSubsystem.update(); hoodSubsystem.update(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java index 7933ae4..f004d4b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java @@ -11,10 +11,11 @@ public class BlueFarPaths { public enum PathState { - FIRST_PATH (FIRST_MOVE, 2.0), - SECOND_PATH (SECOND_MOVE, 4.0), - THIRD_PATH (THIRD_MOVE, 5.0), - FOURTH_PATH (FOURTH_MOVE, 5.0), + FIRST_PATH (FIRST_MOVE, 0.5), + SECOND_PATH (SECOND_MOVE, 6.0), + THIRD_PATH (THIRD_MOVE, 3.5), + FOURTH_PATH (FOURTH_MOVE, 3), + FIFTH_PATH (FIFTH_MOVE, 3.5), DONE (null, Double.POSITIVE_INFINITY); PathState(PathContainer pathContainer, double timer) { @@ -38,7 +39,7 @@ PathContainer getPath() { .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ - new Pose(0, 0, Math.toRadians(0)), + new Pose(0, 0, -0.7068), new Pose(-14.711, -7.6111, -0.7068) } )) @@ -52,14 +53,20 @@ PathContainer getPath() { new Pose(-9.37, -18.48, Math.toRadians(0)) } )) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-9.37, -18.48, Math.toRadians(0)), + new Pose(-66.21, -7.83, -0.23) + } + )) .build(); static PathContainer THIRD_MOVE = new PathContainer.PathContainerBuilder() .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ - new Pose(-9.37, -18.48, Math.toRadians(0)), - new Pose(-66.21, -7.83, -0.23) + new Pose(-66.21, -7.83, -0.23), + new Pose(-58.21, 19.41, -0.23) } )) .build(); @@ -68,8 +75,18 @@ PathContainer getPath() { .setIncrement(0.01) .addCurve(new BezierCurve( new Pose[]{ + new Pose(-58.21, 19.41, -0.23), new Pose(-66.21, -7.83, -0.23), - new Pose(-58.21, 19.41, -0.23) + } + )) + .build(); + + static PathContainer FIFTH_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.01) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-66.21, -7.83, -0.23), + new Pose(-14.711, -7.6111, -0.7068), } )) .build(); @@ -85,7 +102,7 @@ public static PathFollower getPathFollower(PathState state) { 0.2 ) .setDeceleration(PestoFTCConfig.DECELERATION) - .setLookAhead(2.0) + .setLookAhead(1.0) .setSpeed(0.6) .setHeadingPID(new PID(PestoFTCConfig.HEADING_KP, 0, 0)) .setEndpointPID(new PID(PestoFTCConfig.ENDPOINT_KP, 0, 0)) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java index c1d2da3..902ca3b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java @@ -16,10 +16,10 @@ @Config @Autonomous(name = "Tuning Auto") public class TuningAuto extends BaseRobot { - public static double endpoint_kp = 0; + public static double endpoint_kp = 0.3; public static double heading_kp = 0; - public static double deceleration = 0.01; - public static double speed = 0.5; + public static double deceleration = 35; + public static double speed = 0.6; public static double look_ahead = 1; @Override From d1a0ccc6cf13338df7877eff99f3ae23158483a8 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 15 Jan 2026 20:41:18 -0800 Subject: [PATCH 15/25] retry --- .../ftc/teamcode/PestoFTCConfig.java | 2 +- .../ftc/teamcode/autonomous/BlueFar.java | 69 ++++++++++++++++++- .../ftc/teamcode/autonomous/BlueFarPaths.java | 64 ++++++++++++++--- 3 files changed, 121 insertions(+), 14 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 9ffc481..408c84b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -58,7 +58,7 @@ public class PestoFTCConfig implements ConfigInterface { public static double HOOD_AUTO_FAR = 0.04; // SHOOTER - public static double SHOOTER_CLOSE = 0.70; + public static double SHOOTER_CLOSE = 0.65; public static double SHOOTER_MIDDLE = 0.87; public static double SHOOTER_FAR = 1.0; public static double AUTO_FAR = 1.0; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java index f11c887..b804121 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java @@ -1,10 +1,14 @@ package org.firstinspires.ftc.teamcode.autonomous; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.DONE; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.EIGHTH_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FIFTH_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FIRST_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FOURTH_PATH; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.NINTH_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SECOND_PATH; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SEVENTH_PATH; +import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SIXTH_PATH; import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.THIRD_PATH; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; @@ -31,8 +35,9 @@ public class BlueFar extends BaseRobot { public void nextState() { switch (state) { case FIRST_PATH: + mecanumController.drive(0, 0, 0); FrontalLobe.useMacro("outtake"); - while (Utils.timer(7, "outtake") && opModeIsActive() && !isStopRequested()) { + while (Utils.timer(8.5, "outtake") && opModeIsActive() && !isStopRequested()) { FrontalLobe.update(); MotorCortex.update(); tracker.update(); @@ -48,7 +53,6 @@ public void nextState() { } intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); state = SECOND_PATH; @@ -56,6 +60,7 @@ public void nextState() { pathFollower = BlueFarPaths.getPathFollower(state); break; case SECOND_PATH: + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); @@ -78,6 +83,61 @@ public void nextState() { pathFollower = BlueFarPaths.getPathFollower(state); break; case FIFTH_PATH: + state = SIXTH_PATH; + start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state); + break; + case SIXTH_PATH: + FrontalLobe.removeMacros(""); + Utils.clear(); + + FrontalLobe.useMacro("outtake"); + while (Utils.timer(8.5, "outtake") && opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + tracker.update(); + pathFollower.update(); + + mecanumController.setIsStatic(tracker.getRobotVelocity().getMagnitude() < 1.0); + + feederSubsystem.update(); + hoodSubsystem.update(); + indexerSubsystem.update(); + intakeSubsystem.update(); + outtakeSubsystem.update(); + } + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + + state = SEVENTH_PATH; + start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state); + break; + case SEVENTH_PATH: + state = EIGHTH_PATH; + start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state); + + outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); + intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); + feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); + indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); + + break; + case EIGHTH_PATH: + state = NINTH_PATH; + start = System.nanoTime() / 1E9; + pathFollower = BlueFarPaths.getPathFollower(state); + + intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); + feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); + + break; + case NINTH_PATH: + FrontalLobe.removeMacros(""); + Utils.clear(); + FrontalLobe.useMacro("outtake"); while (Utils.timer(7, "outtake") && opModeIsActive() && !isStopRequested()) { FrontalLobe.update(); @@ -142,11 +202,14 @@ public void runOpMode() { if (state == DONE) { FrontalLobe.driveController.drive(0, 0, 0); + telemetry.addData("tracker", tracker.getCurrentPosition()); + telemetry.update(); continue; } - if (pathFollower == null) + if (pathFollower == null) { continue; + } pathFollower.update(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java index f004d4b..64c8161 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java @@ -12,10 +12,14 @@ public class BlueFarPaths { public enum PathState { FIRST_PATH (FIRST_MOVE, 0.5), - SECOND_PATH (SECOND_MOVE, 6.0), + SECOND_PATH (SECOND_MOVE, 4.0), THIRD_PATH (THIRD_MOVE, 3.5), - FOURTH_PATH (FOURTH_MOVE, 3), - FIFTH_PATH (FIFTH_MOVE, 3.5), + FOURTH_PATH (FOURTH_MOVE, 0.5), + FIFTH_PATH (FIFTH_MOVE, 2.0), + SIXTH_PATH (SIXTH_MOVE, 0.5), + SEVENTH_PATH (SEVENTH_MOVE, 5), + EIGHTH_PATH (EIGHTH_MOVE, 5), + NINTH_PATH (NINTH_MOVE, 5), DONE (null, Double.POSITIVE_INFINITY); PathState(PathContainer pathContainer, double timer) { @@ -46,16 +50,16 @@ PathContainer getPath() { .build(); static PathContainer SECOND_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) + .setIncrement(0.05) .addCurve(new BezierCurve( new Pose[]{ new Pose(-14.711, -7.6111, Math.toRadians(0)), - new Pose(-9.37, -18.48, Math.toRadians(0)) + new Pose(-9.37, -24, Math.toRadians(0)) } )) .addCurve(new BezierCurve( new Pose[]{ - new Pose(-9.37, -18.48, Math.toRadians(0)), + new Pose(-9.37, -27, -0.23), new Pose(-66.21, -7.83, -0.23) } )) @@ -72,25 +76,65 @@ PathContainer getPath() { .build(); static PathContainer FOURTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) + .setIncrement(0.1) .addCurve(new BezierCurve( new Pose[]{ new Pose(-58.21, 19.41, -0.23), - new Pose(-66.21, -7.83, -0.23), + new Pose(-66.21, -20, -0.23), } )) .build(); static PathContainer FIFTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) + .setIncrement(0.1) .addCurve(new BezierCurve( new Pose[]{ - new Pose(-66.21, -7.83, -0.23), + new Pose(-66.21, -20, -0.23), + new Pose(-14.711, -20, -0.7068), + } + )) + .build(); + + static PathContainer SIXTH_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.1) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-14.711, -20, -0.7068), new Pose(-14.711, -7.6111, -0.7068), } )) .build(); + static PathContainer SEVENTH_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.1) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-14.711, -7.6111, -0.23), + new Pose(-44, -20, -0.147), + } + )) + .build(); + + static PathContainer EIGHTH_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.1) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-44, -20, -0.147), + new Pose(-39.7, 15.0, -0.151), + } + )) + .build(); + + static PathContainer NINTH_MOVE = new PathContainer.PathContainerBuilder() + .setIncrement(0.1) + .addCurve(new BezierCurve( + new Pose[]{ + new Pose(-39.7, 15.0, -0.847), + new Pose(-15.5, -4.08, -0.847), + } + )) + .build(); + public static PathFollower getPathFollower(PathState state) { // TODO: create secondary PathFollower pathFollower = new PathFollower.PathFollowerBuilder( From 3107e876feb678650d7b1cb0ac8f832def1fa90b Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 15 Jan 2026 21:06:11 -0800 Subject: [PATCH 16/25] done today --- .../org/firstinspires/ftc/teamcode/autonomous/BlueFar.java | 5 ++--- .../firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java | 6 +++--- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java index b804121..3297aba 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java @@ -43,7 +43,8 @@ public void nextState() { tracker.update(); pathFollower.update(); - mecanumController.setIsStatic(tracker.getRobotVelocity().getMagnitude() < 1.0); + double distanceToEndpoint = Pose.dist(tracker.getCurrentPosition(), pathFollower.getPathContainer().getEndpoint()); + mecanumController.setIsStatic(distanceToEndpoint > 0.3 && tracker.getRobotVelocity().getMagnitude() < 0.5); feederSubsystem.update(); hoodSubsystem.update(); @@ -52,7 +53,6 @@ public void nextState() { outtakeSubsystem.update(); } - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); state = SECOND_PATH; @@ -70,7 +70,6 @@ public void nextState() { pathFollower = BlueFarPaths.getPathFollower(state, 0.2); break; case THIRD_PATH: - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); state = FOURTH_PATH; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java index 64c8161..f88349a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java @@ -54,12 +54,12 @@ PathContainer getPath() { .addCurve(new BezierCurve( new Pose[]{ new Pose(-14.711, -7.6111, Math.toRadians(0)), - new Pose(-9.37, -24, Math.toRadians(0)) + new Pose(-9.37, -30, Math.toRadians(0)) } )) .addCurve(new BezierCurve( new Pose[]{ - new Pose(-9.37, -27, -0.23), + new Pose(-9.37, -30, -0.23), new Pose(-66.21, -7.83, -0.23) } )) @@ -70,7 +70,7 @@ PathContainer getPath() { .addCurve(new BezierCurve( new Pose[]{ new Pose(-66.21, -7.83, -0.23), - new Pose(-58.21, 19.41, -0.23) + new Pose(-58.21, 22, -0.23) } )) .build(); From dc6f384450fa5aaa5eae1f75ccbc9d6cda4f21cf Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Sat, 17 Jan 2026 11:08:06 -0800 Subject: [PATCH 17/25] teleop changes --- .../firstinspires/ftc/teamcode/FieldOriented.java | 12 ++++++++++++ .../firstinspires/ftc/teamcode/PestoFTCConfig.java | 4 ++++ 2 files changed, 16 insertions(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java index be79dd2..8f97685 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java @@ -27,6 +27,8 @@ public void runOpMode() { boolean rotationLocked = false; double angle = 0.0; + boolean usingOdometry = true; + super.initialize(); waitForStart(); @@ -41,6 +43,14 @@ public void runOpMode() { boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; mecanumController.setIsStatic(isStatic); + if (gamepadInterface1.isKeyDown(GamepadKey.Y)) { + usingOdometry = !usingOdometry; + if (usingOdometry) + teleOpController.useTrackerIMU(tracker); + else + teleOpController.useIMU(); + } + if (gamepadInterface1.isKeyDown(GamepadKey.B)) { braking = !braking; mecanumController.setZeroPowerBehavior(braking ? DcMotor.ZeroPowerBehavior.BRAKE : DcMotor.ZeroPowerBehavior.FLOAT); @@ -172,6 +182,8 @@ public void runOpMode() { telemetry.addData("x", tracker.getCurrentPosition().getX()); telemetry.addData("y", tracker.getCurrentPosition().getY()); telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.addData("teleop r", teleOpController.getHeading()); + telemetry.addData("using odometry", !usingOdometry); telemetry.addData("target", intakeSubsystem.dropdownTarget); telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); telemetry.update(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 408c84b..89e964a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -1,6 +1,7 @@ package org.firstinspires.ftc.teamcode; import com.acmerobotics.dashboard.config.Config; +import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; @@ -131,6 +132,9 @@ public static void initialize(HardwareMap hardwareMap) { .build(); TeleOpController teleOpController = new TeleOpController(driveController, hardwareMap); + + teleOpController.configureIMU(new RevHubOrientationOnRobot(RevHubOrientationOnRobot.LogoFacingDirection.RIGHT, RevHubOrientationOnRobot.UsbFacingDirection.UP)); + teleOpController.useTrackerIMU(tracker); teleOpController.setSpeedController(gamepad -> gamepad.left_bumper ? 0.6 : 1.0); From b3efff9388d8c89b4ada6660d2e628f73b81e42b Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Sun, 18 Jan 2026 01:56:46 -0800 Subject: [PATCH 18/25] new twot --- .../ftc/teamcode/PestoFTCConfig.java | 2 - .../ftc/teamcode/TWOTLateralTuner.java | 230 ++++++++++++++++++ .../ftc/teamcode/TWOTLocalizer.java | 72 ++++++ .../ftc/teamcode/TWOTRotationTuner.java | 172 +++++++++++++ .../ftc/teamcode/TWOTTranslationalTuner.java | 229 +++++++++++++++++ build.dependencies.gradle | 8 +- libs/PestoCore-release.aar | Bin 96021 -> 100145 bytes 7 files changed, 708 insertions(+), 5 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 89e964a..e0e3b2e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -77,8 +77,6 @@ public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); Cerebrum.initialize(); - MotorCortex.getMotor("3"); - MecanumController driveController = new MecanumController( MotorCortex.getMotor("frontLeft"), MotorCortex.getMotor("frontRight"), diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java new file mode 100644 index 0000000..e7512c2 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java @@ -0,0 +1,230 @@ +package org.firstinspires.ftc.teamcode; + +import com.acmerobotics.dashboard.PestoDashCore; +import com.acmerobotics.dashboard.config.variable.DataItem; +import com.acmerobotics.dashboard.config.variable.QualitativeSelector; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.shprobotics.pestocore.drivebases.trackers.TWOT; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; +import com.shprobotics.pestocore.processing.PestoTelemetry; + +import org.ejml.simple.SimpleMatrix; + +import java.util.ArrayList; + +@TeleOp(name = "TWOT Lateral Tuner") +public class TWOTLateralTuner extends LinearOpMode { + double distance = 24.5; + + @Override + public void runOpMode() { + FrontalLobe.initialize(hardwareMap); + PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; + + QualitativeSelector recordingSelector = new QualitativeSelector("recording?", "no", new String[]{"no", "yes"}); + pestoTelemetry.addToDash(recordingSelector); + pestoTelemetry.update(); + + TWOT tracker = new TWOT.TrackerBuilder( + hardwareMap, + 505.3169, + new SimpleMatrix(new double[][]{ + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + }), + new SimpleMatrix(new double[][]{ + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + }), + new SimpleMatrix(new double[][]{ + new double[]{-0.11201892953178422}, + new double[]{-0.0034454197797296054}, + new double[]{0.11231265526595093}, + }), + "backLeft", + "frontLeft", + "backRight", + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE + ) + .build(); + + telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); + telemetry.addLine("1. Press a to start recording"); + telemetry.addLine("2. Push the robot " + distance + " inches right (no vertical movement)"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m11, m21, m31, m41, m51, m61"); + telemetry.update(); + + ArrayList T_arr = new ArrayList<>(); + + double m11 = 0.0; + double m21 = 0.0; + double m31 = 0.0; + double m41 = 0.0; + double m51 = 0.0; + double m61 = 0.0; + + waitForStart(); + + tracker.reset(); + while (opModeIsActive() && !isStopRequested()) { + while (opModeIsActive() && !isStopRequested() && !gamepad1.a) { + pestoTelemetry.update(); + + DataItem item = PestoDashCore.getItem(recordingSelector.getId()); + + if (item != null && item.getValue() != null) { + String selection = (String) item.getValue(); + if (selection.equals("yes")) + break; + } + + telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); + telemetry.addLine("1. Press a to start recording"); + telemetry.addLine("2. Push the robot " + distance + " inches right (no vertical movement)"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m11, m21, m31, m41, m51, m61"); + telemetry.addLine(); + telemetry.addLine("Waiting for A"); + telemetry.addLine(); + telemetry.addData("m11", m11); + telemetry.addData("m21", m21); + telemetry.addData("m31", m31); + telemetry.addData("m41", m41); + telemetry.addData("m51", m51); + telemetry.addData("m61", m61); + telemetry.update(); + + pestoTelemetry.clear(); + pestoTelemetry.addToDash("m11", m11); + pestoTelemetry.addToDash("m21", m21); + pestoTelemetry.addToDash("m31", m31); + pestoTelemetry.addToDash("m41", m41); + pestoTelemetry.addToDash("m51", m51); + pestoTelemetry.addToDash("m61", m61); + } + + double TdLCos = 0.0; + double TdLSin = 0.0; + double TdCCos = 0.0; + double TdCSin = 0.0; + double TdRCos = 0.0; + double TdRSin = 0.0; + + double field_x = 0.0; + double field_y = 0.0; + double heading = 0.0; + + MotorCortex.update(); + tracker.reset(); + tracker.leftOdometry.getInchesTravelled(); + tracker.centerOdometry.getInchesTravelled(); + tracker.rightOdometry.getInchesTravelled(); + + while (opModeIsActive() && !isStopRequested() && !gamepad1.b) { + pestoTelemetry.update(); + + DataItem item = PestoDashCore.getItem(recordingSelector.getId()); + + if (item != null && item.getValue() != null) { + String selection = (String) item.getValue(); + if (selection.equals("no")) + break; + } + + MotorCortex.update(); + + double dL = tracker.leftOdometry.getInchesTravelled(); + double dC = tracker.centerOdometry.getInchesTravelled(); + double dR = tracker.rightOdometry.getInchesTravelled(); + + SimpleMatrix r_inputs = new SimpleMatrix(new double[][]{ + new double[]{dL, dC, dR} + }); + + double r = r_inputs.mult(tracker.ODOMETRY_PARAMETERS_R).toArray2()[0][0]; + + double cos = Math.cos(heading); + double sin = Math.sin(heading); + + SimpleMatrix xy_inputs = new SimpleMatrix(new double[][]{ + new double[]{ + dL * cos, + dL * sin, + dC * cos, + dC * sin, + dR * cos, + dR * sin + } + }); + + double x = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_X).toArray2()[0][0]; + double y = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_Y).toArray2()[0][0]; + + field_x += x; + field_y += y; + heading += r; + + TdLCos += (dL * cos); + TdLSin += (dL * sin); + TdCCos += (dC * cos); + TdCSin += (dC * sin); + TdRCos += (dR * cos); + TdRSin += (dR * sin); + + telemetry.addLine("1. Recording!"); + telemetry.addLine(); + telemetry.addLine("2. Push the robot " + distance + " inches right (no vertical movement)"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m11, m21, m31, m41, m51, m61"); + + telemetry.update(); + + pestoTelemetry.clear(); + pestoTelemetry.addToDash("X", field_x); + pestoTelemetry.addToDash("Y", field_y); + pestoTelemetry.addToDash("R", heading); + } + + T_arr.add(new double[]{TdLCos, TdLSin, TdCCos, TdCSin, TdRCos, TdRSin}); + SimpleMatrix T_matrix = new SimpleMatrix(T_arr.size(), 6); + + SimpleMatrix translations = new SimpleMatrix(T_arr.size(), 1); + translations.fill(distance); + + for (int i = 0; i < T_arr.size(); i++) { + T_matrix.setRow(i, new SimpleMatrix(T_arr.get(i))); + } + + SimpleMatrix translational_parameters = T_matrix.pseudoInverse().mult(translations); + + m11 = translational_parameters.get(0, 0); + m21 = translational_parameters.get(1, 0); + m31 = translational_parameters.get(2, 0); + m41 = translational_parameters.get(3, 0); + m51 = translational_parameters.get(4, 0); + m61 = translational_parameters.get(5, 0); + + tracker.ODOMETRY_PARAMETERS_X.set(0, 0, m11); + tracker.ODOMETRY_PARAMETERS_X.set(1, 0, m21); + tracker.ODOMETRY_PARAMETERS_X.set(2, 0, m31); + tracker.ODOMETRY_PARAMETERS_X.set(3, 0, m41); + tracker.ODOMETRY_PARAMETERS_X.set(4, 0, m51); + tracker.ODOMETRY_PARAMETERS_X.set(5, 0, m61); + + } + } +}; \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java new file mode 100644 index 0000000..1e2ffab --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java @@ -0,0 +1,72 @@ +package org.firstinspires.ftc.teamcode; + +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.shprobotics.pestocore.drivebases.trackers.TWOT; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; +import com.shprobotics.pestocore.processing.PestoTelemetry; + +import org.ejml.simple.SimpleMatrix; + +@TeleOp(name = "TWOT Localizer") +public class TWOTLocalizer extends LinearOpMode { + @Override + public void runOpMode() { + FrontalLobe.initialize(hardwareMap); + PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; + + TWOT tracker = new TWOT.TrackerBuilder( + hardwareMap, + 505.3169, + new SimpleMatrix(new double[][]{ + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + }), + new SimpleMatrix(new double[][]{ + new double[]{-3.403336515717541}, + new double[]{1.2699958957478223}, + new double[]{1.3460775162359155}, + new double[]{-1.0179996295954816}, + new double[]{4.3829921388933}, + new double[]{3.4734383975380965}, + }), + new SimpleMatrix(new double[][]{ + new double[]{-0.11201892953178422}, + new double[]{-0.0034454197797296054}, + new double[]{0.11231265526595093}, + }), + "backLeft", + "frontLeft", + "backRight", + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE + ) + .build(); + + waitForStart(); + + tracker.reset(); + while (opModeIsActive() && !isStopRequested()) { + MotorCortex.update(); + tracker.update(); + + telemetry.addData("X", tracker.getCurrentPosition().getX()); + telemetry.addData("Y", tracker.getCurrentPosition().getY()); + telemetry.addData("R", tracker.getCurrentPosition().getHeadingRadians()); + telemetry.update(); + + pestoTelemetry.clear(); + pestoTelemetry.addToDash("X", tracker.getCurrentPosition().getX()); + pestoTelemetry.addToDash("Y", tracker.getCurrentPosition().getY()); + pestoTelemetry.addToDash("R", tracker.getCurrentPosition().getHeadingRadians()); + pestoTelemetry.update(); + } + } +}; \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java new file mode 100644 index 0000000..01d0945 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java @@ -0,0 +1,172 @@ +package org.firstinspires.ftc.teamcode; + +import com.acmerobotics.dashboard.PestoDashCore; +import com.acmerobotics.dashboard.config.variable.DataItem; +import com.acmerobotics.dashboard.config.variable.QualitativeSelector; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.shprobotics.pestocore.drivebases.trackers.Odometry; +import com.shprobotics.pestocore.drivebases.trackers.TWOT; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; +import com.shprobotics.pestocore.processing.PestoTelemetry; + +import org.ejml.simple.SimpleMatrix; + +import java.util.ArrayList; + +@TeleOp(name = "TWOT Rotation Tuner") +public class TWOTRotationTuner extends LinearOpMode { + @Override + public void runOpMode() { + FrontalLobe.initialize(hardwareMap); + PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; + + QualitativeSelector recordingSelector = new QualitativeSelector("recording?", "no", new String[]{"no", "yes"}); + pestoTelemetry.addToDash(recordingSelector); + pestoTelemetry.update(); + + TWOT tracker = new TWOT.TrackerBuilder( + hardwareMap, + 505.3169, + new SimpleMatrix(new double[][]{ + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + }), + new SimpleMatrix(new double[][]{ + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + }), + new SimpleMatrix(new double[][]{ + new double[]{-0.11201892953178422}, + new double[]{-0.0034454197797296054}, + new double[]{0.11231265526595093}, + }), + "backLeft", + "frontLeft", + "backRight", + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE + ).build(); + + Odometry left = tracker.leftOdometry; + Odometry right = tracker.rightOdometry; + Odometry center = tracker.centerOdometry; + + telemetry.addLine("1. Press a to start recording"); + telemetry.addLine("2. Rotate the robot 180 degrees"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m13, m23, m33"); + telemetry.update(); + + FrontalLobe.pestoTelemetry.addToDash(new QualitativeSelector("recording?", "no", new String[]{"no", "yes"})); + FrontalLobe.pestoTelemetry.update(); + + ArrayList T_arr = new ArrayList<>(); + + double m13 = 0.0; + double m23 = 0.0; + double m33 = 0.0; + + waitForStart(); + + tracker.reset(); + while (opModeIsActive() && !isStopRequested()) { + while (opModeIsActive() && !isStopRequested() && !gamepad1.a) { + pestoTelemetry.update(); + + DataItem item = PestoDashCore.getItem(recordingSelector.getId()); + + if (item != null && item.getValue() != null) { + String selection = (String) item.getValue(); + if (selection.equals("yes")) + break; + } + + telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); + telemetry.addLine("1. Press a to start recording"); + telemetry.addLine("2. Rotate the robot 180 degrees"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m13, m23, m33"); + telemetry.addLine(); + telemetry.addLine("Waiting for A"); + telemetry.addLine(); + telemetry.addData("m13", m13); + telemetry.addData("m23", m23); + telemetry.addData("m33", m33); + telemetry.update(); + + pestoTelemetry.clear(); + pestoTelemetry.addToDash("m13", m13); + pestoTelemetry.addToDash("m23", m23); + pestoTelemetry.addToDash("m33", m33); + } + + double TdL = 0.0; + double TdC = 0.0; + double TdR = 0.0; + + double R = 0.0; + + while (opModeIsActive() && !isStopRequested() && !gamepad1.b) { + pestoTelemetry.update(); + + DataItem item = PestoDashCore.getItem(recordingSelector.getId()); + + if (item != null && item.getValue() != null) { + String selection = (String) item.getValue(); + if (selection.equals("no")) + break; + } + + MotorCortex.update(); + + double dL = left.getInchesTravelled(); + double dC = center.getInchesTravelled(); + double dR = right.getInchesTravelled(); + + TdL += dL; + TdC += dC; + TdR += dR; + + R += (dL * m13) + (dC * m23) + (dR * m33); + + telemetry.addLine("1. Recording!"); + telemetry.addLine(); + telemetry.addLine("2. Rotate the robot 180 degrees"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m13, m23, m33"); + telemetry.update(); + + pestoTelemetry.clear(); + pestoTelemetry.addToDash("r", R); + } + + T_arr.add(new double[]{TdL, TdC, TdR}); + SimpleMatrix T_matrix = new SimpleMatrix(T_arr.size(), 3); + + SimpleMatrix rotations = new SimpleMatrix(T_arr.size(), 1); + rotations.fill(Math.PI); + + for (int i = 0; i < T_arr.size(); i++) { + T_matrix.setRow(i, new SimpleMatrix(T_arr.get(i))); + } + + SimpleMatrix rotation_parameters = T_matrix.pseudoInverse().mult(rotations); + + m13 = rotation_parameters.get(0, 0); + m23 = rotation_parameters.get(1, 0); + m33 = rotation_parameters.get(2, 0); + } + } +}; \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java new file mode 100644 index 0000000..1a6701f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java @@ -0,0 +1,229 @@ +package org.firstinspires.ftc.teamcode; + +import com.acmerobotics.dashboard.PestoDashCore; +import com.acmerobotics.dashboard.config.variable.DataItem; +import com.acmerobotics.dashboard.config.variable.QualitativeSelector; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.shprobotics.pestocore.drivebases.trackers.TWOT; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; +import com.shprobotics.pestocore.processing.PestoTelemetry; + +import org.ejml.simple.SimpleMatrix; + +import java.util.ArrayList; + +@TeleOp(name = "TWOT Translational Tuner") +public class TWOTTranslationalTuner extends LinearOpMode { + double distance = 24.5; + + @Override + public void runOpMode() { + FrontalLobe.initialize(hardwareMap); + PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; + + QualitativeSelector recordingSelector = new QualitativeSelector("recording?", "no", new String[]{"no", "yes"}); + pestoTelemetry.addToDash(recordingSelector); + pestoTelemetry.update(); + + TWOT tracker = new TWOT.TrackerBuilder( + hardwareMap, + 505.3169, + new SimpleMatrix(new double[][]{ + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + }), + new SimpleMatrix(new double[][]{ + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + new double[]{0.0}, + }), + new SimpleMatrix(new double[][]{ + new double[]{-0.11201892953178422}, + new double[]{-0.0034454197797296054}, + new double[]{0.11231265526595093}, + }), + "backLeft", + "frontLeft", + "backRight", + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE, + DcMotorSimple.Direction.REVERSE + ) + .build(); + + telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); + telemetry.addLine("1. Press a to start recording"); + telemetry.addLine("2. Push the robot " + distance + " inches forward (no horizontal movement)"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m12, m22, m32, m42, m52, m62"); + telemetry.update(); + + ArrayList T_arr = new ArrayList<>(); + + double m12 = 0.0; + double m22 = 0.0; + double m32 = 0.0; + double m42 = 0.0; + double m52 = 0.0; + double m62 = 0.0; + + waitForStart(); + + tracker.reset(); + while (opModeIsActive() && !isStopRequested()) { + while (opModeIsActive() && !isStopRequested() && !gamepad1.a) { + pestoTelemetry.update(); + + DataItem item = PestoDashCore.getItem(recordingSelector.getId()); + + if (item != null && item.getValue() != null) { + String selection = (String) item.getValue(); + if (selection.equals("yes")) + break; + } + + telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); + telemetry.addLine("1. Press a to start recording"); + telemetry.addLine("2. Push the robot " + distance + " inches forward (no horizontal movement)"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m12, m22, m32, m42, m52, m62"); + telemetry.addLine(); + telemetry.addLine("Waiting for A"); + telemetry.addLine(); + telemetry.addData("m12", m12); + telemetry.addData("m22", m22); + telemetry.addData("m32", m32); + telemetry.addData("m42", m42); + telemetry.addData("m52", m52); + telemetry.addData("m62", m62); + telemetry.update(); + + pestoTelemetry.clear(); + pestoTelemetry.addToDash("m12", m12); + pestoTelemetry.addToDash("m22", m22); + pestoTelemetry.addToDash("m32", m32); + pestoTelemetry.addToDash("m42", m42); + pestoTelemetry.addToDash("m52", m52); + pestoTelemetry.addToDash("m62", m62); + } + + double TdLCos = 0.0; + double TdLSin = 0.0; + double TdCCos = 0.0; + double TdCSin = 0.0; + double TdRCos = 0.0; + double TdRSin = 0.0; + + double field_x = 0.0; + double field_y = 0.0; + double heading = 0.0; + + MotorCortex.update(); + tracker.reset(); + tracker.leftOdometry.getInchesTravelled(); + tracker.centerOdometry.getInchesTravelled(); + tracker.rightOdometry.getInchesTravelled(); + + while (opModeIsActive() && !isStopRequested() && !gamepad1.b) { + pestoTelemetry.update(); + + DataItem item = PestoDashCore.getItem(recordingSelector.getId()); + + if (item != null && item.getValue() != null) { + String selection = (String) item.getValue(); + if (selection.equals("no")) + break; + } + + MotorCortex.update(); + + double dL = tracker.leftOdometry.getInchesTravelled(); + double dC = tracker.centerOdometry.getInchesTravelled(); + double dR = tracker.rightOdometry.getInchesTravelled(); + + SimpleMatrix r_inputs = new SimpleMatrix(new double[][]{ + new double[]{dL, dC, dR} + }); + + double r = r_inputs.mult(tracker.ODOMETRY_PARAMETERS_R).toArray2()[0][0]; + + double cos = Math.cos(heading); + double sin = Math.sin(heading); + + SimpleMatrix xy_inputs = new SimpleMatrix(new double[][]{ + new double[]{ + dL * cos, + dL * sin, + dC * cos, + dC * sin, + dR * cos, + dR * sin + } + }); + + double x = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_X).toArray2()[0][0]; + double y = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_Y).toArray2()[0][0]; + + field_x += x; + field_y += y; + heading += r; + + TdLCos += (dL * cos); + TdLSin += (dL * sin); + TdCCos += (dC * cos); + TdCSin += (dC * sin); + TdRCos += (dR * cos); + TdRSin += (dR * sin); + + telemetry.addLine("1. Recording!"); + telemetry.addLine(); + telemetry.addLine("2. Push the robot " + distance + " inches forward (no horizontal movement)"); + telemetry.addLine("3. Press b to stop recording"); + telemetry.addLine("4. Repeat to get Matrix Values m12, m22, m32, m42, m52, m62"); + + telemetry.update(); + + pestoTelemetry.clear(); + pestoTelemetry.addToDash("X", field_x); + pestoTelemetry.addToDash("Y", field_y); + pestoTelemetry.addToDash("R", heading); + } + + T_arr.add(new double[]{TdLCos, TdLSin, TdCCos, TdCSin, TdRCos, TdRSin}); + SimpleMatrix T_matrix = new SimpleMatrix(T_arr.size(), 6); + + SimpleMatrix translations = new SimpleMatrix(T_arr.size(), 1); + translations.fill(distance); + + for (int i = 0; i < T_arr.size(); i++) { + T_matrix.setRow(i, new SimpleMatrix(T_arr.get(i))); + } + + SimpleMatrix translational_parameters = T_matrix.pseudoInverse().mult(translations); + + m12 = translational_parameters.get(0, 0); + m22 = translational_parameters.get(1, 0); + m32 = translational_parameters.get(2, 0); + m42 = translational_parameters.get(3, 0); + m52 = translational_parameters.get(4, 0); + m62 = translational_parameters.get(5, 0); + + tracker.ODOMETRY_PARAMETERS_Y.set(0, 0, m12); + tracker.ODOMETRY_PARAMETERS_Y.set(1, 0, m22); + tracker.ODOMETRY_PARAMETERS_Y.set(2, 0, m32); + tracker.ODOMETRY_PARAMETERS_Y.set(3, 0, m42); + tracker.ODOMETRY_PARAMETERS_Y.set(4, 0, m52); + tracker.ODOMETRY_PARAMETERS_Y.set(5, 0, m62); + } + } +}; \ No newline at end of file diff --git a/build.dependencies.gradle b/build.dependencies.gradle index b9793d3..5a262cc 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -28,9 +28,11 @@ dependencies { implementation 'org.firstinspires.ftc:Vision:11.0.0' implementation 'androidx.appcompat:appcompat:1.2.0' - implementation 'com.pedropathing:ftc:2.0.4' - implementation 'com.pedropathing:telemetry:1.0.0' - implementation 'com.bylazar:fullpanels:1.0.9' +// implementation 'com.pedropathing:ftc:2.0.4' +// implementation 'com.pedropathing:telemetry:1.0.0' +// implementation 'com.bylazar:fullpanels:1.0.9' + + implementation 'org.ejml:ejml-all:0.43' implementation "dev.frozenmilk.sinister:Sloth:0.2.4" } diff --git a/libs/PestoCore-release.aar b/libs/PestoCore-release.aar index a8607363ff02b6f7578818595a0e38b240ee4984..7cd163980a68f4e7987ae6e6a378b2ea657602f5 100644 GIT binary patch delta 79127 zcmV(nK=Qwp?gg=q2C%JBe*h7)Fq|_104-Pn01E&B0Ap-nb8}^LE^1+Nth-}yX5rc; zoOEnHv6GH%+qOFP6Wi$6wr$&H$F^;!!%n8>oHJ8(PJK1syi@P4egC+w+P|)~_PW+B zMHw(~kiQQ!2r)GAHv}XJeFabukjuY==5N;6&W6Fs!rsx&$j%vPf9%9yZ|dZ1XKd$a z${_3lv^Ej3vo!;n(;HhGIypthPsk4lqKAC#&65NW>CH9YHRLflgfap1QH{k0==u@T zQ&2*Z5YL969ZmNKpl9#I1o@3shPlz2@_M!oWU*W zoXa&!cui-;3AP^-e<0aG&zql!0Js9sBxsuqS{{Sxgs;KZ6Cm>KgJxJs_pghHyUh8& zkFm=c&yo-+fQwN<5(LFH#zYymvg6lcGW=!>n)K zPdL0{s~N)$|02^%RBa0KzZ}LLvr=xLC`<^0{cTG7fxZh8`pdOaYH5x`@!xQf(?ptu z|BFfb-@*ESf5gSm+T6|&=xkx*#PAm#Cuc)jXQzJxl&r|7Fvy6`TMEobiA(uL3Wm$L z2yd-QD<+EqpLZQokE0=_vqt|_dH!>#4{29|SWj5ZET!|=<>qXA<$09iCvFxZa^8YS zT3%$BVH3JtKx%>BZK-#8k$G52$MR=PzLNvj4XJo7&HO&(i!*@H>XMDu~qR8GU-P(g@3}Lp}C_TI09a;dix>^!S1-xXMg# z4S1h?DfjF@H~VxVyvaw?{kv;b)v8DxYiZY^6elc}HfsKYK+Mt{f zD>_mMHB3o()~4;KtKk`IeA;P7Zta8yOu5j@vD7vQ$N7rZt%_6$anwXZ$`9is+|=hd{#V;N&wX+MYU zN720GS8*lhFye25r+G$bsq?jA z&?nC0fw_<#{oipgfzLQn;}GY+VOA;9LepxGce+GcwB6qc&~}(!Kfr@?U7xVTe|Y?& z(n%3|We@NSLEdc0+QaZ_;svA0QXbQpl_+>LK)aRAu#P}H$Ue)!(Xd6fG+gKFvk{C~ zGT_Ezbg?kyEap&uQHi2Lm?#x3C1Etl*A553Pmms3M#<)q9yJYPqvqn17D)tMw4tEs zDXJ!G*Z1aWZqb#M%M4D|Jdf3&e>HtNh)!MDrj)Nj;Lv1r6&WWhu~3(to5`x&vEd~5 za$jmr5hpk%D8riXHX+i-Xvq!t!P~|FCYpv+sU83ip^S-yajg7 zLv%jg?+pJ=aW{6xYV*JG8Wac!{r@e+6{SS~N$hO39}2kU$b44D4D41!e?iEp!ld*t zzY~Ungq1Oc7lx260!#l0oH zMCa)f(SF~|el-0-5vOS4`(>#fXyO7-!otL;{} zo{-Zn6{imfggsSHo)GyVf9D|t=lb50Wdj45&}of8A(YANTYX{ZQF0 z4P*x(E0+V4i5$0_E^1DAY;6YjsckV4bWmG0hb>!qj)dBD(LByTKnGHophWt4-_}w>57d=Y9ustDp2*D!;2N*Fk=d@ps#By#NiC_M-2WyX3Kr zXL~x#&hV+#+G_5mi$s{8O?87)H{H0$Ylj*^^qVoPI6gxcf2M03&`ZhoQ!?aG{*o|C zxMu8E*QZWoS96X`w)U$&Tgl9l>Yjb%?Id3~`$0gsI@7m!Z9as-1Poh=oh!>a!71ss z@S5hodp^rreXJJtSgL@E8sgY0(Wpx&VaTp}sbGa9RaFRki*eH7`osJ53$L zgD|kIuV|DhN-C#B^O9Da>V%1QK4Vm@ifP;g9c_?%e_N%nry^{2QK}5OGBJ+$yMuT@ z0{?ELI|56lKk24LX^o@p$undkzm&tzJ;4ZCX#GS^k)9Avg9PDsr$HfD9QHbFZxjEy z`P?!tDOdT~{c&!wNh?^xyek(SQB{}dudMpu=h*szinOv@fqT0uY@?|ja4T8UGDF-6 z8`>!&e|$b~o}_(>7{*?_#jNPMQr^t(zv=jt#?QM>rMk1C(|KZ<(vsdq+XZV9>Py>( zH^y2847jl`j#JRjA%|0pW^#qjAXQH9TJLZ*JgES}B=xw`UUAj~;tT|+~&gLOe zQq!Zpcf$S>-7`1CRez!{n`}fM$J^jm*tS!~e`sAz+-Rb082Ns0k11BQ`x8Y!F;wDm z?D_Cs!jTBi#@<%*50gY_l1OJ{=!;@_3DS?wA{o_$-aL2f06&)t7`9%U#CMf$(-2F(9oS2i(q1sa<=F-RENnA#hf ze@NN>?Z{?^#-{&EymU3tB(Qu#$Y^0Ajfg0TFd~!5imH@9%JPA9C~^p42uA(OuB-4S zQVp5cw#e7-6rLNncAhb%CkAz%F{2lsp?bds9v>f*dKyP0RW^|AT+MRRpFMJ)jm>;t zFV37m7AS*fL36+LMu2c*dvd&DtVnNef6m%g+rVy_o@O!04$3jT6x1IPbs(!EE6*V$ z8%np1XQ-5|E@vF!bQG!u9cXu$!qG9b!0U3ZyXav6a%R$M>Q>t6v67-wkws`}u6nEQ zQKL<#jPIi0Hm3!4S<8P=0PqY?ABNO)3yXA{ZF&;f@Hm19UWzJ=sRvGtZ!w2se+H3% z^%y!a2SG!k<7qg23xp3Bndqf*r9}JDr3w)B<;UqvwHZx$L}Jmg7%hsgBLWgAIl$g9 zf+LvEVZ@M9dXPeq=+tI(SZS89Yvd{xiEz?IzR?d_Jo>ecq?n@4l({3Bmyh!*9L9J2 z@|Tw!Q9tS_i@@54*M&Sgs4-=Me-|}|!ZSH{Z@`7=sx?p!4sn9t^Rvs>qqH{{vhLJ# ztCo(W0uUNxoLhL>f6-hAN}JeYs_6`vQcE`{oX|I`k$9fkCivj>0{~K!apt7GQ+>?L z9Z3lPg*)Ka$Q)x38EQ#d7>WhpB`-9szVK|zfv(=rpA?1z5%kANfWbn6?P zIJ8!S+4v0pt}Uy0cs{Pwe~V!cy*p9Lmk`5`INdyhXd$ZyJQf|#iJRrzz>BMs-c#@Qt8Bj_OOx!&$^|_`sUMqD!8v5}CF@f@H*w&@+cT zEzRvQgSLbGi6;3`kkm7;)HsUU!o(4)JHEP?A!Eur^HZ(0!MV{>f1iNQ*P(}`n*xD- z!dFn^@G!q~X`-IUZF4MbZ1~IlLjrLttj_oBT)xe(Ckm4LJ-D}=0O1{55)G6gl*d9$ z2RxC85!PQ?`AbUcxTVQzo1{Wyp!)kXeVI~c@XtVBJp6Z2OvTyaT`Pzzrd_v=@8vL( zuM?ClNAFSxZHwxIf9|gP=CX|5v1qJZGq>MF9$>UpEZc7Fzgkzg2aAxg`WRoa3r|jI zA^B{;L^);4wS%vVow{nSdN9>SbCqTHk)q5f3(8XvvTDWx~LS#vlT8NuW@_+lHlMLsUdTpNP^v{+l4)n@{BB?2o6+hq%Oo+-nNY)k}>u8r}`ADL%FN006qy5p2%L;eR&zZR=_vFgS24SzK@u3 zLCeMyGkI6Pf79|=`&X4pDnwm7$C2A~Y($lu*{&A>1EE2ag5tzbGp@H-x4cTcO1VzX zwbW-3{1yr$F_c|} zFSY8G=)i-iWrwhVO;bO|j~oEmD~Rw7r)dcXLwrVJe{1?aPf&84XRQK&Jl~O3?dcB* ze5z+t?=zukGMhMO`(x!vzcG2~?k{dOn6S0p?JL5tfCfPx4JolwlX!{lUp{%Bu+(L}M%m>Ej_;0yx7O%QiE#9H}tF;9! zo3a|%a0|$GuUZw~yUx%fOk~h3>Qd39TGbL6f7!C96Ij=Ne4~ha)qry@kP$I3WzKfi z0H)3ARA1VzO&99Z)FEE5y(EPHY2xchzrbii#{~{2w$o|xq&A{8wG_j9aHL0Ej+Y+T z&Pz!wdmya)X4Yv*#P(rysSfhy^w8X^N7!?cP$*4r#U;yKHkR$l5mX0V93F@?lwU!U ze}?GcZ@AmGEYx6KIh7t1S<_6Bt|@Vu#HQ}_>f|BuSgbYv>L+f^73bo#FsHid==(lu zx7&-$b$Rsd4<5Pl?;1yR9$J6U>n^SN6N|0qN2EjD6{$uZVuMDns>SRxd~__MTFP*! z`@wYO<*jdCt4cJcg&%c-86JE>fj2Yee`yoYI{iA5jZaskrbx)A~9MTi81tUcbE{eOzr52O!ALu`tuiMuo0#OCfBBZM;{HxF&!WR<>L- z2l7q?GKeK~9J$3RJrCA}I@o-piL*7UiM)x;UH8<`J-V6H7IIFcv} zRUm2A8%7$B9|>B>4uuBWimHNDt1)%B>6j4)P0mPqE>& z1x3PH_cQ?yYBC>1aPve&r+i9;-j#jvll#%yy=XC#b=`b;QnpnD_jHc8xC4_wYTV2i zoKp(FhpUZDbL)h3v60k@e=Wx?zNZSChJX}$EqX=|MVpSV!Y*qJE~oquQrb&?pYi+~ z(+>d@cU5fxp)P6&f zytuLcBeLrY{1aL22bYz!?6>Brz02QX;U>7i>W?;mUoWO`=2ZkRe~`iC3^{P-aVuSL zRqrXj%&G}yo8&8fT4KvL99a`7S5FP#SueA@a?a1dPkiM=LJr|YCt!EC@LWCJBSR|n z;jeO!?7 z_vI4FsCmW7$zOh5h$$#^c|)lJW?u>fAcTfJ{gV9v2Psh*!FDd6DXO1L&@zwD?Up!{ zY#%nJbKun$xTf~YOy3BnivB7?Ikwr2Hew;e*@EBlgZtoTNUtSXD~d3QE;eaP{j_2nIi01vfic}q<j@e@%Mp64ozW6ew7{(KxkAev?Rk)1Z1ZEdFFF{%nTzkt`ReUeqt2g-U+= zF`;%Xt)=j@XwIIYiC-VIM>DqBm2v)R30Ap@m&(Glca}u1Pf0H}+a-Maz;`?H{-b`-eo?j<4 z`%`^NIzCwZQr%NG4Ex%#^WUF-XJn9U?)_bqpY@Cnq%tig?MBm`*yJ5?_VJ zyd#dye(EV)?31Mq5Bux}qmBCizh834Pbl2*24 zkiZV1(hOZaF$Qr5;jOfvdTTmxA@v7P(Xun*e|A^2^5)zAROon7dbG?iUag<{qnD;N zhr0Ds$M#S4=9_u@Q?BEMA1R%UY`a<@MROjnZ3f1?Wiz*|FXX@5lUtW<*HthO5S_mk zh3CI$PyS<;RIDoHw4sXk)$JaCMJbh?K`W;MC5`(-iZq4(r-%hkBE3UuzYU^c$zAXJ0tGUnWqtkzH=EG&PBHebN|zN8|;(Kr%8@jo-SZ+d&5-}QSx zV0U@1O&EWs1++zgC%}&q+)L=Rwr$PYtq{NtnoH7Ww45<84Z#jSu_{Z_jFn*pjobIz zXLPilwPa-+WQLS>4m{uw0%5x83DQGue;+HmsC4x7(XuaE7_^bvh_U8N+)BUmDlB4` z&SHhRQ5|*w#>VTO*Op-=dImgt z)dYm+c#g|=nuQ-?`jNbl?G{AT0uuBl7;tCvAf10`B z&Eb;&Owj<4GSIV3$3Crk_Bm5_T_MdC6_tWU@|J}+xLemrPT$2LA2>@5go0x@JjW|s zdG%SbmDyXfJIz?YHznzN-HA=I7cVQ;>e_c~=W1h-tbQAb#XKyqw}x>%8I<+Ya(GmJ zrX?aHG^%pN`2ov^7*#l(Q-)nae_kR~N_oYpOXzHyGuh@kCV;f?g@DoBWp2B4<=7|( zzlBFEdbQ7m93^q%Zatpsnv?g?k~aY!VmP^$E$(NkdGEckX)<|W5Uj}E7-vX+#Y}W{ z<|e|pO5FgXm#DKn?ux5j3hLOi&iaL5!NeSL&t~PVz?C|eV3lS`{r6g#e=bFOTSk+N zkH!i{yiR#AnT%~V!=>V-rp{&AC15Ljz2!Kl>?8JSfHnD6H#(nm9u!cuhqxo2$H*d|7|mUC@ply2%nkp7VOK^nDfNV`l)*#9lAcl) zCLIz_SlBtkAu9O{UL;bPe|T{wA=X&D?fhQje1)#a=Kwbo^6`4nhQs_LZ;lJGgzZsO zrSt{Dq}-v6jNf=`6r4h`>F?ODpdTSD0tT+Q(jPoSfucw8SAh~a&asD0f4)qBGfYj< zC|4AdKIwy*@(RHeab(=`H|yZ)OyLL(_OkimiCz_rol9#kAgNT(f2IjD#CPEVi#rXp z`>-|OS$Do8B>v;G1r09y4Qw#!n+tgi%$X(zlTh)4+usYu;0b?2ocs<{c!sF`4PpKq zX#O5hyRQxY8OAR3iHj7PjOE+1p~@`FmgBO)EsK{{_>^8cthIXJ%InyPmt_iM)*Fo; z`|`PG@b}PKV<-3Of12_AW5aq{y2WX@Zg+*P*27c5yKLbJKD)K?1@iBLAsN1&^zk)hLH%`mpJb#}C~wl;Ni zVi5hGX_5b(_@{O(B~Hn22%?Mk%80-Ng%jDEU?AQ?RU7jff5TPP0F;)rWMl;-B=tX+ zhI-_p@D$P<20H6^LElJxA|vj~BBa-XF3*Ew|NJ_M8GU{`xyk$iLg#&3Cu$LDNj7O; zrKWG{U@?>?S0Y@jCCZ)SsE@-=q6#cgOQ>Tf89SJ!y;USqWjIoe5G?__>-PI)C~l#7 zBEg$xaa|#Me@3*-9;0Rn{r)-Z&~v#YN}fWxhv8<0SR7MR+zl;U`m{gCxtE>($K^Td zc0ynCD|X1cG-t1>l7zhJc>7`cjBE;DBhMBtt5KceJmZOjU>sP*x@YidiDa$O%Dg*? zAZ#~@hm!Ns=`T0+r)d}Jb+FQMd|eJL{}jp}F7*q%e>f-OG!E%tXnXMsyGG$v2W4CW zINp&cX&gE?NHcH((OVHpZg`{A;Pch{C>P*vLdt86#y?H9mNV1j7Q_J88m{OS2Y_i& z8;b?Juh17lb9%UD0amgE>;{ z=yqB&f8G8adSUzv5Xt`+=;cg}4Q*X){uBHo%`=T3qku02?HptzaApVa z?Vs!7aG9x`kk*)i_Fd3+4fXv}8=>w$ql!Xz&}6o(<+IzgGR%OPL%^+W+m3em0EYu| zdAHn82)@!kt4?ptgr4&6<=5GB3yH`wKeL*qf69@}t~b-$d%bQpO$q#7R(NheS7UbC zmB2H>JK>?S;E&9cVT!r(i$XGE;j`3?fsiLP?$kNkg9Z;!p5NQBzA@3QSw}^kt^Z7k z8I3w-T9UM4lGDfxRii5}d1|v{C0v4ELV&TQ?+EJOLkb1!p5E{ae9?eM8vm|3c54I> ze>oXohI)Dl;?Bb&V<{<~??{m>>zLat97$SqZ>qV4_IA_~LLhI-->=pcsBEmewAc-9fm6*@kA}Wk;)CH5aP6Bfs&DrikH&A)ACSkcwlIeFneG2WK35o}f0Tz* zd06)TCtioy`8)cc#f-5im9z5TmA|CnKvQQuMCZ%Xm6^r3&Q5}=?aA8HFDcAAD!*DKJdDPw7fG_zgZqEb|#E%dZWNN$Lhuv7j&hqgVg0Mk`$z=OPE*x z>`k_WMG@eYkQLhOwaJ%^G@}pJe|*oxil!JvJr}>Ig7H%wVZt+yleCRxmyFv;rFA^G zyF(W+j^HLfAoIkgmQwAlup*J+Swb--sZsJ+ZFFvTlF!6;(H19Ecvi!uB2dlFGz>Zj zVUAOT`krNYdz971(OLLog>5U^cU9*FT|{@af}ZV{1F0@c-n@dRvYHATe;u2&Wt|z^ z&Ih*d6zm}1XFJo#R5EfR6SS`wdaX|Ze<+ui=7?m9&w6wtR&rciJouKnmb_|g0zv+{ z?NBIHKg%=Tap$N>*1->(@t^%CAyKR&z#P?*Nos=Q>6|2{;lUB&iV)nBJ1!Wc33u>V zW_MWSP{XG@%h@R;ZN0rCf5%N^OO<}_tbF4&Izdk6UeFI<@X@{Bm+H@f_3iKTgCgEf zx9*ODOA5Dr#<${4X$hxlkDR%gvR}Uf9I_QHBkgslwQI=b3`JZPlERU_#K~Vs!~x_#ZG&oa=fQLkRS8+v}j7v@!sn1jI;gL zRElTH%<-Fu6ZFW1e+#Jk*vdhmUNgGr<4`ks&c&A>o+(`04_2O35lK*se}lT6@Ad$@pfJEtCO~_^ z$VGMYVgq|)YL*?O&%DTRhwQP#{TsJ}g=Sh-`iYBoasHwK8a{R|)dAwmy3pCGNs5(M8u8GMS|AZC-CvD_^N`(v<~B2RR5fGu*9{%mvr zB233PJ-OUUa7AwEj*v2pNly0O1@livABEgp>OLF!pATCeq8IqKcu_Sb4+MW^gg(Xm?p|v7@>2uBk^H} zYg$TQf52GxM2p^wEHZ^OMgk7GI6_|hst#`WRwT!$kg||)guXXp$`{L^)eynl8DMql z3Tw)iP*nn9a)-X(fT-zNUZU6B-&$Y)2}zJQXBR{4WW8^UXx0q9NM~s_&<>_Z^8E`-rG&4qGeNZ*h;c8za0WUl04Fu$Ok za&wSuSY3(4fwRV_IqvvdE6f6 zue`JIme|x_>yc57&+Cy$l2hEFh}c=Tl&=rRN4f>1#rax@Es8Mpcp^SZxNk0Uy*zt6(+`($E9j$f1nT)gOO zforqv`Qu2kO{2O6%@fH38Kui}>&ACHnLiOe6tU(_us6v%s0U;FzNBrQrL$4rf3}8R zn0ynI8cvyEYKgj^6N628d7#cE8V?l>SdX2Cw7*Z+oh)B2uiINOnR7Z?#dJA+&)S=; z=6aY;err?BRp{37*lw8Q64=#?`pFbs@@dM2PZIyb;#Hc_n)T~O! z%C9D)rx~*8 z_wcq61$Kio4sbWFs(XB0vHEi_RyckeN>6tG?lyyc%e>EFKtRZ_K|mz_U)-juskNzs z{ePOxZp~MH^b>qvy&C^56l5?^q;KJ)*8w%rBcdy0I2fXE(n2Uee>vt!#EH{}#`HBY zx%m>gn@+izH1_Vy94WbP(z3?uO;VZL&#$46rM_=nH;5Ar?z?wqqp>_U-Y3~7@7^=d zJYBClsd}JwfG@;6_#+%@XVn7fyw5ZyQ&AOhZfrhA*GcBaZ)!YOP1)TNdA#TZH9~Bb ztl-Yz`EZx)*}uv-f8rgonJBC>^;nHPv__qEXfo`tsH`S$X&EfJ&#Eqplv6ImkhG~T z1WPK3h<&FUfBz;#MJ`0`R+q>Q(gSk0J1;vTuxyw*v}V^gh*yj{$jR9Ls3`=c0Y6X5 zG3t7MtI1IHCKj*4iDq5NnS`)s$zW?b)eKkrhL8H1pB2CFf5KdG3%Cs0BbUe0d3=lX zB^CKuB=$Tk;`6|dUx0sRLc7_jn%Bl=nyD^3h~vLe^N89_sp}LOBi;m4)mebigPdr$ zS#iK#1%OT<9c1CZmO3V(&#hjm2PFojn^43{MT}vX>i_ihTrt9;NEapGAe@v*UJr{w zEN?0CdmaPhe}jVT>?n3FjFAgtZqOTPKpl?PO?)IP~ zEA8h2I%FR!+O1(AaXOx#HHmL;gAqY2#~nwI^rMVBY-zRnfZrJg+=O^TeB5^xb+rL} z5+cZGPYGe`TPuTmb=_KXNkQPUs-3MhQ!L2-DyhvGz`a29CIMvmHxxY-Ay={Yi6O^wImFFFusX5%{X)M^oyYduEIfe0_gC zU)hyJ6dIW8au$|J#!U*uDa<8Y@H-v{Hh!zFy4?CiTn#4vOoo_4gFG`WkQ5+?tKzDR z5=K8_q>J~B<+d&c1rMd|UE2V#NNk4mF4*NYe`DarfzbAxfrXK01lomvGi$Fp`o~=` z?_^|k0xUSDIEzB)lp8zb02B*r!Qfo-r(s@8w{u=K()__D~U^uVV!?hOgx(TOOqx_Wut2P)ql2W7VRwtXpvnX zt`2~4hD$i}Qqw_`Ct0jY9#s)-2amFL{TTJSZR@MK;QN9|xdTxhAohSf65*j0dFRK! zNp;XA7ExwSktFm}91SH4m5wzJOz;*Rf0g*Y2b-R(eCvRpn}!x8d7e9e2juN{L+3fR zqa-Npu=Gy(bD|s?zc~^1xT;PaPhmvQn^FlE@W`Q|%LT)tiS%3b{ z)a7Ok_`0s)?5#GhRdZT~ctiued+`zyVt4+6(K7|+${Z_FqgBe3U1MDR#ModGNS3bT>YRVy*)v#vL^|7H8mcUV&)CPA4Ok1@!ip zUwd?1meLGQ^h#?-rK4>@+Ua#Ke+~u;*jklM=x5IAw~A*VYZx7u;8a4H7?2mLX7mOU z4DZ)Zrd6u6WyYpE#Um;q<^5W$7SPt+DR)7CqJx11<}W@6>O~kc8c|Ep8HmP{@TBulpn{@1t( zI^ z9xdO#`<@)l{RI-vIk1F9g#c1kC?1se9Rmnn_e9bYo5qX`mxXx6rOnp47V904Q#|*rI+Za zQHA1|(j$PY@XxS+2|c z`+B10_dv!-f6)FYe$GIp?Uu}w+g&G}#~CA?5xyrKVy*kGcP;UEtvWEV4sIV^hRW`J z3|M`d+3N%n>@~^o4m7xN7Q12M&7eJ!!;t_$?VbaneJ^20$yf;L(4iP|EV6Oa*r*%? zA;+FME!){a?tu%TSJs%L22VVX{-~wi`B8&0hAsA>f43tf(#(GL5vR(2N}=<_pUDKM zNY!Rc)#d|)kAWEp&%$UK-?bO++@s2+u8}f}wM6KL23w39z-oT8g-aJ456eqm2!;(L zA-mV${Tq{0u1O2=rVdx6f~A=Cz3%j(UBK3;k-1DmtDFI8Ok;#{#FjdDoqzXBs=LZn z48VQlf0pJ5wf&7vAKsLp7^z;Wtthqd1N_IJ z6nmix?=C^VA%WWbsvfh>83zpTQnG(FKA@fyf5KS8+nChasrNvd^w{zvr!oU#ifn9& zFoIfza_9(QiREP-XaShXEBJu0&QTbl?$wZtlTJG81SkAZ;`>DVtjf^k((T6a%P;9| z;Q8>;fcxyf=yh%WK>Bw(NjiE!wEZ`-0R1m4UOGD(8e9Ei(c0A6)X@fL3v~MXvFbmw zfB!nMA6G9A#snXdjloGtM9g#tY5J3vv0i8i1_r#$i~fUK$MHnPi2BYFo)-iu__iG1 z&>#$-XPUz2^X>D6tN@O?%Hr^pTl!)`Cbt;lNYgvE0QLKzfVo~iBE+y2;vJy<1slEn zC?*m?pt=)a!^N!~qIOH=9Nk-)8m2uLe^WT|HOC=X$Tl0gH}g%3Lp+xAdJu;AnO0+8cNs+1FcOA6@j+)e|A7y z=YQ-2IFgC}V_Q+h+0fbLU$;z}Rdt;fnixhzOHiKZjz<~F|cQ>QP9Ppd(eQ2G!`ED-Tby zQ9GSsDf?v;O_sD8(|Gwl34#}W+3YHdGWBu=F3+%8bI*#T+%JiKIIf=_mEd#)S$@0ZQ2L znR0i6RI)L+&SCA!0-0F>9A7Wxw9!ar`f|-anMLBp3+|MlU)D9Qqnu2zx`SM_tiP`{ z%>*|m#>U6W#||Qb>iu8PdxfA1W4?j3ka$1sjkZ#K1n#DG zewuhg@)Te2u`+fn>X7s`|I?H3lxvmejm6A;#)w`jFVqR;3?Bm3e_4hV&X(?ABbP%O z-!Ya1Ms4<-pjE$3W)g+V`)ocI!9wGr3JldCE8UL1rnb)EGJ?KM4K?vS41|XIlr1Op z9Bt|L*UW4cqQEQ8QqKHVj=6RwI|uN1Q%*xG47~ZAGljxz^WOAQk`h4(Wf*_4sYg`B zE1mxQ&@;qN?&qb2e?{}Ge2^=3Q~K<5gILCmi(uy7k6`5Ld*lUS zOr(CMzxnlk&HVXxc71?l+yv__Q{OWP-Gfb5_f&)- z&;suX!{ycVNWAv69c?!f53= z_-`k%iS$g!hxX*WLjAikxR#;=e|`f2xrG1$(f)5z1~FS>I}=k! zQJ|x#u`|%l_Fw9dWTUX4h(7w2YU^AHF(Milj>KC=e*+DG*b#&t3nA7Ts^S#(UP`9X zxzu*txFcRfB8`Kdvv9u(WzP9gN`kE4&el$GlJmuNveM}Fe)V2j3u1OFDgiavfysVp zVXhGJ#E7A1a&t$C*sbX3B@^MJ=SE7fR`1-+p(Fmg@wWW7brX|h6;2E}HAyrk8H{0b zzk!VGf7u8HQj4)jwrK8GUTu{cM@q%_5ba|8?qk))sPHPwl=2j-qY4%J@+lf}S!a}f zO`G!jhD%24E=!~Ue}Y42=k!yt9OA22!#?b{2zAqyEjODTgqEx3H~L>v8=+R*Z*uUv z+#=6}LR=Q?VXiw*nci1ygVuMlzZ-7E=Qh(3e<)H&R&#hZgaDG~n6jIF$Ra0Q(4t*^ zv-(|W?UqZ-lDMp8!jM{~p>k0MstB}(VOZ>u>Y3u=_PrTJDO5wVDkz|S+t!QiI&K&I zSC@LiHqCGp`Y?Pewe8Af$8-UzyXAs#h&tu%|P8_UC*tj4{ay-f;|6t!*(X? z6wisy-94vDn|J#tW|+79RP7&dM=hNYf2yotM2IF3B+SL)9@*^|n0Jw-bmo<0P2>{M zO~D8YR{ge}`T4D-9ADUpT_tojJMsft*03SDWl!XWI+CENgkc{*JMJ!9A&qy6}X_3=_)lKRRNYH%n;JU*6+Ff`I7$e>d^| zUs(kcI~!AHM-N3i6Q}Ie4={)76s&;a}%f8>!slV2u5=g^kI9oO8jx-#oALw5PT zsQ#j1;)7NKNq3vt=)o`J&A<5CpFd`}dc8dDdVRhg0fGdvrcF%NX|^H{tJL>udTid;R{rK`f1R5T%>cLl2CI>bqs#UbG+LN&4xH)~E89S*?M$}T zV~T!c6%+{`5xXs2%9Iq?A8+CgF2!}9&Q{f3Lv>n~N>|uQy!j+l5pKDF89O@kWiive z?gC*ks6bwAs-zr-3wQ>-7I+CESY2jrRcF#EWDc8^y~PyknkM5*+zcB|f0w`0pgl9e zbv>QrxzYl{6)bK)xRh+Oz@N_uoxdh(u}d0H3NUR3pUtP~PW{cfp3)xxq5+J4;=?ZR z%uO@eF@Q;?M^grI45wu9eb^`JL_y_MV!$943LhM{cZkNC&P9i~x4DZ^q-``#3bhuZ zz72cDrk9zjjW$r{TaFd6e^SR`Mu;vGugqdBkx|Ut?tmL;uy=op7_Q{G`W90_i3B%Q zX65W%7TZmW?O5pApRCWO03BK&TKMH{$a^;;;|4N67FO$jGb{ z%=!m9ex2SMgVY1qeko|29PCCi3P&=pLq@Dokh7ZwyR16zIB`7S2*G^&un1+gZUZC9|wh0cPCj2vjVS{cWs0 z_Q5y&XOStxQO=zO`^{oUmEcnveb?a#)!WSWl%14lGBIk~Ur_ zGMN_?g-&#)1UoA-ONfX#jT8|2^0(t3BN~`5j>OdWex`UqfAeUusVYVfIiRIdBpQSQ+Pn{dr* zKiCJOk~H+<%(3NRxtdzkbxWyb))p&fcMO|widd9PIp`+LQc0~%1B)*bJAPzKz z*!C<0e`3Ri7~O5!_-H7wI$O~wm2I(~+uZ94Eyp5ZsmB*0yvz_AyR?*#>vqpE!Eyky zVy?KdEl*qcdL?Gp=@!;Ab~1&)C#fx^i&z~HvE`z87iT{fr1(K3{;$t z)C^}B>iueXicD2TqQhws4gfUjnDVglGVV}>o?CTSzt+~Ym>Ra#ab~DbJ7xTrf;|VfVm{L( zf4vTh<+M+2_QlS*%Gh|SJL;_?_M&?3`=TfVa$c%TvFX|$L#{@BAj%0;MRWx!&4DTG z&cS-pA~K}=e4xl7x`*@x_71DVD43%o z!-nuM!U^9Y{enW@rbDVssNvz=<>%@sgw2yV{W*;@x7`(L0x06@eHY|8YJR9df9>HL z1IfxVL_{D!ex4E(7z!iFD~xP!pY-$CF^lMsNWKp*iwK%W5?K^4iv-KwKI113rwrq% zf!+p(NXPa1qFn0;c)nt{ih%Izr{BoQaE-OrFh$!2U)3h5nkeCW@Oq@)`7^Kh9q~tk zjeA!@Fd2=PPl6a(=jDS8JLMXnf0ueK06jp$zs>}Z?52w(^+x=BSMyMIsL`J5wuL0~ ziK5{lcu$(3e*j95^ig)W;t>~0CP43z9Lkx6?XG!`mT#YCyl~#cxo#%Yqu}%MMvKjcxMFJASM7&Gkm|M~@xB z0Nme7!#N>1R&706f+7&^z*EUV$z+SoZd&sa(YJqb@j z?aNh>dWoyr5lgl87R{R?Ek~SN)%Sc9^Fr*`_a$=elpjfvFGTG(6@L@jv7*&}b{abs z@{ZITHVQ|qzg`i;FC97rSR%`|pfPUv$-DEGkc<-`f$cZ$1Yw>3@PG-1%I03k&g;PJ z12*$Cz&Dw~B;kbs@OR-wjy#dzrFN9!5AOBNVg>FY`Uj~~?%SX)p3ra* z-dH7U<_4<^nD0|PsDIoKXkPKgcj#bnH}uo;Lvt04P;X^3{(pxGFU(l%$HYZyb)xmX`YSVSP6 zywEib05}{ z)a!QC{j43&`+v(EU@g#fSpZatqaQyHO6BjBxEbSi>4QYXM*2+@OU*H&hRAh}3ImcU z@&$-1vDd}9kwElJG18(3n*OlA5l1>_P~9$02Mg5v(Ug_Mb$g*>8(2mD2xK$R1>fH% z#_X%7s-ie4qfXOhE1AS15{B``i?#&i#_jf~1h#UMhJWo=bMNt`AciEVS&MO}nNdjw z2m=ArWJQN}Dj=|Q$v{656Z!0grgb$35#v1xKxvpN-b-21CP-$+s-g#n65&1yc1Bf> zMvXp9wMaQf7qLkaM{#OtDj+V$Y`3Bo~M^$j(14U4R5T z;gAik)&zwV?9R7t32C;@;GDYOrhj ze5Z7$13rM`+z z=k*HGHy7q@V|wB2h3N=6}hf~+IS(%j11pVn{wc%y38fC1TM zBEdmJ3|u4Atp;t)r_PF)Dmw=Z(C|3A3Cp+1a$2lnKpMr|Q#bVPLBsf2OvTYm!~ql?~AA;rIIF)ZU`W-5O+GleH4AJ_T| zMVd=ZW{#6NLRfC|bK+)?ezF~sf|SvT@B5M@PTh+fz~SCrVxN?o1B$mLIz&@U1Z6=Y zB2K0t(g9CdcJ+~zfVOW`JLBCp8lzSPtFs*kMfp+94V(x^emo>5T49f-M=?|?o`1uv zSDoool!9jYHxkvCXf{n+Pui=0b%J!^?C@vKCS^buF$EWuJGp{cl!x>x_RaQn{?S71 zjv}74K-J5*MZLpq3pG>lUqFPya)4dkIW~G@2fPi;Eqz9Q0t;lm>3g``rQHL*<6lsp z_r9=8B(>P%c@rkxqTLg`lY|gF4u3P*E!gg;*~Nl-5$>wr+p~szYWwyx&z3xl};gnuYd@t)U9Qx!&|ezykf9h6kLkPHAGJ%~39+(EcSpZ%%v+kZV=uL#?{ zOpJ?#dP5hqNJ|Bb?jr>H0l+0T+pV8NfD}Qevc0be9^DH-qJeV5J|PD*`aAJKu;^!q zpFcelOiC!>5mC^YvA~}ai0KBD<1|1F2yNFc1)6yoEjv!GL^2SVU;kE*pUZj@i$^kS z{5M7P6(|*#<$e^DYnY^l7k?XGG~lNneb~z_&h$sEZ;^}eNemJkNZvOpa+nm<3o0kS zEjf8{>_9A?H5nk+f#9wbh=)2Dy%C}x$(Lr2k!ybM5gz>W`~K%nj|vg4-fI@}4f;*e zAvsAl<Nc83bq>D?^`- z2s&kC4GXsM*l(eq@4;L-)?b$&F)q|A-h;c57q95R(@G$nfLeL{w4*i}c3F@Vc3HXu zR*)~~FG|p&C=O_irhlpW(NbiWxn4-O;O@o-y+Q7K9@`+;vpb%)V}zBbO&}d(Y0J?r z!h5o7^Bsu5Uc$Xj#Hn-~Sciet0n0mX(yvm#-+)^}CmP!OB#P;DqVV$oag=%f(QtY9 zq&xciUxd3}j#=R$U$VX5G=^GS!@k&aok_oB5H=~4@EQ(;4_AtFD*1jW|Kx@TtaF^F z_~?3xJt!U=&h{XAgU1OAf94f|J_IUv6~k;k|7W3~R4nI;t597YUj0How3;FY;n$DE z_w@n#1GRljjg@P!VAoIXTcD4443pxSBv6p6N}{9eqe!0$&?bT;smj3jbbDqb#gTWK zP2_?`Eeo}AB6lkQoc42~^CQ|&0q&+j^<3zH^}BQ?-IhDJgir#5dz5FD*UR0LS{L@? zQAm?knj?RR)&!a(BJ~6y^RBcNl+jNZKl}c2j%uu~2>q`E!BprXm8{~4Lq$g=J9R<& zRx>qO8R;x+ITKjQ+Ob)gF+-+su^p!h?#;1*C@}dCAo6yCWiR@fC_zT%nmp zjxeS?hpQ~gC`_}>zeq8rVnQ5?;sDZe_;)3wM0tO~A;p<62t9JRpea_myf_tB0T%<7 z*v_X@HNxFt8OsXp-kCh|xX)KEROc1y?V2203+w@Bxl<#i%Tit@At6KyX$~Y3G4c#w zMx|NgZIv>w(f2%T9?bZX6CSh67b@o(P%G-uN0%KWSsaX?0X!Ht{2R{FYj*n@v?ZwJ zt7d;SWXS7jpQUn!&i4W%l+`rCe+zRaD$j?qc+7+P&kE+zjVF_sKFZb!)vWCk7yAb- zES9e314<481~w~Vm^JQ*;YXxKWz=yxuPadNTD{^WrJ2~1RodhTifZrYRc>+J9A&#h z#gaD4Qf7&k_!2C4IW$MDP7|a`YsGl733Y#ANE^i~l6IUl7Io{%K>}(i`2-|oNlG6u z!sn}z<0A|1JrTu`KYZsFAYqM}CZ@45vc}jK94yuCT}V(AOW1s#7d7}rA4Y;Qq>U09 zJ7~do#tii{GcBw&m84CZr8NJ}hA*&)Z);l>hPAaIb|1)eu$oXe7{O8}B8fLVX{ zwqz%XQSC%kM#>g052K0HvyoRus;aLpXi7Iq=LbeRh1KK*igSBk^2yZ({8GhRC(hR} zY%tfUv|L8NfE8{VHL+q=YqngTVK$=vQI%X%HT#M%{*qRUw4B2}zz?fohU?Cm{djb`4BrBxT&)D>>jmEN=gjbjJxG{CbaL+L6A9}Vk zXY+T8MVqAy*LIH(Kj>{1Jt0@$x-I@ma4YCKgl5w`ByO#c5t?#>pFF>J9Q6D!u!QMa*8Ig0J_yaWjqI;aW@WjLo~X|f+~NkYk4JbR?)+2 zN1$h(XxGf64xu&CKJBY?4=g)maa^#fOlvZoRUC{?k;Wsa!He+t zQXvw3x(!ph&5+GP3}xa>4p2y~ABSg0yo#9Ab%%S~D}&ctHoRY=2b%dC0&Wg)>0#ks z8JC!!qe@@?^J$*VAiICgcP85EC)hRdkzH_FMS@-+9STpMHx}WKN;-gDfB83>_A};r* zk(SY*O)>nIT9?#$urM087L9%z=u0OTb$%NdOZyI*e3_B^jgmIfydfkJG16gmSd@LS z$#em5ZAg`SHWh!guZ2jsBNlB!fDh_b%|r)|A<3D03_Dbc+1D+rVJGH;HrLvZccQ2J z9 zk9XnJue5!+a;NJuH%UgY!F;gztoohA%9+wM(`$j?Mk{|zhx``^q+Ci6P#en>$6B!R zzl@_mUM*r;DQFbl!_@gBThcboq;kfBdZpCvGS8MTM?i+h!uK8#C$BE5}1zm>k>`YgC0tkvI`~~ngrZU8B5?4rDJrovscPtk zNj61g&l3c+IeCYcK6nj+){UsG!j?A~tS|WW1JOMk$@_gxXf;g-l|J~*15tXD5}n|9 z52b%NF~5+6LO>p~Opj41(2nRtJ(T^`R0-dm04-wz_`%od$8f<~il{GurB*$p*PT*r zvo<*eFuX$aUcP!dTYPimGJ*TUZqFeVI@NMLRVz@eW?>r|VV@0D_o*d|Q2j-epe>Kv zV8km^>NQHKD^9EWRqFnqDC!q`%_~^RI$nR%NbdpEPHV^)=$19x`e7U0fbRn87ftJW zR@(lb25Ofr7I+^0L~z>mlm1Ps``qS!-*r^oetY0uNmtz*&2Qu`77}jKY})QRKk8!j z=ZfGhi$pC0b%*O$iCD44wYX1zSaxukF=Yyw36}^7s=IKs#2|Z8;?;2~7=4OJ#!|s%BaR&ehHr(ti&y z#MM?>di=8%fCT_h|33{d{3{2D=wJW;yO-_%3OJ}(D`F`l`;$SV87CeQ^Hr`)pOC0y zx}4vHq+p2ho`FC2vh_&iGrEkNoBAdlw!60eNt1!27EZAP#nNZWSLct6P-&tUVtuma zR$r(VaNz0ehmFm@?l4c^fekrP<0{-k9!%1=CD}emF*LQFW!gGIb>-fy!^xRqKVg}@ zpm9yiDa3+rljWl(f26vP=t%S|S{#(RvlHDd5QEAB!U`{jFUY1iui;e5S9`!-q=*_` zT*inF{xfV2s!gFYh!Ik(I$^TD`U>vQAQic#e@3%3nW4|I4e&66{6setD?(xCnTP}! z)TGzR6=lrFc)WV{pba5i>{~DunwP-`=lKQ>Y_58r3xdHAEg=ry^}hn95|yvDC3GwzJ+>fnxcP=vR<)E zXQUxtq`cLSy-Y*71jAVGCfFrEsK&;ECfeL0p6ma+R(<(=1f!FVr4}aTL0-sNk_JA3 zT5Gl-qs@+Rfw2*p+&Vc|zfh={dbnBAfBGbi;giaxB7Yahb#{^R;Pv+tNW3*ZX`FAtoA9`qFGj*W;!fipBRZ1FQ)Xy zJG3EkW`Bs$saBLAzSPYdtvl4j7B53v>?`I+o5+hk>1=DbSjY%Xb%^c(E1y+Ad_=!# z(G8yZ4O{yy;hATeji@9zoZ{HM@FJhzvYKTf=gaf6T0vX7SkZe#2&AtlA#^T!(@?ci@lRWJUR zZEPPN>|L|>m%T@=dIJ653Qg$|SCF@F1S2iDzB3=_J{1Uwq&nI#M*iP??k$Lt)EByU zn16ETjReN!_+LMnuP~i2qU>^>s9P!yewqgV$Ra1mCX$!Cb3n07r5Tm3Eli;eAuPEl zcDsb`BPt13U)+O0W&ZsW^^FYSqfLSTTB_eH%YAG6&$<{206^k@2=M-eaLU%QSfYP? zP+>-9Ho8ENfNV00n(ih0q%)G_$ROY7=70F4qUrIy^G!YJMW?czUEw5pRla$xQ4-6N zKY%|9D`skaLZsgsLwZf9l~8E2=af8JMZeF55H(R`lrR-xfV@jfs@VxCex3aT=T zg*bePplAet1N1R(2n213G9L8-cxb<{Rr@enpjYe%*sIo5b{wJu63ZY)o1s#u5r2g@ z-N+w02(yALFN4trTo5Z)8sup%G(*(uVHT%XW=k<0+9f3P8G|HFZ_N=SW>i^z5<5Aj zy5RZK2mS`SV9ZO3gs_X)CF|G8HCyXspg%~po?IJjctBnpc!#?nX34pRt?T@h4 zh_~^{Cux7fNL7p$c?1|Ll%tr)B!5*0?Dr&GK$iRD9s+OuefBrbJ#(S=w%dcKAY433 z*2Kn>u%=6%xuP*{`gWpd?oLP!!L#?Of~hWmx>~N0cY-gL4Lxl!a>@QFV}z-6@CxIHJ`1Sv=) zl@(GSs-KDv8llrdyvdl03{jt$tH_M`Fk=djKTu09`(Boa-9vqNR_w80T>2a9C;N_Cf>o^K6$9ds22MUMa@S)ux|zVE)WTdsUS~yEr}; zBHSInXf1ey6^i>hmnR~oEy4DdQK+JILksY zuslgVNh7zgGw6|xVbWnPJbuGh9L`NpPaC83+oDX2M=qGaxz3)B@g6k~-f5FDAd})8 z3i0=3rZg<`srl6pKh(zq=A6HxR&{-C}GgSiULD{y+DCwP8w7V~ z$8Y$ccE1|`@39SvY-91gd?@zc-WT?Scw*?6D{1-mmE9L=SR_&+C!McF`XJ}Y- zuDk!92dZ|Nv&^0K78tSmo=)WuF8Qny{^@?6Jgl*mt zv>JW<#a)v3yMbOE8YqxVl!$!(ZU#^-Yku42OyXxSEItv$0x`qnrKn#JfPuJF@Fw(P z^Dzoh)M)u7k$-y!V3h5^dENqNrS|_;9)jNyOrua4sUOwd&tq7tMeHUTR@py*z8CWM|w}$hLI;8^Apv-gjBy;Tao8Oe|nh6C+(=4BmT#mIuk1fCS!y#yrud~-@$-FVHC+5 zMuxk{xH^}1k~2xra-=)4pdrh_nv2wlH8s*X4Q(_ePD2zb2)f2{m$}0>E*;hM3QV@X zsDb|NXnXu|OL_b&2$_Wjxnc4g@>n}XLPk#O3xCAC1%~BGF9>0AonS zx}pGLQayq!9aAwGOyI^_(6pT!LN0}H6YupK`!U;FQPi}6exY32-l-M+dr}m&!GiA$ zlhYwTtHkmZIJpp1v8Nz|5?XShr#2yl z@%VdtnVuoR@Pd5bHFbs}Tf*EK>}Z;1s6g z0)zV*1b;4yLw30{qsUGB=^{6dVfQ8rVShmlmehS5Vk@blJ+@}?<>l*9`YdFuvjU}% z1N#RlWWm-b#e#8Qo6{#dV(Iy$xkfuHTpNB~8A2)^QzN1{qd2M>Opgr*3u2o5+?Efr z&@eo2H~BZ7F}gn$^`5BQu?7UZJTQ}Pkc2SLa&Bkmtew~p^qv0^z6^~1q>_e(@I(=HtBrZC2w0}=c(721m zS)Y%!s1a)zu{BIm#ozqkk~8|A{`qX_u+>x&=aE)KYvn>x@e8H9I z^5gInn|X=MzhPg$0pWXvll2scUaTV5+McyPQ&<1OnR~^;`1B$B41YLp4UD!)SKjW4 zenok{f%fM6fv1h+ruADEy+awt6ojqbgYC%~x+NM=kp&;zIFiM$bA(Fp7kfcaNGk;j z+7}Roa)>Gw3Pu|SFc6VNll2N_lUA(f)BGV$MDZ9vc?|bf+gG#hi0zS|IPbewfWXA= z=N{E=Z!0^ynLsM~dw)m~Hb-Xkyl)P}4U_ZWcd2bh*f4kMe`~OLpf?D5YF7{BX6dZg zNYK{JQKyX1RnAeTjnI|PVb^2Ox1s``Qw3pD3FlQ#(ALaxcO0>Ia?z)_MDWAzlG+)v~?`rZ>+$z)UXawngtTe#s1e|tE1$j{-#JAcp|Qu1F@ZDnmYm7l-? z0JM?*vGD(gu>Y@8aMgE5q*DwZ)H>t!Tw^Q2IHU}|zt5m!e)y;*AaPRGcYq`I0*ly} z%LKL5=E>VAfE!OxOx+13ujxCl!V3h4B-GuR=`X22Yj_-sKX}>aPwuX(2~z1W5@Otj z-Mg>XuR61ySAU(p@3WMvfG`KmCRP0#5G&+NdGdoFpx;?JW9PwE1{OB`OkA+h;MD=g zI16d^`};|3|m6;PXA%w8RPA%98a=tGHeDMoebxl zwuXYt&w>?vNY-rO&*u}8C(~j=Ot$HyR=0WR=<@arW`EzTk$JX0ITjj9vRS!D3z`yJ zEa6xQLs}qKD4Ple1#hVxE#%Y}Gv^vXs*>ov#}*K*=KfS3aO8VFMu!$^{&FYoVAyg+ z?a@YX+N*+OqU?lpGGlu&_E?%pM@yIDX0fp_a5JQ1&gT^q+i4=V9PCicbb_9m{`#`* zN^K~Oh=1M<)B)6K@AGtN3qDmDqIKCnQZ3q^MMELSdLnyRa_=zG{q^`jaS6*Y(VcBd z&VD_5p$QhczV7b7-iGo#a#_Sy4wH9qmDAU~-tOPK`Gykg0e5I6c=H>mOPZWG_U=D+ zCBq&7j!L=Rs7h~yo$SoZ@2%0Y9zX~#Y(97eKYv(+A|&8ZY0{o-yc!5nCTsT$I?RSD zY{q^C#~wwI`Jx@Q*-w*8t2#!9Vw0iBLX2T4JYqBH=fq%unlul_;8HUdm*~j$rChik zPskyhCiP11DN8UtMkHkKKFdhQptSvXe~ud%WGl=cuHw=2-fe)nzd#6fJ(Qm)Lq*u; zaDUI-mWXVRrR2h&&Lc1F%t4=<8e|6r#(;&5InStyb>=oVpQO)9M$Iwqy%8_{CWMAY zprSY`3U}Tuh{YtRF<%Rg+Kd9af{1{Ujqv-nt%6~8sw0j;iE>{oPCT8`nwet4)xmS( zuJ0_egOi<~^ddi1AI4Un>B7xmRpIN{S%2~2-!E`mk{J|{<~BrWSo~Usc4|kuRd&O? zHN0f8V&!9{9>tS;%k#a`07ZC+8X(p>(V3+~@4TRAgIH~Z!s{13Z_&&^T0);Ny@*$c z9pC``Xd58?($CZ5bmunJW)e(0+JA(~9fEGsbTwtiTl3nyx+<3)EWJ;M;HkW0_kYTn zzDZ$IOffu4%aR|F3Q#t%qUjd4TMo3+ka&oM(oG23;5$^X3W!l=;^szMBTw@d-mi3v zkM1$!5N?dCk5Z5!wS!+xW^op|zl7S2>#(qcMoytXO zU8aW%EESE-!glv^A!24^o*v=AQ$nybJ^r2udf9ZFbH|b#j=Hf&sGQ<8XFNR@D&Z&# zBCVzz6l;rB28%&Sff+18gK^w=Axn~$;GFe!QH`z3>33`N(2=1|*`$$DdKijMiT7g|_YXi(g zojkiZJm)sHLfX(4$(_qKhJo1D9P!B?XMls^))J98t7jMqibcIt>y&%dQOtWWjU z?3vsJuJWEcbZ(2(Mai5O{%kqGg&WYU%d8}7*@tK`jDpB2s5PAf&VQDre%kju+Co%| zxjh8`;q(CH9g00uO=|U#+65H{j?OO)?5d7uc^OX0Q>~7>mCz%#Uptmm?yr`s5E~0Z z%qcONPrLF&sb{QLyTX*R?{Z1iXvTte-TtwusCa^_0M3r0Ps^-Ng@a|t`t$<6xr3EZ z*^)RQ1rd3aZpY3zn14rZXO;^k|7NY%3qvI`?+4VNo3f1vWJZNiqC)SJg)CLOYlO-I z7hqG?-Bq5V(f3g{1D3*+hIOEb=ZI6$ckfgw?uA z6)xi3iMwV#h`$13b78o!ZM+Y|-*jWjv^qao1S8}UZy6~xx|2w_3{?As7}h+fzGn$o zLbYv8-G_`(rEd;;9G`JJW!OQoRY(5#al15NX{TqifQ{8ajXolYXCv{0&gGLnklaDv zJ(AQJ2(4JdHWddVmpL=9GM#tXN57M(xFLVL`|~qV@I#9GT;Cm}(oZ|o0_i&{>C;m+ zx_ifF#zDRY4_K&fS2#Ql2zYhzW=qq`qW$BO7v1Ay33o=OqJ`Vs0OEx@FNc(96cBEEl< za&-R31keQo5BFAgVDzIh!N3P6BgrAfW@eShT9iy)e)E~m+}BZY5N^jz?WQEeUI!{& zQGdiWp1nEfbg0FTPBlk!q_k%1Z=D)pT_wR?D~jbz!=pHY4T9yGlW1orTKb1>T`V|w z();m_vDdXoFE?2GkY85id4MLxe(ZmttIyjeM%V7=zV2WW0;KOy?$^SRWwv%|@T=~> zYYLG@)I)Y)0DyWh006H4wx;;c3Y~uq2~pBkL=s2l#sR{&7oa1n8e-1#8~;0`-OKu> z9G*ljPnLHlA1a<2CADBR>-TZ8*mJ$R=Dp=0>02bsU zn$^Rt+w=1a+2_o~6%6vBAf|CP>epwi+Dy@V!@+Z^B3vnr(jhT9ky4mxiw)-dS`L+r zI@Xh*FWoFy?WODBU8tmULH|xyZE*%pT@)XVpqd1id)>kUYoJ@cHP$D<5{wVc4g)>) zJT_-`{T90e1w-X#P1{9kSLuHgaDaIn&GdjSz8@9bh>p@`&KFRfO}6bAI1vLQfU?ij z+)B!t%?Fk&$9dDT#BbbQuEDT$3lg$|)l6zhtAbnIW5!j$j||8Zm*jkX~2hzt3J3{lP_rSE?~6wPg2A7A?x z+Iup!Jznq%(mp=$MrxPF(8P{D?u!VW8j~!s^mhg&?K#o4E0b72;~5qb{#yyFDfWa_ zoS8hiN2y7dZ&)!eQyq_V7&h+yeb>c_*^CDZQ+U;i;Ay@wRkG0v{p&ppmElbQS#MYAgKDTJJs6##15(7k2wLXZIwx5q$`yxtX4t}oX2g2@GjUop5jY`i ze*-a~xRR2?{YHPt%l-gr-bdo-`2gE>0v{l(iBVxjfqoK>+-!gvu81N-oo4oS|76db zKdYi~)O-V7($RSFGiqk-p>ntTQN?!p$swNT$Ao&kwpE`L)Qg$)HrGk*rN2 zc#3o&3*tn8RLIW&-H50M3~vnvf}i&Mmw6debn`wn|51NMium7X`}DuAq>`$v(*J8r zr(5;%Ki=eiw~-+rCkxlW%bS-Yti`Mo7h3aD5bM_N=!7zKw%Imzzq1`*vOI6NJ#TL{TLH2A zNO9ZhW}<&7K$pw(&laMb<}hb7L6tA#l#DaJ#Oa^6*chR^h@yYSx<_G|+hlSKOZf#9lYm|Z7l&BQ z3-#uVtA7Sv;DchJR%`@YBnC_iDARUF-6iFpzZmD=ldlDYLKexZZDC7Eq^4rTP$8(b z8}aZ>km1SKNvl<}KG)lS`b(JMD&M8ek&*k@#2nazR=Wl0AL_Z)^^&4S$HF-acZOYt z!^MA!V6+IsI8u#~E|ljLmo}2)Vy6`87Q<*K=(v*K(OMADsDL0}={OCW)4u4{V)29G zUm2QZ$dNAVNlZt9f+HbmHDXwBJV)8^4%W@=vK)-~ga}qnCZK`ak3|nc#q5z?2MDt) zwpozSRt#m4F??I3WX0M?5MRY60b!RA8I6B%pl&Ba!vwz<)!f6ea-h3VgF{(hVkJl&IKPTxkqm5Zx?w@fSpyX$>r}#EWY9{Mb~{&t#dNZ2DG#prU(> z)lAXo`HJb@MbP;`epB55-By~=3?2M15tFnH`aeZ{dyyoZR8^eD&TgOdF!8v%cj>NgL>h0j>R7T3N!8+$Hpta_d z2vcVMjsSfzxJSKZ6^w%Gj*s%@0qB$^B&wRNZeK4+3TFwskhu6Yky+grW-G@Wt*K&3 zhHNmma>S?Bfq|}-DnQ)(DFBzhO@4(ou-qJOmJBRPo(4QK2FDRBC@}W3sy}~&wNW*RP9wL$rjDB{;66_UBl zWS)p)k=(Avx?{-JHKF5l2+X0S0#dSueHV)XS5qNvUgJCuFn))K%oNF<_#>Y&EJR^$ z8NcvEd7eVBty094E7_4Rwu*md?j66t8&>pGDA*ML6?6y1JqvV2V}5yl{oTiu1M^n# zUW|Qj)1%9(f{>#MixQ5#ne$8`>oI`EFEpx51VDn5)Y+bFm zDX@X6n?08hPwo`C47xxt2IFxE3k$o*7C$<|uJDLmZXcs0x-kC6^znaa2R?=z%ozv% znb0#CEboz1j1B0nq#xlxA5G#FEZruIk(FJJfABL@Y4i=X9PVU*XOX-eBesDpQN+N?#%anye5%H}?+U;TT zCt6Y2PwDza}NHE)}#*IgA%%>ZE@ks|r|;0_v6)##?j4 z-pE8>Z7S%hGFXoUciW$<8kjGVoea=Ulm4rbe?YL8I`?)@yFjz7Rm(|0t8k<}=JkG` z9xrgz64hmtdvLysSGBhs^BpVqhSX(=7grks6d&3^B;eFf8sxw9!M%22U5n?mIDsc zK}h46F_y$sn_)!Ok5TmboFPc|*4*|Jb=hNQ--Cr%BHi;jS?Lm(Eg^9^V(2lA`Q6>x zf(6ERzo_kv&T|caYP7pABO)<)^K~yD6~tbXASsepCto*awyCJq$Yx0=RAlTl7^;v}G{#p? z=(b2|pDj`J<83l~a9x#SZmB{aU)B5`_6#A3DjRm!juc>6AU8vu%wb9P1KFDMb>Ak& z5~`XY8j{-A4|E%3b>bBo7MY2PpxO!gk$go-`!;{E`GR?h3_(aDBg|I{F*N?2_041T z$_44(rSn-#NuVUg*bUf%fNk1&Se!+w4!>#f4TvR@AgnY3F;8ZxecZ*k){k^;s(P)+ zcrzL?=NT#{V^c?2GUN54d9_J~oul=tdA}MlaO3s5dwk@gt)ut2{`}+eiDT<5`8-FA z5-ERyK!a>W`r`F+VNNG2_}(0)rDBT+#Nv=+?Isirti`4{gzOe2+*yV|gnIL|^bydQ zHd-N0CQ^Go*yQ#lf*gy!l3C#rgu9esw7PL z%LBvH*)g1^q)PN?mKOCEEmITKba?eX z`fm^U9aqn=iicp9cS*JwJ$)qxK)6>-o{n17{q2-W?MV;eopw4-zzFPlV%OwxLWmX2 zF4~*FmfA=#&x_9H6lP7%19n^%FQOYDZ9`XMNH#NrIAgrzxzN*C!9l|q@>_p>pRCag zXjV`TL%^8jT4UQl3?^6oVpkK#*468T=CZ}88nw4dLVXPe6XQs~md8My=rbh7_XmF@ zN$hzG`RI>PFsCsCR)>wiy9{cT=dyA8Eh<|-7{{?QEKU$vIX-Krj0R8 z=8|?#5;6F3p)8NVQA=!Qy48P7aUf=NC68wf8_y)~r*Ja|CKr9f?8`Lo>H9FgrOD5? zu#B*zEHW(Yqhr%<15(4zg5$dsmT}M66-=}md(BH`1pzUDrqO0$AUFfY;LYK?SXkJ# zmztX}+@q%0;H26FJg^Vu9dNnK&NzzprQ(hn%J$KsjPT@7G({P$9|jMt!xPCwI}o}xT7I*2mM~pxaRSRxy}&{V*NT{jC+;P&^-Q7k!nAvn zq=zc*Cee1fXlzlpyAbhq>Zo6lpgVTTQxDexEjgpf`xgHwKRBfwC#*)OagYJ*iXpIX z=9wK@Mm;oj*nDAsEpb_}7U-ePHu=G650yiI~gZVglf$Svv$5K6DT*KJF$Z#^WTq;8BG1OTG~k z7Fk+N*m*CRC#u@X6ANc+Mz=LWZ@$|b^z~(*x#PC|HOh92kV${$=AzyFkcCEXk-Mop zlx15o(`B(lXXc8$zPwaV5#C3{vRJwn4FKyEP_vq;xjV`qBMnzv7g&J15dMl-lGoz= zfC46oOha3)sblYJ7P@|We^jMO{$n4*=+rnBZ6BYizdr#YQXt5ep0w18*i_ZQf^oPi zm*0lhobw#O9Ls;)b&sLs5T*72`2Jx+HQ@f?M6IiU85N!h%zzN>z8|N*oR;vregK48j;{f?y!;+JAu z0Mk!6%nxiN0(-S`|BA)Fg{z*%X3!&r8rm8(#vfia<&EsOVkqBg7c8IQRtF~Y$vev) z(6US3H&}lpaUhxw?eXMmOpGjSK_0`ZheAk+px_cFBFCk{~Q7AUfn~iAMckMw=-$ zQ+u1And$_)jbL5)#6NY;sI(~4FqJxYM1~K@7I#evJu=hP*^xAn-?J1Q%wONa!mTjA z%7{N9y_E_l@v`E-e9!+i1&gOYbF%OsH;ep_o7MX7OBXW-V`Eh_V`HoT3^o1l(iVpQ zAB%q*M9gJnS(ao`%u*CPhh{CktiZx$^%sR8NoCmBQL;t4!O2w+uSa9EVmIr)Gk0ko zV^nk$$PmL)6es&W@<%x4bcc#4X%4K!jAzU7=I6!rX5De7`}Jtn_htv!?hoE_Um&cG z5?PrL%3zp{$$*Q+1Outm=-l-kax0D^D>Z+vjK&C4?wplPD30VJt=%LXsRHV0A^FVW zeNp;;j5Be3=!TX%foW0VmO+_}WlJI*LzaKJ!Mp`1^Bw)tLlcYfqYMXkm2R3yVCc;04*ZGcd>5_f&K>aky94kiO1jA)m2tmaaHe6Qv2N(m91b-2wHlKUei0hCi9Pj}7EqRRBx8ny*$gybzM0;bGyoMS(2e zEcqIFe$LyR*=igI?(I2742hSS=vaTGHk6AYyx^d_wFY!)^OX@BkA2Q1oZvD&p(PtF zgB3(etQ&&KnbxN0dma2|H(Q<@F>XOob=+r?2{EmC(Np_`AB%9Ltiyva>9Pxs(xqZWxFza=3L#rP==^vEbCBbpniVBK_ zjaCOS+^r~{Cjz37L?{Dvy}J!9)<$v7l&}loto&E{Y$_g@1C;&CKZEOg6t0Txr^zrC z;EoXWf(L&wC6k77lVfjG zlH7r`zUjxiW$~_ZI<-hc1&dc_8Hpq}4((#`%)MIWYhM?w`JLxySWMcdE!!*e^Yt~S zp%Z)UTk>kQx}x(&y=h(zK9RM}qhxMwd28E&!-;|h4wt_7-~A)idrGGDp`nqaq7kH` z!$%_=pE@#+5~Te3G(mrXgC;Wz?y>kW`70=BTa+xs&v4)CRIMH5g(SS@zEsYGk*^qV zwf4Xs_K7pa%JJu9WCgxsc4pF^i65%)&N(oJWx|PPQs?jziDo**MK>xF)HPPl#Lv45 zHcrNcl$ToKzw|{_NiJVTzN{l=T)=g^kk$pIzM&_7U_dKO>j;05@22%U&2T+OU6?5w z&)Q;V_ON57^fb@lT9{X72@VQ=xG>A&?4bLpr=vmJW`Zk;u>Z2nZT;0_V2n&1x^zeQ zV}MIK^5yf3y@X+2OCd*OQn+o*eShx)US>?tH&6fn-7$$ zh~2{n+#>{_s}FzPQ<8I!<#eD~))o!;#g{#UbCxEE$vZHjtu@S5b4cnH<@tupi*(3? z-@C{9713+v6-~8U#HRRl$FT!Y#1g|w-XX9^c7R(h9jAiNoZUoG9{!~wDQ&by+DycT zT%JuxZR?)E)VriWCr8`-Si~%L4P+kOgzIeno^=4gGWLILc|y-7;?4jqK+?bc{B1y2 zL39`Dq&41~2{Uc*#{V!);7}}CBLcQA+%QVK+aGg_E5V}upd|kA z@-T*`Pwkj_ak+0p8+V;>l=3hpBkqvL0K{NudUSA96`wCCezsm%Nf^zY=* z=lGW13Jw4ug#-W~{Xa(z|H%gLs!FFAJ~a@BeWQQ#Opu$!1qTio^2GRHlrh$U4E!60 z%G$Tu^=n`p$Gcs%5?V4$tQVQAuX1jz7rHZ80+*W36aHg=j*{l*@6(g}EshD8faegB z%)Z^Ot!L}0c28{Y@8`@Xz{VXvJ4-%M&@@yr*<#&ufsc4>@&CozJ4I*OZQH`JZQHiZ zif!YKZKqO6-q^OCO2xKq+o%{7<9uu5Z+m^M?X%9_?Z0>~`g1pXYh#W+#vFKfu(LBi zF0}T-8;{k0v7R_zR-RwwP>E%P2~)071}!n^uRSqyaOtbF{6}5G>W?#@W)pr3hCS`H zN!%^Yt@M-A;q0^4y4zy2%p{ow`51}|?*-SISZKXJygqDZC1|BZ1^V0w3-0H7y1E?M z_5|xVf(8n=EM(9{OH;lqUVKy{kTp>;&K7SJz5}|Eof)0$|wH>|A-$=a84oGy$b^*=?`@@EzaeD!X zbO50v#%rt7R;`TvuMtclhQ}|b@2lc)$WfKDBbf@v?y%xTVrs17dcCzuCOs??2<(>` zimW4lqMVwi)b}M%b{DO8R>{q0FJf$~QtRv*0Bh(nNf$2pWJc@J=7_M#*1Z5aL zp+)1PJV>{~NoE+S0imD>SlWD$A1B;6A7$)+K9O!h$5Bru76SB`{3-L;`s}O@Q_!o( zvmU6|0YsFO$z|ALEHSu{;IMRAoL#g%3nPGk z7uwLZqoXqy?N*%rY%$qoyel+NMA8+G3%7noX*>@YcsQk~?~lIcuy{6BQzGl%GMUJI z$K*>UCDxoFgiYP0_RyHnmtW+^8?aQ(Gd_*h8r#+P&nuKvyfpT3Z_6`*f3ke~WoKgV zs>;sp%5F1IgsPknS9F*|H{7+K5+T-qYqv-Soq1n*Lr;$MBWzzxyjAunJ15(6^Phvy zoyBT?Tl*RA!F#1BpI$*QyJkJj2Mzyed&29+=s$-u8rE8MzKU!Zaf!wNC#E6-lK={J z*Ag9YA6vyQaAS1S^{H|=Xy+X*P$k{KU;m>#A;y05)FjHK8ggMlEeO2-g)!8B@jxMU z=EoUB`dJ9TT$K+sM^{UKIYVzp<2jeYwZit4mOX^nil?o+KO(F1^7sYl>do^du-41H z1i{`uqR0YT39N4P=3^H&<2!hbE|!>zR}iLh8%gwbaBfIzOeX^;PLVXI=5SmJcCjhi z1O&=Kan7*mbt7jO2E1JvZNt8QE#woY0jGxR@zWgrXeUybVRa(0jo|QXv{FTX zUE-+D-%n7A3sX>*fQ*k^Ab9#R!X9sbMQ)0o1xQ$sZF@sxcUKR8q9fO0aElH+ zkt(?ejjt_L9XVg9bu;lZ+ol$uczdTsQ63xs}yEd+rak`|v-8&oQ7UrtH$L|n3 zKVm04LG!Hm;p^UaQ-;)+W9ViLAr7H2+3+DISeP(WQD z4u3hZ&sspP6Wx7K^~KtMb6I}af|OO41-$6v;%mveT15Zx;dj^U?1q3$s%RND`zYgb70NP)NjwdCF z60Ot)%}_d>?R)p}6N?~WgoMLEb*rwxxi;&$AuE4g7Uy$=S6_&KfjV^K_(CcZajBa9 zX)mf&Mb~Iocc-uaGw%Ur>yyiLYnoMd_U~@XgU6pHYSi|8vRUm`3#{u8G=UvacE6`L z7GsQNZR*a_ynCmQL8|UKIeVg>$sWF^6N4216QC92k0_e&<~pOUurZd7Fqe*UzBGiI zrCsYZrjkEb$r9;*+33S>K)xi286s=PrJq+OTpF_$1Bh2XC0Tv3Sa+1x<@vtpDy{3R zqcG-dL5*A?a7v2n|IE(1L~xzE!KQzX0Uk5CnuTrYWUvFx-I^OJN4bdOtax-$e^MZ5 z%+dM6=1NSA9Lrj|H~PTNNDa7(K%h=bdC+NY=;O1<9NSd~UXgsHavGyN?`2X0E(KjYwK5*8z%-AxP>6%K} zsSRc@g$fi$`x?wfK4A|@j6d4l{1JGQ3}Hnt)T`$+pz}i*)E|s$2%x+R4>VxG$rv0Qw!@>DiB{E_nuOBi12-GJlcW1l1!lFv+zGF1Uygmw$8th z8tDI~gXjMiEaoUpAc2aaR6ni)1oz1aTGQd7oy958BEW@N_%}>+__Hz$h);IG{gTs% zhBSzO+bcV&)G9{qJ)l{nMx;Y))nCajSlRg&y{oH7SC4hA2gulNQ^c*;A~(OeTbK=f zioY6VV>_eO-Kvm3DBjUYk}U+U0;x553y4xZ``uVJ-;dbIA@~h&hN^f>#NIlHQw$yS z%V@JC$$t7i&XLJ~)|0vgf_p=VVFD7OG{a7Rv>`t`xM$sP@)seje5bJgnIjBgN9gyz z&;aPa++h6QbMzmi#Mdbfu%G|~)2IpxlIJarzd`?oq~g*gB_$1lF!jt}sq zw^{D3Aq)rz#$%rs{BOcLU$-xhNV{NB5adB}_MY=S9Mi{KIF|r%A#HoYvHlFfqw%DF zv_9Go+3AV0YlR@Obja2a->30Gs5D-|5|IIvSbx+6tN!H>&nk~5O+x?Zj8wDf^L=t7ub!m*1gB)zh z?bSAB@g#m*G&IA@a9ucz4_FRC3n}}(NfHtg<~U>E$k4l)6ZD)BA9-C_Y!q{Ul*p9u zWsG&5{wg>UO@x~<3K9b1z?xM~T0$|)@A69F}T9Vh`@}nJM;nZ2c zG?Le%PA)g60nRK^zBCr%ci-sPo9nCW7o?{u%YXRsOjtFKkXv&Ssks5iTg}r=I15-< z5~`{(lp(Rjo6yo!foKzV0$uul9~q4pWvqJ*(Y0=63Y=HxCM!oPcoz*pepeg+DA7MBr zLb)MnPK0IStvGF{vsewp=7!H%W|&W0XE5eZ(=DnpJ2+;Da`k|7ay_>dH!c4~FMxwf z2phRaG<^qWRj0jG(3da}yl++B;ag6B(a+S#w}-wv;sAVAn-4jRk{e?+qVbVUPyj{- z+o*C9Q=V+)nozIf@}*jTcEJ12?F|ZnzBzwa^r;|uTul<9l^h?zsF!qmIz}KURR0zW zi8a*;`9lIAmXh)v9Tb=&7bMZ9#Ll@D$|cYrEDpMQWT=`F0~ela5-UKl%M!~112m1S zRJ?6Wd^eu^0bG=ztKpb20ngo&weu*9GSNeo8MXJ)7eN+YcQGJ;rO)>I5!rN#=SmuG zcojfQ`9lvwG8e31Xu#95sbe-y^OKv#7{&yutYB1^%|iQ(LQ{OO_B*P;(C)r1eXdh_Inr45^)Xq2#)t%FjIu=;w+iGcNrj8eFoD^*k} zpKfH8rzW&`Whp>Ih1C6l#2S}%Lk9K{4cXOP^r7I9luU1f3JOEM+v=(;Q}@hGkM)-OBBH*;ajrYDPUP3q9Ctqb_CcsCUDrew z4+9AoA(?}J1)}O<`HD;2bPl1^7RG3{!MD*t5P5CcUJhwsv-2e{` zYN7mTeYEs;TcUR};PQMX+)FNb_H(q!bv+(Jmk@zlpJlk12zVgK>_S~o4{CM7Hq~#G(BmyCXpre)`X*XV|JYS74r zc0wQ0HNrX>qk@Lo>ODV^hth#D)J7+F?avAyxVW{=alb39eFtk7X9qd)vLRIV)zhC- z`3c}6UBD0#ic(W1T#hEz%iuhK)-stw`&KxgY0WVq zE3+5vPQpHGt*PLGkiK>xf<3lBZ!_8z!^rJ_JQ;*~-NXxRfOXFew$+TFm$oHfsf{?F zPNEXMqiLUTsSU``M$NzDJ%~*y$PxK~szn6J;2+~6BYHRC4=SB{)PcIU@Ct3^cJ2w`8 zbS}fGtC_P zU(J8MkhV*l=`lNlb;kg7*-uW8#6&jz(hu67A*VD=i4&L_f6t|}+?Fs{!GM6AV}gLl z{r}~Y{?iG;dZMpjenQoTURdJd%OaM4(8`c(qnQ(MiGy)r4MQ<6azUZtv86&;-+Uvt zkiwadFOl(SFJ@H8;xI_!vR}w4j)_icJWF*r>uw1wE!!cCpqCW0m?2;`D2TY^nU1@#QDx$PEq5+~ zs7Xd379+-(47_d4iEXc_Hd9*9#q})G8TfP2dWka^VwTHJ<-X!nlv^}XhA`6@Qs%F=habih9{2{GYwGt@; zg0CFmASQGt%$W%m)v1yD`r zdED(txVD)I&M~)x5Gi97Sw~7r*#6Rmu1>xZ5%?I}p)q*B3D`64j)kmO-GAm6ek#Cm zr&R^|_8DhkIwUlZIg=mYP7_2qHPSQ|{v51RK=5#uLG<7%(eu>u&=|O+dM~FsTAJ|`e(R#)zv`*iPO8G>0L9gXv*+(V__Xa7H z*krK4emNPRG1ivTkE+IhqdZ+#)$6QW@HIuC7kUuizvmKL12z)hU+c6u;u~oly)yq@6$WqP?Lbey#TooM^7*W0brLU=3pQaf8eii5(BF% zH&X7n(&V8{Xq}%oQ1V!Dx+Mx#Yt<4@F>8goj>BZETaG}X@;)tp%rO8bgl$Wtv2mAU zkP6YINPz28=Lx1oN$&9({_}=()fNsd=B2zxy0+XodRjtjK<;3P=76{zCN1WrzQ+o>>TLg%2$X{3 ziH|5lNYnA2u4N!s*^22GRyhoYBkm8&Ks(Dm%FsFQ*W+M+fv?i9PMp^bj@vCF^^@O2 z6Ph;FwAlu_F-uMi*|)@hXI*=R4OJTNKB~z;)yY$R#>hR^SEAsstB{aCgK+ng+G}_w zNO5;fGNr#}bjS{+Ng>cq&~ft<-NWrEn0n?e_Rd2MN%4Cx>`%KPI9lFi>n-RrSid~JRh z+3*5?XsMn{4BR7L?w9VxbJ8sI=eY#au+&BR6@PSEOith0=Fu{3+z>M~O8#b3vn5Gl z%{F|Lt8&z_hZzY=AjZp>}g8vJI`7ILHxmoHR?C zJr-CGmAXI0XcvrQD)2m>V{GJ(6Dk1rMt~z6Gm}596S(r3!#>dXyejSQMbs8O!dTJ` z&Z-Sk>Q;E~z|5-9We;@}jgD&fNX)Qlu z36RIeYV_lazeNKi8+>4nt_EPvty?;OecH@lmbksq7;u-Ii(+)~eEXGLe9kPp5|=k? zNw%dFCA3QTEHdV7#@-reh=C#C98bDtbPTKUFnI3Dvo5~q!ntBdJz0t?u-PNxqX=Cg zlGw=ZUEY?`=s>rov9yV)8~oIwsNibya|;uxn52zT5v9ihX z7PQU`w6&_H!T~FeTSEcXzmQhq=CxmyM!PaI(vuU$G!IArd2o?J$i-hRI8Gp#TJH5) zQZNwtK815Mow(Fp8YfBG>RM&E7blkeszH7mo40c`^~T;KQ?u9r zEbHgt`pi4d+T@n-i50I(-XJr7Poh^KSkEENAUe^&FCMu2Z0pWG6-FiAXd_qkkp_=F zZh|FrGj=%%@~Bwg&R$z@mCDY9NJ{yWm`aXK;2eW1Kw~bYr-#mUMeO)NBjZcioaopg zB14K-$4)Rx37O4Jc*jsI@|o8+l?F+(k3MQ?7)0f^Q5dRj9E!U43enVmozS_%@}{~M z8-{#$O~>!$4$NdG4Ys3(<{~e$Ki9&$ifoG}b9xv5V`@sxp8dJmzr0pt5?j~uc3y1m zx(uIr{t)^38ULdxMiQEPZ>BpK|1`Jf8OadX^9mC{3Nb>%-4aZ4xtGe`m zVPrTE5TXB9LF4%k5%d3l^|St)r1^IZQ<7q@g)fOQ@|9FZIhKeLu3Y|rDu-sJ#vq0& zVP)EsA_9+tK^!(kP!DLp_vHTGeQWk`+HylsA=rHb{%rjYL3Ax|`rTAXqw79O?IbV08 zk)-dxdnwgHcX^C|j5Ud739*g6Zbe|H-)g9IX>sYTP;=5ZBB)7!%q>qY-tj|lG*cho zBwTS0HhE=30fH($LprD{_fWjX2+_n+SLQs1qZ~Wj^6!) z^%j@!=uXeHCB-FIS!~_qqMQ6rvNrkoh7(L?!}VO~FkD`LH%IIK02%#t%d=x)<=Kj1 zn;7*^GF(YEr3=TO6x#ZR?pJx6 zHx(3j5X8TKBF&ttCJoeL^^!ki=EmzXkC_;$(Bd~Rz*BDf zUroM!cxkfSe~B}zi_ed`oG27<|HizELd<(Z{8a+U7hX$8(Buwl5}ri%*&%coPD~W% zGq$!$f9rFuZHlirz&U89hNMb;?ym$FZz@!0zlX(ta5dLv^;g{Xn5eN_JLL2vHtp6; zz1f0$hb@4QXv7+ww-BK|>+zO)=yrBrB%7NtpwM0qp3e+IT6{RAFe57>L|sW})f8NL zN!r1Jb@~O42Mb{hi8J+qlqyH=6XM0>9HQQkH?2Tma;kOI{q2i9d^Rw$|A8zP0yGIn zOxQqw1pGN(6Do^^!9=IazK9OjC+rY>7OqX6H27|7;saQ4tJUfg9Y^~lI_`W5!L&Xs zc^fV!OR)89ub*#C>5Tr%sR5l^thLI(2@(S{mg$wL)sxS81;(=r{)${clc)WnW4Au1 zRWGDt3-XCoNTrqfa-Ff+274@KLDaqeYPK(bHqTgcy*eB%*j#X^jB(kOEVLp@8l-zY{fb)y%twS2-fk#gb!#W`-Zsb)!k z7I}*5vq!rvO@$kE#da0l7UX&_-k*LisdG|@dBMhylS-KLRb|#6s}i_*%!mi@ei6Sa zK7i}jslYGDf4+u-ct&j^{zAEbecb=UYv{k+KZNr9Nc}7r_w*kk)UlxOO5X@T>)1&8 zvO}mdE92>Cj~oyPzKfG4`qVN`JU%^teS)l-sF0G|#dNq@`CK>RSHo_~;bc1-KL5U? z(S?M4w~=V?O{2hc>95x)+E)~G@LT+u9;7VqFV?;OYbNCNFn4>j&x5t9?1(Bx7R&?) z5h)EheyA)t&GH5Q&!;o8M+lC90s-+r1Oegtzn;z#@Nbc!^3To*#nl^p&(~ix?ndce&2Bw4L{Efxf424TE$k^<_xU4U#5zDsN0H75g z|0`hbR^0M+J=SR5f-fnfJA{IhCckS;vtEa0i-FZ73rwwVNYcQT*BWoCvaJ(^sVgjr{V z88``K90mL(z&s89H9QBUYg@ALV{5D;FN=1w9p(&taV`%rqJftvo#ziWRF<^NG=nWZ z!+sf1%4_vyNVYL`a14N~3?Z#>N#uPl#KqEF7(&&-QB0!uKqZq>rc_^jRCGc$at!2A=<0n|r&F1Lx6Z5#`?&Ip|#mUA_|Bl59DHINBO ze~l4>8dx_s{9Ma+jfuLh?4z-{hnCg~Q$rGGk(2(iWKG=UG}N;~6-37a zYP#*Yy6_FKy5P2d1Il3(9$gl}2~K$T^0rD9gFk-c+r>kPF?JfXrDf6lkddfa^>(fn zO`YcLE9ReImug5_cYZPcKh-Lj^bnT6%tevxEA{adYR)n?KQkHmuQLG)7W~TPS3hwp zX&8dGq3TZtBYU7FE{6Dl3{imOXLG`U-?i9nmNh<6UrQT*VoP`Q3sNOgRiU`@7!2LH zf1Y;m$EfQ7l`2o)Q12ASoJ-ojz@<4E)~QtYMg_A}&dP4P;fTnj#})h98v^Fs$HQ=Q zt-Y46+Di6k0$#q1YicfC;gC<{n(lS8Ts5~kz2_1&tOO6!)KrPCbkpp!1n1vMv)g83 z*a+7pZosgA&At=E!>u0`%xGo_eD_8kHN&=27)=>Jv8aV&@iN$70Q>RT>E(k@w)F;L z)9(2MsyjaiZS~flmwWPurVIpcj~pW2(idK|i01j)4caGW)oSYiCDIxC|4Dlp_E>& zJ*oiDD%I>TnkwS?#f;@v9G7#6eSfTjTjxF2MJ~b9r?96BIR?e1Hn4$uI4s?7w?~rp z!BI$JMT`S)YdFrrG&qtCB{J-=N@*@tdB4DyK6qT}o8RMg;2@MZtYo)|77tJUP*ax) zd_=8(-C$F{prta`QtNV0DE5q0tR$K&Su)Hop1RyZzq$!g*}ZKfA5EYA%)lKnKGaCt zar;6b+X$H+Pg4QwW*%GCq~Pg&P65xZv^LC4ed)-{V#LXd+=41@b}xzHAmldlt?e0N zc5!H8>lAVxn@`;|a<1?$#-}_h_gYVAfKf|-i_WhFFDUwIyYM2zgH1F8=V0IVi-lsB zKl>NYP?*ur_=TzIT2MW}DWOnQdmg(`oR;r!dM2F{ys#m<>qG?_l3L2|=+eZbSjjP- z?{qoUDbFdH=a~!j!;=p8b!^B4bgr&llT4j>y*oIHc!8=|d-w>G5YWl3^;((cR5b#B zgS|hDFhV80ySDMRhhN$dLuCV>P|V`&SJ98;NS!80AcU>{=1=NU2 z4-WziEphn8yi3d@CkvU@C@Qu8G~^EA>4EM??+bP+J$U*{1qG58n&u>qNjP}R<3C=cBq66Ya#r2JUR)=GHpk~}3F9Rac6P3#vos6h;x{i!^caJxv z;x|7(C3B`=3&9p9J%L!6lH4`3AX*jI1Z`7^Go3RuQ>z9X!R8d$ZZ*?1VR1KgJ?uFn z)Q6}y-h(LbL?dGdzA&n17U_A*Ps!}vAe*P_1A49Q#Fclr$-7#uch9-Ahi06Ar1^1o zA$>FNE5akp@0Vn~6eBlsqe@e(cF{y{e_LvuI92TH2Mz+V`j>-a{eN|C;?^!^c7XpJ zbrilq7HJU|I((Dg;NayDtfU&q{uZq`iYCW^umyL#^9h{;O|L_j2h z@lI^8>TYx>{QCV;v&80cnR=~bxWGlQu~GL?YTFXc+?C46a=Q9y(W{z&z%U?FOcAQz zjXy#&UH*-l6&T%n)1y5-at#|)zLJGmJGt7|4eB+YCe0L`f7Yr!;Dm@ z)5yd|NggEH8F2x`($5*p*gv~69MHmaI0$~B$x-5mSNkS%-tpi($p-1e0iYsuJqB8` zz}A6|x=oy}Eo!IFz!eAGM@B8Wh}!su`pZ?Bv=`7ZOAxUDF@myxa@=f4OUf^}{WOr= zV;n>*^45M%Isa0qHb{HLd;-?KtLgTUTOndRq#T6t4UuH0H ze~7MGB&fs%qpg5UrlUn>ZLBDJnA76%6ckLDCf+rzd1T{}@-9a7!y!0eb1ZT$mt_@yKuw}ilih8@8FH7!d-7;Y>SK@gWLqt}B+FQ6?fagjyj>sizJUuDn6SII zv(n$s>Y#@9Ebu&-y8XAlcfaU*ZJ)nPSs&(K6@&g4Q&u){vl4f7a5J%X0Ju>66Z)q| z_MaLCj`)%of@b{N<{d9CgxrlGXqhM*K{fcY1w6%n3Kv{BZIB6Q>o+3H=cF0?7gFr! za6h~bgh@2^Gq|nb6-uOjNEd%beWDKLnAmo3pfTPBTY6Yr3!ZGobp<@E4D5hr4~2<; zBe5nuG6t~*Y6x#SFFn>E;G0nR9bLI#h6d2Ibqoy<63O(XywzdbYxR@dN%S5~s+FZQ zTXD93nd6`ZF~1-olR;@NaReg)joFJonmdOu2P8g9Jttf@60F)LRDE_9LnFtz2oUse zoLM4Sfvjc=cRv`PiiQ=g(Di*(Ajou0za7J$W3eGfBZJnn#_m0YUOy52`po{&gy%Un zMq^I+6J3UpmH-2;fjMs5=#?blpv}|AvUa3@7hvixGp@YO6KjI_8X27Am9pAJ)uwQG z{-vqSWM|c}LXh2$ATApr=rFj<&^cXuv(MYi8r7-zEvO*(*Hgu}qyF|7?@p6F1?aLp zwrCIWibfh4gf=QIu{#TDY}*9vrW9Dq;L1*_X0Y~n4CBjM7bc;+Rm^Vc*6Pz?8s-## zTFaDLnfN02MBk>ah26VMCUo&qqE|!Ptt7F$g9-IU#$>G7UxO?>ksqK zYWG;TfK14V5b;aSV4gj*F)vRmg|6d&v}NBK@GI2*?0%yE;Z}{PtclO2T~`G9{^;x_ zT@V3tfn$sSZ(GLvK>$)bLJ>B*fOyKu*iJQ$x4q$%a7tMh`_wH|0OxWf64|NP>-#M} zveSc5wJFxxo3SV2s9vK*eBmE--IdV~JeTL>Pg;@UVM50Pf=h(!-7OrSB)g=4#=O?B zP5bDXnD-m~Et zVJ?%)Bxd$PfK{oJuZz7`#N~IPQXya9H9VYcl2aE^cLmZ82G(sr8nbwuTr0}GK^!`_ z{WBHEh)}67nLzIaqU>+|v<0qz=j`7%0HxohX5Hxk7dsT}I)aAQM%yCLn7}f%=*G6r z^L;c_{{Jhs~)2N`Sr7>)z7A0g^@T8CFc;BMO@6xmS^ zN4xdjU6IK0y{{HnoCqI?|7_&TrZ_}dkRTxVi2tgS`M)#r|C}(dr-iP6h4G2hh7b}2 z0)|#6NuPp}OwzQ3Hb_RIfLK1HT7pfONQ(eOn3k`ef9vu;mrF}CBzoQdt?NJAoZnTw zZuuqiC5Bz~$WM(Le+=4wIxv|%A>}> zU1htW{x)EQm8pzjMNT~*&jgW^&qjrMw#(V}L5}ZQpTi&sm`EjmRxTY3lp@rdqo^$j zK``J0+-;#KV42jo_=yd01=YBd@|#ZUm9mrEhM@F$5XSAQfX1vVt=7=a;u6{!mC4cm z+H4RXQ52v;Ip!o}r^eLD1)Mp{(psR^(N|I@3o=9ub9>mU71`>M#EG&VAmn8B{{4x5C(#p2j+3wFV$&w1`vaUU zQ=Bh$d=Y`C)Yb>>zJV{%D>mDPQ-8(HTzyk?f|IJj0(eS)%~1@IshRvoI3CZ1U;}m! z$4~XvnULBk5#(Ev8XWeuAW#j@aF#U|8?sW%EqXRIIim^ZrwB)eosul3CB*_2#G@3q z7_;{s;Ot4uDtppggEz_*4}mc08+_w0J4f!nMeBGIQMdbe4Whm9oOq zUqll#Ny5m~Rm~xrh@h5T0!Pu=j6;~;ny-w)IfILq-`;!#aU}76zi=n3*{kK_3lywi zWhUi9hPKTZcC>Uk@;J*Y|^zIdbuQ~q0OeL&E)biu8Gr2o<^suaA9RS%Z4T_5NpW>`lIq@L3rs7>;SBpGV` zA~veOBBD?LI%Jem315IzTrcOM>rFHWYs`gz&fsp$TVQHGZJ&&?5M*V77UY*i=A6Wd zT@iWaT=3=7PXV4Vg0q*-D36$>VO0DiHxko~88UqJe! zBNIP)d5CT@VV6^WxxsD>0O0KIP9h@7Xp4NU>&{c__pH#V!Nb6W+WzpoMa<$y*fjTl zo8GACPK$uw6`$NQ>XZ*|)#n}ci%e=jtH#W;8bsIOb!MyYo-LI!MCl2FEP%;_dB5b_ z_r8EXcn>Lno*a6yqabi~nRL3SV zh~QVCiPJykCqZ1Dyiq*vakQJnkFrO9=gX~6vPT-Rn6Au5IXc7au(CwG|9VCQAGh~+ zBQt1_Z|v~Oy2ZA6Kypu>>reB-o{uPFEm5Tw`6=!dSCqfss|j(Qc8IKK4$IG(Z6FqZ zZO>nR?0><8+8=wp65`Zq4kJwC-D-ciXGV#X#%@G>I2Oz(rApb|`!-r=Ne-*4Ed}4olW1s3#s! zpeSQ7Ts$tbwm3U-UpPE;=sbgezANt=qBho!^-gB(vtEz*`3L%ewGJA_675N~X@*$r z8C(`>iZbv>lx178nyt7zWCph;)m3D(Ugdm@wVM3VwXPB$m|2>yEYF#$6J5=l;HHgk zWOvq^(UBA@7#Npr<;$rdI*`}D(86Ct%m1&4mH?Om>;Nt%|KRs;JSz+S zgJ=J&(;VId>{abGZL0%+vego_0a22Cn$_!{X7whH)E8H0fekm%&qY5v#Af^Z5hgon zw^QxYZK~{KZ=FrPITi7Pka`9uOpxcU3bQ-96$sK5Y#6`EOcz&(v29O7GQ7NQ$ zMgk4CcysCoQ+xNsy6CJ^vc@_rMET&PRi;P2yqx&FNhxO9r^>`|1qM72*9b^RzIH8o8#|4Xec`}R)(teu&4RDg7NmBvk7FT8;@z3z0vyaVxOf3NT(F&SnWM(Y;vu+Wr z{A?_+^b1p`Ct^c~y>HAlRC}-Y?Efb5heJF#HyY_2R*k*7LEJ)2sY*t{(irsWmntxf zzp7Nm`^coGB9YWpL80#W6h>=lwET!psh?xS=b#<$s7TIy(Tr9c6Sr8N+?o&$8Yg*l z)1*8iJ%g)%`k5yb73sk#9>9jj8=h8#H--~)zek0OYz!Gpu*8|;TK7$wmEd3;8c==c z7MX03NKceF_hTtJ$W+pbtipM0mK(XLjg6pI6m5_=wGJwdg<)a8oePUCQHrWY8h*MT z-s!j{7;Srb%u1Y}Q7`iNZK}8gPo{f$Yr5<3C&aFQ4=#Rff@uAGCD(8P*u9A4!Z5AB z`V@+~L%=ZhETf>{^w|7i!I=u^Wzt-bB2d?4XseV~D(!UC(<2u_CvY#vcQ9qg1S576X&16|^KK>@H`2=Upo1oCG-$pxJ; z`**6xu})+I2yYu$wF-9aM0J*}oW$t^uXICH+M~G`^op=|St`Gmno#jB@^FZk7Q}yB z{gC=iURp{8Tx#swaScAw+#F@OpjSb%?t)^3+sn^HL!uxk6YO{n`KFA^wd1Q=o?a1u zV3$QUFalpe@CLPESpUv=^2g!rvaJ=Ry_q;~zAh!g{%{&Q=Xyxwtk%}j+_WA0;Yj!n zA>)OO?Vwnh&yaJFOxw?}qBuz3vvTzCkS1@sw!|JZU@S~)i9;|+XJKxx&#Bv-(BXC} zrr<(eI>?Cn#B)#RKC8zaYt;VuaC!@W*~Rto5G;d9(L$8aGQs?_%oP*I!xac`!&YKy zwNVWR(c<)@5TC9B`}8s1mND<@x7*4R@Vy zXYjFv?t(a!Fg*ipX=6m*=P5XfqH4|?x((2SYCsi#8Eu+9L{<&)J>QOtZy?!9 zZgy?igP`inVqP-r%%;6@{!d8m?-#^x-`aH(7!I)cNYBt{DYn=`b88Csa~vwgmQT#> z6`4>!H7uh1WSF^o54&P!C}G6pRG{#aSbh&nXm!wk!GE46}AnrLx=I@yY; zLLFy7oqk4tZbD{erp(1u;a*LD3ttInA46qI=^aC-Y!W}bjCJMY589PE{rj=9^4$LJ zgx4Diq|Hv*00W$Y9hB7BYfGAulfe`C#a+3`Bl^f|+sGIE>Y*0xI5{`5uh<&+w7EEX zoPG_00nY4RcbrkOU>P6i*Hcrm+g%v}${O0#QF?SGfd;^S#K|&cu2<@R_z?O`lAge= zyvDw@j|13ST0SK#01b*lfP61xVu%q}szAXqp+*k?rnQf2r%@9Q*bVX?x{O*BclpPcOOr(^Nso1 zDjT=wJNErB!295MA~t$vj}m`of|-{s0Qc7_4mVHHN99lF9QK11JF^-Oto!rkVMEJd z$5lMJ>FAwCP79=HnXlAmfBfrseNo@4=x&7T`C;$4!#4+Hrug^S%a^|;&KKaqmHgmA zK!yqb)tmQ!|Aw>0VI&1j`#fT%Y z2+N+6VdKDm%)>TvE;&pL!qj^60q(Jlqpmm(S3D_*AGBD}U zy~)!)r}=|Ww5VF`e3C?7N~gP97`Fm6InHbfl~9|1Aj}19(s*HWiH-iCa9o6ipqgJo znlthn%1BGHizXQ&H3?{{+=!^zl~AzAcncM}V-@XJ3g0wj70+w;h^;Nv5%Gf_wO5G| zGfj@J;387g@mV*7m(YTyaTkUYbQtTP%8JQd*`$xxx!Ku-1{{?W=GF#ff^_KTLfpXs zLA08GFm98{Oh^+IXk{k;d<<1Q4EPod3__1(l7*N;pc!Xz-*4(bFVV`1$nAT7XK)(R z}-z@dCDT#uiaVg3~fP>gP^w8$z5e5L)~YD%+T}kme%gi zZZwlL9q~rPx~3^21eY3pfG+A#Ui8{kVft&EY;Vu7iS*E60-JGDT=}kFoxLgr04w!ITd@C)=YcgPTM%fa}(*z(0C(lmoi$6K0KIsjs*UHlJ!GGhHspigj8svb~jNOeK@ETTo4pBO7luinnB&3 zj2@vN$}_ez8E&EIj=4t3y;vp5Lxy|n{?b}41H7X@=K`rIyW@ya_UD!ChDk+79nnw- zm*6~!>PGz;fw!EzCZnUraWWDio07yW$zdt66 z?at_Xe3Cg0JD>Ug;rjT67I?trKOM5a9NWCi-rVH*==SK|_+nA7gP+gRoT*3qc90{7Xfw*l?1E zwuSm74Zd27RL>f__mRiKdW9aS17kUYoz@wP6nSwWv+R>u3z3XP1x;}re-hM#Y}O&< zN6LhZwZ&=0TvVx^6rE3nQCEgAR4kf=zmHBx?5D_l_ru19AnH_6ne0oUv3G`i8sCj2 zRrQ#`2{Ppu*2!;nv(z0c>7!_n{-}Nul8j8e@5}0ng)M}@b|e%qc{yu!Y0~+d~sxGF`&Vkq=7fXd~#iN z92zl^jZag|M+f=vtpb&L_v3bEk)_@r<#J{m&dkVL7D)iBLB44O#zPfON4PT@du8$H ziHCs)5Vq_m=~gLJcb=dB!uQqs)Q|546#w5s}Xi zw5Q!P2nauOywr$(CZQJTnm(^w4x6jO;`<>bATXW{zf0?<~`{T_(#uE|w zB=iWFaRIPRytx==&yAb_c;!4KJexkOhZk07#D=ikbe+Kpn#C#C$e}bfO!Rf-VM{N)$WfihUyUVmR~sd_C<@sVRF*30piy_OH&lV`7tbTMlRX{*B)ed-Nyg6O(QW!RJAHJ`a= zpmYHP4XO9M0o$q}Om+g)9la;9wtoatZ}XwQQmTS0Z@+DHp8Wa>KvkM)>< zsUtF^rjSKNAxZVrw5?;LsBlQ~cF>CjEN#X3__m5IxdY3XjlJhg?HhAgWC6ID2mv$(~nA6A210==SpV z`z=rqU#R%D6TXYBeb>$w;FpnKiIGTde+wMGDhi2wnN4%Df;Y&0qZQ3QECvY^+lpqOWo_C*wg`Nm1ZK84AmIB(D> z#@Qsir36I@aD9Q&cosL6or!XumBTbxsPV0i3Zg|si>HeDw1TziIaD=|R5Ah+e+D0D z?cj5Gqj~9kZF0me;ZXauC{ZUvMUoB4e9J6t>C-bM zqQ#*wQAjm26U5o*k)7E*4bm*(qRQQW<5HR#SqTAy007WL0RW)?UkCJdPXE;hqjv3t zyo%amC6P*_+G=fVec=xa*+PO0e~l#0Kn4;{kiG^6!?9+8yiyg@E&dC&3bikj#U^RG znfY@bex`WI!Ynakwi%yk$ygC)Y5D>F1b_Lo!!9pZtuh-#6k^PK~I+g|et(vjFZw{Dy z+f(=sm4%OXWiHc?z`X76W@V(3)lK62(s#zk?&8rM9XN z5g0pz`T6o4hn`G@7JRMae;h~D=mzVCbZW8z#?mDY-m(S#^*efSmZ=w(?9h196`Y?I zfvZ0nezVEpES}n18K#iy?vmgNiu!9!*WCO}merU9Y;Qp3$V81QJvGnP{b>;j74AUY zhr_uhqee%2w|KzSGki`2yRr9-%$0NaY<`e?%)D2HGelWoLn>Rwe~Ps}*c}keeFQDj zrP4nVuN#1ak`}jKb;($9Ubz zAehE-#>thDKgDs3bKOCA5J0=X#I+b8>yD3vbtcc*$3aLs{-HlN<2d1+R;BlWy8I%|eG%c{@ZE>j$9K8{k= zmH=uObXOWD47`nKe2>jLcBA=C&hcAl8~~ATO)P+v>(Dh*f2OS?0PyqAxO?!$RVB}H z{J2gT;{?(zD=fUh-mT@?+Qrf$Kw2yl=RL9wHUk#b`3#-7sy6Q8;F{LL%NmR1&OK~X zlZA4rx@XP!p_zw2*to?uDH_&ddA;qzP&3v}P^{9{V{_8FiLx4%b&Cs*Nx@3hr%QK4 zzN>EG#c}EOe=?Kxdb16itvJ^W=PB#bv5c=?pM!L+MG77|G?SjDV^**_?>SiUbzu!z(vP@xYxJ1Uf12>DjH3UIB4&Z0c7{-M#2T*& zAfHumikNI=IJ|<`aQKi>&_`0S?f_eK#=7Y0x<4Cmj3NCwz$5r+v0OhFWesyATVWb= zqWTt>`V~sx@Y?XTPwB%hGG9$P7P?>GNgBw~8{cg$`&X|=;lc0Q*sP@ucK#g)W?PSr zS0Gaje^Vy@HEyNEW<8lxdW1!e(BzfB;U0VtIHYxaMcQD1-LG8Msz~d9p=r&_~ zg~m9F^#jS)Ti(VggY~2O3rFzvG=g`T@m`qqdwv419O;QpfOVXsas=qb3MelP@6wHA zf3RL{2*Nlh9;Bi~`(&`gRN*?QFt}r2bu?rF;R)57Ps0UPk|VA&Cr%LjD_l|wbt%x^ zVBBt}YNcJJ6u5#ND1*3)`7z~_RH#p0%(ow9^Y?&)S|gz3^;DKLz|{DEG<2LSIUbVq z(1-Mp`C?z!E3w8k#D)#qNJeRnBCl%qe}2upTJd+8yD)sMJ?>Q=(*_G33IWb5?n9T$ z&w_{!B&x+hKlSs1TyI4SeoAaXn3hg4=TTmDW&*FfcPjioFt!cv*rMI!Z~+ct)O$(Y z*pWjlsiX1-{xq zm(zV=@JPNPf6-E^a}j-)27!|M;UwFj-U4z zm_DK$>M+J{nm!Hde@k2t-ywM1Dixl3tpdB(0G&VwXhF$Y zl`0RHl>_pg8`t)zLl_DS<$F}MjKj36&(@&@-hw;q@H2&0f1X_$7 z2knBXbPy_aTO{~lr5mm6JB&0(U7f2sP0Lhnq|pra-CK^&Aan!|LJ0k1RwRVTsGY z=_|^Xc=Spy>3t6-qr4NlB)EqZHpBQ55C7uhLM|jjfAqr{3GWL}AFtG4bBbJGW|)op z9LOtE;x;P?1}~I#i;%6ACkp+ckdcAQJup-B-At{%yJA6cOk<+#TSY`H6(4fza73-H zb0)xa<_I3C5a(uY@%RHASoFG$Fy}x1Xs7%tk2o^@vCjX!jV%`VHe^+AGPK4Y?KmdRr!2jxn zvwu=zM`sgvX$xB`6JudTB@;(iyT9nM6m_hS1yOjHiZzgvevT@ii!BH0Bafh>AX0@S z5C1zbW1ff8g)NAzfPwodpH9Lq8u}VFr4y<0YxV&*@x|bjq5}`G)r^+0KO;- zD}36qIC;syvvvlR6pYV=mn0`-6*>wjoa}TJ-Mqy`a{x36NTs6vBV{kath7jCR)GkX zf1JsMj2xNFI5W|>-7dQU*C>a_KwZK+^$M!2baNs+0QWWEOr?4kNtid~svk#cBh3Ph zJ9K|V_nbl?Xzz4qc~)!2q*F4^q&dB1jWL15BG80hDs-`Te<(d(bQJ;*-?7S@4?N1Y zSTWRW>pN+~6e2i>y6wxO4aV&~!<8z5fBsRqBvO-eH$8xtMv7I~5`$s;V16_T!}ENv&k)nOTH`6DgP zBo)f;oM+GDzwv^lDgkOB{!t}PFaQ9qe_x$s?40c!|I0IO$^KEMuh3LFTB}zvk%4{u zOQLED_aH{X{0IqBFbJ~kbOX2Gf0RqvoE)MzGCqGdZ3+d6?i)aFii3<(O=TgXb>rXJ zO~>9luUYu~eLmm}abBd(gvSKeh1j5>A@Ucm^eNutiJ~aiZ-j9_wfJ`jWRtD`c(mR< z$(Jb`A5wRs7G?NnOsMA~l0|q7)2c@SwvSa>yrr$1l+8r0c$A+JSHZL^e{4}Ff(wEZ zBJ|p!9>`f&EH=t0#lA|#nqRoRG%0BBj}+^u1)zo$Y|}lH*ntN1Uy;`i{J$q!`)W~3 zI@Et)`oO*E!05*-e$XfWpvJW8wm~wst6Af7RXil{ShSLB^pQ zzrk1y*!$F^oRkydk$Wj%DKN=(6rNfZq$d8btR>EnH$8C44VDz$f9sv&cJ)&stE%B3 z!wBBli1994hZA9 zB&Lt|4m8F++(D1=e`ah{o9Q>c#3`U)k}Qthk5HRn(u^B%-VUgKN>&QdBiSfSS|kb- z6lTE%yB-u>y(@z}$0#_VDHgH&f!`kjXFpJCi(qF!Hgs15=j@fY=Y1i7TJ11B*lrUB z6T00C%at%b-xnb*Kb@k4#Mr|!{IJPH6N2L-5Q2nRxZ)$=e|EKtP;{;EP#SCh+E2ao zO5-NL$2r9$%0cjfwAcBwN$~6!sO1Vs%UOEMqCw3r+wbs8xCsyEj-J$S+tKep`5Esw z*zahQ=hEIn$7!|J*O^7pmtjsbPO6oaoxPJej%Z`cX^mDK^@!;ERzc{#zmXjQSosP? z|1q>gi2o-;fBR>zouZ@lpS%F`G>}pO%_3TYQHByi8zrf|8ImIctgQOMt>~A__1v&Z zY~1Zl5({?wZo5J~^()Z$b)WKlx$8Ovv=#D$NgkY>$8Ng6r*G!^{Juc-@#3Jy39JnI zM=1|6YCQ_id7zi&h|Hz@rf%C|{G7F~Y$x+uCWNm+f8j%vq@K=+E~r8`buh=x0}2!^ z+bb_W=J)t!Y{-?dsT@%;FSJIls0^3})9(XD-)-I)AOBaVa)XPG}df zb~vdj7Y}Aa5jPAmEV6O;oQO6~5$`e9lapmEv57KFGL(w^RMr$#1ho=!`v^D4Z&oHN zA(~a^f3P~po^apO(UBYD{7E5*=bkz6RQwyeH+%%NJM5V@yUhU*pJBQW*H?Zz{a5@z z>dj&#T-y(2B|#Lb9dyE>N5xn76kdi(&Gg~}Z?UQ)+@yXnHabHp$Rde_8rNUgWYN|Y z+W3PYd<~2-a+snO!;JZ_g*~G|srv0omH3#He->qUWzR4b#4zroqL3y)ZEyj0X=h@q z`S|PhW;WWRDaGVZ?Nb4qEKA6b!yQIOvlOUa$*GA&to(ka2VB1+2p`WO=nZ%ZDoS~X zV&^p?i%sE?@kc@(JHFGy7B7_c1ez%;d~Dfd7l~CumAEWYGmLb(LQh*{5hhy8!F4J~ ze?b=x3GJf9gQEoViEL}3L|E4IN8wT)Tyc8o-BeZTf8F{F!q}FrM%Hd3xlDKtZ`Gjo z=KN+grqiA4$f?Jt7+?_GN=UdlLD+XdaEvHC#34k(Ok^3-Lq!f4*ZyD9iJymmaOR?AKan>lN)`5xQVa54^`Sce}z(^x!DLaf`>}2L|_D`sMv->mFWDKDbZ5-tWkYq6? zn{pj0iv}!lkM??dieP;gMotZb%F)fpM<^3Fti2L~&u@WL8N#n$QeTY05Li^>N``l1Rxa`*JQf0fWz+= zMB6;b(Cg{;K7aA(0k~3NAPJGqgmn3~ma^(fjhP*FCyY{ULwof`$z!o{e;Q#b4w@pc z4~Q|ke5}DqdIFs%*M*=5H&@HD7Q6(B@}n3isDcY^r&py|){Xf`=GkNGU=ms*B!PS* zVeZ2ZQ6UU+IUfG4X|V6JDzo&DBg+N{0AT(ffAY_ok%^O&g{>LAu!*CIp`(kEo!ze@aj=ajg-RVx?4>qyS4CIui?3aL$;SENH@ZGv_FO^$U>R z>s+R;BcdO)Z1XLO0|)M9mQ2L5g}nawV*29!wOg;rkJs-7qM!2vK@0>KtdPtQ!x*D) z=Gwk$BB#@(##3u8(!gGXORj3Qfp5{7 zW1VSB@b!IX{YsZt?gs1t!s;lA-K1VfE32U)iV=*cPC3(p5WUC@r?DYWm_z_aT2>(` z&Y&Zq&UEtI&1rDVgdZd zqD&QuPm0toMJeobf4Vz(6HJlUI*hO)WE}OXQTk?)&c(vSphLISE-x~%c;7I>%xfZCCbkXUQ5|l8(Qa80P99 zup+SmBP6oeyE>)@nHv1zyF#Y#TN7*V?cz<2B+7D^7R_YNe-}qSTpg8B;NlTH;Y8!!#&|8v>!hRAsyaqk7suMc+x^T5nRUx^nBoO_dfVx?FUS z*+Xnuk3I((rmb3J+5`g5JTJwx=9dr#NRd5ox8ohVU@kuzpSnlw&-fpnl$cO~^O&cf zL7C}!6dnW7f0ntgS15KH5}iRzdZ@Z(bO6t?5~W`29;gOX$FK|F@Mm5HJ4 zP@uv{FKQKUrlPj_X&ztJi-XzX@mPTi6+u#W1(-##e^#9HHfjwnb?%&GzC>rL@B{0= z)t0r0>!DpnKdC>-)q6RI??TlC5jtR~S+I5iQ5f(Rlj>683qMC}hZVSJlw-r=l8z@x zEMm8>q?j&+Cz2t+RO9r(-@|h>$JBj~u5B8TwAnk^f=|S}!ja+YM@FK^h~V#H4587T zF1^EWe~;6RDK?CyZwxB4p`PzH>&{;2Hw49TjoT2vLUjbmaZ_0Lxwn7rKYJM*Vr_dw z&vS_qz$11;zJ24AE+KaAk~0dQQz@zsq1YN=!72ET(x8NRvVIthhWGiOzXZxMuMMYB zByB0IIe$^X@CbnFg+)Bv!uFQz+Rd-hfaMVmf94((2VBFDz~cCYI)OFHF@Aw0Ktyao zrSyJd|97)rY!PgD{4?_a{8#bIKbyUst*M2XgsroQqp5+>f2C0524sgAV07>G!goj^ykKS(bkr5(SD zR*CBCXIsE%+*g9u$~MWqSCCGrPqq_6p`)bI4-Z_jwHKYeSrg9Zy^+e{nT(#kw@$mb z7jH5-WqXLY3Jy5GrsAOW9RQ(!{~Go4f4Q-de;ajHB=>{szOa=70dbw@4e+@jGLYuv zj)U32?!tRoBTo=-hsF3rVeDtvr*Osf{@X2r{_LdF;XgBMz<&ke|7kNt9shA>%v##c z(1b+Bz{v5ha4;pd#}7F#Lz$ag(b3cn7aXe-4j! zB#!_d)nsO5Dy?bp!o|t^=ld66{itw6?m*HpJarkJ<4nb^A$Q_%F0sZ8PXx>5f-Oc+go6e^HqXvbbLz z8UB6jz+sCGB_BAskfNbweJ83ce;}QENB|Roo}6G9MSOr%v}53{2=!)#+V~daRn+a@ zNYWo9`R@qe003BU{}sc_|Nrj%#qgrx<&CrK@>T2F(xe$@((n>sZGA}Is5>>q)*2j0 zGokKIidk1roTM+>MQm|nX_k?LidG!&p9Cf@geOx@2rnd*f*{l&p~|$se^(sLQVeou zFKoWVRbZiOv&d$HRUY)dm7!sw2JhQ?AI8e;Hk*B)mFphYlmTny8t(XZCy>xLOfp@g8w2w&MR;^0J)h$*dQ znrDH1D@{^kX3cD?=^1S0f54l>SZnvt-F33Kujue=J4h;cUV?NmRA0=P#gEae~e3H^bT2sIM4!r@22otK-UGPDI+ zi#Km4ER@fvdpdzqf2i7}hQMr4)=V`4;(Z1t*2F0i*r~Y@4;#1Pz~d9035_n)C8Wd| z3DGt1BASb*R;RGQ(pk6_(KRLeB!a}Sxg}KKi$_#!Mp5UGt4X4p21)%)R8NUG3yY`X z15$UD68Z{4QgGPs_mUeAz#GxUctXtErMr@-v};uLBz1w>e=U#6GsZWb{t~cDyRx*s zdf4+?Gr_$|P2iwtXd!bZcm`~RGGwheqE%+SdVN}w+9ihET;igd4KTb)@z7zQmlZVk zm;3Mr;Du0JD$WI2l4b``s4q!ypIDX0@=E2tj#jL*L#%5h1f_-Gt4#GHET|Azt;+g| zv{6wAuI}eQf9t{R)aI)U>1&OOO(W-L1ZkI!KoUoc>pu2#sA|Xf3S~K`MhYI-W_Zkz zwDS5tC`&f)34;^l3ySjIQ+_sHOydcY8Lzlsr@R}=hXi0l26OjFVH2U&rHi;;<8&E} z(h-&=mT7^yO^&FRy-1KyqLMArIE$8&rZCx%b8>gUe~yD-hGCYjT&w7NjM`3GO6Z0` zwMOwx!zYzy#HODTDl#vc8aMYA=gJHCq~)OfK-US|bpO=UPGbmD*`zU0MIZ|SQ&c2} zev2oW4v*Bbr%tLMMOrG%t#bqUGy_su%06Yfv@vB%G3Q5EU0QSiZG)~(PdsD7?O^NK zNok^4e^R{3_10sU78iRy93$L}2!h(K+V^>J3Sf2mF}8v^=)l?X6k!`a?;;Fe{#MXCJjG8uN{h^GH!$#0a6pvu!2lJ1 zK+HnrfDd=&`N#x)rW0HEW1n8xd(&b9rZx+Mf1JdVEc|`kZ9N&5)?%}enuA21J8UV) z8iL)bd;MyQWBmNaKT>XA3CM)TJg1Y_oGCzUwh^^9Yhox6Rq8q|gnZwU;9_o95HwHa z7J+Xpe3o=v9kar~iNC1V18s47iyb-*g@?vokkG_%{UzTj-(Rgr8$CD*0fJ%Qe?WR1CzN%fWl;RF8$0Iy+jrOF&$!2*!XnIW#THEtY zrASQfOt{k~Cio_Os)Lv+w_i=YY)RxAlD)G-D1)N+WPNlD#vbM^p=mskNk{l`Lhk zr;ruDMNoGJq^k8#X{rv7n&NMp+bMExBz$(1Zhb!d-^S4bT$)sd*V8|qfw1SCf0K0& zemLR99-yM~CrVJccX#`_bh_+%ThlN9LiQnlm?5M@}!+r%s=3eKuaSp}rkLF%Xg8NO69BSU&OkY6fi6 zl7At-9`C4pfb|`v#~Tbd>AQ^|e|;zKebGl07_C%i_xn}7;B)GYbD=LyL$HCAKsj z=3kZV8{}iaf8&hN0Scj~UfH%VKO}EAIuy&aZU~cDGaucLaIZRz2zjJ9QP&Z^ z0`C`p5YtdWghM|vnN(~*4cmnU0H0Y9g`&P4K=ptf^ zEn}=)Le$L_f3R`IMmeqh9Z5VlhDf!i2$ctrCn`KEA%vZkz|;e|5YMYu|E zyGGy$y-D@AD^heqVV5UR$9w=$o#2+suV#|hNEQA-nEb#_Q2-H@>**BdB&iFd2JZdk z05eWM^zMYg75v)WHPLbK9v94$OM6rd0!|Sp{5vcQc(0;(6 z#2TP>a95)dSntf1Pdi?1}AakKl=X9l8_oN~=!jM`Gt2E#t@nB9up zye5~$f4+DIaNO|OoK<*4B5NT2qR-`VWk!epBSf8SmRurN_y-L-wfGP>0}UO5%EPs5 zba;w4c7DrTl!_s%ck`{kx^V1E#T5NYq>HxI=>5Ksf=rGL2iZy#7Lz%6Y^0`wnD4Sv zPo!dP2$-h5b2x-cyPob3Ssm$$a|K<8NL^4AfAh%pAA(Ilvp1_0&2ld)P=kTbRyzU_ zj!4JU<P9tVb)B>Jq0uvVgOi;%Tu6)%g}tO4{w$)4;G4} ze><$6XXgj*#z1ij_Xl#jH;6d1dsVYLw?il+lGbYNGm=I-#we&onL2yEL^ZP!kVG{X2I9cv_XZWqg37O5@2 zRU0&{4JgifWUhOy^e2s(W`$2BFzz<-BgQOWf`TMDA&2RXKLM#P~rJriTuo zCzc49=l}6(NQkQw0bY-mM{*}I#9YbsV{fTRe{k|pA8)Wqw?^uaAI?w&j_;V{ILgNtg5+l$9!enV z{PPLPYzYkf4TDNF(m6WDCOy(|ntaq46p+@n0W~3WYeZFdKiD3(gngAHqV`iAb6>G{s|0@X8nc0| zXgdPDxnm+PXl`@RYvFcsrmmc5+zUzm?1Inx?F9fgK}$nShjK!AS81;_ z4%bhtbTbFBcc!Pt9Hdgvf9SHfLsmI0iA64)3QYC#Ak#%eCqd^cimNr7g7Yr5UuNM~BV?VV)JS%GbASJ4Isb zjwXhK;CF>FHv$(x+vw=S`aD$T}u}Wf5Ag!=A4YN|CB6V@^w=d4AH-itehZL`N%Z2NoZ55*l3lSSLeBp zi1XhKo*Cf#%`@HWUDU&oWh*i;Sz7Mn&W;u|I_vx^3Ou$36O7bl^~P9S>>DrG zZ+P`(7Em}TPZ#2>+M{%-~IAL)_*St_@?7CnGuSAv`d z?HIf@c*FMeeWFn$=eI~gF?}Ec0SOdQr*YfCQ__8k3eRW zQ9gV#z=us6_5^)7P6^8ULt>QU>WxBf^2^v~Ll|Fty!(IoJn z#Y~dF#x^zvw#H6>C2AC@nDV` ze^Z5e#rnC>-xycK-n)_{>p&_Lu#jA!)`w^qO#HW)@8!pfD2d4Y^|l?=@}0N z1$>DQVPjkweFaqDBCf}(RvMjdcj$t1Z(JBrLQno<1t&COyxC{`WHpp&cOkrLKKFhq zF(Z`a!SThfnHS70@pYQL<%qT`UDs?_e?GRUp=4De+9iPoVP$(N18TTx{+A^!g^x8p z@hLV*g#2f?6>W16-B8lKXKBgz9+sO!3|{Xi>cGWPnR}2dpNVM4<|o)wN+gi2Vs&wv zSi8u=43<5%8-*I=nJ(XEneDq?mlsUf9yyjW3udfCgFkb<<|NM;7auJ^s{=kZf8}lv zDFFR9>`Mkf-v@BLf0)H)aM}}79J>vL++ZeeJYW3V8CtJ3PRjV>S$h45nDdm|;SGv(?RJsws%}T*NGk zn{eomnB9IzB{agaCT9%O81_*5(12;0d$3LS*(T0&C$W%NNKD-J(RzKW$)bMZs8*lC z`nH}jP#$XTAkm;i(<(-UmxvWcnvo_izNNJe7hPsLA7x_=fysOOnfn)5e~meB9FVC@ zvO{b^u{#E&^~I~4wuu|hYTOd6sJb0k0-dRrCnjp*>2^t@H)>ln6%Vhw}m3f7wTAGK1~1{Vty~ z#B)P(Oqzew>hJ{!+9QWzNjK%_Uq^`@c2qcOOCRY19AKg<7Y%G-1eyD$e#r&lhe54A zxI!3^3JX;GKDZ%<^yMOJ_xDQJ-Ny(N#_=T^pce*FLg}(itH&|Gw3+pJt1|t2>Gqf{ z&rKQ}000O1-^e-tf0JhZMa!sWrG&kT=^LA%L4qb-FJp-_=3qFMNHBi8g|;@TKek3K z9vx$JMy68?TaAdctz(c~y!zlPm884%o>Q8K!~-nDyYySCjQMjuZ~nB*^$ndVWAPZL zMippcl)*HV7d_{`ckX_BmecQhC+`bpm*5Lw0PLp)#OYeNe`i4I`S0kA@yw3f;rTTe z>PyI*PPWJ5JKgQmDehcWDHA2fLnv!jO9}}|(6|%xl*MzM zsf>v(N6V<#e;UV1!b=$Nq`0#ej8;e%*>u_8rKjqYPMW)z!hxL%3{BQ$NKlzV%9<%0 zYPz{U>vi|{LAY<)Lvy%t`{@E=S<4C29H!1^OhI!au}t6} zOk`GNMyY5DqUXcQ>a~XOaOI5Z1n%$hEI>D!aFR?>f6Sv)ukdb;DG5W{L*a09+(q+S zJR|(s3_62Ws>?q3sN6`LFNT_c3bHe|6%%z3X`SZ*aems1j~U<~ay$r>ZuoS@=Ugx^ zA;W;rsyB;Oy4^U|5!w%{rv)2>Tym5ia3mHVYwD(i9xS*>#>R}xmwjd+f?wnA26P)5 zW4qcee@>Rm$K`{UIX~<-3m|`P+s&+5Sj}fQs{V3bb1F~Kesd5V(!ibD+iXOkrOWT2 znGiOWY5qmppa6Re3db+clv;QB5^X5b)>3n(QgYFhWs4Jm_1|GKUd-wx-DB zbS*lFVU^999CcGpMoK7ls>@lTfSR+4$pGI`eNqZnV<{C^`VN2TzQNbp6<-x(? zii;^((H^qZb2F7NqV^CaY@W7;kflHDN}NQXMZn7$$Z~FR^~8$LmKL)9j)nPJY^g;KnkZ2|8&fgq zu~Z{JrbC%Emi4c9^J*VwC8ZzR$kxnOe|?gI@2c=IlR<23g|ogI4w#Yfs+kpy7HiB) zNhrHRcKQyA`5?19O+q#63qaUqkwWlwY628xRI*mAr9|dObzvZ#CtiWBQ9`RQog@T8 z`o0v981TTFlnfdnpH-Rt3y;ti`W{bPJ~W+ttKhBy?{0@z+MzGchz8vdAU$aX?VLW~e(l#>Lc3r1@JvXbx#KGYY`7=q z&;`KH=bmMceSzZSXuY)!%a<|m%tk@f<0A5e(%!iQo*X>`?EoNYe_wDXzn<*+GYqLt+ka|9Ft(m?&5=jRmttozFaRCy8c%-nvC9XLr zUY611&E}M7FSAE1OH+7b+g41b15GBfyuwS~9(Ajvw5gS#B&O_ff8>|UU@Ey4Su1Yt zU@K_~e#4>6Aua(_>=cj$ql87eLZIxak6v`U?V*x%{PSsV9R5r4_5pXOY}hUMwFTxXFd zu86n;TcdH__F^2Vf0+2CDL^43jR*>cx687(eJH~w5PgAC4Vkd-&j|X=jVa?8}lalRq{kd-d!vN^TVfJ$~)2gEa0|Rqq89` z(W8L>K_uu$kOi5B;fBu;X0R9{2v;036|FZ|- zKhNio=pI>Me?gewv4DC6h{BRUDpDyyu@D4t@sA(q`8!$}^$VuBTUR3c%M|Vacu;#q z1SsMSEUl00%z1j(_yDu@cJsv9o*5e-o#w@{3&<5+j(kHt+$a8+z649Cau z!nhtLGrcbTg%}BYx0i^D)7I{?2N>Y z2mLqT@_+1;vWd0He>|l57hG1-k^9Hp0AO0^jS~4k zh($6be@-Ytg%1gpm63&n>`zP~?w)NchS7M**0n_TMU!XFatr=a6zyip4lQI9?32#z z<#^rkoZa<){`{N=;975F1Tloh1lNdRkj`_=d-c}sbB4z@8&ZZLx;@^ie2o!0Wi^H- zimB@*ICZ2e6)Z?BzZkVi7B`Cp2%lAp-rP5?f7CW6Jb~S7&+pbjkE+&4Ua9SXjb^&56Tc@E)#omVW2jD$V&L zq<{F{jeJ^lchR>-ozHrCAiD@ zCV$wG9*2f})r#!o)4~+slJYr*v0#*ylxR9!bvjtnKHE)Y1RZ~H_~u&Tfo-uL8J4!( z|Hyv>Up;RrU+jNFxA?3o-aa!bh#QfL>~=7Ym^G2q?GQ35VbLP<`uh_I#&zZS&oLVpoK`DW!LTW667#|d@na2skEuK+Wg*WnRLDyS@WcP~ho*A1<1tqD6wl|FAw)`v&@ktsGuu#zu-2M{2cv zm+5NW+|cNEudLFU8D%D9k zkKq+mL%@e8tsmnU(hp2a)R8h;{_U93imnBhpm>3~eF)kqPSul(1F?{jOn;p^B}h4o zGpg9-a7JZIU`IudF-j4o+BBI5O}vbY7mq1o)}Be6yy~%WO0l(o(OqRDP%MmA@KBME z$lt>a<#}mLO>C8K#mF;B2>h9`RP324RGFA*@e6_m=*FlkhB*O`IFQ!)*}0vND5MD! zCyfT?F(t9#f(iAYCc0&J6n}u&2TS%=A!w`RHXGv&kXaQ7(67<*OccYyZ=esrerXjaNGzv(v6q?3Mz1-OGj8JnKq2y`4y2uU zCx=(p1qk(~GMi%yuEdNSEqO)4$flmEt=Cwjfpk2U`B?`5ct&e3V-a%<)Vmk+NSWmg zo~aTAQKU%|?rx}X7T5S?vJU^JwX*=LYS|t*BHa?wNC-%Ghje#09{SJ?l1i5#-CY9G zU5Dl%NVha74N?Mv$bbLbcz>Vg`R=>kd*M6q&4zFN*6dlcW@hi1wYCahEBeQ6uzI~J z3@I5enalzl9JIc(;uTMalO{5=AjOkW?>ZgWcb{!^4Oa<_?z=61U{+W*IZbJ^6IOu0 zG;TvaG+s>IPwN|ZqI$VBQJ`W&D9w9S|4eOi_`$4h`iA4`gnwp{ISZ+!4hMW$UHn~= ztRx+IC4}*vqy`&3`j-{FD0*IfPwwdk=kr>u@`8~w2?RdYRdXc3N8x#f#JTw3Oe_n7 zj|Gj$VdrP)YtF>**a5k;Lmrf0fS_bPqpmVn2EswOkicrX#V%Z(jWv{?=@*9J1YV_ zP)8@ODQh%7>4N-ni-b=&C#bgYGRB`<(+EAccsz_F`F|!>sc|*6W_}{QnJ3ezvNALm zl)w6jfwq-tCC{{#1gv=nhp--y=hXqMLtVfl)Yw%)B-aL)MczlOt9iY3-->hN;9WhI zyq;&I_yfg;Bf431A8?gj+9*-UY-cCtWPGl;B0FcNTIn*O2AO%CT3}8kVM_usyHFAQ zON0`biGNOj) zh<~q6^bMyu#uI9{JnS zm3=YC=fYc2%PW`S4)<-5(PbN2?%o%7MlTQd_B}@CPY>qvI}H6cm|!w5ZAj#?s(;5i z$HN|p7njq|=X0qRHN;I@>wIpQU}pdq?jhiMX)dIHK}cXwSIt3kcY`%vGMUq zSOJIlcxEWpmp&}%TKJJ_T;z}!2n)pJ2(O|K%*!TDHDNx^8kDr#Hcm8aEEtDtjMLJg!(de)Dt4b$ig0044LCgoKxdc1LeaC>;7FKlDmIj;1`en}ZO>Jc! z0B_hez?v+JO-F0r(EUx*_ishZ+4W|e3mgRkKiB|b2+z9L$1L9?>s_g74}TcO1R?g! z!}ynX8IL;A9-8QE4%O^ej<`|z-`JxW!DDahJ}6cW$zQ^Xe}EIM{Dt5s_nUQfW2$61(4qPu?Xz6~i>WL(< z1N)gi!OTk0xb^XDl;ME>BS*m~`;gYk+ijW3NB0$Jo@{#?f2?@m(trLO)pnt0Jh0vM zS-rLDCHnwV43XTK^I2+e5K4`5%&hq}E@ti2X!QzXJ@4|f%2LGl<3y^;_t60uj%ZI_ zjubwmuc437CuD!%>FW_%(+j2`sXKCt7WYg5^iW=?9ugJ#vtP$wCIl-JC+9^D3-}Id z^H`U-HN17oNo=``vxIuDfL2O3gGtJYR&2o#QcXs`1Iu%SXG zDh44H>7XjKMz}acG_kB@l!H0k7S~*r0W_|B>$b;ogom5zFWHthj#TrD$qV|QHG86^ z3-c0>hH!A;g4swK9RoJle3B;SNKUfI`!&L7D;%eD)R9vgd4Jx08WEUiv+hqHbrJ-? z&dVeu`Eh`rvFKf5gOi7Whi&tWN=?sm#?SDgi;p#2D*8EJuDD8vOpr|p{O@IqV zy(|jG=Tq7!e1B@Gr&7PhzNWL0XAplwg*LRcRi{GUbg{DTNw|XHA}@Lwuy%C)K8cUx zrboKqU`3~4Cs#!s#WxrrDXHS+(S{3e(MvbY`N4Uu(8LpOrS`}-`auej#ZY%B%^-Cl zsej$NIbA}L`>_x|-`$0v2dZ$EsA;&z-Uezpku;Q#H-9g~ksafYLI%(ahu;@^=19_0w$V1wT4vR@DynyN9^*CTK1<=nJXyYpr4-OdWE$!90$X6x z#k0ngBY(Enf+{Y)?|9#PV!ZKat~j|%ADc^xy0mFyJM-IAIO&;Knu?J(;XM+c2U*~Q%$iB|sjFz>vs-#lfBVLg>ACt6ITsD-Z zePQahnEh6@Bl=)+TQ49`%8IC!@YC+)w)~v*FoSZe}i`lDN6Lp}(P@t$vt&Ed1#ht(cV%et%Q?7pZiv z;H_dO8tkj=FC$NVJiflg+?sP~h;}*E_J3D8v74D|dvk;}YV>qMf(5(x?BUFW2Yg@I zi@X->q3Q_Fnlv3}Vmw!yab;UN0BL)Y#}nASW0K=d%>t+B-JRKLWCv5!uc9B;ACEux z-yr)E>W6OB-_H2_dY-5 zI@bux1@44^n>4A8h_=STWqqAlV%Prbb!eIv=jJb#G$@NQpF+n7Ji=Zz4TNJD@Zt2&L#y~z1NB47b}8KiI7Lrau0`~x_@2jTy3b- z#oo-f@;%+csks)jjP|rpW$LFi^h(BBcyMBpv8~dvIJx^h5=Znx1@Z~g_w68?nyH8p4{hD=3;M9h#vqT(TkT`!xn8uwm*6FGE zU^qWnw%~&NuzFl1J6ur)8Go(Z4(4eC8Z5Zng4SnLQ>%S7aa&oebwkH(i|BC(!l6tn zh6wfzO~Wel9r4deLX|>;_%jXp`vRynX7KC-?&pZ}Z5k5}V=tejTP`eSMB8A>qxJ4yAQiCa zp=veQvuT+Q(JNnpwrH#F#**2B+i4DanD5jwGg#{ebq0EDU!J_lNNQf_y{os0uu?Lk z6||cuisOAIH$lT$*wKOu7RI@D63LN%)3UF_rgrqjx?%kit(cgTG@G7b@GE(LrAm~| zbZzZWv9l8z@*;;1Ie*6io&1}q(l-j81pb}Vnh%d?K19{{Oh>Y1u(H}yR?aGYxh229UBspaOn=0oQ3C468R^K<1hVO? zMi`}W9uv0LjU!tm%w{Ad>uFFAT?L@h6gf(f8`Trl024#u5gv2PD%W3NYgrzrJO|=% z@CTAz25qHi7QzXK^4;BXg)_~rt5JA5cnTIWe#3yAfvA3pN&^a`g^Pa8!Um_NSwdsj zN^`g0RdlAOV1J8i(=;aUrkJCbT{U2M_5NvJNqp_(7E4C@+tI8ds?WTh9~X!wQ1n2I zIFmsAps?B^b4RJ#RrQ^s9MD-L zcP%vNxfX~kwSiJW)MT+fL_w*IPF7j_1!Yk)=}tLgC9YIaw6zljKN%>7*o{34$R#(C zUEh6Fh>~SDy~VgPzCvoDF-=0o|K%RM%P=hm*mavWKcBoB({gIF=wFeZ(Mxm(9ItlU-DMt67Ri}GuJbN8qxt^S% z#9|V=Kgyij6o&8c#Qme2j~^#UIVSwZi*xe0PWJ#Dzih>xNpL`ws5D}1#I`2CY(-D1 zSiC=O#h-LoE6!z;mOx*e&!f^D?p4rZRexl9+haw1vw5vtVLdiTC$Kvl)4x#EYByQN z*>r$geI9Ea7^9wUUAWO$zfssI4zo@C6%T>eKH&Lq3t^vqfEj_l6BkbE}L_ zULx3vU7^p+I>gDTSVr1#k2m+?Z!Z+YO&ND_6kJ*Lab{5`PHgX!d*~SSd04gQSm3Wv zPY0`a_g~0Jj^Sdi@nwZk=J>AA;(u+BtbSJch$`sM(&EuEx+P>mZoletjUNv4ac%at zKWV_bsWs{_G?#ut8OmhLc6xYhec8GqhkFY)80ZFb}>BqOwB<8Dm83#Xo; zFJ9E0F-IHERB!2;>70$sef;n5b=hS2lkI(Gf!a}X5#^H)4_UvW{mG}L3V#l!09&Bf ze?BeM^}vsnQqqGHr%=%PA;CE3|^Fa?{3SsI1HzQuUT@Ej?N& zr-8s49F#6hXE0CYj3$7Mn!?3U_yELAhMtS@iHL|-D=#+J7jRQ&DStD{aS*lqfxm&} zbx=H|hu9#o`n*Ks`B7XQ!|h&Gnko7W`&6-^i&#I>f*Yg!Q+L+tDxv3&a-I{DFPf>c z$U5#(mBO~^0p~lNh`HIVKnzh%!DPlHUaDC+g)B>q&3my&A^@Jwm7Jq=Uhe$V+^*!L z{o%xxd-^TJcX^(}d4Hu@JJB{+&-FVc({~0o+CLUAWDwd3MG}5{Pqpex0qYGj_~0U# zm{pJOT~%Q22(nz$!XBqj04BYs4)Qk1fn3h=*_AKtEUohUH`u8d0G@NJ?bRmzJ1i9~ zUL-3{rqO#tvRAq%&2>kGCw?s8_NJIzeySRF+KE;I%3FQAP=AyfT+pL)o2Kjy7_ujG zpaB$ zgga)`xpAbf5`Svx+u|J|ccQ_#CT8QbbcWsXa)D~43jFPULdluO_+ zT?C_P39P3c6o@=pCPfAhZ|4`u=hn4n$o7@STuA{NGYd)^g7M(!c=5{n)e}lY&Ce!D zVCh0o)OZPSZ3Tlk3qn+*(fS7xHcZ5}lX3&dLm9w z#2m^){36%-J)Hn#CAUZ&;TvbFR;`VFU4;v*DTt8*cn@y;vc9zKa(2sSljs?$kt3xk z%PMX)t$%u&rvo$X`Fuv4dM}wkYgmu=HD3t(2fS$&_g4=NxuR!}5k5;>)B;Wz?=Mz= zk^{&3a8obcx%a+~t%*0jn`^qINp~$KHH*Hc(708#RGr6R)M)op|L|j-J#4?qy)DaI zL~DvEzZXs|)R7G#SD9@#1I+47Gb6Q@#iaxx=zqRX7kFyffnGGEdvymUaBqgsgIhkd zAqW?tkq?f6b7?&xj;6%Z<6~x*+%pe_>O+&EOe% zkFn5Q;jK>|w^N2lC%N5e-Cji6>T@#_^46s0RzlpWehuRUqB!Sj(dVj3A#^bahE#mE zeYj4=JEX1{3&$MYmx&K=MNq$rF;wKf&@`pB2^!%x!MDlt2$R$0*cn>$ZVSDj(|=Uw zjls0iDpJ!_*a$sSJ)!j9pl|C8eyR;LbG7>JA*QYh37GI}nvHw%J@T>V zuOI2r@#~1_xz0JaIm7Nd_q9qr=YNuLW@HywsG_p4)Z%C-rwb+Bs>;-9h@X=KGF(v8 z4pI|h&6SW;zL6(0NDS3zrq_I+9RE7csZqr;RYt z>pT=1IclPb5!O?zB+~~zXSS*wz!7Ou0aMf^ch3Z6C;5~H!?1V3ZJ8g&3x5Dk!-R|l z+kv^8O#s4mDzrqV*jRE{BzmNhSHXjh5)rO0@X9HdsB!3VN|L`p9lmRVrPnL~+(o@!*Rl6zh2q0Utz(LPfECu_`@rB2_Pw)*QeMGW%A@vt`+wTw0Z8JLWW#RF zRA>v%I3Z=`3R#6=S!!ca73IUV!mSIeweOI7=;uPH2SIeaony7!vO7R;PH=N`*b23( zY6yrcVvsLmMR$%OWRv4v!hJ5T0N|_%i5CgjU2I#V5N%2o4|AO&B&Q84Cfk`0D1bBW z)RW6lw-~VYvfC+_Wq)+n#q~{+g%{7NQy;8n3ao%eq%@Ygqd{MOPTe8M|A>`S$?+Zw zKZa%;PJ@jM?W01qYW3v=`(NsvPZgk0EdA0FKJF=LFs(yh=g z$EG;TQx@%rxZ@Lr<;yUI+$zJH|1fRhE#(6e%elq4u!q{%y?@rR5^`M|^axG?Ye(<$ zmH6vyxpR?U0A8D?h5$}F)54e*2;XL`wS-B|I5m1Bz>QAAW2(x!*ybXW2~RmOGe!w| z^t2e(g{?iae|Po1Ztdi}YQTxXfc%X;FO{!CnI|k2sJ!M2N5SEfy%xs!^)_BVu|C<1 zJj6nsfwBF_c|Y!tkZoKDVa>8@UpYiv5J0)Xi6_k&9`g&k%`E$)m1bsL7EV+ zMX;1-5dgpsxtyn53$!%vcEsDrDJ4l6J88=?ryHX5U^?{`W}2qGYl*8+%4+WR&OgQ{ zK_?Z9aSjD#Vl>U$H(jlvDzoVT$xo@&U84yL7d1X6l7B7LG~P6bVuk^;SVN&w@T_U1 ztce_xo3~%We&=D(=xQyBaPc}&uxHF|r7xX*IG-dAdp%(rWiLS0Mg8blfO~lrb;3pViq!3gCt?TpF$32l3RCvDd#+pZY5s?$+BiFuq zgr!2=Fn>lxNJ%SaRXL38)V3Wo>Kl7#)k&Xv9zWBjju`szSdb|_mmFg~F2Z3@DbJpj zEoE00Gn0gvRHon>&!DJXe-LvXVWcHY4AcsCuzG$3(_F(eW z72G9qh3C4Fv023>2X0BmO}-n#pdfeM%ztoR$tV7X5fcH$2Pu*%MTWI=-lW%ZVOYAC zm{v@H;tp#TKy3%Vj@W_zHt*BBq5d8Mw3!cpf;1)fj{qTjKCWa!sGhH}^OwiL_^bwN zmH4cKR$QU9JGW=%j%jt+N|U3|LF z^NFSx%>Dw;O%c3@c^#1mU~ z!!p9KZEJIl$%oT9nyj|*D%AUlsp%7p6*|$9mVnYho+=0Pv?*`)GSysnHIE=;PjE+X zWgD8wC6}+Eixa6sQ%V=(0r$iR38A1dPA}}R!!#W9b~ag7@0XU4Wm_2P{|ZI?`{@1u zyR$SPfBDyvZNUXcli-##&3|mN3J&Rmnusp$cDueUpo*@(5I?K{2ox(=wQJ?8ljrg7 zJ}j#D?AZ9!Mfkw;s1H9YBX+ldK9ED0b>lMcHp(ITGSg14{C;SXlFLZe!pDoHk&8^@ zuV2=rVGJ)hLlj@BVyWGe3d$YAmAtW@uPR~Ltw_NI(HT^n>K>IW3(>YcuG4 z=kTH(=74OnrM(3-Nq+$SS*x+}CT8~%ZxT0pcN2VZL2`Z7=rx_I=e>mbZc!Q$CNU9S z`{r}jPj!tG`ae&z+pPz8uHxhETk=v=qt^~-ccO;y2+_$1F5!-t+sI{e84RV=HD}RH zau0Fti}vv3c_x^BLidQcerk_8d9p?2+m7_rWG)nJW-B;SRe#3j+n2)Sx=J1mr_9ad2f{qdKuRTJQCCG`LLlHT!JE& zMHyp@c}YW0wSSgZ>3~r^W}=6*Zxoqo_)4Eu06+4ljH({#gVywGeNqJ?gb}7EP`ZIf z^@P%I>3I994ptUb(FVuX8_MyTxh*}7nsNJBhxxi^BTm!Wka4$EGXPIA*)n=3)#7W> zmTas}R#N3{=Cu&shebq1^;=nNyZSRHK8TxRQq7=>8Gmk08m$K&I`gF_2JwZ2AW|BL zjh1=Rh&&)3E_&D!fQY%d|_3$Tu^hn>_H#a5wy}gn%+rx=~ zyvN2LDwIMB-aJygRW>m!>whR~)40#5U1?Yrzv7$_FFkAeLQ^)8AVu`TRvcysR_3Mb z;H$kmx*H901o3_vOkUhbnwmh=&!ZW+a@t(}jDHM+6>mbzJ4MSB7MUwC#BV(3kIN}X z^|K_UuSi=igC1qzRSFH5ic`iU$vk^$iW^Q35-Vg9BJ5VLcrAQDQk2nvUOP4?jd!ANzzIBU{f6 zcz<^=r7#O%|CzNlQtuJxh5l)y3aBRueqV-1yXqQ2tkK?dMPfacpG2p(D|QB+q%^0Q zYurc_Z0E{U-n-}MbB~tYuFJYcvEqEOUsg|15U)A#Yj|3(h&yEh!JtwQPH}Cdj9cig zII4^`tKJe%L)h_QRfgaL1)~%h0|mj>uz#&qs!y@-Z7N-6@;2}m^69p_;-bVD@4{>u zs$@*k{nimooIOvMKTcq9JtwVr!cxB=I|L_$w)bi&oOBKy-Fr-AG@YA1yL~Q(LNK6~ zSETtpR;EAzkJTssv?IQ>WB9}q7T}g*-39~uCC_%}1#g7FcCRvTNVXG6$GXImJ%0}Q z^VjdZI1UH333c^*W<8Nl-)9>6gxGkdzE8gcX7I$LFd^=-Im4p?Jv1tIf^(So-1F-5 zT>)I&!+X_vuyb^CHFwtfwfOrnAuYRKk|XM`Oa!x!Rcj&&D@29^Z4!Kl`G?@^(PESId)hV;j`H#e9tmPd>sSlvV#q<@BCkHQ{v z&P3TxI}XmL7ltP7FoYRYkuG!;kY^|`0mJCGJ=&dT%Jrk0lei2=2SBO-K3KVuUqUdd2`iY{aTGQ-ANvu3Y8@$3QIZ3682p)%| z0oN^i=QuV}Dg4i3Tr)al(@LAUhK_eSch1w)`?!JG4#>m3FU9nFnt!5^&E9Dbd`a>v zxBZN1J*i%Eaw5iFW-1p}?_N{{_c0-Qvek1k;G#OZR-jE?Jyvgu8kxfSoExIo5+ky40X5^AQz>hTF@M*Z}_R5D?M!I!s+(ZnsD&wz=kD$rV zyJm6?Em*HAT+2NwcvpkxI*;**j&~7Y%vJb6?s z(8;)BQ?*4HS{y37m);7IGA_F<7(Vd#ZEQ8s&ss}Obb}A9q_J)XCBA+m5aF>leM8|}Hlh(Ki2v^L^^6$?)$6l}*4L|7e&#C?>w|uiEXGEe za<97#2|v24^?wex#BxGxf{c6diM4(}9U*7Gsa3-!(AHn_0aQtKhNuT$8%j@(*x@(Jx%g;`T z!?A=n2x8yz+Ph5YBUXh8WV9ahCBd#y2R%JqM78qZ8GjSX&LWtXuw9?E6B2U1#md{J z6(avcYV&3l)ram*pA){Zs%gT-?E7G=4YET-ZnRfz&q1C2VqQL!wc(x?m9cPrp<|H% z;KL>Ccia=94o4#Vke{-_o-O)ms4ir=sV_M%qM}jkq>Y}u+{Es)o9(CVHcTf-^NhX# z2Om_`34aZo3M$%3?+mcz5%fIjXcLGgLuQqD+5i_%urATYNLn9o)NrmPlUS&Y7ybr= z^+txcdr;>YkfPJoNYOH6Dpoa*NDY~x7JmkrURX9X9!)L+W)gcQHL2!cENU$`sv}2B zHrR|Deu~w61G}^Zb@ycu5k`&{@+V&FOa>Dl9DlG;S(xnZo4Bl9m3tVAIh4Dil0Jx) z=Hh(P_L#~-iVo{N>z6JMKP$ArM^DBLmSl{`u%{X@ZBgFk1#4FH$-XN4Fl~?!i5eHH z0#A!i+-Xah7WUA@+yf_B8~)Se=r&pBC*z#+6uujH6c4)0F&;-#+6i!Y5#D4iBgiGn zRe$MAYp3MbcAeGj^^mjU2Ehx?qiWQcluQJnUGse(&Yca`jTR}n!Y`B;>HFQ0DSf7D zs=H~u{3QfjWW6|Q{Gj3@TrrkZZbh694IKlOZWhV>j~2mj>6?;7ewUCL^c`53yWd-w)J zdC(LOZq{;32w@%(28Q`N$~^p^q^QVB{8+XcqLm6WMD_wQbPb|V{z$f&xjWF*+<%2d z8enJc2rz>R4GK-M*K;vdMuLIyz=eTf|Bix%`4bd*^QS+Sf8@68J_jiqKo|nw$*;u! zIr;yiB1#d3{mBsHafaM7sqa9m#D55K2D+P@09+s})8A6j*#3It;g`$e|9|1fOfk}r z=17pnI38P$isq&Odw(~(|3wY#q&${7~XoJ5zTBxVrrpPvTyT3w#Fg8GlER9Lbda<+bucq`mH;}Nn|_O?0c3uNs5qGY zms`Tm7ruQB>1P=b+gJNel^dadMin)4ONe#+H?vr3OV&7^KA!uwh_SzvG%b`C0DouJ&iD zt?aO%c?KEh4RIhX@Eu;);_u;q%#*6UzrhD7S0nruFY6nx-2P{I|9|SzKPJ6p9rvsF z#k*lc4=5teKTFckR@V4axAXciC%_!y)Ja3NJQ_>O|{ z{HG~a&gSOYR_5lm|GJ$&V?LcOm#K{q^HG49kK%WlFogbNn*10|jti^`A|)4RE#kWnvBh+Cwbx zyV4)p;fx6ZSvth)5u-!U}bJ5<$q@X2XkSaoNAaWNNEy+R`?F>(e_u+|9-&zkI5HORWl|KgPFPy-NhH$ z{|fov3xC+AlPF=zKBzD-{iM*{uBi7ffPV~uP6_{S_jT;26U0LchfWUrP59v4UrQAW zO@Pka`Hc{>@b~g~LX)7AI({Q9Fa4bqkI)?GoOa(h(tm4zC&L{y2Rg6THx9#xpU$!c zEgU+Z)i>c-n|~?06*K@kbIvya;_lzcqw^ngIH;sD-#8k3e=o%hGzmIE%Quqq{$EYk z0?mL9$oq}4dG+_g^FouLBg}py`G5Hv@n)eh(4kYmVbH(+Gl5j0iO|tDzY!H+?))RM zH=&8pQGXQwt)1bR?*6j1ZJR$@q`BP|ytMC`#WL6{tVMfQqREje!nz^9|#O z@kf|H4txVmfev%fHJ8X5z={p%Y>lkHDnek!mT44MGFPvIK@gXfP3f3RyoMIIjE z7ZD@m!5V38nk=oHGFcEm)U%b^%EOWQCW+ Nb^%KU2ZjLv001u84<-Nr delta 74951 zcmV(rK<>Y>js}(P1+cAAe-XO}oPZ+%0PjWt01E&B0Ap-nb8}^LE^1+Nth;4UWzDuF z3WdA7ZlG{?cXzkKedF#@xVyW%yF=j=?(XjHP|(%)p6-b6#EX7?JMM~=KXS(UHOClp zj?7%CC<6u#^7nxT0YC%3As|WUD}aK4T>Kq0f1}2BHVjS{_KtQ&e|FA5V?Gv24NSVwTXzGtr^gq-q_mE$tgO1T)tlrJ>+Y5jwFCsZ?^fiA&;H-7(h9F z3b&|pCf6+CHI)@7f7pIRh-3#nXMQY#!4-feLEB`|@(@fXd)EC6w|p9)s#f)CJP7A{ z&3hu622?y$SHCW)_kepC+nckE{81X2FboxZOdq!(W=Ri8e;X|{afod$44(YpZ`Q?J zhYsx!IlE8u8Yoj39Hf-g+qOU!)yhUycqUL}vQW}E1b3BogqCzLb zs&C#)IJji18O00#BGXG$Z3^FYd^pv&vszWHiqx^1b`?q<4a`bx{+ZK1V>h9Mt|+Sy;4O+m zW7)e}f8<#yu_+Bw`f*_(nf8Hb5Jb9%z2E&(r7PF%9Jy7}eMf-^6T2QvA@I-a>JB_1 zMt=hVk^URw{J+hvteuixQt({FB|CQl{Nd+_^?BU$gmdzGg8!G)`>Vg6r4O6rM zIU`ndq!MbFlJKkz+Ywj8Q`W{GH)s0!eS?(}e}NHX87G?p(mv*zG6R$2-d*=o*B)DL zN6XiC0w7gJ-$TLS(WKz0if|%$u6oYFZF|poZLaMZj3jGceFQp23>MC+X_-eeMzzv@ z4%v^OdC9NfNzP)%Uk6Y942{1DI*7q@4t^-y(mP=t>MOwuLHa|ymtg3b&aNZga}tUm zf8e|hdd*m8gXR%(m+lYs)xcha&KxR*E$urd3^NZ;#ew~x)3KsBs|Dvooq;3Sa~)}z zCV~S;PK`;wLn5*p)kzq~KcEvD+H;T{KcRjgKA^bVJ{ecVc1D-6Bo;dVSh9Vr5aMM+ zpG!3WUtDstk#{Jqf4OhKeD*4;Y4ho)e}Ba+n*e6_T+b5*r1~u)&tTAle)lUmTSWzd z`W1sO5?eeFkS*`*(S(ClJ*gsWHVL<Vu{|G*iZl|h)Oqr}&Tai$l*A1Gu~JUmC8 zuMLAfeijeRh4kqAj*A6+#+4d_ID3Lwp-2l&t3BH85^2$Pe@@Kj3!HYNM}}};L!l>RyM;v1o0sIECWZw5!uvmovY7A zFk;Do8;jA!#*(v`Mg2`BiV9((RJ53c*(6^(6aYU?dSDqPn@f7wG=zhiOF&vA5p>>$ zf~Kdanyg*lo2R)+S5_`FFj4b7e_Dgq^ywfvd2X9hz5;s^(8~O!r8-p?4G^k2-k8vN$m`D`I%0Ix%4aNMRQWRHr zHIFn%=i~j(@K1`nu`^bi|DCTwfq>Be-%?yrO7uU8ovrpm0nZ$n&&rsAf8B~W2su@l zlpf|OVK7Ko8B2J65ZOX5PY`(OQ{QT~Ki+Z9c0i|``vz5@UZGm9knCPgJw#?%-1Au6 zThdE>mOhPVK`mBrxZ63w;pBQWf%9?PsP6~G2u2fw+|SJoFN(Z4pC8 zH?m#H&U{Y8g^+*O0ZB&zvI*%)#;vLse~ts@b7>_n(HnBA;(xRm=u$bW=}6skIplz8 z*vD;09InAiM*Zcz#F+SXo#*uJrNSQ|RWn}x>iWBpI&-ojW?9dGfBKl+jmGt1S6|T& zmEF=nwjZ)`DKMGXantF%=9tIUW?+xn77IZKwN-P-@+C6o*waW3N0P>Bw&rCiMWuO& z8@SV;$up!8#a&~W7T3{Zsf}^97*!#UvG|ZJZB}ozi07)5wcj>pc9P)_?3xO=NR&W0 z{h)F<0=HQD<)S1rf7poE!f-Gh!DY20Hvyc%bM33fz>{X?^5_8?fZE+2$}IELbrpof zsLJPT4cid7!5Z0@FuM3|dNb%RqkUBAO`hZ;uon>MUCe>z1MrfcliOUd?AGUQPH zk}yiRV(e4br%q&7bB;{5_NzW!&diePo_XNyB%eS1K}fVR{cGXMd=Qff7`7ZcTb6Z< zTheXeHN}7Xe44fLP%Z4SSOFC^$gx?XQI}4_kX`js!3s&Lsu1=T;!N842RKf8L-M{o>T17k^MGVuRFRc+^Sv@DeE~-$|b>SCEB5duGxZ4u%B>n7{mi zVD6T)qXP$K<^~sNCP3fBNOJ6;MQ*}$>JqG%j#)A>lE&RX!Eo02+@>cHaL(my@Uzg9 za8tH}D6s8U(FjwNR8EQJ1+6&MF%#`v#)w!I)0hc5f7$@|mP%nyMcB-OR2g(-VjSSR zgLps!|4yVk0!yYp>4rsVjic@HGh`yal*7+m!3bJt{X|ZYo)Auh1mSn50U=mi_BtGI z6aU${+%hgHSNWN}F>bL5D_Fz4OBWqcRhQ_mtoq>R*!up8w6Yt4JG&|zqsbm{D_PSr zL%eYtf7(eS0zPk^q&!-C5D;Jh4n^N$;ZVf;9>C zrENp&qpbo4+&Je)Dd=aALn%?oIY#k%0!rx9(NJR@bIPqjn&YeVw%xEUU8?G@_5;uX8JGf7vNxwyq?uH_f4{TG606$ziK3qv zDseITd~he>NQ`e|Z>#x-Ng^~!q%$(~MKQbtY1>dD+zfqthcw68cNf5aL?u3f&hP)R z$6sJAa7g7py>Kmif)lZ8-xh0-TZ!p&`){5nKCrK%5DWz50qXy+E1Q_Q0*y_b7$gjB ze@yKSO{8r9c4RX{W7Gdtyku0+w9r3o30YyVf+ZCN(S!ZTM72?fjMFA4!^8)SqYCme zWsYI#@_FVrg;u6>(=M$yCd?`rIgOJK*S>bpVjZ{aiJM4P+k9oE|HWD?6 zK7Bw9z>x}|iOT?kDB@ru>P(M!Q}*S#RiGpUfAK{vU?#)>c>e1W{&4%!G&!rJzW zv>;hWz18oW36e~#8AS^2Edw(-f09?wah1F20YI%$r~OqaBY%u zjvrC_&_9xLDul1_W^3)E%8SYX3zZJ<^~E!l_-L?;-VgFxhRa-zuyF6#e;())VlwU+ zp=1g^Hj)zO8C91|zfD+Fo0vK!yP)n%zL!$dz|FPOVM+%L-n9Uv8~d3SuW_+;)B{4! zGEHFj=+d2G#GkI8#mGdQ`p|~&iYVVnST_u@SIoCrH%w>FyFB2rKFx&|`Dz)|9diKM zbu=*m3R$(?m#c5^2NNe>|AtvXF(5?PzR# z`$$ZfQp~$I1aAqWugX^%ut8{y0<{C?D?UoSmeMXQ=p%GPCACmP-UWUc#O)&C=MUh7 zq@HBS&T~{pI4QJjdC%gI1`G0ZP|7pdT=_b`tgVIDMM`r;d--xfS+2qQs{21n%f1nG zP<>(_SyGdas^W|!e?{~md}t0Sptnbi`@J@6fF>L5oVX%?-*sAJ>P2s22m>li-EL;_ zdD$O59d)&2HrgRgd2D}vO8is!w%Sg{3eX@RZs;H&%>NbP%b0rnr{s&(q1;uLF+PbB z9?4$Ue0dqYmciG-gS24Sz7LymLCeMin7pgsY5A=Et4bvmf1<9O%KaMv&uK4~q--7=v*6xmB!ljSm z8HnFdBtM7ev}MkTG`Yw+AIz>IkXrFdbl}0#vO`$Mp{bwcM-G7O6-4-k+q8&_DLyT+ zIdzvOC^^Qne_DZoJlBy`?dcB*e5_|v|7AkcWHx@r_Q%STetqJ?-Cx{nAYpT@+gF5P z9u0y#8d74pCh-E@zkK2>VY4N;{q!44TIFHh=afxmOV#Gs2d)3=1YCM!|1F6>xocE% zfTo?>viRN8)6?ju4l!eFx0#e{NvBwznpyIm9;~+hf0$?fuWzmk$<7!#VZTV8z`eX$ zTx{}USlTrWV5)H*N-ir4*O!JVt&d;je6hzJ;$w=xVHpR9WVnw>t+VD%(#>uz>Cq%K z%mv2h_;0#y6tB2eE!?8|tF;9!nX($#a0|$GuUHk|xlYp~jAzg+=u*+7TGbL8*|Mh- zTGxJjlN4eSf9OeJLAp0m9qg#T&c>qtMxY(vKb4kfnJY4M~sqBXS?!+UU~ zM_i1R?%U2uNi2CFtodfvX-UNX!t7EV;LYiwxl@m@=Om#}n%ay@mb+*y+m$1%4mv;B z7ilQJgeDEqBUpF0ZJDpZzH}m$I>8JNKB2(tY4fykXq`SCNk>`(c8VQlyp*bm=?6W3 zpTa&EfAidn5m0{(=1KyC^Tltq@k_ofdK5RFK!mzSNPiCLaoB?4q6Qbm9qO*&mfGas zMTiz@Tn#?C#*+h0DmA;=PwEIVYIs%eRd*?uLP4@)4vf%-M)1agFhqsG{^=D9Wg)UG z(ZvXd3Yct%kZ|IC>qKfo!^CjLeO|QYsA}>>fBt?5@-u9#^s*75tD8~?+aVk8l|!y^ zpoNt!*Yv);6QK-Z2^~jnu}aUqb)gOp-$>$2&B{XMiHv`|?OSISxKA}8Lv}s$egMq1 zWf@lzWxhP^E#;md4##Cr-Lf-T&QY16Q9urGQ8}i-??x%ropEEm=|2(H()(If`QomMQVzGL{?RjWi<<(xmFfXYsr7yR6!!#X=GnS-<;)Ca+X7zkBjb9{gNZ6KAaiD zB7&)*VzanFqJ3?yLQ|0zS(z4Dk#?vy(Likm#Aqyv(9#)dQe#>;-WhWr>vZ>?>{2B# z*HNaKw)48L0`f6L&~7U4KHtDYcVCvZe<4*}`H9bUe1A=pNK zA@3WFMf1CT)h)5MzXG(3s1_nir}8g@fLSr z5=f1k9))vC;rDR0k!fxnmo7GvTDIl5A@EdT(-4qCuSL)3p=i_bRoG#T!Q+%4e?&@q z$^T_M_r~-?0L5KZTfq4I_*<;xd8+jv>7Aq|-+?7N2*Q-5>(#fwUm|mFq(A&n-4(U{ z49{!7AxWNJTmKQ+@df^gtoDP;N?P(;_0-WUn6)9Iw4d7WTv%7T8&mc&AWzZ2^*VS}I9ls`)0sDe1QYd{<<2)E*DAt(>k*j{h*7HVPBVhJ3fA#kF6{CU; zbtrw9m+|-I63M7}#m&iIdYz9cD0F#4sRCwS2m~O6hCTk4{Qw6kQ5nW@E}t%{pGeR$ zkI(IvIFM`~GNyCj)fTv-_RCCP52uR$DnmK4*@-q{0*rwFxE6iDZpq;aDaSB|E(q%c zo!eGf(wFvFU6yk`&4T@WZ(xYjtaN`8|_e$$|OFf9ILe=7cLhV_vw7pPv) zFQ0)*e)}=5b|tN)@Uv*vo}r0fAGAj^w-mAfOjwpUGPMCYsMt+`OKj!S!b(xP!;H?&UmdY{hrQbiJ9} z#y!7}Y4#?6De3rNfAdRqPhK0nZP1sdxX5SvB%8wsyj+y;f{cCGW^NU)*R~Ae@`9TKh+y==IxKUj^}=)bT+c>YJn8ZdAzn6m~)oR+_Juq|FkDZ14Exv z-#|dvAwfWR{)_hH-k>L6;@@Kxtobi`J7y+SYe?xP8(i@-jtlXYHULGIuetPhR z6(Rr-3<*#~aXQ>y2sx-XwwU#jT!U~JMX~7CVN?3bM@LV7Pf z<$uG_&U5JOLdBfA_ftmljidM625AJ3kJIe!loLSPC1wTy%w8GzcHavo7?l7ukXgRXFtXIkl;WpvdYB=35F4p0#MUGUsJx%yUJ#d~+CC531Z!^~YLE$a2 z=a`~s;0Lgr0nl!nW1s`7B{RJK-cR1r18N}$T5tLLs^G2r*nMd+R@mkY> zar$Gkm~T(0HCx>EDpP`}{Sxl<&c3ni#C1jF-5 zEyDpK@$(v+NKV>2xQ9PUq3IgKzHzxjnmWd910Z?QESL?X0a$9i13N z|7Td_e+T|kF^h?l^6P@=;=M8=@Ic{2_9hsJw@}r_yvA@#!LfgSAIFS5za3v^{s5u#zNr(n2(=`eu&+|n zH+8TWOp_}SF4hv|&T-VoWhYSumZ&Avv6GDMPto2e600&Csz!*GfZcZc{WcW0&^(sl zO|!VFkUb?{VvkX?gns`Va_G5O6eUj~-NkgXLM)D{Dei_AE`8ja<=o9qfB)n19Cb6U zulW@_=v|t#TUALy-gLBeKXpnrNuZHu3zyZXPH~p;$U!&;tYY0Y__Rc_)@WtknLrS> zo4`lOdFk|*oBY$X1NAykX*sqghn9Z=V9iZtyhUl#bB{#fQe`@gg>V1$4a5o|4wMOHgqFT+FZgLA^fNKp`^oqlPX;B-E z#du$)FNEgwjG@tVq1`Pv#=#h2<8`VkIC|lwNV)0HKG$sBsB_UT@Q-#ytE~^_NU@{a zZq0Q2C-lMu*QU_0ARzbnARvWFDk(uzq=BQsQuuDs;2&61U95q=Q?#+JS#sBaf36s&t{-7oM(10HGYyXxqT5r)Wd zKQq+hOAvP+HW^Dv@mxoWWLd}TM&WSMf_uZb5!0ygT2aMwf5KXZEhB4IIIY&aYt1wt zv--XsWb4nUnDR4XFu40-YMe#y@SG1J6aoKNI7 zPF^pfOvE|ce`17@T-GLWVSJ-5n6z~gn1fkk6ej3&x>03N zHT=4UQGC#)*-kc|1}ZCg=FscvNIz43yVqDWL7RTRJWjQRF|^N2-yibX!YHLYq{@S` z_doGE%+BA@2P~$IMX8*X2QK|34f~rq>mfQ{9xu%-f5vpS6I5-FS08_CQKf-87&gKQ zVd3gpI3)h)Y`^h=*CnFmovwOfxwqIJH@4}G0^=O58&jOum9`F2m$yh#kfttSUiq^- z(GnI#h+jfhXtUcUUozZ`K2Y;L6FZt>1oce(yb8uob(jg?JWkR!mR&M#J(bpR|MnJL zz&L^%f3Q#Hi9;==+FM~oBEz$YVoFk@(D8 zrwH{u%kbtftBa$v@W(RSX0-2$&I`JT?n(tc+iwR_U6#B#1y5x)6*f9HY0Ek@xa|)d z-$~d3zRz~1;mKs=L?&ooG4xuW0{&1gFU?`ee-xj!=tk`1xVU)mO?54K)z}2W{4?9Z zP^vzbXZ)ki5tFR_A2wq@`;J4RScic*swETDghx|3NlZfn!+?qqyyIIg7^HD`@K|Pd zSmjW|$2`lKNhEE(-9yI>WJ{Gk@2q^|RXRaV=3dYbVDRCc-|a|0sYk2mg) ze}an&H@}Q;#GBF*PShSab2DYVJjvv*5E!br7}m7baa^lpZ7kDBUyGX^w7y5K$tFZ{ zRgtMNn=bNxkIFaoFpcABh&mHtT^{k!(3pp+g0y{pzSljh=Ng)ku*Ho)icO@fNmUz@ zY~TE3Au2$=j zXUfd+8;=w8$b}22`q^L&Zh}L2{??eKeAcqtH65aC{FJ4nsw#o$Nq}rkm7Kdmf0<0# z=!<2ARzXkA>H<9LFtp8NEjo3+4D50!bukUAJ;hz5BN?OZoUAzdjbr2}-RPQj&pZyF zxVwfSla}jsRmNU3vf$%TGjYbnmmi)fT-yg$o>UP@Sc{9gmG5>BJFn2sP$oco&d5b| z{bB=qZEBVsq|dy-aEt7*&HaQ|f5AdCB`f{N#k(+f-T)0BJDchN@nv0TcL4iY{e4*6 z$r{BN<;x6{)Tbt*ehvTh2Rh~RtwhC&!ZeFc-nPQb1(E$cd>e8WD4g`Q@LA(#fj;3h zd_vsOpzx#I=~jWe@TBPIsg%- zV~n0$ZaKIjw{%-b8O9_iJL;O)rSo@HVA&uF^D(?Pwm1en^OZwYpV%!FoFPcgpvqn> zG}fq6>L{-~L^w67Dyb5?P&2YAmi$Vp!?*n~@5?EP-Jl;Ub69t_R&_Sr{_k5OEjUfb z?cX~s88jcKwO!DwLd>eUf8o@RUmQ1idvp}+z7X6o+1vyBFP_WLda8cE^xYj2c!Mgy z>2LM1G<8b8Tyn9vd+wrd=@P-m&p$n^b`c!VUF$g}v?hA*Uq(z3XUz}Ox!RHVu){Si zrq5%pd7?${Mi!Yu8Y2M*T^u3Le^&=Ld@GV;R7jamI7Hu_Hsy1p&D+ek?F<{Qv3akSE1&6}NoUe%w{w z+IUNBXt4FjsK)2@NF>QAZc{{TFRM9fLw0K|ApR1Pujn!Z<$_Q_A$Bwigz3Klqgj19 zTnAcvqLtF`e{a1tXy{2ebRRF$P__qu_Tcckzf+GPI<39W!1McLVnvRfmjs-@=xc#% zv+erhO0rF%x&_S<%L5su%X90-wmq3Y5k3^L=S*-m$U3M8Vt;)}+dNBWqrPnpzA*VF zC^eig!_*RYKPLv8^725PNi-fP8n7NY4QhX%sykk~e^^?xw_-BqbhL`;a{8XNJ5kMb zKb8E}rkbnJ5zeWvbB{~*uC`*6Dh@NFL5mrA{Dbx>IczB56;sB$*r?vQXGl4w#G!mm z?nLM3FvlItpC(WD5a?!V2_M2sNOJcIXtg_R0BG)r1!|lYWbE)nb927z;I($vfc#04 z2;}5&f4Pk8jF_DAb4I_uea`9)W91;JH5#EQ&keTM&n;*yF?_6huitv)N&*9oZ0(&+E(lC{Hzye+pvYKBmsW}+*FoZvj zh$5_8I-3%v3%)MsyR|>}*GHGAXym0dP)g&!e?mDQX>rSlw5s%qG<_0`9;qU-Wzg9a zRI2zz>fdOG&YaLIr&(Ya7>V>uK)VLlZkTyQ`8cpDQE1dj)vLs-G@~`^*NlcNi!my{ znv5Q&&8nn{Dm7gUwVQ$|M7IqKKGfa$IBr(Qk0yJ9Roc~)Pl>ulnf61ipGT{+lSsV4z6f!bh$GYNCflm&tH3Md74{P=IpG6Nuv{4UOrmVsdjO za@U=5(`oG8nK@E&-=t-Y*P5gAKa*T@mw}#cT42)q7&8#v01W$ zJA>!LU9e~WF5`%I$Y!Fj%G6^u_Rtz})}hI;zofF7xS?gRxW| zsU!yYPBlI~5uqX%qIRoGWC!U1x!awW91&R7O&waZ>l?%?MjYg1Y=6`gg3^GWCFK}( zy}#9DsCom$t8k-Pmvbf{>{&9{nocys)xHs+zUF7e@3}Bn++bV;?UKu5>pZ+g`jU$L zEE0Pj67jj`Cnz8|HKE;TRn2Q-e>2TgmmR?MU$1#U?WWXqii{C&f~o2(!0bUzwA-lI zXRpG5P9Pm%;lGkPBB9T%UakiPfYOaC;-@0UFiiG+`g$%KVN;}w5^@kt$Rw|Y#UPfq zl=wZ5g7HB?c6Jmy7skkiF*oQ9H=qv1>n1*%&|8%j?6)_iH)lIHjp$Pjf3}{q>5@-J zG>05()g*a2tg{R&s|ydP`yah(UgWILUUtOb{lZMr*q8U8e2~rr7R}4I*i2Z;94nW% zprNUEMB}j7QaII2EGf24KD9*-qTVfDHu$^>#{57#!x?g>QHWOJ$Yk%Ba7k&7C;7b5yatOX6`O%a*f9swZBLrXHSI<{= zDG`MR=DL)HZIW@F0&xO!0T=v^&w)eGs;e%yHXc`lMKGNq=FlL|ObaB%ki%1PRYnP; zA2!m(|Hg7t7lVS2()O-xfUy8DLwXnN@|req<3MP8&cMdZGXm`*xSp|B9r@!fn0Gw9 zG7c6TQ=CO1bi$1jf3gpXjXiI0CizoLg-3tmkGN|LK=!nGkUD)(wRC9VKCD zhoyJQpJV0FfB22@u!j|O>Uatxdfvo}TMq*LxQK7}ph>46MKSZtspE1ZiO>3Tx27)F ztH9Sa4QFq)Ijx$LGQ>j~=$-SIkPy4G7tEeXFi(DdU8#_``_CC-uGjp%b3 z3TaaSJn1FBid$yKvk!S{-B~Yp^OKlR>wD(#!#B~;f9yq;1;FS%ME9#kLZ;naxnOYB zm(5G7|Fr*R8t0=tMoh8G9ms>ntD(F0F%)y{FEQ?@$+0*Em-7ll8*(}xt}LLpzxdjv zV0gcJ zG_6vle=RdM-7X$h2`TT>Vzq#_?oPQ4`V$=tBs72V*;g;ZoYsh1jLuk)@(vR{ihhG3< z#)AXN{E?LMdCj$0_TTtN#N8a(EjliYqxrOqUx55wyR0W$SxY7t29m`a1^+9&1RdGU zA>pR`ELt#R!N3m|a1GPDLX2MIMS<-i&c)Zr1-Fs&&e@SRJ)Tn=(|t-BRD_Mqt?Gz12JFz&(t92Ckqg>UjCo zfHi43R!3(^d`Lz@3PM-mZ-|Z7b21b_aGWWig zsQEpRF%q;dik~x3X{#mk_-4mR=V97NXPEC%2cUJ=^{yrUu2lyn*1_$gf6GwWy@v^_ zPcw6sK!UR>8Qy^gH^yQ&1lS1LB{>)lz^L7IAhPcz>L?ivK^;60Lyko@ZW-)!O11;@kk@+$<>29k)~ zYvAsU$tl;Q1+byR6{%n;W__nSbzm2;Ibvik)6gnsKpN8+p&YTP&Ryr<{gUdgav6i+ zK72!Sh}!+-7&Mzm3`U6$&DxCqb`t=fcCPcAu-ne zLOFPdu*mYV2DHGKf6goTfUwR{7^d#kkc^W~I_(4}`cUHgMEk7D(B;zY#`ViD>22Wo z@X>(#>^tvuZT>*|r=27n*(cumJF@`&FKk{qI~p2W{l})Ysk5o04bT?o^!H=c|BU|Y z=kU0Cc`zpUkZep&N@4)hEu`sBTE=>zMHm?HGB5fMZXL&Ce-$I@TT6Ie5TxLnasoqx zFan+_3ZKun&lj=+IPNNogA;D)^KqHnV$4HL@7My=?*jtndijVDLsp2l80{}O=QFSnZ@=Y(1C zF7;q*mcnone;_Nhw74ZkmO6yYjrmxM+7F;55+ytu$FmYKD0*RXkZjHNEv(JgTR7PF zBV2)u+v^9v<1T%+_ref;LH?P;T0o?F2^a_nBQywz`hPix5_ZBsYZF67psl?f(AN1s z&H)_BME~P3O~u*J+2vms8k$vgoz_*6`R-CpB&0AXf5==U^MV9zu+G4hDajBVtSQ*q zT*EGYhC;;_P?krKnv!u1aPWeB1-cQI!8L(_&71q84_rlS>m=;{UJO(>zi#g|*YLX5 z_xpOH_-V?T7)DG@T0#;N6l62cNBzC)elQrNZlcl(QMS{T_>yfY1S`5{xIMkhJ2PO@u810tEcPHMUuqZ{ ze@c0VTFnGJnuVXH(^pkTt{7x03q{LmpB+J`_nHCh6@n^^`3BNL;(fH&+Di2icpKXJ zY2ppZlYGHP$~dv8gVI<0kB`EWu2r7b7Sneb!+NQ_P{)+hdjSDI;e^djkbldux+ByeI2>LcP)POq}2o3c~TTbX% z+S0AB>6t1-fmhtcoVm>$bL~ua4&c#-oQ75yc=H)&3WeFmo#}-nC4vyj5WzxIkEn`Q zI{n#!XNaBL&kGBS<{9}QSL&wpnW+Y`jB6Lc%-tWs_5piUyO3mEA{IHc0_FTif4)O- zNK9X70GRWD-&VP(0b;tQ0}h)l8IQ}zU{nL&oN;b(|Y;P#B7c2OiUd` zfsUre&Okfce^rMh8-;mA^pUSrTjxrMVbQp7B;GO_XbgyLLFmyCfYx9Yr?B^8GL6oK zw&VIOU;&9V4tmzY{W6p}f9FRj39^1WTRX*Z&KKA5a--M#<$Gx@h}n&(1k^wW7W;*T zxkAVzBc`6o^(`f0x1yt$OoWe~8!6#xy>mB*j`&mKP5Djh1{TQ*oEUOyl4wja7{kV1 z0~y(~5elRhW07pp?C-qVDm9Ljiti!X#RT0)s*O?MRhB8`DOQISe=79llQiVA&M1AF zHsyB>7mU_jmPi5qga^*f=_g`2fXi3IUpQ|O>ZZ$^ZZ_KpEtk!2^uMLnL#?>q zMV^U-xGdPiT(=)Hy)W4YtZ!wX8m`4>H_{O(Qb<;Ec-Dn5B+sy9H+~_D9CtyBcKw>s z?@DX8Tx6ESV=WVgf7CJ!m5VY^MW8hd!)A|E&lDH8@69Mmp&Fb~K>_vKvR-J{aXaU~ zywDT2X@;ZFhv8eUZC5Tkq6<*nVQ-7j-O1DJA`Rm|54-#ootfaQJzFsg$a?-*+Hjlt z!*hR`uTP9W0FyblPb2JrMK717%m{yEiEN*aPf2*1W~ljzf20cEeyeIdhPuPPnq5mD+)D5TdH(T+<4o2m zo)ewBb4Ham=k`&|FlYIx+Sl)nS~@ONS;2@9O(;l|i_JZ}(x z85XSiZ7cKhe_KmAfv^+1O6W{>dr}v5;W3jL7L?z=b;LGrme8cXyvKtC0nz<$;{Cs( z3MO_orp}HYigqSW{~y#3?i2hE>f=FU5cK#X4+on3e>Mp^gSHgzxZ;M@m061!w9EHJ z^%o5jAFvWgy4}!54}KYI{>|6^{4ved>*Z+|)1AxIc&+Qej?W-D^v`pnyU2AOhd z<+XvNGymA8eqZII$L4)ynZsszcOk{PrpfpMFT;k@o&~2U7-dOs8b;Tw?g=~ zmC!@C{{e-mqu zv;U3YS!7Z)m4sd%JVAsO{5r-DbUg_XaGF^!GWsU=2~N(05{yw$mp_f3+yfxkKSC+8 zccj6TKS0~y4{*Gpkuwi_kI8r@#F3^D#+Z|Meg*Ju9Y zoZ6iB`w;qfd+al-6Qwbsfb5^yw3W$qZP+M=GQW|Gljt8ZtvkCs%UQL(o$CSR2lKt{h09>DxtxFf*JMP&@uMG;&W=BimL4thbGMr{x(6S^%XG;QdS z&+c~%`;9v}s!oX^fBbPQbfnv>H8|A?dRB4DUSdCP^-@tL+0H!+t6F8_7bY+2A8bTc zo(?H~yr)R1L9sfG&#h;t*vHP+0m~mfH|s8cudZq_HEgNlPE((B%J?q^dk$>Ie5Ofy z?H9{wpV;h)opF`1@lHa4rx5?La1>=*NfZppaD@d%EU zTcGgr+`VHrf6H+0nIBF7EXDKp6$`?67$D^>DH$O&wmG{Yr9{dZ35&z1qf*BMIGa=% zHiU-}jr$Jj7Zmz79Z+RL4GrxqJy%B|Y#h((&uW~y?JQFhLIJAxT##p}`Jn=}hpr7I zE6WfOff(|0l%T*+7)f4XWPAIhpGS^a#0SLkzwon&f1!CKkwx*dNU-hgGk)@L$}pZ7 z=&f^zbX=`1$h8iG=PP!r2nfG^`VAis)mUo{QM9e|Rc(-}i4wgBuSM#eJ@bm+0zMLK z+`AHj$!NTM62!e}qXNWe3Y1aiL@a^d8BfoQb^juLx7_ns;ak=e!f72^3_tx6nj!A4vx;{J+`{ zO22O(WFblWsyhZE-IX2OE7;!yFo}4H{Bj7ncetz7k_j8}(gI={%M5W`tPRj0eR$f! zYwLsUETVe~#XLo0N3L1V1*rP1kw2#H;Wa=mKy?yBVf-klLGoE zpg~tLq}V&tg5|=HIM)db>(&!m#sy}#0srB&pCoXu7YZl`OE1Y-(!HkBojkotxBa|7 ze<2MB6OvE;sC}I-Uf;o+ zT)glt;e3E zACb7yct#YF1KaZpBtoxJiXN$b9W}WXe)=wTrIH?LAXvuV5?#{HZMPwSo0#8kWl%1P z(V13SL0kr2LCiA>~NH%jG`@PG1ZzJhQc`;Edmci=;kN8ABf=5Py*KQtU% zAXXKht-<;X{?D-iZ0;MJfK=lvTriY7_Hp?>P@Q5zs1Wo-W!|_HoBIt(cZAfG;1%2W z5$_C@Oq@I}CfcpEH^9bfWTrwR+sz2}f3WsWF`|WA)@W7jGI!awZQHhO+qP}nwtsEg zwr$;WI;U@PI=Ow*|KC{;EAw&9d{bkMZ%h?|G->d5+MwAOi_$h{plfJD(z#e4Mi>Mj zp1jaC4Fay{(fbczM*4vHI{H?w2gH9r(DDuA03UDw0B95d0OJ2U2l`)aGrOgprmFj{ z>0~_aXo~^oOriMYkPX44c$R7=iGPg3WXe)mJhiC8ml@E3Mo-J~SVs(wxE7hA+z4nB zr6H!}i&?9Uzq59thjo_R3O^^ynaFyFsD2$iq?NWmtO`p@zuztA>&1mek4&b_*(mp^ z*QwX-sQXzvuJ@NYz*?Z|vH*w@M?ZcZqzc}ZxEbSi>4QYXM*2+@OU*HYhJVO)jtT>! zDbfY7E3wzbxsgEhOfll32de(CzY#||XHeZPb_WaO{Lz$^#C3b2V;g8i{s=@f&;=jf z6Jz$(Q&mx%lu@VYvXx9?5edWi;ze76a^rS;R03PMNyB!lx%c=|5JQsGti`y~%%~&- zxPgFavZBK~6%c5;WT2mjiGO_dLesjMgNX5-1fVo@74M}iX%hr9V^z_ELy2%71v{fE zN25j`hFYYYql?%iiK95RG!+n+W47P3gGmkD;M^t1R-YU__6*T76NIsp6;hozDN|KR zlMn;z=o~B{>xEF&95v7u0*7_52e4DWisJqc(xPbF`*eFDN{e7CqJInc8bs&cmM%bo zop6W-S8IYo3U=pPw}doXXE4rPa9@$@@<498L_`~uI#iqX6TYQm5?tfuEPnZE6ZIfg zD!x;?(*YkqZaaYejwp`gsgtEBR>njrS$lx;ZwU%!nfs7EyGcK8;8u=&RX@~^zaBcV z^ZJE_k=yinMUROR1b?Zsc6lnnj*DA3UfS-p0wtpmJVDlxWNB{Y?N94Bf4xyOYe0eQ zG7({+zz438=vITa=2K@yOqHDj2I%*qM-Dt)uGj+XB+sVh^V=>%0`PNR(?>TTg$t;;@~6w%r?fPCSr{`(O@CJffD2^8AlN_$!SflG z@?yf^#gecj2>9jK>kUU?g9>jN6mHLp7FZw+W!eP$?AiS1oJt)u&SglOZ+hCZFlMCc zz@PK=s8Ak8zXN;nQlqvIG&&->?o`4!_pO1D&_wU35aZvq7?!a!GnGG^nZgs2k8Ayf zBF&{HGsnps!GA5c`8jd2M?cvPNrB7g#P@wk5~uD(4q$O^FR@O_%>l*R5*?x`CW5jc z5D+F)5a|9)S$6f2lz_BvR6FC|HX5T;1*@|i2Sxc&%?+FgM}9mcCR$;QrbjVUDxO2H zSDoool!9dWHxkvCXf{n+Pui=0bpm%`@9<~NCS^bsF@FUYl{>kDT9k+MD)!Cxb^g^t z>5d|vv_R3zxJ9|cX$v(|@LxcH#B_jJ-8nXTV+Xtq%q@LJdIAk(zUh0o+@;<7bH~4+ zKJR^Dmq=={$MYskx<$Jucqa)icpPT3Td>_xvx^D&BHUHKw`UC=-*6O}{O8;S_p8BA z*I$>K3$DJcI}um4EGhMeyie03r>f8`cRqpb_502f?DB zA%6b!OfV^-ghxa{XT}15N+5$08F(8y(yA(*~Wwh)#xf01hV1E5uJ$^3hNh~hO zurXeW=qpev4$J*02-h%44KEg)XuwZD+OU^foav8R-y#>`lNbaTki2hHhcDG(2JFj^ycKcX+q9wXQM-Xk2?=lA{3ogNheY`xbk#2eI` zq(gF&Y|5#FB&yMQPUtM>el749bC=&=N-*!kq+3aor68XYSI~iYc-x=@pEfFtB!@G7 z<{y>5-Fnz%_}@BSgkxwQ_@2EWTF5uBH!_3)F?Kf0xq*IDvCO|BO5hZBS-JyO;4i2zN|2%`4k(SLsru1U zB$v5f2)E$w#sYjHvc2ClhFToMzSwh}Nxx)ZHYw!r8V>jmigPOY zen|i1h6l`Z?5FtXdWk(q9&FC`AbEqw2@8Mb6@fl@Dt8sbY(D>Ip`cVu=ZdRPT^?Tj zLO#@*A_n2tkHq)&0r~^AeGHA2Yp-C}Pwra;ppSTTlW?0PP~fXdqND7iNS_LjCW0iX z%E0$@duBw%k$0L+q=H5*3$<|~cPjww_H&~1Bic{_?xsQYT&RHcyL2YqmOI#lPy&N{ z(2$STSBY*JL1ezlv^#maEuCx{8(NAbU`~Gr{YRs+({jUSTRH!1A ztm277MMot&bwT=8Gc{Qm=`1Wc6Bx?cv00fhL#A-C9j7S7&IaM?_D9JD#D^kz$<*z; zBO-6{6^d3Ip_xXGFs3|*t1QYW46{u<#28aCA&y0H0BJe=yAo2Oyno=3;!J4x9yuJ4 z6f0d`>gr1iAVQaMBCdw~(kY8qj@!kmf9^Pwyr^Pv8-f_XIK$t0$a zvUNf=Yx~5-{y__irK|aXl7oPO&59UijXPqv5vfrbb?naT3Y5B5uXssmCiY~NHaUW# z+WUExTO2n>+3rxWq>ZwaS)wJr1j}6x%~7k<1gX+mF`jHfU4LlOM)8WI9Vd-N-FkB1 zfLcmE0ZCbs(g*bL`D$bx%M1aYJf-?;?{7-Oc1X)N@tG4=%qOLcn}5@f{^HlOE3 z4Svywk)RA|qlCr|TCkllL;cK53u{d!Y13vYO}yFg1s3sbZEM2CiVOyL4syG|^QMe* zS#os=KvD%z>wn&s>?AR&ov6x4*}~;vRFQf%^2$h6_0sRhT z9NL_;gDsSGoj_d4P<6NVOz~k!i~Dpn>L`Z?Vy|nc-CYn zT?OHyfxfI@Mfd1z@TOR_S-Nm+_XzQW-e%Dfa`mm-;-3V!g04eoHqAp$u^#R23djc` zAu!{ff`52y=PvtTyXO12$C}Eljl6jvz908`fkm-mGmI>XKM9Wd%7T>&`62BYZRo|U z8HdWOAX6piE%>XMC%ABor9CZA0efb1AmU39_A6kc}dWlF2E(xlP<9dM|W0U1FTf-=&EP%Mzh)+Rmf)N$8IyTaruoFBhO~bpO>|Du1OQ{}O zGO#qH-OoQP=dhWMoY`pyXB)b%Q}?=4_fRFgU(6$?Xc7ycTJ2NDbMP5=<6t&KqpK{a z!hgD!R|01hJ-l`Vdgh6C%{=PhTNCZmzDoDd1HZ^MuJc?7BV}Ch_BoyQ!Jwd9lj*GD zpmmBg9zhIVgvXZ(5$V%yn9^;AY!+fD6K8UOLTdduJUil5#H6k}+}mCmyxy|m{1QD- z&EMd0a{iPa7VedCiTOFI^yNRF=GhFg>wkP_qOMN95TZWcvyb?U5xx9{!(|DD)6EKf zL^WQhV+bvC0`f|hn2=ohB<+6=mH^PEaD1#$grY8)0M#MAQ_^Q-Nx9SuDPGgVG`)x$2SVlU~{m z{e-D8Jo=@u$mD*!3#Wdi?aP%rU6;8@GJ*-_gTZIj?<7{vl%|Oux*}Fy)?|IJ*;2ctK9TqT>2a7ZS?uA^bOl*!3A!;2BjHx3VRjW zeHN%muUD^9YhJB$6^L3?)qmae0J31zx-_(JVfBw7$ls0ov>~MG5TEJgrTu;~mR(de zqWXFS^2+X`&D^ui*egh@zS70QqX!co!f(Tg9dL=#5GdY6s>J+rM@*<>)~UWtA>2N_ zMPFHjK}p>Bk8d|HAwP4=y0RY_&?_F-BgRRQ4?t@o{;aNy&n9UYH-8@6v5Dgjzz@9I zgc*GPyYBnyq#f`}ra&_1%XkJB$)}3;R7g-(*#^d9pFZTOXw?hGa>!i=w`&PsG>TLN z1~xWDC6*>t4b?Eorl{ty&CZ_<3TZq=nS5Ie)Z;n(ZaDUkCIiy0TTCS&R1%lZuY(pdLvw`A1 zwPX>hzla>P<#8K~aAiupMk#g0X;r^U-TxCs{bH|q1tVFx$h zgqt**w!6-cx>)_WB6!OpQOiKx;rdk~R%~%C?$aNJ9ZY6SnL=j5B|?JgE*v#6$exsV zb({)XpCXbmZCR!uq_HnmoirOrST3g|hes%H}T-mV46?;qc+B|@l{~FyQxAcXo znO1>wweyAa-vNfW+Dc20f7k*r008R$w*bSxI6y@IdjE%P>i-Kks8}mvDkJ%m(4-kB z91-(Xu1uehsAIUC--M)~i}IdNpNaZuSjGUYLCLOlBw*F0%5TzDQwgbV`XUbRS zkBm@hq8DO)vgTG_s1|VG>FkGz&A;w2Pv3zFIZ@*(+(Q~n(zhkqK1eY%wVq|#Izn;f z-mJsUnPNX-nZ2NKP0T68glm&@r6zx%x{v5c^ekE&l)AGM-7OG<%mTs;FNQ0~rZ}(R zRLNI+z*?k;8eUvRj}HDjY!0GLp)-gcQmi^*vcCEX=FlJ&xut(bvox8Z&#?{gFoN_% zHxw&EVdt5M2pH6)*U1%S(}hprl`?_8$V8n3Pn4y2PqJfh#xxN#NF6IBJ=>ERrYA~w zONk~2FPNp@4w&^Ms~IA_WLY98oT5%v{yw}ME*y=&2)<&;HMRt%tcAoLgnN4#?4c&C zP~i$&&MRk+j?0jB!m~o)dabYymy?R79S7o~GM%LgEt9UM8UeMF$)+5CtwAW`iblSL za%!5Qe~r9eu}f#9Az!4t)sMAIL%9UaSnnp-B|oUf#)2x^+#;Uq|GQRw`FsSeY!+c5 zQcY^D;Z@U>emv8VLmgj2X^rVYUdUOJ1~!3GYqlVx%?^Koz7d(+IyqOrP^g%CxLMMF z`Xr6+Bi->sqg{C|%bPosWTzK@8|9(^2x0q}JRPV1v_^U|44*GRvu-@PN3Lkq?)V&t zhH`8yXRC?gdL#-~8jW7gLpX0?fs_WV`m1Wx#+RKB0sRO*FN*2i#P@Y}k@Db$_X#B4 z8lN=Ix8O~9+{_mv;U00PagQDy$>b?BHcfO(k`q7-+L;vT3CR8wNIl`FH#>_>ihxaas!`}JIywoDMk^_4?kP` zSu?2c?T0`szJ{}Fg{#tkk1B+*J%ps9U6+qhM-AlphEVsJlnvJ+wnC7YGvtSN0x|z7 zG!f73rR9$uuVUQbBed+J<-gk)yGuw(argZ3Mo2sOn^Dz^|79E7hYNGp?EPi$QLCOn zk5{27J>m-d_6={O1>1M#1J$PjE|FA68^*~0o6o%kUXuDk_YPfu?!1w}xE%lMC-W7i z^F@?h&J%S@#lcV0;2&A!1kptDa(50WmZ>zO(zS&lv>}8k7sYOu(0xQD;p&TX5U9+* zf1SViy;93B>tBY-oG-Ovb8Lx=wBZc=#iO?E?`6;o6Mr7 zd&xfOj3hZSh&Q@_IX>_r_`gL;6*7_ZqDTZw!#tcKd@DAc?qXW$_5B#74AS_h-BWyL|ZG7@c+TYMp6{AHS z0fq|Y$R;v>N!0=SJqZ^O+_P{F$7mt!Pv2Z1<>5^xzXpEb_ zohX{S6Ou!4?Y*j?s|z5nmTTml;ELsg2rHr%G&~%MGuJnFwO1P~d4}vqBh6#b(Pf`- zODFc+dlJMy?;&nH>|+lV*FDE2%V>tppd?besM3djpQo|U4*^F_7XZs4J=VuIJ1CPV zVnQ2kPs_#$GfIRVeI#6R4Ec9%6!{i>;t%0*80|K0&q+6d3ld3Xh17@Yr{aS~=(G@S zGUg&f)Fn8M=^)RN1-mnGu2CJUWoXzzpeCB&PYr<{m3glENGGqGgjP0;Kr z+{a;mmp?|uP|>utu34ID*%&OU(o(#omVWUtzQ(>9u{cfNbDir^JE14HnFC0)^l=yC z9L^jLD~;S2HbkYq#Vm1uC7@N$$;26FSttgUC&?#ie+0)VAqvpXnZ88RAQk+A<@lIw+!!nTKUEIa1?)dV!JvV57v8@KA7WxhKT02_ zht!{{4$*ALG_QMPv_MHvTFWBU_hGSr!)6i4qrMvU684}%gYN37AZ+wt^0q>?j%CRy zNB2o0LoHB2A_mh-9pZzmK^oLhhmA(#t(0eU6aA@I^r9hb^Nyg^=;JT$lDyvy^y<(+ zhG3#Z;PZDgfNWXw+cswsKZ9oRi69n;87419`2q(F#G!&Sp%53nmyU?aNWa^2E}Kq&nF8*h@sKFugM|AqpvUt_8sZxpD;D?iteKLXaaSSR z()n)y_kg(HWrc@lY#cGMfJse^bcHdv?=`+LhwYix4aMe}NKPZPp0n+zKQrvFTsPgH zd$*pwKx?s?(s%m7K^*AMW_oOe80%ro@r=<)`j!>QhQN9-@0}6#vByZ>$?jqyrT-r&_BtgrO z?!M+$#Y0!?Gy~R`l;lQPc(tzB5ctoAiVwxheDeXs#uu zsJw)RopvfX7wq(N+$;;*%v-!?qND=|E@Nxq+R&7f(%M%$%UTUgcQc(@9kxJh6KYK0tJ%< zyt!KRhNl#fP7^aG3=v@It#l!gR1-t2(|oQ*;Ni1O(OrU5n2rk!?q}frxhM|V<<5*E zH|?j3+&G5an=FKX1vOYw_pynsq>A>~n#GrwuSe;#kTA~*ltK>dAEb~3TcZ>U#{bxy zKG_jV&nL|_+F9Y)@bk(LQt_A?5yctBQPp60Y&cjD)8yy2e2|5P;d;BtzwwOG{jI3? zMB$D#AmHVJo^*pCgnlNcpSI&#dKXhEYthN4sFofEA|>g6YstUvFi)CtIe0|4b=w^d1o{0#l3xQ>iVrQtXq1Z&PiM<`;~DF_{l?W{h@_U z=916xm?-YAGg4_ZEV{emaVe91NL5a!PwSb)MW>E`_NfUfcdA9#1+w6xsX)+Lg_B~bJrs2F1>8~NKPA<(de7D9qrZ;Y}Izd zNX~`F5%hD?LG(*(9zGWrgQOl)z!xxaO|zHUJ7|G@J#E0vf!BIZC($||jQL%AI;Oxu z5G$B}-Qg9zMJ9uqrhZCmQghEa-4qF(bCLubNS4&%Xq|J=1RL-P;q&@=K0LZWM3AcN z!RG0GjZ?eneLg_@3=VFNz#X6>I&&g09WuY|{OtET3h!A1Y;RtEY@T8>FOm5-tm`)* ze6Mh_o&wQ}Ris+mv-W4|>R(uMuUKfGJ|v%i0q3oO(KhMI+da{*D9<;L-h4l>w2|Dj ze#@eFNaL7-u+@9eJvl?SL<1_a;DZ}SviNn5PznBGFK`NJr9eUZ0-{h3QKdq`Xu|*o zBC=?*UcqeAiuHV&zr=~i9s|ga;ofTdYStaGJ@OOheb)-$7+C$>quT9lWoI`Nh(&mR zhZJFRWJb^X=Fr^GIS+o9+IEBubEp2d2AcWeTqv2kNpbHd#!ga5LcA`>(#~mM82c% zJ&~16HbpOY@`<{I8@_P2hl7Xw98SD{1I-~N|CMShYrCoZPt9m;#D9$N|Cee1Usu6Z z-yIQ8(S1QA&X0q^$1%N9+X_u`ZVhYN^eWw~+xio*RL)&ThOJ$MCPjI zfQt8n^iL6Qyyojqt!5dvgyx<8IleQ-+gCZBWZh)g3^+O&&O2=l1(}}(EBKJC*}|RA zCnQg%#e|q_(@Cvv^U%@d?HkO0zF8yjY<+SpG?Zksa*q}?CAL_?vJ!^0fUi(C6$%R8 zQaf76sV`>EH3C;9(R+_Az+27ztvuk!_k4^FE!6zwPTWDa<%-&)jo`Fb1CzT_sxn0FvVWvnv^|T4M2hu9^04IIVWh+J_&|0E%Q4ZNZA#95J$j)D7P`Lf?!VrK z^gMD|#8M8EcW{-{*S+5E-@EyS6zlmZ~oH+LGKXxU<8u$~Ha=THL-Uu_< znU~*Nqh&n+A6(dc@CtT+un0*=z@yTnJ=u6Q5Ts1j?iqBL4O!TX^$LbHiY)U*J8H9^ zCYM%qj0VXjLy?6L!%}#}X421z&Hy=S9*oYVW-Knzk?l*la6O)oLpV+9mEKd9V0w%| z$liUHk&aGj`|upP(+&B5V>LTYZ=O^9r0G#4dd4ElEsRZkCl29SMDv( z_eui<{vm3BSnEV*mJY4+f}Rb0wGk4xU-Z01GXrr6ZNl^-ULkgX1Ms75fb>g0Pmj}` z+f0 zZZ(<3S>*l_ayPES!VZSpROF5tM)b0Bzv(<(CTB5sax!`Sz@@cAT}6E&#k|~liy|$t z_$%vt>dX;;;U>mDb7b}+hWPW&E}PYs{ws7R34PFO(w%iG7qNAj9yYL4G&T#%-OGiD znUQ&VgacOz-qQ5=dm`v%({0WjQ*t=!#vZ}LQ+FBo{q75YNwIv7QJ7X~bzxkwa`({+f$K?G zC02v6^3}oE<2h`xy+bKxJqCX{yEbMfI-x~@Xu9+oAs45S=q0<7ewWyg*&l}zNs4rM zmFQ3~R7EsE@HYEvV*XCrr^#u|YnoNIQ!0aJ8-9TsAN%1P1AW?y17QIXpZj_MB=QTVI(Lfm7dtCBT7C0mg2BJ)myV?a`#V__uQd#Tcj>> z=DhG{%K;ATfM#80B~i;hc#B~acveBJ>D-@xY+353eb1vU1htskL$DuC4?y0b*fZ6n zRv)Qd5b;0J`K5tf)$uGZ!zp>H)p55HdZhMi$CAqZ)p8YLV?hWxB}VgUSDwiAjP+_) z7*h6KE~y&Lm{6|UKQ>aNBa12yEI^Fr)RT(iPb=fJ|c-{Bk_aE<&!>;+(FwtlGGUp ztyse{6$c`hIWw;^op;$syOTD$A%DI5`!iASLyGfU-yNjVPdn5C;X5kn(^ECNd&i(^ zS-#Kwl~oCP(H^5~hn(L+**2k^#GxycUWsDigCnWctnh2BbyyLt!WC>>vtd36@s&_1 zbAdiUsbyWn{d)gvV^z?jyB|!)ir`ZNfY4E%N)f~Q5$Yi=z@&t5u!?*lzJHT)bpF=_ z&;=bA=T>)M^rJGtzy~`c$sxsNW|hcVluTZJ^O?@v*HLj0cE?QZrX<8(2Qpnzf5bJO zy*cP~sKt*?HAi!#v}OyhPK~gxlHjft*>a}gQ5@a|-g3=Jw6ha6{X@4d77Q%u{dmXN z>sq9j8?=4MFRSuAK$BuW_J7dT=WP?cYxi?scQ6Sa!gnb5YvIT;TRS!QRrlX}3Xw*X zL-s!a0QH~%09^m$p5i}m==^IRg_5=+qBs&aHW0qO03BJ?5Obd2INp$UFYB9fcoMlh zS>By|sCa6W)PmKl-^a;f&-Lz__m+dCi{&f-?zenOsi{ET5wURbf`7NC#|`^yRu8vs z&(AMJpEDO%Fz|*|uZgL=3b5@;*~@D=BL> zA84{1=S|BJzj1rH2E)=VaL5W~GpQx53Ql#88CNAY%3tR{-+{r7XsBpU*?3j#J+sjv z>uk3BqFR5&Sh=aU=M=4Ps7mPl$B}3>+JeX2OD4-O!C`cqz8I$nCtT|ZUx;jOA27u2!@Ht-tawc+ z8S=YO8)eI8XMe|x`A~=BZihy%84pqfI$vLjvsf^09H^gc-EQL^PF_+teHo&sGdEXi zx1XVhT>0Za)@E~udSG0)EHSeXTTAZy+@jK=4E0<~3=nA!9gLR5s%EE#$qz7jGc}H~ zzXmoJPR*ZO!0bvnp!%r|&dz3GCcZiW2Q2!YrXqjj0oMe$GR~+h@VG9?U5$o~K#BR}q=LEO?4Md0J zN=gp*8-F1$`wOUfABnB!^T)39&jI|J7!^ho$S2{*%?60!iYOA~X=ZQtPxid|vnnb_ z%{S0BZGuU_vn-B%#ajLu={xq%I)joa?99@KWa>-!{Gj`hUyB@@402@}$=VdWr$`5q zAa(?Bh5QWAjfi@{@YY};*lEvy(U;}v&zvj-0e=8MLI42J`X7g+l9_|Cv8tJ|vDJSD z=YI$E469!L^GDt9HWGLcF_)EPS&~IDOHu3`s(Q+5 z&411xyT7>0eSt7KN@Qh1$b(@vCIc=O6AYwMqjT4HNUhk4tkgI%8Y4`(b5=H?*piF1 zc9XEA3Mi+AOBf`jhX8c?OpS4M0+ z_BofZg3I)TmTa^PR^TnMZtx~&TAQNpb#R~EYG;XAn139xZuV*Vr-fn_JbD}@$Adap$o=j)`m%TNlI>Mt z8$1MQqexuJ2QMf9$pC&_BfI)!N8UzJ!;Nvi6LAUVMfRvxeC_dLLXq*owTl+XYBUxvMQTR-@ zN~_DRXcYf)*JmTB&Rdh5tCYv0tMjByO4(87OBbDsD^4vnKZTi~8{F_z*(rb~U!6Zw zP;^`=43nuxT8{b3AK7YC9V&U*2V`JRnUfp2E3VR|zYpMo>et3R@+iFAH#=w#k z2p+_gOd85fj=fPyatG4-rXTN?#kuB$C`Xw2Q?v_iB}|eO1>+uCa0^e%@8Eaep!{q`cG;|D`XgN^Kl6U7aF9(w2lzz zZd%XN499cSg_*MPtSxqC4=ZL$PxB16g?V+B;Gp1#3!^N~4yvDeIvS*HCb*Ia3y*DX z3r~-MF*0@N(jES<0S@WNm(MTO61tTJgQW&Tr7lBdvHI;A)_;fT9!xy>EtO6VV5ju% zQNKFItR7=@Zaz@1B32LIpB^CqU45{glAL=?rvuHhwrIdFzU&$7vot{r-hmNqtzoX3 zLsG9O&o?Aq#6uqZ-aXc@h+Z?VXsX>JHpQ?Vrx z@GlifX`?mLW`80!r1ES+YFqaNrrsq5Iyu_r$0BC2YasLJCLCw;_pAc|ma%8c6M8lg zckbtJ1G);LyHF>s@!llYuKY;oBJDr=2|$(5(*|$+57Pt=#ga85pzFd7qr|)YF}FAp zEZPrB;twwmW2pMnj+qyi`!=+3*9k`{4`VXo4tZP-uz!ohW0@0#x)kCz6tQ0IMD0CX z56KBf8xLcu_bLz#ty~YA#F0VC@qRE(tDGC_h3*WNz@?`1gnueeYkvMdJ-Odv zn}7;<4k60y+wIzVww`MD#P*EbOi$iI5lliJq9UZSQ6scbPcJdq7^`{1AYImwn;`ARV49j5LqVTN z1%Cy+3<$XBJj^^C-ue!BJUg^lok$mToqhIVcy>vp*jMwQh^rQU2 zXc~}MqQD2JzqEg6Gk7Y6`%SG@pX9lV?0?X#4=S>9=@eV^-GiKWIgY|IuOVZRI@fUk z7R&9FhD1@URv)N1xvh#BZ}9ioO76_)M+pH(Ns(fF(+ZW@WGJ4H9G!r%N|8K*3n#|d zVDEVo4UtlOf&rmX)Hp!CPg&8vOBp>PoOn(mUyDt+D3Ljn7f`hr>20RL*5JsY4}Y6N zARFuQ_iv2D0!@*4$eDHJ%iM93=!5OaKd8yKpO2i_QAv?V=!^50=(Q8CT^$X(%n5=< z%b#irwPVb=@Ug$KHeC(5WFQJ|0|pX(aEPapN>K&qqR~PAKu}~dca!%njvBv{2d^I= zpF60vp$%jSNUUJoAOOPPuQFXZ4S!IJVz_`qLCQw@y?9kh(h{{!aNL7 zFt$}MOpV7L;-H2yB#q2r*nG~$HNq!geA0$6sO!lC z`g}t5sGh^hU;5tbvZGem%=*lbt9}-a*36qF#DH(FhZcJ$Xn#0-8Pm`?vBbTyMWu6vM$9m=I zq@Oi{1WE?VuseWXVO*++x(U&@)k%k@%q1V()gNJcPk$8pUD*vO4lxbc4fTz`)Y;ph zqc_mZ!h%}WS((?+j`Me@lyA`?Cp35~j{g9uTu4gN_2Zkt%ZH)^$qpnvk>T*_*-!twG9fDSt4kqitS?C8XMCdLJX* z@&QKkbbl`gy~1)y<_OouSKk8Bj6Y)O2M&Y019ru=^ss0T?X^tPxAnxkr;~T<0;vo@ zeFYJIhqB;K8G{nyj`y|#eD9Kg%_w>Lq+=w?_F--8l_a=Z?_fpoEj*!mkIAI6Z4X?r zl;s{R-BJrBE_y?#M3t9#M539mtXbEFZ5)*(xqrdxhUQ%?-nn(AiTS5wA@h{FdXimR zr*xYl33M}Jzp|OrHB}iqEg5=SNgm&qr&3pqP8KOfw-P6}vyE=lhA0sh{pgT&)CW*) zYY^V7;`_4Q{e8zY6ZP2|0up$zUa{v581L%?{k7M68c2z7#`Ii-ky4$ zzkhyOdOp%``}2O#S0CJd`be?v%k~8EKIX(B99qkY`wGAPm!01ju1f7)|F9GR|4%qi z|J|^dEjtMd$p5$MWzCrTfDo%K4GPR&kO(3C4=)|(roK97X1X@+>E0i&q_p8-W!#R6 z&Pv7d(MK0BI+0P);5wxbf-8DPjwSc1s(-Py6Akl00*3o!LG$&9Eiq>k!{Hyn58W(O zdxZLXdBP`|2MS?=#lW=?QWf@moD|mqC%Ub#V@5(?PHnW|N;Z9g&raNA9UHAu@=RfZ zYR{K>0;!({d?(*O?!W@b#_^FVp{HsfKb@>|PH1^cz-FG)sQ>OGBwkyvuYXvBfPeqL zn~wg!ee^G<#MR3T()|tbO(n_CPg*e569c;dAz{(L$H(^vHgL^Sv=cuZbNR6Q5B0mY zAS!5Rz44zb&QIRm-~0C$*gc>~U_yUMYuANdrkN8Kv}y>45q^ugVt*l?s|;?;c`oV1EM9oHVfY2X(zHYmTah&fUl)BUhxXeFC_ZMdepK zn@j-^1hpijm1;*NFqsTJD{8wO>fb!lIG&9a^A37sN|{hlmF?YkH_g?fmE?ylKXDQnrIkLaEPZG)9vNNPki;*~9Vw z;#9$2(Jw4e000Q2{}Tl)C0E=332N~#dJ2nmhqs)26PHjvUxEap2AQ6mzl|lKwc_R+ zhR}scV+)ix%azTIHi*jR_{6PvD=NwW)V}dcri!%c=u_} zCugna%)00A$LESQfaje%GJlrZu~537gA!ekG4(#ku9PZi zQkfB1$m|mFds6{s&z-upk(T^Hep-s0)VCMgq*==-p*b^-qEpC3n^BrRb3Pqid}S4q z90;mlGeW9D2*Tt8SGU%8dJ|G9{eELqol~ha^UdXiHH;m4fFH&Z!++AaxwdM;iJwVX zNd+;wh6k#vp;Wz;@;D5T5%DsV+BETUi50xJ1%vg~N!2HCmHL>)VU;t`ila(&v9VgX zWrIb|X%-0}rW;e`l2C{4BBDZ8tqnpQ`YU5qfpW-o5zy(3k7Ce z;?wOMebNndjug{QD9`!*As)a_dp{YEa=e$dL>_YCiBY5mVSlIB6KJdgC9xO~l<6*z z03l<6sW7f1!3+M&|8c7OsInLBO?R9fjm*$gmv!7%rkcx)?g}5QB&cnfs=M zFTMGIkR>6C8m3wOKRNpnRxSmR`kL_KW7ck3d~m!Q4%+yXS#ALl&1V>n_+dIXKDfjI znn=PqK>5Riu79S@opZ4&KdfYW;QFAY`C}RkCTizIDuP3Ge(+qwdk5wv686tP&519? zghDsWaAF-oCkiPbT%*}+Gjqe*MO5%#@G=q}KqO6$vCm*Bq_kWh*gfz%di=eBlR+1$DI1yBw z>62rWCWq)qryL9>)HrPDP%(}wORVfCj{|;0#GJaeYZC{j>wjzI!hvzd!bZb7!Nh=m za(b3!H0Wmekn6j*;JrKrH}>GH!#J;RyHj8EH5f|eqDeaB)GaT$m1zkssU(ynX?H4l z1lKO1w|^-(N}zoeX9(9*bemjb5N{_?QHIQ4y?(0JEr&tJIR0d{Z2xc-L?f!INIW~x za1D z&<1ivHb8I`6+5e+tGE;HG=+7j>};HcAWM-TcYi11P#O_7=e>)t-SZ6g7`rf$^5o5E zA*6L!;(Qr~tSn?ezUL5Ty+!HYHef(^^I$pkn}!MS{qY5uTdeo*g|CX=Az5kL#yO8R zjK;L$>5i|mkLIpv8O87{a?N8-(fqs=kHw|`Pz7KS*YZ~}?OJpj+f+;OAKg@o?}xpG z-hUvVmR43=d*sA%kv-G{-Rxqmt1kC|j9uTF@VY@curYVAw~-Vq9foIIJFA|~i~mzP zH|=_-585wgZGFuYV^ZgWvrHFTktwQ-xQv@V!Urlt8}1;pKMuX-%&_Z!dgdD^0N~}% z;3ZDuD_r9fE#f8U{|Q_DhJ*bEnEeLd{eKp26T^E*R3rblhA>9g4v^Ij0^KWu+$&Po z9+}lX(#MeK9vCECAjrPVkC`)g5s8l{Qc(_jB??zFo%s+>FAO5zP9ZVbLkrimW1zIz8o6A%UW+4qvK7VRg z#XA04%{X0yIZ!M}=KVaY4KngRlvrZSW+I}3R|;rm1IR0dFK>%8IMFqL09`<$zx1*1 zn57Nj)XoR?s;-}PuiZoS4g~Ydi~la>ppSNM7{o;JW_$Ze{Z103Uo+xQZG;L?j4PEw#*}B}hNau)i)XcnyCg?3W0?owNNOYq=U~K=!czE(MykicnMd zZ_D#9>`t*gC307w#<(#>)~g)|E{?^3=#$z{&>2~C!X&cteWYDWK+eVuXJt zB4`V7#o`_vMby%nOxlSo){EIi(NT#_=P5SlJ*~barMuYC#OwK_D8tk|XFabc+qc`_ z+pi@ahkO1Pc zM;h+pW~H&0?1ea@1}TAPv?xOo@UAU8rlY*dRB zPT^=N!f14i;^wFd&^Vg>vT2_Odjy`C6Vf$crU?yLm@gSSinzMHG(VreFFt>{r;^oB z%7G;b@%KlSiluNN5PbC*2Qj`Ue%@4|uwIqS&(9Qkgu{}BWfL!?HGKLcX>()#2UwSW zzO+JY)Q}_)DJnLH+s&4QbBBrG0&^!2ks?NcWwf}M^&ed5;^-qDj*qbu5{>tVfGz$0 zM9^x@tvavZOCF9ZwKBk`-za|*(>}hD)QRj6cZML+v5C5=pn9lY9>Lv78quAzRJZ87 z4Efr$#FdJr+J%|fb*Xix8m`qC9(_#il->C?P@A6eY`z;09BP+X{Nri&q*o&dzwHuj$jx9z$Qb? zPEREE$XDYi3RYicsMLRXt-(zb-?p%zujsz&ct;eX+NLR%Y}y8O6N|}EzY>l@>2+3+ ztq)EJ+nzve?Iuev8LUGd57)289Yll3#Y7s;UZse)Q|8N;uSm?&?P;G3l9bo7HB9u=5R^A?l>M@k5;julF$bP0IBS4M&gQIB@NI#Hoqm<$(&3ef!Ztd* zk%@XM^x4{y#J)G5YD&&Isn>ht?>o|UdlGak}=!fG#^Te5GDh z!h%jv>|WsyU%7oW!5I?`>m8sglf>k(U2EJgmi0H-5XFg}YV^WCE>tZC78BecXTE{OK32BClN3;AG#Af`Qaq zg5#BK*rztm%$7|ZTE2a{7i*YVI$uP?Q;rtu8H2@eU4-#E42p?_LI)y!QWtd-Z6VO! z@>>RJ1c`m%BRLye>h0vK2L|J0D96X#q|Yo%Bd}B#5;FKfBIM@4r)#qjn8?8j%a+sV zs`Kb6ai@Ql@ACl1mSC=Kuh$xdVy+!dD|?>SUy*dO2y~+}xZF;?tnbJ7l&HW7esOs)6(v$5$0H#%GHg? zCZuNaFk94N$~1BAgnuJM^5G1lLm-wh-{WMSp@}P2Fdy6t0giCoRPL;v|Jr*V`%wMs zx@4daQA^|)V_7FCvo27vNB*M|GqYTWEyRC8Br3K;q{%p|lB(SEcSS&MmJPhJ|1@fG!tKXkzm!Yfo;nr(J(nU*5vh33_f-kasbz-o`{KB59{vSJ$OXa>y^K zC{a>PldN#4XtuZmtv3a2tE?%v$BN}rmxuK$pb@`)8&ILvs>q1&;D9m7#nF2iS|S&8 z_EQatNtCj@Q6A~TiDA2Ll-q$P5SX!8V{3oIpJhX4 zJS5s!yR~!A&?wRe%d9@ynEk+6pV}5Wwd7IG9b)26@C*R!J)#~$CmO8fhI`1e>grc! zP~?d+bWs~^bl>M9SVlKxlNBe6i~;WMxA#>l?@kIQmpzLrXIlr%)4KrF=aYMTXV&7Tbu8`{MCWfx@tGEmkY8T#KbxZ^pt<&EdxG%Ka(Z8o41m3FFadvqyPrh|+pv3V*Y;y@c)7||1Q&SV}RTfD)!u z_J}HrW~oXqiYjht(wr;|kAp!RI!(|3XvFv6`qgu1`gqoQOHeM*a|`}r^#MV2BWLo< zaREFHJH6B=;CUwdd**-R?<{cuSQ=F9k6(GfxEN+q1V5%1!CBp{o$1=EE)?J_iZ-*| zqM;d#c>@4ZpfoB%!E_WYKKBdwCXrvLDJCj~=7)fcSeo)&;kLT&pT>91pGn2@4V}Ji6&%bBq4u&v&up;FI~9bG4M1w z;Eb^NEmG56Y^qcvK{s&!TB42a{1g#m9K{@L6LZssz(%*-SmE62+*hvZsAot}llGKT zmQ=Lsi{N0YHpoG^>J()B#)<+2ReXW8SCjYgSd8CnMC?bIz-R>E?xnS$S7X!r#?ZtmGpovS_dxC9K|+Mzh!vR^)$l2l)q=B*fQM4)so)3&vAu zE`HN`CY%gg7q*aX$t&z4h_F(hwT9W6n#8?13y zBI#GB;8A}VF;T4d`1%^%o%e;73BJN0$B?Nik_y#@pCVkGiD13mJ{JA;e7og8b=y;d z`byofoy=Hg-{5$#5LS>l)1OEwvSfeW!Jdpx!D@}UGx7w+XPU=7KflSs z<^m!H9!X;$KofC9h4h8NU*a^NGMVX(wY%*KX>q+nkHF{P+U0%(-EU8R0`u=Q+q|P< zX`V$UoX#K^H%27x!bD{VwqNY@@~kMF&}$tV(YZw1D)k*9F)(8o-x%9Gc%4>ZJi6hp z$@qUYxH~R8_ZqU>bb~v$A)i?UmD{MUHW*s0vB#qqMcf*$=lWxEjU+az!q9@u1cpl) zR$NF!%A;j9Xj6+91)(U_(g<+nP<&NH9Lm}~@$ob#Oe(0FF^j%r_?F4wDwI1V`C=2( z489PuJI;qD4b`NGKDQbE6cq*Pt#A5yTU&olg(T}gag@{q8=7kHj$s5*HF*+S$;HnQ zDJ3kDU*J}mXcT9XC9Ax+ci2#uyHb_!RMKukZuH^(9q^RA_yMsX(DZp)0dujY#PWMh z95;Ezh{ipmxD9491z>M)g_bGo& z6$1*d_>%y%o|U9OE0`*yB94~k*dBr4m)MU4?>dIbr|0J{kTqlFA7r-Coi3K%H%<6e zuv@Y?SxyEof3B!?AYnhO#XI^^$uXS=8q^C96a?&jm#WhOmE`CG8>tqa4G~EnI0OI z_D42h*%avmG~?oG{pat*EZ#O^3^&Yq6VrQw$vK$sf_olmZoIAx=X&!JI|P3`P=9xL z)%}^be7@fHnZ5Ctx!Ll0-jp)D0pkubw1Oci6P=$AjuXDnH=Q0!LFi2Lb2+a`uZ0T+ zGHh1lpuz6 z;FGSSn%f+zc@#Hm>Z>%>=Z8TNkUI;F$z4)S}nGiv+zYZ+{B3bo+7j! zzgbb4Q!`Taw|NZ)q(Lce)K(x_$JM|w05Z~qG(yD@4>=H*%k!ZKm4|=F(FtCI6^x1* zlKl;lQSnuf(|@?5Q+Y zf`9KbF!2C&#~SWEs!ZIc9T`l^&CD&dW3Rn3rkvhg5(e{P8gWQzN^VmexO;uXN83NI zArZlGk~0j;Fr5sB+k}5x`rD?{`Xn$@UF8lM`jiT-6f<)yFs5xTFyV@0<+r-{o!p#0 z-j-is1LMm}g$qGPZcU{fW%gpnOMhqZ-hL6l1F!?~PBjKmpXfMUCtG)L%w4;}wF8+i zRCSNZ#+Ot$|g#$LAkg+saK0NSuF!PY1rrU{~Gr5LZ!? zG;otrQO^sM5giVxXm{r8!#2U{gW3-%Mo_qQm<1*|;N8mFE0p#B`jYJw4JSm~s?(H| zM)5&Lpk_AMx|lb2nRTq1eSux6B5B_HM*CH(mNV)itbCh^AlX&u;mOyWr*C~_F!0@E z02a;pl*+EFaVvkQ=>vD58cv5IdZEQHhxvf?k$|KZGeZAAb=d6|HQtfm%bTLh_jHSr z#gdgFxN;cuJvo1$ck#!m>H!tX&p%P`6~>*4JHElCIOsPhRrbdOGL_Fu?|R^fNTnte z`a2r^=iMekadWIZm#^E44`%&ezl~~Yu3X@dPi31QbTWTkG`73E<`dK{1&&fxRfw*2 zQtdJY7T!y;+GnF#2{*)V!LUt#5yQi69Out!Wb*&=LLM{4wv-=Bo;WqHgJSm7KUf6& z{nh2^jZeD$4r1Nm@eHc7Fb{3{K9HMp`j@&C1aF@VBF@4GUZjxv<;E8ztquHzAsu8p zid3|jxfFj_@|MUOf$QkG<&FDoCk!v9kCnA~Jr##-%twkBOa2?uPT-Yr$m4bkS-6>4 zro1pm1)9EuPPHR4AI~zy^eBol{N>e@`A!U%W0~z>ypv1&BgR=a-ov|~w;MSc#kww_ zk!mC~&3CU?g67ddP<&OC9dCOi*4!j0f)ynq^r(MQaXv-qAm4{BXhQO*@6%1d5R@3K zM31p1H+SA}bGI>kc%AJ~^MHVb66bQ;N^c1EtYnM?nha?YOf7ePPJwUzq=?M^4wAQq z_d!O$t|%{Rgw2Fq0g!c+RF}IspJgkTHFHYf>>)d!drwLWX11YZ^mQrx^i_6I1vjgY z#9)62a);^8<{UArC?uh68abEMyM6{aM`#b@OOAzWy*I?)u(egYcF_}xuF5v7(BNYu+9cizPf~_ z(g(T}@eiz|Xpaxt?5gCKNfX}K%UNo+kJTW1@Cx@~U675BJFdzx+c zFFA8ZrW`-=V()|dXFpbjMwvdYNc+e~Z)L|6r&(;Hh~EE21}tH^$j28P1Z3@>3y$S~ zdbx>NIh)!7{$uooydu6Ph5#}f(FY5TiCicfoJxTu ze-to08hZUOj5^X5uY4jwf~>idaRaa<9~80Swk$L!@g*ta4?ftMx41!fhFbYCS3zevZf{Ej0Daab#vF;ePxg6SZ3@`4`hPY~o7G~z+ zaeyN#C&3>MkpRXsxyhol*(rZt`{%W0nbrL&9?wab!Ov&0t}^wqM7md2y4VH_n9h(q_4+ zdg}-!@=zX`yA2n|tq)=~$JXyRIh$Nt4Aht8Br~0zlq`Q$DGu~s9Vc|zjq*j&LYsVROlfip-Z%^!Ji}GMyE4?C3Uu^6Dm8i7S z5d5);3l|W-x4*kOFu-E3iuS_)GL*9OFMkU7Mm1=8{}al3F#jDH^go5NlCi7hzez$H zTiFAg$^UTus4f87P~9HTW|5+(q)2oH*@}@n{>j z!Yda)(hn{r*)HIIdmajrs2`+rS;ET~Oa7KB`ilHQ9m+Pg>10P^xDT>$H@^`$-HPq@ ze_S2h1=G;!oY)IXp;6B;B9b0)K(UiXepy+Q1UC{}^)f zOjLjSmG!9s&wXNq#uWcIsuUwN9tK<;bHb*{Gf~`Li@TqB{aDxE#7%laX@fh)81XG4 zDA6-{t(&r4{^;UcLyOVYvU8OnYXCt^CS1UNXobFOrtbEDr-dc5OW|i=eopOk`Oo8l zj%cqg<9&JP(tXw_cd_y&YH5UaN=?ywb1Hvqn|SQzWLS%!iZ03)u#PwkqpLb+M#0=Q z%pR(?shh0qC^hVbKD zjYc3l7J2@}6s$7AT7Nh4KpcP5Z8DE5_=~QyI`)a@{F3xVBV05>=x|7Ig>bXC zjpLnYo7j}w7P@5@H5>hLOBO@0$Ia69A>|Y^7wHjYf+%DnS4$R&sPft#ID^X3K05a% zEj8e{<5^EH&=cxBwL)TQCkR-RJpI1he?wgP5G)b&0p7sF*(5r46ZMoM?P7mm-T9|7 ziN(scp*-lvqI223P_mB-miUnJ_gx~&{LxEYAVI)kakHxnMi_I})(%@QV?J;H6X19F(Y?uX$pDDxStcCUGK zEeP(qBTSwZ`FOn7;ME<0EZ2YcW{$;y@QL_egM7sVhbR*g1O)$|VwC&;Daik0CZDb* zx+caKQaeI$AP5**y#!q{N)k!)GTIO+i9BN2uu3sDVFC>T5Mf5HYT>=x??N^;)qv>j z;E#^qTuWYe)rQ5l^tUK>!odY<9;N{Gd_Rd!yJzRfd*z>6NQk|!!K@@ju zBBLZJQz=Up;C-sVlwF{&DTII5NUK+5C2J0!!b#%HolA#Qgj3UMZ!(>^FK7~?HYT2P zLQ#ZI(#<)?$(fGhlGI$J(biK`BMme_40V0nuM^(xmB5L#8YJXk^7`|IelOk|Lxz*5 z>ulXFsPh|~HA8=lH)di9fxE=U8||TyH^DO|%bG)P)zwUGOJtIRve6uPM#WwPk)e_F zS11n8nP3xkAIDea&WVu9F#+UfqADErjQ~&;&tQ%v1{<gcOO(m$9&rAwX_+-;rp^=Tf`>qu_!GXVRu_M>ajq+lt6^$@?E(N4uLGTb zf(@Tpy2C4h;VQg;3Sb+7(Mp?lG?3D8rs+Zp45TlVM>3aNb)K4XRvP6WoOCHPnaY@O zI-8>#SD`5P@DtX+OcXaXaZ$C;A|j|`6UR|-GG!Oyv*Il!cS`4^;j=RvMI23dI4Ic7 zZ1HUU{04so%U_*MzT_B}??iDCaRY6Mi{{hJi>Q~)C1yE^XstG*L^@`5X`z@@BD4Uv ziF8PdY>27)r&fu?w+4qOE7Gu4H?w>9{cf_Vn>iaEVODbdmE!}GOiw#LV3EYp#FfqP zB@sMw*_Fr{t3!K&?A5HAkdl$Wqkypu@Tq1x_IiIRvHofY5pj2Xa)g<3)&LR^KQY8y znEC8$j+GRg&_4>xC(`F+rMggoWZv-12nHLT^Wk(NqF%It+kvXruPK(@Gnh;ghp90Y zc!4rlTcLJh&0#$-XgH24SJNaf$@OZY9%p-RGATlQi(+4h4zVTN`_L+U#2 zgIa$ljY^QBHY{PI`Y9j^`lCZeDi-tlOUCwbEVgsz7w?-)6V_A6Qc;f)$@3 zNc|bznGTA7{_6Mti}#p}Nr4&#(H^h7nO?b@*TEcX@CjEPzh@08aYq{V{%qfe9SMJd zQ}c80#JMUafnFHD98HYwDK8P?`t+UrX`j8rIBtwBDo=J}iY>yB*<^Jt(!mL4mxVd< zqxJ<6e8SGpl~lh`uBp>A^A6kk5y>rSejwEodm+4(rC5bZxLV9JwlMFYPXpp2^$1zP z43>{0OJ6kZ#*VM-#P5<3bs*+uHQ0Z#%?w6}+N;g(YTuLsDV5ET_-Nd}8GLCa{%vtJ z|J9-I<{fpgb%h$PY!gDMgw1E-Hh$v^C-)Y=K$z#@ud3R|zkGcJbIIEL`p2pU{l7$Y zk`A`E4j%u2Ix$Otsg2~nX*F8{%p~3H|C4xVa-5JXxCqMdF1feG%u8)uT|8kT%Mo?Q~eR&qkb@u0YoAF;At4guK+2w_bvh3-4k+s}O zE}Ez&HYeR#Z3)r*!3mi*-t2!GLN40L`%4-^Z%5hMwgn(8bO7P0KJEUQzg40At1`4c zeoxDa#CksDz};i2tpxq_kmM7S%3T<9me!=dtr-k~^Cb%7iX;WW*L!A^@L3_9jNyiO zN{iq@% z0AZ?&W@jpsE4T6)8Dy24dLF%uqm^|kH3vUN61u$zMZ1xThs>VFTTEo9lDl?Y$Db^K zlTtpVD*~v$&68a}l+u5~YEtqx_;!t~rzt0Szl$nPN*``^SGn=o%B$zswhSmaJPb zfdT310neAvp&f>{ z<+5pDpB^!r6dQiVSH6p6^M7RFjTkf?b1h;Ufc_*Qehl)TL!Nm_Ej!%-k~eL3G~sTf zXKnjjzh>|9Ja2zBKJR>;jv#|{+{Hr!9HpsKl|i}0l-Nf7(miSIVlqrs)~! zD}F571gq6e`4+yRYIH=b=&%n>IR>g94ITqO#s9L41?5B`UBIfcRW*v4iz-%1%Uc+M zUe~GsL-{I8q`i)fYswRTxX8=bpPa#HE{~NR(<%rH5@p!^g3-QKrq967tagmK6g9w&6vR&$bO0f_e zPCx^yj$9*>%oFH{66Sv|Ck2{FSdx}Ijn8o*H@CAA)QO-C5vSBc#WK?`9&~VGu_j1T z)=0t648VUop0oy`?W~Mjit#b%Mx4A)7Zu}4_pEHsbRShi?0Mtj*Tsu8EL3ogNXoRm#YT2-Lc7nUMqUR4K zusbMhgN(E3AJoLTT#0*Fp2$mIV{x^1Yh4?L1^K zvqSyP-yw_7Km6*+`|i6_Y7^pL!$xpC(r0y#^zLM%KzW2F>mTeE+Yj`I?MARu;0nU_ z**g`P$8v6k1PgpJe!lMg@kRc~(u75ds7h&KUBE?{iL;uhaT`@q>RGI2A|$5jG~8lo z&1!$8!%*lg8;bpovQLDhGT$Nr=NN?H#=5d7s22iCkZ{`;HHc%j*0?rY;5>bnf_?=lyM zczIFmkL7R4KV&5(l)&Yt{#}=#V~wpb=1YG%WhAR^C=%+P&!(Oa~JB9!|je{u(NN5h0p73EX+(g zupf_w?h(>oSy>N@lz0s|hDf!14a$oG^*k!Zj*h5vXX=XWK>f!kFXf~H4XI8&_5~j@d)=_c>`snmwvnA(o{qrM85PV$2rc5xzDiv%aok;i z@YbxwCYGC3a1gDIzl-0upy9@JWg~s7esx8Y&2E;;BroB9)(9K>NX-Mc`wc7LI$K|= zA8NSjeY%29#B~!s)!$XwruqK z;JkxLma=o}EA9l9=jIC%q36~eO$&d6bN;*{{`}dY6HkAL&HLjVjfQ-iH6*8|;2_(+ zLUiTS%ua#nw1|p|F4z{LQ0yB0(Fen5Q~IJqQnS`iKJuyPRLc4!jClIND z77M7CDW5LTb^_Gvr4Qu9XJlkZUrrb7*R=8$gZ9%`B$wRNcgZC3!Ao0JO#P-=o!5I9 zFD=U%=!t*3B}dxolJVEa$=^junY*!|9z7j8g zflr-}rNbFeCm7_&>T|;xBMpC&_J)2tGZDSpljf(Wp-CB|Ls#T)1RR8)u2AH7rc4Z@ z&nD{f-^r;TSb5uny{G0;zyi>q$oa|kgC~a>a3%BQE#hl*0brU3xVGvwVSv3rui;xn zuq?DAywcL+acL7L+)t_e&A{pmNcY4(`)SY-y5JyzNG+l%ii4yiH(!5k^WUF8jfDPL zp9~8czUt4g2>g^YYCQ$fO$TRlTwt66Y8&;Utkt^wy8C@OeY&@aXn7QH?>yK^z<4fdzmQMlx{X| z?(hTWNM#mo?=S3!5rEg>$z)8_>^=ql>?9Kpt3Ph-8V(nC;b%p)Q#RY-s;y~_JJ!QR z%ZP!+h{GD5>`c^d6Nfocl=OGXiy!_?oSukJWmFHs&BBOR?9qR_Ju+k5$K2KHzkE1f zgbP#jg$Dr{A^h)p-v67c?B99ATCjRq!d0Bb@l_D(NW@9t zf+@>6{4f0j5hwjGp05%H={TBOa@2jwmRE9GG^)!Pd77*htCtN{RyHz1gE%&5U5jEhaB!1njiFNSRcQdQ=O%{F4ES?Hpg)PZ5tyGk3xzCGg}p#0ouaIp^R*3MAzCECF}|5nPtS zbVLT9vdX1GH>Z`xwyd<0(}i?Q`jz_XAoMzR9oF0drlx;|eVEJoY@{vaCmcr*ReNbH zWt-%q4!}YzI}ZBILsNH~i20;YQ4A~U6l#(3zI!WtN+pamdeyw+znjBe)QM@)Jm-51 zr+fN;p`e+p&%aOs`KTOK%D*GzBj3^WFa=x1Ay42e$BV&w(ov>SxkV1drxc}(Af@&O zxJbdI#`b@w&iWk}4nxo)>$LJn5_l*a@9$t-^U-8EvdEP~tOGF@v46w~nTc->1cu=v zEC$xp3Tn*CZ7Lxx%PbkE3)jS>sc<2pW>rAJBI7NV>x`FoT+9Ddmr=N=+b6cNP(#EI ze9~GYM$9lizJ?1=R>No66k0|LoWWfjiPvVRhbn(9B6DGtI@#c2V-*~9P>P>lACeB# zrkf9T0|NxoXu!BmB{3pRmZOy#`|;9Oa?|6R)6)w+l}Z#~3WBDe$Nsvl2facoEhMw+ z`;*RLM2BA|a)96}&q~5C4rL1f_a^5&m}&yGSp#{G1_2V`u~r+odL|vYzN!83p?I59 z96^7;_x=?{-XnZfKWP*SMZS}9K1UNBP468!q=A(!q^xf#z$B!5aFq^oOPS)3$eo&) zg3US|Z_XKtjV$xx<>ddys#b{@e$~|x7yO(_a8S3q))mr>3S> zq|BYwY)ocK6F@t4c|UDJ*bM7%{PASj_A~EI>)~R+pi69!0`2`)Auz+VhoG#tX*Tj4 z3z3t!65h8|?i6m)>z1eN+j)hGdTncxqNXqTsPSr5tjK@Tb?LpNFt=Hs!3l9kmMVX{ z=D^-BjQ5XLpOQc`6Y=W4H{wmAr_k;#Lv1flfnd(kW5X|4?hcp|Vl$YXyd?YSQTdlR zU?zoqe<>ac1HhvHlgsk4gylfOq)$iqLx?3nP%At(rzo7xr{ zava|hU2jQ_1$aL|JLD$WBe5@y08lj|OB3W6J=aw~%ld*MqmT)wr&D&6xFCP|X03;k z_l%v^aGT%;<_T?>oRdi!E=3(3PQF9{Yh`>9k>Q(Wry%8jYnF^d!lbpaxT|Ma*^TQd%iW-N&z3}FF8Oeik?_vl!FCD+mRn4 zV-9F2gv)U5ihH4GiVq#Od^mq6s&A&@xwoj(Y@-OW*(?Ts*}`)x)!*`_dxQp&UkoYt z`TDX9UHsnVMQ?>^FuQkIVEktVrlL4Q0^(i@t>OIauBJ0P-dbNbbT&ISyffeVxSopL1srnv%>*B;#I&riwKRJ?xjwlyy_z>@0#lcHjrAlLu{j!IA^+-4mLxQF$r;9x_f|-ht`^%NEXfcK>YBcvG|A)(E zG@%t@8qxWDtSw)L@`TmXx0B#*NKYX9sKl_b?kq>xKXYPYR^!HV5@n~EJ;>Wz$Ei*+DasCUQS&Uiv;y3lX(RB znLH_NWqwvZA6cR+N$Xv1*qtr}6@w=3=dB$a^Ci5{^SHSwfI3}RD)U-k|=h)Fjn1zu$d-5PYfAa6sW&0q3=b%kW^n4 zi$+Xj?cE&x*-18XCr_!?^R$yuXrcR8sf-DSBO~IDSpvYKpJx(|@mPt|8Rmq>R#7x| z>aOn&ge|T9v0Z-x6&7=n6ws6PNlWOxt|p<1{ufL(mL?+O7G^5osyO(5$b`NiBTd4s z2M1Fx-b$?>GQpDO`>)D8+?2X2Di)niC?KLnuEs{?UFKC=jy=+_^bc3}C&qS0(P_o2 zioY%mo{WmDGPb%O)tAEV_nr^*`b3R>Gc<|y1(IlF;je%5D(;E&nMl*XfY+@Ll|bl2vg|Ad2Z78WUARk5BOmy zvwU#7I7=zq?psA+=!!X5WKJVQFCV;)@J%tro9IU!0r<_i$RGE+!7A3M@_B7a+YU3DM9`9YpF1_{QC)wz`GXEW1EF>F>rOb(?K z83kgi9`MWX?~%i1OW6zZnKrUDzxr}aW^&D2=VWSTPTzH6!;jQwj%gpZ{TeeTJtvv| zftm-wm!CK$GF1@zR}X?!ZA!Lc?4X3L{D9Q52+4mkFV9d9C_CwhD{W82f_xxw*jCXP z)6<1yl1x0%{8;D8=Xr9Sv?2-yOFegtGZOyDXkpi!M4gZZ=K}sE>xkJ@LhxP4ZazPO z)>VW?d)v^5QLp3pj9QPEO{*a)HzdO^7K4Fy6SCptyC;beAN6}+U_h)*S#01V7RDRY zw<>=!WOaU(=kUeMV`Qq7%hAjxWxni$M367$ldqfBhRax;^zoT;Ohjr=!`2A3>AGh_ z&GzRDDF4s9j(zi`WnMJghm{qAfm8ym%6bvZ4Q`_ST8FmmiH6Tf>g!#-N}3!l&1oO~ zYrTYzZPeCE^HULij)P~JVXp`t{{2#lh0K3RwC#3#?8!IOanhSc^&xNS*F3iB{*rkd zEVQ1BdVHJuP=#?wPwei5n!aI(h3+==)ICPM2yVu~PfxCHKE~0+t-u2r{>aMnV7)@p z-t3A&M2H4m>SVl8p7fv)PaU)J$CX2;c=8_B`*&ia)BQ>Vkf!#5Z!2qi*oK7g zhl^`H6TI9$aPMdae;M9Lh(Pn0=k`}uP7utfRL*0pL3`7bFkna7(lF-4Jm7y(!<{Ve zn;!O3^LSEj?;(0{qD$H1q*w2cB+2bofV^>s#QhWDSV;XN&n$7suOLa1;0+$bEQ?&A zgrqPYsrR=Wk=1QQM}nev#SlFnW?YN2vScCY!nsNwgGfzUHf{A^T6y7d;}5Jh=vktX z+%&;f!{xoxWxKIf3Do^2qIG{0BtC|T5I(2aFt`H-jL5UWLYev`!DaT=w5jQ0$s!;^ zBwF?KI9V2UL`N2Xy&QX(q*~X%%u<>jUI~GM0Rhp$00Ck89|L*^m;d0wXx_M>uVQxF zNT<+iwAh;2Uj9OaZ6-&DNBhZ42@yt;wg!d3y=H~JQW@R#a|5#yvp0W(-7ayeiS2U^ zdAexP$|50sriqw!(M$zlaq1EIjClFH-61zevn5My@f_M_SFqb-M&LQyC-FK=(6KPNackG!{Tb$bJW$^mv%Ji`j!kaMH!QVboNtR zjq;4EO~{Dkw#%yiE+>C}NXPQ6{^H*%(RF8=l$&*pLdR)4Ej%maJ594+{@GBTtxsXQ zP;Ph!tuH`8l5J^L5dz|AcbUJrgwhf5Cx1?>sYwt95#49v)qbIUA)B`Y9Ym=j$u0neJe zCL_cB!Xa<>&;=>t=KeD}Z}!o%N!DnC`6$_YgU3JlR0*aL+<2NT0)o$!X1d6|qEU$jCOW#HV|^NJ|&~sZL-sedEmf$6@Uf zy)f9H&~U-BB(uz!ZcYuGBi)jH)o*r>HI^ffK(%sP7_$?; zGnEGc*-kR9+wL8|!SXiy^bHsbLh4@~10w4_c*B}u?+gO|ycGKYy|Ak4Jw_bcA#WB> zv2BA#G|+#uy*yL1P*MoWfCq5hr`+T;X4jZY*N?4i%MV*U)7G$Xd2XP6cg${3)gGd!vq?C#jkKp)+ht)CiKtAu>ru zxiWtgR!(Lzbi^X!C!W80M83el-SWFX|l6|6qy);v+EOL}5l*-J2UhUxT(=*7ZRx@JdhFI$L zLz$L4frd%r_2arrXXy1*l6U#B9)$G=ArhZ#x$zE=b%NtE6!?X5I3I1_lFcNj9zB>J zv2grog$a&HP)8|ZwX&f|r{G#x=)!+u;~KZ0Ci5KR$Gm@Bcp!+c2`Q|!WFdQk3A4^V1p<|Ruaj+CeeiTP+ zmj?zu3Dxc)cAWU8@~X4cxs`hlYnD|iC#9ZZ$Tg0H*SV~l>_iwO1h0gToo;_i`Qhzo zvATZ!$&ME z+8X*k$u0nQ%WaSNQaC&j%q0$9d4)2Q6SbZbvtPKL9rR$AV%ck~^vKYY(WiB^3tsBQ zjq|oGtayac8dDaJ_Zl9Em+pVaJkLgSLP;ruVKhbpQDeV(2_<~>N(alT@g$X}>`7Lx zKJ@B9g)}daAA}&D$nw6Lq66gbcGr`8WA!Rzzeue$;ZuKcLn4V}4XAnpd|-VsI@EP2 z@<8h~Nf{%8M!Qor9T{%m$B>fWSw!C?}eNCYQ<(kDY}bEe6Y(^ourXS}p_f#x(lR_FB=HqC^+^+)qjE-*Bs}LwOou)r zjSdyp`O)zTw%LO~CwD9MIxUa`XsF)eb&q zxcN)R{#^+)I~g+*w$nW|^QjU=L$dsR{o4`Lzk3q$C7%Cxt7CuXGt8yOaI9GY`tJPY zAJq(e-bQJQbkjse1bu{&@;UD5LoSw`qSvb`MNwXbpM*lGyI)|l5T7c9pEd=#XoPb; z#S$yayRq~Eva4SF%p@aRy{OXLe}rM@u@--Z0_}&6azFm1rP$vispJ9%0&@D#8vFkd zQdk;0n|T=j^YVXhG#zILTQx7of5#QcsyB*@N*DqTS1Z+6T%*W<-=qb$c~P)0Ho?qB zc!{)>A?d@4`sGRs%|#c?Uz)6FKkyK9KMSLt1uEn$cLRLCpo~xz zF^6zY=zFzouLvRh2ayRY)%ojm^BrCT^|#o9vY#ottKNSNa9*xgLc#eUp|r&aV4=zj zE)X8P1KRCFb%33;neh&#Tte~XK3iZdU zihd>U%^OF|K^$e~vVGbbmLZ1KXIo&tugESJ@^pcXcjxf*NRM5}(DZ)CZx+PEHjxxY z81>q1a^io`lFb&bT^9P|&W=_6#${R$iYR8su5IUM2u6}eD)y}baxs(jyDY~LWAfe2 z*8(M3(wYT0%7mX3`4sUdWqHO>jlMqyq$7=g7@ql1uzzTFc3t1haV~TmuGel%0|{-@ z5mQ<5za7=j0+ckK85XP40|xAyZ{#XaxAlr;BJS0oRxViq`GKf}HRdC?0fQ3D8u!+OKg#wxTqT_Wb$m}g=? z`*TZG`7H8(gP{u)Ji--flt_W%%IWEZeErjf-%WH{dn;Ddr}O|d|4LFa*|?B9r(-%T z{XfF2f1IHslw&BmpMMy-E2bs z{_jYCd$62zTB1LM>mvY3I7Cv;csQ@ z3W#Fo?F$oE%=~MA;1Yw0S&0%AMQwm1uwqFr*HKN|y!3})6QH!}dg96Z@fIb8(lg4W zh*Yd@lvL=HW*G@)Z4O!Wgr?d2##++8Dc5j+r6pVAVS$9Nfq&Gi_Rz!xlCS#+WH(c- zu=s!nD+U+T!a@7zyUR1W(|`_{SU^)+^BPM$xz%p~lPqwd=U^}`PV)cb>>Z;s@4htQ zRP3Z;+qP}nwr$(CQL$}1cg%`yJE=H%tGoX*)AOu%O;69a`<%6YAMUex?Y+-+Rv__z z@SUoB_#mR~ij~65x4x4%%pgN@soTCh+hE<_Gu@~X>7P_eqO>@7)5sSjyQ*3oHz|uM z>SF0u5?QIZpk9Fyyv3dyIZBx(k^6YHF7SkHciS;;9>#r|C;Cm)#?U9oFZ?aO_PqIy zR)?u_BmC3)KS+uFGaGU5@#tG_@&kQ;$NSjF)tr9o1F)7UI+@<1KbE?spf1|QQfrlQ z6wKQNe>|MXE~EPe1NR6#PzTLYwB6(uxUJVF`|5I#b|*}-D3EkX9bu6ylXU&b)^R3W z8J4wCIMU`!R;BFDefB!}2QOHf@(<0Qe^rSS90-W(zpqZR_Ad5L|HCtG$^BJ-rmwIx zI$G;janXT&{41hr3Xfn$!e5b+q~MTb+Zl%LA*ok#xw%AdWPAbcIuweM-M2q{C=N2u zv{ZzM)=Z9bnofLnUbFG}`+Ol7;=M^-2u}!Z3bDb$LKQAw=~I2klf+PN-U#D=YxD08 z$fel)^=Q3&QZJLXzN8*REh-3q&zR89MI;Ld7-m&Z0&E{Ew0MhKx2c;+TnQ+@Bd@P=)QqLe;d)UwYR3Zr**cL3T6kcc_C6_d%d&V zZvLudRW%%B7~x*?+fj+<<1OX3Nq|50@q1QR#W2E=1dRnun>Bf^5U}Fzi!s5+&4Uhh zx(^1=Q1)iDd3CipnD?BfEp*yci19?hj9!J$O{Iu33sYUEsqXWC;?fqRUZyVS{Zr25 zzDdoj7e8RV7R3$l-hlz!!yWV(ZzjgIS^i^-oC1obDH7QIh_#8P&A5>l?LRcm$Vwr5 zq#A`ui^PC~!!5bs)`DZIcV&@h83o6+#3Oe<@cTpI9R^D65bX`ghVE7XSY1{?)I47CJI0!zF_Bwwz37)TmSuKOMoM*Hw7}o5v9YSTeO=-5`Xhg<5v+hm-Z8!0&WnB0M3?Wom`p*T?B~{p_ zF6Nj;V1bfVd*#)~+#cVwEx8Idl@luFrS>S<()|Gscw(DEJtJtg;mqpU^wp|R=lU8N zmr?`exK06UhqIbW@n9A-al;V90vmVFsaWGA@g8G;JvmwCBAXb)1VgFlZxt;uB`|9t z_m2p}U(G6HB}6kC9M%Up;~smuy7B~6@-;BV%43RE3^V?EE$kT$PBUm%uEfWrv@F9bdxotbhV>W~gE9qf zgAcS%KNny5g}>%tZmTnzT1@_@eKL@fWfA#lxWm|Zh62?)B`v9lmEYg&fa^Gt@aY1Q z-jJuDqLhayZca0**bD&~e7sM<{= z*Kx1mts2zc++$V~I=$JB+0AT=wR#kFYR(;ThcKRO`4;i@pM+-4 z*A99ae^)I)|5eTMf7-aRsh#uxh@iBwjPOAW7@<4y5~yhLKcaPcfEgW~3|y#M0+EV~ zYqC68AP{y7Vr(B}>Gkz`pTBs2^nu(cFpz{ur$f8^T1#2=qygqf-HD@A+c4g}(F$0s zoW__+gJy{A1LBOXAFJ?EUceVAb)o1X&DC(rP0r#d4_%NdcAwOcoZZ;H(KVS@5{s zX716im9HQ4-WRfU9g+QDWt(r&960bVGi0JxE#&nlms6MTuig4h{=EJ#ko}w=h~l6i z;DuyH7$z8f(>D%PDh&(ID<}vx>G4{w`Y-B4l4_Eo-LGKkWS!n3^b25dT5n@{iyN8k!>>Fu`1}L zrHnGg%q0x!fl0DeB)+NAyA-8xQyCr*O|V7YYp}vfQ1R3&#u=MMx|j3ggO1(SyS&Kc z4oN7Iydwp}~OpQmVY zNja@EG0fIKVntzp|A>^#X7B2l9As(;KZ4(GQ_qr0-o?Ap5AVv0n#NAGC>Vm!cX#CSX>Tu5g z_(z!u6(pZ|>KTlgo=5R12yKb`W|?BQA;|^Qw1=u&R`1d)bZ5ce;RmREt;qK>f$D zJLFU7TbVe2+71OOtjvOT@n#xoo4?k{RlNkb9UhN0gisL_byuKyG;75LZ=?3$V&~3j z)=Ny5DnE$9TWwj3gg)9;%pZ+E^7Y;>5xdYe!Gw+&>Xxisz!ZkO#iV*v_`=VT+u;SS zn&sFCxTIr=k_*`F%c*9I5lLi-u+=y{2oDGx&9QZV-=nLW#w2YH&UO&vv9IuC_y$o? zD6*pXyBI@gbZ3k2u-s#G0Hp>%#>Suu8|uYwv);_5K|^pn*O)EwD|AP&JU4|+pGW)W z{D>UHwgoAkp#ep}lByc$XVb0)< z@{C`giI9<7(5b!O|9IAVp+&Ia>F>(($A6W-{AaVbw==Uem$Y*+buu$F{vRb2`2o2h z23TLrqEOrZkQYeAAcxi11Crt5LHJ)=TQu5#%q5bN+6gbzwKy+8e9(Jgk`kK{Cj9Sf zesTPL+x$Q>4jF~y42r!eu8Ls!@1x~fYMpl7_kz;LDYe!I%TDK86V>Lm^M;~QWv4JP z?2j@FNa-i9VpU=W2050nnh%v=wQ@~z?-itz8WZh=(C8>>^uq&JZ0$woZ#IN;`ER6u z@_44BXYZ|3t{%mkOwKu;qHcl%F0W}gXnhC3=-=z3{=T=i3U8w>O630V-IsRKprCGZ zyn()#M20e)-0`p**j;#kR>>13+Tk!hQ5gFf_9@(Oeg1Kapg$-1Z20dA`^SF;;{VfO ziaGt;oiQ63dm~d4Swmx|f2D(|aXof_z>J6?fRD`qFeJPn;H(VbBQPXFQKG^K5y6ut zHHWbdUe8<}ohTjwJgSMTs5Dx$;`z(d_s{pQAN8Zck$D5jCkWJKbWYP1cShVv!+FG- z(>#$ZSMzp6ZR4S|D=hxbd`^*p1DBV*IdF0?U2igcn6RWB<=gr+&)~uRn-#QwdT9{B z=ehhvWwOW;{&i&d4{-yBEw+?=5adEiMppHmsB%B(JVFDR2=wIz!zmI1rDL3e?nJ3K zE7Zrfpsu6u{y~!dD8+wI01pJjg8N@Fy!`*4&c7I5G`)RrmR!GT-CCNo;!PV~0&Q## z$s6@1C)rvWPzo4aB;LEpM&NGjmbViW35o!6k(7WXlN=goIKNg&HK) znD+OILs*JI?;V6K7P$&6^=uc|Y_ZCN-?uU~E!7eHS|7q$ncZh{9&(*~y=OWu(6@c= zF@e$}t%WE8|ghGtb$<8`I3N z&8UQv6#-_;Y)Ogbi4EAODKI(QEvrVF>k&T4gFcZ@IDyWk+jc8V!HipK4t77^GHmBv z5TijqoLD1Bfuqu-G)fbHAq$fbhPM;OOM^7X807h2&EI7wf1Nr7Cg@-=Oa~U@4THrD z`Yp;~RUoPvr3NigEgRTw@1jU`BF`})RrRl*UlcADt+o4gHW8}q3SoX&1x}m?wbht0 zjniWkjXrgu{)W_{2(B3ke;l_UKlRS9(2N{o=1BVl$4ufLciw+cZq> zXQKL(gfqWzCNUs?eP1bQpeQ5_kNy52webkD5mSsO#JpX)D}_qCN>xu%7o^kjlrn8{ z>lGjgx40`u+pCW~r#&6gtK0+uhK3e8Yl>&cRwzr>nk!ai-mBlIEu~Xp#LXokrquw; ztDFE64t7;R^Ki9~U`a|S_rYi zR6oLk3W?RKVvs}|9gXPbaq+tz!d`u@%80(!xY#UeZd#Cb@dz|&#H8+HKbNW&z*i{8 zIXP1B$TrPmfux<^|3O)@`9K(ws8CRp|DO80@p1}Jn9O9^<0kdpNFg*38!CjmM;e<5 zwJt-{?FOfR%W#yAuq>%e8_a!TM6K*al7teKY=Oo_tdumB$(Edxy8~_v6f+#NbooZr zz;o1Y!b(yv9J)1{Zweu~G&3&aj8KVr!OWz&w>VEhz&AY?O$1#xeADAoODCNnTy>Mi zPz{kR6kJJ(9Of;7WGW&`+krZ{f)r`7Ft5%X^wS)FSamVyjOohOj4joIA8}=I!4a$t zraB|(oC&vst!F2-iDpshHqS?&VM;>$`4B+385s<{UA6D~;vC58EHYLwP4|ky3Ncnv z%!%04k?u_+yIlMLz4r{Obv(VGTK2NdT6ExIb%wZ&kbfDDuW%>m6OrmK5v@(;z8e&D zB{(2|M)_!nia#K3sd~VNyZn4)iay{`hgerZL9!kD% zMQ}O0D+rdadWXmdh?pTA)4;4SbmlMW^+a2LnA&28Nk`$KaS$XlHClW5W&JBay-4)( z!k_?WE{WDr@)fv(o+*fV-VL#MgU5>{I*`g>GyS$ah`y>_zLeq~E!Q(5Y?b!3!`XIe zKX__YA4bRPO|?i|{#>}zHa6roW3q#oDz9H%qij+128>N)R>-#KceXMkSuWIQa;I5; z3rVumU3nDwkr6?*oCRATziVedH|YR52-+|+jn#~ns!sA#ZKZsjlxaySRP(sh7b~iM zdaN)b)0MELH%Y|Fi=_0z9Md9SX86gSESP`QzINl=6#csG3=P0BS$PCLSE_e9?1*YU zDXo@NtdgZH?hLBpSQK?;@Te)_uDP8e_g2z(NBPe8Bj9ZeEzq?|b$Bh~ z;~5xx)+I&nK*Sj@?f?~)KS`3x)yn|#JHTJ%))@6W#GfuNGB-0EQ_hmI36QWAZ~I~e z#&3wY^~$zjjA_Y<&=cmbc*~6X9hHxMX2IN49W}L3pEh;A_1SpYhWd60%|Jwdek;xS z^IZn=QAUE{fU|-7*wJ^&-WPpjf$?&6PQQQE3qGg*7#I5D zcudIQ`gi3^aIu^~Iw>GQfUOfv>f3kuzH9}*!I|(e!;q8E?JDuT6K`-B zPMbb5pX!S!WktF}_YSS`!7m$snC9-6!kHqpS!sZ1CY6v;9?tw~nWy35A0#cAR#k56 zyX1=~ZSlpaARn)HZ*Y06Y-}+2nPr=-LeUC)E^Uw|f!u*8Gly58#&1LlHS&T#l@3x4gWIF$4pM{rBZ1hYkEc!_D|`_r`FA3%ee7Nar*?8kn=DQHQvj^@M8rPic-c=aBo zQ8QlmRw?3F-8`-^zD{I+RCxC$LEN?H=i5u$t@h^97jbD->&7ERX!4-&zXy}Ak~qmc zPhM_v&!~!=ah@q!+Bs&3&wQ%UXVREv^6V2e>9dq@&=D5kgCr#Y$vq3Tua6~;^n-_{Q8QirU)W`zjIZdaPOGt@b6sQ zW^`q`scyyz$VDQa%W!mdD|f%yokHqI^otC~qcGfnsdapD6zRS{H7zNb@y zlcX-38l-oB-4S+-e(2p9gDd2l_))o%S0RYEh++!~hu3wH zB1re?p#6YBnKe-T*1LPMYkTzW)_kVPy9chX|0c)$*$dmv0nrQjCTu72l~#k$pVCZ* z{THzMFU*a(u&b0#EN{dSxYNO_(^1^jNC-zbya76YA52D`IP1)FUJSs7$c47p^Uum}x0wZsrN z0}UOb>f?=DOhl>=_OF)NXjLOtpXR#&4dJ+#ib?wAC|4cp(T9B@McG_i4zlHFEG7$x zxF{`uMRC6+=bk8~+E8#U2bTy)*LHn95jkC%iVHm7keC!`bVa%x3+#|+q+l=MQxsP;?O2>xFtRYC6WXGgw9MU$otnR>6556e*9 z`82)nP@Bx-C*FWN#?tLQgXU#o4dWU>UFVE{Ls-l--rz*%E%}FhQC#)+qz3%6`w|Ra z+T)wm%cG^z=nkvb`Ne^U32?mP!-4$n?N6MUy{eg=yCK+#lGSMU{fF(Ry6y{fo+uXM zAKzLsD&R1QBS^5y`#@O?LP48CYa0}wbl}%+79I%5{^ZEMh-}-FZ8y#fG{X3z9jhdN zbncf+T$X7q$7&6lHii`EJ+e2w)&>(MOf$k~l9>0r_B08s3*|#mrKdB zN@c&7^e#|BBDZfBjXnOXWu5%29N$|dw7;`I-2b^bWcwbAbf~UBR>#!re=>xp8SfK! zP&J0MOJ{a!mvR77Zlb6Y>#f<#7c)(N6K?yGaj4}ahb0qJ=&rv`Bp4=tk11ND z%HrW(AuK7Byg_Bpv00|sd8IRNQ*yTC=Bc;TG$duHk2gfMTQhCQA7>~M#}6PihVt=+ zDD@eShZ4j(_k2n+Qv!={%b*&Abb*esNsn}rt`H4?2G+hYq$Xr;jjZbK2jAnCbf}Vo zvgkU!1=>3L5rqPzr44!dlohUjcukkH$?SCwfG@?D3$+7t2Ei#vszY2*Z@}Rc!V+f9 z69LJi3PAm-&a8l>_9>%bO#4Q;R_AFph#8@oscy^HI<+rz@!G^@0= zLg25UITO^1wj;os2M~QhbDxD-jj)$DbK^wgo=*;77ku7tF95m)M!%JReD#;wV_z+v zJd_v0yH0!`V z-$3LN|El7OdKjBJ{IBcfxe2p!e-Zg;-@Q4y8j9%N?!Yb_gCo6_41-S0=+L}Wxwv-x#RfydThijlUY z(HMt|ed`VPji9l_0tT<9y_&`lWP7st`j0u_04ni7_P>IEf&42N&i`A%{Cj!i|16ce zUCW*yWY>b6hV2-`=(y<{d>!3SD{8p+I~?0@r#X~J#sN*;nq*N9GNNxG$)9vxLG1` zP#E}ssMk>~mU?63+D$G0?)+`S_0f`{Q}vZr$|2LkgZh$qLrYD7$~(%3Ojlt|F7anPL^%JX z;z%P)kbY3AC&%YR)8ByJ6eCsl0Z@`7G zWwz1Q^zur8h6cI9hqN`RjJXCbaFx(!RWFUnus?Lgc`zxAETJbCS;h&A9BcL+J6#EX zW7?gMsG7@rm`utHV|jFX@o(k@cTakqVsAO3?aI(IA6AHKYA9KejB!n*L0sOR%!D4U znp?M`rSP@ECqBa_iB$NEu%>MerW;Cr@G33&-otWtjK%ByL>;(XEb|DK<1-cO*!%?l zlNtqVr&L{>F5WIWKaJ&p?M|T%b*{&Mw^?TQuHWSi8@@-5rNV+4=hzUyT(3331K{GL z1!{G~$EMs3CIzDZhI`2b>iYnx4+yv13`zgP)VMuBtm6LkVmasde-BfNqqgn$Bo4b0-AO+~zgCxU$5-sakQC=ceSQ$o|{DhX)I$U(wsb44?tB6cK+t1wV z;58P!@xW%XDUNXk#U2GYqf%u(RA%+*$5=T{;cD~ikT>ID%JEGG^nI_oj!L@14t%dcNLjUqdLZNarf{<8C= z*^9L7yLW?nBcsx^d#idIX|;axWQ&HgqzebjXA^7~Q+7EDjU!Lz9^C8YEtpJHWU8Zw z42PZ!3N};~xy9r444qy>Z-D zn8A11j>~6_@Z6D{lIPyEJN$rx_sF4HGR!#o*HGeyofMDSGDf<73@}lZiv_hXg3f+Z zzvO}P!=hFnTq6!hhX<*DAKVf{`Eil82Y4s$?qdWA0~mC(|v4tNw|!t!tQ5yz=NLovgR@o?Dua!~-JByLc>J#{4;#KX+E< z_J+=sxp0D0qXs;GKFVMg#*3c&&^!CEJ;Uk$y_5e1yG!teH~{|J67p;{!YeTC;y5OA zEUV*gcy85|`U>i|`v&I*H=zQ0Y^;R^;%YS-Di3$|>0cL$3YDFO_ z1r~p5k-Bi9JDEA&_u9x?_Ue{o@5qF^TvS!m}aF;xF7Nt=Ql>4?lESD>yAZ9M2tX_Kv4_Dr}PT=7_-x6%22`AYM#Ufhm8t?Xmk}#}2 z3?4VvL+n?JS7ZR2VQ27ib=e0Wl{<;c&WIKLev0ERd}IUWT{ zH+(x2axa+|kzpZbG@8XL-EW=h2pxts(nCx@uQ*D74>*#FPqg$>!w%+MrQ%}86v{p` ze?r{g?gn-nnP9uwEliXv#Q%aQb9vlv7C`>owx3?Lw4TdpR9kmhbuLfUd2@?T&Bms37Rnq~!qei@#)Ak^A%vIR%!j`sW zqJmBC%7cT2Wmhw@qCI5m=VmJ5pE^U7aQQl#LRJBA%kh#ymVqzlpi6nh)#J;)TiVD5 zJEHogVnR8Ht6f>0QMfClW0HY0OM-7*KKL?!XJdr3S)%wn`F)n0=(KGKraYmApACwc z&Fn55_XJjQ=Cq5Hr1_*Uon=J$*-X8Gf=s2BxKul1Ue6q!L?4a&D6*vcFubVlr1_Fzh5SnQ?3ZX(jSQ@&9O(sr z4w`5&K3g+!89=t|1}uc&;>R`JJ$9m*u_`@vsLla@*V%)0Z|C5|i}Dv;e+@ zNzJ%UNiCU6S?XG5EI(=oqnhzvZNm#=r>u?`>cx7e>b>WS#It9R%*oN!5#YXmK>4&- z$VugZo_Ze>fnC)gA zJy|}W`A_T;Bl$xosq5^wVEzx>_jkj~?J!s8M1$^#P+qix_Rb&h>-#lVFdmn_JmWIw z9{7rZ8y+dSbb$zSdFMHRFEE^cT+@VW&sWz&k)l z+SorIowm^LNKNsE$X`vr77g$Vq=heqp&<{bUn&va@gXT!)lYtE3b+TDi$lrFS33V7 zKY%&yijB>^nW6o(#_iL%mv5KyJgwGGEH z9Es;s)@)4whhTzUAMbQmxDZ)w*A2IJ}`Z8eu0ra`02ugow1vS6w1-y6s505V8 zNr=&M$ej4xn9WJ}>YRw(&R{lQTi@Fz-E>h2S(|mzhV=7+Tg}wfk!S`uX-)AHiz~1= zlf;7H>Hog!YU7~=0zyG5*5$7g0gYap= zRcutAfy;Fsb?WvLcVKHY-p4_lBMlS3G!-~>q!CfkNKXhvua*MNP*kgxe^kCQwD~s* zlNjNdsgMc7*dH~8oY8UR+AUp{#n5*9(pHag88Pt(;70Z1v@hjWsV1f?Y7@R0D#o9u z3CmO`36=0!mGB#X6^~_s3+&}eRJ{EOl;|}A&uK~5Zoz~sylsy=p6v_5{=?I$d6_0H z6AR3oW?p%jejx9jUG#fvBkgIf(kY+w)wecPRfu;3njX7Wc1|Mjq-hPfa$18K=qtl`|4auh!W=6D|#U|BrhO@W= z*Zo#$K{^9}%LWPF%d<^TJ{HeGJ z3BHOgmEq(hK^WK5bUNfU8=cHn4WBTt8Y5of?E9=Vt z+uZ;VT9}Ozg};bJDm7jxQI!t~m6ef&gzRrlA>ol@Cyvp0#n!b*_C=F#!Ey)jQWWEE z#ttK79O9e7?d^2a@to83e)0UA59C&FYz#Ss#suGpVVJ>l!h8MJ?R$>LHWONgA+|l% zs&a#W5jJTJKoi5%^A?;u(vuDmBvx36-Xx2k!TN!aU5nn_H>TVM5FW?wb>MgJphs12 zB(KzQ#748(q6XA!)#|!&D;3z}UvG&l$JxdZ+ZzrJkU+y8`MZ3R5TUA^x$;AT1&?G; zBS3&ob6)u^KY$^y z-p>tmi;2PAZ$GoXj13sWt#8RCQx~{ewIA+AhB-4(4Ztl0Zo73Brfeb?|E_yJR{2{stLA#!vf@z^AeWddF3A2k9Qa$Q^gGW^ zc{TtkZvnp$A4cYz*oAH}TRKs3s#ZV1w`dYk?G%S`mqP8#Wgj%9K`hY_x1;z45ffG! z=ljP+aie2k17D6b(uPZOB!PVd+QDIeh{O)nD#PJ{hgch-u%66#lZgFTnH<#-%qF&g z9>IO)H^Gj~7!1^_c2p;yHl_fVwC@S5C8L~_WYgh_^TDdl`ED8`*w~}vH`gK$T#LiV zu#DCI$FDbtm5Y}0h5k2m%g?If?Q`RT_z~%-Zby^I8B-~}4k6NZkTSZvmQwk(AP`anonu&pcJ_P(VwiSD ze!rk@N1%#|bM_ip%u+(jTR^jNwm=b9$+u@32QA+k#WU3T8`Lb;iS$o@Tm!q9LM#?Y z3r>>)px)5vGlaS1Mq7?;{<0$u$!$V5nfvEeEUC=}s4d%YX|e9Re(V~KGedd-*@0$o zW2A|9t*!N}TNzm^xq%#v{u|W8`p?e%3saVJn7o>n-_BD2U~pm2!ON9}^>yzB&XWx<$-u;NtSM% zGL*dKIaSn8DB4Q7?Z#LGRCWa-%xjDS6UDIbn^l{W z&0>fZJH-;3e|p6!63ZE1+*Ou}@oVnHwEI{faHxXWEZQF0b;$G>?UB|jhK<6CBH}*+009=^#+SHh>pkVSM~uAp7E+HAaa(0diQb; zDXYA}D^0Q>nlyRb!yOgg@&><5&hezATGl`5fWfQ0B&=e8zG5-Y@an2--GW0n8&n+2 z#0(czLV4g}?9y$e%_UMHIBw*-4Bw=rYH^9k`YfUtoOa%tU~;~Ubd=mT>0a?=YoS=d z8dIF(ttCKdaTHa%QrhS@;HR5@3GAW#QXMWaD9H&&mZS+E>jt+yabYk5QqiI= zz+I*XeEg_6`r$;zSDYFS`vQ3a%y=S>(BvSFPRS`?vP-Z;)o&75;9hX5tfJ<#tPaMF%e(z0i!Pe(@D?O^$8LjE`%)y%9aCv z)2f%u({yXG`EAIf74pseK=iE{VBHy#{G=e+8@y(8_tzhmtsw81s(CH1CDQQ!9t;!jim`p11>DO6z-AqXI#Ir#tTv7LWK z8Zmn(W7Gc}V$|QAl>w+6nZvR|D3D@N1HVT>yGo0H5juOd zCefwcN4BX!EW=9cSRADnER(|Knl0Z7OJ)&iE{kQ~?8=y5OTGoo-<-?(+)f2%x2?(9 zhGT!szFc2iy3edVT&)%L>G~be0_DC~<47Ym%=OPlPzaaRP^}fQDweh;Em>*2wk|MH z14=H^Q!C9>TMDC?HZIzgPQR>w@Zm5D5x8m(ZVV!dnT6+b!x2A55XGCoW*ShS!eYTU zuxr4}!%7PeUI$yCa#3LynBue(Of2wFJ3VA9*2pVi zv%S&lJ=CbWPI&KhaB4K{48Z_37RIL} z`#zPZqd=1-GdT6uzp2G{?g@mk*%+D+?r{ldu~K|t8l#QJl6rJ{%nS{IZj_H-F?~lt zX!mJ@X3?Rg5zIBWf z_DC@tB6?Q5#wzt^dQW~y36;lAFN~h%_MK4Ys%xf?$9~G+LnL6)OC$a=bfyHrD?@6u zY0@~2RiOv#lEx`E)vIuq%)6`aa|AKM{7qDJ!fLa7>tWk}K$9R~h4QwcuU1hyT?!P& zU|EZ-y7{FruaA`z7`F~?6^qIUibn%FJYci=IIw5Kn3+)kj5uu$K?jUJX$z}3_jv@P zDiP$h4okn3p)%Xp*Pmv%7rL!Rvu7Q741w1qQqugGdjsgTUXTFk)0WrWYcz80fxqS- zQRB*PS%e#ZNj`mKt-01eCyK}=I><^)zT|6ZB~5EngeNSbi&O4ZeWnK~dW!eUMvaRptgUPyjG5rJ?AYat9@z=2{9ZdrW&82ZcJxpTw|} zCnwDc1nti|`yQA(@XpeLFF|{^?}ure%%4Nz#aBCj8m(sq3d+#Fp@yQO3SRErC}3v8 zluIl}PJ1Or9;iD_x4v=s8CYhMgW+Toq$Rli&HJX5DWz_Ayj+|h8zK0Lpyn`HD0kjE zO24AXi1?3RBB30TZ^OpmN~RCxIsMFxhR-(NMIxo*v=rI)&>uHl%Ua8*g7`vm5u)nQ zl9`@=m#Bu65TbT7l6xl5jtC2Ine#GjZpCr!TMe{KFw=-bJCA45JQ-)Zd-rndPZeRj z8wzROi7x3&p4ae-jLgL>eFT;ut2Y>f)1Cv`GHw~Gc@&&|*EtS7;K$uNYVSd)5({u) zwvMf><{2;(Yv5`b#8@D_l$b+Jj3ukERHJ-<`tF!>NIkX>l*si zx|exX_90%UA24I^j>0Dx47WGDcc*L!$g>oeTiR1_-(o=-sy4uVyG&gvW#F5S0xab@ ze45nvmXaoBjGoYjys?G9T|5cZ#1ir6PRdOwkHN>iDyBTqNV{oqu z@(f$4sLTC|?uqc}FOoANa5N1QKe?rsNurIZ*CSj(GC4EN84x{ZMY;xEOCazr1MVtH zpYw-`|3J4U!c9+%6d_8#<+#d!fY*2j-!68;H2lmG>$|%}+x~N_{SjxD%<|yvMe&6Z zyC?tqixlhqA43?Tb=G#9f1zJJ+<#TP_+J6p-O$NI-ptI|)a8G}ei!c8BdFi8q}HaM zMI2GWB3a;ILiGl*8-ZsIdVkAnDrb7?{aa}adR zWhEyLr|jj}Nq=(qdjC9X_dOw;;?LDRrhJ)^Zlnwg=-_)EU*~4NXYKSjf4}ALeE;l+ z^h*>#Cju`d>->p~(aGh#`@28cOLP5e;iKt&m|1u~rJ3f-a>>tNteFHuylV?bo4E z0je}@l_y{yi{o^ZvV^j#uQ616q`S6Qwc!j!(l9TOA1NyV1zTea)A~`l^5zd&~QD$;tvDAmgs^PK>8$W-KF~>{F=sF$2)<(+*)*h$qmzJ0>(7v_6K6E zTV=t1E+HV>d}A{w&bANlnympYA8ECF5*ql78sHqQ}e2n zS0$-QpVkwm^0gGF1@a780ofxa+)S?pqteO@kKCNrx0Vk)YLRt=Hv(qwaM&5zc@^F&7=oVPY^m{BQjpj}tFQT<^1r4~znES}-&0Q{=f1Q$%`9O%s<6sCT zb5F9dl;#?Q%&|R;*Xe0c^NglrEH^dAq6M-*g7F^xV;(Tq6^40c3yD{>#- z1ZbzFj7pZN$YgSs+DUpEl4QY*+KN$nSuA&$JSGM*C;0ABrZ zYN#9t0Pvkk&5J| z#S{9R?5WwjQsP$*kDCpw1!%2a8sx`_UhiugG|uMe{xI*8J*#7fgLK62fb+4 zun67yb6U-6NE^&C1T?;G!m`9=hP^@SB5r$1>D@uwxz8VR4K9l7R=ytjDvg5O`kgiU zdeWhOmMpU)1)y*CTP{4vfS~?TsdwH9kG)_Nu>!Dz zbtqz`aaN9me_VLI@z}0Rd6ukF3;8XBwPD%m!r3u`nQJTBpDI3VC^o3hM4kYL0AqU?`9gX=w zhxcq3f1-UjMDHLY8k4LKE6xzy3s&!p=I+_iP$Hkwr^%<;EK&^iYW)eW%@=NKZ}1~g zYeL%-{c3N-HopPj)jjbw`S=5KBfY+8Ju!B9dCvuN22j;A(>QOcZT4}|R zhZ9RSZuGI?|7-0mz@lop2fm;nNJ&WuNW+pVf89#AbeGGrz|swpf;0-!-6;qnAX3te zG!jw*Dk&w6$bWs~<75B6e#Q&W!gDS>=XYl2%-orKXU<7>Q@{5l`ssXp%58Sz$hCg9 z%&K4_+dD2B&Ys>}^-2*TC+=LsTNOGVJECXIIZ}x~(!}2GGcvp}CqHA(M6Q^>HfSyo zf45#P&TW|#!<3)Rt6Ux8p3`EU2RUsqzjpHBSgFKfpc^Q-(i_n}nOAE)T*OuNk>J^0 zq{aORwPcIjg%{5ka$kr8macsvMCG&b^X;u6X|wS&A=b0Ugo#v5?(_se!*eZdE44Y04&}&P^fD2fd^Q>!ae|URysL6#5xT-!KSH3i@d{H86ZU9kJ^RXOF z9IiF0Jd4gFlf0c`k}C9YVg7~?b=q5D0b=|yJ29ak`z_M#c~%AgrQ@qS%KgI!s8(V} zSfgXMQF6*=VU|3D)vZKJlQ~f%MopYKN9Ju@X>_qeOKX&_+WKv-<}Wi$iDv0ue+Q^F zx9`hH4iMnX@uvk-XL!vr5H66tJyhPn5b|NKac$^d6gH)_dFy#h6av_o8#`@}>-4B< zO}(itTO0|pC0cg5-S)_KH2Y~W-$_Jo4mcOB%p9%1d9ku@dGiE0f8)YzpmLxC z79m+|f$WR8TssXRKgoGJ{XVH~U>R1hwl=uQmUjgTm!-X>{i7h(( zlSP2~6EqH(f_NAS+|0Sxf9u&OurjfCNlE!Mvm!ISz$X=EGX0z%AI!WLsAPZQA5HBl z)_qNFLLzK$Gpd65bhR`If;Gx9l5gNB){Zvm%p!l+1@x>`*w;?ZZD{ymHBA~t11?P= za-A-0qS5{u4~Ka@^8@<;3L`Rim9&gp_Gy;t)yU0TVBW^rjLl>|f1d2b%%=Fbwcgko zT)moW7kGUyx+huKGgMlPx7)`vHQs+=b5lH*S$H`JP2?4>O6lhu&aG2b*(U-_R%4N*#9CK?;raslP4!T@MP|vt$S(Uy3ptv($-|0wz zDIb1B!(_ZblTWN2FShcIui%bcVst3(qMOVO%_>tHk=`sDHMFiHe_IN#`3n^NX--vQNtR9M zGNZ_yBvg}^#2W&U!aE3zO$Hf&2F>zv_f-oO1ln&D07yG?8V_uEIA(ii%!0AlQd~xNnBZZIB)uhmb9c{-N+9=~8?Al$t%|E1H%gl3 zJN?9}J(lUCup@7G1h5lJHPewE0i9gvb<2j61#ZuUNyXs?7f;u}Qsr9Gyd%y;$`-_X z?O~?HJD?zZB{xME>J!XL=-p76D@OTqPZ?(nfK)I(|0a_~0G)v0H@avhPL zJap4YxbG@%RPjYObHA>s(wU1$Ok*m`HL6u9RO7YnH(c3m@4czLis$`wb z_e1*{f4Z>Bz@yYU%T6{m*3rIlv;0EhKrFAjlf2~|Fn4fY%9C_X)_yaZkk8YIBv5b40aF--r!)4A7Rd#o7x6l zmekEet5o&@W^3v5C%9V;Jb1i#>(=rcdR-|_fA`VB1Nvg8tOw@Mo`^d{$a{KRnkdQ4 zn>-KeDDSy~$Q$bfJrYh(9}@Ul+f<`{8@;s^>j`s)01KM%7!S^h)1*)V(c}m5I{kZ;Ek?o@ zL>6~lPe%;UwlkZPn%zmY)W%1LT!ZCwIG20oJnDk>ff{Oj5jf_W zd8!%;3qd<7+tfY_OfPr0R305hY@rXL3Ty+5MLuov_qp+fv75h$bg9pY+i}*ws;6?V zFZ_TIhC{iXxzp?t0C0-)gKH%vlRv^F-_?SdIGLY&h^eDY)5 zP(b^ZuG6?fodfckLtCwsFSmpP3y0ujDUGR_Cg)2^U=aCYX{vT*^tc?1d7qA3%mLf?lCb0~-Ov0` z1tyuN!Hi{%jHEa*OXfCKpy!$z$8d4zU99mwu>(*9JQWp4A{#HXtqClT>kxG@fJ3SqWm~FM-O6T#&!mRbomwxd{;W8oiO{mf|E( z36qPcjV_v8#x>)LuT}91X?sX-6OS7mnw%R)&Lk3?nq$D1Bm&H3SXXpUOp|bIN)-xd zqMNU1SnZmndcUE$MYRStf4?&I?tZ{~o7S;)DffUYO8qwcYg&VTXyU^Zz0TD%n3E3p zfkjY-wA|n{)d8uJ;@)zR+DTCP8}t^Y@j$xndLUopKsk@>GR%Xkqq;hHmQF<_u%0`# zn?Ge%XPheV1LvEVtK8gvurXsYcd`x_v87wNm?J8LIP+A28Fg18f6^WJVS@OB_AQyr z6;pn5kDBc>+51-u?z}ASu zue6k5U@X_8-nfu}zK+sDIoH|@EEgQi&Cru1Ll5i}cI2?4{dnTdhCNuIQ=(OjN41ls zB-#*)|d?UZu>{1WS(Ezwki4*guSdqay2Qm5ELvGGfoh@<7P7rN*El zc&)4yJi?zw7WL?VD z?u_!CAxyoD+j#TwJn-<=pqIusgbWyLmLVyt+5q2XH5)JXE8fC`GS66r{v{ThrR7Huy z!`CihvrOyX|F-GXcr)Y7Kov*dAwJ9vn6bwe}>Qt#Ykf_D>Q7VxbN6Ym!wd* z8DN-)7B{<7n!&^1Dm&rLM)X#gVw;VqtQIhAl`6{3jA156t(LbQf21Zi**i0s!j!v8VJb%BYQ${&)vxix z4RWxxgsHr?U1cK#?hH29Qm->rHQ8CEqNHO!iuU6jV`zE0qv6oZ#*{+1Q=3Vu;PR}( zxU7H2bmh{^#2UklOr1UJ9Rpdxofg0L>qA;Gru2t;w)YIOB~iR3AP-+m+`B$paCGqi zf4#(Q-q6UTNe*NVpu-if!ZZi;N2e9aY3!d8~W5af81f{v#>TI>7&BZzsS}%H(a0B&v_7LMiN!b zU^Xx!mE^o^nCOFTRI_apqB*&`vT}9P57}th$Sc?OxNx0*MP@;si)Z@75V9e7My~z6 z13&WYquGXzCXzaO5_;ZD6ZXZZL4DClk^8pAQj;})aqYIVk(Fd4%p2>~AHdRne+zhf zLsbvid<1@6f;;1O9k!>sm!G)wAmman~V*)Mq$ZPJf;GDKR(KP@|GpbK@NEfCjCN#*__m-{%z5>#uj z!*sC!ix~O*>?ZNCV5}$lC}`pUe>-VQ?K9>B+E>TS=tCU$o(`RAUbLZh#-HYmEIMKD zV_vedJjUV2Z|sj(T__0hxC4RQ!JY+*KCbaA?B*@Cg(i)7a1^Ozx~RJP8@Y8fv_7rF zG(O<=GH|pfx2;NOV)@83)JH}lWQ5;}+-v*#BI0&7S&+vgGx)MC7~_A1e`(XYry70v zJSPn>IN%CYEKs?kiYw)xf7wGId15h9`j~yCB!QqFs9*9)XZ@h^3Y|erXjbEH#e2IJ za@L0f_o#*-{Bg5A%ERL^PbCSSUp8jq5r>+`Kbmm@0?HMX*zNm?kP3}ls#cfzZ9Y-& zPal#MgRIhcrkYdcwsEst2jc1@WO{0MIDKrD+OKqIqD-n=N&96ke|(wZGIQuJPXT(3 z6NcN4!*0kHw&u{sf%V4B2L`LyTpoLnIWxH!6Nw8^>Zyd!X&?EvlIS@+P)2B)pbu&(m(H!BfxUNRhkAqOKY`o0Uaqjj0lG ztl^j09u#ELEuDF3&iJ;Y(lEDD6uHLMMFA25YC$F6)>22TerhCo8U%BEiZoL;$SqF|^9>g%D)&9Keq zB+{>dd~Ky4XQxy!y9eegiwUcF%-jsC3EDut{LN#bpOWg(2^LjSz;{w_q_hsJMweqw zTbggrCdyk*e`un<3l4qopxxYb$;pQ;_IlJft4az@L~nIm|8v;71Ak(yKYw80C2D=K z{vtQ}Ti37k=F!&pq2t|!NEy`Jk7qRf4C@(YVGmto%qC4z1o8x8bjo!TX%I)Lc44OW zKitoMkIY{ID0y2J3RK{9vY~tl8X*l3yNwxD5F^3ke{>^?qyBPLma)|6BbjP-kSE(G zO_cze{1N_^?Vy0eb2B5X5s}Ch3qaM^NGa>z*&25Jpv_pPb zH;vwx+z!m?VpKd;GBzk`rMcf1y&2INDpC)tv`TLj#6!*q@Rqr^W5V!rWcb6;#|PTBI<=_7q$E#BE}$n7Ust zO;Y-Zyyn24F@^A{a3@5ZIwDTy-XjP>2vfaSE~_v}vsww`Fhmr~Pp=0>Bp=+J8G)3H zhqF)MssECC71Or)(CkBpXy~k>=*sj(`gFySe;Tf#$7Ulz$wW;yC_NOj+z z8j5yUJFynGuG)FxGH_ToS(GW3>`k@H>M9BmR^R^;lGJ+3g*t|~`?f!RetDRTbI^)7 ze};?}NOzjIGI(pfG)3sTf?tFtnTIL;<#+^@kY739 zt?GAIQU(2Z&36ToHu;mbP-3^)VT+0te+$eU2fRy-`+T8-ORY+Lf$8>S4f7IrRypPO zp1g7AT<_K*(a~!eb3_01F4fR8(9$jOT{2P!vl}6m@wFDq9YXqgTEl$%i?&0DEd_@c z1PKV%ai3*T%B5f411_oBaU3)Ntf&fJAa^u8bS;>ba@rVL62{qBs0qT^1S^-4e>8dd zD;=$zA{bx$Pc2E{Ei2kV!TPd4OGrYNw&f|-_FUpkBy>xEaxaU1k^_g(YGByGMycCTbE zBb;J~iFn4juOxOg&C(R3SVwe3|I^}B;VLje;p(J$3ap1EC(d}Og$nCLe*o1^yQy&o z;z&kdUg?-@^QfjlX*VoSg}d(LQve=r9VN1q@j{r;Q*nuIc%N&@b;Y)l>LwR>KUvrSgfq3&4_(YU5;tCZ}UDwI| zj%!x;@GYeh1nxyRr8LSWe-&19_iQaUF7G9&wei5xZP9yMABpLxaAKoPx>2s&BKx z?*WrcL`-tvhthN9E#NI~X;(_|=_sTIB=H!kin`PeOY^N<_1ReVFnS zPO02IlNN6kj^!A0f8LZ4I!$2j0{N!EM%=mA<$NEzwl!T~c8T4);JE)KJ#gKhP2c%C zP{s+5rY_XLbY01%@Kl(bWyX2Z;JT03i&|s7w7JAsXO#O-=`CK?$3E#2b|88)QD5!Q z^PJr0L)1Wxc|3WGZK&(q>k}%kqCWK?A)+@2Pex6!X`bwaf7U*Ed*ltB4V~}y9%eT( zOqF}mWI(dvqT1S96V1(Jh@K@c_(t(%rq7;}z;1Z`^2g37pH~e1LC-UYJ>@(Pp08~) z$Mx?vNzQ__79YARUwtMS7Yj2eZ_7G;Es{!L-$s1(AcQC$Rnqev|I9p7kIvjw?99FG zYav%e7KkHXfAQHkj_6$~4HitP-Qtf!o}=@>`)LZp+?97gI6aMcLc(f(%vxC3;q*$@ z5`!@1F1cmbTMSPiQky-IkqRVcf9zd=`2xlIB_7OzI^X)nb}@HP>hcgb)2ERa+kytd zz%bfryf-{ULAIN>1mHhq1Keu#k}w=8G7}$h?LP>=e{3ync<0dvyf*8xc7|qyWa1>Z z@coW}kEIpDou7mht)-VcZ)6d-FgDZ)hEt$}B<@yTj3%C!sAD02?zdUFrzsPgt3?>n zg$+89xz^mReGf*}=wzs97B~{Al0~YD&RkA3iq0e=8x)Nx7YZ208%>NW`#A7mF7rV{ zhNf(Qe+ebZ2nf1>S6G9w^2nbQJ3|wFm(L=V+1L}m!>}k=cBLySZABRudn$u^MO4!B z(o?87zqAdGlCYxfe9QcSBkiF=4NCZMRQKbQJ{gWgebziy)k=CFh| zh^op;QmepYVs467d{u$^{5%3N_Cy{<{04PxedT6$$?Of&fQ!i=BuTvw;4^3>WWa^9 zf1wx)N7_gU2>@7wf0zMhUzNUq?+(m=VpD9j2`krF2 zm6@#r%*ou^@oV5qM<=k2ljFAu1}%Ho50L=?xr=|kwK*f~A^#vj!PZq7u2~9Z<@EQH zJVc5s52)A-PMEj^0I;2-OrZQAMOjwjf7`kv?>7}@!{wbzh$VP%`Fpxepe`^7)RA2p zYz?&on;?V+MWop1Izp7t003740D$8hB>?*;DDu#|-`4-3rR_@}yvBJ@0RX{s`e})N zPXGTX$nDVF_ISASIKZ1j>KsU(^t&Jjmp#mK9K4aC+2>L3AgfI`lqsUX@><;fWo1GnQEyeAo)vqOjf-?8JbtAD@7P_{Mshbj@^ z4_P{f_p=nZ@2j3O#a!s$F+~+>2KSDCa*OHOq-ij`DjuRB@`pwL9liq;e{3QFb^?E! zuTs_pIKlw{h?xKY*>n6HiGPLvZS13`MV9XHY8S%-0Cdh_Q8a!N`&Tcd{pN>cjhJ@(V zE8ahi{)r+J+_b&)87{RTAx@C6@BJe8+aU1<>Ca?vUqUB9ypKVAe}5X}YWvG=4BEb4sKd#FRAGdJereW8M#ex2Ox&pC|UuAgpmen9f-Y>JEcCh&wyD{KK?5syD~O z6E2UV{&|AyjBz>je+L=jFb9a$KdAS7P^Rq;m-W#QJN)a6AI(S&b~67udj-R6;2wBR z`mP_28WU3_!$-YqScvPZnw(!jf185rm@@eVE)^po7O<%BCn!?zskyByynN#3P>7|} z*SWJf)I`eJ<~tKc?TlxDBe*mSM=P8|6Fm79^nafM|2}zNf2wrU81675R}s6oTk)@u z|6BNOn+{(NR`SFE0NTkByPbH&FMz)dLCl-}U-jDf(^=FJl_O?QJyUMh`D^)95ebOt zEzbxnJ-?Ui5|MDP@JFoVYvaJD006N?F6jUO From 90d78870d44ee9163451152dbafacdeffeaf1433 Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Thu, 22 Jan 2026 19:27:41 -0800 Subject: [PATCH 19/25] working --- TeamCode/build.gradle | 24 +- .../ftc/teamcode/FieldOriented.java | 165 +------------ .../ftc/teamcode/PestoFTCConfig.java | 106 +------- .../ftc/teamcode/TWOTLateralTuner.java | 230 ------------------ .../ftc/teamcode/TWOTLocalizer.java | 72 ------ .../ftc/teamcode/TWOTRotationTuner.java | 172 ------------- .../ftc/teamcode/TWOTTranslationalTuner.java | 229 ----------------- .../org/firstinspires/ftc/teamcode/Utils.java | 43 ---- .../ftc/teamcode/autonomous/BlueFar.java | 222 ----------------- .../ftc/teamcode/autonomous/BlueFarPaths.java | 177 -------------- .../ftc/teamcode/autonomous/RedFar.java | 97 -------- .../ftc/teamcode/autonomous/RedFarPaths.java | 62 ----- .../ftc/teamcode/autonomous/Test.java | 44 ---- .../ftc/teamcode/autonomous/TuningAuto.java | 76 ------ .../ftc/teamcode/subsystems/BaseRobot.java | 47 +--- .../teamcode/subsystems/FeederSubsystem.java | 38 --- .../teamcode/subsystems/HoodSubsystem.java | 80 ------ .../teamcode/subsystems/IndexerSubsystem.java | 36 --- .../teamcode/subsystems/IntakeSubsystem.java | 100 -------- .../teamcode/subsystems/OuttakeSubsystem.java | 50 ---- build.dependencies.gradle | 2 +- 21 files changed, 20 insertions(+), 2052 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/OuttakeSubsystem.java diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index bf43315..4b478ca 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -12,22 +12,22 @@ // Custom definitions may go here // Include common definitions from above. -buildscript { - repositories { - mavenCentral() - maven { - url "https://repo.dairy.foundation/releases" - } - } - dependencies { - classpath "dev.frozenmilk:Load:0.2.4" - } -} +//buildscript { +// repositories { +// mavenCentral() +// maven { +// url "https://repo.dairy.foundation/releases" +// } +// } +// dependencies { +// classpath "dev.frozenmilk:Load:0.2.4" +// } +//} apply from: '../build.common.gradle' apply from: '../build.dependencies.gradle' -apply plugin: 'dev.frozenmilk.sinister.sloth.load' +//apply plugin: 'dev.frozenmilk.sinister.sloth.load' android { namespace = 'org.firstinspires.ftc.teamcode' diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java index 8f97685..d9965d7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java @@ -1,34 +1,16 @@ package org.firstinspires.ftc.teamcode; -import com.qualcomm.hardware.limelightvision.LLResult; -import com.qualcomm.hardware.limelightvision.LLResultTypes; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotor; -import com.shprobotics.pestocore.devices.GamepadKey; import com.shprobotics.pestocore.processing.FrontalLobe; import com.shprobotics.pestocore.processing.MotorCortex; -import org.apache.commons.math3.util.MathUtils; import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -import java.util.List; @TeleOp(name = "Field Oriented") public class FieldOriented extends BaseRobot { @Override public void runOpMode() { - PestoFTCConfig.initializePinpoint = true; - boolean braking = false; - boolean rotationLocked = false; - double angle = 0.0; - - boolean usingOdometry = true; - + PestoFTCConfig.initializePinpoint = false; super.initialize(); waitForStart(); @@ -37,156 +19,13 @@ public void runOpMode() { FrontalLobe.update(); MotorCortex.update(); gamepadInterface1.update(); - tracker.update(); teleOpController.updateSpeed(gamepad1); - boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; - mecanumController.setIsStatic(isStatic); - - if (gamepadInterface1.isKeyDown(GamepadKey.Y)) { - usingOdometry = !usingOdometry; - if (usingOdometry) - teleOpController.useTrackerIMU(tracker); - else - teleOpController.useIMU(); - } - - if (gamepadInterface1.isKeyDown(GamepadKey.B)) { - braking = !braking; - mecanumController.setZeroPowerBehavior(braking ? DcMotor.ZeroPowerBehavior.BRAKE : DcMotor.ZeroPowerBehavior.FLOAT); - } - - if (gamepadInterface1.isKeyDown(GamepadKey.RIGHT_BUMPER)) { - rotationLocked = !rotationLocked; - - double[] angles = new double[]{0.0, Math.PI / 2, Math.PI, 3 * Math.PI / 2}; - double bestDist = Double.POSITIVE_INFINITY; - - for (double x : angles) { - double dist = Math.abs(x - MathUtils.normalizeAngle(tracker.getCurrentPosition().getHeadingRadians(), x)); - - if (dist < bestDist) { - bestDist = dist; - angle = x; - } - } - } - if (gamepad1.x) { - tracker.reset(); teleOpController.resetIMU(); } - boolean intaking = gamepad1.right_trigger > 0.05; - boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; - boolean rejecting = !intaking && !outtaking && gamepad1.a; - boolean neutralizing = !intaking && !outtaking && !rejecting; - - if (rotationLocked) { - double correction = angle - MathUtils.normalizeAngle(tracker.getCurrentPosition().getHeadingRadians(), angle); - correction = correction * -0.6; // 0.6 == headingKP - correction += Math.signum(correction) * PestoFTCConfig.STATIC_DRIVE; - - teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, correction); - } else if (outtaking) { - LLResult result = limelight.getLatestResult(); - - List results = result.getFiducialResults(); - - if (result != null && result.isValid() && results.size() > 0 && results.get(0).getFiducialId() != 21) { - double rotate = -result.getTx()*PestoFTCConfig.KP; - rotate = Math.min(1, Math.max(-1, rotate)); - - if (rotate < 0) - rotate -= PestoFTCConfig.STATIC_DRIVE; - else - rotate += PestoFTCConfig.STATIC_DRIVE; - - teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, rotate); - telemetry.addData("tx", result.getTx()); - } else { - telemetry.addLine("No Target :("); - teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - } - } else - teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - - if (!outtaking && state == RobotState.OUTTAKE) { - FrontalLobe.removeMacros("outtake"); - } - - if (intaking) { - state = RobotState.INTAKE; - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } - - if (outtaking && state != RobotState.OUTTAKE) { - state = RobotState.OUTTAKE; - - FrontalLobe.useMacro("outtake"); - } - - if (rejecting) { - state = RobotState.REJECT; - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.REJECT); - feederSubsystem.setState(FeederSubsystem.FeederState.REVERSE); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } - - if (neutralizing) { - state = RobotState.NEUTRAL; - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - } - - -// // Nice little LED display on the gamepad - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) - gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); - - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) - gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); - - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) - gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); - -// // Cycle hood modes - if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { - if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { - hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); - } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { - hoodSubsystem.setState(HoodSubsystem.HoodState.MID); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_MIDDLE); - } - } - - feederSubsystem.update(); - hoodSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - indexerSubsystem.update(); - - telemetry.addData("x", tracker.getCurrentPosition().getX()); - telemetry.addData("y", tracker.getCurrentPosition().getY()); - telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); - telemetry.addData("teleop r", teleOpController.getHeading()); - telemetry.addData("using odometry", !usingOdometry); - telemetry.addData("target", intakeSubsystem.dropdownTarget); - telemetry.addData("pitch", intakeSubsystem.imu.getRobotYawPitchRollAngles().getPitch()); - telemetry.update(); + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index e0e3b2e..f8cbfe3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -5,11 +5,8 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; -import com.shprobotics.pestocore.algorithms.Constants; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; -import com.shprobotics.pestocore.drivebases.trackers.DeterministicTracker; -import com.shprobotics.pestocore.drivebases.trackers.ThreeWheelOdometryTracker; import com.shprobotics.pestocore.processing.Cerebrum; import com.shprobotics.pestocore.processing.ConfigInterface; import com.shprobotics.pestocore.processing.FrontalLobe; @@ -22,57 +19,6 @@ public class PestoFTCConfig implements ConfigInterface { private static boolean initialized = false; // don't mess with this :O public static boolean initializePinpoint = true; - public static double mass = 21.7; // lbs - public static double MAX_FORCE = 2220; - public static double DECELERATION = 35; - - // ODOMETRY - private static String leftName = "backLeft"; - private static String centerName = "frontLeft"; - private static String rightName = "backRight"; - - private static DcMotorSimple.Direction leftDirection = DcMotorSimple.Direction.REVERSE; - private static DcMotorSimple.Direction centerDirection = DcMotorSimple.Direction.REVERSE; - private static DcMotorSimple.Direction rightDirection = DcMotorSimple.Direction.REVERSE; - - private static double ODOMETRY_TICKS_PER_INCH_CENTER = 505.3169; - private static double ODOMETRY_TICKS_PER_INCH_LEFT = 505.3169; - private static double ODOMETRY_TICKS_PER_INCH_RIGHT = 505.3169; - public static double FORWARD_OFFSET = -1.565; - public static double ODOMETRY_WIDTH = 9.1474; - - - // DROPDOWN - public static double DROPDOWN_DRIVE = 35; // 0.29; - public static double DROPDOWN_INTAKE = 85; // 0.47; - public static double DROPDOWN_PUSH = 35; // 0.29; - public static double DROPDOWN_PUSH_AUTO = 35; // 0.29; - - // INDEXER - public static double INDEXER_OUTTAKE = 0.10; - public static double INDEXER_BLOCK = 0.24; - - // HOOD - public static double HOOD_CLOSE = 0.01; - public static double HOOD_MID = 0.04; - public static double HOOD_FAR = 0.01; - public static double HOOD_AUTO_FAR = 0.04; - - // SHOOTER - public static double SHOOTER_CLOSE = 0.65; - public static double SHOOTER_MIDDLE = 0.87; - public static double SHOOTER_FAR = 1.0; - public static double AUTO_FAR = 1.0; - - // CAMERA - public static double STATIC_DRIVE = 0.1; - public static double KP = 0.015; - - // AUTO - public static double DRIVE_STATIC = 0.25; - public static double HEADING_KP = 0.5; - public static double ENDPOINT_KP = 0.3; - public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); Cerebrum.initialize(); @@ -91,59 +37,13 @@ public static void initialize(HardwareMap hardwareMap) { DcMotorSimple.Direction.FORWARD }); -// driveController.setPowerVectors(new Vector2D[]{ -// new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), -// new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), -// new Vector2D(-Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)), -// new Vector2D(Math.min(FORWARD_VELOCITY / STRAFE_VELOCITY, 1.0), Math.min(STRAFE_VELOCITY / FORWARD_VELOCITY, 1.0)) -// }); - driveController.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); -// driveController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); driveController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); -// driveController.frontLeft.setAccelerationMax(5.0); -// driveController.frontRight.setAccelerationMax(5.0); -// driveController.backLeft.setAccelerationMax(5.0); -// driveController.backRight.setAccelerationMax(5.0); - - driveController.frontLeft.setAccelerationMax(Double.POSITIVE_INFINITY); - driveController.frontRight.setAccelerationMax(Double.POSITIVE_INFINITY); - driveController.backLeft.setAccelerationMax(Double.POSITIVE_INFINITY); - driveController.backRight.setAccelerationMax(Double.POSITIVE_INFINITY); - - if (initializePinpoint) { - DeterministicTracker tracker = new ThreeWheelOdometryTracker.TrackerBuilder( - hardwareMap, - ODOMETRY_TICKS_PER_INCH_LEFT, - ODOMETRY_TICKS_PER_INCH_RIGHT, - ODOMETRY_TICKS_PER_INCH_CENTER, - FORWARD_OFFSET, - ODOMETRY_WIDTH, - leftName, - centerName, - rightName, - leftDirection, - centerDirection, - rightDirection - ) - .build(); - - TeleOpController teleOpController = new TeleOpController(driveController, hardwareMap); - - teleOpController.configureIMU(new RevHubOrientationOnRobot(RevHubOrientationOnRobot.LogoFacingDirection.RIGHT, RevHubOrientationOnRobot.UsbFacingDirection.UP)); - - teleOpController.useTrackerIMU(tracker); - - teleOpController.setSpeedController(gamepad -> gamepad.left_bumper ? 0.6 : 1.0); - - teleOpController.counteractCentripetalForce(tracker, MAX_FORCE); - - FrontalLobe.teleOpController = teleOpController; - FrontalLobe.tracker = tracker; - } + TeleOpController teleOpController = new TeleOpController(driveController, hardwareMap); + teleOpController.configureIMU(new RevHubOrientationOnRobot(RevHubOrientationOnRobot.LogoFacingDirection.RIGHT, RevHubOrientationOnRobot.UsbFacingDirection.UP)); + FrontalLobe.teleOpController = teleOpController; FrontalLobe.driveController = driveController; - Constants.mass = mass; } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java deleted file mode 100644 index e7512c2..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLateralTuner.java +++ /dev/null @@ -1,230 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.acmerobotics.dashboard.PestoDashCore; -import com.acmerobotics.dashboard.config.variable.DataItem; -import com.acmerobotics.dashboard.config.variable.QualitativeSelector; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.shprobotics.pestocore.drivebases.trackers.TWOT; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; -import com.shprobotics.pestocore.processing.PestoTelemetry; - -import org.ejml.simple.SimpleMatrix; - -import java.util.ArrayList; - -@TeleOp(name = "TWOT Lateral Tuner") -public class TWOTLateralTuner extends LinearOpMode { - double distance = 24.5; - - @Override - public void runOpMode() { - FrontalLobe.initialize(hardwareMap); - PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; - - QualitativeSelector recordingSelector = new QualitativeSelector("recording?", "no", new String[]{"no", "yes"}); - pestoTelemetry.addToDash(recordingSelector); - pestoTelemetry.update(); - - TWOT tracker = new TWOT.TrackerBuilder( - hardwareMap, - 505.3169, - new SimpleMatrix(new double[][]{ - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - }), - new SimpleMatrix(new double[][]{ - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - }), - new SimpleMatrix(new double[][]{ - new double[]{-0.11201892953178422}, - new double[]{-0.0034454197797296054}, - new double[]{0.11231265526595093}, - }), - "backLeft", - "frontLeft", - "backRight", - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE - ) - .build(); - - telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); - telemetry.addLine("1. Press a to start recording"); - telemetry.addLine("2. Push the robot " + distance + " inches right (no vertical movement)"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m11, m21, m31, m41, m51, m61"); - telemetry.update(); - - ArrayList T_arr = new ArrayList<>(); - - double m11 = 0.0; - double m21 = 0.0; - double m31 = 0.0; - double m41 = 0.0; - double m51 = 0.0; - double m61 = 0.0; - - waitForStart(); - - tracker.reset(); - while (opModeIsActive() && !isStopRequested()) { - while (opModeIsActive() && !isStopRequested() && !gamepad1.a) { - pestoTelemetry.update(); - - DataItem item = PestoDashCore.getItem(recordingSelector.getId()); - - if (item != null && item.getValue() != null) { - String selection = (String) item.getValue(); - if (selection.equals("yes")) - break; - } - - telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); - telemetry.addLine("1. Press a to start recording"); - telemetry.addLine("2. Push the robot " + distance + " inches right (no vertical movement)"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m11, m21, m31, m41, m51, m61"); - telemetry.addLine(); - telemetry.addLine("Waiting for A"); - telemetry.addLine(); - telemetry.addData("m11", m11); - telemetry.addData("m21", m21); - telemetry.addData("m31", m31); - telemetry.addData("m41", m41); - telemetry.addData("m51", m51); - telemetry.addData("m61", m61); - telemetry.update(); - - pestoTelemetry.clear(); - pestoTelemetry.addToDash("m11", m11); - pestoTelemetry.addToDash("m21", m21); - pestoTelemetry.addToDash("m31", m31); - pestoTelemetry.addToDash("m41", m41); - pestoTelemetry.addToDash("m51", m51); - pestoTelemetry.addToDash("m61", m61); - } - - double TdLCos = 0.0; - double TdLSin = 0.0; - double TdCCos = 0.0; - double TdCSin = 0.0; - double TdRCos = 0.0; - double TdRSin = 0.0; - - double field_x = 0.0; - double field_y = 0.0; - double heading = 0.0; - - MotorCortex.update(); - tracker.reset(); - tracker.leftOdometry.getInchesTravelled(); - tracker.centerOdometry.getInchesTravelled(); - tracker.rightOdometry.getInchesTravelled(); - - while (opModeIsActive() && !isStopRequested() && !gamepad1.b) { - pestoTelemetry.update(); - - DataItem item = PestoDashCore.getItem(recordingSelector.getId()); - - if (item != null && item.getValue() != null) { - String selection = (String) item.getValue(); - if (selection.equals("no")) - break; - } - - MotorCortex.update(); - - double dL = tracker.leftOdometry.getInchesTravelled(); - double dC = tracker.centerOdometry.getInchesTravelled(); - double dR = tracker.rightOdometry.getInchesTravelled(); - - SimpleMatrix r_inputs = new SimpleMatrix(new double[][]{ - new double[]{dL, dC, dR} - }); - - double r = r_inputs.mult(tracker.ODOMETRY_PARAMETERS_R).toArray2()[0][0]; - - double cos = Math.cos(heading); - double sin = Math.sin(heading); - - SimpleMatrix xy_inputs = new SimpleMatrix(new double[][]{ - new double[]{ - dL * cos, - dL * sin, - dC * cos, - dC * sin, - dR * cos, - dR * sin - } - }); - - double x = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_X).toArray2()[0][0]; - double y = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_Y).toArray2()[0][0]; - - field_x += x; - field_y += y; - heading += r; - - TdLCos += (dL * cos); - TdLSin += (dL * sin); - TdCCos += (dC * cos); - TdCSin += (dC * sin); - TdRCos += (dR * cos); - TdRSin += (dR * sin); - - telemetry.addLine("1. Recording!"); - telemetry.addLine(); - telemetry.addLine("2. Push the robot " + distance + " inches right (no vertical movement)"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m11, m21, m31, m41, m51, m61"); - - telemetry.update(); - - pestoTelemetry.clear(); - pestoTelemetry.addToDash("X", field_x); - pestoTelemetry.addToDash("Y", field_y); - pestoTelemetry.addToDash("R", heading); - } - - T_arr.add(new double[]{TdLCos, TdLSin, TdCCos, TdCSin, TdRCos, TdRSin}); - SimpleMatrix T_matrix = new SimpleMatrix(T_arr.size(), 6); - - SimpleMatrix translations = new SimpleMatrix(T_arr.size(), 1); - translations.fill(distance); - - for (int i = 0; i < T_arr.size(); i++) { - T_matrix.setRow(i, new SimpleMatrix(T_arr.get(i))); - } - - SimpleMatrix translational_parameters = T_matrix.pseudoInverse().mult(translations); - - m11 = translational_parameters.get(0, 0); - m21 = translational_parameters.get(1, 0); - m31 = translational_parameters.get(2, 0); - m41 = translational_parameters.get(3, 0); - m51 = translational_parameters.get(4, 0); - m61 = translational_parameters.get(5, 0); - - tracker.ODOMETRY_PARAMETERS_X.set(0, 0, m11); - tracker.ODOMETRY_PARAMETERS_X.set(1, 0, m21); - tracker.ODOMETRY_PARAMETERS_X.set(2, 0, m31); - tracker.ODOMETRY_PARAMETERS_X.set(3, 0, m41); - tracker.ODOMETRY_PARAMETERS_X.set(4, 0, m51); - tracker.ODOMETRY_PARAMETERS_X.set(5, 0, m61); - - } - } -}; \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java deleted file mode 100644 index 1e2ffab..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTLocalizer.java +++ /dev/null @@ -1,72 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.shprobotics.pestocore.drivebases.trackers.TWOT; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; -import com.shprobotics.pestocore.processing.PestoTelemetry; - -import org.ejml.simple.SimpleMatrix; - -@TeleOp(name = "TWOT Localizer") -public class TWOTLocalizer extends LinearOpMode { - @Override - public void runOpMode() { - FrontalLobe.initialize(hardwareMap); - PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; - - TWOT tracker = new TWOT.TrackerBuilder( - hardwareMap, - 505.3169, - new SimpleMatrix(new double[][]{ - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - }), - new SimpleMatrix(new double[][]{ - new double[]{-3.403336515717541}, - new double[]{1.2699958957478223}, - new double[]{1.3460775162359155}, - new double[]{-1.0179996295954816}, - new double[]{4.3829921388933}, - new double[]{3.4734383975380965}, - }), - new SimpleMatrix(new double[][]{ - new double[]{-0.11201892953178422}, - new double[]{-0.0034454197797296054}, - new double[]{0.11231265526595093}, - }), - "backLeft", - "frontLeft", - "backRight", - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE - ) - .build(); - - waitForStart(); - - tracker.reset(); - while (opModeIsActive() && !isStopRequested()) { - MotorCortex.update(); - tracker.update(); - - telemetry.addData("X", tracker.getCurrentPosition().getX()); - telemetry.addData("Y", tracker.getCurrentPosition().getY()); - telemetry.addData("R", tracker.getCurrentPosition().getHeadingRadians()); - telemetry.update(); - - pestoTelemetry.clear(); - pestoTelemetry.addToDash("X", tracker.getCurrentPosition().getX()); - pestoTelemetry.addToDash("Y", tracker.getCurrentPosition().getY()); - pestoTelemetry.addToDash("R", tracker.getCurrentPosition().getHeadingRadians()); - pestoTelemetry.update(); - } - } -}; \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java deleted file mode 100644 index 01d0945..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTRotationTuner.java +++ /dev/null @@ -1,172 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.acmerobotics.dashboard.PestoDashCore; -import com.acmerobotics.dashboard.config.variable.DataItem; -import com.acmerobotics.dashboard.config.variable.QualitativeSelector; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.shprobotics.pestocore.drivebases.trackers.Odometry; -import com.shprobotics.pestocore.drivebases.trackers.TWOT; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; -import com.shprobotics.pestocore.processing.PestoTelemetry; - -import org.ejml.simple.SimpleMatrix; - -import java.util.ArrayList; - -@TeleOp(name = "TWOT Rotation Tuner") -public class TWOTRotationTuner extends LinearOpMode { - @Override - public void runOpMode() { - FrontalLobe.initialize(hardwareMap); - PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; - - QualitativeSelector recordingSelector = new QualitativeSelector("recording?", "no", new String[]{"no", "yes"}); - pestoTelemetry.addToDash(recordingSelector); - pestoTelemetry.update(); - - TWOT tracker = new TWOT.TrackerBuilder( - hardwareMap, - 505.3169, - new SimpleMatrix(new double[][]{ - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - }), - new SimpleMatrix(new double[][]{ - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - }), - new SimpleMatrix(new double[][]{ - new double[]{-0.11201892953178422}, - new double[]{-0.0034454197797296054}, - new double[]{0.11231265526595093}, - }), - "backLeft", - "frontLeft", - "backRight", - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE - ).build(); - - Odometry left = tracker.leftOdometry; - Odometry right = tracker.rightOdometry; - Odometry center = tracker.centerOdometry; - - telemetry.addLine("1. Press a to start recording"); - telemetry.addLine("2. Rotate the robot 180 degrees"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m13, m23, m33"); - telemetry.update(); - - FrontalLobe.pestoTelemetry.addToDash(new QualitativeSelector("recording?", "no", new String[]{"no", "yes"})); - FrontalLobe.pestoTelemetry.update(); - - ArrayList T_arr = new ArrayList<>(); - - double m13 = 0.0; - double m23 = 0.0; - double m33 = 0.0; - - waitForStart(); - - tracker.reset(); - while (opModeIsActive() && !isStopRequested()) { - while (opModeIsActive() && !isStopRequested() && !gamepad1.a) { - pestoTelemetry.update(); - - DataItem item = PestoDashCore.getItem(recordingSelector.getId()); - - if (item != null && item.getValue() != null) { - String selection = (String) item.getValue(); - if (selection.equals("yes")) - break; - } - - telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); - telemetry.addLine("1. Press a to start recording"); - telemetry.addLine("2. Rotate the robot 180 degrees"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m13, m23, m33"); - telemetry.addLine(); - telemetry.addLine("Waiting for A"); - telemetry.addLine(); - telemetry.addData("m13", m13); - telemetry.addData("m23", m23); - telemetry.addData("m33", m33); - telemetry.update(); - - pestoTelemetry.clear(); - pestoTelemetry.addToDash("m13", m13); - pestoTelemetry.addToDash("m23", m23); - pestoTelemetry.addToDash("m33", m33); - } - - double TdL = 0.0; - double TdC = 0.0; - double TdR = 0.0; - - double R = 0.0; - - while (opModeIsActive() && !isStopRequested() && !gamepad1.b) { - pestoTelemetry.update(); - - DataItem item = PestoDashCore.getItem(recordingSelector.getId()); - - if (item != null && item.getValue() != null) { - String selection = (String) item.getValue(); - if (selection.equals("no")) - break; - } - - MotorCortex.update(); - - double dL = left.getInchesTravelled(); - double dC = center.getInchesTravelled(); - double dR = right.getInchesTravelled(); - - TdL += dL; - TdC += dC; - TdR += dR; - - R += (dL * m13) + (dC * m23) + (dR * m33); - - telemetry.addLine("1. Recording!"); - telemetry.addLine(); - telemetry.addLine("2. Rotate the robot 180 degrees"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m13, m23, m33"); - telemetry.update(); - - pestoTelemetry.clear(); - pestoTelemetry.addToDash("r", R); - } - - T_arr.add(new double[]{TdL, TdC, TdR}); - SimpleMatrix T_matrix = new SimpleMatrix(T_arr.size(), 3); - - SimpleMatrix rotations = new SimpleMatrix(T_arr.size(), 1); - rotations.fill(Math.PI); - - for (int i = 0; i < T_arr.size(); i++) { - T_matrix.setRow(i, new SimpleMatrix(T_arr.get(i))); - } - - SimpleMatrix rotation_parameters = T_matrix.pseudoInverse().mult(rotations); - - m13 = rotation_parameters.get(0, 0); - m23 = rotation_parameters.get(1, 0); - m33 = rotation_parameters.get(2, 0); - } - } -}; \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java deleted file mode 100644 index 1a6701f..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TWOTTranslationalTuner.java +++ /dev/null @@ -1,229 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.acmerobotics.dashboard.PestoDashCore; -import com.acmerobotics.dashboard.config.variable.DataItem; -import com.acmerobotics.dashboard.config.variable.QualitativeSelector; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.shprobotics.pestocore.drivebases.trackers.TWOT; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; -import com.shprobotics.pestocore.processing.PestoTelemetry; - -import org.ejml.simple.SimpleMatrix; - -import java.util.ArrayList; - -@TeleOp(name = "TWOT Translational Tuner") -public class TWOTTranslationalTuner extends LinearOpMode { - double distance = 24.5; - - @Override - public void runOpMode() { - FrontalLobe.initialize(hardwareMap); - PestoTelemetry pestoTelemetry = FrontalLobe.pestoTelemetry; - - QualitativeSelector recordingSelector = new QualitativeSelector("recording?", "no", new String[]{"no", "yes"}); - pestoTelemetry.addToDash(recordingSelector); - pestoTelemetry.update(); - - TWOT tracker = new TWOT.TrackerBuilder( - hardwareMap, - 505.3169, - new SimpleMatrix(new double[][]{ - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - }), - new SimpleMatrix(new double[][]{ - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - new double[]{0.0}, - }), - new SimpleMatrix(new double[][]{ - new double[]{-0.11201892953178422}, - new double[]{-0.0034454197797296054}, - new double[]{0.11231265526595093}, - }), - "backLeft", - "frontLeft", - "backRight", - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE, - DcMotorSimple.Direction.REVERSE - ) - .build(); - - telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); - telemetry.addLine("1. Press a to start recording"); - telemetry.addLine("2. Push the robot " + distance + " inches forward (no horizontal movement)"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m12, m22, m32, m42, m52, m62"); - telemetry.update(); - - ArrayList T_arr = new ArrayList<>(); - - double m12 = 0.0; - double m22 = 0.0; - double m32 = 0.0; - double m42 = 0.0; - double m52 = 0.0; - double m62 = 0.0; - - waitForStart(); - - tracker.reset(); - while (opModeIsActive() && !isStopRequested()) { - while (opModeIsActive() && !isStopRequested() && !gamepad1.a) { - pestoTelemetry.update(); - - DataItem item = PestoDashCore.getItem(recordingSelector.getId()); - - if (item != null && item.getValue() != null) { - String selection = (String) item.getValue(); - if (selection.equals("yes")) - break; - } - - telemetry.addLine("Prereq. Run TWOT Rotation Tuner"); - telemetry.addLine("1. Press a to start recording"); - telemetry.addLine("2. Push the robot " + distance + " inches forward (no horizontal movement)"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m12, m22, m32, m42, m52, m62"); - telemetry.addLine(); - telemetry.addLine("Waiting for A"); - telemetry.addLine(); - telemetry.addData("m12", m12); - telemetry.addData("m22", m22); - telemetry.addData("m32", m32); - telemetry.addData("m42", m42); - telemetry.addData("m52", m52); - telemetry.addData("m62", m62); - telemetry.update(); - - pestoTelemetry.clear(); - pestoTelemetry.addToDash("m12", m12); - pestoTelemetry.addToDash("m22", m22); - pestoTelemetry.addToDash("m32", m32); - pestoTelemetry.addToDash("m42", m42); - pestoTelemetry.addToDash("m52", m52); - pestoTelemetry.addToDash("m62", m62); - } - - double TdLCos = 0.0; - double TdLSin = 0.0; - double TdCCos = 0.0; - double TdCSin = 0.0; - double TdRCos = 0.0; - double TdRSin = 0.0; - - double field_x = 0.0; - double field_y = 0.0; - double heading = 0.0; - - MotorCortex.update(); - tracker.reset(); - tracker.leftOdometry.getInchesTravelled(); - tracker.centerOdometry.getInchesTravelled(); - tracker.rightOdometry.getInchesTravelled(); - - while (opModeIsActive() && !isStopRequested() && !gamepad1.b) { - pestoTelemetry.update(); - - DataItem item = PestoDashCore.getItem(recordingSelector.getId()); - - if (item != null && item.getValue() != null) { - String selection = (String) item.getValue(); - if (selection.equals("no")) - break; - } - - MotorCortex.update(); - - double dL = tracker.leftOdometry.getInchesTravelled(); - double dC = tracker.centerOdometry.getInchesTravelled(); - double dR = tracker.rightOdometry.getInchesTravelled(); - - SimpleMatrix r_inputs = new SimpleMatrix(new double[][]{ - new double[]{dL, dC, dR} - }); - - double r = r_inputs.mult(tracker.ODOMETRY_PARAMETERS_R).toArray2()[0][0]; - - double cos = Math.cos(heading); - double sin = Math.sin(heading); - - SimpleMatrix xy_inputs = new SimpleMatrix(new double[][]{ - new double[]{ - dL * cos, - dL * sin, - dC * cos, - dC * sin, - dR * cos, - dR * sin - } - }); - - double x = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_X).toArray2()[0][0]; - double y = xy_inputs.mult(tracker.ODOMETRY_PARAMETERS_Y).toArray2()[0][0]; - - field_x += x; - field_y += y; - heading += r; - - TdLCos += (dL * cos); - TdLSin += (dL * sin); - TdCCos += (dC * cos); - TdCSin += (dC * sin); - TdRCos += (dR * cos); - TdRSin += (dR * sin); - - telemetry.addLine("1. Recording!"); - telemetry.addLine(); - telemetry.addLine("2. Push the robot " + distance + " inches forward (no horizontal movement)"); - telemetry.addLine("3. Press b to stop recording"); - telemetry.addLine("4. Repeat to get Matrix Values m12, m22, m32, m42, m52, m62"); - - telemetry.update(); - - pestoTelemetry.clear(); - pestoTelemetry.addToDash("X", field_x); - pestoTelemetry.addToDash("Y", field_y); - pestoTelemetry.addToDash("R", heading); - } - - T_arr.add(new double[]{TdLCos, TdLSin, TdCCos, TdCSin, TdRCos, TdRSin}); - SimpleMatrix T_matrix = new SimpleMatrix(T_arr.size(), 6); - - SimpleMatrix translations = new SimpleMatrix(T_arr.size(), 1); - translations.fill(distance); - - for (int i = 0; i < T_arr.size(); i++) { - T_matrix.setRow(i, new SimpleMatrix(T_arr.get(i))); - } - - SimpleMatrix translational_parameters = T_matrix.pseudoInverse().mult(translations); - - m12 = translational_parameters.get(0, 0); - m22 = translational_parameters.get(1, 0); - m32 = translational_parameters.get(2, 0); - m42 = translational_parameters.get(3, 0); - m52 = translational_parameters.get(4, 0); - m62 = translational_parameters.get(5, 0); - - tracker.ODOMETRY_PARAMETERS_Y.set(0, 0, m12); - tracker.ODOMETRY_PARAMETERS_Y.set(1, 0, m22); - tracker.ODOMETRY_PARAMETERS_Y.set(2, 0, m32); - tracker.ODOMETRY_PARAMETERS_Y.set(3, 0, m42); - tracker.ODOMETRY_PARAMETERS_Y.set(4, 0, m52); - tracker.ODOMETRY_PARAMETERS_Y.set(5, 0, m62); - } - } -}; \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java deleted file mode 100644 index a86c99c..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils.java +++ /dev/null @@ -1,43 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import android.util.Pair; - -import java.util.ArrayList; - -public class Utils { - private static ArrayList> timers; - - public static void clear() { - timers = new ArrayList<>(); - } - - public static boolean hasTimer(String id) { - for (Pair timer: timers) { - if (timer.second.equals(id)) - return true; - } - - return false; - } - - public static double getTime(String id) { - for (Pair timer: timers) { - if (timer.second.equals(id)) - return timer.first; - } - - return -1; - } - - public static boolean timer(double time, String id) { - double currentTime = System.nanoTime() / 1E9; - - for (Pair timer: timers) { - if (timer.second.equals(id)) - return time > (currentTime - timer.first); - } - - timers.add(new Pair<>(currentTime, id)); - return true; - } -} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java deleted file mode 100644 index 3297aba..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFar.java +++ /dev/null @@ -1,222 +0,0 @@ -package org.firstinspires.ftc.teamcode.autonomous; - -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.DONE; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.EIGHTH_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FIFTH_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FIRST_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.FOURTH_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.NINTH_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SECOND_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SEVENTH_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.SIXTH_PATH; -import static org.firstinspires.ftc.teamcode.autonomous.BlueFarPaths.PathState.THIRD_PATH; - -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.geometries.PathFollower; -import com.shprobotics.pestocore.geometries.Pose; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.PestoFTCConfig; -import org.firstinspires.ftc.teamcode.Utils; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IndexerSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -@Autonomous(name = "Blue Far") -public class BlueFar extends BaseRobot { - BlueFarPaths.PathState state; - PathFollower pathFollower; - double start; - - public void nextState() { - switch (state) { - case FIRST_PATH: - mecanumController.drive(0, 0, 0); - FrontalLobe.useMacro("outtake"); - while (Utils.timer(8.5, "outtake") && opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - tracker.update(); - pathFollower.update(); - - double distanceToEndpoint = Pose.dist(tracker.getCurrentPosition(), pathFollower.getPathContainer().getEndpoint()); - mecanumController.setIsStatic(distanceToEndpoint > 0.3 && tracker.getRobotVelocity().getMagnitude() < 0.5); - - feederSubsystem.update(); - hoodSubsystem.update(); - indexerSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - } - - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - - state = SECOND_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); - break; - case SECOND_PATH: - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - state = THIRD_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state, 0.2); - break; - case THIRD_PATH: - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - - state = FOURTH_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); - break; - case FOURTH_PATH: - state = FIFTH_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); - break; - case FIFTH_PATH: - state = SIXTH_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); - break; - case SIXTH_PATH: - FrontalLobe.removeMacros(""); - Utils.clear(); - - FrontalLobe.useMacro("outtake"); - while (Utils.timer(8.5, "outtake") && opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - tracker.update(); - pathFollower.update(); - - mecanumController.setIsStatic(tracker.getRobotVelocity().getMagnitude() < 1.0); - - feederSubsystem.update(); - hoodSubsystem.update(); - indexerSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - } - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - - state = SEVENTH_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); - break; - case SEVENTH_PATH: - state = EIGHTH_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); - - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.INTAKE); - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.NEUTRAL); - - break; - case EIGHTH_PATH: - state = NINTH_PATH; - start = System.nanoTime() / 1E9; - pathFollower = BlueFarPaths.getPathFollower(state); - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - - break; - case NINTH_PATH: - FrontalLobe.removeMacros(""); - Utils.clear(); - - FrontalLobe.useMacro("outtake"); - while (Utils.timer(7, "outtake") && opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - tracker.update(); - pathFollower.update(); - - mecanumController.setIsStatic(tracker.getRobotVelocity().getMagnitude() < 1.0); - - feederSubsystem.update(); - hoodSubsystem.update(); - indexerSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - } - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - - state = DONE; - start = System.nanoTime() / 1E9; - break; - case DONE: - break; - } - } - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = true; - Utils.clear(); - super.initialize(); - - mecanumController.setStaticPower(PestoFTCConfig.DRIVE_STATIC); - - state = FIRST_PATH; - pathFollower = BlueFarPaths.getPathFollower(state); - - hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_CLOSE); - - waitForStart(); - - start = System.nanoTime() / 1E9; - - while (opModeIsActive() && !isStopRequested()) { - double currentTime = System.nanoTime() / 1E9; - - FrontalLobe.update(); - MotorCortex.update(); - tracker.update(); - - double distanceToEndpoint = Pose.dist(tracker.getCurrentPosition(), pathFollower.getPathContainer().getEndpoint()); - mecanumController.setIsStatic(distanceToEndpoint > 0.3 && tracker.getRobotVelocity().getMagnitude() < 0.5); - - feederSubsystem.update(); - hoodSubsystem.update(); - indexerSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - - if (state == DONE) { - FrontalLobe.driveController.drive(0, 0, 0); - telemetry.addData("tracker", tracker.getCurrentPosition()); - telemetry.update(); - continue; - } - - if (pathFollower == null) { - continue; - } - - pathFollower.update(); - - telemetry.addData("target", pathFollower.getPathContainer().getCurrentPosition()); - telemetry.update(); - - if (pathFollower.isFinished() || (currentTime - start) > state.getTimer()) - nextState(); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java deleted file mode 100644 index f88349a..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/BlueFarPaths.java +++ /dev/null @@ -1,177 +0,0 @@ -package org.firstinspires.ftc.teamcode.autonomous; - -import com.shprobotics.pestocore.algorithms.PID; -import com.shprobotics.pestocore.geometries.BezierCurve; -import com.shprobotics.pestocore.geometries.PathContainer; -import com.shprobotics.pestocore.geometries.PathFollower; -import com.shprobotics.pestocore.geometries.Pose; -import com.shprobotics.pestocore.processing.FrontalLobe; - -import org.firstinspires.ftc.teamcode.PestoFTCConfig; - -public class BlueFarPaths { - public enum PathState { - FIRST_PATH (FIRST_MOVE, 0.5), - SECOND_PATH (SECOND_MOVE, 4.0), - THIRD_PATH (THIRD_MOVE, 3.5), - FOURTH_PATH (FOURTH_MOVE, 0.5), - FIFTH_PATH (FIFTH_MOVE, 2.0), - SIXTH_PATH (SIXTH_MOVE, 0.5), - SEVENTH_PATH (SEVENTH_MOVE, 5), - EIGHTH_PATH (EIGHTH_MOVE, 5), - NINTH_PATH (NINTH_MOVE, 5), - DONE (null, Double.POSITIVE_INFINITY); - - PathState(PathContainer pathContainer, double timer) { - this.pathContainer = pathContainer; - this.timer = timer; - } - - PathContainer pathContainer; - double timer; - - PathContainer getPath() { - return this.pathContainer; - } - - double getTimer() { - return this.timer; - } - } - - static PathContainer FIRST_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(0, 0, -0.7068), - new Pose(-14.711, -7.6111, -0.7068) - } - )) - .build(); - - static PathContainer SECOND_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.05) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-14.711, -7.6111, Math.toRadians(0)), - new Pose(-9.37, -30, Math.toRadians(0)) - } - )) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-9.37, -30, -0.23), - new Pose(-66.21, -7.83, -0.23) - } - )) - .build(); - - static PathContainer THIRD_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-66.21, -7.83, -0.23), - new Pose(-58.21, 22, -0.23) - } - )) - .build(); - - static PathContainer FOURTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.1) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-58.21, 19.41, -0.23), - new Pose(-66.21, -20, -0.23), - } - )) - .build(); - - static PathContainer FIFTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.1) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-66.21, -20, -0.23), - new Pose(-14.711, -20, -0.7068), - } - )) - .build(); - - static PathContainer SIXTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.1) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-14.711, -20, -0.7068), - new Pose(-14.711, -7.6111, -0.7068), - } - )) - .build(); - - static PathContainer SEVENTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.1) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-14.711, -7.6111, -0.23), - new Pose(-44, -20, -0.147), - } - )) - .build(); - - static PathContainer EIGHTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.1) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-44, -20, -0.147), - new Pose(-39.7, 15.0, -0.151), - } - )) - .build(); - - static PathContainer NINTH_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.1) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(-39.7, 15.0, -0.847), - new Pose(-15.5, -4.08, -0.847), - } - )) - .build(); - - public static PathFollower getPathFollower(PathState state) { - // TODO: create secondary - PathFollower pathFollower = new PathFollower.PathFollowerBuilder( - FrontalLobe.driveController, - FrontalLobe.tracker, - state.getPath(), - 0.2, - 0.0, - 0.2 - ) - .setDeceleration(PestoFTCConfig.DECELERATION) - .setLookAhead(1.0) - .setSpeed(0.6) - .setHeadingPID(new PID(PestoFTCConfig.HEADING_KP, 0, 0)) - .setEndpointPID(new PID(PestoFTCConfig.ENDPOINT_KP, 0, 0)) - .build(); - - return pathFollower; - } - - public static PathFollower getPathFollower(PathState state, double driveSpeed) { - // TODO: create secondary - PathFollower pathFollower = new PathFollower.PathFollowerBuilder( - FrontalLobe.driveController, - FrontalLobe.tracker, - state.getPath(), - 0.2, - 0.0, - 0.2 - ) - .setDeceleration(PestoFTCConfig.DECELERATION) - .setLookAhead(2.0) - .setSpeed(driveSpeed) - .setHeadingPID(new PID(PestoFTCConfig.HEADING_KP, 0, 0)) - .setEndpointPID(new PID(PestoFTCConfig.ENDPOINT_KP, 0, 0)) - .build(); - - return pathFollower; - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java deleted file mode 100644 index 2729807..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFar.java +++ /dev/null @@ -1,97 +0,0 @@ -package org.firstinspires.ftc.teamcode.autonomous; - -import static org.firstinspires.ftc.teamcode.autonomous.RedFarPaths.PathState.DONE; - -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.geometries.PathFollower; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.PestoFTCConfig; -import org.firstinspires.ftc.teamcode.Utils; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; -import org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem; -import org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem; - -@Autonomous(name = "Red Far") -public class RedFar extends BaseRobot { - RedFarPaths.PathState state; - PathFollower pathFollower; - double start; - - public void nextState() { - switch (state) { - case FIRST_PATH: - mecanumController.drive(0, 0, 0); - FrontalLobe.useMacro("outtake"); - while (Utils.timer(7.0, "outtake")) { - FrontalLobe.update(); - MotorCortex.update(); - - feederSubsystem.update(); - hoodSubsystem.update(); - indexerSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - } - - intakeSubsystem.setState(IntakeSubsystem.IntakeState.NEUTRAL); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.NEUTRAL); - feederSubsystem.setState(FeederSubsystem.FeederState.STOPPED); - - state = DONE; - break; - case DONE: - break; - } - } - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = true; - Utils.clear(); - super.initialize(); - - state = RedFarPaths.PathState.FIRST_PATH; - pathFollower = RedFarPaths.getPathFollower(state); - - hoodSubsystem.setState(HoodSubsystem.HoodState.AUTO_FAR); - outtakeSubsystem.setPower(PestoFTCConfig.SHOOTER_FAR); - - waitForStart(); - - start = System.nanoTime() / 1E9; - - while (opModeIsActive() && !isStopRequested()) { - double currentTime = System.nanoTime() / 1E9; - - FrontalLobe.update(); - MotorCortex.update(); - tracker.update(); - - boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; - mecanumController.setIsStatic(isStatic); - - feederSubsystem.update(); - hoodSubsystem.update(); - indexerSubsystem.update(); - intakeSubsystem.update(); - outtakeSubsystem.update(); - - if (state == DONE) { - FrontalLobe.driveController.drive(0, 0, 0); - continue; - } - - if (pathFollower.isFinished() || (currentTime - start) > state.getTimer()) - nextState(); - - if (pathFollower != null) - pathFollower.update(); - - telemetry.update(); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java deleted file mode 100644 index a0714d6..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/RedFarPaths.java +++ /dev/null @@ -1,62 +0,0 @@ -package org.firstinspires.ftc.teamcode.autonomous; - -import com.shprobotics.pestocore.algorithms.PID; -import com.shprobotics.pestocore.geometries.BezierCurve; -import com.shprobotics.pestocore.geometries.PathContainer; -import com.shprobotics.pestocore.geometries.PathFollower; -import com.shprobotics.pestocore.geometries.Pose; -import com.shprobotics.pestocore.processing.FrontalLobe; - -import org.firstinspires.ftc.teamcode.PestoFTCConfig; - -public class RedFarPaths { - public enum PathState { - FIRST_PATH (FIRST_MOVE, 5.0), - DONE (null, Double.POSITIVE_INFINITY); - - PathState(PathContainer pathContainer, double timer) { - this.pathContainer = pathContainer; - this.timer = timer; - } - - PathContainer pathContainer; - double timer; - - PathContainer getPath() { - return this.pathContainer; - } - - double getTimer() { - return this.timer; - } - } - - static PathContainer FIRST_MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(0, 0, -0.4), - new Pose(0, 9, -0.4) - } - )) - .build(); - - public static PathFollower getPathFollower(PathState state) { - PathFollower pathFollower = new PathFollower.PathFollowerBuilder( - FrontalLobe.driveController, - FrontalLobe.tracker, - state.getPath(), - 0.2, - 0.05, - 0.2 - ) - .setDeceleration(PestoFTCConfig.DECELERATION) - .setLookAhead(1.5) - .setSpeed(0.75) - .setHeadingPID(new PID(0.3, 0, 0)) - .setEndpointPID(new PID(0.001, 0, 0)) - .build(); - - return pathFollower; - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java deleted file mode 100644 index 205148f..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/Test.java +++ /dev/null @@ -1,44 +0,0 @@ -package org.firstinspires.ftc.teamcode.autonomous; - -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.drivebases.trackers.ThreeWheelOdometryTracker; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.PestoFTCConfig; -import org.firstinspires.ftc.teamcode.Utils; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; - -@Autonomous(name = "Test") -public class Test extends BaseRobot { - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = true; - Utils.clear(); - super.initialize(); - - waitForStart(); - - double dL = 0.0; - double dC = 0.0; - double dR = 0.0; - - while (opModeIsActive() && !isStopRequested()) { - MotorCortex.update(); - - if (gamepad1.b) { - dL = 0.0; - dC = 0.0; - dR = 0.0; - } - - dL += ((ThreeWheelOdometryTracker) tracker).leftOdometry.getInchesTravelled(); - dC += ((ThreeWheelOdometryTracker) tracker).centerOdometry.getInchesTravelled(); - dR += ((ThreeWheelOdometryTracker) tracker).rightOdometry.getInchesTravelled(); - - telemetry.addData("dL", dL); - telemetry.addData("dC", dC); - telemetry.addData("dR", dR); - telemetry.update(); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java deleted file mode 100644 index 902ca3b..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/TuningAuto.java +++ /dev/null @@ -1,76 +0,0 @@ -package org.firstinspires.ftc.teamcode.autonomous; - -import com.acmerobotics.dashboard.config.Config; -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.shprobotics.pestocore.algorithms.PID; -import com.shprobotics.pestocore.geometries.BezierCurve; -import com.shprobotics.pestocore.geometries.PathContainer; -import com.shprobotics.pestocore.geometries.PathFollower; -import com.shprobotics.pestocore.geometries.Pose; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.PestoFTCConfig; -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; - -@Config -@Autonomous(name = "Tuning Auto") -public class TuningAuto extends BaseRobot { - public static double endpoint_kp = 0.3; - public static double heading_kp = 0; - public static double deceleration = 35; - public static double speed = 0.6; - public static double look_ahead = 1; - - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = true; - super.initialize(); - - mecanumController.setStaticPower(PestoFTCConfig.STATIC_DRIVE); - - PathContainer MOVE = new PathContainer.PathContainerBuilder() - .setIncrement(0.01) - .addCurve(new BezierCurve( - new Pose[]{ - new Pose(0, 0, 0.0), - new Pose(0, 30, 0.0) - } - )) - .build(); - - PathFollower pathFollower = new PathFollower.PathFollowerBuilder( - FrontalLobe.driveController, - FrontalLobe.tracker, - MOVE, - 0.2, - 0.05, - 0.2 - ) - .setDeceleration(deceleration) - .setLookAhead(look_ahead) - .setSpeed(speed) - .setHeadingPID(new PID(heading_kp, 0, 0)) - .setEndpointPID(new PID(endpoint_kp, 0, 0)) - .build(); - - waitForStart(); - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - tracker.update(); - -// boolean isStatic = tracker.getRobotVelocity().getMagnitude() < 1.0; -// mecanumController.setIsStatic(isStatic); - - pathFollower.update(); - - telemetry.addData("decelerating", pathFollower.isDecelerating()); - telemetry.addData("X", tracker.getCurrentPosition().getX()); - telemetry.addData("Y", tracker.getCurrentPosition().getY()); - telemetry.addData("R", tracker.getCurrentPosition().getHeadingRadians()); - telemetry.update(); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java index 271b389..2886dc3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java @@ -1,6 +1,5 @@ package org.firstinspires.ftc.teamcode.subsystems; -import com.qualcomm.hardware.limelightvision.Limelight3A; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.hardware.DcMotor; import com.shprobotics.pestocore.devices.GamepadInterface; @@ -16,14 +15,6 @@ public class BaseRobot extends LinearOpMode { public DeterministicTracker tracker; public TeleOpController teleOpController; - public FeederSubsystem feederSubsystem; - public HoodSubsystem hoodSubsystem; - public IntakeSubsystem intakeSubsystem; - public OuttakeSubsystem outtakeSubsystem; - public IndexerSubsystem indexerSubsystem; - - public Limelight3A limelight; - public GamepadInterface gamepadInterface1; public RobotState state; @@ -41,51 +32,17 @@ public void initialize() { mecanumController = (MecanumController) FrontalLobe.driveController; mecanumController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + teleOpController = FrontalLobe.teleOpController; + if (PestoFTCConfig.initializePinpoint) { tracker = FrontalLobe.tracker; tracker.reset(); - - teleOpController = FrontalLobe.teleOpController; } - feederSubsystem = new FeederSubsystem(); - hoodSubsystem = new HoodSubsystem(); - intakeSubsystem = new IntakeSubsystem(); - outtakeSubsystem = new OuttakeSubsystem(); - indexerSubsystem = new IndexerSubsystem(); - - limelight = hardwareMap.get(Limelight3A.class, "limelight"); - - limelight.pipelineSwitch(0); - limelight.start(); - gamepadInterface1 = new GamepadInterface(gamepad1); // State initialization state = RobotState.NEUTRAL; - - // MACRO initialization - - FrontalLobe.addMacro("outtake", new FrontalLobe.Macro() { - @Override - public void start() { - FrontalLobe.removeOtherMacros(this); - outtakeSubsystem.setState(OuttakeSubsystem.OuttakeState.OUTTAKE); - } - - @Override - public boolean loop(double v) { - // how long (seconds) before starting to move other components - if (v < 1.0) - return false; - - feederSubsystem.setState(FeederSubsystem.FeederState.FORWARD); - intakeSubsystem.setState(IntakeSubsystem.IntakeState.OUTTAKE); - indexerSubsystem.setState(IndexerSubsystem.IndexerState.OUTTAKE); - - return true; - } - }); } @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java deleted file mode 100644 index 705e267..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/FeederSubsystem.java +++ /dev/null @@ -1,38 +0,0 @@ -package org.firstinspires.ftc.teamcode.subsystems; - -import static org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem.FeederState.FORWARD; -import static org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem.FeederState.REVERSE; -import static org.firstinspires.ftc.teamcode.subsystems.FeederSubsystem.FeederState.STOPPED; - -import com.shprobotics.pestocore.hardware.CortexLinkedCRServo; -import com.shprobotics.pestocore.processing.MotorCortex; - -public class FeederSubsystem { - private final CortexLinkedCRServo feeder; - private FeederState state; - - public enum FeederState { - FORWARD, - REVERSE, - STOPPED - } - - public FeederSubsystem() { - feeder = MotorCortex.getCRServo("feeder"); - state = STOPPED; - } - - public void setState(FeederState state) { - this.state = state; - } - - public void update() { - if (state == FORWARD) - feeder.setPowerResult(1.0); - if (state == REVERSE) - feeder.setPowerResult(-1.0); - if (state == STOPPED) - feeder.setPowerResult(0.0); - - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java deleted file mode 100644 index 93b8625..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java +++ /dev/null @@ -1,80 +0,0 @@ -package org.firstinspires.ftc.teamcode.subsystems; - -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_AUTO_FAR; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_CLOSE; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_FAR; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_MID; -import static org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem.HoodState.CLOSE; - -import com.qualcomm.robotcore.hardware.DistanceSensor; -import com.shprobotics.pestocore.hardware.CortexLinkedServo; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; - -public class HoodSubsystem { - private final CortexLinkedServo hood; - private final CortexLinkedServo led; - private final DistanceSensor distanceSensor; - - private HoodState state; - - public enum HoodState { - CLOSE, - MID, - FAR, - AUTO_FAR - } - - public HoodSubsystem() { - hood = MotorCortex.getServo("hood"); - led = MotorCortex.getServo("led"); - - distanceSensor = (DistanceSensor) MotorCortex.hardwareMap.get("distance"); - - state = CLOSE; - } - - public HoodState getState() { - return state; - } - - public void setState(HoodState state) { - this.state = state; - } - - public double getDistance() { - return distanceSensor.getDistance(DistanceUnit.CM); - } - - public void update() { - boolean ledOverride = distanceSensor.getDistance(DistanceUnit.CM) < 10; - - if (ledOverride) - led.setPositionResult(0.39); // YALLOW - - if (state == CLOSE) { - hood.setPositionResult(HOOD_CLOSE); - if (!ledOverride) - led.setPositionResult(0.5); // GREEN - } - - if (state == HoodState.MID) { - hood.setPositionResult(HOOD_MID); - if (!ledOverride) - led.setPositionResult(0.61); // BLUE - } - - if (state == HoodState.FAR) { - hood.setPositionResult(HOOD_FAR); - if (!ledOverride) - led.setPositionResult(0.28); // RED - } - - if (state == HoodState.AUTO_FAR) { - hood.setPositionResult(HOOD_AUTO_FAR); - if (!ledOverride) - led.setPositionResult(0.28); // RED - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java deleted file mode 100644 index f419d32..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IndexerSubsystem.java +++ /dev/null @@ -1,36 +0,0 @@ -package org.firstinspires.ftc.teamcode.subsystems; - -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.INDEXER_BLOCK; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.INDEXER_OUTTAKE; - -import com.shprobotics.pestocore.hardware.CortexLinkedServo; -import com.shprobotics.pestocore.processing.MotorCortex; - -public class IndexerSubsystem { - private final CortexLinkedServo indexer; - - private IndexerState state; - - public enum IndexerState { - OUTTAKE, - NEUTRAL - } - - public IndexerSubsystem() { - indexer = MotorCortex.getServo("blocker"); - - state = IndexerState.NEUTRAL; - } - - public void setState(IndexerState state) { - this.state = state; - } - - public void update() { - if (state == IndexerState.OUTTAKE) { - indexer.setPositionResult(INDEXER_OUTTAKE); - } else { - indexer.setPositionResult(INDEXER_BLOCK); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java deleted file mode 100644 index e6b81cc..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeSubsystem.java +++ /dev/null @@ -1,100 +0,0 @@ -package org.firstinspires.ftc.teamcode.subsystems; - -import static com.qualcomm.robotcore.hardware.DcMotorSimple.Direction.REVERSE; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_DRIVE; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_INTAKE; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_PUSH; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.DROPDOWN_PUSH_AUTO; -import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.INTAKE; -import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.NEUTRAL; -import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.OUTTAKE; -import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.OUTTAKE_AUTO; -import static org.firstinspires.ftc.teamcode.subsystems.IntakeSubsystem.IntakeState.REJECT; - -import com.qualcomm.hardware.rev.Rev9AxisImu; -import com.shprobotics.pestocore.hardware.CortexLinkedCRServo; -import com.shprobotics.pestocore.hardware.CortexLinkedMotor; -import com.shprobotics.pestocore.processing.MotorCortex; - -public class IntakeSubsystem { - private final CortexLinkedMotor intake; - public final CortexLinkedCRServo dropdown; - - public final Rev9AxisImu imu; - private double pitchVelocity = 0.0; - private double pitch = 0.0; - private double time = 0.0; - private double power = 0.0; - public double dropdownTarget; - - private IntakeState state; - - public enum IntakeState { - INTAKE, - NEUTRAL, - REJECT, - OUTTAKE, - OUTTAKE_AUTO - } - - public IntakeSubsystem() { - intake = MotorCortex.getMotor("intake"); - intake.setDirection(REVERSE); - - imu = (Rev9AxisImu) MotorCortex.hardwareMap.get("ext_imu"); - - dropdown = MotorCortex.getCRServo("dropdown"); - - state = NEUTRAL; - dropdownTarget = DROPDOWN_DRIVE; - } - - public void setState(IntakeState state) { - this.state = state; - } - - public void update() { - if (state == INTAKE) { - intake.setPowerResult(1.0); - dropdownTarget = DROPDOWN_INTAKE; - } - - if (state == NEUTRAL) { - intake.setPowerResult(0.15); - dropdownTarget = DROPDOWN_DRIVE; - } - - if (state == REJECT) { - intake.setPowerResult(-1.0); - dropdownTarget = DROPDOWN_INTAKE; - } - - if (state == OUTTAKE) { - intake.setPowerResult(1.0); - dropdownTarget = DROPDOWN_PUSH; - } - - if (state == OUTTAKE_AUTO) { - intake.setPowerResult(1.0); - dropdownTarget = DROPDOWN_PUSH_AUTO; - } - - pitchVelocity = (imu.getRobotYawPitchRollAngles().getPitch() - pitch) / ((System.nanoTime() - time) / 1E9); - - // dropdown PID logic - pitch = imu.getRobotYawPitchRollAngles().getPitch(); - time = System.nanoTime(); - - // power save with <10 degrees of error - if (Math.abs(dropdownTarget - pitch) < 10) { - dropdown.setPowerResult(0.0); - return; - } - - double error = 0.008 * (dropdownTarget - pitch) - 0.003 * pitchVelocity; - - power = Math.min(1.0, Math.max(-1.0, error)); - - dropdown.setPowerResult(-power); - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/OuttakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/OuttakeSubsystem.java deleted file mode 100644 index 807365b..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/OuttakeSubsystem.java +++ /dev/null @@ -1,50 +0,0 @@ -package org.firstinspires.ftc.teamcode.subsystems; - -import static com.qualcomm.robotcore.hardware.DcMotor.RunMode.RUN_USING_ENCODER; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.INDEXER_BLOCK; -import static org.firstinspires.ftc.teamcode.PestoFTCConfig.INDEXER_OUTTAKE; -import static org.firstinspires.ftc.teamcode.subsystems.OuttakeSubsystem.OuttakeState.OUTTAKE; - -import com.shprobotics.pestocore.hardware.CortexLinkedMotor; -import com.shprobotics.pestocore.hardware.CortexLinkedServo; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; -import org.firstinspires.ftc.teamcode.PestoFTCConfig; - -public class OuttakeSubsystem { - private final CortexLinkedMotor shooter; - - private OuttakeState state; - - private double power = PestoFTCConfig.SHOOTER_CLOSE; - - public enum OuttakeState { - OUTTAKE, - NEUTRAL - } - - public OuttakeSubsystem() { - shooter = MotorCortex.getMotor("shooter"); - shooter.setMode(RUN_USING_ENCODER); - - state = OuttakeState.NEUTRAL; - } - - public void setState(OuttakeState state) { - this.state = state; - } - - public void setPower(double power) { - assert 0 <= power && power <= 1; - this.power = power; - } - - public void update() { - if (state == OUTTAKE) { - shooter.setPowerResult(power); - } else { - shooter.setPowerResult(0.0); - } - } -} diff --git a/build.dependencies.gradle b/build.dependencies.gradle index 5a262cc..afc4534 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -34,6 +34,6 @@ dependencies { implementation 'org.ejml:ejml-all:0.43' - implementation "dev.frozenmilk.sinister:Sloth:0.2.4" +// implementation "dev.frozenmilk.sinister:Sloth:0.2.4" } From 1dc162ec918b882584fdea11143fa322b1e3a59d Mon Sep 17 00:00:00 2001 From: skurian27 <122177586+skurian27@users.noreply.github.com> Date: Fri, 23 Jan 2026 18:12:03 -0800 Subject: [PATCH 20/25] started bot code --- .../ftc/teamcode/FieldOriented.java | 31 ---- .../ftc/teamcode/PestoFTCConfig.java | 105 +++++++++++-- .../ftc/teamcode/subsystems/BaseRobot.java | 47 +++++- .../teamcode/subsystems/BlockerSubsystem.java | 34 ++++ .../teamcode/subsystems/HoodSubsystem.java | 38 +++++ .../subsystems/IntakeOuttakeSubsystem.java | 64 ++++++++ .../ftc/teamcode/teleops/Drive.java | 145 ++++++++++++++++++ .../ftc/teamcode/teleops/Move.java | 29 ++++ local.properties | 4 +- 9 files changed, 448 insertions(+), 49 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BlockerSubsystem.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java deleted file mode 100644 index d9965d7..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/FieldOriented.java +++ /dev/null @@ -1,31 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.shprobotics.pestocore.processing.FrontalLobe; -import com.shprobotics.pestocore.processing.MotorCortex; - -import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; - -@TeleOp(name = "Field Oriented") -public class FieldOriented extends BaseRobot { - @Override - public void runOpMode() { - PestoFTCConfig.initializePinpoint = false; - super.initialize(); - - waitForStart(); - - while (opModeIsActive() && !isStopRequested()) { - FrontalLobe.update(); - MotorCortex.update(); - gamepadInterface1.update(); - teleOpController.updateSpeed(gamepad1); - - if (gamepad1.x) { - teleOpController.resetIMU(); - } - - teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index f8cbfe3..eaf3a4f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -1,12 +1,14 @@ package org.firstinspires.ftc.teamcode; import com.acmerobotics.dashboard.config.Config; -import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; +import com.shprobotics.pestocore.algorithms.Constants; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; +import com.shprobotics.pestocore.drivebases.trackers.DeterministicTracker; +import com.shprobotics.pestocore.drivebases.trackers.ThreeWheelOdometryTracker; import com.shprobotics.pestocore.processing.Cerebrum; import com.shprobotics.pestocore.processing.ConfigInterface; import com.shprobotics.pestocore.processing.FrontalLobe; @@ -16,34 +18,119 @@ @Config @PestoConfig() public class PestoFTCConfig implements ConfigInterface { - private static boolean initialized = false; // don't mess with this :O + public static boolean initialized = false; // don't mess with this :O public static boolean initializePinpoint = true; + public static double mass = 23.7; // lbs + public static double MAX_FORCE = 2170; + public static double DECELERATION = 100; + public static double ENDPOINT_KP = 0.3; + public static double HEADING_KP = 4; + + // ODOMETRY + public static String leftName = "backL"; + public static String centerName = "backR"; + public static String rightName = "frontR"; + + public static DcMotorSimple.Direction leftDirection = DcMotorSimple.Direction.FORWARD; + public static DcMotorSimple.Direction centerDirection = DcMotorSimple.Direction.REVERSE; + public static DcMotorSimple.Direction rightDirection = DcMotorSimple.Direction.FORWARD; + + public static double ODOMETRY_TICKS_PER_INCH = 505.3169; + public static double FORWARD_OFFSET = -1.9; + public static double ODOMETRY_WIDTH = 4.1789; + + public static double STATIC_DRIVE = 0.22; + + // DROPDOWN + public static double DROPDOWN_DRIVE = 0.4; + public static double DROPDOWN_INTAKE = 0.25; + public static double DROPDOWN_PUSH = 0.35; + + // BLOCKER + public static double BLOCKER_BLOCK = 0.4; + public static double BLOCKER_OUTTAKE = 0.7; + + // INDEXER + public static double INDEXER_IN = 0.20; + public static double INDEXER_OUTISH = 0.52; + public static double INDEXER_OUT = 0.589; + + // HOOD + public static double HOOD_CLOSE = 0.33; + public static double HOOD_MID = 0.34; + public static double HOOD_FAR = 0.35; + + // SHOOTER + public static double SHOOTER_KP = 0.3; + + public static double SHOOTER_FF_CLOSE = 0.32; + public static double SHOOTER_FF_MIDDLE = 0.5; + public static double SHOOTER_FF_FAR = 0.5; + public static double SHOOTER_FF_AUTO = 0.5; + + public static double SHOOTER_CLOSE = 1.8; + public static double SHOOTER_MIDDLE = 3.5; + public static double SHOOTER_FAR = 2.6; + public static double SHOOTER_AUTO = 2.6; + + public static double SHOOTER_RPM_TOLERANCE = 0.15; + + // TURRET + public static double TURRET_LEFT = 100; + public static double TURRET_RIGHT = -100; + public static double TURRET_STATIC = 0.12; //increase when its a little off + public static double TURRET_KP = 0.006; + + // BRAKE + public static double BRAKE_DOWN = 0.3; + public static double BRAKE_UP = 0.1; + public static void initialize(HardwareMap hardwareMap) { MotorCortex.initialize(hardwareMap); Cerebrum.initialize(); - MecanumController driveController = new MecanumController( + MecanumController mecanumController = new MecanumController( MotorCortex.getMotor("frontLeft"), MotorCortex.getMotor("frontRight"), MotorCortex.getMotor("backLeft"), MotorCortex.getMotor("backRight") ); - driveController.configureMotorDirections(new DcMotorSimple.Direction[]{ + FrontalLobe.driveController = mecanumController; + + mecanumController.configureMotorDirections(new DcMotorSimple.Direction[]{ DcMotorSimple.Direction.REVERSE, DcMotorSimple.Direction.FORWARD, DcMotorSimple.Direction.REVERSE, DcMotorSimple.Direction.FORWARD }); - driveController.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); - driveController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + mecanumController.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); + + ThreeWheelOdometryTracker tracker = new ThreeWheelOdometryTracker.TrackerBuilder( + hardwareMap, + ODOMETRY_TICKS_PER_INCH, + ODOMETRY_TICKS_PER_INCH, + ODOMETRY_TICKS_PER_INCH, + 0.0, + 0.0, + "left", + "center", + "right", + DcMotorSimple.Direction.FORWARD, + DcMotorSimple.Direction.FORWARD, + DcMotorSimple.Direction.FORWARD + ) + .build(); + + FrontalLobe.tracker = tracker; - TeleOpController teleOpController = new TeleOpController(driveController, hardwareMap); - teleOpController.configureIMU(new RevHubOrientationOnRobot(RevHubOrientationOnRobot.LogoFacingDirection.RIGHT, RevHubOrientationOnRobot.UsbFacingDirection.UP)); + TeleOpController teleOpController = new TeleOpController(mecanumController, hardwareMap); FrontalLobe.teleOpController = teleOpController; + teleOpController.useTrackerIMU(tracker); - FrontalLobe.driveController = driveController; + FrontalLobe.driveController = mecanumController; + Constants.mass = mass; } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java index 2886dc3..75a90b5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java @@ -12,12 +12,17 @@ public class BaseRobot extends LinearOpMode { public MecanumController mecanumController; - public DeterministicTracker tracker; public TeleOpController teleOpController; + public DeterministicTracker tracker; + + public BlockerSubsystem blockerSubsystem; + public HoodSubsystem hoodSubsystem; + public IntakeOuttakeSubsystem intakeOuttakeSubsystem; public GamepadInterface gamepadInterface1; public RobotState state; + public boolean brake; public enum RobotState { INTAKE, @@ -30,23 +35,51 @@ public void initialize() { FrontalLobe.initialize(hardwareMap); mecanumController = (MecanumController) FrontalLobe.driveController; - mecanumController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); +// mecanumController.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); teleOpController = FrontalLobe.teleOpController; - if (PestoFTCConfig.initializePinpoint) { - tracker = FrontalLobe.tracker; - tracker.reset(); - } + tracker = FrontalLobe.tracker; + + blockerSubsystem = new BlockerSubsystem(); + hoodSubsystem = new HoodSubsystem(); + intakeOuttakeSubsystem = new IntakeOuttakeSubsystem(); gamepadInterface1 = new GamepadInterface(gamepad1); // State initialization state = RobotState.NEUTRAL; + brake = false; + + // MACRO initialization + + FrontalLobe.addMacro("outtake", new FrontalLobe.Macro() { + @Override + public void start() { + FrontalLobe.removeOtherMacros(this); + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.PREREV); + } + + @Override + public boolean loop(double v) { + // how long (seconds) before starting to move other components + if (v < 0.3) + return false; + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.REV); + if (v < 2) + return false; + + blockerSubsystem.setState(BlockerSubsystem.BlockerState.NEUTRAL); + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.OUTTAKE); + + + return true; + } + }); } @Override public void runOpMode() { } -} \ No newline at end of file +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BlockerSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BlockerSubsystem.java new file mode 100644 index 0000000..4c98d9a --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BlockerSubsystem.java @@ -0,0 +1,34 @@ +package org.firstinspires.ftc.teamcode.subsystems; + +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.BLOCKER_BLOCK; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.BLOCKER_OUTTAKE; + +import com.shprobotics.pestocore.hardware.CortexLinkedServo; +import com.shprobotics.pestocore.processing.MotorCortex; + +public class BlockerSubsystem { + private CortexLinkedServo blocker; + + private BlockerState state; + + public enum BlockerState{ + BLOCK, + NEUTRAL + } + + public BlockerSubsystem(){ + blocker = MotorCortex.getServo("blocker"); + state = BlockerState.BLOCK; + } + + public void setState(BlockerState state){this.state = state;} + + public void update(){ + if (state == BlockerState.BLOCK){ + blocker.setPositionResult(BLOCKER_BLOCK); + } + else{ + blocker.setPositionResult(BLOCKER_OUTTAKE); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java new file mode 100644 index 0000000..f7372a6 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/HoodSubsystem.java @@ -0,0 +1,38 @@ +package org.firstinspires.ftc.teamcode.subsystems; + +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_CLOSE; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_FAR; +import static org.firstinspires.ftc.teamcode.PestoFTCConfig.HOOD_MID; + +import com.shprobotics.pestocore.hardware.CortexLinkedServo; +import com.shprobotics.pestocore.processing.MotorCortex; + +public class HoodSubsystem { + private CortexLinkedServo hood; + private HoodState state; + public enum HoodState{ + CLOSE, + MID, + FAR + } + + public HoodSubsystem(){ + hood = MotorCortex.getServo("hood"); + state = HoodState.CLOSE; + } + + public void setState(HoodState state){this.state = state;} + + public HoodState getState(){return this.state;} + public void update(){ + if(state == HoodState.CLOSE){ + hood.setPositionResult(HOOD_CLOSE); + } + else if(state == HoodState.MID){ + hood.setPositionResult(HOOD_MID); + } + else{ + hood.setPositionResult(HOOD_FAR); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java new file mode 100644 index 0000000..0da670f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java @@ -0,0 +1,64 @@ +package org.firstinspires.ftc.teamcode.subsystems; + +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.shprobotics.pestocore.hardware.CortexLinkedMotor; +import com.shprobotics.pestocore.processing.MotorCortex; + +public class IntakeOuttakeSubsystem { + private final CortexLinkedMotor theGoatorRight; + private final CortexLinkedMotor theGoatorLeft; + private final CortexLinkedMotor shooter; + private IntakeOuttakeState state; + + public enum IntakeOuttakeState{ + REJECT, + NEUTRAL, + PREREV, + REV, + INTAKE, + OUTTAKE + } + + public IntakeOuttakeSubsystem(){ + theGoatorRight = MotorCortex.getMotor("theGoatorRight"); + theGoatorRight.setDirection(DcMotorSimple.Direction.REVERSE); + theGoatorLeft = MotorCortex.getMotor("theGoatorLeft"); + shooter = MotorCortex.getMotor("shooter"); + state = IntakeOuttakeState.NEUTRAL; + } + + public void setState(IntakeOuttakeState state){this.state = state;} + + public void update(){ + if (state == IntakeOuttakeState.INTAKE){ + theGoatorRight.setPowerResult(1); + theGoatorLeft.setPowerResult(1); + shooter.setPowerResult(0); + } + else if (state == IntakeOuttakeState.REJECT){ + theGoatorRight.setPowerResult(-1); + theGoatorLeft.setPowerResult(-1); + shooter.setPowerResult(-1); + } + else if (state == IntakeOuttakeState.PREREV){ + theGoatorRight.setPowerResult(0); + theGoatorLeft.setPowerResult(0); + shooter.setPowerResult(0.5); + } + else if (state == IntakeOuttakeState.REV){ + theGoatorRight.setPowerResult(0); + theGoatorLeft.setPowerResult(0); + shooter.setPowerResult(1); + } + else if (state == IntakeOuttakeState.OUTTAKE){ + theGoatorRight.setPowerResult(1); + theGoatorLeft.setPowerResult(1); + shooter.setPowerResult(1); + } + else{ + theGoatorRight.setPowerResult(0); + theGoatorLeft.setPowerResult(0); + shooter.setPowerResult(0); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java new file mode 100644 index 0000000..6e8c821 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java @@ -0,0 +1,145 @@ +package org.firstinspires.ftc.teamcode.teleops; + +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.shprobotics.pestocore.devices.GamepadKey; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.BlockerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeOuttakeSubsystem; + +@TeleOp(name = "CP?") +public class Drive extends BaseRobot { + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = false; + + super.initialize(); + +// boolean rotationLocked = false; +// double angle = 0.0; + + waitForStart(); + + tracker.reset(); + + while (opModeIsActive() && !isStopRequested()) { + FrontalLobe.update(); + MotorCortex.update(); + gamepadInterface1.update(); + tracker.update(); + +// if (gamepad1.x) { +// tracker.reset(); +// teleOpController.resetIMU(); +// } + +// if (gamepadInterface1.isKeyDown(GamepadKey.RIGHT_BUMPER)) { +// rotationLocked = !rotationLocked; +// +// double[] angles = new double[]{0.0, Math.PI / 2, Math.PI, 3 * Math.PI / 2}; +// double bestDist = Double.POSITIVE_INFINITY; +// +// for (double x : angles) { +// double dist = Math.abs(x - MathUtils.normalizeAngle(tracker.getCurrentPosition().getHeadingRadians(), x)); +// +// if (dist < bestDist) { +// bestDist = dist; +// angle = x; +// } +// } +// } + +// if (rotationLocked) { +// double correction = angle - MathUtils.normalizeAngle(tracker.getCurrentPosition().getHeadingRadians(), angle); +// correction = correction * -0.6; // 0.6 == headingKP +// correction += Math.signum(correction) * PestoFTCConfig.STATIC_DRIVE; +// +// teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, correction); +// } else { +// teleOpController.driveFieldCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); +// } + + teleOpController.driveRobotCentric(-gamepad1.left_stick_y, gamepad1.left_stick_x, gamepad1.right_stick_x); + + boolean intaking = gamepad1.right_trigger > 0.05; + boolean outtaking = !intaking && gamepad1.left_trigger > 0.05; + boolean rejecting = !intaking && !outtaking && gamepad1.a; + boolean neutralizing = !intaking && !outtaking && !rejecting; + + + if (!outtaking && state == RobotState.OUTTAKE) { + FrontalLobe.removeMacros("outtake"); + } + + if (intaking) { + state = RobotState.INTAKE; + + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.INTAKE); + blockerSubsystem.setState(BlockerSubsystem.BlockerState.BLOCK); + } + + if (outtaking && state != RobotState.OUTTAKE) { + state = RobotState.OUTTAKE; + + FrontalLobe.useMacro("outtake"); + } + + if (rejecting) { + state = RobotState.REJECT; + + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.REJECT); + blockerSubsystem.setState(BlockerSubsystem.BlockerState.NEUTRAL); + } + + if (neutralizing) { + state = RobotState.NEUTRAL; + + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.NEUTRAL); + blockerSubsystem.setState(BlockerSubsystem.BlockerState.BLOCK); + } + + + +// // Nice little LED display on the gamepad + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) + gamepad1.setLedColor(0, 255, 0, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) + gamepad1.setLedColor(0, 0, 255, Integer.MAX_VALUE); + + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) + gamepad1.setLedColor(255, 0, 0, Integer.MAX_VALUE); + +// // Cycle hood modes + if (gamepadInterface1.isKeyDown(GamepadKey.TOUCHPAD)) { + if (hoodSubsystem.getState() == HoodSubsystem.HoodState.CLOSE) { + hoodSubsystem.setState(HoodSubsystem.HoodState.MID); + + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.MID) { + hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); + + } else if (hoodSubsystem.getState() == HoodSubsystem.HoodState.FAR) { + hoodSubsystem.setState(HoodSubsystem.HoodState.CLOSE); + } + } + + + blockerSubsystem.update(); + hoodSubsystem.update(); + intakeOuttakeSubsystem.update(); + + +// telemetry.addData("x", tracker.getCurrentPosition().getX()); +// telemetry.addData("y", tracker.getCurrentPosition().getY()); +// telemetry.addData("r", tracker.getCurrentPosition().getHeadingRadians()); +// telemetry.addData("turret", turretSubsystem.getPosition()); +// telemetry.addData("shooter", outtakeSubsystem.getRPM()); +// telemetry.addData("target", outtakeSubsystem.getTargetRPM()); +// telemetry.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java new file mode 100644 index 0000000..8ca475a --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java @@ -0,0 +1,29 @@ +package org.firstinspires.ftc.teamcode.teleops; + +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.shprobotics.pestocore.devices.GamepadKey; +import com.shprobotics.pestocore.processing.FrontalLobe; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.BlockerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeOuttakeSubsystem; + +@Autonomous(name = "move?!") +public class Move extends BaseRobot { + @Override + public void runOpMode() { + PestoFTCConfig.initializePinpoint = false; + + super.initialize(); + + waitForStart(); + + mecanumController.drive(0.5, 0, 0); + sleep(500); + mecanumController.drive(0, 0, 0); + } +} diff --git a/local.properties b/local.properties index eb5652b..59887c7 100644 --- a/local.properties +++ b/local.properties @@ -4,5 +4,5 @@ # Location of the SDK. This is only used by Gradle. # For customization when using a Version Control System, please read the # header note. -#Wed Nov 19 15:52:17 PST 2025 -sdk.dir=/Users/william/Library/Android/android-sdk +#Thu Jan 22 19:34:16 PST 2026 +sdk.dir=C\:\\Users\\seank\\AppData\\Local\\Android\\Sdk From 4d4f4463066a90eb534052c52e0df1ed505f5901 Mon Sep 17 00:00:00 2001 From: skurian27 <122177586+skurian27@users.noreply.github.com> Date: Fri, 23 Jan 2026 18:24:33 -0800 Subject: [PATCH 21/25] ughghgh --- .../java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java | 6 +++--- .../java/org/firstinspires/ftc/teamcode/teleops/Drive.java | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index eaf3a4f..7eb56e4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -115,9 +115,9 @@ public static void initialize(HardwareMap hardwareMap) { ODOMETRY_TICKS_PER_INCH, 0.0, 0.0, - "left", - "center", - "right", + "backRight", + "frontRight", + "backLeft", DcMotorSimple.Direction.FORWARD, DcMotorSimple.Direction.FORWARD, DcMotorSimple.Direction.FORWARD diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java index 6e8c821..23c1b99 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java @@ -24,7 +24,7 @@ public void runOpMode() { waitForStart(); - tracker.reset(); + tracker.reset(); while (opModeIsActive() && !isStopRequested()) { FrontalLobe.update(); From 69b70f58b431d3f8df00a414bfffb2862c6d230d Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Fri, 23 Jan 2026 18:31:36 -0800 Subject: [PATCH 22/25] new code --- .../java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java | 5 ++--- .../org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java | 4 +--- 2 files changed, 3 insertions(+), 6 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 7eb56e4..3d4b67b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -7,7 +7,6 @@ import com.shprobotics.pestocore.algorithms.Constants; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; -import com.shprobotics.pestocore.drivebases.trackers.DeterministicTracker; import com.shprobotics.pestocore.drivebases.trackers.ThreeWheelOdometryTracker; import com.shprobotics.pestocore.processing.Cerebrum; import com.shprobotics.pestocore.processing.ConfigInterface; @@ -113,8 +112,8 @@ public static void initialize(HardwareMap hardwareMap) { ODOMETRY_TICKS_PER_INCH, ODOMETRY_TICKS_PER_INCH, ODOMETRY_TICKS_PER_INCH, - 0.0, - 0.0, + -2.0, + 5.0, "backRight", "frontRight", "backLeft", diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java index 75a90b5..4ce0193 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/BaseRobot.java @@ -1,15 +1,12 @@ package org.firstinspires.ftc.teamcode.subsystems; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import com.qualcomm.robotcore.hardware.DcMotor; import com.shprobotics.pestocore.devices.GamepadInterface; import com.shprobotics.pestocore.drivebases.controllers.MecanumController; import com.shprobotics.pestocore.drivebases.controllers.TeleOpController; import com.shprobotics.pestocore.drivebases.trackers.DeterministicTracker; import com.shprobotics.pestocore.processing.FrontalLobe; -import org.firstinspires.ftc.teamcode.PestoFTCConfig; - public class BaseRobot extends LinearOpMode { public MecanumController mecanumController; public TeleOpController teleOpController; @@ -40,6 +37,7 @@ public void initialize() { teleOpController = FrontalLobe.teleOpController; tracker = FrontalLobe.tracker; + tracker.reset(); blockerSubsystem = new BlockerSubsystem(); hoodSubsystem = new HoodSubsystem(); From ec5d266bcfa6a3e37ed79e7ec956d166d1313e30 Mon Sep 17 00:00:00 2001 From: skurian27 <122177586+skurian27@users.noreply.github.com> Date: Fri, 23 Jan 2026 18:50:35 -0800 Subject: [PATCH 23/25] tuned drive --- .../org/firstinspires/ftc/teamcode/PestoFTCConfig.java | 2 +- .../org/firstinspires/ftc/teamcode/teleops/Drive.java | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index 3d4b67b..f943032 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -113,7 +113,7 @@ public static void initialize(HardwareMap hardwareMap) { ODOMETRY_TICKS_PER_INCH, ODOMETRY_TICKS_PER_INCH, -2.0, - 5.0, + 4.9299, "backRight", "frontRight", "backLeft", diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java index 23c1b99..49593f1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java @@ -32,10 +32,10 @@ public void runOpMode() { gamepadInterface1.update(); tracker.update(); -// if (gamepad1.x) { -// tracker.reset(); -// teleOpController.resetIMU(); -// } + if (gamepad1.b) { + tracker.reset(); + teleOpController.resetIMU(); + } // if (gamepadInterface1.isKeyDown(GamepadKey.RIGHT_BUMPER)) { // rotationLocked = !rotationLocked; From 5306f69718e51fa321611322cae65a43f718ff21 Mon Sep 17 00:00:00 2001 From: skurian27 <122177586+skurian27@users.noreply.github.com> Date: Sat, 24 Jan 2026 12:40:48 -0800 Subject: [PATCH 24/25] wrote first auto kinda --- .../subsystems/IntakeOuttakeSubsystem.java | 16 ++++---- .../ftc/teamcode/teleops/Move.java | 2 +- .../ftc/teamcode/teleops/Trust.java | 40 +++++++++++++++++++ 3 files changed, 49 insertions(+), 9 deletions(-) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Trust.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java index 0da670f..e600f5b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/IntakeOuttakeSubsystem.java @@ -6,7 +6,7 @@ public class IntakeOuttakeSubsystem { private final CortexLinkedMotor theGoatorRight; - private final CortexLinkedMotor theGoatorLeft; + //private final CortexLinkedMotor theGoatorLeft; private final CortexLinkedMotor shooter; private IntakeOuttakeState state; @@ -22,7 +22,7 @@ public enum IntakeOuttakeState{ public IntakeOuttakeSubsystem(){ theGoatorRight = MotorCortex.getMotor("theGoatorRight"); theGoatorRight.setDirection(DcMotorSimple.Direction.REVERSE); - theGoatorLeft = MotorCortex.getMotor("theGoatorLeft"); + //theGoatorLeft = MotorCortex.getMotor("theGoatorLeft"); shooter = MotorCortex.getMotor("shooter"); state = IntakeOuttakeState.NEUTRAL; } @@ -32,32 +32,32 @@ public IntakeOuttakeSubsystem(){ public void update(){ if (state == IntakeOuttakeState.INTAKE){ theGoatorRight.setPowerResult(1); - theGoatorLeft.setPowerResult(1); + // theGoatorLeft.setPowerResult(1); shooter.setPowerResult(0); } else if (state == IntakeOuttakeState.REJECT){ theGoatorRight.setPowerResult(-1); - theGoatorLeft.setPowerResult(-1); + // theGoatorLeft.setPowerResult(-1); shooter.setPowerResult(-1); } else if (state == IntakeOuttakeState.PREREV){ theGoatorRight.setPowerResult(0); - theGoatorLeft.setPowerResult(0); + // theGoatorLeft.setPowerResult(0); shooter.setPowerResult(0.5); } else if (state == IntakeOuttakeState.REV){ theGoatorRight.setPowerResult(0); - theGoatorLeft.setPowerResult(0); + // theGoatorLeft.setPowerResult(0); shooter.setPowerResult(1); } else if (state == IntakeOuttakeState.OUTTAKE){ theGoatorRight.setPowerResult(1); - theGoatorLeft.setPowerResult(1); + //theGoatorLeft.setPowerResult(1); shooter.setPowerResult(1); } else{ theGoatorRight.setPowerResult(0); - theGoatorLeft.setPowerResult(0); + // theGoatorLeft.setPowerResult(0); shooter.setPowerResult(0); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java index 8ca475a..575f9fe 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Move.java @@ -22,7 +22,7 @@ public void runOpMode() { waitForStart(); - mecanumController.drive(0.5, 0, 0); + mecanumController.drive(0.65, 0, 0); sleep(500); mecanumController.drive(0, 0, 0); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Trust.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Trust.java new file mode 100644 index 0000000..536bf8d --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Trust.java @@ -0,0 +1,40 @@ +package org.firstinspires.ftc.teamcode.teleops; + +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.shprobotics.pestocore.processing.MotorCortex; + +import org.firstinspires.ftc.teamcode.PestoFTCConfig; +import org.firstinspires.ftc.teamcode.subsystems.BaseRobot; +import org.firstinspires.ftc.teamcode.subsystems.BlockerSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.HoodSubsystem; +import org.firstinspires.ftc.teamcode.subsystems.IntakeOuttakeSubsystem; + +@Autonomous +public class Trust extends BaseRobot { + @Override + public void runOpMode(){ + PestoFTCConfig.initializePinpoint = false; + super.initialize(); + waitForStart(); + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.PREREV); + blockerSubsystem.setState(BlockerSubsystem.BlockerState.BLOCK); + hoodSubsystem.setState(HoodSubsystem.HoodState.FAR); + double start = System.nanoTime()/1E9; + while(opModeIsActive() && !isStopRequested() && System.nanoTime()/1E9 - start < 15){ + if((System.nanoTime()/1E9) - start > 0.3 && (System.nanoTime()/1E9) - start < 2){ + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.REV); + } + else if((System.nanoTime()/1E9) - start > 2){ + intakeOuttakeSubsystem.setState(IntakeOuttakeSubsystem.IntakeOuttakeState.OUTTAKE); + blockerSubsystem.setState(BlockerSubsystem.BlockerState.NEUTRAL); + } + MotorCortex.update(); + intakeOuttakeSubsystem.update(); + blockerSubsystem.update(); + hoodSubsystem.update(); + } + } + + +} + From 48b71af66b755ca75826ba1c6b5f7f6a01d533ec Mon Sep 17 00:00:00 2001 From: william27b <122133075+william27b@users.noreply.github.com> Date: Sat, 24 Jan 2026 12:43:57 -0800 Subject: [PATCH 25/25] I am speed --- .../ftc/teamcode/PestoFTCConfig.java | 16 ++++++++++++++++ .../ftc/teamcode/teleops/Drive.java | 3 +++ local.properties | 4 ++-- 3 files changed, 21 insertions(+), 2 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java index f943032..d1b831d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PestoFTCConfig.java @@ -129,6 +129,22 @@ public static void initialize(HardwareMap hardwareMap) { FrontalLobe.teleOpController = teleOpController; teleOpController.useTrackerIMU(tracker); + // TODO: set speed controller lambda + // b is circle + // a is cross + // x is square + // y is triangle + // left_bumper + // right_bumper + // left_trigger > 0.05 + // right_trigger > 0.05 + // dpad_down + // dpad_left + // dpad_right + // dpad_up + // touchpad + teleOpController.setSpeedController(gamepad -> gamepad.x ? 0.6 : 1.0); + FrontalLobe.driveController = mecanumController; Constants.mass = mass; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java index 49593f1..f68e4a1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleops/Drive.java @@ -32,6 +32,9 @@ public void runOpMode() { gamepadInterface1.update(); tracker.update(); + // use lambda + teleOpController.updateSpeed(gamepad1); + if (gamepad1.b) { tracker.reset(); teleOpController.resetIMU(); diff --git a/local.properties b/local.properties index 59887c7..f9b6351 100644 --- a/local.properties +++ b/local.properties @@ -4,5 +4,5 @@ # Location of the SDK. This is only used by Gradle. # For customization when using a Version Control System, please read the # header note. -#Thu Jan 22 19:34:16 PST 2026 -sdk.dir=C\:\\Users\\seank\\AppData\\Local\\Android\\Sdk +#Fri Jan 23 18:13:04 PST 2026 +sdk.dir=/Users/william/Library/Android/android-sdk