From 984474fecea55476399f1ff0195dedb3489efb3d Mon Sep 17 00:00:00 2001 From: AvidCoder27 Date: Wed, 7 Aug 2024 15:50:10 -0400 Subject: [PATCH] move registerCommands to RobotContainer --- .../java/frc/team5115/RobotContainer.java | 31 ++++++++++++++- .../frc/team5115/commands/AutoCommands.java | 38 ------------------- 2 files changed, 29 insertions(+), 40 deletions(-) delete mode 100644 src/main/java/frc/team5115/commands/AutoCommands.java diff --git a/src/main/java/frc/team5115/RobotContainer.java b/src/main/java/frc/team5115/RobotContainer.java index 7a34695..4b543a2 100644 --- a/src/main/java/frc/team5115/RobotContainer.java +++ b/src/main/java/frc/team5115/RobotContainer.java @@ -1,13 +1,14 @@ package frc.team5115; import com.pathplanner.lib.auto.AutoBuilder; +import com.pathplanner.lib.auto.NamedCommands; + import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import frc.team5115.commands.AutoCommands; import frc.team5115.commands.DriveCommands; import frc.team5115.subsystems.amper.Amper; import frc.team5115.subsystems.amper.AmperIO; @@ -113,7 +114,7 @@ public RobotContainer() { // Register auto commands for pathplanner // PhotonVision is passed in here to prevent warnings, i.e. "unused variable: vision" - AutoCommands.registerCommands(drivetrain, vision, arm, amper, intake, feeder, shooter); + registerCommands(drivetrain, vision, arm, amper, intake, feeder, shooter); // Set up auto routines autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); @@ -185,6 +186,32 @@ private void configureButtonBindings() { .onFalse(DriveCommands.triggerAmp(arm, amper, intake, feeder)); } + /** + * Registers commands for pathplanner to use in autos + * + * @param shooter the shooter subsystem + * @param arm the arm subsystem + * @param drivetrain the drivetrain subsytem (not currently used) + * @param photonVision the photonvision subsystem (not currently used) + */ + public static void registerCommands( + Drivetrain drivetrain, + PhotonVision vision, + Arm arm, + Amper amper, + Intake intake, + Feeder feeder, + Shooter shooter) { + NamedCommands.registerCommand( + "InitialShoot", + DriveCommands.prepareShoot(arm, intake, feeder, shooter, 15, 5000) + .andThen(DriveCommands.feed(intake, feeder))); + NamedCommands.registerCommand("Intake", DriveCommands.intakeUntilNote(arm, intake, feeder)); + NamedCommands.registerCommand("Shoot", DriveCommands.feed(intake, feeder)); + NamedCommands.registerCommand( + "PrepareClose", DriveCommands.prepareShoot(arm, intake, feeder, shooter, 15, 5000)); + } + /** * Use this to pass the autonomous command to the main {@link Robot} class. * diff --git a/src/main/java/frc/team5115/commands/AutoCommands.java b/src/main/java/frc/team5115/commands/AutoCommands.java deleted file mode 100644 index db7cca9..0000000 --- a/src/main/java/frc/team5115/commands/AutoCommands.java +++ /dev/null @@ -1,38 +0,0 @@ -package frc.team5115.commands; - -import com.pathplanner.lib.auto.NamedCommands; -import frc.team5115.subsystems.amper.Amper; -import frc.team5115.subsystems.arm.Arm; -import frc.team5115.subsystems.drive.Drivetrain; -import frc.team5115.subsystems.feeder.Feeder; -import frc.team5115.subsystems.intake.Intake; -import frc.team5115.subsystems.shooter.Shooter; -import frc.team5115.subsystems.vision.PhotonVision; - -public class AutoCommands { - /** - * Registers commands for pathplanner to use in autos - * - * @param shooter the shooter subsystem - * @param arm the arm subsystem - * @param drivetrain the drivetrain subsytem (not currently used) - * @param photonVision the photonvision subsystem (not currently used) - */ - public static void registerCommands( - Drivetrain drivetrain, - PhotonVision vision, - Arm arm, - Amper amper, - Intake intake, - Feeder feeder, - Shooter shooter) { - NamedCommands.registerCommand( - "InitialShoot", - DriveCommands.prepareShoot(arm, intake, feeder, shooter, 15, 5000) - .andThen(DriveCommands.feed(intake, feeder))); - NamedCommands.registerCommand("Intake", DriveCommands.intakeUntilNote(arm, intake, feeder)); - NamedCommands.registerCommand("Shoot", DriveCommands.feed(intake, feeder)); - NamedCommands.registerCommand( - "PrepareClose", DriveCommands.prepareShoot(arm, intake, feeder, shooter, 15, 5000)); - } -}