diff --git a/Robot2024/src/main/java/com/team2813/subsystems/Drive.java b/Robot2024/src/main/java/com/team2813/subsystems/Drive.java index ffa6dbd..d6056e4 100644 --- a/Robot2024/src/main/java/com/team2813/subsystems/Drive.java +++ b/Robot2024/src/main/java/com/team2813/subsystems/Drive.java @@ -14,6 +14,7 @@ import static com.team2813.Constants.FRONT_RIGHT_STEER_ID; import static com.team2813.Constants.PIGEON_ID; +import java.util.OptionalDouble; import java.util.OptionalLong; import com.ctre.phoenix6.configs.CurrentLimitsConfigs; @@ -277,9 +278,9 @@ public SwerveConfig getOffsets() { */ public void addMeasurement(Pose2d pose) { double timestamp = Timer.getFPGATimestamp(); - OptionalLong msDelay = limelight.getLocationalData().lastMSDelay(); + OptionalDouble msDelay = limelight.getLocationalData().lastMSDelay(); if (msDelay.isPresent()) { - timestamp -= msDelay.getAsLong() / 1000.0; + timestamp -= msDelay.getAsDouble() / 1000.0; } drivetrain.addVisionMeasurement(pose, timestamp); } diff --git a/Robot2024/src/main/java/com/team2813/subsystems/IntakePivot.java b/Robot2024/src/main/java/com/team2813/subsystems/IntakePivot.java index 7abea7f..a5e85ef 100644 --- a/Robot2024/src/main/java/com/team2813/subsystems/IntakePivot.java +++ b/Robot2024/src/main/java/com/team2813/subsystems/IntakePivot.java @@ -3,22 +3,20 @@ import static com.team2813.Constants.INTAKE_PIVOT; import com.ctre.phoenix6.signals.NeutralModeValue; -import com.team2813.lib2813.control.Encoder; import com.team2813.lib2813.control.InvertType; -import com.team2813.lib2813.control.Motor; import com.team2813.lib2813.control.PIDMotor; import com.team2813.lib2813.control.encoders.CancoderWrapper; import com.team2813.lib2813.control.motors.TalonFXWrapper; import com.team2813.lib2813.subsystems.MotorSubsystem; -import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; -import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.units.Angle; +import edu.wpi.first.units.Measure; +import edu.wpi.first.units.Units; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import java.util.function.Supplier; + public class IntakePivot extends MotorSubsystem { - - Motor intakePivotMotor; - Encoder intakePivotEncoder; public IntakePivot() { @@ -29,9 +27,6 @@ public IntakePivot() { .PID(0.315, 0, 0) .acceptableError(0.5) .startingPosition(Rotations.INTAKE_UP)); - - intakePivotMotor = new TalonFXWrapper(INTAKE_PIVOT, InvertType.CLOCKWISE); - } private static PIDMotor pivotMotor() { @@ -46,7 +41,7 @@ public void periodic() { SmartDashboard.putNumber("Intake Pivot CANCoder Position", encoder.position()); } - public static enum Rotations implements MotorSubsystem.Position { + public enum Rotations implements Supplier> { INTAKE_DOWN(-0.782471), INTAKE_UP(-0.000732); @@ -55,12 +50,17 @@ public static enum Rotations implements MotorSubsystem.Position { } private final double pos; - @Override + + @Deprecated public double getPos() { return pos; } - - } + + @Override + public Measure get() { + return Units.Rotations.of(pos); + } + } } diff --git a/Robot2024/src/main/java/com/team2813/subsystems/ShooterPivot.java b/Robot2024/src/main/java/com/team2813/subsystems/ShooterPivot.java index 7b79e2c..713f2c6 100644 --- a/Robot2024/src/main/java/com/team2813/subsystems/ShooterPivot.java +++ b/Robot2024/src/main/java/com/team2813/subsystems/ShooterPivot.java @@ -14,8 +14,13 @@ import com.team2813.lib2813.subsystems.MotorSubsystem; import com.team2813.lib2813.util.ConfigUtils; +import edu.wpi.first.units.Angle; +import edu.wpi.first.units.Measure; +import edu.wpi.first.units.Units; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import java.util.function.Supplier; + public class ShooterPivot extends MotorSubsystem { public ShooterPivot() { @@ -57,7 +62,7 @@ public void periodic() { SmartDashboard.putNumber("Shoooter Pivot CANCoder Position", encoder.position()); } - public static enum Position implements MotorSubsystem.Position { + public static enum Position implements Supplier> { TOP_HARD_STOP(0), SUBWOOFER_FRONT(0.007080), SUBWOOFER_SIDE(0.007080), @@ -70,10 +75,15 @@ public static enum Position implements MotorSubsystem.Position { Position(double pos) { this.pos = pos; } - - @Override + + @Deprecated public double getPos() { return pos; } + + @Override + public Measure get() { + return Units.Rotations.of(pos); + } } }