]> git.taranathan.com Git - FRC2026.git/commitdiff
logging
authormaxwtan <100314265+MaxwellTTan20@users.noreply.github.com>
Wed, 18 Feb 2026 20:36:09 +0000 (12:36 -0800)
committermaxwtan <100314265+MaxwellTTan20@users.noreply.github.com>
Wed, 18 Feb 2026 20:36:09 +0000 (12:36 -0800)
src/main/java/frc/robot/subsystems/Climb/ClimbConstants.java
src/main/java/frc/robot/subsystems/Climb/LinearClimb.java
src/main/java/frc/robot/subsystems/Climb/LinearClimbIO.java [new file with mode: 0644]

index 5bf5a39f6446774974d95e849240db9333d829c1..768b4967e17c6463c6cdf52aac9975c2fee0db02 100644 (file)
@@ -6,7 +6,7 @@ public class ClimbConstants {
 
     // CHANGE LATER
     // gear ratio for converting motor rotations to linear distance
-    public final static double CLIMB_GEAR_RATIO = 1.0 / 45.0;
+    public final static double CLIMB_GEAR_RATIO = 45.0;
     public final static double WHEEL_RADIUS = Units.inchesToMeters(0.334);
     public final static double BOTTOM_POSITION = Units.inchesToMeters(-8);
     public final static double CLIMB_POSITION = Units.inchesToMeters(-6);
index 9a3f2bb4c100e1eb3c31a7524dabdf5328de241a..076fbbbb0a6ab6e3ebd89e666806b078adecde48 100644 (file)
@@ -14,13 +14,15 @@ import edu.wpi.first.wpilibj2.command.InstantCommand;
 import edu.wpi.first.wpilibj2.command.SubsystemBase;
 import frc.robot.constants.IdConstants;
 
-public class LinearClimb extends SubsystemBase {
+public class LinearClimb extends SubsystemBase implements LinearClimbIO{
     private final TalonFX motor;
     private boolean calibrating = false;
     private double downPosition = ClimbConstants.BOTTOM_POSITION;
     private double upPosition = ClimbConstants.UP_POSITION;
     private double climbPosition = ClimbConstants.CLIMB_POSITION;
 
+    private LinearClimbIOInputs inputs = new LinearClimbIOInputs();
+
     private final PIDController pid = new PIDController(
             ClimbConstants.PID_P,
             ClimbConstants.PID_I,
@@ -85,7 +87,7 @@ public class LinearClimb extends SubsystemBase {
      *         rotations * gearRatio * 2 * PI * radius
      */
     public double getAsMeters() {
-        return getPosition() * ClimbConstants.CLIMB_GEAR_RATIO * 2 * Math.PI * ClimbConstants.WHEEL_RADIUS;
+        return inputs.positionMeters;
     }
     /**
      * goes to the up position
@@ -149,4 +151,10 @@ public class LinearClimb extends SubsystemBase {
         calibrating = false;
         setCurrentLimits(ClimbConstants.CLIMB_CURRENT);
     }
+
+    @Override
+    public void updateInputs() {
+        inputs.positionMeters = Units.rotationsToRadians(motor.getPosition().getValueAsDouble()) * ClimbConstants.WHEEL_RADIUS / ClimbConstants.CLIMB_GEAR_RATIO;
+        inputs.motorCurrent = motor.getStatorCurrent().getValueAsDouble();
+    }
 }
diff --git a/src/main/java/frc/robot/subsystems/Climb/LinearClimbIO.java b/src/main/java/frc/robot/subsystems/Climb/LinearClimbIO.java
new file mode 100644 (file)
index 0000000..4273b7b
--- /dev/null
@@ -0,0 +1,13 @@
+package frc.robot.subsystems.Climb;
+
+import org.littletonrobotics.junction.AutoLog;
+
+public interface LinearClimbIO {
+    @AutoLog
+    public static class LinearClimbIOInputs{
+        public double positionMeters = 0.0;
+        public double motorCurrent = 0.0;
+    }
+
+    public void updateInputs();
+}