diff --git a/src/main/java/frc4388/robot/constants/BuildConstants.java b/src/main/java/frc4388/robot/constants/BuildConstants.java index 675a76b..d5db97c 100644 --- a/src/main/java/frc4388/robot/constants/BuildConstants.java +++ b/src/main/java/frc4388/robot/constants/BuildConstants.java @@ -7,12 +7,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "2026KPopRobotHunters"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 117; - public static final String GIT_SHA = "f15a26aaef05d6a17e359cc3e189c5b5c1b1ceec"; - public static final String GIT_DATE = "2026-02-27 21:19:01 MST"; + public static final int GIT_REVISION = 119; + public static final String GIT_SHA = "9362d4389fe838757f8de94f4c17e5994c8adba0"; + public static final String GIT_DATE = "2026-02-27 21:38:24 MST"; public static final String GIT_BRANCH = "shikhar-op-controls"; - public static final String BUILD_DATE = "2026-02-27 21:29:33 MST"; - public static final long BUILD_UNIX_TIME = 1772252973524L; + public static final String BUILD_DATE = "2026-02-27 21:51:30 MST"; + public static final long BUILD_UNIX_TIME = 1772254290903L; public static final int DIRTY = 1; private BuildConstants(){} diff --git a/src/main/java/frc4388/robot/subsystems/intake/IntakeIO.java b/src/main/java/frc4388/robot/subsystems/intake/IntakeIO.java index c619182..5f99722 100644 --- a/src/main/java/frc4388/robot/subsystems/intake/IntakeIO.java +++ b/src/main/java/frc4388/robot/subsystems/intake/IntakeIO.java @@ -3,13 +3,14 @@ package frc4388.robot.subsystems.intake; import static edu.wpi.first.units.Units.Amps; import static edu.wpi.first.units.Units.Rotations; import static edu.wpi.first.units.Units.RotationsPerSecond; +import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond; import org.littletonrobotics.junction.AutoLog; -import edu.wpi.first.units.measure.Acceleration; import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularAcceleration; +import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; -import edu.wpi.first.units.measure.Velocity; public interface IntakeIO { @AutoLog @@ -19,10 +20,8 @@ public interface IntakeIO { Angle armTargetAngle = Rotations.of(0); Current armMotorCurrent = Amps.of(0); - @SuppressWarnings("rawtypes") - Velocity armMotorVelocity; - @SuppressWarnings("rawtypes") - Acceleration armMotorAcceleration; + AngularVelocity armMotorVelocity = RotationsPerSecond.of(0); + AngularAcceleration armMotorAcceleration = RotationsPerSecondPerSecond.of(0); // Angle shooterPitch = Rotations.of(0); // Angle shooterTargetPitch = Rotations.of(0); @@ -40,7 +39,7 @@ public interface IntakeIO { // public default void setShooterAngle(ShooterState state, Angle angle) {} // public default void setShooterPitch(ShooterState state, Angle angle) {} public default void setArmAngle(IntakeState state, Angle angle) {} - public default void testSetArmAgle(IntakeState state, Angle angle){} + public default void testSetArmAngle(IntakeState state, Angle angle){} public default void stopArm() {} public default void setRollerOutput(IntakeState state, double rollerOutput) {} public default void armOutput(double percentOutput) {} diff --git a/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java b/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java index 20e56ad..820ae3e 100644 --- a/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java +++ b/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java @@ -89,7 +89,7 @@ public class IntakeReal implements IntakeIO { } @Override - public void testSetArmAgle(IntakeState state, Angle angle){ + public void testSetArmAngle(IntakeState state, Angle angle){ state.armTargetAngle = angle; Angle motorAngle = angle.times(IntakeConstants.ARM_MOTOR_GEAR_RATIO); @@ -128,7 +128,6 @@ public class IntakeReal implements IntakeIO { ); } - @SuppressWarnings("rawtypes") @Override public void updateInputs(IntakeState state) { state.armAngle = m_armMotor.getPosition().getValue().div(IntakeConstants.ARM_MOTOR_GEAR_RATIO); @@ -137,8 +136,8 @@ public class IntakeReal implements IntakeIO { state.rollerMotorCurrent = m_rollerMotor.getStatorCurrent().getValue(); state.retractedLimit = !m_armLimitSwitch.get(); - // state.armMotorVelocity = (Velocity) m_armMotor.getVelocity(); - // state.armMotorAcceleration = (Acceleration) m_armMotor.getAcceleration(); + state.armMotorVelocity = m_armMotor.getVelocity().getValue(); + state.armMotorAcceleration = m_armMotor.getAcceleration().getValue(); if(state.retractedLimit) { // Set the arm motor to be zero if the limit switch is pressed