]> git.taranathan.com Git - FRC2026.git/commitdiff
constants added :(
authoreileha <eileenhan369@gmail.com>
Sat, 7 Feb 2026 18:30:54 +0000 (10:30 -0800)
committereileha <eileenhan369@gmail.com>
Sat, 7 Feb 2026 18:30:54 +0000 (10:30 -0800)
src/main/java/frc/robot/constants/IntakeConstants.java [new file with mode: 0644]
src/main/java/frc/robot/subsystems/Intake/Intake.java

diff --git a/src/main/java/frc/robot/constants/IntakeConstants.java b/src/main/java/frc/robot/constants/IntakeConstants.java
new file mode 100644 (file)
index 0000000..8e09939
--- /dev/null
@@ -0,0 +1,20 @@
+package frc.robot.constants;
+
+import edu.wpi.first.math.util.Units;
+
+public class IntakeConstants {
+
+    // Motors (set actual ids)
+    public static final int rightID = 1;
+    public static final int leftID = 2;
+    public static final int rollerID = 3;
+
+    // Intake positions
+
+    public static final double maxExtension = 12; // in inches: convert to rotations later
+    public static final double startingPoint = 0;
+
+    // for simulation
+    public static final double kMaxRotations = 37.5;
+    public static final double kMaxVisualLength = 0.75;
+}
index 4e8e807cd5bd02ee51d003a4b90c65f88a1032b5..51b0a3a01d3f1a37d542ed25afefca3f6216509b 100644 (file)
@@ -17,6 +17,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 import edu.wpi.first.wpilibj.util.Color8Bit;
 import edu.wpi.first.wpilibj2.command.InstantCommand;
 import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import frc.robot.constants.IntakeConstants;
 
 
 public class Intake extends SubsystemBase {
@@ -25,28 +26,17 @@ public class Intake extends SubsystemBase {
     private final MechanismLigament2d robotFrame; 
     private final MechanismLigament2d robotHeight; 
     private final MechanismLigament2d robotPos;
-    
-    
-    // set actual IDs
-    final int rightID = 1;
-    final int leftID = 2;
-    final int rollerID = 3;
 
     private TalonFX rollerMotor; 
     private TalonFX rightMotor; //leader
     private TalonFX leftMotor; //invert this one
-    private double maxExtension = 12.0; // this should go in a constants file
-    private double startingPoint; // this should go in a constants file
-    private MotionMagicVoltage voltageRequest = new MotionMagicVoltage(0);
-
-    final double kMaxRotations = 37.5;
-    final double kMaxVisualLength = 0.75;
 
+    private MotionMagicVoltage voltageRequest = new MotionMagicVoltage(0);
 
     public Intake() {
-        rightMotor = new TalonFX(rightID);
-        leftMotor = new TalonFX(leftID);
-        rollerMotor = new TalonFX(rollerID); 
+        rightMotor = new TalonFX(IntakeConstants.rightID);
+        leftMotor = new TalonFX(IntakeConstants.leftID);
+        rollerMotor = new TalonFX(IntakeConstants.rollerID); 
 
         // right motor configs
         TalonFXConfiguration Config = new TalonFXConfiguration();
@@ -65,15 +55,8 @@ public class Intake extends SubsystemBase {
         leftMotor.getConfigurator().apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake));
         leftMotor.getConfigurator().apply(Config);
 
-
         //Follower follower = new Follower(rightMotor.getDeviceID(), true);
         leftMotor.setControl(new Follower(rightMotor.getDeviceID(), MotorAlignmentValue.Opposed));
-        
-
-        SmartDashboard.putData("Extend Intake", new InstantCommand(() -> extend()));
-        SmartDashboard.putData("Retract Intake", new InstantCommand(() -> retract()));
-
-        
 
         mechanism = new Mechanism2d(80, 80);
         MechanismRoot2d root = mechanism.getRoot("Root", 0, 1);
@@ -92,7 +75,7 @@ public class Intake extends SubsystemBase {
         SmartDashboard.putNumber("Intake Position:", getPosition());
 
         // report the position of the extension
-        double percentExtended = getPosition() / kMaxRotations;
+        double percentExtended = getPosition() / IntakeConstants.kMaxRotations;
 
         percentExtended = Math.max(0.0, Math.min(1.0, percentExtended));
 
@@ -112,7 +95,7 @@ public class Intake extends SubsystemBase {
         rightMotor.setControl(voltageRequest.withPosition(setpoint));
 
         // set the position quickly (should be in simultation and move slowly)
-        robotExtension.setLength(12.0 * setpoint/kMaxRotations);
+        robotExtension.setLength(12.0 * setpoint/IntakeConstants.kMaxRotations);
     }
 
     /**
@@ -128,12 +111,12 @@ public class Intake extends SubsystemBase {
     }
 
     public void extend() {
-       setPosition(maxExtension);
+       setPosition(IntakeConstants.maxExtension);
 
     }
 
     public void retract(){
-        setPosition(startingPoint);
+        setPosition(IntakeConstants.startingPoint);
         
     }