From b220328f44863563b577690eb3c520d976471b86 Mon Sep 17 00:00:00 2001 From: shayan-mrafiee Date: Wed, 25 Feb 2026 20:13:11 -0600 Subject: [PATCH] Added turret to shooter, added its hook to testop, and assigned slot 2 to it. --- src/main/java/frc/robot/RobotContainer.java | 5 +++-- .../java/frc/robot/subsystems/shooter/Shooter.java | 10 +++++++++- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 4decaf5..0a5e38e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -41,7 +41,7 @@ public class RobotContainer private final CommandXboxController _operator = new CommandXboxController(1); private final Drive _drivetrain = TunerConstants.createDrivetrain(); private final Intake _intake = new Intake(); - private final Shooter _shooter = new Shooter(); + private final Shooter _shooter = new Shooter(_drivetrain::getState); private final TestOperation _testop = new TestOperation(); // private final Turret _turret = new Turret(_drivetrain::getState); private final Autos _autos = new Autos(_drivetrain); @@ -106,11 +106,12 @@ private void configureTestBindings() _testop.add("feeder", _shooter._feeder.getHook()); _testop.add("flywheel", _shooter._flywheel.getHook()); _testop.add("hood", _shooter._hood.getHook()); - // turret + _testop.add("turret", _shooter._turret.getHook()); // climber _testop.connect(0, "intake", "intake-extend"); _testop.connect(1, "feeder"); + _testop.connect(2, "turret"); _testop.connect(3, "flywheel", "hood"); _operator.leftBumper().whileTrue(_testop.cmd_shift()); diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index 4f322a6..d98244c 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -1,11 +1,16 @@ package frc.robot.subsystems.shooter; +import java.util.function.Supplier; + +import com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState; + import edu.wpi.first.epilogue.Logged; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.ShooterConstants; import frc.robot.subsystems.shooter.Hood.HoodPosition; +import frc.robot.subsystems.shooter.Turret.TurretState; @Logged public class Shooter extends SubsystemBase @@ -55,18 +60,21 @@ public Command passCmd() public final Flywheel _flywheel; public final Feeder _feeder; public final Hood _hood; + public final Turret _turret; private ShooterState _state; - public Shooter() + public Shooter(Supplier swerveStateSupplier) { _flywheel = new Flywheel(); _feeder = new Feeder(); _hood = new Hood(); + _turret = new Turret(swerveStateSupplier); _state = ShooterState.Idle; _hood.setHoodPosition(HoodPosition.Shoot); _feeder.set(false); _flywheel.stop(); + _turret.setTurretState(TurretState.Idle); } @Override