From 360cf5dce15e860c59f6e0e03670acf400e5a433 Mon Sep 17 00:00:00 2001 From: kayla-016 Date: Mon, 27 Jan 2025 17:22:31 -0500 Subject: [PATCH] rollerbar controls --- src/main/java/frc/robot/RobotContainer.java | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 7992950..58d07e0 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -23,6 +23,9 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.commands.DriveCommands; +import frc.robot.subsystems.coralrollerbar.CoralRoller; +import frc.robot.subsystems.coralrollerbar.CoralRollerIOReal; +import frc.robot.subsystems.coralrollerbar.CoralRollerIOSim; import frc.robot.subsystems.drive.Drive; import frc.robot.subsystems.drive.GyroIO; import frc.robot.subsystems.drive.GyroIOPigeon2; @@ -40,6 +43,7 @@ public class RobotContainer { // Subsystems private final Drive drive; + private final CoralRoller coralRoller; // Controller private final CommandXboxController controller = new CommandXboxController(0); @@ -51,6 +55,7 @@ public class RobotContainer { public RobotContainer() { switch (Constants.currentMode) { case REAL: + coralRoller = CoralRoller.init(new CoralRollerIOReal()); // Real robot, instantiate hardware IO implementations drive = new Drive( @@ -62,6 +67,7 @@ public RobotContainer() { break; case SIM: + coralRoller = CoralRoller.init(new CoralRollerIOSim()); // Sim robot, instantiate physics sim IO implementations drive = new Drive( @@ -73,6 +79,7 @@ public RobotContainer() { break; default: + coralRoller = CoralRoller.init(new CoralRollerIOSim()); // Replayed robot, disable IO implementations drive = new Drive( @@ -145,6 +152,12 @@ private void configureButtonBindings() { new Pose2d(drive.getPose().getTranslation(), new Rotation2d())), drive) .ignoringDisable(true)); + controller + .leftBumper() + .onTrue(Commands.runOnce(() -> coralRoller.setVelocity(0.9), coralRoller)); + controller + .rightBumper() + .onTrue(Commands.runOnce(() -> coralRoller.setVelocity(-0.9), coralRoller)); } /**