From 8c0d0053f9f096b941f0cbe61940c26aa9b76bb8 Mon Sep 17 00:00:00 2001 From: WesleyWong-972 Date: Wed, 11 Feb 2026 14:56:58 -0800 Subject: [PATCH] ewht --- .../java/frc/robot/subsystems/shooter/Shooter.java | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index 97a277b..0ca40c1 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -26,13 +26,13 @@ public class Shooter extends SubsystemBase implements ShooterIO { private TalonFX shooterMotorLeft = new TalonFX(IdConstants.SHOOTER_LEFT_ID, Constants.SUBSYSTEM_CANIVORE_CAN); private TalonFX shooterMotorRight = new TalonFX(IdConstants.SHOOTER_RIGHT_ID, Constants.SUBSYSTEM_CANIVORE_CAN); - + private TalonFX feederMotor = new TalonFX(IdConstants.FEEDER_ID, Constants.SUBSYSTEM_CANIVORE_CAN); //rotations/sec // Goal Velocity / Double theCircumfrence private double shooterTargetSpeed = 0; - public double shooterPower = 0.5; + public double feederPower; //Velocity in rotations per second VelocityVoltage voltageRequest = new VelocityVoltage(0); @@ -89,6 +89,8 @@ public class Shooter extends SubsystemBase implements ShooterIO { // set start up for phase initially: phase = FlywheelPhase.START_UP; + feederPower = 1.0; + SmartDashboard.putData("Turn on shooter", new InstantCommand(() -> setShooter(ShooterConstants.SHOOTER_VELOCITY))); SmartDashboard.putData("Turn ALL off", new InstantCommand(() -> deactivateShooterAndFeeder())); SmartDashboard.putData("Turn off Shooter", new InstantCommand(() -> setShooter(0))); @@ -97,8 +99,6 @@ public class Shooter extends SubsystemBase implements ShooterIO { public void periodic(){ updateInputs(); runVelocity(Units.rotationsToRadians(getShooterVelcoity())); - SmartDashboard.putNumber("Shot Power", shooterPower); - shooterPower = SmartDashboard.getNumber("Shot Power", shooterPower); if (phase == FlywheelPhase.BANG_BANG || phase == FlywheelPhase.START_UP) { // shooter target speed is in RPS // Duty-cycle bang-bang (apply to both) 100% speeds @@ -109,6 +109,7 @@ public class Shooter extends SubsystemBase implements ShooterIO { shooterMotorLeft.setControl(new TorqueCurrentFOC(ShooterConstants.TORQUE_CURRENT_CONTROL_GOAL_AMP)); shooterMotorRight.setControl(new TorqueCurrentFOC(ShooterConstants.TORQUE_CURRENT_CONTROL_GOAL_AMP)); } + feederMotor.set(feederPower); } /** Run closed loop at the specified velocity. */ @@ -146,8 +147,8 @@ public class Shooter extends SubsystemBase implements ShooterIO { System.out.println("Shooter is working"); } - public void setShooterPower(double power){ - this.shooterPower = power; + public void setFeederPower(double power) { + this.feederPower = power; } public double getShooterVelcoity() { -- 2.39.5