From a81461e343ffe77aad20f5e40904bf123e067fae Mon Sep 17 00:00:00 2001 From: Ishan1522 Date: Fri, 15 Nov 2024 17:55:39 -0500 Subject: [PATCH 01/13] maybe it will work --- src/main/java/frc/robot/BuildConstants.java | 20 +-- .../frc/robot/extras/util/JoystickUtil.java | 72 +++++++++++ .../frc/robot/subsystems/intake/Intake.java | 49 ++++++++ .../subsystems/intake/IntakeInterface.java | 39 ++++++ .../subsystems/intake/PhysicalIntake.java | 119 ++++++++++++++++++ .../subsystems/intake/SimulatedIntake.java | 60 +++++++++ 6 files changed, 350 insertions(+), 9 deletions(-) create mode 100644 src/main/java/frc/robot/extras/util/JoystickUtil.java create mode 100644 src/main/java/frc/robot/subsystems/intake/Intake.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeInterface.java create mode 100644 src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java create mode 100644 src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index de35250..cea2cd0 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -1,17 +1,19 @@ package frc.robot; -/** Automatically generated file containing build version information. */ +/** + * Automatically generated file containing build version information. + */ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "4829-BaseRobotCode"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 15; - public static final String GIT_SHA = "f6cf5383d95d1116029cbb69e2db020295f5c2bf"; - public static final String GIT_DATE = "2024-11-09 19:29:39 EST"; - public static final String GIT_BRANCH = "actual-unit-tests"; - public static final String BUILD_DATE = "2024-11-09 19:50:39 EST"; - public static final long BUILD_UNIX_TIME = 1731199839115L; - public static final int DIRTY = 1; + public static final int GIT_REVISION = 9; + public static final String GIT_SHA = "489425d396236751b7dfe7735b944f8b36beac20"; + public static final String GIT_DATE = "2024-11-10 12:24:24 EST"; + public static final String GIT_BRANCH = "ExamplesYay"; + public static final String BUILD_DATE = "2024-11-15 17:54:44 EST"; + public static final long BUILD_UNIX_TIME = 1731711284284L; + public static final int DIRTY = 0; - private BuildConstants() {} + private BuildConstants(){} } diff --git a/src/main/java/frc/robot/extras/util/JoystickUtil.java b/src/main/java/frc/robot/extras/util/JoystickUtil.java new file mode 100644 index 0000000..3f51dd3 --- /dev/null +++ b/src/main/java/frc/robot/extras/util/JoystickUtil.java @@ -0,0 +1,72 @@ +package frc.robot.extras.util; + +import frc.robot.Constants.HardwareConstants; +import java.util.function.DoubleSupplier; + +public class Util { + + /** + * Deadbands a value to 0 + * + * @param value Value to input + * @param deadband If the the input is within this value, the function will return 0. + * @return 0.0 if the value is within specified deadband range + */ + private static double deadband(double value, double deadband) { + if (Math.abs(value) > deadband) { + if (value > 0.0) { + return (value - deadband) / (1.0 - deadband); + } else { + return (value + deadband) / (1.0 - deadband); + } + } else { + return 0.0; + } + } + + /** + * Function to modify a singular joystick axis. + * + * @param supplierValue Supplies a double, usually by a joystick. + * @param exponent Exponent to raise the supplied value to. + * @return Returns the modified value. + */ + public static double modifyAxis(DoubleSupplier supplierValue, int exponent) { + double value = supplierValue.getAsDouble(); + + // Deadband + value = deadband(value, HardwareConstants.DEADBAND_VALUE); + + // Raise value to specified exponent + value = Math.copySign(Math.pow(value, exponent), value); + + return value; + } + + /** + * Converts the two axis coordinates to polar to get both the angle and radius, so they can work + * in a double[] list. + * + * @param xJoystick The supplied input of the xJoystick. + * @param yJoystick The supplied input of the yJoystick. + * @param exponent The exponent to raise the supplied value to. + * @return The modified axises of both joysticks in polar form. + */ + public static double[] modifyAxisPolar( + DoubleSupplier xJoystick, DoubleSupplier yJoystick, int exponent) { + double xInput = deadband(xJoystick.getAsDouble(), HardwareConstants.DEADBAND_VALUE); + double yInput = deadband(yJoystick.getAsDouble(), HardwareConstants.DEADBAND_VALUE); + if (Math.abs(xInput) > 0 && Math.abs(yInput) > 0) { + double theta = Math.atan(xInput / yInput); + double hypotenuse = Math.sqrt(xInput * xInput + yInput * yInput); + double raisedHypotenuse = Math.pow(hypotenuse, exponent); + xInput = Math.copySign(Math.sin(theta) * raisedHypotenuse, xInput); + yInput = Math.copySign(Math.cos(theta) * raisedHypotenuse, yInput); + return new double[] {xInput, yInput}; + } + return new double[] { + Math.copySign(Math.pow(xInput, exponent), xInput), + Math.copySign(Math.pow(yInput, exponent), yInput) + }; + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.java b/src/main/java/frc/robot/subsystems/intake/Intake.java new file mode 100644 index 0000000..1936b87 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/Intake.java @@ -0,0 +1,49 @@ +package frc.robot.subsystems.intake; + +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.Logger; + +public class Intake extends SubsystemBase { + private IntakeInterface io; + private IntakeInputsAutoLogged inputs = new IntakeInputsAutoLogged(); + + public Intake(IntakeInterface io) { + this.io = io; + } + + /** + * sets the angle of the pivot in degrees + * + * @param angle desired angle in degrees + */ + public void setPivotAngle(double angle) { + double angleRots = Units.degreesToRotations(angle); + io.setPivotPosition(angleRots); + Logger.recordOutput("OTBIntake/Pivot", angleRots); + } + + /** + * Sets the speed of the intake rollers + * + * @param speed intake roller speed (-1.0 to 1.0) + */ + public void setIntakeSpeed(double speed) { + io.setIntakeSpeed(speed); + Logger.recordOutput("OTBIntake/Intake", speed); + } + + public void setPivotSpeed(double speed) { + io.setPivotSpeed(speed); + } + + public void getPivotPosition() { + io.getPivotPosition(); + } + + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("OTBIntake", inputs); + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java b/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java new file mode 100644 index 0000000..5fb35da --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java @@ -0,0 +1,39 @@ +package frc.robot.subsystems.intake; + +import org.littletonrobotics.junction.AutoLog; + +public interface IntakeInterface { + @AutoLog + public static class IntakeInputs { + public boolean isConnected = true; + + // intake motor + public double intakeVelocity = 0.0; + public double intakeTemp = 0.0; + public double intakeAppliedVolts = 0.0; + public double intakeCurrentAmps = 0.0; + + // pivot + public double pivotPosition = 0.0; + public double pivotVelocity = 0.0; + public double pivotTemp = 0.0; + public double pivotAppliedVolts = 0.0; + public double pivotCurrentAmps = 0.0; + } + + default void updateInputs(IntakeInputs inputs) {} + + default void setPivotPosition(double position) {} + + default void setIntakeSpeed(double speed) {} + + default double getIntakeSpeed() { + return 0.0; + } + + default void setPivotSpeed(double speed) {} + + default double getPivotPosition() { + return 0.0; + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java new file mode 100644 index 0000000..34f0110 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java @@ -0,0 +1,119 @@ +package frc.robot.subsystems.intake; + +import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.MotionMagicVoltage; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.FeedbackSensorSourceValue; +import com.ctre.phoenix6.signals.GravityTypeValue; +import com.ctre.phoenix6.signals.InvertedValue; +import com.ctre.phoenix6.signals.NeutralModeValue; +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; +import frc.robot.Constants.HardwareConstants; + +public class PhysicalIntake implements IntakeInterface { + private final TalonFX intakeMotor = new TalonFX(IntakeConstants.INTAKE_MOTOR_ID); + private final TalonFX leaderPivotMotor = new TalonFX(IntakeConstants.LEFT_INTAKE_PIVOT_MOTOR_ID); + private final TalonFX followerPivotMotor = + new TalonFX(IntakeConstants.RIGHT_INTAKE_PIVOT_MOTOR_ID); + + private final MotionMagicVoltage mmPositionRequest = new MotionMagicVoltage(0); + + private final StatusSignal intakeVelocity; + private final StatusSignal pivotPosition; + private final StatusSignal pivotVelocity; + + public PhysicalIntake() { + TalonFXConfiguration intakeConfig = new TalonFXConfiguration(); + + intakeConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; + intakeConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + intakeConfig.MotorOutput.DutyCycleNeutralDeadband = HardwareConstants.MIN_FALCON_DEADBAND; + + intakeConfig.CurrentLimits.StatorCurrentLimit = 0.0; + intakeConfig.CurrentLimits.StatorCurrentLimitEnable = false; + intakeConfig.CurrentLimits.SupplyCurrentLimit = 0.0; + intakeConfig.CurrentLimits.SupplyCurrentLimitEnable = false; + + intakeMotor.getConfigurator().apply(intakeConfig); + + TalonFXConfiguration pivotConfig = new TalonFXConfiguration(); + + pivotConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; + pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + pivotConfig.MotorOutput.DutyCycleNeutralDeadband = HardwareConstants.MIN_FALCON_DEADBAND; + + pivotConfig.CurrentLimits.StatorCurrentLimit = 0.0; + pivotConfig.CurrentLimits.StatorCurrentLimitEnable = false; + pivotConfig.CurrentLimits.SupplyCurrentLimit = 0.0; + pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = false; + + pivotConfig.Slot0.kP = 0.0; + pivotConfig.Slot0.kI = 0.0; + pivotConfig.Slot0.kD = 0.0; + pivotConfig.Slot0.kS = 0.0; + pivotConfig.Slot0.kV = 0.0; + pivotConfig.Slot0.kA = 0.0; + pivotConfig.Slot0.kG = 0.0; + pivotConfig.Slot0.GravityType = GravityTypeValue.Arm_Cosine; + + pivotConfig.MotionMagic.MotionMagicCruiseVelocity = 0.0; + pivotConfig.MotionMagic.MotionMagicAcceleration = 0.0; + + // pivotConfig.Feedback.FeedbackRotorOffset = 0.0; + // pivotConfig.Feedback.RotorToSensorRatio = 0.0; + pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = false; + pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = 0.0; + pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitEnable = false; + pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitThreshold = 0.0; + pivotConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RotorSensor; + + leaderPivotMotor.setPosition(0); + followerPivotMotor.setPosition(0); + + leaderPivotMotor.getConfigurator().apply(pivotConfig); + pivotConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + followerPivotMotor.getConfigurator().apply(pivotConfig); + + intakeVelocity = intakeMotor.getVelocity(); + pivotPosition = leaderPivotMotor.getRotorPosition(); + pivotVelocity = leaderPivotMotor.getVelocity(); + } + + @Override + public void updateInputs(IntakeInterfaceInputs inputs) { + inputs.intakeVelocity = intakeVelocity.getValueAsDouble(); + inputs.pivotPosition = pivotPosition.getValueAsDouble(); + inputs.pivotVelocity = pivotVelocity.getValueAsDouble(); + } + + @Override + public void setPivotPosition(double position) { + leaderPivotMotor.setControl(mmPositionRequest.withPosition(position)); + followerPivotMotor.setControl(mmPositionRequest.withPosition(position)); + } + + @Override + public void setPivotSpeed(double speed) { + leaderPivotMotor.set(speed); + followerPivotMotor.set(speed); + } + + @Override + public double getPivotPosition() { + leaderPivotMotor.getRotorPosition().refresh(); + return leaderPivotMotor.getRotorPosition().getValueAsDouble(); + } + + @Override + public void setIntakeSpeed(double speed) { + intakeMotor.set(speed); + } + + @Override + public double getIntakeSpeed() { + intakeMotor.getVelocity().refresh(); + return intakeMotor.getVelocity().getValueAsDouble(); + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java new file mode 100644 index 0000000..212e5ba --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java @@ -0,0 +1,60 @@ +package frc.robot.subsystems.intake; + +import edu.wpi.first.math.controller.ArmFeedforward; +import edu.wpi.first.math.controller.ProfiledPIDController; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints; +import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; + +public class SimulatedIntake implements IntakeInterface { + DCMotorSim intakeSim = new DCMotorSim(null, DCMotor.getFalcon500(1), 0); + SingleJointedArmSim pivotSim = + new SingleJointedArmSim( + DCMotor.getFalcon500(2), IntakeConstants.INTAKE_PIVOT_GEAR_RATIO, 0, 0, 0, 0, false, 0); + private final Constraints pivotConstraints = new Constraints(0, 0); + private final ProfiledPIDController pivotController = + new ProfiledPIDController(0, 0, 0, pivotConstraints); + + private final ArmFeedforward pivotFF = new ArmFeedforward(0, 0, 0, 0); + + private double intakeAppliedVolts = 0.0; + private double pivotAppliedVolts = 0.0; + + public SimulatedIntake(IntakeInputs inputs) { + intakeSim.update(0.02); + pivotSim.update(0.02); + + inputs.intakeVelocity = intakeSim.getAngularVelocityRadPerSec() / (Math.PI * 2); + inputs.intakeCurrentAmps = intakeSim.getCurrentDrawAmps(); + inputs.intakeAppliedVolts = intakeAppliedVolts; + + inputs.pivotPosition = pivotSim.getAngleRads() / (Math.PI * 2); + inputs.pivotVelocity = pivotSim.getVelocityRadPerSec() / (Math.PI * 2); + inputs.pivotAppliedVolts = pivotAppliedVolts; + inputs.pivotCurrentAmps = pivotSim.getCurrentDrawAmps(); + } + + @Override + public void setPivotPosition(double position) { + pivotSim.setInputVoltage( + pivotController.calculate(position, pivotSim.getAngleRads() / (Math.PI * 2)) + + pivotFF.calculate( + pivotController.getSetpoint().position, pivotController.getSetpoint().velocity)); + } + + @Override + public void setIntakeSpeed(double speed) { + intakeSim.setInputVoltage(speed); + } + + @Override + public double getIntakeSpeed() { + return intakeSim.getAngularVelocityRadPerSec() / (Math.PI * 2); + } + + @Override + public double getPivotPosition() { + return pivotSim.getAngleRads() / (Math.PI * 2); + } +} \ No newline at end of file From 9d9d7fdb13134e795a41b0517defa01a44a57728 Mon Sep 17 00:00:00 2001 From: Ishan1522 <36376931+NNLUliskey@users.noreply.github.com> Date: Mon, 18 Nov 2024 17:30:03 -0500 Subject: [PATCH 02/13] Added more intake stuff and made it finally build! --- src/main/java/frc/robot/BuildConstants.java | 12 ++-- .../frc/robot/extras/util/JoystickUtil.java | 10 +-- .../frc/robot/subsystems/intake/Intake.java | 29 ++------ .../subsystems/intake/IntakeConstants.java | 27 ++++++++ .../subsystems/intake/IntakeInterface.java | 29 ++++---- .../subsystems/intake/PhysicalIntake.java | 67 +------------------ .../subsystems/intake/SimulatedIntake.java | 37 ++-------- .../robot/subsystems/swerve/SwerveDrive.java | 2 +- .../swerve/odometryThread/OdometryThread.java | 7 +- ...{VisionIOReal.java => PhysicalVision.java} | 6 +- ...{VisionIOSim.java => SimulatedVision.java} | 0 .../frc/robot/subsystems/vision/Vision.java | 26 +++---- .../{VisionIO.java => VisionInterface.java} | 6 +- 13 files changed, 86 insertions(+), 172 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeConstants.java rename src/main/java/frc/robot/subsystems/vision/{VisionIOReal.java => PhysicalVision.java} (99%) rename src/main/java/frc/robot/subsystems/vision/{VisionIOSim.java => SimulatedVision.java} (100%) rename src/main/java/frc/robot/subsystems/vision/{VisionIO.java => VisionInterface.java} (88%) diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index cea2cd0..ad2a1e3 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -7,13 +7,13 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "4829-BaseRobotCode"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 9; - public static final String GIT_SHA = "489425d396236751b7dfe7735b944f8b36beac20"; - public static final String GIT_DATE = "2024-11-10 12:24:24 EST"; + public static final int GIT_REVISION = 10; + public static final String GIT_SHA = "a81461e343ffe77aad20f5e40904bf123e067fae"; + public static final String GIT_DATE = "2024-11-15 17:55:39 EST"; public static final String GIT_BRANCH = "ExamplesYay"; - public static final String BUILD_DATE = "2024-11-15 17:54:44 EST"; - public static final long BUILD_UNIX_TIME = 1731711284284L; - public static final int DIRTY = 0; + public static final String BUILD_DATE = "2024-11-18 17:29:09 EST"; + public static final long BUILD_UNIX_TIME = 1731968949047L; + public static final int DIRTY = 1; private BuildConstants(){} } diff --git a/src/main/java/frc/robot/extras/util/JoystickUtil.java b/src/main/java/frc/robot/extras/util/JoystickUtil.java index 3f51dd3..a9c2030 100644 --- a/src/main/java/frc/robot/extras/util/JoystickUtil.java +++ b/src/main/java/frc/robot/extras/util/JoystickUtil.java @@ -1,9 +1,9 @@ package frc.robot.extras.util; -import frc.robot.Constants.HardwareConstants; +import frc.robot.Constants.JoystickConstants; import java.util.function.DoubleSupplier; -public class Util { +public class JoystickUtil { /** * Deadbands a value to 0 @@ -35,7 +35,7 @@ public static double modifyAxis(DoubleSupplier supplierValue, int exponent) { double value = supplierValue.getAsDouble(); // Deadband - value = deadband(value, HardwareConstants.DEADBAND_VALUE); + value = deadband(value, JoystickConstants.DEADBAND_VALUE); // Raise value to specified exponent value = Math.copySign(Math.pow(value, exponent), value); @@ -54,8 +54,8 @@ public static double modifyAxis(DoubleSupplier supplierValue, int exponent) { */ public static double[] modifyAxisPolar( DoubleSupplier xJoystick, DoubleSupplier yJoystick, int exponent) { - double xInput = deadband(xJoystick.getAsDouble(), HardwareConstants.DEADBAND_VALUE); - double yInput = deadband(yJoystick.getAsDouble(), HardwareConstants.DEADBAND_VALUE); + double xInput = deadband(xJoystick.getAsDouble(), JoystickConstants.DEADBAND_VALUE); + double yInput = deadband(yJoystick.getAsDouble(), JoystickConstants.DEADBAND_VALUE); if (Math.abs(xInput) > 0 && Math.abs(yInput) > 0) { double theta = Math.atan(xInput / yInput); double hypotenuse = Math.sqrt(xInput * xInput + yInput * yInput); diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.java b/src/main/java/frc/robot/subsystems/intake/Intake.java index 1936b87..80bd0c2 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/intake/Intake.java @@ -5,22 +5,11 @@ import org.littletonrobotics.junction.Logger; public class Intake extends SubsystemBase { - private IntakeInterface io; + private IntakeInterface intakeInterface; private IntakeInputsAutoLogged inputs = new IntakeInputsAutoLogged(); - public Intake(IntakeInterface io) { - this.io = io; - } - - /** - * sets the angle of the pivot in degrees - * - * @param angle desired angle in degrees - */ - public void setPivotAngle(double angle) { - double angleRots = Units.degreesToRotations(angle); - io.setPivotPosition(angleRots); - Logger.recordOutput("OTBIntake/Pivot", angleRots); + public Intake(IntakeInterface intakeInterface) { + this.intakeInterface = intakeInterface; } /** @@ -29,21 +18,13 @@ public void setPivotAngle(double angle) { * @param speed intake roller speed (-1.0 to 1.0) */ public void setIntakeSpeed(double speed) { - io.setIntakeSpeed(speed); + intakeInterface.setIntakeSpeed(speed); Logger.recordOutput("OTBIntake/Intake", speed); } - public void setPivotSpeed(double speed) { - io.setPivotSpeed(speed); - } - - public void getPivotPosition() { - io.getPivotPosition(); - } - @Override public void periodic() { - io.updateInputs(inputs); + intakeInterface.updateInputs(inputs); Logger.processInputs("OTBIntake", inputs); } } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java new file mode 100644 index 0000000..9700cfe --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java @@ -0,0 +1,27 @@ +package frc.robot.subsystems.intake; + +// This cool file contains constants for our intake +public final class IntakeConstants { + public static final int INTAKE_MOTOR_ID = 0; + public static final int LEFT_INTAKE_PIVOT_MOTOR_ID = 62; + public static final int RIGHT_INTAKE_PIVOT_MOTOR_ID = 0 - 9; + + public static final int NOTE_SENSOR_ID = 0 - 9; + + public static final double INTAKE_PIVOT_GEAR_RATIO = 8.0; + + public static final double INTAKE_PIVOT_OUT = 0 - 9; + public static final double INTAKE_PIVOT_IN = 0 - 9; + + public static final double INTAKE_PIVOT_NEUTRAL_SPEED = 0.0; + + public static final double OUTTAKE_SPEED = 0 - 9; + public static final double INTAKE_SPEED = 0.8; + public static final double INTAKE_NEUTRAL_SPEED = 0.0; + public static final double FLAPPER_SPEED = 1.0; + + public static final double INTAKE_STATOR_LIMIT = 60; + public static final double INTAKE_SUPPLY_LIMIT = 40; + public static final boolean INTAKE_STATOR_ENABLE = true; + public static final boolean INTAKE_SUPPLY_ENABLE = true; +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java b/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java index 5fb35da..725f336 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java @@ -5,35 +5,32 @@ public interface IntakeInterface { @AutoLog public static class IntakeInputs { - public boolean isConnected = true; + public boolean isConnected = true; // // intake motor public double intakeVelocity = 0.0; public double intakeTemp = 0.0; public double intakeAppliedVolts = 0.0; public double intakeCurrentAmps = 0.0; - - // pivot - public double pivotPosition = 0.0; - public double pivotVelocity = 0.0; - public double pivotTemp = 0.0; - public double pivotAppliedVolts = 0.0; - public double pivotCurrentAmps = 0.0; } + /** + * Updates intake values + * @param inputs + */ default void updateInputs(IntakeInputs inputs) {} - default void setPivotPosition(double position) {} - + /** + * Sets the intake speed + * @param speed The intake speed value from -1 to 1 (negative being reversed) + */ default void setIntakeSpeed(double speed) {} + /** + * Gets the current speed of the intake + * @return Current velocity of the intake + */ default double getIntakeSpeed() { return 0.0; } - - default void setPivotSpeed(double speed) {} - - default double getPivotPosition() { - return 0.0; - } } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java index 34f0110..919a68c 100644 --- a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java @@ -14,15 +14,10 @@ public class PhysicalIntake implements IntakeInterface { private final TalonFX intakeMotor = new TalonFX(IntakeConstants.INTAKE_MOTOR_ID); - private final TalonFX leaderPivotMotor = new TalonFX(IntakeConstants.LEFT_INTAKE_PIVOT_MOTOR_ID); - private final TalonFX followerPivotMotor = - new TalonFX(IntakeConstants.RIGHT_INTAKE_PIVOT_MOTOR_ID); private final MotionMagicVoltage mmPositionRequest = new MotionMagicVoltage(0); private final StatusSignal intakeVelocity; - private final StatusSignal pivotPosition; - private final StatusSignal pivotVelocity; public PhysicalIntake() { TalonFXConfiguration intakeConfig = new TalonFXConfiguration(); @@ -38,72 +33,12 @@ public PhysicalIntake() { intakeMotor.getConfigurator().apply(intakeConfig); - TalonFXConfiguration pivotConfig = new TalonFXConfiguration(); - - pivotConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; - pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - pivotConfig.MotorOutput.DutyCycleNeutralDeadband = HardwareConstants.MIN_FALCON_DEADBAND; - - pivotConfig.CurrentLimits.StatorCurrentLimit = 0.0; - pivotConfig.CurrentLimits.StatorCurrentLimitEnable = false; - pivotConfig.CurrentLimits.SupplyCurrentLimit = 0.0; - pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = false; - - pivotConfig.Slot0.kP = 0.0; - pivotConfig.Slot0.kI = 0.0; - pivotConfig.Slot0.kD = 0.0; - pivotConfig.Slot0.kS = 0.0; - pivotConfig.Slot0.kV = 0.0; - pivotConfig.Slot0.kA = 0.0; - pivotConfig.Slot0.kG = 0.0; - pivotConfig.Slot0.GravityType = GravityTypeValue.Arm_Cosine; - - pivotConfig.MotionMagic.MotionMagicCruiseVelocity = 0.0; - pivotConfig.MotionMagic.MotionMagicAcceleration = 0.0; - - // pivotConfig.Feedback.FeedbackRotorOffset = 0.0; - // pivotConfig.Feedback.RotorToSensorRatio = 0.0; - pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = false; - pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = 0.0; - pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitEnable = false; - pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitThreshold = 0.0; - pivotConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RotorSensor; - - leaderPivotMotor.setPosition(0); - followerPivotMotor.setPosition(0); - - leaderPivotMotor.getConfigurator().apply(pivotConfig); - pivotConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - followerPivotMotor.getConfigurator().apply(pivotConfig); - intakeVelocity = intakeMotor.getVelocity(); - pivotPosition = leaderPivotMotor.getRotorPosition(); - pivotVelocity = leaderPivotMotor.getVelocity(); } @Override - public void updateInputs(IntakeInterfaceInputs inputs) { + public void updateInputs(IntakeInputs inputs) { inputs.intakeVelocity = intakeVelocity.getValueAsDouble(); - inputs.pivotPosition = pivotPosition.getValueAsDouble(); - inputs.pivotVelocity = pivotVelocity.getValueAsDouble(); - } - - @Override - public void setPivotPosition(double position) { - leaderPivotMotor.setControl(mmPositionRequest.withPosition(position)); - followerPivotMotor.setControl(mmPositionRequest.withPosition(position)); - } - - @Override - public void setPivotSpeed(double speed) { - leaderPivotMotor.set(speed); - followerPivotMotor.set(speed); - } - - @Override - public double getPivotPosition() { - leaderPivotMotor.getRotorPosition().refresh(); - return leaderPivotMotor.getRotorPosition().getValueAsDouble(); } @Override diff --git a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java index 212e5ba..ef43c72 100644 --- a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java @@ -6,41 +6,19 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints; import edu.wpi.first.wpilibj.simulation.DCMotorSim; import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; +import static edu.wpi.first.units.Units.*; + public class SimulatedIntake implements IntakeInterface { DCMotorSim intakeSim = new DCMotorSim(null, DCMotor.getFalcon500(1), 0); - SingleJointedArmSim pivotSim = - new SingleJointedArmSim( - DCMotor.getFalcon500(2), IntakeConstants.INTAKE_PIVOT_GEAR_RATIO, 0, 0, 0, 0, false, 0); - private final Constraints pivotConstraints = new Constraints(0, 0); - private final ProfiledPIDController pivotController = - new ProfiledPIDController(0, 0, 0, pivotConstraints); - - private final ArmFeedforward pivotFF = new ArmFeedforward(0, 0, 0, 0); - private double intakeAppliedVolts = 0.0; - private double pivotAppliedVolts = 0.0; public SimulatedIntake(IntakeInputs inputs) { intakeSim.update(0.02); - pivotSim.update(0.02); - - inputs.intakeVelocity = intakeSim.getAngularVelocityRadPerSec() / (Math.PI * 2); + + inputs.intakeVelocity = RadiansPerSecond.of(intakeSim.getAngularVelocityRadPerSec()).in(RotationsPerSecond); inputs.intakeCurrentAmps = intakeSim.getCurrentDrawAmps(); inputs.intakeAppliedVolts = intakeAppliedVolts; - - inputs.pivotPosition = pivotSim.getAngleRads() / (Math.PI * 2); - inputs.pivotVelocity = pivotSim.getVelocityRadPerSec() / (Math.PI * 2); - inputs.pivotAppliedVolts = pivotAppliedVolts; - inputs.pivotCurrentAmps = pivotSim.getCurrentDrawAmps(); - } - - @Override - public void setPivotPosition(double position) { - pivotSim.setInputVoltage( - pivotController.calculate(position, pivotSim.getAngleRads() / (Math.PI * 2)) - + pivotFF.calculate( - pivotController.getSetpoint().position, pivotController.getSetpoint().velocity)); } @Override @@ -50,11 +28,6 @@ public void setIntakeSpeed(double speed) { @Override public double getIntakeSpeed() { - return intakeSim.getAngularVelocityRadPerSec() / (Math.PI * 2); - } - - @Override - public double getPivotPosition() { - return pivotSim.getAngleRads() / (Math.PI * 2); + return RadiansPerSecond.of(intakeSim.getAngularVelocityRadPerSec()).in(RotationsPerSecond); } } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java b/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java index 740bb8b..5f0b642 100644 --- a/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java +++ b/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java @@ -18,8 +18,8 @@ import frc.robot.extras.util.DeviceCANBus; import frc.robot.extras.util.TimeUtil; import frc.robot.subsystems.swerve.SwerveConstants.DriveConstants; -import frc.robot.subsystems.swerve.gyroIO.GyroInputsAutoLogged; import frc.robot.subsystems.swerve.gyroIO.GyroInterface; +import frc.robot.subsystems.swerve.gyroIO.GyroInputsAutoLogged; import frc.robot.subsystems.swerve.moduleIO.ModuleInterface; import frc.robot.subsystems.swerve.odometryThread.OdometryThread; import frc.robot.subsystems.swerve.odometryThread.OdometryThreadInputsAutoLogged; diff --git a/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java b/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java index b65ad20..b15e05c 100644 --- a/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java +++ b/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java @@ -54,16 +54,17 @@ static OdometryThread createInstance(DeviceCANBus canBus) { registeredInputs.toArray(new OdometryDoubleInput[0]), registeredStatusSignals.toArray(new BaseStatusSignal[0])); case SIM -> new OdometryThreadSim(); - case REPLAY -> inputs -> {}; + //case REPLAY -> inputs -> {}; + default -> throw new IllegalArgumentException("Unexpected value: " + Robot.CURRENT_ROBOT_MODE); }; } @AutoLog - class OdometryThreadInputs { + public class OdometryThreadInputs { public double[] measurementTimeStamps = new double[0]; } - void updateInputs(OdometryThreadInputs inputs); + default void updateInputs(OdometryThreadInputs inputs) {} default void start() {} diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOReal.java b/src/main/java/frc/robot/subsystems/vision/PhysicalVision.java similarity index 99% rename from src/main/java/frc/robot/subsystems/vision/VisionIOReal.java rename to src/main/java/frc/robot/subsystems/vision/PhysicalVision.java index aa4405d..12f4641 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOReal.java +++ b/src/main/java/frc/robot/subsystems/vision/PhysicalVision.java @@ -14,7 +14,7 @@ import java.util.concurrent.TimeUnit; import java.util.concurrent.atomic.AtomicBoolean; -public class VisionIOReal implements VisionIO { +public class PhysicalVision implements VisionInterface { private Pose2d lastSeenPose = new Pose2d(); private double headingDegrees = 0; @@ -28,7 +28,7 @@ public class VisionIOReal implements VisionIO { */ private PoseEstimate[] limelightEstimates; - public VisionIOReal() { + public PhysicalVision() { limelightEstimates = new PoseEstimate[3]; for (int limelightNumber = 0; limelightNumber < limelightEstimates.length; limelightNumber++) { limelightThreads.put(limelightNumber, new AtomicBoolean(true)); @@ -37,7 +37,7 @@ public VisionIOReal() { } @Override - public void updateInputs(VisionIOInputs inputs) { + public void updateInputs(VisionInputs inputs) { inputs.camerasAmount = limelightEstimates.length; inputs.cameraConnected = true; diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOSim.java b/src/main/java/frc/robot/subsystems/vision/SimulatedVision.java similarity index 100% rename from src/main/java/frc/robot/subsystems/vision/VisionIOSim.java rename to src/main/java/frc/robot/subsystems/vision/SimulatedVision.java diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 72a4df2..493763d 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -6,49 +6,49 @@ import org.littletonrobotics.junction.Logger; public class Vision extends SubsystemBase { - private final VisionIO visionIO; - private final VisionIOInputsAutoLogged inputs = new VisionIOInputsAutoLogged(); + private final VisionInterface visionInterface; + private final VisionInputsAutoLogged inputs = new VisionInputsAutoLogged(); - public Vision(VisionIO visionIO) { + public Vision(VisionInterface visionInterface) { // Initializing Fields - this.visionIO = visionIO; + this.visionInterface = visionInterface; } @Override public void periodic() { // Updates limelight inputs - visionIO.updateInputs(inputs); - Logger.processInputs(visionIO.getLimelightName(0), inputs); + visionInterface.updateInputs(inputs); + Logger.processInputs(visionInterface.getLimelightName(0), inputs); } // Add methods to support DriveCommand public int getNumberOfAprilTags(int limelightNumber) { - return visionIO.getNumberOfAprilTags(limelightNumber); + return visionInterface.getNumberOfAprilTags(limelightNumber); } public double getLimelightAprilTagDistance(int limelightNumber) { - return visionIO.getLimelightAprilTagDistance(limelightNumber); + return visionInterface.getLimelightAprilTagDistance(limelightNumber); } public double getTimeStampSeconds(int limelightNumber) { - return visionIO.getTimeStampSeconds(limelightNumber); + return visionInterface.getTimeStampSeconds(limelightNumber); } public double getLatencySeconds(int limelightNumber) { - return visionIO.getLatencySeconds(limelightNumber); + return visionInterface.getLatencySeconds(limelightNumber); } public void setHeadingInfo(double headingDegrees, double headingRateDegrees) { - visionIO.setHeadingInfo(headingDegrees, headingRateDegrees); + visionInterface.setHeadingInfo(headingDegrees, headingRateDegrees); } @AutoLogOutput(key = "Vision/Has Targets") public boolean canSeeAprilTags(int limelightNumber) { - return visionIO.canSeeAprilTags( + return visionInterface.canSeeAprilTags( limelightNumber); // Assuming we're checking the shooter limelight } public Pose2d getPoseFromAprilTags(int limelightNumber) { - return visionIO.getPoseFromAprilTags(limelightNumber); + return visionInterface.getPoseFromAprilTags(limelightNumber); } } diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIO.java b/src/main/java/frc/robot/subsystems/vision/VisionInterface.java similarity index 88% rename from src/main/java/frc/robot/subsystems/vision/VisionIO.java rename to src/main/java/frc/robot/subsystems/vision/VisionInterface.java index ad9c125..8458163 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIO.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionInterface.java @@ -3,9 +3,9 @@ import edu.wpi.first.math.geometry.Pose2d; import org.littletonrobotics.junction.AutoLog; -public interface VisionIO { +public interface VisionInterface { @AutoLog - class VisionIOInputs { + class VisionInputs { public boolean cameraConnected = false; public double latency = 0.0; public double fiducialMarksID = 0.0; @@ -14,7 +14,7 @@ class VisionIOInputs { public int targetsCount = 0; } - void updateInputs(VisionIOInputs inputs); + void updateInputs(VisionInputs inputs); String getLimelightName(int limelightNumber); From 8d44ff46c1d6368e7110dd2cfe3db73c86389ed5 Mon Sep 17 00:00:00 2001 From: Ishan1522 <36376931+NNLUliskey@users.noreply.github.com> Date: Mon, 18 Nov 2024 17:46:04 -0500 Subject: [PATCH 03/13] intake commands --- .../frc/robot/commands/intake/Outtake.java | 36 ++++++++++++++++++ .../robot/commands/intake/RegularIntake.java | 37 +++++++++++++++++++ 2 files changed, 73 insertions(+) create mode 100644 src/main/java/frc/robot/commands/intake/Outtake.java create mode 100644 src/main/java/frc/robot/commands/intake/RegularIntake.java diff --git a/src/main/java/frc/robot/commands/intake/Outtake.java b/src/main/java/frc/robot/commands/intake/Outtake.java new file mode 100644 index 0000000..704381f --- /dev/null +++ b/src/main/java/frc/robot/commands/intake/Outtake.java @@ -0,0 +1,36 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands.intake; + +import edu.wpi.first.wpilibj2.command.Command; + +public class Outtake extends Command { + private final Intake intakeSubsystem; + + public Outtake(Intake intake) { + this.intakeSubsystem = intake; + addRequirements(this.intakeSubsystem); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + intakeSubsystem.setIntakeSpeed(-1); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc/robot/commands/intake/RegularIntake.java b/src/main/java/frc/robot/commands/intake/RegularIntake.java new file mode 100644 index 0000000..2dcac9f --- /dev/null +++ b/src/main/java/frc/robot/commands/intake/RegularIntake.java @@ -0,0 +1,37 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands.intake; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.subsystems.intake.Intake; + +public class RegularIntake extends Command { + private final Intake intakeSubsystem; + + public RegularIntake(Intake intake) { + this.intakeSubsystem = intake; + addRequirements(this.intakeSubsystem); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + intakeSubsystem.setIntakeSpeed(1); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} From c9b53f77ffe5d9294a84e77fe471839907a42770 Mon Sep 17 00:00:00 2001 From: Ishan1522 Date: Wed, 20 Nov 2024 17:53:15 -0500 Subject: [PATCH 04/13] Cool elevator stuff --- src/main/java/frc/robot/BuildConstants.java | 10 +++--- .../frc/robot/commands/intake/Outtake.java | 5 ++- .../robot/commands/intake/RegularIntake.java | 4 +-- .../robot/subsystems/elevator/Elevator.java | 18 ++++++++++ .../elevator/ElevatorConstants.java | 15 ++++++++ .../elevator/ElevatorInterface.java | 35 +++++++++++++++++++ .../subsystems/elevator/PhysicalElevator.java | 4 +++ .../elevator/SimulatedElevator.java | 4 +++ 8 files changed, 84 insertions(+), 11 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/elevator/Elevator.java create mode 100644 src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java create mode 100644 src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java create mode 100644 src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java create mode 100644 src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index ad2a1e3..95dab91 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -7,12 +7,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "4829-BaseRobotCode"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 10; - public static final String GIT_SHA = "a81461e343ffe77aad20f5e40904bf123e067fae"; - public static final String GIT_DATE = "2024-11-15 17:55:39 EST"; + public static final int GIT_REVISION = 12; + public static final String GIT_SHA = "8d44ff46c1d6368e7110dd2cfe3db73c86389ed5"; + public static final String GIT_DATE = "2024-11-18 17:46:04 EST"; public static final String GIT_BRANCH = "ExamplesYay"; - public static final String BUILD_DATE = "2024-11-18 17:29:09 EST"; - public static final long BUILD_UNIX_TIME = 1731968949047L; + public static final String BUILD_DATE = "2024-11-20 17:52:01 EST"; + public static final long BUILD_UNIX_TIME = 1732143121634L; public static final int DIRTY = 1; private BuildConstants(){} diff --git a/src/main/java/frc/robot/commands/intake/Outtake.java b/src/main/java/frc/robot/commands/intake/Outtake.java index 704381f..79c6cd0 100644 --- a/src/main/java/frc/robot/commands/intake/Outtake.java +++ b/src/main/java/frc/robot/commands/intake/Outtake.java @@ -1,10 +1,9 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. +// This command ejects the note from the intake by reversing the rollors package frc.robot.commands.intake; import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.subsystems.intake.Intake; public class Outtake extends Command { private final Intake intakeSubsystem; diff --git a/src/main/java/frc/robot/commands/intake/RegularIntake.java b/src/main/java/frc/robot/commands/intake/RegularIntake.java index 2dcac9f..7b9ca19 100644 --- a/src/main/java/frc/robot/commands/intake/RegularIntake.java +++ b/src/main/java/frc/robot/commands/intake/RegularIntake.java @@ -1,6 +1,4 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. +// This command runs the rollers from the intake and grabs the note from the floor package frc.robot.commands.intake; diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java new file mode 100644 index 0000000..1db8498 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -0,0 +1,18 @@ +package frc.robot.subsystems.elevator; + +import edu.wpi.first.wpilibj2.command.SubsystemBase; + +public class Elevator extends SubsystemBase { + /** Creates a new Elevator. */ + private ElevatorInterface elevatorInterface; + private ElevatorInputsAutoLogged inputs = new ElevatorInputsAutoLogged(); + + public Elevator(ElevatorInterface elevatorInterface) { + this.elevatorInterface = elevatorInterface; + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + } +} diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java new file mode 100644 index 0000000..2c362b4 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java @@ -0,0 +1,15 @@ +package frc.robot.subsystems.elevator; + +public class ElevatorConstants { + public static final double DRUM_RADIUS = 0 - 9; + public static final double ELEVATOR_GEAR_RATIO = 2; + public static final double ENCODER_CONVERSION_FACTOR = 71.81; + public static final double MIN_HEIGHT = 0; + public static final double MAX_HEIGHT = 0 - 9; + + public static final double INTAKE_POSITION = MIN_HEIGHT; + public static final double SHOOT_AMP_POSITION = 0 - 9; + public static final double SHOOT_SPEAKER_POSITION = 0 - 9; + public static final double SHOOT_PASS_POSITION = 0 - 9; + public static final double ELEVATOR_OVER_DEFENSE = MAX_HEIGHT; +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java new file mode 100644 index 0000000..9c987ee --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java @@ -0,0 +1,35 @@ +package frc.robot.subsystems.elevator; + +import org.littletonrobotics.junction.AutoLog; + +public interface ElevatorInterface { + + @AutoLog + public static class ElevatorInputs { + public double leaderMotorPosition = 0.0; + public double leaderMotorVelocity = 0.0; + public double leaderMotorAppliedVolts = 0.0; + public double leaderMotorCurrentAmps = 0.0; + + public double followerMotorPosition = 0.0; + public double followerMotorVelocity = 0.0; + public double followerMotorAppliedVolts = 0.0; + public double followerMotorCurrentAmps = 0.0; + } + + public default void updateInputs(ElevatorInputs inputs) {} + + public default double getElevatorPosition() { + return 0.0; + } + + public default void setElevatorPosition(double position) {} + + public default void setElevatorSpeed(double speed) {} + + public default void setVolts(double volts) {} + + public default double getVolts() { + return 0.0; + } +} diff --git a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java new file mode 100644 index 0000000..9cbfa8d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java @@ -0,0 +1,4 @@ +package frc.robot.subsystems.elevator; + +/** Add your docs here. */ +public class PhysicalElevator {} diff --git a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java new file mode 100644 index 0000000..cabae5e --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java @@ -0,0 +1,4 @@ +package frc.robot.subsystems.elevator; + +/** Add your docs here. */ +public class SimulatedElevator {} From 6762114ac2a99b8dc7365259326727050fc0a888 Mon Sep 17 00:00:00 2001 From: Ishan1522 Date: Fri, 6 Dec 2024 17:58:34 -0500 Subject: [PATCH 05/13] more elevator stuff --- src/main/java/frc/robot/BuildConstants.java | 12 ++-- .../robot/subsystems/elevator/Elevator.java | 20 +++++++ .../subsystems/elevator/PhysicalElevator.java | 60 ++++++++++++++++++- .../elevator/SimulatedElevator.java | 10 +++- 4 files changed, 94 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index 95dab91..44abc36 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -7,13 +7,13 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "4829-BaseRobotCode"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 12; - public static final String GIT_SHA = "8d44ff46c1d6368e7110dd2cfe3db73c86389ed5"; - public static final String GIT_DATE = "2024-11-18 17:46:04 EST"; + public static final int GIT_REVISION = 13; + public static final String GIT_SHA = "c9b53f77ffe5d9294a84e77fe471839907a42770"; + public static final String GIT_DATE = "2024-11-20 17:53:15 EST"; public static final String GIT_BRANCH = "ExamplesYay"; - public static final String BUILD_DATE = "2024-11-20 17:52:01 EST"; - public static final long BUILD_UNIX_TIME = 1732143121634L; - public static final int DIRTY = 1; + public static final String BUILD_DATE = "2024-12-06 16:29:40 EST"; + public static final long BUILD_UNIX_TIME = 1733520580115L; + public static final int DIRTY = 0; private BuildConstants(){} } diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java index 1db8498..0f7ff46 100644 --- a/src/main/java/frc/robot/subsystems/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -11,6 +11,26 @@ public Elevator(ElevatorInterface elevatorInterface) { this.elevatorInterface = elevatorInterface; } + public double getElevatorPosition() { + return elevatorInterface.getElevatorPosition(); + } + + public double getVolts(){ + return elevatorInterface.getVolts(); + } + + public void setElevatorPosition(double position){ + elevatorInterface.setElevatorPosition(position); + } + + public void setElevatorSpeed(double speed){ + elevatorInterface.setElevatorSpeed(speed); + } + + public void setVolts(double volts){ + elevatorInterface.setVolts(volts); + } + @Override public void periodic() { // This method will be called once per scheduler run diff --git a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java index 9cbfa8d..9a8424f 100644 --- a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java @@ -1,4 +1,62 @@ package frc.robot.subsystems.elevator; +import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.hardware.TalonFX; + +import edu.wpi.first.units.measure.Angle; +import frc.robot.subsystems.elevator.ElevatorInterface.ElevatorInputs; + /** Add your docs here. */ -public class PhysicalElevator {} +public class PhysicalElevator { + private TalonFX leaderMotor = new TalonFX(0); + private TalonFX followerMotor = new TalonFX(0); + + StatusSignal leaderPosition; + Statussignal followerPosition; + public PhysicalElevator() { + TalonFXConfiguration elevatorConfig = new TalonFXConfiguration(); + + elevatorConfig.Slot0.kP = 0; + elevatorConfig.Slot0.kI = 0; + elevatorConfig.Slot0.kD = 0; + + leaderMotor.getConfigurator().apply(elevatorConfig); + followerMotor.getConfigurator().apply(elevatorConfig); + } + + public void updateInputs(ElevatorInputs inputs) { + inputs.leaderMotorPosition = leaderPosition.getValueAsDouble(); + inputs.leaderMotorVelocity = leaderVelocity.getValueAsDouble(); + inputs.leaderMotorAppliedVolts = leaderAppliedVolts.getValueAsDouble(); + inputs.leaderMotorCurrentAmps = leaderCurrentAmps.getValueAsDouble(); + + inputs.followerMotorPosition = followerPosition.getValueAsDouble(); + inputs.followerMotorVelocity = followerVelocity.getValueAsDouble(); + inputs.followerMotorAppliedVolts = followerAppliedVolts.getValueAsDouble(); + inputs.followerMotorCurrentAmps = followerCurrentAmps.getValueAsDouble(); + } + + public double getElevatorPosition() { + return leaderMotor.getRotorPosition().getValueAsDouble(); + } + + public void setElevatorPosition(double position) { + leaderMotor.setPosition(position); + followerMotor.setPosition(position); + } + + public void setElevatorSpeed(double speed) { + leaderMotor.set(speed); + followerMotor.set(speed); + } + + public void setVolts(double volts) { + leaderMotor.setVoltage(volts); + followerMotor.setVoltage(volts);; + } + + public double getVolts() { + return leaderMotor.getMotorVoltage().getValueAsDouble(); + } +} diff --git a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java index cabae5e..62468d4 100644 --- a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java @@ -1,4 +1,12 @@ package frc.robot.subsystems.elevator; +import edu.wpi.first.wpilibj.simulation.ElevatorSim; + /** Add your docs here. */ -public class SimulatedElevator {} +public class SimulatedElevator implements ElevatorInterface { + private ElevatorSim simulatedElevator = new ElevatorSim(DCMotor.getFalcon500(2), ); + + public SimulatedElevator() { + + } +} From 9b2d52efc94f51550c86781dc4d51112afc44b13 Mon Sep 17 00:00:00 2001 From: Ishan1522 Date: Mon, 16 Dec 2024 17:53:23 -0500 Subject: [PATCH 06/13] Hopefully i finish this soon --- .../robot/subsystems/elevator/Elevator.java | 10 +- .../elevator/ElevatorConstants.java | 7 + .../elevator/ElevatorInterface.java | 6 - .../subsystems/elevator/PhysicalElevator.java | 35 +- .../elevator/SimulatedElevator.java | 28 +- .../subsystems/intake/IntakeThing/.gitignore | 184 +++++++++ .../.wpilib/wpilib_preferences.json | 6 + .../intake/IntakeThing/WPILib-License.md | 24 ++ .../intake/IntakeThing/build.gradle | 102 +++++ .../gradle/wrapper/gradle-wrapper.jar | Bin 0 -> 43583 bytes .../gradle/wrapper/gradle-wrapper.properties | 7 + .../subsystems/intake/IntakeThing/gradlew | 252 ++++++++++++ .../subsystems/intake/IntakeThing/gradlew.bat | 94 +++++ .../intake/IntakeThing/settings.gradle | 30 ++ .../IntakeThing/src/main/deploy/example.txt | 3 + .../src/main/java/frc/robot/Constants.java | 19 + .../src/main/java/frc/robot/Main.java | 25 ++ .../src/main/java/frc/robot/Robot.java | 100 +++++ .../main/java/frc/robot/RobotContainer.java | 59 +++ .../main/java/frc/robot/commands/Autos.java | 20 + .../main/java/frc/robot/commands/Intake.java | 42 ++ .../frc/robot/subsystems/IntakeSubsystem.java | 37 ++ .../vendordeps/Phoenix6-25.0.0-beta-3.json | 359 ++++++++++++++++++ .../vendordeps/WPILibNewCommands.json | 38 ++ 24 files changed, 1456 insertions(+), 31 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.jar create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json create mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java index 0f7ff46..a894a76 100644 --- a/src/main/java/frc/robot/subsystems/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -15,19 +15,15 @@ public double getElevatorPosition() { return elevatorInterface.getElevatorPosition(); } - public double getVolts(){ + public double getVolts() { return elevatorInterface.getVolts(); } - public void setElevatorPosition(double position){ + public void setElevatorPosition(double position) { elevatorInterface.setElevatorPosition(position); } - public void setElevatorSpeed(double speed){ - elevatorInterface.setElevatorSpeed(speed); - } - - public void setVolts(double volts){ + public void setVolts(double volts) { elevatorInterface.setVolts(volts); } diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java index 2c362b4..5856e6c 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java @@ -1,8 +1,13 @@ package frc.robot.subsystems.elevator; public class ElevatorConstants { + public static final double ELEVATOR_P = 0 - 9; + public static final double ELEVATOR_I = 0 - 9; + public static final double ELEVATOR_D = 0 - 9; + public static final double DRUM_RADIUS = 0 - 9; public static final double ELEVATOR_GEAR_RATIO = 2; + public static final double ELEVATOR_CARRIAGE_MASS = 0 - 9; public static final double ENCODER_CONVERSION_FACTOR = 71.81; public static final double MIN_HEIGHT = 0; public static final double MAX_HEIGHT = 0 - 9; @@ -12,4 +17,6 @@ public class ElevatorConstants { public static final double SHOOT_SPEAKER_POSITION = 0 - 9; public static final double SHOOT_PASS_POSITION = 0 - 9; public static final double ELEVATOR_OVER_DEFENSE = MAX_HEIGHT; + + public static final double VELOCITY_METERS_PER_SECOND = 0 - 9; } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java index 9c987ee..9f2b93b 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java @@ -7,14 +7,10 @@ public interface ElevatorInterface { @AutoLog public static class ElevatorInputs { public double leaderMotorPosition = 0.0; - public double leaderMotorVelocity = 0.0; public double leaderMotorAppliedVolts = 0.0; - public double leaderMotorCurrentAmps = 0.0; public double followerMotorPosition = 0.0; - public double followerMotorVelocity = 0.0; public double followerMotorAppliedVolts = 0.0; - public double followerMotorCurrentAmps = 0.0; } public default void updateInputs(ElevatorInputs inputs) {} @@ -25,8 +21,6 @@ public default double getElevatorPosition() { public default void setElevatorPosition(double position) {} - public default void setElevatorSpeed(double speed) {} - public default void setVolts(double volts) {} public default double getVolts() { diff --git a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java index 9a8424f..541f450 100644 --- a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java @@ -1,10 +1,13 @@ package frc.robot.subsystems.elevator; +import java.io.ObjectInputFilter.Status; + import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.hardware.TalonFX; import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.Voltage; import frc.robot.subsystems.elevator.ElevatorInterface.ElevatorInputs; /** Add your docs here. */ @@ -13,13 +16,23 @@ public class PhysicalElevator { private TalonFX followerMotor = new TalonFX(0); StatusSignal leaderPosition; - Statussignal followerPosition; + StatusSignal followerPosition; + + StatusSignal leaderAppliedVoltage; + StatusSignal followerAppliedVoltage; + public PhysicalElevator() { + leaderPosition = leaderMotor.getRotorPosition(); + followerPosition = followerMotor.getRotorPosition(); + + leaderAppliedVoltage = leaderMotor.getMotorVoltage(); + followerAppliedVoltage = followerMotor.getMotorVoltage(); + TalonFXConfiguration elevatorConfig = new TalonFXConfiguration(); - elevatorConfig.Slot0.kP = 0; - elevatorConfig.Slot0.kI = 0; - elevatorConfig.Slot0.kD = 0; + elevatorConfig.Slot0.kP = ElevatorConstants.ELEVATOR_P; + elevatorConfig.Slot0.kI = ElevatorConstants.ELEVATOR_I; + elevatorConfig.Slot0.kD = ElevatorConstants.ELEVATOR_D; leaderMotor.getConfigurator().apply(elevatorConfig); followerMotor.getConfigurator().apply(elevatorConfig); @@ -27,18 +40,11 @@ public PhysicalElevator() { public void updateInputs(ElevatorInputs inputs) { inputs.leaderMotorPosition = leaderPosition.getValueAsDouble(); - inputs.leaderMotorVelocity = leaderVelocity.getValueAsDouble(); - inputs.leaderMotorAppliedVolts = leaderAppliedVolts.getValueAsDouble(); - inputs.leaderMotorCurrentAmps = leaderCurrentAmps.getValueAsDouble(); - inputs.followerMotorPosition = followerPosition.getValueAsDouble(); - inputs.followerMotorVelocity = followerVelocity.getValueAsDouble(); - inputs.followerMotorAppliedVolts = followerAppliedVolts.getValueAsDouble(); - inputs.followerMotorCurrentAmps = followerCurrentAmps.getValueAsDouble(); } public double getElevatorPosition() { - return leaderMotor.getRotorPosition().getValueAsDouble(); + return leaderPosition.getValueAsDouble(); } public void setElevatorPosition(double position) { @@ -46,11 +52,6 @@ public void setElevatorPosition(double position) { followerMotor.setPosition(position); } - public void setElevatorSpeed(double speed) { - leaderMotor.set(speed); - followerMotor.set(speed); - } - public void setVolts(double volts) { leaderMotor.setVoltage(volts); followerMotor.setVoltage(volts);; diff --git a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java index 62468d4..a9d0384 100644 --- a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java @@ -1,12 +1,38 @@ package frc.robot.subsystems.elevator; +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.simulation.ElevatorSim; /** Add your docs here. */ public class SimulatedElevator implements ElevatorInterface { - private ElevatorSim simulatedElevator = new ElevatorSim(DCMotor.getFalcon500(2), ); + private ElevatorSim simulatedElevator = new ElevatorSim(DCMotor.getFalcon500(2), ElevatorConstants.ELEVATOR_GEAR_RATIO, ElevatorConstants.ELEVATOR_CARRIAGE_MASS, ElevatorConstants.DRUM_RADIUS, ElevatorConstants.MIN_HEIGHT, ElevatorConstants.MAX_HEIGHT, true, 0.0); + private PIDController simPID; + private double currentVolts; public SimulatedElevator() { + simPID = new PIDController(ElevatorConstants.ELEVATOR_P, ElevatorConstants.ELEVATOR_I, ElevatorConstants.ELEVATOR_D); + } + + public void updateInputs(ElevatorInputs inputs) { + inputs.leaderMotorPosition = getElevatorPosition(); + inputs.followerMotorPosition = getElevatorPosition(); + } + + public void setElevatorPosition(double position) { + simulatedElevator.setState(simPID.calculate(position), ElevatorConstants.VELOCITY_METERS_PER_SECOND); + } + + public double getElevatorPosition() { + return simulatedElevator.getPositionMeters(); + } + + public void setVolts(double volts) { + currentVolts = simPID.calculate(volts); + simulatedElevator.setInputVoltage(currentVolts); + } + public double getVolts() { + return currentVolts; } } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore b/src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore new file mode 100644 index 0000000..375359c --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore @@ -0,0 +1,184 @@ +# This gitignore has been specially created by the WPILib team. +# If you remove items from this file, intellisense might break. + +### C++ ### +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +### Java ### +# Compiled class file +*.class + +# Log file +*.log + +# BlueJ files +*.ctxt + +# Mobile Tools for Java (J2ME) +.mtj.tmp/ + +# Package Files # +*.jar +*.war +*.nar +*.ear +*.zip +*.tar.gz +*.rar + +# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml +hs_err_pid* + +### Linux ### +*~ + +# temporary files which can be created if a process still has a handle open of a deleted file +.fuse_hidden* + +# KDE directory preferences +.directory + +# Linux trash folder which might appear on any partition or disk +.Trash-* + +# .nfs files are created when an open file is removed but is still being accessed +.nfs* + +### macOS ### +# General +.DS_Store +.AppleDouble +.LSOverride + +# Icon must end with two \r +Icon + +# Thumbnails +._* + +# Files that might appear in the root of a volume +.DocumentRevisions-V100 +.fseventsd +.Spotlight-V100 +.TemporaryItems +.Trashes +.VolumeIcon.icns +.com.apple.timemachine.donotpresent + +# Directories potentially created on remote AFP share +.AppleDB +.AppleDesktop +Network Trash Folder +Temporary Items +.apdisk + +### VisualStudioCode ### +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json + +### Windows ### +# Windows thumbnail cache files +Thumbs.db +ehthumbs.db +ehthumbs_vista.db + +# Dump file +*.stackdump + +# Folder config file +[Dd]esktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msix +*.msm +*.msp + +# Windows shortcuts +*.lnk + +### Gradle ### +.gradle +/build/ + +# Ignore Gradle GUI config +gradle-app.setting + +# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) +!gradle-wrapper.jar + +# Cache of project +.gradletasknamecache + +# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 +# gradle/wrapper/gradle-wrapper.properties + +# # VS Code Specific Java Settings +# DO NOT REMOVE .classpath and .project +.classpath +.project +.settings/ +bin/ + +# IntelliJ +*.iml +*.ipr +*.iws +.idea/ +out/ + +# Fleet +.fleet + +# Simulation GUI and other tools window save file +networktables.json +simgui.json +*-window.json + +# Simulation data log directory +logs/ + +# Folder that has CTRE Phoenix Sim device config storage +ctre_sim/ + +# clangd +/.cache +compile_commands.json diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json b/src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json new file mode 100644 index 0000000..acab627 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "enableCppIntellisense": false, + "currentLanguage": "java", + "projectYear": "2025beta", + "teamNumber": 4829 +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md b/src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md new file mode 100644 index 0000000..645e542 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md @@ -0,0 +1,24 @@ +Copyright (c) 2009-2024 FIRST and other WPILib contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of FIRST, WPILib, nor the names of other WPILib + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle b/src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle new file mode 100644 index 0000000..ec028da --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle @@ -0,0 +1,102 @@ +plugins { + id "java" + id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1" +} + +java { + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 +} + +def ROBOT_MAIN_CLASS = "frc.robot.Main" + +// Define my targets (RoboRIO) and artifacts (deployable files) +// This is added by GradleRIO's backing project DeployUtils. +deploy { + targets { + roborio(getTargetTypeClass('RoboRIO')) { + // Team number is loaded either from the .wpilib/wpilib_preferences.json + // or from command line. If not found an exception will be thrown. + // You can use getTeamOrDefault(team) instead of getTeamNumber if you + // want to store a team number in this file. + team = project.frc.getTeamNumber() + debug = project.frc.getDebugOrDefault(false) + + artifacts { + // First part is artifact name, 2nd is artifact type + // getTargetTypeClass is a shortcut to get the class type using a string + + frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + } + + // Static files artifact + frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy') + directory = '/home/lvuser/deploy' + } + } + } + } +} + +def deployArtifact = deploy.targets.roborio.artifacts.frcJava + +// Set to true to use debug for JNI. +wpi.java.debugJni = false + +// Set this to true to enable desktop support. +def includeDesktopSupport = false + +// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. +// Also defines JUnit 5. +dependencies { + annotationProcessor wpi.java.deps.wpilibAnnotations() + implementation wpi.java.deps.wpilib() + implementation wpi.java.vendor.java() + + roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) + roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + + roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) + roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + + nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) + nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) + simulationDebug wpi.sim.enableDebug() + + nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) + nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) + simulationRelease wpi.sim.enableRelease() + + testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' +} + +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' +} + +// Simulation configuration (e.g. environment variables). +wpi.sim.addGui().defaultEnabled = true +wpi.sim.addDriverstation() + +// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') +// in order to make them all available at runtime. Also adding the manifest so WPILib +// knows where to look for our Robot Class. +jar { + from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + from sourceSets.main.allSource + manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) + duplicatesStrategy = DuplicatesStrategy.INCLUDE +} + +// Configure jar and deploy tasks +deployArtifact.jarTask = jar +wpi.java.configureExecutableTasks(jar) +wpi.java.configureTestTasks(test) + +// Configure string concat to always inline compile +tasks.withType(JavaCompile) { + options.compilerArgs.add '-XDstringConcat=inline' +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.jar b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.jar new file mode 100644 index 0000000000000000000000000000000000000000..a4b76b9530d66f5e68d973ea569d8e19de379189 GIT binary patch literal 43583 zcma&N1CXTcmMvW9vTb(Rwr$&4wr$(C?dmSu>@vG-+vuvg^_??!{yS%8zW-#zn-LkA z5&1^$^{lnmUON?}LBF8_K|(?T0Ra(xUH{($5eN!MR#ZihR#HxkUPe+_R8Cn`RRs(P z_^*#_XlXmGv7!4;*Y%p4nw?{bNp@UZHv1?Um8r6)Fei3p@ClJn0ECfg1hkeuUU@Or zDaPa;U3fE=3L}DooL;8f;P0ipPt0Z~9P0)lbStMS)ag54=uL9ia-Lm3nh|@(Y?B`; zx_#arJIpXH!U{fbCbI^17}6Ri*H<>OLR%c|^mh8+)*h~K8Z!9)DPf zR2h?lbDZQ`p9P;&DQ4F0sur@TMa!Y}S8irn(%d-gi0*WxxCSk*A?3lGh=gcYN?FGl z7D=Js!i~0=u3rox^eO3i@$0=n{K1lPNU zwmfjRVmLOCRfe=seV&P*1Iq=^i`502keY8Uy-WNPwVNNtJFx?IwAyRPZo2Wo1+S(xF37LJZ~%i)kpFQ3Fw=mXfd@>%+)RpYQLnr}B~~zoof(JVm^^&f zxKV^+3D3$A1G;qh4gPVjhrC8e(VYUHv#dy^)(RoUFM?o%W-EHxufuWf(l*@-l+7vt z=l`qmR56K~F|v<^Pd*p~1_y^P0P^aPC##d8+HqX4IR1gu+7w#~TBFphJxF)T$2WEa zxa?H&6=Qe7d(#tha?_1uQys2KtHQ{)Qco)qwGjrdNL7thd^G5i8Os)CHqc>iOidS} z%nFEDdm=GXBw=yXe1W-ShHHFb?Cc70+$W~z_+}nAoHFYI1MV1wZegw*0y^tC*s%3h zhD3tN8b=Gv&rj}!SUM6|ajSPp*58KR7MPpI{oAJCtY~JECm)*m_x>AZEu>DFgUcby z1Qaw8lU4jZpQ_$;*7RME+gq1KySGG#Wql>aL~k9tLrSO()LWn*q&YxHEuzmwd1?aAtI zBJ>P=&$=l1efe1CDU;`Fd+_;&wI07?V0aAIgc(!{a z0Jg6Y=inXc3^n!U0Atk`iCFIQooHqcWhO(qrieUOW8X(x?(RD}iYDLMjSwffH2~tB z)oDgNBLB^AJBM1M^c5HdRx6fBfka`(LD-qrlh5jqH~);#nw|iyp)()xVYak3;Ybik z0j`(+69aK*B>)e_p%=wu8XC&9e{AO4c~O1U`5X9}?0mrd*m$_EUek{R?DNSh(=br# z#Q61gBzEpmy`$pA*6!87 zSDD+=@fTY7<4A?GLqpA?Pb2z$pbCc4B4zL{BeZ?F-8`s$?>*lXXtn*NC61>|*w7J* z$?!iB{6R-0=KFmyp1nnEmLsA-H0a6l+1uaH^g%c(p{iT&YFrbQ$&PRb8Up#X3@Zsk zD^^&LK~111%cqlP%!_gFNa^dTYT?rhkGl}5=fL{a`UViaXWI$k-UcHJwmaH1s=S$4 z%4)PdWJX;hh5UoK?6aWoyLxX&NhNRqKam7tcOkLh{%j3K^4Mgx1@i|Pi&}<^5>hs5 zm8?uOS>%)NzT(%PjVPGa?X%`N2TQCKbeH2l;cTnHiHppPSJ<7y-yEIiC!P*ikl&!B z%+?>VttCOQM@ShFguHVjxX^?mHX^hSaO_;pnyh^v9EumqSZTi+#f&_Vaija0Q-e*| z7ulQj6Fs*bbmsWp{`auM04gGwsYYdNNZcg|ph0OgD>7O}Asn7^Z=eI>`$2*v78;sj-}oMoEj&@)9+ycEOo92xSyY344^ z11Hb8^kdOvbf^GNAK++bYioknrpdN>+u8R?JxG=!2Kd9r=YWCOJYXYuM0cOq^FhEd zBg2puKy__7VT3-r*dG4c62Wgxi52EMCQ`bKgf*#*ou(D4-ZN$+mg&7$u!! z-^+Z%;-3IDwqZ|K=ah85OLwkO zKxNBh+4QHh)u9D?MFtpbl)us}9+V!D%w9jfAMYEb>%$A;u)rrI zuBudh;5PN}_6J_}l55P3l_)&RMlH{m!)ai-i$g)&*M`eN$XQMw{v^r@-125^RRCF0 z^2>|DxhQw(mtNEI2Kj(;KblC7x=JlK$@78`O~>V!`|1Lm-^JR$-5pUANAnb(5}B}JGjBsliK4& zk6y(;$e&h)lh2)L=bvZKbvh@>vLlreBdH8No2>$#%_Wp1U0N7Ank!6$dFSi#xzh|( zRi{Uw%-4W!{IXZ)fWx@XX6;&(m_F%c6~X8hx=BN1&q}*( zoaNjWabE{oUPb!Bt$eyd#$5j9rItB-h*5JiNi(v^e|XKAj*8(k<5-2$&ZBR5fF|JA z9&m4fbzNQnAU}r8ab>fFV%J0z5awe#UZ|bz?Ur)U9bCIKWEzi2%A+5CLqh?}K4JHi z4vtM;+uPsVz{Lfr;78W78gC;z*yTch~4YkLr&m-7%-xc ztw6Mh2d>_iO*$Rd8(-Cr1_V8EO1f*^@wRoSozS) zy1UoC@pruAaC8Z_7~_w4Q6n*&B0AjOmMWa;sIav&gu z|J5&|{=a@vR!~k-OjKEgPFCzcJ>#A1uL&7xTDn;{XBdeM}V=l3B8fE1--DHjSaxoSjNKEM9|U9#m2<3>n{Iuo`r3UZp;>GkT2YBNAh|b z^jTq-hJp(ebZh#Lk8hVBP%qXwv-@vbvoREX$TqRGTgEi$%_F9tZES@z8Bx}$#5eeG zk^UsLBH{bc2VBW)*EdS({yw=?qmevwi?BL6*=12k9zM5gJv1>y#ML4!)iiPzVaH9% zgSImetD@dam~e>{LvVh!phhzpW+iFvWpGT#CVE5TQ40n%F|p(sP5mXxna+Ev7PDwA zamaV4m*^~*xV+&p;W749xhb_X=$|LD;FHuB&JL5?*Y2-oIT(wYY2;73<^#46S~Gx| z^cez%V7x$81}UWqS13Gz80379Rj;6~WdiXWOSsdmzY39L;Hg3MH43o*y8ibNBBH`(av4|u;YPq%{R;IuYow<+GEsf@R?=@tT@!}?#>zIIn0CoyV!hq3mw zHj>OOjfJM3F{RG#6ujzo?y32m^tgSXf@v=J$ELdJ+=5j|=F-~hP$G&}tDZsZE?5rX ztGj`!S>)CFmdkccxM9eGIcGnS2AfK#gXwj%esuIBNJQP1WV~b~+D7PJTmWGTSDrR` zEAu4B8l>NPuhsk5a`rReSya2nfV1EK01+G!x8aBdTs3Io$u5!6n6KX%uv@DxAp3F@{4UYg4SWJtQ-W~0MDb|j-$lwVn znAm*Pl!?Ps&3wO=R115RWKb*JKoexo*)uhhHBncEDMSVa_PyA>k{Zm2(wMQ(5NM3# z)jkza|GoWEQo4^s*wE(gHz?Xsg4`}HUAcs42cM1-qq_=+=!Gk^y710j=66(cSWqUe zklbm8+zB_syQv5A2rj!Vbw8;|$@C!vfNmNV!yJIWDQ>{+2x zKjuFX`~~HKG~^6h5FntRpnnHt=D&rq0>IJ9#F0eM)Y-)GpRjiN7gkA8wvnG#K=q{q z9dBn8_~wm4J<3J_vl|9H{7q6u2A!cW{bp#r*-f{gOV^e=8S{nc1DxMHFwuM$;aVI^ zz6A*}m8N-&x8;aunp1w7_vtB*pa+OYBw=TMc6QK=mbA-|Cf* zvyh8D4LRJImooUaSb7t*fVfih<97Gf@VE0|z>NcBwBQze);Rh!k3K_sfunToZY;f2 z^HmC4KjHRVg+eKYj;PRN^|E0>Gj_zagfRbrki68I^#~6-HaHg3BUW%+clM1xQEdPYt_g<2K+z!$>*$9nQ>; zf9Bei{?zY^-e{q_*|W#2rJG`2fy@{%6u0i_VEWTq$*(ZN37|8lFFFt)nCG({r!q#9 z5VK_kkSJ3?zOH)OezMT{!YkCuSSn!K#-Rhl$uUM(bq*jY? zi1xbMVthJ`E>d>(f3)~fozjg^@eheMF6<)I`oeJYx4*+M&%c9VArn(OM-wp%M<-`x z7sLP1&3^%Nld9Dhm@$3f2}87!quhI@nwd@3~fZl_3LYW-B?Ia>ui`ELg z&Qfe!7m6ze=mZ`Ia9$z|ARSw|IdMpooY4YiPN8K z4B(ts3p%2i(Td=tgEHX z0UQ_>URBtG+-?0E;E7Ld^dyZ;jjw0}XZ(}-QzC6+NN=40oDb2^v!L1g9xRvE#@IBR zO!b-2N7wVfLV;mhEaXQ9XAU+>=XVA6f&T4Z-@AX!leJ8obP^P^wP0aICND?~w&NykJ#54x3_@r7IDMdRNy4Hh;h*!u(Ol(#0bJdwEo$5437-UBjQ+j=Ic>Q2z` zJNDf0yO6@mr6y1#n3)s(W|$iE_i8r@Gd@!DWDqZ7J&~gAm1#~maIGJ1sls^gxL9LLG_NhU!pTGty!TbhzQnu)I*S^54U6Yu%ZeCg`R>Q zhBv$n5j0v%O_j{QYWG!R9W?5_b&67KB$t}&e2LdMvd(PxN6Ir!H4>PNlerpBL>Zvyy!yw z-SOo8caEpDt(}|gKPBd$qND5#a5nju^O>V&;f890?yEOfkSG^HQVmEbM3Ugzu+UtH zC(INPDdraBN?P%kE;*Ae%Wto&sgw(crfZ#Qy(<4nk;S|hD3j{IQRI6Yq|f^basLY; z-HB&Je%Gg}Jt@={_C{L$!RM;$$|iD6vu#3w?v?*;&()uB|I-XqEKqZPS!reW9JkLewLb!70T7n`i!gNtb1%vN- zySZj{8-1>6E%H&=V}LM#xmt`J3XQoaD|@XygXjdZ1+P77-=;=eYpoEQ01B@L*a(uW zrZeZz?HJsw_4g0vhUgkg@VF8<-X$B8pOqCuWAl28uB|@r`19DTUQQsb^pfqB6QtiT z*`_UZ`fT}vtUY#%sq2{rchyfu*pCg;uec2$-$N_xgjZcoumE5vSI{+s@iLWoz^Mf; zuI8kDP{!XY6OP~q5}%1&L}CtfH^N<3o4L@J@zg1-mt{9L`s^z$Vgb|mr{@WiwAqKg zp#t-lhrU>F8o0s1q_9y`gQNf~Vb!F%70f}$>i7o4ho$`uciNf=xgJ>&!gSt0g;M>*x4-`U)ysFW&Vs^Vk6m%?iuWU+o&m(2Jm26Y(3%TL; zA7T)BP{WS!&xmxNw%J=$MPfn(9*^*TV;$JwRy8Zl*yUZi8jWYF>==j~&S|Xinsb%c z2?B+kpet*muEW7@AzjBA^wAJBY8i|#C{WtO_or&Nj2{=6JTTX05}|H>N2B|Wf!*3_ z7hW*j6p3TvpghEc6-wufFiY!%-GvOx*bZrhZu+7?iSrZL5q9}igiF^*R3%DE4aCHZ zqu>xS8LkW+Auv%z-<1Xs92u23R$nk@Pk}MU5!gT|c7vGlEA%G^2th&Q*zfg%-D^=f z&J_}jskj|Q;73NP4<4k*Y%pXPU2Thoqr+5uH1yEYM|VtBPW6lXaetokD0u z9qVek6Q&wk)tFbQ8(^HGf3Wp16gKmr>G;#G(HRBx?F`9AIRboK+;OfHaLJ(P>IP0w zyTbTkx_THEOs%Q&aPrxbZrJlio+hCC_HK<4%f3ZoSAyG7Dn`=X=&h@m*|UYO-4Hq0 z-Bq&+Ie!S##4A6OGoC~>ZW`Y5J)*ouaFl_e9GA*VSL!O_@xGiBw!AF}1{tB)z(w%c zS1Hmrb9OC8>0a_$BzeiN?rkPLc9%&;1CZW*4}CDDNr2gcl_3z+WC15&H1Zc2{o~i) z)LLW=WQ{?ricmC`G1GfJ0Yp4Dy~Ba;j6ZV4r{8xRs`13{dD!xXmr^Aga|C=iSmor% z8hi|pTXH)5Yf&v~exp3o+sY4B^^b*eYkkCYl*T{*=-0HniSA_1F53eCb{x~1k3*`W zr~};p1A`k{1DV9=UPnLDgz{aJH=-LQo<5%+Em!DNN252xwIf*wF_zS^!(XSm(9eoj z=*dXG&n0>)_)N5oc6v!>-bd(2ragD8O=M|wGW z!xJQS<)u70m&6OmrF0WSsr@I%T*c#Qo#Ha4d3COcX+9}hM5!7JIGF>7<~C(Ear^Sn zm^ZFkV6~Ula6+8S?oOROOA6$C&q&dp`>oR-2Ym3(HT@O7Sd5c~+kjrmM)YmgPH*tL zX+znN>`tv;5eOfX?h{AuX^LK~V#gPCu=)Tigtq9&?7Xh$qN|%A$?V*v=&-2F$zTUv z`C#WyIrChS5|Kgm_GeudCFf;)!WH7FI60j^0o#65o6`w*S7R@)88n$1nrgU(oU0M9 zx+EuMkC>(4j1;m6NoGqEkpJYJ?vc|B zOlwT3t&UgL!pX_P*6g36`ZXQ; z9~Cv}ANFnJGp(;ZhS(@FT;3e)0)Kp;h^x;$*xZn*k0U6-&FwI=uOGaODdrsp-!K$Ac32^c{+FhI-HkYd5v=`PGsg%6I`4d9Jy)uW0y%) zm&j^9WBAp*P8#kGJUhB!L?a%h$hJgQrx!6KCB_TRo%9{t0J7KW8!o1B!NC)VGLM5! zpZy5Jc{`r{1e(jd%jsG7k%I+m#CGS*BPA65ZVW~fLYw0dA-H_}O zrkGFL&P1PG9p2(%QiEWm6x;U-U&I#;Em$nx-_I^wtgw3xUPVVu zqSuKnx&dIT-XT+T10p;yjo1Y)z(x1fb8Dzfn8e yu?e%!_ptzGB|8GrCfu%p?(_ zQccdaaVK$5bz;*rnyK{_SQYM>;aES6Qs^lj9lEs6_J+%nIiuQC*fN;z8md>r_~Mfl zU%p5Dt_YT>gQqfr@`cR!$NWr~+`CZb%dn;WtzrAOI>P_JtsB76PYe*<%H(y>qx-`Kq!X_; z<{RpAqYhE=L1r*M)gNF3B8r(<%8mo*SR2hu zccLRZwGARt)Hlo1euqTyM>^!HK*!Q2P;4UYrysje@;(<|$&%vQekbn|0Ruu_Io(w4#%p6ld2Yp7tlA`Y$cciThP zKzNGIMPXX%&Ud0uQh!uQZz|FB`4KGD?3!ND?wQt6!n*f4EmCoJUh&b?;B{|lxs#F- z31~HQ`SF4x$&v00@(P+j1pAaj5!s`)b2RDBp*PB=2IB>oBF!*6vwr7Dp%zpAx*dPr zb@Zjq^XjN?O4QcZ*O+8>)|HlrR>oD*?WQl5ri3R#2?*W6iJ>>kH%KnnME&TT@ZzrHS$Q%LC?n|e>V+D+8D zYc4)QddFz7I8#}y#Wj6>4P%34dZH~OUDb?uP%-E zwjXM(?Sg~1!|wI(RVuxbu)-rH+O=igSho_pDCw(c6b=P zKk4ATlB?bj9+HHlh<_!&z0rx13K3ZrAR8W)!@Y}o`?a*JJsD+twZIv`W)@Y?Amu_u zz``@-e2X}27$i(2=9rvIu5uTUOVhzwu%mNazS|lZb&PT;XE2|B&W1>=B58#*!~D&) zfVmJGg8UdP*fx(>Cj^?yS^zH#o-$Q-*$SnK(ZVFkw+er=>N^7!)FtP3y~Xxnu^nzY zikgB>Nj0%;WOltWIob|}%lo?_C7<``a5hEkx&1ku$|)i>Rh6@3h*`slY=9U}(Ql_< zaNG*J8vb&@zpdhAvv`?{=zDedJ23TD&Zg__snRAH4eh~^oawdYi6A3w8<Ozh@Kw)#bdktM^GVb zrG08?0bG?|NG+w^&JvD*7LAbjED{_Zkc`3H!My>0u5Q}m!+6VokMLXxl`Mkd=g&Xx z-a>m*#G3SLlhbKB!)tnzfWOBV;u;ftU}S!NdD5+YtOjLg?X}dl>7m^gOpihrf1;PY zvll&>dIuUGs{Qnd- zwIR3oIrct8Va^Tm0t#(bJD7c$Z7DO9*7NnRZorrSm`b`cxz>OIC;jSE3DO8`hX955ui`s%||YQtt2 z5DNA&pG-V+4oI2s*x^>-$6J?p=I>C|9wZF8z;VjR??Icg?1w2v5Me+FgAeGGa8(3S z4vg*$>zC-WIVZtJ7}o9{D-7d>zCe|z#<9>CFve-OPAYsneTb^JH!Enaza#j}^mXy1 z+ULn^10+rWLF6j2>Ya@@Kq?26>AqK{A_| zQKb*~F1>sE*=d?A?W7N2j?L09_7n+HGi{VY;MoTGr_)G9)ot$p!-UY5zZ2Xtbm=t z@dpPSGwgH=QtIcEulQNI>S-#ifbnO5EWkI;$A|pxJd885oM+ zGZ0_0gDvG8q2xebj+fbCHYfAXuZStH2j~|d^sBAzo46(K8n59+T6rzBwK)^rfPT+B zyIFw)9YC-V^rhtK`!3jrhmW-sTmM+tPH+;nwjL#-SjQPUZ53L@A>y*rt(#M(qsiB2 zx6B)dI}6Wlsw%bJ8h|(lhkJVogQZA&n{?Vgs6gNSXzuZpEyu*xySy8ro07QZ7Vk1!3tJphN_5V7qOiyK8p z#@jcDD8nmtYi1^l8ml;AF<#IPK?!pqf9D4moYk>d99Im}Jtwj6c#+A;f)CQ*f-hZ< z=p_T86jog%!p)D&5g9taSwYi&eP z#JuEK%+NULWus;0w32-SYFku#i}d~+{Pkho&^{;RxzP&0!RCm3-9K6`>KZpnzS6?L z^H^V*s!8<>x8bomvD%rh>Zp3>Db%kyin;qtl+jAv8Oo~1g~mqGAC&Qi_wy|xEt2iz zWAJEfTV%cl2Cs<1L&DLRVVH05EDq`pH7Oh7sR`NNkL%wi}8n>IXcO40hp+J+sC!W?!krJf!GJNE8uj zg-y~Ns-<~D?yqbzVRB}G>0A^f0!^N7l=$m0OdZuqAOQqLc zX?AEGr1Ht+inZ-Qiwnl@Z0qukd__a!C*CKuGdy5#nD7VUBM^6OCpxCa2A(X;e0&V4 zM&WR8+wErQ7UIc6LY~Q9x%Sn*Tn>>P`^t&idaOEnOd(Ufw#>NoR^1QdhJ8s`h^|R_ zXX`c5*O~Xdvh%q;7L!_!ohf$NfEBmCde|#uVZvEo>OfEq%+Ns7&_f$OR9xsihRpBb z+cjk8LyDm@U{YN>+r46?nn{7Gh(;WhFw6GAxtcKD+YWV?uge>;+q#Xx4!GpRkVZYu zzsF}1)7$?%s9g9CH=Zs+B%M_)+~*j3L0&Q9u7!|+T`^O{xE6qvAP?XWv9_MrZKdo& z%IyU)$Q95AB4!#hT!_dA>4e@zjOBD*Y=XjtMm)V|+IXzjuM;(l+8aA5#Kaz_$rR6! zj>#&^DidYD$nUY(D$mH`9eb|dtV0b{S>H6FBfq>t5`;OxA4Nn{J(+XihF(stSche7$es&~N$epi&PDM_N`As;*9D^L==2Q7Z2zD+CiU(|+-kL*VG+&9!Yb3LgPy?A zm7Z&^qRG_JIxK7-FBzZI3Q<;{`DIxtc48k> zc|0dmX;Z=W$+)qE)~`yn6MdoJ4co;%!`ddy+FV538Y)j(vg}5*k(WK)KWZ3WaOG!8 z!syGn=s{H$odtpqFrT#JGM*utN7B((abXnpDM6w56nhw}OY}0TiTG1#f*VFZr+^-g zbP10`$LPq_;PvrA1XXlyx2uM^mrjTzX}w{yuLo-cOClE8MMk47T25G8M!9Z5ypOSV zAJUBGEg5L2fY)ZGJb^E34R2zJ?}Vf>{~gB!8=5Z) z9y$>5c)=;o0HeHHSuE4U)#vG&KF|I%-cF6f$~pdYJWk_dD}iOA>iA$O$+4%@>JU08 zS`ep)$XLPJ+n0_i@PkF#ri6T8?ZeAot$6JIYHm&P6EB=BiaNY|aA$W0I+nz*zkz_z zkEru!tj!QUffq%)8y0y`T&`fuus-1p>=^hnBiBqD^hXrPs`PY9tU3m0np~rISY09> z`P3s=-kt_cYcxWd{de@}TwSqg*xVhp;E9zCsnXo6z z?f&Sv^U7n4`xr=mXle94HzOdN!2kB~4=%)u&N!+2;z6UYKUDqi-s6AZ!haB;@&B`? z_TRX0%@suz^TRdCb?!vNJYPY8L_}&07uySH9%W^Tc&1pia6y1q#?*Drf}GjGbPjBS zbOPcUY#*$3sL2x4v_i*Y=N7E$mR}J%|GUI(>WEr+28+V z%v5{#e!UF*6~G&%;l*q*$V?&r$Pp^sE^i-0$+RH3ERUUdQ0>rAq2(2QAbG}$y{de( z>{qD~GGuOk559Y@%$?N^1ApVL_a704>8OD%8Y%8B;FCt%AoPu8*D1 zLB5X>b}Syz81pn;xnB}%0FnwazlWfUV)Z-~rZg6~b z6!9J$EcE&sEbzcy?CI~=boWA&eeIa%z(7SE^qgVLz??1Vbc1*aRvc%Mri)AJaAG!p z$X!_9Ds;Zz)f+;%s&dRcJt2==P{^j3bf0M=nJd&xwUGlUFn?H=2W(*2I2Gdu zv!gYCwM10aeus)`RIZSrCK=&oKaO_Ry~D1B5!y0R=%!i2*KfXGYX&gNv_u+n9wiR5 z*e$Zjju&ODRW3phN925%S(jL+bCHv6rZtc?!*`1TyYXT6%Ju=|X;6D@lq$8T zW{Y|e39ioPez(pBH%k)HzFITXHvnD6hw^lIoUMA;qAJ^CU?top1fo@s7xT13Fvn1H z6JWa-6+FJF#x>~+A;D~;VDs26>^oH0EI`IYT2iagy23?nyJ==i{g4%HrAf1-*v zK1)~@&(KkwR7TL}L(A@C_S0G;-GMDy=MJn2$FP5s<%wC)4jC5PXoxrQBFZ_k0P{{s@sz+gX`-!=T8rcB(=7vW}^K6oLWMmp(rwDh}b zwaGGd>yEy6fHv%jM$yJXo5oMAQ>c9j`**}F?MCry;T@47@r?&sKHgVe$MCqk#Z_3S z1GZI~nOEN*P~+UaFGnj{{Jo@16`(qVNtbU>O0Hf57-P>x8Jikp=`s8xWs^dAJ9lCQ z)GFm+=OV%AMVqVATtN@|vp61VVAHRn87}%PC^RAzJ%JngmZTasWBAWsoAqBU+8L8u z4A&Pe?fmTm0?mK-BL9t+{y7o(7jm+RpOhL9KnY#E&qu^}B6=K_dB}*VlSEiC9fn)+V=J;OnN)Ta5v66ic1rG+dGAJ1 z1%Zb_+!$=tQ~lxQrzv3x#CPb?CekEkA}0MYSgx$Jdd}q8+R=ma$|&1a#)TQ=l$1tQ z=tL9&_^vJ)Pk}EDO-va`UCT1m#Uty1{v^A3P~83_#v^ozH}6*9mIjIr;t3Uv%@VeW zGL6(CwCUp)Jq%G0bIG%?{_*Y#5IHf*5M@wPo6A{$Um++Co$wLC=J1aoG93&T7Ho}P z=mGEPP7GbvoG!uD$k(H3A$Z))+i{Hy?QHdk>3xSBXR0j!11O^mEe9RHmw!pvzv?Ua~2_l2Yh~_!s1qS`|0~0)YsbHSz8!mG)WiJE| z2f($6TQtt6L_f~ApQYQKSb=`053LgrQq7G@98#igV>y#i==-nEjQ!XNu9 z~;mE+gtj4IDDNQJ~JVk5Ux6&LCSFL!y=>79kE9=V}J7tD==Ga+IW zX)r7>VZ9dY=V&}DR))xUoV!u(Z|%3ciQi_2jl}3=$Agc(`RPb z8kEBpvY>1FGQ9W$n>Cq=DIpski};nE)`p3IUw1Oz0|wxll^)4dq3;CCY@RyJgFgc# zKouFh!`?Xuo{IMz^xi-h=StCis_M7yq$u) z?XHvw*HP0VgR+KR6wI)jEMX|ssqYvSf*_3W8zVTQzD?3>H!#>InzpSO)@SC8q*ii- z%%h}_#0{4JG;Jm`4zg};BPTGkYamx$Xo#O~lBirRY)q=5M45n{GCfV7h9qwyu1NxOMoP4)jjZMxmT|IQQh0U7C$EbnMN<3)Kk?fFHYq$d|ICu>KbY_hO zTZM+uKHe(cIZfEqyzyYSUBZa8;Fcut-GN!HSA9ius`ltNebF46ZX_BbZNU}}ZOm{M2&nANL9@0qvih15(|`S~z}m&h!u4x~(%MAO$jHRWNfuxWF#B)E&g3ghSQ9|> z(MFaLQj)NE0lowyjvg8z0#m6FIuKE9lDO~Glg}nSb7`~^&#(Lw{}GVOS>U)m8bF}x zVjbXljBm34Cs-yM6TVusr+3kYFjr28STT3g056y3cH5Tmge~ASxBj z%|yb>$eF;WgrcOZf569sDZOVwoo%8>XO>XQOX1OyN9I-SQgrm;U;+#3OI(zrWyow3 zk==|{lt2xrQ%FIXOTejR>;wv(Pb8u8}BUpx?yd(Abh6? zsoO3VYWkeLnF43&@*#MQ9-i-d0t*xN-UEyNKeyNMHw|A(k(_6QKO=nKMCxD(W(Yop zsRQ)QeL4X3Lxp^L%wzi2-WVSsf61dqliPUM7srDB?Wm6Lzn0&{*}|IsKQW;02(Y&| zaTKv|`U(pSzuvR6Rduu$wzK_W-Y-7>7s?G$)U}&uK;<>vU}^^ns@Z!p+9?St1s)dG zK%y6xkPyyS1$~&6v{kl?Md6gwM|>mt6Upm>oa8RLD^8T{0?HC!Z>;(Bob7el(DV6x zi`I)$&E&ngwFS@bi4^xFLAn`=fzTC;aimE^!cMI2n@Vo%Ae-ne`RF((&5y6xsjjAZ zVguVoQ?Z9uk$2ON;ersE%PU*xGO@T*;j1BO5#TuZKEf(mB7|g7pcEA=nYJ{s3vlbg zd4-DUlD{*6o%Gc^N!Nptgay>j6E5;3psI+C3Q!1ZIbeCubW%w4pq9)MSDyB{HLm|k zxv-{$$A*pS@csolri$Ge<4VZ}e~78JOL-EVyrbxKra^d{?|NnPp86!q>t<&IP07?Z z^>~IK^k#OEKgRH+LjllZXk7iA>2cfH6+(e&9ku5poo~6y{GC5>(bRK7hwjiurqAiZ zg*DmtgY}v83IjE&AbiWgMyFbaRUPZ{lYiz$U^&Zt2YjG<%m((&_JUbZcfJ22(>bi5 z!J?<7AySj0JZ&<-qXX;mcV!f~>G=sB0KnjWca4}vrtunD^1TrpfeS^4dvFr!65knK zZh`d;*VOkPs4*-9kL>$GP0`(M!j~B;#x?Ba~&s6CopvO86oM?-? zOw#dIRc;6A6T?B`Qp%^<U5 z19x(ywSH$_N+Io!6;e?`tWaM$`=Db!gzx|lQ${DG!zb1Zl&|{kX0y6xvO1o z220r<-oaS^^R2pEyY;=Qllqpmue|5yI~D|iI!IGt@iod{Opz@*ml^w2bNs)p`M(Io z|E;;m*Xpjd9l)4G#KaWfV(t8YUn@A;nK^#xgv=LtnArX|vWQVuw3}B${h+frU2>9^ z!l6)!Uo4`5k`<<;E(ido7M6lKTgWezNLq>U*=uz&s=cc$1%>VrAeOoUtA|T6gO4>UNqsdK=NF*8|~*sl&wI=x9-EGiq*aqV!(VVXA57 zw9*o6Ir8Lj1npUXvlevtn(_+^X5rzdR>#(}4YcB9O50q97%rW2me5_L=%ffYPUSRc z!vv?Kv>dH994Qi>U(a<0KF6NH5b16enCp+mw^Hb3Xs1^tThFpz!3QuN#}KBbww`(h z7GO)1olDqy6?T$()R7y%NYx*B0k_2IBiZ14&8|JPFxeMF{vW>HF-Vi3+ZOI=+qP}n zw(+!WcTd~4ZJX1!ZM&y!+uyt=&i!+~d(V%GjH;-NsEEv6nS1TERt|RHh!0>W4+4pp z1-*EzAM~i`+1f(VEHI8So`S`akPfPTfq*`l{Fz`hS%k#JS0cjT2mS0#QLGf=J?1`he3W*;m4)ce8*WFq1sdP=~$5RlH1EdWm|~dCvKOi4*I_96{^95p#B<(n!d?B z=o`0{t+&OMwKcxiBECznJcfH!fL(z3OvmxP#oWd48|mMjpE||zdiTBdWelj8&Qosv zZFp@&UgXuvJw5y=q6*28AtxZzo-UUpkRW%ne+Ylf!V-0+uQXBW=5S1o#6LXNtY5!I z%Rkz#(S8Pjz*P7bqB6L|M#Er{|QLae-Y{KA>`^} z@lPjeX>90X|34S-7}ZVXe{wEei1<{*e8T-Nbj8JmD4iwcE+Hg_zhkPVm#=@b$;)h6 z<<6y`nPa`f3I6`!28d@kdM{uJOgM%`EvlQ5B2bL)Sl=|y@YB3KeOzz=9cUW3clPAU z^sYc}xf9{4Oj?L5MOlYxR{+>w=vJjvbyO5}ptT(o6dR|ygO$)nVCvNGnq(6;bHlBd zl?w-|plD8spjDF03g5ip;W3Z z><0{BCq!Dw;h5~#1BuQilq*TwEu)qy50@+BE4bX28+7erX{BD4H)N+7U`AVEuREE8 z;X?~fyhF-x_sRfHIj~6f(+^@H)D=ngP;mwJjxhQUbUdzk8f94Ab%59-eRIq?ZKrwD z(BFI=)xrUlgu(b|hAysqK<}8bslmNNeD=#JW*}^~Nrswn^xw*nL@Tx!49bfJecV&KC2G4q5a!NSv)06A_5N3Y?veAz;Gv+@U3R% z)~UA8-0LvVE{}8LVDOHzp~2twReqf}ODIyXMM6=W>kL|OHcx9P%+aJGYi_Om)b!xe zF40Vntn0+VP>o<$AtP&JANjXBn7$}C@{+@3I@cqlwR2MdwGhVPxlTIcRVu@Ho-wO` z_~Or~IMG)A_`6-p)KPS@cT9mu9RGA>dVh5wY$NM9-^c@N=hcNaw4ITjm;iWSP^ZX| z)_XpaI61<+La+U&&%2a z0za$)-wZP@mwSELo#3!PGTt$uy0C(nTT@9NX*r3Ctw6J~7A(m#8fE)0RBd`TdKfAT zCf@$MAxjP`O(u9s@c0Fd@|}UQ6qp)O5Q5DPCeE6mSIh|Rj{$cAVIWsA=xPKVKxdhg zLzPZ`3CS+KIO;T}0Ip!fAUaNU>++ZJZRk@I(h<)RsJUhZ&Ru9*!4Ptn;gX^~4E8W^TSR&~3BAZc#HquXn)OW|TJ`CTahk+{qe`5+ixON^zA9IFd8)kc%*!AiLu z>`SFoZ5bW-%7}xZ>gpJcx_hpF$2l+533{gW{a7ce^B9sIdmLrI0)4yivZ^(Vh@-1q zFT!NQK$Iz^xu%|EOK=n>ug;(7J4OnS$;yWmq>A;hsD_0oAbLYhW^1Vdt9>;(JIYjf zdb+&f&D4@4AS?!*XpH>8egQvSVX`36jMd>$+RgI|pEg))^djhGSo&#lhS~9%NuWfX zDDH;3T*GzRT@5=7ibO>N-6_XPBYxno@mD_3I#rDD?iADxX`! zh*v8^i*JEMzyN#bGEBz7;UYXki*Xr(9xXax(_1qVW=Ml)kSuvK$coq2A(5ZGhs_pF z$*w}FbN6+QDseuB9=fdp_MTs)nQf!2SlROQ!gBJBCXD&@-VurqHj0wm@LWX-TDmS= z71M__vAok|@!qgi#H&H%Vg-((ZfxPAL8AI{x|VV!9)ZE}_l>iWk8UPTGHs*?u7RfP z5MC&=c6X;XlUzrz5q?(!eO@~* zoh2I*%J7dF!!_!vXoSIn5o|wj1#_>K*&CIn{qSaRc&iFVxt*^20ngCL;QonIS>I5^ zMw8HXm>W0PGd*}Ko)f|~dDd%;Wu_RWI_d;&2g6R3S63Uzjd7dn%Svu-OKpx*o|N>F zZg=-~qLb~VRLpv`k zWSdfHh@?dp=s_X`{yxOlxE$4iuyS;Z-x!*E6eqmEm*j2bE@=ZI0YZ5%Yj29!5+J$4h{s($nakA`xgbO8w zi=*r}PWz#lTL_DSAu1?f%-2OjD}NHXp4pXOsCW;DS@BC3h-q4_l`<))8WgzkdXg3! zs1WMt32kS2E#L0p_|x+x**TFV=gn`m9BWlzF{b%6j-odf4{7a4y4Uaef@YaeuPhU8 zHBvRqN^;$Jizy+ z=zW{E5<>2gp$pH{M@S*!sJVQU)b*J5*bX4h>5VJve#Q6ga}cQ&iL#=(u+KroWrxa%8&~p{WEUF0il=db;-$=A;&9M{Rq`ouZ5m%BHT6%st%saGsD6)fQgLN}x@d3q>FC;=f%O3Cyg=Ke@Gh`XW za@RajqOE9UB6eE=zhG%|dYS)IW)&y&Id2n7r)6p_)vlRP7NJL(x4UbhlcFXWT8?K=%s7;z?Vjts?y2+r|uk8Wt(DM*73^W%pAkZa1Jd zNoE)8FvQA>Z`eR5Z@Ig6kS5?0h;`Y&OL2D&xnnAUzQz{YSdh0k zB3exx%A2TyI)M*EM6htrxSlep!Kk(P(VP`$p0G~f$smld6W1r_Z+o?=IB@^weq>5VYsYZZR@` z&XJFxd5{|KPZmVOSxc@^%71C@;z}}WhbF9p!%yLj3j%YOlPL5s>7I3vj25 z@xmf=*z%Wb4;Va6SDk9cv|r*lhZ`(y_*M@>q;wrn)oQx%B(2A$9(74>;$zmQ!4fN; z>XurIk-7@wZys<+7XL@0Fhe-f%*=(weaQEdR9Eh6>Kl-EcI({qoZqyzziGwpg-GM#251sK_ z=3|kitS!j%;fpc@oWn65SEL73^N&t>Ix37xgs= zYG%eQDJc|rqHFia0!_sm7`@lvcv)gfy(+KXA@E{3t1DaZ$DijWAcA)E0@X?2ziJ{v z&KOYZ|DdkM{}t+@{@*6ge}m%xfjIxi%qh`=^2Rwz@w0cCvZ&Tc#UmCDbVwABrON^x zEBK43FO@weA8s7zggCOWhMvGGE`baZ62cC)VHyy!5Zbt%ieH+XN|OLbAFPZWyC6)p z4P3%8sq9HdS3=ih^0OOlqTPbKuzQ?lBEI{w^ReUO{V?@`ARsL|S*%yOS=Z%sF)>-y z(LAQdhgAcuF6LQjRYfdbD1g4o%tV4EiK&ElLB&^VZHbrV1K>tHTO{#XTo>)2UMm`2 z^t4s;vnMQgf-njU-RVBRw0P0-m#d-u`(kq7NL&2T)TjI_@iKuPAK-@oH(J8?%(e!0Ir$yG32@CGUPn5w4)+9@8c&pGx z+K3GKESI4*`tYlmMHt@br;jBWTei&(a=iYslc^c#RU3Q&sYp zSG){)V<(g7+8W!Wxeb5zJb4XE{I|&Y4UrFWr%LHkdQ;~XU zgy^dH-Z3lmY+0G~?DrC_S4@=>0oM8Isw%g(id10gWkoz2Q%7W$bFk@mIzTCcIB(K8 zc<5h&ZzCdT=9n-D>&a8vl+=ZF*`uTvQviG_bLde*k>{^)&0o*b05x$MO3gVLUx`xZ z43j+>!u?XV)Yp@MmG%Y`+COH2?nQcMrQ%k~6#O%PeD_WvFO~Kct za4XoCM_X!c5vhRkIdV=xUB3xI2NNStK*8_Zl!cFjOvp-AY=D;5{uXj}GV{LK1~IE2 z|KffUiBaStRr;10R~K2VVtf{TzM7FaPm;Y(zQjILn+tIPSrJh&EMf6evaBKIvi42-WYU9Vhj~3< zZSM-B;E`g_o8_XTM9IzEL=9Lb^SPhe(f(-`Yh=X6O7+6ALXnTcUFpI>ekl6v)ZQeNCg2 z^H|{SKXHU*%nBQ@I3It0m^h+6tvI@FS=MYS$ZpBaG7j#V@P2ZuYySbp@hA# ze(kc;P4i_-_UDP?%<6>%tTRih6VBgScKU^BV6Aoeg6Uh(W^#J^V$Xo^4#Ekp ztqQVK^g9gKMTHvV7nb64UU7p~!B?>Y0oFH5T7#BSW#YfSB@5PtE~#SCCg3p^o=NkMk$<8- z6PT*yIKGrvne7+y3}_!AC8NNeI?iTY(&nakN>>U-zT0wzZf-RuyZk^X9H-DT_*wk= z;&0}6LsGtfVa1q)CEUPlx#(ED@-?H<1_FrHU#z5^P3lEB|qsxEyn%FOpjx z3S?~gvoXy~L(Q{Jh6*i~=f%9kM1>RGjBzQh_SaIDfSU_9!<>*Pm>l)cJD@wlyxpBV z4Fmhc2q=R_wHCEK69<*wG%}mgD1=FHi4h!98B-*vMu4ZGW~%IrYSLGU{^TuseqVgV zLP<%wirIL`VLyJv9XG_p8w@Q4HzNt-o;U@Au{7%Ji;53!7V8Rv0^Lu^Vf*sL>R(;c zQG_ZuFl)Mh-xEIkGu}?_(HwkB2jS;HdPLSxVU&Jxy9*XRG~^HY(f0g8Q}iqnVmgjI zfd=``2&8GsycjR?M%(zMjn;tn9agcq;&rR!Hp z$B*gzHsQ~aXw8c|a(L^LW(|`yGc!qOnV(ZjU_Q-4z1&0;jG&vAKuNG=F|H?@m5^N@ zq{E!1n;)kNTJ>|Hb2ODt-7U~-MOIFo%9I)_@7fnX+eMMNh>)V$IXesJpBn|uo8f~#aOFytCT zf9&%MCLf8mp4kwHTcojWmM3LU=#|{3L>E}SKwOd?%{HogCZ_Z1BSA}P#O(%H$;z7XyJ^sjGX;j5 zrzp>|Ud;*&VAU3x#f{CKwY7Vc{%TKKqmB@oTHA9;>?!nvMA;8+Jh=cambHz#J18x~ zs!dF>$*AnsQ{{82r5Aw&^7eRCdvcgyxH?*DV5(I$qXh^zS>us*I66_MbL8y4d3ULj z{S(ipo+T3Ag!+5`NU2sc+@*m{_X|&p#O-SAqF&g_n7ObB82~$p%fXA5GLHMC+#qqL zdt`sJC&6C2)=juQ_!NeD>U8lDVpAOkW*khf7MCcs$A(wiIl#B9HM%~GtQ^}yBPjT@ z+E=|A!Z?A(rwzZ;T}o6pOVqHzTr*i;Wrc%&36kc@jXq~+w8kVrs;%=IFdACoLAcCAmhFNpbP8;s`zG|HC2Gv?I~w4ITy=g$`0qMQdkijLSOtX6xW%Z9Nw<;M- zMN`c7=$QxN00DiSjbVt9Mi6-pjv*j(_8PyV-il8Q-&TwBwH1gz1uoxs6~uU}PrgWB zIAE_I-a1EqlIaGQNbcp@iI8W1sm9fBBNOk(k&iLBe%MCo#?xI$%ZmGA?=)M9D=0t7 zc)Q0LnI)kCy{`jCGy9lYX%mUsDWwsY`;jE(;Us@gmWPqjmXL+Hu#^;k%eT>{nMtzj zsV`Iy6leTA8-PndszF;N^X@CJrTw5IIm!GPeu)H2#FQitR{1p;MasQVAG3*+=9FYK zw*k!HT(YQorfQj+1*mCV458(T5=fH`um$gS38hw(OqVMyunQ;rW5aPbF##A3fGH6h z@W)i9Uff?qz`YbK4c}JzQpuxuE3pcQO)%xBRZp{zJ^-*|oryTxJ-rR+MXJ)!f=+pp z10H|DdGd2exhi+hftcYbM0_}C0ZI-2vh+$fU1acsB-YXid7O|=9L!3e@$H*6?G*Zp z%qFB(sgl=FcC=E4CYGp4CN>=M8#5r!RU!u+FJVlH6=gI5xHVD&k;Ta*M28BsxfMV~ zLz+@6TxnfLhF@5=yQo^1&S}cmTN@m!7*c6z;}~*!hNBjuE>NLVl2EwN!F+)0$R1S! zR|lF%n!9fkZ@gPW|x|B={V6x3`=jS*$Pu0+5OWf?wnIy>Y1MbbGSncpKO0qE(qO=ts z!~@&!N`10S593pVQu4FzpOh!tvg}p%zCU(aV5=~K#bKi zHdJ1>tQSrhW%KOky;iW+O_n;`l9~omqM%sdxdLtI`TrJzN6BQz+7xOl*rM>xVI2~# z)7FJ^Dc{DC<%~VS?@WXzuOG$YPLC;>#vUJ^MmtbSL`_yXtNKa$Hk+l-c!aC7gn(Cg ze?YPYZ(2Jw{SF6MiO5(%_pTo7j@&DHNW`|lD`~{iH+_eSTS&OC*2WTT*a`?|9w1dh zh1nh@$a}T#WE5$7Od~NvSEU)T(W$p$s5fe^GpG+7fdJ9=enRT9$wEk+ZaB>G3$KQO zgq?-rZZnIv!p#>Ty~}c*Lb_jxJg$eGM*XwHUwuQ|o^}b3^T6Bxx{!?va8aC@-xK*H ztJBFvFfsSWu89%@b^l3-B~O!CXs)I6Y}y#0C0U0R0WG zybjroj$io0j}3%P7zADXOwHwafT#uu*zfM!oD$6aJx7+WL%t-@6^rD_a_M?S^>c;z zMK580bZXo1f*L$CuMeM4Mp!;P@}b~$cd(s5*q~FP+NHSq;nw3fbWyH)i2)-;gQl{S zZO!T}A}fC}vUdskGSq&{`oxt~0i?0xhr6I47_tBc`fqaSrMOzR4>0H^;A zF)hX1nfHs)%Zb-(YGX;=#2R6C{BG;k=?FfP?9{_uFLri~-~AJ;jw({4MU7e*d)?P@ zXX*GkNY9ItFjhwgAIWq7Y!ksbMzfqpG)IrqKx9q{zu%Mdl+{Dis#p9q`02pr1LG8R z@As?eG!>IoROgS!@J*to<27coFc1zpkh?w=)h9CbYe%^Q!Ui46Y*HO0mr% zEff-*$ndMNw}H2a5@BsGj5oFfd!T(F&0$<{GO!Qdd?McKkorh=5{EIjDTHU`So>8V zBA-fqVLb2;u7UhDV1xMI?y>fe3~4urv3%PX)lDw+HYa;HFkaLqi4c~VtCm&Ca+9C~ zge+67hp#R9`+Euq59WhHX&7~RlXn=--m8$iZ~~1C8cv^2(qO#X0?vl91gzUKBeR1J z^p4!!&7)3#@@X&2aF2-)1Ffcc^F8r|RtdL2X%HgN&XU-KH2SLCbpw?J5xJ*!F-ypZ zMG%AJ!Pr&}`LW?E!K~=(NJxuSVTRCGJ$2a*Ao=uUDSys!OFYu!Vs2IT;xQ6EubLIl z+?+nMGeQQhh~??0!s4iQ#gm3!BpMpnY?04kK375e((Uc7B3RMj;wE?BCoQGu=UlZt!EZ1Q*auI)dj3Jj{Ujgt zW5hd~-HWBLI_3HuO) zNrb^XzPsTIb=*a69wAAA3J6AAZZ1VsYbIG}a`=d6?PjM)3EPaDpW2YP$|GrBX{q*! z$KBHNif)OKMBCFP5>!1d=DK>8u+Upm-{hj5o|Wn$vh1&K!lVfDB&47lw$tJ?d5|=B z^(_9=(1T3Fte)z^>|3**n}mIX;mMN5v2F#l(q*CvU{Ga`@VMp#%rQkDBy7kYbmb-q z<5!4iuB#Q_lLZ8}h|hPODI^U6`gzLJre9u3k3c#%86IKI*^H-@I48Bi*@avYm4v!n0+v zWu{M{&F8#p9cx+gF0yTB_<2QUrjMPo9*7^-uP#~gGW~y3nfPAoV%amgr>PSyVAd@l)}8#X zR5zV6t*uKJZL}?NYvPVK6J0v4iVpwiN|>+t3aYiZSp;m0!(1`bHO}TEtWR1tY%BPB z(W!0DmXbZAsT$iC13p4f>u*ZAy@JoLAkJhzFf1#4;#1deO8#8d&89}en&z!W&A3++^1(;>0SB1*54d@y&9Pn;^IAf3GiXbfT`_>{R+Xv; zQvgL>+0#8-laO!j#-WB~(I>l0NCMt_;@Gp_f0#^c)t?&#Xh1-7RR0@zPyBz!U#0Av zT?}n({(p?p7!4S2ZBw)#KdCG)uPnZe+U|0{BW!m)9 zi_9$F?m<`2!`JNFv+w8MK_K)qJ^aO@7-Ig>cM4-r0bi=>?B_2mFNJ}aE3<+QCzRr*NA!QjHw# z`1OsvcoD0?%jq{*7b!l|L1+Tw0TTAM4XMq7*ntc-Ived>Sj_ZtS|uVdpfg1_I9knY z2{GM_j5sDC7(W&}#s{jqbybqJWyn?{PW*&cQIU|*v8YGOKKlGl@?c#TCnmnAkAzV- zmK={|1G90zz=YUvC}+fMqts0d4vgA%t6Jhjv?d;(Z}(Ep8fTZfHA9``fdUHkA+z3+ zhh{ohP%Bj?T~{i0sYCQ}uC#5BwN`skI7`|c%kqkyWIQ;!ysvA8H`b-t()n6>GJj6xlYDu~8qX{AFo$Cm3d|XFL=4uvc?Keb zzb0ZmMoXca6Mob>JqkNuoP>B2Z>D`Q(TvrG6m`j}-1rGP!g|qoL=$FVQYxJQjFn33lODt3Wb1j8VR zlR++vIT6^DtYxAv_hxupbLLN3e0%A%a+hWTKDV3!Fjr^cWJ{scsAdfhpI)`Bms^M6 zQG$waKgFr=c|p9Piug=fcJvZ1ThMnNhQvBAg-8~b1?6wL*WyqXhtj^g(Ke}mEfZVM zJuLNTUVh#WsE*a6uqiz`b#9ZYg3+2%=C(6AvZGc=u&<6??!slB1a9K)=VL zY9EL^mfyKnD zSJyYBc_>G;5RRnrNgzJz#Rkn3S1`mZgO`(r5;Hw6MveN(URf_XS-r58Cn80K)ArH4 z#Rrd~LG1W&@ttw85cjp8xV&>$b%nSXH_*W}7Ch2pg$$c0BdEo-HWRTZcxngIBJad> z;C>b{jIXjb_9Jis?NZJsdm^EG}e*pR&DAy0EaSGi3XWTa(>C%tz1n$u?5Fb z1qtl?;_yjYo)(gB^iQq?=jusF%kywm?CJP~zEHi0NbZ);$(H$w(Hy@{i>$wcVRD_X|w-~(0Z9BJyh zhNh;+eQ9BEIs;tPz%jSVnfCP!3L&9YtEP;svoj_bNzeGSQIAjd zBss@A;)R^WAu-37RQrM%{DfBNRx>v!G31Z}8-El9IOJlb_MSoMu2}GDYycNaf>uny z+8xykD-7ONCM!APry_Lw6-yT>5!tR}W;W`C)1>pxSs5o1z#j7%m=&=7O4hz+Lsqm` z*>{+xsabZPr&X=}G@obTb{nPTkccJX8w3CG7X+1+t{JcMabv~UNv+G?txRqXib~c^Mo}`q{$`;EBNJ;#F*{gvS12kV?AZ%O0SFB$^ zn+}!HbmEj}w{Vq(G)OGAzH}R~kS^;(-s&=ectz8vN!_)Yl$$U@HNTI-pV`LSj7Opu zTZ5zZ)-S_{GcEQPIQXLQ#oMS`HPu{`SQiAZ)m1at*Hy%3xma|>o`h%E%8BEbi9p0r zVjcsh<{NBKQ4eKlXU|}@XJ#@uQw*$4BxKn6#W~I4T<^f99~(=}a`&3(ur8R9t+|AQ zWkQx7l}wa48-jO@ft2h+7qn%SJtL%~890FG0s5g*kNbL3I&@brh&f6)TlM`K^(bhr zJWM6N6x3flOw$@|C@kPi7yP&SP?bzP-E|HSXQXG>7gk|R9BTj`e=4de9C6+H7H7n# z#GJeVs1mtHhLDmVO?LkYRQc`DVOJ_vdl8VUihO-j#t=0T3%Fc1f9F73ufJz*adn*p zc%&vi(4NqHu^R>sAT_0EDjVR8bc%wTz#$;%NU-kbDyL_dg0%TFafZwZ?5KZpcuaO54Z9hX zD$u>q!-9`U6-D`E#`W~fIfiIF5_m6{fvM)b1NG3xf4Auw;Go~Fu7cth#DlUn{@~yu z=B;RT*dp?bO}o%4x7k9v{r=Y@^YQ^UUm(Qmliw8brO^=NP+UOohLYiaEB3^DB56&V zK?4jV61B|1Uj_5fBKW;8LdwOFZKWp)g{B%7g1~DgO&N& z#lisxf?R~Z@?3E$Mms$$JK8oe@X`5m98V*aV6Ua}8Xs2#A!{x?IP|N(%nxsH?^c{& z@vY&R1QmQs83BW28qAmJfS7MYi=h(YK??@EhjL-t*5W!p z^gYX!Q6-vBqcv~ruw@oMaU&qp0Fb(dbVzm5xJN%0o_^@fWq$oa3X?9s%+b)x4w-q5Koe(@j6Ez7V@~NRFvd zfBH~)U5!ix3isg`6be__wBJp=1@yfsCMw1C@y+9WYD9_C%{Q~7^0AF2KFryfLlUP# zwrtJEcH)jm48!6tUcxiurAMaiD04C&tPe6DI0#aoqz#Bt0_7_*X*TsF7u*zv(iEfA z;$@?XVu~oX#1YXtceQL{dSneL&*nDug^OW$DSLF0M1Im|sSX8R26&)<0Fbh^*l6!5wfSu8MpMoh=2l z^^0Sr$UpZp*9oqa23fcCfm7`ya2<4wzJ`Axt7e4jJrRFVf?nY~2&tRL* zd;6_njcz01c>$IvN=?K}9ie%Z(BO@JG2J}fT#BJQ+f5LFSgup7i!xWRKw6)iITjZU z%l6hPZia>R!`aZjwCp}I zg)%20;}f+&@t;(%5;RHL>K_&7MH^S+7<|(SZH!u zznW|jz$uA`P9@ZWtJgv$EFp>)K&Gt+4C6#*khZQXS*S~6N%JDT$r`aJDs9|uXWdbg zBwho$phWx}x!qy8&}6y5Vr$G{yGSE*r$^r{}pw zVTZKvikRZ`J_IJrjc=X1uw?estdwm&bEahku&D04HD+0Bm~q#YGS6gp!KLf$A{%Qd z&&yX@Hp>~(wU{|(#U&Bf92+1i&Q*-S+=y=3pSZy$#8Uc$#7oiJUuO{cE6=tsPhwPe| zxQpK>`Dbka`V)$}e6_OXKLB%i76~4N*zA?X+PrhH<&)}prET;kel24kW%+9))G^JI zsq7L{P}^#QsZViX%KgxBvEugr>ZmFqe^oAg?{EI=&_O#e)F3V#rc z8$4}0Zr19qd3tE4#$3_f=Bbx9oV6VO!d3(R===i-7p=Vj`520w0D3W6lQfY48}!D* z&)lZMG;~er2qBoI2gsX+Ts-hnpS~NYRDtPd^FPzn!^&yxRy#CSz(b&E*tL|jIkq|l zf%>)7Dtu>jCf`-7R#*GhGn4FkYf;B$+9IxmqH|lf6$4irg{0ept__%)V*R_OK=T06 zyT_m-o@Kp6U{l5h>W1hGq*X#8*y@<;vsOFqEjTQXFEotR+{3}ODDnj;o0@!bB5x=N z394FojuGOtVKBlVRLtHp%EJv_G5q=AgF)SKyRN5=cGBjDWv4LDn$IL`*=~J7u&Dy5 zrMc83y+w^F&{?X(KOOAl-sWZDb{9X9#jrQtmrEXD?;h-}SYT7yM(X_6qksM=K_a;Z z3u0qT0TtaNvDER_8x*rxXw&C^|h{P1qxK|@pS7vdlZ#P z7PdB7MmC2}%sdzAxt>;WM1s0??`1983O4nFK|hVAbHcZ3x{PzytQLkCVk7hA!Lo` zEJH?4qw|}WH{dc4z%aB=0XqsFW?^p=X}4xnCJXK%c#ItOSjdSO`UXJyuc8bh^Cf}8 z@Ht|vXd^6{Fgai8*tmyRGmD_s_nv~r^Fy7j`Bu`6=G)5H$i7Q7lvQnmea&TGvJp9a|qOrUymZ$6G|Ly z#zOCg++$3iB$!6!>215A4!iryregKuUT344X)jQb3|9qY>c0LO{6Vby05n~VFzd?q zgGZv&FGlkiH*`fTurp>B8v&nSxNz)=5IF$=@rgND4d`!AaaX;_lK~)-U8la_Wa8i?NJC@BURO*sUW)E9oyv3RG^YGfN%BmxzjlT)bp*$<| zX3tt?EAy<&K+bhIuMs-g#=d1}N_?isY)6Ay$mDOKRh z4v1asEGWoAp=srraLW^h&_Uw|6O+r;wns=uwYm=JN4Q!quD8SQRSeEcGh|Eb5Jg8m zOT}u;N|x@aq)=&;wufCc^#)5U^VcZw;d_wwaoh9$p@Xrc{DD6GZUqZ ziC6OT^zSq@-lhbgR8B+e;7_Giv;DK5gn^$bs<6~SUadiosfewWDJu`XsBfOd1|p=q zE>m=zF}!lObA%ePey~gqU8S6h-^J2Y?>7)L2+%8kV}Gp=h`Xm_}rlm)SyUS=`=S7msKu zC|T!gPiI1rWGb1z$Md?0YJQ;%>uPLOXf1Z>N~`~JHJ!^@D5kSXQ4ugnFZ>^`zH8CAiZmp z6Ms|#2gcGsQ{{u7+Nb9sA?U>(0e$5V1|WVwY`Kn)rsnnZ4=1u=7u!4WexZD^IQ1Jk zfF#NLe>W$3m&C^ULjdw+5|)-BSHwpegdyt9NYC{3@QtMfd8GrIWDu`gd0nv-3LpGCh@wgBaG z176tikL!_NXM+Bv#7q^cyn9$XSeZR6#!B4JE@GVH zoobHZN_*RF#@_SVYKkQ_igme-Y5U}cV(hkR#k1c{bQNMji zU7aE`?dHyx=1`kOYZo_8U7?3-7vHOp`Qe%Z*i+FX!s?6huNp0iCEW-Z7E&jRWmUW_ z67j>)Ew!yq)hhG4o?^z}HWH-e=es#xJUhDRc4B51M4~E-l5VZ!&zQq`gWe`?}#b~7w1LH4Xa-UCT5LXkXQWheBa2YJYbyQ zl1pXR%b(KCXMO0OsXgl0P0Og<{(@&z1aokU-Pq`eQq*JYgt8xdFQ6S z6Z3IFSua8W&M#`~*L#r>Jfd6*BzJ?JFdBR#bDv$_0N!_5vnmo@!>vULcDm`MFU823 zpG9pqjqz^FE5zMDoGqhs5OMmC{Y3iVcl>F}5Rs24Y5B^mYQ;1T&ks@pIApHOdrzXF z-SdX}Hf{X;TaSxG_T$0~#RhqKISGKNK47}0*x&nRIPtmdwxc&QT3$8&!3fWu1eZ_P zJveQj^hJL#Sn!*4k`3}(d(aasl&7G0j0-*_2xtAnoX1@9+h zO#c>YQg60Z;o{Bi=3i7S`Ic+ZE>K{(u|#)9y}q*j8uKQ1^>+(BI}m%1v3$=4ojGBc zm+o1*!T&b}-lVvZqIUBc8V}QyFEgm#oyIuC{8WqUNV{Toz`oxhYpP!_p2oHHh5P@iB*NVo~2=GQm+8Yrkm2Xjc_VyHg1c0>+o~@>*Qzo zHVBJS>$$}$_4EniTI;b1WShX<5-p#TPB&!;lP!lBVBbLOOxh6FuYloD%m;n{r|;MU3!q4AVkua~fieeWu2 zQAQ$ue(IklX6+V;F1vCu-&V?I3d42FgWgsb_e^29ol}HYft?{SLf>DrmOp9o!t>I^ zY7fBCk+E8n_|apgM|-;^=#B?6RnFKlN`oR)`e$+;D=yO-(U^jV;rft^G_zl`n7qnM zL z*-Y4Phq+ZI1$j$F-f;`CD#|`-T~OM5Q>x}a>B~Gb3-+9i>Lfr|Ca6S^8g*{*?_5!x zH_N!SoRP=gX1?)q%>QTY!r77e2j9W(I!uAz{T`NdNmPBBUzi2{`XMB^zJGGwFWeA9 z{fk33#*9SO0)DjROug+(M)I-pKA!CX;IY(#gE!UxXVsa)X!UftIN98{pt#4MJHOhY zM$_l}-TJlxY?LS6Nuz1T<44m<4i^8k@D$zuCPrkmz@sdv+{ciyFJG2Zwy&%c7;atIeTdh!a(R^QXnu1Oq1b42*OQFWnyQ zWeQrdvP|w_idy53Wa<{QH^lFmEd+VlJkyiC>6B#s)F;w-{c;aKIm;Kp50HnA-o3lY z9B~F$gJ@yYE#g#X&3ADx&tO+P_@mnQTz9gv30_sTsaGXkfNYXY{$(>*PEN3QL>I!k zp)KibPhrfX3%Z$H6SY`rXGYS~143wZrG2;=FLj50+VM6soI~up_>fU(2Wl@{BRsMi zO%sL3x?2l1cXTF)k&moNsHfQrQ+wu(gBt{sk#CU=UhrvJIncy@tJX5klLjgMn>~h= zg|FR&;@eh|C7`>s_9c~0-{IAPV){l|Ts`i=)AW;d9&KPc3fMeoTS%8@V~D8*h;&(^>yjT84MM}=%#LS7shLAuuj(0VAYoozhWjq z4LEr?wUe2^WGwdTIgWBkDUJa>YP@5d9^Rs$kCXmMRxuF*YMVrn?0NFyPl}>`&dqZb z<5eqR=ZG3>n2{6v6BvJ`YBZeeTtB88TAY(x0a58EWyuf>+^|x8Qa6wA|1Nb_p|nA zWWa}|z8a)--Wj`LqyFk_a3gN2>5{Rl_wbW?#by7&i*^hRknK%jwIH6=dQ8*-_{*x0j^DUfMX0`|K@6C<|1cgZ~D(e5vBFFm;HTZF(!vT8=T$K+|F)x3kqzBV4-=p1V(lzi(s7jdu0>LD#N=$Lk#3HkG!a zIF<7>%B7sRNzJ66KrFV76J<2bdYhxll0y2^_rdG=I%AgW4~)1Nvz=$1UkE^J%BxLo z+lUci`UcU062os*=`-j4IfSQA{w@y|3}Vk?i;&SSdh8n+$iHA#%ERL{;EpXl6u&8@ zzg}?hkEOUOJt?ZL=pWZFJ19mI1@P=$U5*Im1e_8Z${JsM>Ov?nh8Z zP5QvI!{Jy@&BP48%P2{Jr_VgzW;P@7)M9n|lDT|Ep#}7C$&ud&6>C^5ZiwKIg2McPU(4jhM!BD@@L(Gd*Nu$ji(ljZ<{FIeW_1Mmf;76{LU z-ywN~=uNN)Xi6$<12A9y)K%X|(W0p|&>>4OXB?IiYr||WKDOJPxiSe01NSV-h24^L z_>m$;|C+q!Mj**-qQ$L-*++en(g|hw;M!^%_h-iDjFHLo-n3JpB;p?+o2;`*jpvJU zLY^lt)Un4joij^^)O(CKs@7E%*!w>!HA4Q?0}oBJ7Nr8NQ7QmY^4~jvf0-`%waOLn zdNjAPaC0_7c|RVhw)+71NWjRi!y>C+Bl;Z`NiL^zn2*0kmj5gyhCLCxts*cWCdRI| zjsd=sT5BVJc^$GxP~YF$-U{-?kW6r@^vHXB%{CqYzU@1>dzf#3SYedJG-Rm6^RB7s zGM5PR(yKPKR)>?~vpUIeTP7A1sc8-knnJk*9)3t^e%izbdm>Y=W{$wm(cy1RB-19i za#828DMBY+ps#7Y8^6t)=Ea@%Nkt)O6JCx|ybC;Ap}Z@Zw~*}3P>MZLPb4Enxz9Wf zssobT^(R@KuShj8>@!1M7tm|2%-pYYDxz-5`rCbaTCG5{;Uxm z*g=+H1X8{NUvFGzz~wXa%Eo};I;~`37*WrRU&K0dPSB$yk(Z*@K&+mFal^?c zurbqB-+|Kb5|sznT;?Pj!+kgFY1#Dr;_%A(GIQC{3ct|{*Bji%FNa6c-thbpBkA;U zURV!Dr&X{0J}iht#-Qp2=xzuh(fM>zRoiGrYl5ttw2#r34gC41CCOC31m~^UPTK@s z6;A@)7O7_%C)>bnAXerYuAHdE93>j2N}H${zEc6&SbZ|-fiG*-qtGuy-qDelH(|u$ zorf8_T6Zqe#Ub!+e3oSyrskt_HyW_^5lrWt#30l)tHk|j$@YyEkXUOV;6B51L;M@=NIWZXU;GrAa(LGxO%|im%7F<-6N;en0Cr zLH>l*y?pMwt`1*cH~LdBPFY_l;~`N!Clyfr;7w<^X;&(ZiVdF1S5e(+Q%60zgh)s4 zn2yj$+mE=miVERP(g8}G4<85^-5f@qxh2ec?n+$A_`?qN=iyT1?U@t?V6DM~BIlBB z>u~eXm-aE>R0sQy!-I4xtCNi!!qh?R1!kKf6BoH2GG{L4%PAz0{Sh6xpuyI%*~u)s z%rLuFl)uQUCBQAtMyN;%)zFMx4loh7uTfKeB2Xif`lN?2gq6NhWhfz0u5WP9J>=V2 zo{mLtSy&BA!mSzs&CrKWq^y40JF5a&GSXIi2= z{EYb59J4}VwikL4P=>+mc6{($FNE@e=VUwG+KV21;<@lrN`mnz5jYGASyvz7BOG_6(p^eTxD-4O#lROgon;R35=|nj#eHIfJBYPWG>H>`dHKCDZ3`R{-?HO0mE~(5_WYcFmp8sU?wr*UkAQiNDGc6T zA%}GOLXlOWqL?WwfHO8MB#8M8*~Y*gz;1rWWoVSXP&IbKxbQ8+s%4Jnt?kDsq7btI zCDr0PZ)b;B%!lu&CT#RJzm{l{2fq|BcY85`w~3LSK<><@(2EdzFLt9Y_`;WXL6x`0 zDoQ?=?I@Hbr;*VVll1Gmd8*%tiXggMK81a+T(5Gx6;eNb8=uYn z5BG-0g>pP21NPn>$ntBh>`*})Fl|38oC^9Qz>~MAazH%3Q~Qb!ALMf$srexgPZ2@&c~+hxRi1;}+)-06)!#Mq<6GhP z-Q?qmgo${aFBApb5p}$1OJKTClfi8%PpnczyVKkoHw7Ml9e7ikrF0d~UB}i3vizos zXW4DN$SiEV9{faLt5bHy2a>33K%7Td-n5C*N;f&ZqAg#2hIqEb(y<&f4u5BWJ>2^4 z414GosL=Aom#m&=x_v<0-fp1r%oVJ{T-(xnomNJ(Dryv zh?vj+%=II_nV+@NR+(!fZZVM&(W6{6%9cm+o+Z6}KqzLw{(>E86uA1`_K$HqINlb1 zKelh3-jr2I9V?ych`{hta9wQ2c9=MM`2cC{m6^MhlL2{DLv7C^j z$xXBCnDl_;l|bPGMX@*tV)B!c|4oZyftUlP*?$YU9C_eAsuVHJ58?)zpbr30P*C`T z7y#ao`uE-SOG(Pi+`$=e^mle~)pRrdwL5)N;o{gpW21of(QE#U6w%*C~`v-z0QqBML!!5EeYA5IQB0 z^l01c;L6E(iytN!LhL}wfwP7W9PNAkb+)Cst?qg#$n;z41O4&v+8-zPs+XNb-q zIeeBCh#ivnFLUCwfS;p{LC0O7tm+Sf9Jn)~b%uwP{%69;QC)Ok0t%*a5M+=;y8j=v z#!*pp$9@!x;UMIs4~hP#pnfVc!%-D<+wsG@R2+J&%73lK|2G!EQC)O05TCV=&3g)C!lT=czLpZ@Sa%TYuoE?v8T8`V;e$#Zf2_Nj6nvBgh1)2 GZ~q4|mN%#X literal 0 HcmV?d00001 diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties new file mode 100644 index 0000000..fbacf71 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties @@ -0,0 +1,7 @@ +distributionBase=GRADLE_USER_HOME +distributionPath=permwrapper/dists +distributionUrl=https\://services.gradle.org/distributions/gradle-8.10.2-bin.zip +networkTimeout=10000 +validateDistributionUrl=true +zipStoreBase=GRADLE_USER_HOME +zipStorePath=permwrapper/dists diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew new file mode 100644 index 0000000..f5feea6 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew @@ -0,0 +1,252 @@ +#!/bin/sh + +# +# Copyright © 2015-2021 the original authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# https://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +# + +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# +############################################################################## + +# Attempt to set APP_HOME + +# Resolve links: $0 may be a link +app_path=$0 + +# Need this for daisy-chained symlinks. +while + APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path + [ -h "$app_path" ] +do + ls=$( ls -ld "$app_path" ) + link=${ls#*' -> '} + case $link in #( + /*) app_path=$link ;; #( + *) app_path=$APP_HOME$link ;; + esac +done + +# This is normally unused +# shellcheck disable=SC2034 +APP_BASE_NAME=${0##*/} +# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) +APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s +' "$PWD" ) || exit + +# Use the maximum available, or set MAX_FD != -1 to use that value. +MAX_FD=maximum + +warn () { + echo "$*" +} >&2 + +die () { + echo + echo "$*" + echo + exit 1 +} >&2 + +# OS specific support (must be 'true' or 'false'). +cygwin=false +msys=false +darwin=false +nonstop=false +case "$( uname )" in #( + CYGWIN* ) cygwin=true ;; #( + Darwin* ) darwin=true ;; #( + MSYS* | MINGW* ) msys=true ;; #( + NONSTOP* ) nonstop=true ;; +esac + +CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar + + +# Determine the Java command to use to start the JVM. +if [ -n "$JAVA_HOME" ] ; then + if [ -x "$JAVA_HOME/jre/sh/java" ] ; then + # IBM's JDK on AIX uses strange locations for the executables + JAVACMD=$JAVA_HOME/jre/sh/java + else + JAVACMD=$JAVA_HOME/bin/java + fi + if [ ! -x "$JAVACMD" ] ; then + die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +else + JAVACMD=java + if ! command -v java >/dev/null 2>&1 + then + die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +fi + +# Increase the maximum file descriptors if we can. +if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then + case $MAX_FD in #( + max*) + # In POSIX sh, ulimit -H is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 + MAX_FD=$( ulimit -H -n ) || + warn "Could not query maximum file descriptor limit" + esac + case $MAX_FD in #( + '' | soft) :;; #( + *) + # In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 + ulimit -n "$MAX_FD" || + warn "Could not set maximum file descriptor limit to $MAX_FD" + esac +fi + +# Collect all arguments for the java command, stacking in reverse order: +# * args from the command line +# * the main class name +# * -classpath +# * -D...appname settings +# * --module-path (only if needed) +# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. + +# For Cygwin or MSYS, switch paths to Windows format before running java +if "$cygwin" || "$msys" ; then + APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) + CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) + + JAVACMD=$( cygpath --unix "$JAVACMD" ) + + # Now convert the arguments - kludge to limit ourselves to /bin/sh + for arg do + if + case $arg in #( + -*) false ;; # don't mess with options #( + /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath + [ -e "$t" ] ;; #( + *) false ;; + esac + then + arg=$( cygpath --path --ignore --mixed "$arg" ) + fi + # Roll the args list around exactly as many times as the number of + # args, so each arg winds up back in the position where it started, but + # possibly modified. + # + # NB: a `for` loop captures its iteration list before it begins, so + # changing the positional parameters here affects neither the number of + # iterations, nor the values presented in `arg`. + shift # remove old arg + set -- "$@" "$arg" # push replacement arg + done +fi + + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Collect all arguments for the java command: +# * DEFAULT_JVM_OPTS, JAVA_OPTS, JAVA_OPTS, and optsEnvironmentVar are not allowed to contain shell fragments, +# and any embedded shellness will be escaped. +# * For example: A user cannot expect ${Hostname} to be expanded, as it is an environment variable and will be +# treated as '${Hostname}' itself on the command line. + +set -- \ + "-Dorg.gradle.appname=$APP_BASE_NAME" \ + -classpath "$CLASSPATH" \ + org.gradle.wrapper.GradleWrapperMain \ + "$@" + +# Stop when "xargs" is not available. +if ! command -v xargs >/dev/null 2>&1 +then + die "xargs is not available" +fi + +# Use "xargs" to parse quoted args. +# +# With -n1 it outputs one arg per line, with the quotes and backslashes removed. +# +# In Bash we could simply go: +# +# readarray ARGS < <( xargs -n1 <<<"$var" ) && +# set -- "${ARGS[@]}" "$@" +# +# but POSIX shell has neither arrays nor command substitution, so instead we +# post-process each arg (as a line of input to sed) to backslash-escape any +# character that might be a shell metacharacter, then use eval to reverse +# that process (while maintaining the separation between arguments), and wrap +# the whole thing up as a single "set" statement. +# +# This will of course break if any of these variables contains a newline or +# an unmatched quote. +# + +eval "set -- $( + printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | + xargs -n1 | + sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | + tr '\n' ' ' + )" '"$@"' + +exec "$JAVACMD" "$@" diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat new file mode 100644 index 0000000..9d21a21 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat @@ -0,0 +1,94 @@ +@rem +@rem Copyright 2015 the original author or authors. +@rem +@rem Licensed under the Apache License, Version 2.0 (the "License"); +@rem you may not use this file except in compliance with the License. +@rem You may obtain a copy of the License at +@rem +@rem https://www.apache.org/licenses/LICENSE-2.0 +@rem +@rem Unless required by applicable law or agreed to in writing, software +@rem distributed under the License is distributed on an "AS IS" BASIS, +@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +@rem See the License for the specific language governing permissions and +@rem limitations under the License. +@rem +@rem SPDX-License-Identifier: Apache-2.0 +@rem + +@if "%DEBUG%"=="" @echo off +@rem ########################################################################## +@rem +@rem Gradle startup script for Windows +@rem +@rem ########################################################################## + +@rem Set local scope for the variables with windows NT shell +if "%OS%"=="Windows_NT" setlocal + +set DIRNAME=%~dp0 +if "%DIRNAME%"=="" set DIRNAME=. +@rem This is normally unused +set APP_BASE_NAME=%~n0 +set APP_HOME=%DIRNAME% + +@rem Resolve any "." and ".." in APP_HOME to make it shorter. +for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi + +@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" + +@rem Find java.exe +if defined JAVA_HOME goto findJavaFromJavaHome + +set JAVA_EXE=java.exe +%JAVA_EXE% -version >NUL 2>&1 +if %ERRORLEVEL% equ 0 goto execute + +echo. 1>&2 +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 + +goto fail + +:findJavaFromJavaHome +set JAVA_HOME=%JAVA_HOME:"=% +set JAVA_EXE=%JAVA_HOME%/bin/java.exe + +if exist "%JAVA_EXE%" goto execute + +echo. 1>&2 +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 + +goto fail + +:execute +@rem Setup the command line + +set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar + + +@rem Execute Gradle +"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* + +:end +@rem End local scope for the variables with windows NT shell +if %ERRORLEVEL% equ 0 goto mainEnd + +:fail +rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of +rem the _cmd.exe /c_ return code! +set EXIT_CODE=%ERRORLEVEL% +if %EXIT_CODE% equ 0 set EXIT_CODE=1 +if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% +exit /b %EXIT_CODE% + +:mainEnd +if "%OS%"=="Windows_NT" endlocal + +:omega diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle b/src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle new file mode 100644 index 0000000..969c7b0 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle @@ -0,0 +1,30 @@ +import org.gradle.internal.os.OperatingSystem + +pluginManagement { + repositories { + mavenLocal() + gradlePluginPortal() + String frcYear = '2025' + File frcHome + if (OperatingSystem.current().isWindows()) { + String publicFolder = System.getenv('PUBLIC') + if (publicFolder == null) { + publicFolder = "C:\\Users\\Public" + } + def homeRoot = new File(publicFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } else { + def userFolder = System.getProperty("user.home") + def homeRoot = new File(userFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } + def frcHomeMaven = new File(frcHome, 'maven') + maven { + name 'frcHome' + url frcHomeMaven + } + } +} + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt new file mode 100644 index 0000000..bb82515 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt @@ -0,0 +1,3 @@ +Files placed in this directory will be deployed to the RoboRIO into the +'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function +to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java new file mode 100644 index 0000000..c50ba05 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java @@ -0,0 +1,19 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +/** + * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean + * constants. This class should not be used for any other purpose. All constants should be declared + * globally (i.e. public static). Do not put anything functional in this class. + * + *

It is advised to statically import this class (or one of its inner classes) wherever the + * constants are needed, to reduce verbosity. + */ +public final class Constants { + public static class OperatorConstants { + public static final int kDriverControllerPort = 0; + } +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java new file mode 100644 index 0000000..8776e5d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java new file mode 100644 index 0000000..c711f35 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java @@ -0,0 +1,100 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandScheduler; + +/** + * The methods in this class are called automatically corresponding to each mode, as described in + * the TimedRobot documentation. If you change the name of this class or the package after creating + * this project, you must also update the Main.java file in the project. + */ +public class Robot extends TimedRobot { + private Command m_autonomousCommand; + + private final RobotContainer m_robotContainer; + + /** + * This function is run when the robot is first started up and should be used for any + * initialization code. + */ + public Robot() { + // Instantiate our RobotContainer. This will perform all our button bindings, and put our + // autonomous chooser on the dashboard. + m_robotContainer = new RobotContainer(); + } + + /** + * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics + * that you want ran during disabled, autonomous, teleoperated and test. + * + *

This runs after the mode specific periodic functions, but before LiveWindow and + * SmartDashboard integrated updating. + */ + @Override + public void robotPeriodic() { + // Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled + // commands, running already-scheduled commands, removing finished or interrupted commands, + // and running subsystem periodic() methods. This must be called from the robot's periodic + // block in order for anything in the Command-based framework to work. + CommandScheduler.getInstance().run(); + } + + /** This function is called once each time the robot enters Disabled mode. */ + @Override + public void disabledInit() {} + + @Override + public void disabledPeriodic() {} + + /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ + @Override + public void autonomousInit() { + + // schedule the autonomous command (example) + if (m_autonomousCommand != null) { + m_autonomousCommand.schedule(); + } + } + + /** This function is called periodically during autonomous. */ + @Override + public void autonomousPeriodic() {} + + @Override + public void teleopInit() { + // This makes sure that the autonomous stops running when + // teleop starts running. If you want the autonomous to + // continue until interrupted by another command, remove + // this line or comment it out. + if (m_autonomousCommand != null) { + m_autonomousCommand.cancel(); + } + } + + /** This function is called periodically during operator control. */ + @Override + public void teleopPeriodic() {} + + @Override + public void testInit() { + // Cancels all running commands at the start of test mode. + CommandScheduler.getInstance().cancelAll(); + } + + /** This function is called periodically during test mode. */ + @Override + public void testPeriodic() {} + + /** This function is called once when the robot is first started up. */ + @Override + public void simulationInit() {} + + /** This function is called periodically whilst in simulation. */ + @Override + public void simulationPeriodic() {} +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java new file mode 100644 index 0000000..9c94d46 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java @@ -0,0 +1,59 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +import frc.robot.Constants.OperatorConstants; +import frc.robot.commands.Intake; +import frc.robot.subsystems.IntakeSubsystem; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import edu.wpi.first.wpilibj2.command.button.Trigger; + +/** + * This class is where the bulk of the robot should be declared. Since Command-based is a + * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} + * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including + * subsystems, commands, and trigger mappings) should be declared here. + */ +public class RobotContainer { + // The robot's subsystems and commands are defined here... + private final IntakeSubsystem IntakeSubsystem = new IntakeSubsystem(); + + // Replace with CommandPS4Controller or CommandJoystick if needed + private final CommandXboxController m_driverController = + new CommandXboxController(OperatorConstants.kDriverControllerPort); + + /** The container for the robot. Contains subsystems, OI devices, and commands. */ + public RobotContainer() { + // Configure the trigger bindings + configureBindings(); + } + + /** + * Use this method to define your trigger->command mappings. Triggers can be created via the + * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary + * predicate, or via the named factories in {@link + * edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for {@link + * CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller + * PS4} controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight + * joysticks}. + */ + private void configureBindings() { + // Schedule `ExampleCommand` when `exampleCondition` changes to `true` + // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed, + // cancelling on release. + m_driverController.a().whileTrue(new Intake(IntakeSubsystem)); + } + + /** + * Use this to pass the autonomous command to the main {@link Robot} class. + * + * @return the command to run in autonomous + */ + // public Command getAutonomousCommand() { + // // An example command will be run in autonomous + // return Autos.exampleAuto(IntakeSubsystem); + // } +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java new file mode 100644 index 0000000..c44a0f7 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java @@ -0,0 +1,20 @@ +// // Copyright (c) FIRST and other WPILib contributors. +// // Open Source Software; you can modify and/or share it under the terms of +// // the WPILib BSD license file in the root directory of this project. + +// package frc.robot.commands; + +// import frc.robot.subsystems.IntakeSubsystem; +// import edu.wpi.first.wpilibj2.command.Command; +// import edu.wpi.first.wpilibj2.command.Commands; + +// public final class Autos { +// /** Example static factory for an autonomous command. */ +// // public static Command exampleAuto(IntakeSubsystem subsystem) { +// // return Commands.sequence(subsystem.exampleMethodCommand(), new Intake(subsystem)); +// } + +// private Autos() { +// throw new UnsupportedOperationException("This is a utility class!"); +// } +// } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java new file mode 100644 index 0000000..447d133 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java @@ -0,0 +1,42 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import frc.robot.subsystems.IntakeSubsystem; +import edu.wpi.first.wpilibj2.command.Command; + +/** An example command that uses an example subsystem. */ +public class Intake extends Command { + + private final IntakeSubsystem intakeSubsystem; + + public Intake(IntakeSubsystem intakeSubsystem) { + this.intakeSubsystem = new IntakeSubsystem(); + addRequirements(intakeSubsystem); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + intakeSubsystem.setSpeed(1.0); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + intakeSubsystem.setSpeed(0.0); + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java new file mode 100644 index 0000000..af8bfd2 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java @@ -0,0 +1,37 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems; + +import com.ctre.phoenix6.hardware.TalonFX; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; + +public class IntakeSubsystem extends SubsystemBase { + private final TalonFX myMotor; + + public IntakeSubsystem() { + myMotor = new TalonFX(2); + } + +public void setSpeed(double speed){ + myMotor.set(speed); +} + + public boolean exampleCondition() { + // Query some boolean state, such as a digital sensor. + return false; + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + } + + @Override + public void simulationPeriodic() { + // This method will be called once per scheduler run during simulation + } +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json b/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json new file mode 100644 index 0000000..092ae53 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json @@ -0,0 +1,359 @@ +{ + "fileName": "Phoenix6-25.0.0-beta-3.json", + "name": "CTRE-Phoenix (v6)", + "version": "25.0.0-beta-3", + "frcYear": "2025", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json", + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", + "offlineFileName": "Phoenix6-replay-frc2025-beta-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "25.0.0-beta-3" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "api-cpp-sim", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.0.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "25.0.0-beta-3", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.0.0-beta-3", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "25.0.0-beta-3", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.0.0-beta-3", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.0.0-beta-3", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.0.0-beta-3", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.0.0-beta-3", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.0.0-beta-3", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.0.0-beta-3", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.0.0-beta-3", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.0.0-beta-3", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json b/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json new file mode 100644 index 0000000..3718e0a --- /dev/null +++ b/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json @@ -0,0 +1,38 @@ +{ + "fileName": "WPILibNewCommands.json", + "name": "WPILib-New-Commands", + "version": "1.0.0", + "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "frcYear": "2025", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-cpp", + "version": "wpilib", + "libName": "wpilibNewCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxarm32", + "linuxarm64", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxuniversal" + ] + } + ] +} From bbb9fc8a835aa763fd49a7ece6248d8b91b7275a Mon Sep 17 00:00:00 2001 From: Ishan1522 Date: Wed, 18 Dec 2024 17:55:03 -0500 Subject: [PATCH 07/13] idk how that got in there --- src/main/java/frc/robot/BuildConstants.java | 12 +- .../elevator/ElevatorInterface.java | 2 - .../subsystems/intake/IntakeThing/.gitignore | 184 --------- .../.wpilib/wpilib_preferences.json | 6 - .../intake/IntakeThing/WPILib-License.md | 24 -- .../intake/IntakeThing/build.gradle | 102 ----- .../gradle/wrapper/gradle-wrapper.jar | Bin 43583 -> 0 bytes .../gradle/wrapper/gradle-wrapper.properties | 7 - .../subsystems/intake/IntakeThing/gradlew | 252 ------------ .../subsystems/intake/IntakeThing/gradlew.bat | 94 ----- .../intake/IntakeThing/settings.gradle | 30 -- .../IntakeThing/src/main/deploy/example.txt | 3 - .../src/main/java/frc/robot/Constants.java | 19 - .../src/main/java/frc/robot/Main.java | 25 -- .../src/main/java/frc/robot/Robot.java | 100 ----- .../main/java/frc/robot/RobotContainer.java | 59 --- .../main/java/frc/robot/commands/Autos.java | 20 - .../main/java/frc/robot/commands/Intake.java | 42 -- .../frc/robot/subsystems/IntakeSubsystem.java | 37 -- .../vendordeps/Phoenix6-25.0.0-beta-3.json | 359 ------------------ .../vendordeps/WPILibNewCommands.json | 38 -- 21 files changed, 6 insertions(+), 1409 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.jar delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json delete mode 100644 src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index 44abc36..f14a657 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -7,13 +7,13 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "4829-BaseRobotCode"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 13; - public static final String GIT_SHA = "c9b53f77ffe5d9294a84e77fe471839907a42770"; - public static final String GIT_DATE = "2024-11-20 17:53:15 EST"; + public static final int GIT_REVISION = 15; + public static final String GIT_SHA = "9b2d52efc94f51550c86781dc4d51112afc44b13"; + public static final String GIT_DATE = "2024-12-16 17:53:23 EST"; public static final String GIT_BRANCH = "ExamplesYay"; - public static final String BUILD_DATE = "2024-12-06 16:29:40 EST"; - public static final long BUILD_UNIX_TIME = 1733520580115L; - public static final int DIRTY = 0; + public static final String BUILD_DATE = "2024-12-18 17:41:48 EST"; + public static final long BUILD_UNIX_TIME = 1734561708416L; + public static final int DIRTY = 1; private BuildConstants(){} } diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java index 9f2b93b..e7bb047 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java @@ -7,10 +7,8 @@ public interface ElevatorInterface { @AutoLog public static class ElevatorInputs { public double leaderMotorPosition = 0.0; - public double leaderMotorAppliedVolts = 0.0; public double followerMotorPosition = 0.0; - public double followerMotorAppliedVolts = 0.0; } public default void updateInputs(ElevatorInputs inputs) {} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore b/src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore deleted file mode 100644 index 375359c..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/.gitignore +++ /dev/null @@ -1,184 +0,0 @@ -# This gitignore has been specially created by the WPILib team. -# If you remove items from this file, intellisense might break. - -### C++ ### -# Prerequisites -*.d - -# Compiled Object files -*.slo -*.lo -*.o -*.obj - -# Precompiled Headers -*.gch -*.pch - -# Compiled Dynamic libraries -*.so -*.dylib -*.dll - -# Fortran module files -*.mod -*.smod - -# Compiled Static libraries -*.lai -*.la -*.a -*.lib - -# Executables -*.exe -*.out -*.app - -### Java ### -# Compiled class file -*.class - -# Log file -*.log - -# BlueJ files -*.ctxt - -# Mobile Tools for Java (J2ME) -.mtj.tmp/ - -# Package Files # -*.jar -*.war -*.nar -*.ear -*.zip -*.tar.gz -*.rar - -# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml -hs_err_pid* - -### Linux ### -*~ - -# temporary files which can be created if a process still has a handle open of a deleted file -.fuse_hidden* - -# KDE directory preferences -.directory - -# Linux trash folder which might appear on any partition or disk -.Trash-* - -# .nfs files are created when an open file is removed but is still being accessed -.nfs* - -### macOS ### -# General -.DS_Store -.AppleDouble -.LSOverride - -# Icon must end with two \r -Icon - -# Thumbnails -._* - -# Files that might appear in the root of a volume -.DocumentRevisions-V100 -.fseventsd -.Spotlight-V100 -.TemporaryItems -.Trashes -.VolumeIcon.icns -.com.apple.timemachine.donotpresent - -# Directories potentially created on remote AFP share -.AppleDB -.AppleDesktop -Network Trash Folder -Temporary Items -.apdisk - -### VisualStudioCode ### -.vscode/* -!.vscode/settings.json -!.vscode/tasks.json -!.vscode/launch.json -!.vscode/extensions.json - -### Windows ### -# Windows thumbnail cache files -Thumbs.db -ehthumbs.db -ehthumbs_vista.db - -# Dump file -*.stackdump - -# Folder config file -[Dd]esktop.ini - -# Recycle Bin used on file shares -$RECYCLE.BIN/ - -# Windows Installer files -*.cab -*.msi -*.msix -*.msm -*.msp - -# Windows shortcuts -*.lnk - -### Gradle ### -.gradle -/build/ - -# Ignore Gradle GUI config -gradle-app.setting - -# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) -!gradle-wrapper.jar - -# Cache of project -.gradletasknamecache - -# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 -# gradle/wrapper/gradle-wrapper.properties - -# # VS Code Specific Java Settings -# DO NOT REMOVE .classpath and .project -.classpath -.project -.settings/ -bin/ - -# IntelliJ -*.iml -*.ipr -*.iws -.idea/ -out/ - -# Fleet -.fleet - -# Simulation GUI and other tools window save file -networktables.json -simgui.json -*-window.json - -# Simulation data log directory -logs/ - -# Folder that has CTRE Phoenix Sim device config storage -ctre_sim/ - -# clangd -/.cache -compile_commands.json diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json b/src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json deleted file mode 100644 index acab627..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/.wpilib/wpilib_preferences.json +++ /dev/null @@ -1,6 +0,0 @@ -{ - "enableCppIntellisense": false, - "currentLanguage": "java", - "projectYear": "2025beta", - "teamNumber": 4829 -} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md b/src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md deleted file mode 100644 index 645e542..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/WPILib-License.md +++ /dev/null @@ -1,24 +0,0 @@ -Copyright (c) 2009-2024 FIRST and other WPILib contributors -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - * Neither the name of FIRST, WPILib, nor the names of other WPILib - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND -ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR -PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR -ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND -ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS -SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle b/src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle deleted file mode 100644 index ec028da..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/build.gradle +++ /dev/null @@ -1,102 +0,0 @@ -plugins { - id "java" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1" -} - -java { - sourceCompatibility = JavaVersion.VERSION_17 - targetCompatibility = JavaVersion.VERSION_17 -} - -def ROBOT_MAIN_CLASS = "frc.robot.Main" - -// Define my targets (RoboRIO) and artifacts (deployable files) -// This is added by GradleRIO's backing project DeployUtils. -deploy { - targets { - roborio(getTargetTypeClass('RoboRIO')) { - // Team number is loaded either from the .wpilib/wpilib_preferences.json - // or from command line. If not found an exception will be thrown. - // You can use getTeamOrDefault(team) instead of getTeamNumber if you - // want to store a team number in this file. - team = project.frc.getTeamNumber() - debug = project.frc.getDebugOrDefault(false) - - artifacts { - // First part is artifact name, 2nd is artifact type - // getTargetTypeClass is a shortcut to get the class type using a string - - frcJava(getArtifactTypeClass('FRCJavaArtifact')) { - } - - // Static files artifact - frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { - files = project.fileTree('src/main/deploy') - directory = '/home/lvuser/deploy' - } - } - } - } -} - -def deployArtifact = deploy.targets.roborio.artifacts.frcJava - -// Set to true to use debug for JNI. -wpi.java.debugJni = false - -// Set this to true to enable desktop support. -def includeDesktopSupport = false - -// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. -// Also defines JUnit 5. -dependencies { - annotationProcessor wpi.java.deps.wpilibAnnotations() - implementation wpi.java.deps.wpilib() - implementation wpi.java.vendor.java() - - roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) - roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) - - roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) - roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) - - nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) - nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) - simulationDebug wpi.sim.enableDebug() - - nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) - nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) - simulationRelease wpi.sim.enableRelease() - - testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' - testRuntimeOnly 'org.junit.platform:junit-platform-launcher' -} - -test { - useJUnitPlatform() - systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' -} - -// Simulation configuration (e.g. environment variables). -wpi.sim.addGui().defaultEnabled = true -wpi.sim.addDriverstation() - -// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') -// in order to make them all available at runtime. Also adding the manifest so WPILib -// knows where to look for our Robot Class. -jar { - from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } - from sourceSets.main.allSource - manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) - duplicatesStrategy = DuplicatesStrategy.INCLUDE -} - -// Configure jar and deploy tasks -deployArtifact.jarTask = jar -wpi.java.configureExecutableTasks(jar) -wpi.java.configureTestTasks(test) - -// Configure string concat to always inline compile -tasks.withType(JavaCompile) { - options.compilerArgs.add '-XDstringConcat=inline' -} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.jar b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.jar deleted file mode 100644 index a4b76b9530d66f5e68d973ea569d8e19de379189..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 43583 zcma&N1CXTcmMvW9vTb(Rwr$&4wr$(C?dmSu>@vG-+vuvg^_??!{yS%8zW-#zn-LkA z5&1^$^{lnmUON?}LBF8_K|(?T0Ra(xUH{($5eN!MR#ZihR#HxkUPe+_R8Cn`RRs(P z_^*#_XlXmGv7!4;*Y%p4nw?{bNp@UZHv1?Um8r6)Fei3p@ClJn0ECfg1hkeuUU@Or zDaPa;U3fE=3L}DooL;8f;P0ipPt0Z~9P0)lbStMS)ag54=uL9ia-Lm3nh|@(Y?B`; zx_#arJIpXH!U{fbCbI^17}6Ri*H<>OLR%c|^mh8+)*h~K8Z!9)DPf zR2h?lbDZQ`p9P;&DQ4F0sur@TMa!Y}S8irn(%d-gi0*WxxCSk*A?3lGh=gcYN?FGl z7D=Js!i~0=u3rox^eO3i@$0=n{K1lPNU zwmfjRVmLOCRfe=seV&P*1Iq=^i`502keY8Uy-WNPwVNNtJFx?IwAyRPZo2Wo1+S(xF37LJZ~%i)kpFQ3Fw=mXfd@>%+)RpYQLnr}B~~zoof(JVm^^&f zxKV^+3D3$A1G;qh4gPVjhrC8e(VYUHv#dy^)(RoUFM?o%W-EHxufuWf(l*@-l+7vt z=l`qmR56K~F|v<^Pd*p~1_y^P0P^aPC##d8+HqX4IR1gu+7w#~TBFphJxF)T$2WEa zxa?H&6=Qe7d(#tha?_1uQys2KtHQ{)Qco)qwGjrdNL7thd^G5i8Os)CHqc>iOidS} z%nFEDdm=GXBw=yXe1W-ShHHFb?Cc70+$W~z_+}nAoHFYI1MV1wZegw*0y^tC*s%3h zhD3tN8b=Gv&rj}!SUM6|ajSPp*58KR7MPpI{oAJCtY~JECm)*m_x>AZEu>DFgUcby z1Qaw8lU4jZpQ_$;*7RME+gq1KySGG#Wql>aL~k9tLrSO()LWn*q&YxHEuzmwd1?aAtI zBJ>P=&$=l1efe1CDU;`Fd+_;&wI07?V0aAIgc(!{a z0Jg6Y=inXc3^n!U0Atk`iCFIQooHqcWhO(qrieUOW8X(x?(RD}iYDLMjSwffH2~tB z)oDgNBLB^AJBM1M^c5HdRx6fBfka`(LD-qrlh5jqH~);#nw|iyp)()xVYak3;Ybik z0j`(+69aK*B>)e_p%=wu8XC&9e{AO4c~O1U`5X9}?0mrd*m$_EUek{R?DNSh(=br# z#Q61gBzEpmy`$pA*6!87 zSDD+=@fTY7<4A?GLqpA?Pb2z$pbCc4B4zL{BeZ?F-8`s$?>*lXXtn*NC61>|*w7J* z$?!iB{6R-0=KFmyp1nnEmLsA-H0a6l+1uaH^g%c(p{iT&YFrbQ$&PRb8Up#X3@Zsk zD^^&LK~111%cqlP%!_gFNa^dTYT?rhkGl}5=fL{a`UViaXWI$k-UcHJwmaH1s=S$4 z%4)PdWJX;hh5UoK?6aWoyLxX&NhNRqKam7tcOkLh{%j3K^4Mgx1@i|Pi&}<^5>hs5 zm8?uOS>%)NzT(%PjVPGa?X%`N2TQCKbeH2l;cTnHiHppPSJ<7y-yEIiC!P*ikl&!B z%+?>VttCOQM@ShFguHVjxX^?mHX^hSaO_;pnyh^v9EumqSZTi+#f&_Vaija0Q-e*| z7ulQj6Fs*bbmsWp{`auM04gGwsYYdNNZcg|ph0OgD>7O}Asn7^Z=eI>`$2*v78;sj-}oMoEj&@)9+ycEOo92xSyY344^ z11Hb8^kdOvbf^GNAK++bYioknrpdN>+u8R?JxG=!2Kd9r=YWCOJYXYuM0cOq^FhEd zBg2puKy__7VT3-r*dG4c62Wgxi52EMCQ`bKgf*#*ou(D4-ZN$+mg&7$u!! z-^+Z%;-3IDwqZ|K=ah85OLwkO zKxNBh+4QHh)u9D?MFtpbl)us}9+V!D%w9jfAMYEb>%$A;u)rrI zuBudh;5PN}_6J_}l55P3l_)&RMlH{m!)ai-i$g)&*M`eN$XQMw{v^r@-125^RRCF0 z^2>|DxhQw(mtNEI2Kj(;KblC7x=JlK$@78`O~>V!`|1Lm-^JR$-5pUANAnb(5}B}JGjBsliK4& zk6y(;$e&h)lh2)L=bvZKbvh@>vLlreBdH8No2>$#%_Wp1U0N7Ank!6$dFSi#xzh|( zRi{Uw%-4W!{IXZ)fWx@XX6;&(m_F%c6~X8hx=BN1&q}*( zoaNjWabE{oUPb!Bt$eyd#$5j9rItB-h*5JiNi(v^e|XKAj*8(k<5-2$&ZBR5fF|JA z9&m4fbzNQnAU}r8ab>fFV%J0z5awe#UZ|bz?Ur)U9bCIKWEzi2%A+5CLqh?}K4JHi z4vtM;+uPsVz{Lfr;78W78gC;z*yTch~4YkLr&m-7%-xc ztw6Mh2d>_iO*$Rd8(-Cr1_V8EO1f*^@wRoSozS) zy1UoC@pruAaC8Z_7~_w4Q6n*&B0AjOmMWa;sIav&gu z|J5&|{=a@vR!~k-OjKEgPFCzcJ>#A1uL&7xTDn;{XBdeM}V=l3B8fE1--DHjSaxoSjNKEM9|U9#m2<3>n{Iuo`r3UZp;>GkT2YBNAh|b z^jTq-hJp(ebZh#Lk8hVBP%qXwv-@vbvoREX$TqRGTgEi$%_F9tZES@z8Bx}$#5eeG zk^UsLBH{bc2VBW)*EdS({yw=?qmevwi?BL6*=12k9zM5gJv1>y#ML4!)iiPzVaH9% zgSImetD@dam~e>{LvVh!phhzpW+iFvWpGT#CVE5TQ40n%F|p(sP5mXxna+Ev7PDwA zamaV4m*^~*xV+&p;W749xhb_X=$|LD;FHuB&JL5?*Y2-oIT(wYY2;73<^#46S~Gx| z^cez%V7x$81}UWqS13Gz80379Rj;6~WdiXWOSsdmzY39L;Hg3MH43o*y8ibNBBH`(av4|u;YPq%{R;IuYow<+GEsf@R?=@tT@!}?#>zIIn0CoyV!hq3mw zHj>OOjfJM3F{RG#6ujzo?y32m^tgSXf@v=J$ELdJ+=5j|=F-~hP$G&}tDZsZE?5rX ztGj`!S>)CFmdkccxM9eGIcGnS2AfK#gXwj%esuIBNJQP1WV~b~+D7PJTmWGTSDrR` zEAu4B8l>NPuhsk5a`rReSya2nfV1EK01+G!x8aBdTs3Io$u5!6n6KX%uv@DxAp3F@{4UYg4SWJtQ-W~0MDb|j-$lwVn znAm*Pl!?Ps&3wO=R115RWKb*JKoexo*)uhhHBncEDMSVa_PyA>k{Zm2(wMQ(5NM3# z)jkza|GoWEQo4^s*wE(gHz?Xsg4`}HUAcs42cM1-qq_=+=!Gk^y710j=66(cSWqUe zklbm8+zB_syQv5A2rj!Vbw8;|$@C!vfNmNV!yJIWDQ>{+2x zKjuFX`~~HKG~^6h5FntRpnnHt=D&rq0>IJ9#F0eM)Y-)GpRjiN7gkA8wvnG#K=q{q z9dBn8_~wm4J<3J_vl|9H{7q6u2A!cW{bp#r*-f{gOV^e=8S{nc1DxMHFwuM$;aVI^ zz6A*}m8N-&x8;aunp1w7_vtB*pa+OYBw=TMc6QK=mbA-|Cf* zvyh8D4LRJImooUaSb7t*fVfih<97Gf@VE0|z>NcBwBQze);Rh!k3K_sfunToZY;f2 z^HmC4KjHRVg+eKYj;PRN^|E0>Gj_zagfRbrki68I^#~6-HaHg3BUW%+clM1xQEdPYt_g<2K+z!$>*$9nQ>; zf9Bei{?zY^-e{q_*|W#2rJG`2fy@{%6u0i_VEWTq$*(ZN37|8lFFFt)nCG({r!q#9 z5VK_kkSJ3?zOH)OezMT{!YkCuSSn!K#-Rhl$uUM(bq*jY? zi1xbMVthJ`E>d>(f3)~fozjg^@eheMF6<)I`oeJYx4*+M&%c9VArn(OM-wp%M<-`x z7sLP1&3^%Nld9Dhm@$3f2}87!quhI@nwd@3~fZl_3LYW-B?Ia>ui`ELg z&Qfe!7m6ze=mZ`Ia9$z|ARSw|IdMpooY4YiPN8K z4B(ts3p%2i(Td=tgEHX z0UQ_>URBtG+-?0E;E7Ld^dyZ;jjw0}XZ(}-QzC6+NN=40oDb2^v!L1g9xRvE#@IBR zO!b-2N7wVfLV;mhEaXQ9XAU+>=XVA6f&T4Z-@AX!leJ8obP^P^wP0aICND?~w&NykJ#54x3_@r7IDMdRNy4Hh;h*!u(Ol(#0bJdwEo$5437-UBjQ+j=Ic>Q2z` zJNDf0yO6@mr6y1#n3)s(W|$iE_i8r@Gd@!DWDqZ7J&~gAm1#~maIGJ1sls^gxL9LLG_NhU!pTGty!TbhzQnu)I*S^54U6Yu%ZeCg`R>Q zhBv$n5j0v%O_j{QYWG!R9W?5_b&67KB$t}&e2LdMvd(PxN6Ir!H4>PNlerpBL>Zvyy!yw z-SOo8caEpDt(}|gKPBd$qND5#a5nju^O>V&;f890?yEOfkSG^HQVmEbM3Ugzu+UtH zC(INPDdraBN?P%kE;*Ae%Wto&sgw(crfZ#Qy(<4nk;S|hD3j{IQRI6Yq|f^basLY; z-HB&Je%Gg}Jt@={_C{L$!RM;$$|iD6vu#3w?v?*;&()uB|I-XqEKqZPS!reW9JkLewLb!70T7n`i!gNtb1%vN- zySZj{8-1>6E%H&=V}LM#xmt`J3XQoaD|@XygXjdZ1+P77-=;=eYpoEQ01B@L*a(uW zrZeZz?HJsw_4g0vhUgkg@VF8<-X$B8pOqCuWAl28uB|@r`19DTUQQsb^pfqB6QtiT z*`_UZ`fT}vtUY#%sq2{rchyfu*pCg;uec2$-$N_xgjZcoumE5vSI{+s@iLWoz^Mf; zuI8kDP{!XY6OP~q5}%1&L}CtfH^N<3o4L@J@zg1-mt{9L`s^z$Vgb|mr{@WiwAqKg zp#t-lhrU>F8o0s1q_9y`gQNf~Vb!F%70f}$>i7o4ho$`uciNf=xgJ>&!gSt0g;M>*x4-`U)ysFW&Vs^Vk6m%?iuWU+o&m(2Jm26Y(3%TL; zA7T)BP{WS!&xmxNw%J=$MPfn(9*^*TV;$JwRy8Zl*yUZi8jWYF>==j~&S|Xinsb%c z2?B+kpet*muEW7@AzjBA^wAJBY8i|#C{WtO_or&Nj2{=6JTTX05}|H>N2B|Wf!*3_ z7hW*j6p3TvpghEc6-wufFiY!%-GvOx*bZrhZu+7?iSrZL5q9}igiF^*R3%DE4aCHZ zqu>xS8LkW+Auv%z-<1Xs92u23R$nk@Pk}MU5!gT|c7vGlEA%G^2th&Q*zfg%-D^=f z&J_}jskj|Q;73NP4<4k*Y%pXPU2Thoqr+5uH1yEYM|VtBPW6lXaetokD0u z9qVek6Q&wk)tFbQ8(^HGf3Wp16gKmr>G;#G(HRBx?F`9AIRboK+;OfHaLJ(P>IP0w zyTbTkx_THEOs%Q&aPrxbZrJlio+hCC_HK<4%f3ZoSAyG7Dn`=X=&h@m*|UYO-4Hq0 z-Bq&+Ie!S##4A6OGoC~>ZW`Y5J)*ouaFl_e9GA*VSL!O_@xGiBw!AF}1{tB)z(w%c zS1Hmrb9OC8>0a_$BzeiN?rkPLc9%&;1CZW*4}CDDNr2gcl_3z+WC15&H1Zc2{o~i) z)LLW=WQ{?ricmC`G1GfJ0Yp4Dy~Ba;j6ZV4r{8xRs`13{dD!xXmr^Aga|C=iSmor% z8hi|pTXH)5Yf&v~exp3o+sY4B^^b*eYkkCYl*T{*=-0HniSA_1F53eCb{x~1k3*`W zr~};p1A`k{1DV9=UPnLDgz{aJH=-LQo<5%+Em!DNN252xwIf*wF_zS^!(XSm(9eoj z=*dXG&n0>)_)N5oc6v!>-bd(2ragD8O=M|wGW z!xJQS<)u70m&6OmrF0WSsr@I%T*c#Qo#Ha4d3COcX+9}hM5!7JIGF>7<~C(Ear^Sn zm^ZFkV6~Ula6+8S?oOROOA6$C&q&dp`>oR-2Ym3(HT@O7Sd5c~+kjrmM)YmgPH*tL zX+znN>`tv;5eOfX?h{AuX^LK~V#gPCu=)Tigtq9&?7Xh$qN|%A$?V*v=&-2F$zTUv z`C#WyIrChS5|Kgm_GeudCFf;)!WH7FI60j^0o#65o6`w*S7R@)88n$1nrgU(oU0M9 zx+EuMkC>(4j1;m6NoGqEkpJYJ?vc|B zOlwT3t&UgL!pX_P*6g36`ZXQ; z9~Cv}ANFnJGp(;ZhS(@FT;3e)0)Kp;h^x;$*xZn*k0U6-&FwI=uOGaODdrsp-!K$Ac32^c{+FhI-HkYd5v=`PGsg%6I`4d9Jy)uW0y%) zm&j^9WBAp*P8#kGJUhB!L?a%h$hJgQrx!6KCB_TRo%9{t0J7KW8!o1B!NC)VGLM5! zpZy5Jc{`r{1e(jd%jsG7k%I+m#CGS*BPA65ZVW~fLYw0dA-H_}O zrkGFL&P1PG9p2(%QiEWm6x;U-U&I#;Em$nx-_I^wtgw3xUPVVu zqSuKnx&dIT-XT+T10p;yjo1Y)z(x1fb8Dzfn8e yu?e%!_ptzGB|8GrCfu%p?(_ zQccdaaVK$5bz;*rnyK{_SQYM>;aES6Qs^lj9lEs6_J+%nIiuQC*fN;z8md>r_~Mfl zU%p5Dt_YT>gQqfr@`cR!$NWr~+`CZb%dn;WtzrAOI>P_JtsB76PYe*<%H(y>qx-`Kq!X_; z<{RpAqYhE=L1r*M)gNF3B8r(<%8mo*SR2hu zccLRZwGARt)Hlo1euqTyM>^!HK*!Q2P;4UYrysje@;(<|$&%vQekbn|0Ruu_Io(w4#%p6ld2Yp7tlA`Y$cciThP zKzNGIMPXX%&Ud0uQh!uQZz|FB`4KGD?3!ND?wQt6!n*f4EmCoJUh&b?;B{|lxs#F- z31~HQ`SF4x$&v00@(P+j1pAaj5!s`)b2RDBp*PB=2IB>oBF!*6vwr7Dp%zpAx*dPr zb@Zjq^XjN?O4QcZ*O+8>)|HlrR>oD*?WQl5ri3R#2?*W6iJ>>kH%KnnME&TT@ZzrHS$Q%LC?n|e>V+D+8D zYc4)QddFz7I8#}y#Wj6>4P%34dZH~OUDb?uP%-E zwjXM(?Sg~1!|wI(RVuxbu)-rH+O=igSho_pDCw(c6b=P zKk4ATlB?bj9+HHlh<_!&z0rx13K3ZrAR8W)!@Y}o`?a*JJsD+twZIv`W)@Y?Amu_u zz``@-e2X}27$i(2=9rvIu5uTUOVhzwu%mNazS|lZb&PT;XE2|B&W1>=B58#*!~D&) zfVmJGg8UdP*fx(>Cj^?yS^zH#o-$Q-*$SnK(ZVFkw+er=>N^7!)FtP3y~Xxnu^nzY zikgB>Nj0%;WOltWIob|}%lo?_C7<``a5hEkx&1ku$|)i>Rh6@3h*`slY=9U}(Ql_< zaNG*J8vb&@zpdhAvv`?{=zDedJ23TD&Zg__snRAH4eh~^oawdYi6A3w8<Ozh@Kw)#bdktM^GVb zrG08?0bG?|NG+w^&JvD*7LAbjED{_Zkc`3H!My>0u5Q}m!+6VokMLXxl`Mkd=g&Xx z-a>m*#G3SLlhbKB!)tnzfWOBV;u;ftU}S!NdD5+YtOjLg?X}dl>7m^gOpihrf1;PY zvll&>dIuUGs{Qnd- zwIR3oIrct8Va^Tm0t#(bJD7c$Z7DO9*7NnRZorrSm`b`cxz>OIC;jSE3DO8`hX955ui`s%||YQtt2 z5DNA&pG-V+4oI2s*x^>-$6J?p=I>C|9wZF8z;VjR??Icg?1w2v5Me+FgAeGGa8(3S z4vg*$>zC-WIVZtJ7}o9{D-7d>zCe|z#<9>CFve-OPAYsneTb^JH!Enaza#j}^mXy1 z+ULn^10+rWLF6j2>Ya@@Kq?26>AqK{A_| zQKb*~F1>sE*=d?A?W7N2j?L09_7n+HGi{VY;MoTGr_)G9)ot$p!-UY5zZ2Xtbm=t z@dpPSGwgH=QtIcEulQNI>S-#ifbnO5EWkI;$A|pxJd885oM+ zGZ0_0gDvG8q2xebj+fbCHYfAXuZStH2j~|d^sBAzo46(K8n59+T6rzBwK)^rfPT+B zyIFw)9YC-V^rhtK`!3jrhmW-sTmM+tPH+;nwjL#-SjQPUZ53L@A>y*rt(#M(qsiB2 zx6B)dI}6Wlsw%bJ8h|(lhkJVogQZA&n{?Vgs6gNSXzuZpEyu*xySy8ro07QZ7Vk1!3tJphN_5V7qOiyK8p z#@jcDD8nmtYi1^l8ml;AF<#IPK?!pqf9D4moYk>d99Im}Jtwj6c#+A;f)CQ*f-hZ< z=p_T86jog%!p)D&5g9taSwYi&eP z#JuEK%+NULWus;0w32-SYFku#i}d~+{Pkho&^{;RxzP&0!RCm3-9K6`>KZpnzS6?L z^H^V*s!8<>x8bomvD%rh>Zp3>Db%kyin;qtl+jAv8Oo~1g~mqGAC&Qi_wy|xEt2iz zWAJEfTV%cl2Cs<1L&DLRVVH05EDq`pH7Oh7sR`NNkL%wi}8n>IXcO40hp+J+sC!W?!krJf!GJNE8uj zg-y~Ns-<~D?yqbzVRB}G>0A^f0!^N7l=$m0OdZuqAOQqLc zX?AEGr1Ht+inZ-Qiwnl@Z0qukd__a!C*CKuGdy5#nD7VUBM^6OCpxCa2A(X;e0&V4 zM&WR8+wErQ7UIc6LY~Q9x%Sn*Tn>>P`^t&idaOEnOd(Ufw#>NoR^1QdhJ8s`h^|R_ zXX`c5*O~Xdvh%q;7L!_!ohf$NfEBmCde|#uVZvEo>OfEq%+Ns7&_f$OR9xsihRpBb z+cjk8LyDm@U{YN>+r46?nn{7Gh(;WhFw6GAxtcKD+YWV?uge>;+q#Xx4!GpRkVZYu zzsF}1)7$?%s9g9CH=Zs+B%M_)+~*j3L0&Q9u7!|+T`^O{xE6qvAP?XWv9_MrZKdo& z%IyU)$Q95AB4!#hT!_dA>4e@zjOBD*Y=XjtMm)V|+IXzjuM;(l+8aA5#Kaz_$rR6! zj>#&^DidYD$nUY(D$mH`9eb|dtV0b{S>H6FBfq>t5`;OxA4Nn{J(+XihF(stSche7$es&~N$epi&PDM_N`As;*9D^L==2Q7Z2zD+CiU(|+-kL*VG+&9!Yb3LgPy?A zm7Z&^qRG_JIxK7-FBzZI3Q<;{`DIxtc48k> zc|0dmX;Z=W$+)qE)~`yn6MdoJ4co;%!`ddy+FV538Y)j(vg}5*k(WK)KWZ3WaOG!8 z!syGn=s{H$odtpqFrT#JGM*utN7B((abXnpDM6w56nhw}OY}0TiTG1#f*VFZr+^-g zbP10`$LPq_;PvrA1XXlyx2uM^mrjTzX}w{yuLo-cOClE8MMk47T25G8M!9Z5ypOSV zAJUBGEg5L2fY)ZGJb^E34R2zJ?}Vf>{~gB!8=5Z) z9y$>5c)=;o0HeHHSuE4U)#vG&KF|I%-cF6f$~pdYJWk_dD}iOA>iA$O$+4%@>JU08 zS`ep)$XLPJ+n0_i@PkF#ri6T8?ZeAot$6JIYHm&P6EB=BiaNY|aA$W0I+nz*zkz_z zkEru!tj!QUffq%)8y0y`T&`fuus-1p>=^hnBiBqD^hXrPs`PY9tU3m0np~rISY09> z`P3s=-kt_cYcxWd{de@}TwSqg*xVhp;E9zCsnXo6z z?f&Sv^U7n4`xr=mXle94HzOdN!2kB~4=%)u&N!+2;z6UYKUDqi-s6AZ!haB;@&B`? z_TRX0%@suz^TRdCb?!vNJYPY8L_}&07uySH9%W^Tc&1pia6y1q#?*Drf}GjGbPjBS zbOPcUY#*$3sL2x4v_i*Y=N7E$mR}J%|GUI(>WEr+28+V z%v5{#e!UF*6~G&%;l*q*$V?&r$Pp^sE^i-0$+RH3ERUUdQ0>rAq2(2QAbG}$y{de( z>{qD~GGuOk559Y@%$?N^1ApVL_a704>8OD%8Y%8B;FCt%AoPu8*D1 zLB5X>b}Syz81pn;xnB}%0FnwazlWfUV)Z-~rZg6~b z6!9J$EcE&sEbzcy?CI~=boWA&eeIa%z(7SE^qgVLz??1Vbc1*aRvc%Mri)AJaAG!p z$X!_9Ds;Zz)f+;%s&dRcJt2==P{^j3bf0M=nJd&xwUGlUFn?H=2W(*2I2Gdu zv!gYCwM10aeus)`RIZSrCK=&oKaO_Ry~D1B5!y0R=%!i2*KfXGYX&gNv_u+n9wiR5 z*e$Zjju&ODRW3phN925%S(jL+bCHv6rZtc?!*`1TyYXT6%Ju=|X;6D@lq$8T zW{Y|e39ioPez(pBH%k)HzFITXHvnD6hw^lIoUMA;qAJ^CU?top1fo@s7xT13Fvn1H z6JWa-6+FJF#x>~+A;D~;VDs26>^oH0EI`IYT2iagy23?nyJ==i{g4%HrAf1-*v zK1)~@&(KkwR7TL}L(A@C_S0G;-GMDy=MJn2$FP5s<%wC)4jC5PXoxrQBFZ_k0P{{s@sz+gX`-!=T8rcB(=7vW}^K6oLWMmp(rwDh}b zwaGGd>yEy6fHv%jM$yJXo5oMAQ>c9j`**}F?MCry;T@47@r?&sKHgVe$MCqk#Z_3S z1GZI~nOEN*P~+UaFGnj{{Jo@16`(qVNtbU>O0Hf57-P>x8Jikp=`s8xWs^dAJ9lCQ z)GFm+=OV%AMVqVATtN@|vp61VVAHRn87}%PC^RAzJ%JngmZTasWBAWsoAqBU+8L8u z4A&Pe?fmTm0?mK-BL9t+{y7o(7jm+RpOhL9KnY#E&qu^}B6=K_dB}*VlSEiC9fn)+V=J;OnN)Ta5v66ic1rG+dGAJ1 z1%Zb_+!$=tQ~lxQrzv3x#CPb?CekEkA}0MYSgx$Jdd}q8+R=ma$|&1a#)TQ=l$1tQ z=tL9&_^vJ)Pk}EDO-va`UCT1m#Uty1{v^A3P~83_#v^ozH}6*9mIjIr;t3Uv%@VeW zGL6(CwCUp)Jq%G0bIG%?{_*Y#5IHf*5M@wPo6A{$Um++Co$wLC=J1aoG93&T7Ho}P z=mGEPP7GbvoG!uD$k(H3A$Z))+i{Hy?QHdk>3xSBXR0j!11O^mEe9RHmw!pvzv?Ua~2_l2Yh~_!s1qS`|0~0)YsbHSz8!mG)WiJE| z2f($6TQtt6L_f~ApQYQKSb=`053LgrQq7G@98#igV>y#i==-nEjQ!XNu9 z~;mE+gtj4IDDNQJ~JVk5Ux6&LCSFL!y=>79kE9=V}J7tD==Ga+IW zX)r7>VZ9dY=V&}DR))xUoV!u(Z|%3ciQi_2jl}3=$Agc(`RPb z8kEBpvY>1FGQ9W$n>Cq=DIpski};nE)`p3IUw1Oz0|wxll^)4dq3;CCY@RyJgFgc# zKouFh!`?Xuo{IMz^xi-h=StCis_M7yq$u) z?XHvw*HP0VgR+KR6wI)jEMX|ssqYvSf*_3W8zVTQzD?3>H!#>InzpSO)@SC8q*ii- z%%h}_#0{4JG;Jm`4zg};BPTGkYamx$Xo#O~lBirRY)q=5M45n{GCfV7h9qwyu1NxOMoP4)jjZMxmT|IQQh0U7C$EbnMN<3)Kk?fFHYq$d|ICu>KbY_hO zTZM+uKHe(cIZfEqyzyYSUBZa8;Fcut-GN!HSA9ius`ltNebF46ZX_BbZNU}}ZOm{M2&nANL9@0qvih15(|`S~z}m&h!u4x~(%MAO$jHRWNfuxWF#B)E&g3ghSQ9|> z(MFaLQj)NE0lowyjvg8z0#m6FIuKE9lDO~Glg}nSb7`~^&#(Lw{}GVOS>U)m8bF}x zVjbXljBm34Cs-yM6TVusr+3kYFjr28STT3g056y3cH5Tmge~ASxBj z%|yb>$eF;WgrcOZf569sDZOVwoo%8>XO>XQOX1OyN9I-SQgrm;U;+#3OI(zrWyow3 zk==|{lt2xrQ%FIXOTejR>;wv(Pb8u8}BUpx?yd(Abh6? zsoO3VYWkeLnF43&@*#MQ9-i-d0t*xN-UEyNKeyNMHw|A(k(_6QKO=nKMCxD(W(Yop zsRQ)QeL4X3Lxp^L%wzi2-WVSsf61dqliPUM7srDB?Wm6Lzn0&{*}|IsKQW;02(Y&| zaTKv|`U(pSzuvR6Rduu$wzK_W-Y-7>7s?G$)U}&uK;<>vU}^^ns@Z!p+9?St1s)dG zK%y6xkPyyS1$~&6v{kl?Md6gwM|>mt6Upm>oa8RLD^8T{0?HC!Z>;(Bob7el(DV6x zi`I)$&E&ngwFS@bi4^xFLAn`=fzTC;aimE^!cMI2n@Vo%Ae-ne`RF((&5y6xsjjAZ zVguVoQ?Z9uk$2ON;ersE%PU*xGO@T*;j1BO5#TuZKEf(mB7|g7pcEA=nYJ{s3vlbg zd4-DUlD{*6o%Gc^N!Nptgay>j6E5;3psI+C3Q!1ZIbeCubW%w4pq9)MSDyB{HLm|k zxv-{$$A*pS@csolri$Ge<4VZ}e~78JOL-EVyrbxKra^d{?|NnPp86!q>t<&IP07?Z z^>~IK^k#OEKgRH+LjllZXk7iA>2cfH6+(e&9ku5poo~6y{GC5>(bRK7hwjiurqAiZ zg*DmtgY}v83IjE&AbiWgMyFbaRUPZ{lYiz$U^&Zt2YjG<%m((&_JUbZcfJ22(>bi5 z!J?<7AySj0JZ&<-qXX;mcV!f~>G=sB0KnjWca4}vrtunD^1TrpfeS^4dvFr!65knK zZh`d;*VOkPs4*-9kL>$GP0`(M!j~B;#x?Ba~&s6CopvO86oM?-? zOw#dIRc;6A6T?B`Qp%^<U5 z19x(ywSH$_N+Io!6;e?`tWaM$`=Db!gzx|lQ${DG!zb1Zl&|{kX0y6xvO1o z220r<-oaS^^R2pEyY;=Qllqpmue|5yI~D|iI!IGt@iod{Opz@*ml^w2bNs)p`M(Io z|E;;m*Xpjd9l)4G#KaWfV(t8YUn@A;nK^#xgv=LtnArX|vWQVuw3}B${h+frU2>9^ z!l6)!Uo4`5k`<<;E(ido7M6lKTgWezNLq>U*=uz&s=cc$1%>VrAeOoUtA|T6gO4>UNqsdK=NF*8|~*sl&wI=x9-EGiq*aqV!(VVXA57 zw9*o6Ir8Lj1npUXvlevtn(_+^X5rzdR>#(}4YcB9O50q97%rW2me5_L=%ffYPUSRc z!vv?Kv>dH994Qi>U(a<0KF6NH5b16enCp+mw^Hb3Xs1^tThFpz!3QuN#}KBbww`(h z7GO)1olDqy6?T$()R7y%NYx*B0k_2IBiZ14&8|JPFxeMF{vW>HF-Vi3+ZOI=+qP}n zw(+!WcTd~4ZJX1!ZM&y!+uyt=&i!+~d(V%GjH;-NsEEv6nS1TERt|RHh!0>W4+4pp z1-*EzAM~i`+1f(VEHI8So`S`akPfPTfq*`l{Fz`hS%k#JS0cjT2mS0#QLGf=J?1`he3W*;m4)ce8*WFq1sdP=~$5RlH1EdWm|~dCvKOi4*I_96{^95p#B<(n!d?B z=o`0{t+&OMwKcxiBECznJcfH!fL(z3OvmxP#oWd48|mMjpE||zdiTBdWelj8&Qosv zZFp@&UgXuvJw5y=q6*28AtxZzo-UUpkRW%ne+Ylf!V-0+uQXBW=5S1o#6LXNtY5!I z%Rkz#(S8Pjz*P7bqB6L|M#Er{|QLae-Y{KA>`^} z@lPjeX>90X|34S-7}ZVXe{wEei1<{*e8T-Nbj8JmD4iwcE+Hg_zhkPVm#=@b$;)h6 z<<6y`nPa`f3I6`!28d@kdM{uJOgM%`EvlQ5B2bL)Sl=|y@YB3KeOzz=9cUW3clPAU z^sYc}xf9{4Oj?L5MOlYxR{+>w=vJjvbyO5}ptT(o6dR|ygO$)nVCvNGnq(6;bHlBd zl?w-|plD8spjDF03g5ip;W3Z z><0{BCq!Dw;h5~#1BuQilq*TwEu)qy50@+BE4bX28+7erX{BD4H)N+7U`AVEuREE8 z;X?~fyhF-x_sRfHIj~6f(+^@H)D=ngP;mwJjxhQUbUdzk8f94Ab%59-eRIq?ZKrwD z(BFI=)xrUlgu(b|hAysqK<}8bslmNNeD=#JW*}^~Nrswn^xw*nL@Tx!49bfJecV&KC2G4q5a!NSv)06A_5N3Y?veAz;Gv+@U3R% z)~UA8-0LvVE{}8LVDOHzp~2twReqf}ODIyXMM6=W>kL|OHcx9P%+aJGYi_Om)b!xe zF40Vntn0+VP>o<$AtP&JANjXBn7$}C@{+@3I@cqlwR2MdwGhVPxlTIcRVu@Ho-wO` z_~Or~IMG)A_`6-p)KPS@cT9mu9RGA>dVh5wY$NM9-^c@N=hcNaw4ITjm;iWSP^ZX| z)_XpaI61<+La+U&&%2a z0za$)-wZP@mwSELo#3!PGTt$uy0C(nTT@9NX*r3Ctw6J~7A(m#8fE)0RBd`TdKfAT zCf@$MAxjP`O(u9s@c0Fd@|}UQ6qp)O5Q5DPCeE6mSIh|Rj{$cAVIWsA=xPKVKxdhg zLzPZ`3CS+KIO;T}0Ip!fAUaNU>++ZJZRk@I(h<)RsJUhZ&Ru9*!4Ptn;gX^~4E8W^TSR&~3BAZc#HquXn)OW|TJ`CTahk+{qe`5+ixON^zA9IFd8)kc%*!AiLu z>`SFoZ5bW-%7}xZ>gpJcx_hpF$2l+533{gW{a7ce^B9sIdmLrI0)4yivZ^(Vh@-1q zFT!NQK$Iz^xu%|EOK=n>ug;(7J4OnS$;yWmq>A;hsD_0oAbLYhW^1Vdt9>;(JIYjf zdb+&f&D4@4AS?!*XpH>8egQvSVX`36jMd>$+RgI|pEg))^djhGSo&#lhS~9%NuWfX zDDH;3T*GzRT@5=7ibO>N-6_XPBYxno@mD_3I#rDD?iADxX`! zh*v8^i*JEMzyN#bGEBz7;UYXki*Xr(9xXax(_1qVW=Ml)kSuvK$coq2A(5ZGhs_pF z$*w}FbN6+QDseuB9=fdp_MTs)nQf!2SlROQ!gBJBCXD&@-VurqHj0wm@LWX-TDmS= z71M__vAok|@!qgi#H&H%Vg-((ZfxPAL8AI{x|VV!9)ZE}_l>iWk8UPTGHs*?u7RfP z5MC&=c6X;XlUzrz5q?(!eO@~* zoh2I*%J7dF!!_!vXoSIn5o|wj1#_>K*&CIn{qSaRc&iFVxt*^20ngCL;QonIS>I5^ zMw8HXm>W0PGd*}Ko)f|~dDd%;Wu_RWI_d;&2g6R3S63Uzjd7dn%Svu-OKpx*o|N>F zZg=-~qLb~VRLpv`k zWSdfHh@?dp=s_X`{yxOlxE$4iuyS;Z-x!*E6eqmEm*j2bE@=ZI0YZ5%Yj29!5+J$4h{s($nakA`xgbO8w zi=*r}PWz#lTL_DSAu1?f%-2OjD}NHXp4pXOsCW;DS@BC3h-q4_l`<))8WgzkdXg3! zs1WMt32kS2E#L0p_|x+x**TFV=gn`m9BWlzF{b%6j-odf4{7a4y4Uaef@YaeuPhU8 zHBvRqN^;$Jizy+ z=zW{E5<>2gp$pH{M@S*!sJVQU)b*J5*bX4h>5VJve#Q6ga}cQ&iL#=(u+KroWrxa%8&~p{WEUF0il=db;-$=A;&9M{Rq`ouZ5m%BHT6%st%saGsD6)fQgLN}x@d3q>FC;=f%O3Cyg=Ke@Gh`XW za@RajqOE9UB6eE=zhG%|dYS)IW)&y&Id2n7r)6p_)vlRP7NJL(x4UbhlcFXWT8?K=%s7;z?Vjts?y2+r|uk8Wt(DM*73^W%pAkZa1Jd zNoE)8FvQA>Z`eR5Z@Ig6kS5?0h;`Y&OL2D&xnnAUzQz{YSdh0k zB3exx%A2TyI)M*EM6htrxSlep!Kk(P(VP`$p0G~f$smld6W1r_Z+o?=IB@^weq>5VYsYZZR@` z&XJFxd5{|KPZmVOSxc@^%71C@;z}}WhbF9p!%yLj3j%YOlPL5s>7I3vj25 z@xmf=*z%Wb4;Va6SDk9cv|r*lhZ`(y_*M@>q;wrn)oQx%B(2A$9(74>;$zmQ!4fN; z>XurIk-7@wZys<+7XL@0Fhe-f%*=(weaQEdR9Eh6>Kl-EcI({qoZqyzziGwpg-GM#251sK_ z=3|kitS!j%;fpc@oWn65SEL73^N&t>Ix37xgs= zYG%eQDJc|rqHFia0!_sm7`@lvcv)gfy(+KXA@E{3t1DaZ$DijWAcA)E0@X?2ziJ{v z&KOYZ|DdkM{}t+@{@*6ge}m%xfjIxi%qh`=^2Rwz@w0cCvZ&Tc#UmCDbVwABrON^x zEBK43FO@weA8s7zggCOWhMvGGE`baZ62cC)VHyy!5Zbt%ieH+XN|OLbAFPZWyC6)p z4P3%8sq9HdS3=ih^0OOlqTPbKuzQ?lBEI{w^ReUO{V?@`ARsL|S*%yOS=Z%sF)>-y z(LAQdhgAcuF6LQjRYfdbD1g4o%tV4EiK&ElLB&^VZHbrV1K>tHTO{#XTo>)2UMm`2 z^t4s;vnMQgf-njU-RVBRw0P0-m#d-u`(kq7NL&2T)TjI_@iKuPAK-@oH(J8?%(e!0Ir$yG32@CGUPn5w4)+9@8c&pGx z+K3GKESI4*`tYlmMHt@br;jBWTei&(a=iYslc^c#RU3Q&sYp zSG){)V<(g7+8W!Wxeb5zJb4XE{I|&Y4UrFWr%LHkdQ;~XU zgy^dH-Z3lmY+0G~?DrC_S4@=>0oM8Isw%g(id10gWkoz2Q%7W$bFk@mIzTCcIB(K8 zc<5h&ZzCdT=9n-D>&a8vl+=ZF*`uTvQviG_bLde*k>{^)&0o*b05x$MO3gVLUx`xZ z43j+>!u?XV)Yp@MmG%Y`+COH2?nQcMrQ%k~6#O%PeD_WvFO~Kct za4XoCM_X!c5vhRkIdV=xUB3xI2NNStK*8_Zl!cFjOvp-AY=D;5{uXj}GV{LK1~IE2 z|KffUiBaStRr;10R~K2VVtf{TzM7FaPm;Y(zQjILn+tIPSrJh&EMf6evaBKIvi42-WYU9Vhj~3< zZSM-B;E`g_o8_XTM9IzEL=9Lb^SPhe(f(-`Yh=X6O7+6ALXnTcUFpI>ekl6v)ZQeNCg2 z^H|{SKXHU*%nBQ@I3It0m^h+6tvI@FS=MYS$ZpBaG7j#V@P2ZuYySbp@hA# ze(kc;P4i_-_UDP?%<6>%tTRih6VBgScKU^BV6Aoeg6Uh(W^#J^V$Xo^4#Ekp ztqQVK^g9gKMTHvV7nb64UU7p~!B?>Y0oFH5T7#BSW#YfSB@5PtE~#SCCg3p^o=NkMk$<8- z6PT*yIKGrvne7+y3}_!AC8NNeI?iTY(&nakN>>U-zT0wzZf-RuyZk^X9H-DT_*wk= z;&0}6LsGtfVa1q)CEUPlx#(ED@-?H<1_FrHU#z5^P3lEB|qsxEyn%FOpjx z3S?~gvoXy~L(Q{Jh6*i~=f%9kM1>RGjBzQh_SaIDfSU_9!<>*Pm>l)cJD@wlyxpBV z4Fmhc2q=R_wHCEK69<*wG%}mgD1=FHi4h!98B-*vMu4ZGW~%IrYSLGU{^TuseqVgV zLP<%wirIL`VLyJv9XG_p8w@Q4HzNt-o;U@Au{7%Ji;53!7V8Rv0^Lu^Vf*sL>R(;c zQG_ZuFl)Mh-xEIkGu}?_(HwkB2jS;HdPLSxVU&Jxy9*XRG~^HY(f0g8Q}iqnVmgjI zfd=``2&8GsycjR?M%(zMjn;tn9agcq;&rR!Hp z$B*gzHsQ~aXw8c|a(L^LW(|`yGc!qOnV(ZjU_Q-4z1&0;jG&vAKuNG=F|H?@m5^N@ zq{E!1n;)kNTJ>|Hb2ODt-7U~-MOIFo%9I)_@7fnX+eMMNh>)V$IXesJpBn|uo8f~#aOFytCT zf9&%MCLf8mp4kwHTcojWmM3LU=#|{3L>E}SKwOd?%{HogCZ_Z1BSA}P#O(%H$;z7XyJ^sjGX;j5 zrzp>|Ud;*&VAU3x#f{CKwY7Vc{%TKKqmB@oTHA9;>?!nvMA;8+Jh=cambHz#J18x~ zs!dF>$*AnsQ{{82r5Aw&^7eRCdvcgyxH?*DV5(I$qXh^zS>us*I66_MbL8y4d3ULj z{S(ipo+T3Ag!+5`NU2sc+@*m{_X|&p#O-SAqF&g_n7ObB82~$p%fXA5GLHMC+#qqL zdt`sJC&6C2)=juQ_!NeD>U8lDVpAOkW*khf7MCcs$A(wiIl#B9HM%~GtQ^}yBPjT@ z+E=|A!Z?A(rwzZ;T}o6pOVqHzTr*i;Wrc%&36kc@jXq~+w8kVrs;%=IFdACoLAcCAmhFNpbP8;s`zG|HC2Gv?I~w4ITy=g$`0qMQdkijLSOtX6xW%Z9Nw<;M- zMN`c7=$QxN00DiSjbVt9Mi6-pjv*j(_8PyV-il8Q-&TwBwH1gz1uoxs6~uU}PrgWB zIAE_I-a1EqlIaGQNbcp@iI8W1sm9fBBNOk(k&iLBe%MCo#?xI$%ZmGA?=)M9D=0t7 zc)Q0LnI)kCy{`jCGy9lYX%mUsDWwsY`;jE(;Us@gmWPqjmXL+Hu#^;k%eT>{nMtzj zsV`Iy6leTA8-PndszF;N^X@CJrTw5IIm!GPeu)H2#FQitR{1p;MasQVAG3*+=9FYK zw*k!HT(YQorfQj+1*mCV458(T5=fH`um$gS38hw(OqVMyunQ;rW5aPbF##A3fGH6h z@W)i9Uff?qz`YbK4c}JzQpuxuE3pcQO)%xBRZp{zJ^-*|oryTxJ-rR+MXJ)!f=+pp z10H|DdGd2exhi+hftcYbM0_}C0ZI-2vh+$fU1acsB-YXid7O|=9L!3e@$H*6?G*Zp z%qFB(sgl=FcC=E4CYGp4CN>=M8#5r!RU!u+FJVlH6=gI5xHVD&k;Ta*M28BsxfMV~ zLz+@6TxnfLhF@5=yQo^1&S}cmTN@m!7*c6z;}~*!hNBjuE>NLVl2EwN!F+)0$R1S! zR|lF%n!9fkZ@gPW|x|B={V6x3`=jS*$Pu0+5OWf?wnIy>Y1MbbGSncpKO0qE(qO=ts z!~@&!N`10S593pVQu4FzpOh!tvg}p%zCU(aV5=~K#bKi zHdJ1>tQSrhW%KOky;iW+O_n;`l9~omqM%sdxdLtI`TrJzN6BQz+7xOl*rM>xVI2~# z)7FJ^Dc{DC<%~VS?@WXzuOG$YPLC;>#vUJ^MmtbSL`_yXtNKa$Hk+l-c!aC7gn(Cg ze?YPYZ(2Jw{SF6MiO5(%_pTo7j@&DHNW`|lD`~{iH+_eSTS&OC*2WTT*a`?|9w1dh zh1nh@$a}T#WE5$7Od~NvSEU)T(W$p$s5fe^GpG+7fdJ9=enRT9$wEk+ZaB>G3$KQO zgq?-rZZnIv!p#>Ty~}c*Lb_jxJg$eGM*XwHUwuQ|o^}b3^T6Bxx{!?va8aC@-xK*H ztJBFvFfsSWu89%@b^l3-B~O!CXs)I6Y}y#0C0U0R0WG zybjroj$io0j}3%P7zADXOwHwafT#uu*zfM!oD$6aJx7+WL%t-@6^rD_a_M?S^>c;z zMK580bZXo1f*L$CuMeM4Mp!;P@}b~$cd(s5*q~FP+NHSq;nw3fbWyH)i2)-;gQl{S zZO!T}A}fC}vUdskGSq&{`oxt~0i?0xhr6I47_tBc`fqaSrMOzR4>0H^;A zF)hX1nfHs)%Zb-(YGX;=#2R6C{BG;k=?FfP?9{_uFLri~-~AJ;jw({4MU7e*d)?P@ zXX*GkNY9ItFjhwgAIWq7Y!ksbMzfqpG)IrqKx9q{zu%Mdl+{Dis#p9q`02pr1LG8R z@As?eG!>IoROgS!@J*to<27coFc1zpkh?w=)h9CbYe%^Q!Ui46Y*HO0mr% zEff-*$ndMNw}H2a5@BsGj5oFfd!T(F&0$<{GO!Qdd?McKkorh=5{EIjDTHU`So>8V zBA-fqVLb2;u7UhDV1xMI?y>fe3~4urv3%PX)lDw+HYa;HFkaLqi4c~VtCm&Ca+9C~ zge+67hp#R9`+Euq59WhHX&7~RlXn=--m8$iZ~~1C8cv^2(qO#X0?vl91gzUKBeR1J z^p4!!&7)3#@@X&2aF2-)1Ffcc^F8r|RtdL2X%HgN&XU-KH2SLCbpw?J5xJ*!F-ypZ zMG%AJ!Pr&}`LW?E!K~=(NJxuSVTRCGJ$2a*Ao=uUDSys!OFYu!Vs2IT;xQ6EubLIl z+?+nMGeQQhh~??0!s4iQ#gm3!BpMpnY?04kK375e((Uc7B3RMj;wE?BCoQGu=UlZt!EZ1Q*auI)dj3Jj{Ujgt zW5hd~-HWBLI_3HuO) zNrb^XzPsTIb=*a69wAAA3J6AAZZ1VsYbIG}a`=d6?PjM)3EPaDpW2YP$|GrBX{q*! z$KBHNif)OKMBCFP5>!1d=DK>8u+Upm-{hj5o|Wn$vh1&K!lVfDB&47lw$tJ?d5|=B z^(_9=(1T3Fte)z^>|3**n}mIX;mMN5v2F#l(q*CvU{Ga`@VMp#%rQkDBy7kYbmb-q z<5!4iuB#Q_lLZ8}h|hPODI^U6`gzLJre9u3k3c#%86IKI*^H-@I48Bi*@avYm4v!n0+v zWu{M{&F8#p9cx+gF0yTB_<2QUrjMPo9*7^-uP#~gGW~y3nfPAoV%amgr>PSyVAd@l)}8#X zR5zV6t*uKJZL}?NYvPVK6J0v4iVpwiN|>+t3aYiZSp;m0!(1`bHO}TEtWR1tY%BPB z(W!0DmXbZAsT$iC13p4f>u*ZAy@JoLAkJhzFf1#4;#1deO8#8d&89}en&z!W&A3++^1(;>0SB1*54d@y&9Pn;^IAf3GiXbfT`_>{R+Xv; zQvgL>+0#8-laO!j#-WB~(I>l0NCMt_;@Gp_f0#^c)t?&#Xh1-7RR0@zPyBz!U#0Av zT?}n({(p?p7!4S2ZBw)#KdCG)uPnZe+U|0{BW!m)9 zi_9$F?m<`2!`JNFv+w8MK_K)qJ^aO@7-Ig>cM4-r0bi=>?B_2mFNJ}aE3<+QCzRr*NA!QjHw# z`1OsvcoD0?%jq{*7b!l|L1+Tw0TTAM4XMq7*ntc-Ived>Sj_ZtS|uVdpfg1_I9knY z2{GM_j5sDC7(W&}#s{jqbybqJWyn?{PW*&cQIU|*v8YGOKKlGl@?c#TCnmnAkAzV- zmK={|1G90zz=YUvC}+fMqts0d4vgA%t6Jhjv?d;(Z}(Ep8fTZfHA9``fdUHkA+z3+ zhh{ohP%Bj?T~{i0sYCQ}uC#5BwN`skI7`|c%kqkyWIQ;!ysvA8H`b-t()n6>GJj6xlYDu~8qX{AFo$Cm3d|XFL=4uvc?Keb zzb0ZmMoXca6Mob>JqkNuoP>B2Z>D`Q(TvrG6m`j}-1rGP!g|qoL=$FVQYxJQjFn33lODt3Wb1j8VR zlR++vIT6^DtYxAv_hxupbLLN3e0%A%a+hWTKDV3!Fjr^cWJ{scsAdfhpI)`Bms^M6 zQG$waKgFr=c|p9Piug=fcJvZ1ThMnNhQvBAg-8~b1?6wL*WyqXhtj^g(Ke}mEfZVM zJuLNTUVh#WsE*a6uqiz`b#9ZYg3+2%=C(6AvZGc=u&<6??!slB1a9K)=VL zY9EL^mfyKnD zSJyYBc_>G;5RRnrNgzJz#Rkn3S1`mZgO`(r5;Hw6MveN(URf_XS-r58Cn80K)ArH4 z#Rrd~LG1W&@ttw85cjp8xV&>$b%nSXH_*W}7Ch2pg$$c0BdEo-HWRTZcxngIBJad> z;C>b{jIXjb_9Jis?NZJsdm^EG}e*pR&DAy0EaSGi3XWTa(>C%tz1n$u?5Fb z1qtl?;_yjYo)(gB^iQq?=jusF%kywm?CJP~zEHi0NbZ);$(H$w(Hy@{i>$wcVRD_X|w-~(0Z9BJyh zhNh;+eQ9BEIs;tPz%jSVnfCP!3L&9YtEP;svoj_bNzeGSQIAjd zBss@A;)R^WAu-37RQrM%{DfBNRx>v!G31Z}8-El9IOJlb_MSoMu2}GDYycNaf>uny z+8xykD-7ONCM!APry_Lw6-yT>5!tR}W;W`C)1>pxSs5o1z#j7%m=&=7O4hz+Lsqm` z*>{+xsabZPr&X=}G@obTb{nPTkccJX8w3CG7X+1+t{JcMabv~UNv+G?txRqXib~c^Mo}`q{$`;EBNJ;#F*{gvS12kV?AZ%O0SFB$^ zn+}!HbmEj}w{Vq(G)OGAzH}R~kS^;(-s&=ectz8vN!_)Yl$$U@HNTI-pV`LSj7Opu zTZ5zZ)-S_{GcEQPIQXLQ#oMS`HPu{`SQiAZ)m1at*Hy%3xma|>o`h%E%8BEbi9p0r zVjcsh<{NBKQ4eKlXU|}@XJ#@uQw*$4BxKn6#W~I4T<^f99~(=}a`&3(ur8R9t+|AQ zWkQx7l}wa48-jO@ft2h+7qn%SJtL%~890FG0s5g*kNbL3I&@brh&f6)TlM`K^(bhr zJWM6N6x3flOw$@|C@kPi7yP&SP?bzP-E|HSXQXG>7gk|R9BTj`e=4de9C6+H7H7n# z#GJeVs1mtHhLDmVO?LkYRQc`DVOJ_vdl8VUihO-j#t=0T3%Fc1f9F73ufJz*adn*p zc%&vi(4NqHu^R>sAT_0EDjVR8bc%wTz#$;%NU-kbDyL_dg0%TFafZwZ?5KZpcuaO54Z9hX zD$u>q!-9`U6-D`E#`W~fIfiIF5_m6{fvM)b1NG3xf4Auw;Go~Fu7cth#DlUn{@~yu z=B;RT*dp?bO}o%4x7k9v{r=Y@^YQ^UUm(Qmliw8brO^=NP+UOohLYiaEB3^DB56&V zK?4jV61B|1Uj_5fBKW;8LdwOFZKWp)g{B%7g1~DgO&N& z#lisxf?R~Z@?3E$Mms$$JK8oe@X`5m98V*aV6Ua}8Xs2#A!{x?IP|N(%nxsH?^c{& z@vY&R1QmQs83BW28qAmJfS7MYi=h(YK??@EhjL-t*5W!p z^gYX!Q6-vBqcv~ruw@oMaU&qp0Fb(dbVzm5xJN%0o_^@fWq$oa3X?9s%+b)x4w-q5Koe(@j6Ez7V@~NRFvd zfBH~)U5!ix3isg`6be__wBJp=1@yfsCMw1C@y+9WYD9_C%{Q~7^0AF2KFryfLlUP# zwrtJEcH)jm48!6tUcxiurAMaiD04C&tPe6DI0#aoqz#Bt0_7_*X*TsF7u*zv(iEfA z;$@?XVu~oX#1YXtceQL{dSneL&*nDug^OW$DSLF0M1Im|sSX8R26&)<0Fbh^*l6!5wfSu8MpMoh=2l z^^0Sr$UpZp*9oqa23fcCfm7`ya2<4wzJ`Axt7e4jJrRFVf?nY~2&tRL* zd;6_njcz01c>$IvN=?K}9ie%Z(BO@JG2J}fT#BJQ+f5LFSgup7i!xWRKw6)iITjZU z%l6hPZia>R!`aZjwCp}I zg)%20;}f+&@t;(%5;RHL>K_&7MH^S+7<|(SZH!u zznW|jz$uA`P9@ZWtJgv$EFp>)K&Gt+4C6#*khZQXS*S~6N%JDT$r`aJDs9|uXWdbg zBwho$phWx}x!qy8&}6y5Vr$G{yGSE*r$^r{}pw zVTZKvikRZ`J_IJrjc=X1uw?estdwm&bEahku&D04HD+0Bm~q#YGS6gp!KLf$A{%Qd z&&yX@Hp>~(wU{|(#U&Bf92+1i&Q*-S+=y=3pSZy$#8Uc$#7oiJUuO{cE6=tsPhwPe| zxQpK>`Dbka`V)$}e6_OXKLB%i76~4N*zA?X+PrhH<&)}prET;kel24kW%+9))G^JI zsq7L{P}^#QsZViX%KgxBvEugr>ZmFqe^oAg?{EI=&_O#e)F3V#rc z8$4}0Zr19qd3tE4#$3_f=Bbx9oV6VO!d3(R===i-7p=Vj`520w0D3W6lQfY48}!D* z&)lZMG;~er2qBoI2gsX+Ts-hnpS~NYRDtPd^FPzn!^&yxRy#CSz(b&E*tL|jIkq|l zf%>)7Dtu>jCf`-7R#*GhGn4FkYf;B$+9IxmqH|lf6$4irg{0ept__%)V*R_OK=T06 zyT_m-o@Kp6U{l5h>W1hGq*X#8*y@<;vsOFqEjTQXFEotR+{3}ODDnj;o0@!bB5x=N z394FojuGOtVKBlVRLtHp%EJv_G5q=AgF)SKyRN5=cGBjDWv4LDn$IL`*=~J7u&Dy5 zrMc83y+w^F&{?X(KOOAl-sWZDb{9X9#jrQtmrEXD?;h-}SYT7yM(X_6qksM=K_a;Z z3u0qT0TtaNvDER_8x*rxXw&C^|h{P1qxK|@pS7vdlZ#P z7PdB7MmC2}%sdzAxt>;WM1s0??`1983O4nFK|hVAbHcZ3x{PzytQLkCVk7hA!Lo` zEJH?4qw|}WH{dc4z%aB=0XqsFW?^p=X}4xnCJXK%c#ItOSjdSO`UXJyuc8bh^Cf}8 z@Ht|vXd^6{Fgai8*tmyRGmD_s_nv~r^Fy7j`Bu`6=G)5H$i7Q7lvQnmea&TGvJp9a|qOrUymZ$6G|Ly z#zOCg++$3iB$!6!>215A4!iryregKuUT344X)jQb3|9qY>c0LO{6Vby05n~VFzd?q zgGZv&FGlkiH*`fTurp>B8v&nSxNz)=5IF$=@rgND4d`!AaaX;_lK~)-U8la_Wa8i?NJC@BURO*sUW)E9oyv3RG^YGfN%BmxzjlT)bp*$<| zX3tt?EAy<&K+bhIuMs-g#=d1}N_?isY)6Ay$mDOKRh z4v1asEGWoAp=srraLW^h&_Uw|6O+r;wns=uwYm=JN4Q!quD8SQRSeEcGh|Eb5Jg8m zOT}u;N|x@aq)=&;wufCc^#)5U^VcZw;d_wwaoh9$p@Xrc{DD6GZUqZ ziC6OT^zSq@-lhbgR8B+e;7_Giv;DK5gn^$bs<6~SUadiosfewWDJu`XsBfOd1|p=q zE>m=zF}!lObA%ePey~gqU8S6h-^J2Y?>7)L2+%8kV}Gp=h`Xm_}rlm)SyUS=`=S7msKu zC|T!gPiI1rWGb1z$Md?0YJQ;%>uPLOXf1Z>N~`~JHJ!^@D5kSXQ4ugnFZ>^`zH8CAiZmp z6Ms|#2gcGsQ{{u7+Nb9sA?U>(0e$5V1|WVwY`Kn)rsnnZ4=1u=7u!4WexZD^IQ1Jk zfF#NLe>W$3m&C^ULjdw+5|)-BSHwpegdyt9NYC{3@QtMfd8GrIWDu`gd0nv-3LpGCh@wgBaG z176tikL!_NXM+Bv#7q^cyn9$XSeZR6#!B4JE@GVH zoobHZN_*RF#@_SVYKkQ_igme-Y5U}cV(hkR#k1c{bQNMji zU7aE`?dHyx=1`kOYZo_8U7?3-7vHOp`Qe%Z*i+FX!s?6huNp0iCEW-Z7E&jRWmUW_ z67j>)Ew!yq)hhG4o?^z}HWH-e=es#xJUhDRc4B51M4~E-l5VZ!&zQq`gWe`?}#b~7w1LH4Xa-UCT5LXkXQWheBa2YJYbyQ zl1pXR%b(KCXMO0OsXgl0P0Og<{(@&z1aokU-Pq`eQq*JYgt8xdFQ6S z6Z3IFSua8W&M#`~*L#r>Jfd6*BzJ?JFdBR#bDv$_0N!_5vnmo@!>vULcDm`MFU823 zpG9pqjqz^FE5zMDoGqhs5OMmC{Y3iVcl>F}5Rs24Y5B^mYQ;1T&ks@pIApHOdrzXF z-SdX}Hf{X;TaSxG_T$0~#RhqKISGKNK47}0*x&nRIPtmdwxc&QT3$8&!3fWu1eZ_P zJveQj^hJL#Sn!*4k`3}(d(aasl&7G0j0-*_2xtAnoX1@9+h zO#c>YQg60Z;o{Bi=3i7S`Ic+ZE>K{(u|#)9y}q*j8uKQ1^>+(BI}m%1v3$=4ojGBc zm+o1*!T&b}-lVvZqIUBc8V}QyFEgm#oyIuC{8WqUNV{Toz`oxhYpP!_p2oHHh5P@iB*NVo~2=GQm+8Yrkm2Xjc_VyHg1c0>+o~@>*Qzo zHVBJS>$$}$_4EniTI;b1WShX<5-p#TPB&!;lP!lBVBbLOOxh6FuYloD%m;n{r|;MU3!q4AVkua~fieeWu2 zQAQ$ue(IklX6+V;F1vCu-&V?I3d42FgWgsb_e^29ol}HYft?{SLf>DrmOp9o!t>I^ zY7fBCk+E8n_|apgM|-;^=#B?6RnFKlN`oR)`e$+;D=yO-(U^jV;rft^G_zl`n7qnM zL z*-Y4Phq+ZI1$j$F-f;`CD#|`-T~OM5Q>x}a>B~Gb3-+9i>Lfr|Ca6S^8g*{*?_5!x zH_N!SoRP=gX1?)q%>QTY!r77e2j9W(I!uAz{T`NdNmPBBUzi2{`XMB^zJGGwFWeA9 z{fk33#*9SO0)DjROug+(M)I-pKA!CX;IY(#gE!UxXVsa)X!UftIN98{pt#4MJHOhY zM$_l}-TJlxY?LS6Nuz1T<44m<4i^8k@D$zuCPrkmz@sdv+{ciyFJG2Zwy&%c7;atIeTdh!a(R^QXnu1Oq1b42*OQFWnyQ zWeQrdvP|w_idy53Wa<{QH^lFmEd+VlJkyiC>6B#s)F;w-{c;aKIm;Kp50HnA-o3lY z9B~F$gJ@yYE#g#X&3ADx&tO+P_@mnQTz9gv30_sTsaGXkfNYXY{$(>*PEN3QL>I!k zp)KibPhrfX3%Z$H6SY`rXGYS~143wZrG2;=FLj50+VM6soI~up_>fU(2Wl@{BRsMi zO%sL3x?2l1cXTF)k&moNsHfQrQ+wu(gBt{sk#CU=UhrvJIncy@tJX5klLjgMn>~h= zg|FR&;@eh|C7`>s_9c~0-{IAPV){l|Ts`i=)AW;d9&KPc3fMeoTS%8@V~D8*h;&(^>yjT84MM}=%#LS7shLAuuj(0VAYoozhWjq z4LEr?wUe2^WGwdTIgWBkDUJa>YP@5d9^Rs$kCXmMRxuF*YMVrn?0NFyPl}>`&dqZb z<5eqR=ZG3>n2{6v6BvJ`YBZeeTtB88TAY(x0a58EWyuf>+^|x8Qa6wA|1Nb_p|nA zWWa}|z8a)--Wj`LqyFk_a3gN2>5{Rl_wbW?#by7&i*^hRknK%jwIH6=dQ8*-_{*x0j^DUfMX0`|K@6C<|1cgZ~D(e5vBFFm;HTZF(!vT8=T$K+|F)x3kqzBV4-=p1V(lzi(s7jdu0>LD#N=$Lk#3HkG!a zIF<7>%B7sRNzJ66KrFV76J<2bdYhxll0y2^_rdG=I%AgW4~)1Nvz=$1UkE^J%BxLo z+lUci`UcU062os*=`-j4IfSQA{w@y|3}Vk?i;&SSdh8n+$iHA#%ERL{;EpXl6u&8@ zzg}?hkEOUOJt?ZL=pWZFJ19mI1@P=$U5*Im1e_8Z${JsM>Ov?nh8Z zP5QvI!{Jy@&BP48%P2{Jr_VgzW;P@7)M9n|lDT|Ep#}7C$&ud&6>C^5ZiwKIg2McPU(4jhM!BD@@L(Gd*Nu$ji(ljZ<{FIeW_1Mmf;76{LU z-ywN~=uNN)Xi6$<12A9y)K%X|(W0p|&>>4OXB?IiYr||WKDOJPxiSe01NSV-h24^L z_>m$;|C+q!Mj**-qQ$L-*++en(g|hw;M!^%_h-iDjFHLo-n3JpB;p?+o2;`*jpvJU zLY^lt)Un4joij^^)O(CKs@7E%*!w>!HA4Q?0}oBJ7Nr8NQ7QmY^4~jvf0-`%waOLn zdNjAPaC0_7c|RVhw)+71NWjRi!y>C+Bl;Z`NiL^zn2*0kmj5gyhCLCxts*cWCdRI| zjsd=sT5BVJc^$GxP~YF$-U{-?kW6r@^vHXB%{CqYzU@1>dzf#3SYedJG-Rm6^RB7s zGM5PR(yKPKR)>?~vpUIeTP7A1sc8-knnJk*9)3t^e%izbdm>Y=W{$wm(cy1RB-19i za#828DMBY+ps#7Y8^6t)=Ea@%Nkt)O6JCx|ybC;Ap}Z@Zw~*}3P>MZLPb4Enxz9Wf zssobT^(R@KuShj8>@!1M7tm|2%-pYYDxz-5`rCbaTCG5{;Uxm z*g=+H1X8{NUvFGzz~wXa%Eo};I;~`37*WrRU&K0dPSB$yk(Z*@K&+mFal^?c zurbqB-+|Kb5|sznT;?Pj!+kgFY1#Dr;_%A(GIQC{3ct|{*Bji%FNa6c-thbpBkA;U zURV!Dr&X{0J}iht#-Qp2=xzuh(fM>zRoiGrYl5ttw2#r34gC41CCOC31m~^UPTK@s z6;A@)7O7_%C)>bnAXerYuAHdE93>j2N}H${zEc6&SbZ|-fiG*-qtGuy-qDelH(|u$ zorf8_T6Zqe#Ub!+e3oSyrskt_HyW_^5lrWt#30l)tHk|j$@YyEkXUOV;6B51L;M@=NIWZXU;GrAa(LGxO%|im%7F<-6N;en0Cr zLH>l*y?pMwt`1*cH~LdBPFY_l;~`N!Clyfr;7w<^X;&(ZiVdF1S5e(+Q%60zgh)s4 zn2yj$+mE=miVERP(g8}G4<85^-5f@qxh2ec?n+$A_`?qN=iyT1?U@t?V6DM~BIlBB z>u~eXm-aE>R0sQy!-I4xtCNi!!qh?R1!kKf6BoH2GG{L4%PAz0{Sh6xpuyI%*~u)s z%rLuFl)uQUCBQAtMyN;%)zFMx4loh7uTfKeB2Xif`lN?2gq6NhWhfz0u5WP9J>=V2 zo{mLtSy&BA!mSzs&CrKWq^y40JF5a&GSXIi2= z{EYb59J4}VwikL4P=>+mc6{($FNE@e=VUwG+KV21;<@lrN`mnz5jYGASyvz7BOG_6(p^eTxD-4O#lROgon;R35=|nj#eHIfJBYPWG>H>`dHKCDZ3`R{-?HO0mE~(5_WYcFmp8sU?wr*UkAQiNDGc6T zA%}GOLXlOWqL?WwfHO8MB#8M8*~Y*gz;1rWWoVSXP&IbKxbQ8+s%4Jnt?kDsq7btI zCDr0PZ)b;B%!lu&CT#RJzm{l{2fq|BcY85`w~3LSK<><@(2EdzFLt9Y_`;WXL6x`0 zDoQ?=?I@Hbr;*VVll1Gmd8*%tiXggMK81a+T(5Gx6;eNb8=uYn z5BG-0g>pP21NPn>$ntBh>`*})Fl|38oC^9Qz>~MAazH%3Q~Qb!ALMf$srexgPZ2@&c~+hxRi1;}+)-06)!#Mq<6GhP z-Q?qmgo${aFBApb5p}$1OJKTClfi8%PpnczyVKkoHw7Ml9e7ikrF0d~UB}i3vizos zXW4DN$SiEV9{faLt5bHy2a>33K%7Td-n5C*N;f&ZqAg#2hIqEb(y<&f4u5BWJ>2^4 z414GosL=Aom#m&=x_v<0-fp1r%oVJ{T-(xnomNJ(Dryv zh?vj+%=II_nV+@NR+(!fZZVM&(W6{6%9cm+o+Z6}KqzLw{(>E86uA1`_K$HqINlb1 zKelh3-jr2I9V?ych`{hta9wQ2c9=MM`2cC{m6^MhlL2{DLv7C^j z$xXBCnDl_;l|bPGMX@*tV)B!c|4oZyftUlP*?$YU9C_eAsuVHJ58?)zpbr30P*C`T z7y#ao`uE-SOG(Pi+`$=e^mle~)pRrdwL5)N;o{gpW21of(QE#U6w%*C~`v-z0QqBML!!5EeYA5IQB0 z^l01c;L6E(iytN!LhL}wfwP7W9PNAkb+)Cst?qg#$n;z41O4&v+8-zPs+XNb-q zIeeBCh#ivnFLUCwfS;p{LC0O7tm+Sf9Jn)~b%uwP{%69;QC)Ok0t%*a5M+=;y8j=v z#!*pp$9@!x;UMIs4~hP#pnfVc!%-D<+wsG@R2+J&%73lK|2G!EQC)O05TCV=&3g)C!lT=czLpZ@Sa%TYuoE?v8T8`V;e$#Zf2_Nj6nvBgh1)2 GZ~q4|mN%#X diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties deleted file mode 100644 index fbacf71..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradle/wrapper/gradle-wrapper.properties +++ /dev/null @@ -1,7 +0,0 @@ -distributionBase=GRADLE_USER_HOME -distributionPath=permwrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-8.10.2-bin.zip -networkTimeout=10000 -validateDistributionUrl=true -zipStoreBase=GRADLE_USER_HOME -zipStorePath=permwrapper/dists diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew deleted file mode 100644 index f5feea6..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew +++ /dev/null @@ -1,252 +0,0 @@ -#!/bin/sh - -# -# Copyright © 2015-2021 the original authors. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# https://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# SPDX-License-Identifier: Apache-2.0 -# - -############################################################################## -# -# Gradle start up script for POSIX generated by Gradle. -# -# Important for running: -# -# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is -# noncompliant, but you have some other compliant shell such as ksh or -# bash, then to run this script, type that shell name before the whole -# command line, like: -# -# ksh Gradle -# -# Busybox and similar reduced shells will NOT work, because this script -# requires all of these POSIX shell features: -# * functions; -# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», -# «${var#prefix}», «${var%suffix}», and «$( cmd )»; -# * compound commands having a testable exit status, especially «case»; -# * various built-in commands including «command», «set», and «ulimit». -# -# Important for patching: -# -# (2) This script targets any POSIX shell, so it avoids extensions provided -# by Bash, Ksh, etc; in particular arrays are avoided. -# -# The "traditional" practice of packing multiple parameters into a -# space-separated string is a well documented source of bugs and security -# problems, so this is (mostly) avoided, by progressively accumulating -# options in "$@", and eventually passing that to Java. -# -# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, -# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; -# see the in-line comments for details. -# -# There are tweaks for specific operating systems such as AIX, CygWin, -# Darwin, MinGW, and NonStop. -# -# (3) This script is generated from the Groovy template -# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt -# within the Gradle project. -# -# You can find Gradle at https://github.com/gradle/gradle/. -# -############################################################################## - -# Attempt to set APP_HOME - -# Resolve links: $0 may be a link -app_path=$0 - -# Need this for daisy-chained symlinks. -while - APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path - [ -h "$app_path" ] -do - ls=$( ls -ld "$app_path" ) - link=${ls#*' -> '} - case $link in #( - /*) app_path=$link ;; #( - *) app_path=$APP_HOME$link ;; - esac -done - -# This is normally unused -# shellcheck disable=SC2034 -APP_BASE_NAME=${0##*/} -# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) -APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s -' "$PWD" ) || exit - -# Use the maximum available, or set MAX_FD != -1 to use that value. -MAX_FD=maximum - -warn () { - echo "$*" -} >&2 - -die () { - echo - echo "$*" - echo - exit 1 -} >&2 - -# OS specific support (must be 'true' or 'false'). -cygwin=false -msys=false -darwin=false -nonstop=false -case "$( uname )" in #( - CYGWIN* ) cygwin=true ;; #( - Darwin* ) darwin=true ;; #( - MSYS* | MINGW* ) msys=true ;; #( - NONSTOP* ) nonstop=true ;; -esac - -CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar - - -# Determine the Java command to use to start the JVM. -if [ -n "$JAVA_HOME" ] ; then - if [ -x "$JAVA_HOME/jre/sh/java" ] ; then - # IBM's JDK on AIX uses strange locations for the executables - JAVACMD=$JAVA_HOME/jre/sh/java - else - JAVACMD=$JAVA_HOME/bin/java - fi - if [ ! -x "$JAVACMD" ] ; then - die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME - -Please set the JAVA_HOME variable in your environment to match the -location of your Java installation." - fi -else - JAVACMD=java - if ! command -v java >/dev/null 2>&1 - then - die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. - -Please set the JAVA_HOME variable in your environment to match the -location of your Java installation." - fi -fi - -# Increase the maximum file descriptors if we can. -if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then - case $MAX_FD in #( - max*) - # In POSIX sh, ulimit -H is undefined. That's why the result is checked to see if it worked. - # shellcheck disable=SC2039,SC3045 - MAX_FD=$( ulimit -H -n ) || - warn "Could not query maximum file descriptor limit" - esac - case $MAX_FD in #( - '' | soft) :;; #( - *) - # In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked. - # shellcheck disable=SC2039,SC3045 - ulimit -n "$MAX_FD" || - warn "Could not set maximum file descriptor limit to $MAX_FD" - esac -fi - -# Collect all arguments for the java command, stacking in reverse order: -# * args from the command line -# * the main class name -# * -classpath -# * -D...appname settings -# * --module-path (only if needed) -# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. - -# For Cygwin or MSYS, switch paths to Windows format before running java -if "$cygwin" || "$msys" ; then - APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) - CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) - - JAVACMD=$( cygpath --unix "$JAVACMD" ) - - # Now convert the arguments - kludge to limit ourselves to /bin/sh - for arg do - if - case $arg in #( - -*) false ;; # don't mess with options #( - /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath - [ -e "$t" ] ;; #( - *) false ;; - esac - then - arg=$( cygpath --path --ignore --mixed "$arg" ) - fi - # Roll the args list around exactly as many times as the number of - # args, so each arg winds up back in the position where it started, but - # possibly modified. - # - # NB: a `for` loop captures its iteration list before it begins, so - # changing the positional parameters here affects neither the number of - # iterations, nor the values presented in `arg`. - shift # remove old arg - set -- "$@" "$arg" # push replacement arg - done -fi - - -# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. -DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' - -# Collect all arguments for the java command: -# * DEFAULT_JVM_OPTS, JAVA_OPTS, JAVA_OPTS, and optsEnvironmentVar are not allowed to contain shell fragments, -# and any embedded shellness will be escaped. -# * For example: A user cannot expect ${Hostname} to be expanded, as it is an environment variable and will be -# treated as '${Hostname}' itself on the command line. - -set -- \ - "-Dorg.gradle.appname=$APP_BASE_NAME" \ - -classpath "$CLASSPATH" \ - org.gradle.wrapper.GradleWrapperMain \ - "$@" - -# Stop when "xargs" is not available. -if ! command -v xargs >/dev/null 2>&1 -then - die "xargs is not available" -fi - -# Use "xargs" to parse quoted args. -# -# With -n1 it outputs one arg per line, with the quotes and backslashes removed. -# -# In Bash we could simply go: -# -# readarray ARGS < <( xargs -n1 <<<"$var" ) && -# set -- "${ARGS[@]}" "$@" -# -# but POSIX shell has neither arrays nor command substitution, so instead we -# post-process each arg (as a line of input to sed) to backslash-escape any -# character that might be a shell metacharacter, then use eval to reverse -# that process (while maintaining the separation between arguments), and wrap -# the whole thing up as a single "set" statement. -# -# This will of course break if any of these variables contains a newline or -# an unmatched quote. -# - -eval "set -- $( - printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | - xargs -n1 | - sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | - tr '\n' ' ' - )" '"$@"' - -exec "$JAVACMD" "$@" diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat b/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat deleted file mode 100644 index 9d21a21..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/gradlew.bat +++ /dev/null @@ -1,94 +0,0 @@ -@rem -@rem Copyright 2015 the original author or authors. -@rem -@rem Licensed under the Apache License, Version 2.0 (the "License"); -@rem you may not use this file except in compliance with the License. -@rem You may obtain a copy of the License at -@rem -@rem https://www.apache.org/licenses/LICENSE-2.0 -@rem -@rem Unless required by applicable law or agreed to in writing, software -@rem distributed under the License is distributed on an "AS IS" BASIS, -@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -@rem See the License for the specific language governing permissions and -@rem limitations under the License. -@rem -@rem SPDX-License-Identifier: Apache-2.0 -@rem - -@if "%DEBUG%"=="" @echo off -@rem ########################################################################## -@rem -@rem Gradle startup script for Windows -@rem -@rem ########################################################################## - -@rem Set local scope for the variables with windows NT shell -if "%OS%"=="Windows_NT" setlocal - -set DIRNAME=%~dp0 -if "%DIRNAME%"=="" set DIRNAME=. -@rem This is normally unused -set APP_BASE_NAME=%~n0 -set APP_HOME=%DIRNAME% - -@rem Resolve any "." and ".." in APP_HOME to make it shorter. -for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi - -@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. -set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" - -@rem Find java.exe -if defined JAVA_HOME goto findJavaFromJavaHome - -set JAVA_EXE=java.exe -%JAVA_EXE% -version >NUL 2>&1 -if %ERRORLEVEL% equ 0 goto execute - -echo. 1>&2 -echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2 -echo. 1>&2 -echo Please set the JAVA_HOME variable in your environment to match the 1>&2 -echo location of your Java installation. 1>&2 - -goto fail - -:findJavaFromJavaHome -set JAVA_HOME=%JAVA_HOME:"=% -set JAVA_EXE=%JAVA_HOME%/bin/java.exe - -if exist "%JAVA_EXE%" goto execute - -echo. 1>&2 -echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2 -echo. 1>&2 -echo Please set the JAVA_HOME variable in your environment to match the 1>&2 -echo location of your Java installation. 1>&2 - -goto fail - -:execute -@rem Setup the command line - -set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar - - -@rem Execute Gradle -"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* - -:end -@rem End local scope for the variables with windows NT shell -if %ERRORLEVEL% equ 0 goto mainEnd - -:fail -rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of -rem the _cmd.exe /c_ return code! -set EXIT_CODE=%ERRORLEVEL% -if %EXIT_CODE% equ 0 set EXIT_CODE=1 -if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% -exit /b %EXIT_CODE% - -:mainEnd -if "%OS%"=="Windows_NT" endlocal - -:omega diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle b/src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle deleted file mode 100644 index 969c7b0..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/settings.gradle +++ /dev/null @@ -1,30 +0,0 @@ -import org.gradle.internal.os.OperatingSystem - -pluginManagement { - repositories { - mavenLocal() - gradlePluginPortal() - String frcYear = '2025' - File frcHome - if (OperatingSystem.current().isWindows()) { - String publicFolder = System.getenv('PUBLIC') - if (publicFolder == null) { - publicFolder = "C:\\Users\\Public" - } - def homeRoot = new File(publicFolder, "wpilib") - frcHome = new File(homeRoot, frcYear) - } else { - def userFolder = System.getProperty("user.home") - def homeRoot = new File(userFolder, "wpilib") - frcHome = new File(homeRoot, frcYear) - } - def frcHomeMaven = new File(frcHome, 'maven') - maven { - name 'frcHome' - url frcHomeMaven - } - } -} - -Properties props = System.getProperties(); -props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt deleted file mode 100644 index bb82515..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/deploy/example.txt +++ /dev/null @@ -1,3 +0,0 @@ -Files placed in this directory will be deployed to the RoboRIO into the -'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function -to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java deleted file mode 100644 index c50ba05..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Constants.java +++ /dev/null @@ -1,19 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot; - -/** - * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean - * constants. This class should not be used for any other purpose. All constants should be declared - * globally (i.e. public static). Do not put anything functional in this class. - * - *

It is advised to statically import this class (or one of its inner classes) wherever the - * constants are needed, to reduce verbosity. - */ -public final class Constants { - public static class OperatorConstants { - public static final int kDriverControllerPort = 0; - } -} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java deleted file mode 100644 index 8776e5d..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Main.java +++ /dev/null @@ -1,25 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot; - -import edu.wpi.first.wpilibj.RobotBase; - -/** - * Do NOT add any static variables to this class, or any initialization at all. Unless you know what - * you are doing, do not modify this file except to change the parameter class to the startRobot - * call. - */ -public final class Main { - private Main() {} - - /** - * Main initialization function. Do not perform any initialization here. - * - *

If you change your main robot class, change the parameter type. - */ - public static void main(String... args) { - RobotBase.startRobot(Robot::new); - } -} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java deleted file mode 100644 index c711f35..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/Robot.java +++ /dev/null @@ -1,100 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot; - -import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.CommandScheduler; - -/** - * The methods in this class are called automatically corresponding to each mode, as described in - * the TimedRobot documentation. If you change the name of this class or the package after creating - * this project, you must also update the Main.java file in the project. - */ -public class Robot extends TimedRobot { - private Command m_autonomousCommand; - - private final RobotContainer m_robotContainer; - - /** - * This function is run when the robot is first started up and should be used for any - * initialization code. - */ - public Robot() { - // Instantiate our RobotContainer. This will perform all our button bindings, and put our - // autonomous chooser on the dashboard. - m_robotContainer = new RobotContainer(); - } - - /** - * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. - * - *

This runs after the mode specific periodic functions, but before LiveWindow and - * SmartDashboard integrated updating. - */ - @Override - public void robotPeriodic() { - // Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled - // commands, running already-scheduled commands, removing finished or interrupted commands, - // and running subsystem periodic() methods. This must be called from the robot's periodic - // block in order for anything in the Command-based framework to work. - CommandScheduler.getInstance().run(); - } - - /** This function is called once each time the robot enters Disabled mode. */ - @Override - public void disabledInit() {} - - @Override - public void disabledPeriodic() {} - - /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ - @Override - public void autonomousInit() { - - // schedule the autonomous command (example) - if (m_autonomousCommand != null) { - m_autonomousCommand.schedule(); - } - } - - /** This function is called periodically during autonomous. */ - @Override - public void autonomousPeriodic() {} - - @Override - public void teleopInit() { - // This makes sure that the autonomous stops running when - // teleop starts running. If you want the autonomous to - // continue until interrupted by another command, remove - // this line or comment it out. - if (m_autonomousCommand != null) { - m_autonomousCommand.cancel(); - } - } - - /** This function is called periodically during operator control. */ - @Override - public void teleopPeriodic() {} - - @Override - public void testInit() { - // Cancels all running commands at the start of test mode. - CommandScheduler.getInstance().cancelAll(); - } - - /** This function is called periodically during test mode. */ - @Override - public void testPeriodic() {} - - /** This function is called once when the robot is first started up. */ - @Override - public void simulationInit() {} - - /** This function is called periodically whilst in simulation. */ - @Override - public void simulationPeriodic() {} -} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java deleted file mode 100644 index 9c94d46..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/RobotContainer.java +++ /dev/null @@ -1,59 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot; - -import frc.robot.Constants.OperatorConstants; -import frc.robot.commands.Intake; -import frc.robot.subsystems.IntakeSubsystem; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import edu.wpi.first.wpilibj2.command.button.Trigger; - -/** - * This class is where the bulk of the robot should be declared. Since Command-based is a - * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} - * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including - * subsystems, commands, and trigger mappings) should be declared here. - */ -public class RobotContainer { - // The robot's subsystems and commands are defined here... - private final IntakeSubsystem IntakeSubsystem = new IntakeSubsystem(); - - // Replace with CommandPS4Controller or CommandJoystick if needed - private final CommandXboxController m_driverController = - new CommandXboxController(OperatorConstants.kDriverControllerPort); - - /** The container for the robot. Contains subsystems, OI devices, and commands. */ - public RobotContainer() { - // Configure the trigger bindings - configureBindings(); - } - - /** - * Use this method to define your trigger->command mappings. Triggers can be created via the - * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary - * predicate, or via the named factories in {@link - * edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for {@link - * CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller - * PS4} controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight - * joysticks}. - */ - private void configureBindings() { - // Schedule `ExampleCommand` when `exampleCondition` changes to `true` - // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed, - // cancelling on release. - m_driverController.a().whileTrue(new Intake(IntakeSubsystem)); - } - - /** - * Use this to pass the autonomous command to the main {@link Robot} class. - * - * @return the command to run in autonomous - */ - // public Command getAutonomousCommand() { - // // An example command will be run in autonomous - // return Autos.exampleAuto(IntakeSubsystem); - // } -} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java deleted file mode 100644 index c44a0f7..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Autos.java +++ /dev/null @@ -1,20 +0,0 @@ -// // Copyright (c) FIRST and other WPILib contributors. -// // Open Source Software; you can modify and/or share it under the terms of -// // the WPILib BSD license file in the root directory of this project. - -// package frc.robot.commands; - -// import frc.robot.subsystems.IntakeSubsystem; -// import edu.wpi.first.wpilibj2.command.Command; -// import edu.wpi.first.wpilibj2.command.Commands; - -// public final class Autos { -// /** Example static factory for an autonomous command. */ -// // public static Command exampleAuto(IntakeSubsystem subsystem) { -// // return Commands.sequence(subsystem.exampleMethodCommand(), new Intake(subsystem)); -// } - -// private Autos() { -// throw new UnsupportedOperationException("This is a utility class!"); -// } -// } diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java deleted file mode 100644 index 447d133..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/commands/Intake.java +++ /dev/null @@ -1,42 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.commands; - -import frc.robot.subsystems.IntakeSubsystem; -import edu.wpi.first.wpilibj2.command.Command; - -/** An example command that uses an example subsystem. */ -public class Intake extends Command { - - private final IntakeSubsystem intakeSubsystem; - - public Intake(IntakeSubsystem intakeSubsystem) { - this.intakeSubsystem = new IntakeSubsystem(); - addRequirements(intakeSubsystem); - } - - // Called when the command is initially scheduled. - @Override - public void initialize() { - } - - // Called every time the scheduler runs while the command is scheduled. - @Override - public void execute() { - intakeSubsystem.setSpeed(1.0); - } - - // Called once the command ends or is interrupted. - @Override - public void end(boolean interrupted) { - intakeSubsystem.setSpeed(0.0); - } - - // Returns true when the command should end. - @Override - public boolean isFinished() { - return false; - } -} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java deleted file mode 100644 index af8bfd2..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/src/main/java/frc/robot/subsystems/IntakeSubsystem.java +++ /dev/null @@ -1,37 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.subsystems; - -import com.ctre.phoenix6.hardware.TalonFX; - -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.SubsystemBase; - -public class IntakeSubsystem extends SubsystemBase { - private final TalonFX myMotor; - - public IntakeSubsystem() { - myMotor = new TalonFX(2); - } - -public void setSpeed(double speed){ - myMotor.set(speed); -} - - public boolean exampleCondition() { - // Query some boolean state, such as a digital sensor. - return false; - } - - @Override - public void periodic() { - // This method will be called once per scheduler run - } - - @Override - public void simulationPeriodic() { - // This method will be called once per scheduler run during simulation - } -} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json b/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json deleted file mode 100644 index 092ae53..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/Phoenix6-25.0.0-beta-3.json +++ /dev/null @@ -1,359 +0,0 @@ -{ - "fileName": "Phoenix6-25.0.0-beta-3.json", - "name": "CTRE-Phoenix (v6)", - "version": "25.0.0-beta-3", - "frcYear": "2025", - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json", - "conflictsWith": [ - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", - "offlineFileName": "Phoenix6-replay-frc2025-beta-latest.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "25.0.0-beta-3" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "api-cpp", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "api-cpp-sim", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "25.0.0-beta-3", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-cpp", - "version": "25.0.0-beta-3", - "libName": "CTRE_Phoenix6_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.0.0-beta-3", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "25.0.0-beta-3", - "libName": "CTRE_Phoenix6_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "25.0.0-beta-3", - "libName": "CTRE_PhoenixTools_Sim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "25.0.0-beta-3", - "libName": "CTRE_SimTalonSRX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "25.0.0-beta-3", - "libName": "CTRE_SimVictorSPX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-3", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.0.0-beta-3", - "libName": "CTRE_SimCANCoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.0.0-beta-3", - "libName": "CTRE_SimProTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "25.0.0-beta-3", - "libName": "CTRE_SimProCANcoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "25.0.0-beta-3", - "libName": "CTRE_SimProPigeon2", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json b/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json deleted file mode 100644 index 3718e0a..0000000 --- a/src/main/java/frc/robot/subsystems/intake/IntakeThing/vendordeps/WPILibNewCommands.json +++ /dev/null @@ -1,38 +0,0 @@ -{ - "fileName": "WPILibNewCommands.json", - "name": "WPILib-New-Commands", - "version": "1.0.0", - "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", - "frcYear": "2025", - "mavenUrls": [], - "jsonUrl": "", - "javaDependencies": [ - { - "groupId": "edu.wpi.first.wpilibNewCommands", - "artifactId": "wpilibNewCommands-java", - "version": "wpilib" - } - ], - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "edu.wpi.first.wpilibNewCommands", - "artifactId": "wpilibNewCommands-cpp", - "version": "wpilib", - "libName": "wpilibNewCommands", - "headerClassifier": "headers", - "sourcesClassifier": "sources", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena", - "linuxarm32", - "linuxarm64", - "windowsx86-64", - "windowsx86", - "linuxx86-64", - "osxuniversal" - ] - } - ] -} From ca5b59c0cbe4238acfb580a3816002515816e81a Mon Sep 17 00:00:00 2001 From: Ishan1522 Date: Fri, 20 Dec 2024 17:57:42 -0500 Subject: [PATCH 08/13] Fun arm things --- .../java/frc/robot/subsystems/arm/Arm.java | 12 ++++ .../robot/subsystems/arm/ArmConstants.java | 15 +++++ .../robot/subsystems/arm/ArmInterface.java | 20 +++++++ .../frc/robot/subsystems/arm/PhysicalArm.java | 31 ++++++++++ .../subsystems/arm/SimulatedElevator.java | 21 +++++++ .../robot/subsystems/elevator/Elevator.java | 3 + .../elevator/ElevatorConstants.java | 3 + .../elevator/ElevatorInterface.java | 8 +++ .../subsystems/elevator/PhysicalElevator.java | 4 +- .../elevator/SimulatedElevator.java | 58 +++++++++---------- 10 files changed, 144 insertions(+), 31 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/arm/Arm.java create mode 100644 src/main/java/frc/robot/subsystems/arm/ArmConstants.java create mode 100644 src/main/java/frc/robot/subsystems/arm/ArmInterface.java create mode 100644 src/main/java/frc/robot/subsystems/arm/PhysicalArm.java create mode 100644 src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java diff --git a/src/main/java/frc/robot/subsystems/arm/Arm.java b/src/main/java/frc/robot/subsystems/arm/Arm.java new file mode 100644 index 0000000..6dfec1f --- /dev/null +++ b/src/main/java/frc/robot/subsystems/arm/Arm.java @@ -0,0 +1,12 @@ +package frc.robot.subsystems.arm; + +import org.littletonrobotics.junction.AutoLog; + +public class Arm { + private ArmInterface armInterface; + private ArmInputsAutoLogged input = new ArmInputsAutoLogged(); + + public Arm(ArmInterface armInterface) { + this.armInterface = armInterface; + } +} diff --git a/src/main/java/frc/robot/subsystems/arm/ArmConstants.java b/src/main/java/frc/robot/subsystems/arm/ArmConstants.java new file mode 100644 index 0000000..78dedfb --- /dev/null +++ b/src/main/java/frc/robot/subsystems/arm/ArmConstants.java @@ -0,0 +1,15 @@ +package frc.robot.subsystems.arm; + +public class ArmConstants { + public static final int ARM_MOTOR_ID = 0 - 9; + + public static final double ARM_P = 0 - 9; + public static final double ARM_I = 0 - 9; + public static final double ARM_D = 0 - 9; + + public static final double ARM_GEAR_RATIO = 0 - 9; + public static final double ARM_INERTIA_MASS = 0 - 9; + public static final double ARM_LENGTH_METERS = 0 - 9; + public static final double MINIMUM_ANGLE_RADIANS = 0 - 9; + public static final double MAXIMUM_ANGLE_RADIANS = 0 - 9; +} diff --git a/src/main/java/frc/robot/subsystems/arm/ArmInterface.java b/src/main/java/frc/robot/subsystems/arm/ArmInterface.java new file mode 100644 index 0000000..0f61537 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/arm/ArmInterface.java @@ -0,0 +1,20 @@ +package frc.robot.subsystems.arm; + +import org.littletonrobotics.junction.AutoLog; + +public interface ArmInterface { + + @AutoLog + public static class ArmInputs { + public double angle = 0.0; + } + + public default void updateInputs(ArmInputs inputs) {} + + public default void setAngle(double angle) {} + + public default double getAngle() { + return 0.0; + } +} + \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java b/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java new file mode 100644 index 0000000..214fe02 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java @@ -0,0 +1,31 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.arm; + +import org.littletonrobotics.junction.AutoLog; + +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.NeutralModeValue; + +public class PhysicalArm implements ArmInterface { + private TalonFX armMotor = new TalonFX(ArmConstants.ARM_MOTOR_ID); + + public PhysicalArm() { + TalonFXConfiguration armConfig = new TalonFXConfiguration(); + + armConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + + armConfig.Slot0.kP = ArmConstants.ARM_P; + armConfig.Slot0.kI = ArmConstants.ARM_I; + armConfig.Slot0.kD = ArmConstants.ARM_D; + + armMotor.getConfigurator().apply(armConfig); + } + + @Override + public void setAngle(double angle) { + } +} diff --git a/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java new file mode 100644 index 0000000..a87ad84 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java @@ -0,0 +1,21 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.arm; + +import org.littletonrobotics.junction.AutoLog; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; + +/** Add your docs here. */ +public class SimulatedElevator implements ArmInterface { + private SingleJointedArmSim armSim = new SingleJointedArmSim(DCMotor.getFalcon500(1), ArmConstants.ARM_GEAR_RATIO, ArmConstants.ARM_INERTIA_MASS, ArmConstants.ARM_LENGTH_METERS, ArmConstants.MINIMUM_ANGLE_RADIANS, ArmConstants.MAXIMUM_ANGLE_RADIANS, false, 0, null); + private PIDController pidSim; + + public SimulatedElevator() { + pidSim = new PIDController(ArmConstants.ARM_P, ArmConstants.ARM_I, ArmConstants.ARM_D); + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java index a894a76..a01530d 100644 --- a/src/main/java/frc/robot/subsystems/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -1,3 +1,6 @@ +/** + * This subsystem is an elevator that uses PID for its position. + */ package frc.robot.subsystems.elevator; import edu.wpi.first.wpilibj2.command.SubsystemBase; diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java index 5856e6c..c3f8da2 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java @@ -1,6 +1,9 @@ package frc.robot.subsystems.elevator; public class ElevatorConstants { + public static final int ELEVATOR_LEADER_MOTOR_ID = 0 - 9; + public static final int ELEVATOR_FOLLOWER_MOTOR_ID = 0 - 9; + public static final double ELEVATOR_P = 0 - 9; public static final double ELEVATOR_I = 0 - 9; public static final double ELEVATOR_D = 0 - 9; diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java index e7bb047..d68dd27 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java @@ -11,8 +11,16 @@ public static class ElevatorInputs { public double followerMotorPosition = 0.0; } + /** + * Updates inputs for elevator for AdvantageKit to log + * @param inputs values related to the elevator + */ public default void updateInputs(ElevatorInputs inputs) {} + /** + * Gets the current position of the elevator + * @return + */ public default double getElevatorPosition() { return 0.0; } diff --git a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java index 541f450..c83160d 100644 --- a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java @@ -12,8 +12,8 @@ /** Add your docs here. */ public class PhysicalElevator { - private TalonFX leaderMotor = new TalonFX(0); - private TalonFX followerMotor = new TalonFX(0); + private TalonFX leaderMotor = new TalonFX(ElevatorConstants.ELEVATOR_LEADER_MOTOR_ID); + private TalonFX followerMotor = new TalonFX(ElevatorConstants.ELEVATOR_FOLLOWER_MOTOR_ID); StatusSignal leaderPosition; StatusSignal followerPosition; diff --git a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java index a9d0384..734c0af 100644 --- a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java @@ -6,33 +6,33 @@ /** Add your docs here. */ public class SimulatedElevator implements ElevatorInterface { - private ElevatorSim simulatedElevator = new ElevatorSim(DCMotor.getFalcon500(2), ElevatorConstants.ELEVATOR_GEAR_RATIO, ElevatorConstants.ELEVATOR_CARRIAGE_MASS, ElevatorConstants.DRUM_RADIUS, ElevatorConstants.MIN_HEIGHT, ElevatorConstants.MAX_HEIGHT, true, 0.0); - private PIDController simPID; - private double currentVolts; - - public SimulatedElevator() { - simPID = new PIDController(ElevatorConstants.ELEVATOR_P, ElevatorConstants.ELEVATOR_I, ElevatorConstants.ELEVATOR_D); - } - - public void updateInputs(ElevatorInputs inputs) { - inputs.leaderMotorPosition = getElevatorPosition(); - inputs.followerMotorPosition = getElevatorPosition(); - } - - public void setElevatorPosition(double position) { - simulatedElevator.setState(simPID.calculate(position), ElevatorConstants.VELOCITY_METERS_PER_SECOND); - } - - public double getElevatorPosition() { - return simulatedElevator.getPositionMeters(); - } - - public void setVolts(double volts) { - currentVolts = simPID.calculate(volts); - simulatedElevator.setInputVoltage(currentVolts); - } - - public double getVolts() { - return currentVolts; - } + private ElevatorSim elevatorSim = new ElevatorSim(DCMotor.getFalcon500(2), ElevatorConstants.ELEVATOR_GEAR_RATIO, ElevatorConstants.ELEVATOR_CARRIAGE_MASS, ElevatorConstants.DRUM_RADIUS, ElevatorConstants.MIN_HEIGHT, ElevatorConstants.MAX_HEIGHT, true, 0.0); + private PIDController simPID; + private double currentVolts; + + public SimulatedElevator() { + simPID = new PIDController(ElevatorConstants.ELEVATOR_P, ElevatorConstants.ELEVATOR_I, ElevatorConstants.ELEVATOR_D); + } + + public void updateInputs(ElevatorInputs inputs) { + inputs.leaderMotorPosition = getElevatorPosition(); + inputs.followerMotorPosition = getElevatorPosition(); + } + + public void setElevatorPosition(double position) { + elevatorSim.setState(simPID.calculate(position), ElevatorConstants.VELOCITY_METERS_PER_SECOND); + } + + public double getElevatorPosition() { + return elevatorSim.getPositionMeters(); + } + + public void setVolts(double volts) { + currentVolts = simPID.calculate(volts); + elevatorSim.setInputVoltage(currentVolts); + } + + public double getVolts() { + return currentVolts; + } } From 312f880b2cbf487258dbc16e4354dc22e1291d87 Mon Sep 17 00:00:00 2001 From: Ishan <98932677+Ishan1522@users.noreply.github.com> Date: Thu, 2 Jan 2025 15:20:11 -0500 Subject: [PATCH 09/13] format --- src/main/java/frc/robot/BuildConstants.java | 6 ++---- .../robot/commands/intake/RegularIntake.java | 2 +- .../frc/robot/extras/util/JoystickUtil.java | 4 ++-- src/main/java/frc/robot/subsystems/arm/Arm.java | 4 +--- .../frc/robot/subsystems/arm/ArmInterface.java | 5 ++--- .../frc/robot/subsystems/arm/PhysicalArm.java | 5 +---- .../robot/subsystems/arm/SimulatedElevator.java | 16 ++++++++++++---- .../frc/robot/subsystems/elevator/Elevator.java | 5 ++--- .../subsystems/elevator/ElevatorConstants.java | 6 +++--- .../subsystems/elevator/ElevatorInterface.java | 4 +++- .../subsystems/elevator/PhysicalElevator.java | 6 ++---- .../subsystems/elevator/SimulatedElevator.java | 17 +++++++++++++++-- .../frc/robot/subsystems/intake/Intake.java | 3 +-- .../subsystems/intake/IntakeConstants.java | 2 +- .../subsystems/intake/IntakeInterface.java | 5 ++++- .../robot/subsystems/intake/PhysicalIntake.java | 5 +---- .../subsystems/intake/SimulatedIntake.java | 15 ++++++--------- .../robot/subsystems/swerve/SwerveDrive.java | 2 +- .../swerve/odometryThread/OdometryThread.java | 5 +++-- 19 files changed, 63 insertions(+), 54 deletions(-) diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index f14a657..52b537e 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -1,8 +1,6 @@ package frc.robot; -/** - * Automatically generated file containing build version information. - */ +/** Automatically generated file containing build version information. */ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "4829-BaseRobotCode"; @@ -15,5 +13,5 @@ public final class BuildConstants { public static final long BUILD_UNIX_TIME = 1734561708416L; public static final int DIRTY = 1; - private BuildConstants(){} + private BuildConstants() {} } diff --git a/src/main/java/frc/robot/commands/intake/RegularIntake.java b/src/main/java/frc/robot/commands/intake/RegularIntake.java index 7b9ca19..07eab50 100644 --- a/src/main/java/frc/robot/commands/intake/RegularIntake.java +++ b/src/main/java/frc/robot/commands/intake/RegularIntake.java @@ -7,7 +7,7 @@ public class RegularIntake extends Command { private final Intake intakeSubsystem; - + public RegularIntake(Intake intake) { this.intakeSubsystem = intake; addRequirements(this.intakeSubsystem); diff --git a/src/main/java/frc/robot/extras/util/JoystickUtil.java b/src/main/java/frc/robot/extras/util/JoystickUtil.java index a9c2030..444024e 100644 --- a/src/main/java/frc/robot/extras/util/JoystickUtil.java +++ b/src/main/java/frc/robot/extras/util/JoystickUtil.java @@ -4,7 +4,7 @@ import java.util.function.DoubleSupplier; public class JoystickUtil { - + /** * Deadbands a value to 0 * @@ -69,4 +69,4 @@ public static double[] modifyAxisPolar( Math.copySign(Math.pow(yInput, exponent), yInput) }; } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/arm/Arm.java b/src/main/java/frc/robot/subsystems/arm/Arm.java index 6dfec1f..10dacba 100644 --- a/src/main/java/frc/robot/subsystems/arm/Arm.java +++ b/src/main/java/frc/robot/subsystems/arm/Arm.java @@ -1,11 +1,9 @@ package frc.robot.subsystems.arm; -import org.littletonrobotics.junction.AutoLog; - public class Arm { private ArmInterface armInterface; private ArmInputsAutoLogged input = new ArmInputsAutoLogged(); - + public Arm(ArmInterface armInterface) { this.armInterface = armInterface; } diff --git a/src/main/java/frc/robot/subsystems/arm/ArmInterface.java b/src/main/java/frc/robot/subsystems/arm/ArmInterface.java index 0f61537..68b1081 100644 --- a/src/main/java/frc/robot/subsystems/arm/ArmInterface.java +++ b/src/main/java/frc/robot/subsystems/arm/ArmInterface.java @@ -3,18 +3,17 @@ import org.littletonrobotics.junction.AutoLog; public interface ArmInterface { - + @AutoLog public static class ArmInputs { public double angle = 0.0; } public default void updateInputs(ArmInputs inputs) {} - + public default void setAngle(double angle) {} public default double getAngle() { return 0.0; } } - \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java b/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java index 214fe02..3ee6ebd 100644 --- a/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java +++ b/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java @@ -4,8 +4,6 @@ package frc.robot.subsystems.arm; -import org.littletonrobotics.junction.AutoLog; - import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.NeutralModeValue; @@ -26,6 +24,5 @@ public PhysicalArm() { } @Override - public void setAngle(double angle) { - } + public void setAngle(double angle) {} } diff --git a/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java index a87ad84..8aa6816 100644 --- a/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java +++ b/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java @@ -4,18 +4,26 @@ package frc.robot.subsystems.arm; -import org.littletonrobotics.junction.AutoLog; - import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; /** Add your docs here. */ public class SimulatedElevator implements ArmInterface { - private SingleJointedArmSim armSim = new SingleJointedArmSim(DCMotor.getFalcon500(1), ArmConstants.ARM_GEAR_RATIO, ArmConstants.ARM_INERTIA_MASS, ArmConstants.ARM_LENGTH_METERS, ArmConstants.MINIMUM_ANGLE_RADIANS, ArmConstants.MAXIMUM_ANGLE_RADIANS, false, 0, null); + private SingleJointedArmSim armSim = + new SingleJointedArmSim( + DCMotor.getFalcon500(1), + ArmConstants.ARM_GEAR_RATIO, + ArmConstants.ARM_INERTIA_MASS, + ArmConstants.ARM_LENGTH_METERS, + ArmConstants.MINIMUM_ANGLE_RADIANS, + ArmConstants.MAXIMUM_ANGLE_RADIANS, + false, + 0, + null); private PIDController pidSim; public SimulatedElevator() { pidSim = new PIDController(ArmConstants.ARM_P, ArmConstants.ARM_I, ArmConstants.ARM_D); } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java index a01530d..82216d9 100644 --- a/src/main/java/frc/robot/subsystems/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -1,6 +1,4 @@ -/** - * This subsystem is an elevator that uses PID for its position. - */ +/** This subsystem is an elevator that uses PID for its position. */ package frc.robot.subsystems.elevator; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -8,6 +6,7 @@ public class Elevator extends SubsystemBase { /** Creates a new Elevator. */ private ElevatorInterface elevatorInterface; + private ElevatorInputsAutoLogged inputs = new ElevatorInputsAutoLogged(); public Elevator(ElevatorInterface elevatorInterface) { diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java index c3f8da2..e02141b 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorConstants.java @@ -3,11 +3,11 @@ public class ElevatorConstants { public static final int ELEVATOR_LEADER_MOTOR_ID = 0 - 9; public static final int ELEVATOR_FOLLOWER_MOTOR_ID = 0 - 9; - + public static final double ELEVATOR_P = 0 - 9; public static final double ELEVATOR_I = 0 - 9; public static final double ELEVATOR_D = 0 - 9; - + public static final double DRUM_RADIUS = 0 - 9; public static final double ELEVATOR_GEAR_RATIO = 2; public static final double ELEVATOR_CARRIAGE_MASS = 0 - 9; @@ -22,4 +22,4 @@ public class ElevatorConstants { public static final double ELEVATOR_OVER_DEFENSE = MAX_HEIGHT; public static final double VELOCITY_METERS_PER_SECOND = 0 - 9; -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java index d68dd27..8ed4759 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorInterface.java @@ -3,7 +3,7 @@ import org.littletonrobotics.junction.AutoLog; public interface ElevatorInterface { - + @AutoLog public static class ElevatorInputs { public double leaderMotorPosition = 0.0; @@ -13,12 +13,14 @@ public static class ElevatorInputs { /** * Updates inputs for elevator for AdvantageKit to log + * * @param inputs values related to the elevator */ public default void updateInputs(ElevatorInputs inputs) {} /** * Gets the current position of the elevator + * * @return */ public default double getElevatorPosition() { diff --git a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java index c83160d..83f09d7 100644 --- a/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/PhysicalElevator.java @@ -1,11 +1,8 @@ package frc.robot.subsystems.elevator; -import java.io.ObjectInputFilter.Status; - import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.hardware.TalonFX; - import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.Voltage; import frc.robot.subsystems.elevator.ElevatorInterface.ElevatorInputs; @@ -54,7 +51,8 @@ public void setElevatorPosition(double position) { public void setVolts(double volts) { leaderMotor.setVoltage(volts); - followerMotor.setVoltage(volts);; + followerMotor.setVoltage(volts); + ; } public double getVolts() { diff --git a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java index 734c0af..4d77838 100644 --- a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java @@ -6,12 +6,25 @@ /** Add your docs here. */ public class SimulatedElevator implements ElevatorInterface { - private ElevatorSim elevatorSim = new ElevatorSim(DCMotor.getFalcon500(2), ElevatorConstants.ELEVATOR_GEAR_RATIO, ElevatorConstants.ELEVATOR_CARRIAGE_MASS, ElevatorConstants.DRUM_RADIUS, ElevatorConstants.MIN_HEIGHT, ElevatorConstants.MAX_HEIGHT, true, 0.0); + private ElevatorSim elevatorSim = + new ElevatorSim( + DCMotor.getFalcon500(2), + ElevatorConstants.ELEVATOR_GEAR_RATIO, + ElevatorConstants.ELEVATOR_CARRIAGE_MASS, + ElevatorConstants.DRUM_RADIUS, + ElevatorConstants.MIN_HEIGHT, + ElevatorConstants.MAX_HEIGHT, + true, + 0.0); private PIDController simPID; private double currentVolts; public SimulatedElevator() { - simPID = new PIDController(ElevatorConstants.ELEVATOR_P, ElevatorConstants.ELEVATOR_I, ElevatorConstants.ELEVATOR_D); + simPID = + new PIDController( + ElevatorConstants.ELEVATOR_P, + ElevatorConstants.ELEVATOR_I, + ElevatorConstants.ELEVATOR_D); } public void updateInputs(ElevatorInputs inputs) { diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.java b/src/main/java/frc/robot/subsystems/intake/Intake.java index 80bd0c2..d109cec 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/intake/Intake.java @@ -1,6 +1,5 @@ package frc.robot.subsystems.intake; -import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.Logger; @@ -27,4 +26,4 @@ public void periodic() { intakeInterface.updateInputs(inputs); Logger.processInputs("OTBIntake", inputs); } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java index 9700cfe..a12910d 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java @@ -24,4 +24,4 @@ public final class IntakeConstants { public static final double INTAKE_SUPPLY_LIMIT = 40; public static final boolean INTAKE_STATOR_ENABLE = true; public static final boolean INTAKE_SUPPLY_ENABLE = true; -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java b/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java index 725f336..0856c0e 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeInterface.java @@ -16,21 +16,24 @@ public static class IntakeInputs { /** * Updates intake values + * * @param inputs */ default void updateInputs(IntakeInputs inputs) {} /** * Sets the intake speed + * * @param speed The intake speed value from -1 to 1 (negative being reversed) */ default void setIntakeSpeed(double speed) {} /** * Gets the current speed of the intake + * * @return Current velocity of the intake */ default double getIntakeSpeed() { return 0.0; } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java index 919a68c..1a863df 100644 --- a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java @@ -4,11 +4,8 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.signals.FeedbackSensorSourceValue; -import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; -import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import frc.robot.Constants.HardwareConstants; @@ -51,4 +48,4 @@ public double getIntakeSpeed() { intakeMotor.getVelocity().refresh(); return intakeMotor.getVelocity().getValueAsDouble(); } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java index ef43c72..abd2aa1 100644 --- a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java @@ -1,13 +1,9 @@ package frc.robot.subsystems.intake; -import edu.wpi.first.math.controller.ArmFeedforward; -import edu.wpi.first.math.controller.ProfiledPIDController; -import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints; -import edu.wpi.first.wpilibj.simulation.DCMotorSim; -import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; import static edu.wpi.first.units.Units.*; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.wpilibj.simulation.DCMotorSim; public class SimulatedIntake implements IntakeInterface { DCMotorSim intakeSim = new DCMotorSim(null, DCMotor.getFalcon500(1), 0); @@ -15,8 +11,9 @@ public class SimulatedIntake implements IntakeInterface { public SimulatedIntake(IntakeInputs inputs) { intakeSim.update(0.02); - - inputs.intakeVelocity = RadiansPerSecond.of(intakeSim.getAngularVelocityRadPerSec()).in(RotationsPerSecond); + + inputs.intakeVelocity = + RadiansPerSecond.of(intakeSim.getAngularVelocityRadPerSec()).in(RotationsPerSecond); inputs.intakeCurrentAmps = intakeSim.getCurrentDrawAmps(); inputs.intakeAppliedVolts = intakeAppliedVolts; } @@ -30,4 +27,4 @@ public void setIntakeSpeed(double speed) { public double getIntakeSpeed() { return RadiansPerSecond.of(intakeSim.getAngularVelocityRadPerSec()).in(RotationsPerSecond); } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java b/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java index 5f0b642..740bb8b 100644 --- a/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java +++ b/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java @@ -18,8 +18,8 @@ import frc.robot.extras.util.DeviceCANBus; import frc.robot.extras.util.TimeUtil; import frc.robot.subsystems.swerve.SwerveConstants.DriveConstants; -import frc.robot.subsystems.swerve.gyroIO.GyroInterface; import frc.robot.subsystems.swerve.gyroIO.GyroInputsAutoLogged; +import frc.robot.subsystems.swerve.gyroIO.GyroInterface; import frc.robot.subsystems.swerve.moduleIO.ModuleInterface; import frc.robot.subsystems.swerve.odometryThread.OdometryThread; import frc.robot.subsystems.swerve.odometryThread.OdometryThreadInputsAutoLogged; diff --git a/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java b/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java index b15e05c..9be8094 100644 --- a/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java +++ b/src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java @@ -54,8 +54,9 @@ static OdometryThread createInstance(DeviceCANBus canBus) { registeredInputs.toArray(new OdometryDoubleInput[0]), registeredStatusSignals.toArray(new BaseStatusSignal[0])); case SIM -> new OdometryThreadSim(); - //case REPLAY -> inputs -> {}; - default -> throw new IllegalArgumentException("Unexpected value: " + Robot.CURRENT_ROBOT_MODE); + // case REPLAY -> inputs -> {}; + default -> + throw new IllegalArgumentException("Unexpected value: " + Robot.CURRENT_ROBOT_MODE); }; } From fd61b3f02c2388729782a03902947bbc62422b4d Mon Sep 17 00:00:00 2001 From: Ishan <98932677+Ishan1522@users.noreply.github.com> Date: Thu, 2 Jan 2025 15:28:16 -0500 Subject: [PATCH 10/13] Remove unnecessary blank line in MathUtil.java --- src/main/java/frc/robot/extras/util/MathUtil.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/java/frc/robot/extras/util/MathUtil.java b/src/main/java/frc/robot/extras/util/MathUtil.java index f8685bc..65acfdf 100644 --- a/src/main/java/frc/robot/extras/util/MathUtil.java +++ b/src/main/java/frc/robot/extras/util/MathUtil.java @@ -2,7 +2,6 @@ import edu.wpi.first.math.geometry.Rotation3d; import frc.robot.BuildConstants; - import java.util.Random; public class MathUtil { From 2eb99bd5948f202956087ca91bffce7eaa7bc459 Mon Sep 17 00:00:00 2001 From: Ishan <98932677+Ishan1522@users.noreply.github.com> Date: Sat, 4 Jan 2025 02:58:07 -0500 Subject: [PATCH 11/13] nerf intake to not use position for otb intake. delete arm example bc it is redundant with elevator existing --- .../java/frc/robot/subsystems/arm/Arm.java | 10 ------- .../robot/subsystems/arm/ArmConstants.java | 15 ---------- .../robot/subsystems/arm/ArmInterface.java | 19 ------------ .../frc/robot/subsystems/arm/PhysicalArm.java | 28 ------------------ .../subsystems/arm/SimulatedElevator.java | 29 ------------------- .../robot/subsystems/elevator/Elevator.java | 4 +++ .../elevator/SimulatedElevator.java | 2 +- .../frc/robot/subsystems/intake/Intake.java | 4 +-- .../subsystems/intake/PhysicalIntake.java | 2 -- .../subsystems/intake/SimulatedIntake.java | 8 +++-- 10 files changed, 13 insertions(+), 108 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/arm/Arm.java delete mode 100644 src/main/java/frc/robot/subsystems/arm/ArmConstants.java delete mode 100644 src/main/java/frc/robot/subsystems/arm/ArmInterface.java delete mode 100644 src/main/java/frc/robot/subsystems/arm/PhysicalArm.java delete mode 100644 src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java diff --git a/src/main/java/frc/robot/subsystems/arm/Arm.java b/src/main/java/frc/robot/subsystems/arm/Arm.java deleted file mode 100644 index 10dacba..0000000 --- a/src/main/java/frc/robot/subsystems/arm/Arm.java +++ /dev/null @@ -1,10 +0,0 @@ -package frc.robot.subsystems.arm; - -public class Arm { - private ArmInterface armInterface; - private ArmInputsAutoLogged input = new ArmInputsAutoLogged(); - - public Arm(ArmInterface armInterface) { - this.armInterface = armInterface; - } -} diff --git a/src/main/java/frc/robot/subsystems/arm/ArmConstants.java b/src/main/java/frc/robot/subsystems/arm/ArmConstants.java deleted file mode 100644 index 78dedfb..0000000 --- a/src/main/java/frc/robot/subsystems/arm/ArmConstants.java +++ /dev/null @@ -1,15 +0,0 @@ -package frc.robot.subsystems.arm; - -public class ArmConstants { - public static final int ARM_MOTOR_ID = 0 - 9; - - public static final double ARM_P = 0 - 9; - public static final double ARM_I = 0 - 9; - public static final double ARM_D = 0 - 9; - - public static final double ARM_GEAR_RATIO = 0 - 9; - public static final double ARM_INERTIA_MASS = 0 - 9; - public static final double ARM_LENGTH_METERS = 0 - 9; - public static final double MINIMUM_ANGLE_RADIANS = 0 - 9; - public static final double MAXIMUM_ANGLE_RADIANS = 0 - 9; -} diff --git a/src/main/java/frc/robot/subsystems/arm/ArmInterface.java b/src/main/java/frc/robot/subsystems/arm/ArmInterface.java deleted file mode 100644 index 68b1081..0000000 --- a/src/main/java/frc/robot/subsystems/arm/ArmInterface.java +++ /dev/null @@ -1,19 +0,0 @@ -package frc.robot.subsystems.arm; - -import org.littletonrobotics.junction.AutoLog; - -public interface ArmInterface { - - @AutoLog - public static class ArmInputs { - public double angle = 0.0; - } - - public default void updateInputs(ArmInputs inputs) {} - - public default void setAngle(double angle) {} - - public default double getAngle() { - return 0.0; - } -} diff --git a/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java b/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java deleted file mode 100644 index 3ee6ebd..0000000 --- a/src/main/java/frc/robot/subsystems/arm/PhysicalArm.java +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.subsystems.arm; - -import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.signals.NeutralModeValue; - -public class PhysicalArm implements ArmInterface { - private TalonFX armMotor = new TalonFX(ArmConstants.ARM_MOTOR_ID); - - public PhysicalArm() { - TalonFXConfiguration armConfig = new TalonFXConfiguration(); - - armConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - - armConfig.Slot0.kP = ArmConstants.ARM_P; - armConfig.Slot0.kI = ArmConstants.ARM_I; - armConfig.Slot0.kD = ArmConstants.ARM_D; - - armMotor.getConfigurator().apply(armConfig); - } - - @Override - public void setAngle(double angle) {} -} diff --git a/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java deleted file mode 100644 index 8aa6816..0000000 --- a/src/main/java/frc/robot/subsystems/arm/SimulatedElevator.java +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.subsystems.arm; - -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; - -/** Add your docs here. */ -public class SimulatedElevator implements ArmInterface { - private SingleJointedArmSim armSim = - new SingleJointedArmSim( - DCMotor.getFalcon500(1), - ArmConstants.ARM_GEAR_RATIO, - ArmConstants.ARM_INERTIA_MASS, - ArmConstants.ARM_LENGTH_METERS, - ArmConstants.MINIMUM_ANGLE_RADIANS, - ArmConstants.MAXIMUM_ANGLE_RADIANS, - false, - 0, - null); - private PIDController pidSim; - - public SimulatedElevator() { - pidSim = new PIDController(ArmConstants.ARM_P, ArmConstants.ARM_I, ArmConstants.ARM_D); - } -} diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java index 82216d9..f1d6258 100644 --- a/src/main/java/frc/robot/subsystems/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -1,6 +1,8 @@ /** This subsystem is an elevator that uses PID for its position. */ package frc.robot.subsystems.elevator; +import org.littletonrobotics.junction.Logger; + import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Elevator extends SubsystemBase { @@ -32,5 +34,7 @@ public void setVolts(double volts) { @Override public void periodic() { // This method will be called once per scheduler run + elevatorInterface.updateInputs(inputs); + Logger.processInputs("Elevator/", inputs); } } diff --git a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java index 4d77838..6d6d099 100644 --- a/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/SimulatedElevator.java @@ -33,7 +33,7 @@ public void updateInputs(ElevatorInputs inputs) { } public void setElevatorPosition(double position) { - elevatorSim.setState(simPID.calculate(position), ElevatorConstants.VELOCITY_METERS_PER_SECOND); + setVolts(simPID.calculate(getElevatorPosition(), position)); } public double getElevatorPosition() { diff --git a/src/main/java/frc/robot/subsystems/intake/Intake.java b/src/main/java/frc/robot/subsystems/intake/Intake.java index d109cec..675d610 100644 --- a/src/main/java/frc/robot/subsystems/intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/intake/Intake.java @@ -18,12 +18,12 @@ public Intake(IntakeInterface intakeInterface) { */ public void setIntakeSpeed(double speed) { intakeInterface.setIntakeSpeed(speed); - Logger.recordOutput("OTBIntake/Intake", speed); + Logger.recordOutput("OTBIntake/IntakeSpeed", speed); } @Override public void periodic() { intakeInterface.updateInputs(inputs); - Logger.processInputs("OTBIntake", inputs); + Logger.processInputs("OTBIntake/", inputs); } } diff --git a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java index 1a863df..08b7a94 100644 --- a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java @@ -12,8 +12,6 @@ public class PhysicalIntake implements IntakeInterface { private final TalonFX intakeMotor = new TalonFX(IntakeConstants.INTAKE_MOTOR_ID); - private final MotionMagicVoltage mmPositionRequest = new MotionMagicVoltage(0); - private final StatusSignal intakeVelocity; public PhysicalIntake() { diff --git a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java index abd2aa1..c68f3fd 100644 --- a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java @@ -3,13 +3,17 @@ import static edu.wpi.first.units.Units.*; import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.wpilibj.simulation.DCMotorSim; public class SimulatedIntake implements IntakeInterface { - DCMotorSim intakeSim = new DCMotorSim(null, DCMotor.getFalcon500(1), 0); + DCMotorSim intakeSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), 0.01, 1), DCMotor.getFalcon500(1), 0); private double intakeAppliedVolts = 0.0; - public SimulatedIntake(IntakeInputs inputs) { + public SimulatedIntake() {} + + @Override + public void updateInputs(IntakeInputs inputs) { intakeSim.update(0.02); inputs.intakeVelocity = From 61690a7cb76fdaad432d65d02b5e0b91449a5e56 Mon Sep 17 00:00:00 2001 From: Ishan <98932677+Ishan1522@users.noreply.github.com> Date: Sat, 4 Jan 2025 03:16:05 -0500 Subject: [PATCH 12/13] format i think? --- src/main/java/frc/robot/subsystems/elevator/Elevator.java | 3 +-- .../java/frc/robot/subsystems/intake/PhysicalIntake.java | 1 - .../java/frc/robot/subsystems/intake/SimulatedIntake.java | 6 +++++- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java index f1d6258..701b932 100644 --- a/src/main/java/frc/robot/subsystems/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -1,9 +1,8 @@ /** This subsystem is an elevator that uses PID for its position. */ package frc.robot.subsystems.elevator; -import org.littletonrobotics.junction.Logger; - import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.Logger; public class Elevator extends SubsystemBase { /** Creates a new Elevator. */ diff --git a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java index 08b7a94..47a918b 100644 --- a/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/PhysicalIntake.java @@ -2,7 +2,6 @@ import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; diff --git a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java index c68f3fd..171c20e 100644 --- a/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java +++ b/src/main/java/frc/robot/subsystems/intake/SimulatedIntake.java @@ -7,7 +7,11 @@ import edu.wpi.first.wpilibj.simulation.DCMotorSim; public class SimulatedIntake implements IntakeInterface { - DCMotorSim intakeSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), 0.01, 1), DCMotor.getFalcon500(1), 0); + DCMotorSim intakeSim = + new DCMotorSim( + LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), 0.01, 1), + DCMotor.getFalcon500(1), + 0); private double intakeAppliedVolts = 0.0; public SimulatedIntake() {} From d6f17c8e3f2333b329c26536c4a865538732682f Mon Sep 17 00:00:00 2001 From: Ishan <98932677+Ishan1522@users.noreply.github.com> Date: Sat, 4 Jan 2025 03:16:50 -0500 Subject: [PATCH 13/13] update beta version --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index cc290c3..1abcd7b 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-2" + id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-3" id "com.peterabeles.gversion" version "1.10" id "com.diffplug.spotless" version "6.25.0" id "pmd"