Skip to content

Commit

Permalink
rollerbar controls
Browse files Browse the repository at this point in the history
  • Loading branch information
kayla-016 committed Jan 27, 2025
1 parent 7f02be9 commit 360cf5d
Showing 1 changed file with 13 additions and 0 deletions.
13 changes: 13 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -40,6 +43,7 @@
public class RobotContainer {
// Subsystems
private final Drive drive;
private final CoralRoller coralRoller;

// Controller
private final CommandXboxController controller = new CommandXboxController(0);
Expand All @@ -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(
Expand All @@ -62,6 +67,7 @@ public RobotContainer() {
break;

case SIM:
coralRoller = CoralRoller.init(new CoralRollerIOSim());
// Sim robot, instantiate physics sim IO implementations
drive =
new Drive(
Expand All @@ -73,6 +79,7 @@ public RobotContainer() {
break;

default:
coralRoller = CoralRoller.init(new CoralRollerIOSim());
// Replayed robot, disable IO implementations
drive =
new Drive(
Expand Down Expand Up @@ -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));
}

/**
Expand Down

0 comments on commit 360cf5d

Please sign in to comment.