From 1c86d1ca11b6fd1d6ac9e81e62b7dbeab26f1b3a Mon Sep 17 00:00:00 2001 From: shlap Date: Thu, 29 Jan 2026 20:03:53 -0500 Subject: [PATCH 1/4] Did the same thing as the other one --- src/main/java/frc/robot/Constants.java | 1 + .../frc/robot/subsystems/climber/Climber.java | 16 ++++++++++++++++ 2 files changed, 17 insertions(+) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 3cfd7aa..78a4c29 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -147,5 +147,6 @@ public class ClimberConstants { public static final Distance DRUM_RADIUS = Inches.of(2.0); public static final DistanceAngleConverter CONVERTER = new DistanceAngleConverter(DRUM_RADIUS); public static final LinearMechCharacteristics CHARACTERISTICS = new LinearMechCharacteristics(new Translation3d(0.0, 0.0, 0.0), MIN_DISTANCE, MAX_DISTANCE, STARTING_DISTANCE, CONVERTER); + public static final double CLIMB_SPEED = 1.0; } } diff --git a/src/main/java/frc/robot/subsystems/climber/Climber.java b/src/main/java/frc/robot/subsystems/climber/Climber.java index 7be04be..d534bc4 100644 --- a/src/main/java/frc/robot/subsystems/climber/Climber.java +++ b/src/main/java/frc/robot/subsystems/climber/Climber.java @@ -1,7 +1,11 @@ package frc.robot.subsystems.climber; +import edu.wpi.first.units.Units; +import edu.wpi.first.units.measure.LinearVelocity; +import edu.wpi.first.units.measure.Velocity; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.lib.W8.mechanisms.linear.LinearMechanism; +import frc.robot.Constants.ClimberConstants; public class Climber extends SubsystemBase { private LinearMechanism _io; @@ -9,6 +13,18 @@ public class Climber extends SubsystemBase { public Climber(LinearMechanism io) { io = _io; } + + public enum State { + IDLE(Units.MetersPerSecond.of(0.0)), + ASCENDING(Units.MetersPerSecond.of(ClimberConstants.CLIMB_SPEED)), + DESCENDING(Units.MetersPerSecond.of(-ClimberConstants.CLIMB_SPEED)); + + private final LinearVelocity velocity; + + private State(LinearVelocity velocity) { + this.velocity = velocity; + } + } @Override public void periodic() {} From d94aa5c4761f9aee6572b7a4dde1bd329da5cdf7 Mon Sep 17 00:00:00 2001 From: shlap Date: Fri, 30 Jan 2026 22:14:30 -0500 Subject: [PATCH 2/4] Added spotlessapply cahnges --- src/main/java/frc/robot/Constants.java | 20 ++++++++++----- .../frc/robot/subsystems/climber/Climber.java | 5 ++-- .../frc/robot/subsystems/hopper/Hopper.java | 25 +++++++++++-------- .../frc/robot/subsystems/shooter/Shooter.java | 11 ++++---- 4 files changed, 35 insertions(+), 26 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 78a4c29..54265cb 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -87,7 +87,8 @@ public class HopperConstants { private static final Distance DRUM_RADIUS = Inches.of(2.0); public static final DistanceAngleConverter CONVERTER = new DistanceAngleConverter(DRUM_RADIUS); public static final AngularVelocity ANGULAR_VELOCITY = RotationsPerSecond.of(1); - public static final AngularAcceleration ANGULAR_ACCELERATION = RotationsPerSecondPerSecond.of(1); + public static final AngularAcceleration ANGULAR_ACCELERATION = + RotationsPerSecondPerSecond.of(1); } public class Ports { @@ -99,7 +100,7 @@ public class Ports { } public final class ShooterConstants { - // Constants for the Shooter + // Constants for the Shooter public static final Angle ANGLE_TOLERANCE = Rotations.of(0.01); public static final AngularVelocity ANGLE_VELOCITY_TOLERANCE = RotationsPerSecond.of(0.01); public static final AngularVelocity CRUISE_VELOCITY = RotationsPerSecond.of(204); @@ -113,9 +114,10 @@ public final class ShooterConstants { public static final Angle STARTING_ANGLE = Rotations.of(0.0); public static final Distance WHEEL_RADIUS = Meters.of(0.5); public static final double FLYWHEEL_VELOCITY_TOLERANCE = 1.0; - public static final RotaryMechCharacteristics CONSTANTS = new RotaryMechCharacteristics(OFFSET, WHEEL_RADIUS, MIN_ANGLE, MAX_ANGLE, STARTING_ANGLE); + public static final RotaryMechCharacteristics CONSTANTS = + new RotaryMechCharacteristics(OFFSET, WHEEL_RADIUS, MIN_ANGLE, MAX_ANGLE, STARTING_ANGLE); } - + public static final int CANDLE_ID = 50; public class IntakeConstants { @@ -137,7 +139,7 @@ public class FeederConstants { public static final AngularVelocity FEED_SPEED = RotationsPerSecond.of(0.0); public static final AngularAcceleration FEED_ACCELERATION = RotationsPerSecondPerSecond.of(0.0); } - + public class ClimberConstants { public static final Distance TOLERANCE = Inches.of(0.1); public static final double GEARING = (5.0 / 1.0); @@ -146,7 +148,13 @@ public class ClimberConstants { public static final Distance STARTING_DISTANCE = Inches.of(0.0); public static final Distance DRUM_RADIUS = Inches.of(2.0); public static final DistanceAngleConverter CONVERTER = new DistanceAngleConverter(DRUM_RADIUS); - public static final LinearMechCharacteristics CHARACTERISTICS = new LinearMechCharacteristics(new Translation3d(0.0, 0.0, 0.0), MIN_DISTANCE, MAX_DISTANCE, STARTING_DISTANCE, CONVERTER); + public static final LinearMechCharacteristics CHARACTERISTICS = + new LinearMechCharacteristics( + new Translation3d(0.0, 0.0, 0.0), + MIN_DISTANCE, + MAX_DISTANCE, + STARTING_DISTANCE, + CONVERTER); public static final double CLIMB_SPEED = 1.0; } } diff --git a/src/main/java/frc/robot/subsystems/climber/Climber.java b/src/main/java/frc/robot/subsystems/climber/Climber.java index d534bc4..07f4a55 100644 --- a/src/main/java/frc/robot/subsystems/climber/Climber.java +++ b/src/main/java/frc/robot/subsystems/climber/Climber.java @@ -2,7 +2,6 @@ import edu.wpi.first.units.Units; import edu.wpi.first.units.measure.LinearVelocity; -import edu.wpi.first.units.measure.Velocity; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.lib.W8.mechanisms.linear.LinearMechanism; import frc.robot.Constants.ClimberConstants; @@ -13,12 +12,12 @@ public class Climber extends SubsystemBase { public Climber(LinearMechanism io) { io = _io; } - + public enum State { IDLE(Units.MetersPerSecond.of(0.0)), ASCENDING(Units.MetersPerSecond.of(ClimberConstants.CLIMB_SPEED)), DESCENDING(Units.MetersPerSecond.of(-ClimberConstants.CLIMB_SPEED)); - + private final LinearVelocity velocity; private State(LinearVelocity velocity) { diff --git a/src/main/java/frc/robot/subsystems/hopper/Hopper.java b/src/main/java/frc/robot/subsystems/hopper/Hopper.java index 95f1b8e..08d7799 100644 --- a/src/main/java/frc/robot/subsystems/hopper/Hopper.java +++ b/src/main/java/frc/robot/subsystems/hopper/Hopper.java @@ -6,23 +6,26 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.lib.W8.io.motor.MotorIO.PIDSlot; import frc.lib.W8.mechanisms.flywheel.FlywheelMechanism; -import frc.robot.Constants; import frc.robot.Constants.HopperConstants; public class Hopper extends SubsystemBase { -private FlywheelMechanism _io; + private FlywheelMechanism _io; -public Hopper(FlywheelMechanism io) { -_io = io; -} + public Hopper(FlywheelMechanism io) { + _io = io; + } -public void setGoal(double position) { - Distance positionInches = Inches.of(position); - _io.runPosition(HopperConstants.CONVERTER.toAngle(positionInches), HopperConstants.ANGULAR_VELOCITY, HopperConstants.ANGULAR_ACCELERATION, null, PIDSlot.SLOT_0); -} + public void setGoal(double position) { + Distance positionInches = Inches.of(position); + _io.runPosition( + HopperConstants.CONVERTER.toAngle(positionInches), + HopperConstants.ANGULAR_VELOCITY, + HopperConstants.ANGULAR_ACCELERATION, + null, + PIDSlot.SLOT_0); + } @Override public void periodic() {} - -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index ba3067c..b812858 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -47,18 +47,17 @@ public Command shoot(double velocity) { () -> { setFlywheelVelocity(velocity); }) - .until( - () -> flyAtVelocity()) + .until(() -> flyAtVelocity()) .andThen( () -> { runFeeder(); }) .andThen( - ()->{ - setFlywheelVelocity(0); - }); + () -> { + setFlywheelVelocity(0); + }); } - + @Override public void periodic() {} } From aace56b063e3537454cfd2d55157193e14195fd2 Mon Sep 17 00:00:00 2001 From: shlap Date: Fri, 30 Jan 2026 22:17:19 -0500 Subject: [PATCH 3/4] Commented out certain parts --- .../frc/robot/subsystems/hopper/Hopper.java | 29 +++++++------------ .../frc/robot/subsystems/shooter/Shooter.java | 24 +++++++-------- 2 files changed, 22 insertions(+), 31 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/hopper/Hopper.java b/src/main/java/frc/robot/subsystems/hopper/Hopper.java index 7649590..6d6a3d0 100644 --- a/src/main/java/frc/robot/subsystems/hopper/Hopper.java +++ b/src/main/java/frc/robot/subsystems/hopper/Hopper.java @@ -14,32 +14,23 @@ public class Hopper extends SubsystemBase { private FlywheelMechanism _io; -<<<<<<< HEAD - private FlywheelMechanism _io; + // public enum State { + // OFF(RevolutionsPerSecond.of(0.0)), + // FORWARD_SLOW(RevolutionsPerSecond.of(HopperConstants.SLOW_SPEED_RPM / 60)), + // FORWARD_FAST(RevolutionsPerSecond.of(HopperConstants.FAST_SPEED_RPM / 60)), + // REVERSE(RevolutionsPerSecond.of(HopperConstants.REVERSE_SPEED_RPM / 60)); - public Hopper(FlywheelMechanism io) { - _io = io; - } + // private final AngularVelocity _stateVelocity; -======= - public enum State { - OFF(RevolutionsPerSecond.of(0.0)), - FORWARD_SLOW(RevolutionsPerSecond.of(HopperConstants.SLOW_SPEED_RPM / 60)), - FORWARD_FAST(RevolutionsPerSecond.of(HopperConstants.FAST_SPEED_RPM / 60)), - REVERSE(RevolutionsPerSecond.of(HopperConstants.REVERSE_SPEED_RPM / 60)); - - private final AngularVelocity _stateVelocity; - - private State(AngularVelocity stateVelocity) { - _stateVelocity = stateVelocity; - } - } + // private State(AngularVelocity stateVelocity) { + // _stateVelocity = stateVelocity; + // } + // } public Hopper(FlywheelMechanism io) { _io = io; } ->>>>>>> ef8c3202dc04e8134474ea1adb2651983dfe66a6 public void setGoal(double position) { Distance positionInches = Inches.of(position); _io.runPosition( diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index fd86a44..c3bf21c 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -37,20 +37,20 @@ public void setFlywheelVelocity(double velocity) { _flywheel.runVelocity(angVelo, ShooterConstants.ACCELERATION, PIDSlot.SLOT_0); } - public enum State { - OFF(Units.RevolutionsPerSecond.of(0.0)), - IDLE(Units.RevolutionsPerSecond.of(ShooterConstants.IDLE_SPEED_RPM / 60)), - SHOOT_FROM_HUB(Units.RevolutionsPerSecond.of(ShooterConstants.HUB_SPEED_RPM / 60)), - SHOOT_FROM_TOWER(Units.RevolutionsPerSecond.of(ShooterConstants.TOWER_SPEED_RPM / 60)), - SHOOT(Units.RevolutionsPerSecond.of(ShooterConstants.DEFAULT_SPEED_RPM / 60)), - SHOOT_ON_MOVE(Units.RevolutionsPerSecond.of(ShooterConstants.DEFAULT_SPEED_RPM / 60)); + // public enum State { + // OFF(Units.RevolutionsPerSecond.of(0.0)), + // IDLE(Units.RevolutionsPerSecond.of(ShooterConstants.IDLE_SPEED_RPM / 60)), + // SHOOT_FROM_HUB(Units.RevolutionsPerSecond.of(ShooterConstants.HUB_SPEED_RPM / 60)), + // SHOOT_FROM_TOWER(Units.RevolutionsPerSecond.of(ShooterConstants.TOWER_SPEED_RPM / 60)), + // SHOOT(Units.RevolutionsPerSecond.of(ShooterConstants.DEFAULT_SPEED_RPM / 60)), + // SHOOT_ON_MOVE(Units.RevolutionsPerSecond.of(ShooterConstants.DEFAULT_SPEED_RPM / 60)); - private final AngularVelocity stateVelocity; + // private final AngularVelocity stateVelocity; - State(AngularVelocity stateVelocity) { - this.stateVelocity = stateVelocity; - } - } + // State(AngularVelocity stateVelocity) { + // this.stateVelocity = stateVelocity; + // } + // } // Checks if the flywheel is at speed and returns a boolean public boolean flyAtVelocity() { From 65d1fce90058af70b80dda1edf37864658f37fd9 Mon Sep 17 00:00:00 2001 From: shlap Date: Fri, 30 Jan 2026 22:37:40 -0500 Subject: [PATCH 4/4] One more spotless apply --- src/main/java/frc/robot/subsystems/shooter/Shooter.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index c3bf21c..f156702 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -2,7 +2,6 @@ import static edu.wpi.first.units.Units.RotationsPerSecond; -import edu.wpi.first.units.Units; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands;