From 2c6d2963aad17d1812861f80f43a0cc9507b4fda Mon Sep 17 00:00:00 2001 From: Ishan1522 Date: Mon, 28 Oct 2024 14:49:32 -0400 Subject: [PATCH] get rid of unused code --- .../swerve/gyroIO/PhysicalGyro.java | 52 +++---------------- 1 file changed, 7 insertions(+), 45 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/swerve/gyroIO/PhysicalGyro.java b/src/main/java/frc/robot/subsystems/swerve/gyroIO/PhysicalGyro.java index ff0d8ec..17f6b03 100644 --- a/src/main/java/frc/robot/subsystems/swerve/gyroIO/PhysicalGyro.java +++ b/src/main/java/frc/robot/subsystems/swerve/gyroIO/PhysicalGyro.java @@ -18,17 +18,18 @@ public class PhysicalGyro implements GyroInterface { private final Queue yawPositionInput; public PhysicalGyro() { - yawPositionInput = OdometryThread.registerInput(getAngle()); + yawPositionInput = OdometryThread.registerInput(()->Degrees.of(gyro.getAngle())); } @Override public void updateInputs(GyroInputs inputs) { inputs.isConnected = gyro.isConnected(); - inputs.yawDegreesRotation2d = getGyroRotation2d(); - inputs.yawVelocity = getRate().in(DegreesPerSecond); - inputs.rollDegrees = getRoll().in(Degrees); - inputs.pitchDegrees = getPitch().in(Degrees); - inputs.yawDegrees = getYaw().in(Degrees); + inputs.yawDegreesRotation2d = gyro.getRotation2d(); + inputs.yawVelocity = gyro.getRate(); + inputs.rollDegrees = gyro.getRoll(); + inputs.pitchDegrees = gyro.getPitch(); + inputs.yawDegrees = gyro.getAngle(); + // inputs.wrappedYaw = gyro.getYaw(); // Handle odometry yaw positions if (!yawPositionInput.isEmpty()) { @@ -41,43 +42,4 @@ public void updateInputs(GyroInputs inputs) { yawPositionInput.clear(); } } - - public void zeroHeading() { - gyro.reset(); - } - - public Supplier getAngle() { - return () -> Degrees.of(-gyro.getAngle()); - } - - public Angle getYaw() { - return Degrees.of(-gyro.getAngle()); - } - - public Angle getWrappedYaw() { - return Degrees.of(-gyro.getYaw()); - } - - public Rotation2d getGyroRotation2d() { - return gyro.getRotation2d(); - } - - public AngularVelocity getRate() { - return DegreesPerSecond.of(-gyro.getRate()); - } - - public Angle getPitch() { - return Degrees.of(gyro.getPitch()); - } - - public Angle getRoll() { - return Degrees.of(gyro.getRoll()); - } - - public Rotation2d getGyroFieldRelativeRotation2d() { - if (AllianceFlipper.isBlue()) { - return getGyroRotation2d(); - } - return AllianceFlipper.flipRotation(getGyroRotation2d()); - } }