]> git.taranathan.com Git - FRC2026.git/commitdiff
Update Shooter.java
authormaxwtan <100314265+MaxwellTTan20@users.noreply.github.com>
Sat, 7 Feb 2026 19:06:49 +0000 (11:06 -0800)
committermaxwtan <100314265+MaxwellTTan20@users.noreply.github.com>
Sat, 7 Feb 2026 19:06:49 +0000 (11:06 -0800)
src/main/java/frc/robot/subsystems/shooter/Shooter.java

index b46d7f32e7f0e26e1898748d2ba10031fbd0b0af..3bd617257ee8fc04c2c9518c71eda48db862e1b0 100644 (file)
@@ -25,13 +25,10 @@ public class Shooter extends SubsystemBase implements ShooterIO {
     private TalonFX shooterMotorLeft = new TalonFX(IdConstants.SHOOTER_LEFT_ID, Constants.RIO_CAN);
     private TalonFX shooterMotorRight = new TalonFX(IdConstants.SHOOTER_RIGHT_ID, Constants.RIO_CAN);
 
-    private TalonFX feederMotor = new TalonFX(IdConstants.FEEDER_ID, Constants.RIO_CAN);
-
     //rotations/sec
 
     // Goal Velocity / Double theCircumfrence
     private double shooterTargetSpeed = 0;
-    private double feederPower = 0;
 
     public double shooterPower = 1.0;
     //Velocity in rotations per second
@@ -72,11 +69,6 @@ public class Shooter extends SubsystemBase implements ShooterIO {
             new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Coast)
         );
 
-        feederMotor.getConfigurator().apply(
-            new MotorOutputConfigs().withInverted(InvertedValue.Clockwise_Positive)
-            .withNeutralMode(NeutralModeValue.Coast)
-        );
-
         // set start up for phase initially:
         phase = FlywheelPhase.START_UP;
 
@@ -104,7 +96,6 @@ public class Shooter extends SubsystemBase implements ShooterIO {
 
         // shooterMotorLeft.set(-shooterPower);
         // shooterMotorRight.set(-shooterPower);
-        feederMotor.set(feederPower);
     }
 
     public void updatePhase() {
@@ -122,7 +113,6 @@ public class Shooter extends SubsystemBase implements ShooterIO {
     }
     public void setFeeder(double power){
         System.out.println("VELOCITY: " + getShooterVelcoity()); 
-        feederPower = power;
     }
 
     public void setShooter(double velocityRPS) {
@@ -145,9 +135,7 @@ public class Shooter extends SubsystemBase implements ShooterIO {
     public void updateInputs() {
         inputs.leftShooterVelocity = shooterMotorLeft.getVelocity().getValueAsDouble();
         inputs.rightShooterVelocity = shooterMotorRight.getVelocity().getValueAsDouble();
-        inputs.feederVelocity = feederMotor.getVelocity().getValueAsDouble();
         inputs.leftShooterCurrent = shooterMotorLeft.getStatorCurrent().getValueAsDouble();
         inputs.rightShooterVelocity = shooterMotorRight.getStatorCurrent().getValueAsDouble();
-        inputs.feederVelocity = feederMotor.getStatorCurrent().getValueAsDouble();
     }
 }