Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
94 changes: 61 additions & 33 deletions src/main/java/org/blackknights/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.*;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import java.util.function.Supplier;
import org.blackknights.commands.*;
import org.blackknights.constants.ScoringConstants;
Expand All @@ -28,8 +29,8 @@ public class RobotContainer {
ButtonBoardSubsystem buttonBoardSubsystem = new ButtonBoardSubsystem(buttonBoard);

// Controllers
Controller primaryController = new Controller(0);
Controller secondaryController = new Controller(1);
CommandXboxController primaryController = new CommandXboxController(0);
CommandXboxController secondaryController = new CommandXboxController(1);

private final NetworkTablesUtils NTTune = NetworkTablesUtils.getTable("debug");

Expand Down Expand Up @@ -88,20 +89,26 @@ private void configureBindings() {
true,
true));

primaryController.leftBumper.whileTrue(
getPlaceCommand(() -> coralQueue.getCurrentPosition(), () -> coralQueue.getNext()));

primaryController.rightBumper.whileTrue(
new ParallelCommandGroup(
new ElevatorArmCommand(
elevatorSubsystem,
armSubsystem,
() -> ScoringConstants.ScoringHeights.INTAKE),
new IntakeCommand(intakeSubsystem, IntakeCommand.IntakeMode.INTAKE)));
primaryController
.leftBumper()
.whileTrue(
getPlaceCommand(
() -> coralQueue.getCurrentPosition(), () -> coralQueue.getNext()));

primaryController
.leftBumper()
.whileTrue(
new ParallelCommandGroup(
new ElevatorArmCommand(
elevatorSubsystem,
armSubsystem,
() -> ScoringConstants.ScoringHeights.INTAKE),
new IntakeCommand(
intakeSubsystem, IntakeCommand.IntakeMode.INTAKE)));

elevatorSubsystem.setDefaultCommand(new BaseCommand(elevatorSubsystem, armSubsystem));

primaryController.dpadDown.whileTrue(new RunCommand(() -> swerveSubsystem.zeroGyro()));
primaryController.povDown().whileTrue(new RunCommand(() -> swerveSubsystem.zeroGyro()));

// SECONDARY CONTROLLER

Expand All @@ -113,32 +120,53 @@ private void configureBindings() {
// secondaryController.rightBumper.onTrue(new InstantCommand(() ->
// coralQueue.stepForwards()));

secondaryController.aButton.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem, armSubsystem, () -> ScoringConstants.ScoringHeights.L1));
secondaryController
.a()
.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem,
armSubsystem,
() -> ScoringConstants.ScoringHeights.L1));

secondaryController.bButton.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem, armSubsystem, () -> ScoringConstants.ScoringHeights.L2));
secondaryController
.b()
.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem,
armSubsystem,
() -> ScoringConstants.ScoringHeights.L2));

secondaryController.xButton.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem, armSubsystem, () -> ScoringConstants.ScoringHeights.L3));
secondaryController
.x()
.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem,
armSubsystem,
() -> ScoringConstants.ScoringHeights.L3));

secondaryController.yButton.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem, armSubsystem, () -> ScoringConstants.ScoringHeights.L4));
secondaryController
.y()
.whileTrue(
new ElevatorArmCommand(
elevatorSubsystem,
armSubsystem,
() -> ScoringConstants.ScoringHeights.L4));

secondaryController
.leftBumper()
.onTrue(new InstantCommand(() -> coralQueue.stepForwards()));

secondaryController.leftBumper.onTrue(new InstantCommand(() -> coralQueue.stepForwards()));
secondaryController
.rightBumper()
.onTrue(new InstantCommand(() -> coralQueue.stepBackwards()));

secondaryController.rightBumper.onTrue(
new InstantCommand(() -> coralQueue.stepBackwards()));
secondaryController
.rightTrigger(0.2)
.whileTrue(new IntakeCommand(intakeSubsystem, IntakeCommand.IntakeMode.OUTTAKE));

// secondaryController.rightTrigger.whileTrue(
// new IntakeCommand(intakeSubsystem, IntakeCommand.IntakeMode.OUTTAKE));
//
// secondaryController.leftTrigger.whileTrue(
// new IntakeCommand(intakeSubsystem, IntakeCommand.IntakeMode.INTAKE));
secondaryController
.leftTrigger(0.2)
.whileTrue(new IntakeCommand(intakeSubsystem, IntakeCommand.IntakeMode.INTAKE));
}

/** Runs once when the code starts */
Expand Down
13 changes: 7 additions & 6 deletions src/main/java/org/blackknights/commands/ClimberCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,35 +2,36 @@
package org.blackknights.commands;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import org.blackknights.subsystems.ClimberSubsystem;
import org.blackknights.utils.Controller;

/** Climber command to control the climber */
public class ClimberCommand extends Command {
public ClimberSubsystem climberSubsystem;
public Controller controller;
public CommandXboxController controller;

/**
* Command to controller the climber, right now over pure voltage
*
* @param climberSubsystem The instance of {@link ClimberSubsystem}
* @param controller A {@link Controller} to control the climber
*/
public ClimberCommand(ClimberSubsystem climberSubsystem, Controller controller) {
public ClimberCommand(ClimberSubsystem climberSubsystem, CommandXboxController controller) {
this.climberSubsystem = climberSubsystem;
this.controller = controller;
addRequirements(climberSubsystem);
}

@Override
public void execute() {
if (controller.dpadDown.getAsBoolean()) {
if (controller.povDown().getAsBoolean()) {
climberSubsystem.setClimberSpeed(1);
} else if (controller.dpadUp.getAsBoolean()) {
} else if (controller.povUp().getAsBoolean()) {
climberSubsystem.setClimberSpeed(-1);
} else if (controller.dpadLeft.getAsBoolean()) {
} else if (controller.povLeft().getAsBoolean()) {
climberSubsystem.setLockSpeed(0.5);
} else if (controller.dpadRight.getAsBoolean()) {
} else if (controller.povRight().getAsBoolean()) {
climberSubsystem.setLockSpeed(-0.5);
} else {
climberSubsystem.setClimberSpeed(0);
Expand Down
76 changes: 0 additions & 76 deletions src/main/java/org/blackknights/utils/Controller.java

This file was deleted.

Loading