Skip to content
Open
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
26 changes: 25 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,37 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Flywheel;

public class RobotContainer {
// Create an instance of the Arm subsystem
private final Arm arm = new Arm();

// Create an instance of the Flywheel subsystem
private final Flywheel flywheel = new Flywheel();

// Create a joystick to run subsystems off of
private final CommandXboxController joystick = new CommandXboxController(0);

public RobotContainer() {
configureBindings();
}

private void configureBindings() {}
private void configureBindings() {
// When left trigger is pressed the arm will run at a fast speed, and when not pressed it will
// stop
joystick.leftTrigger().onTrue(arm.runFast()).onFalse(arm.stopCommand());

// When right trigger is pressed the flywheel will run at a fast speed, and when not pressed it
// will spin slow
joystick.rightTrigger().onTrue(flywheel.runFast()).onFalse(flywheel.runSlow());

// When A button is pressed the flywheel will run at a fast speed, and when not pressed it will
// stop
joystick.a().onTrue(flywheel.runFast()).onFalse(flywheel.stopCommand());
}

public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
Expand Down
30 changes: 30 additions & 0 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Arm extends SubsystemBase {
Expand Down Expand Up @@ -58,6 +59,35 @@ public void setVoltage(double voltage) {
leader.setControl(voltageOut.withOutput(voltage));
}

/**
* Command to run the arm at a slow speed.
*
* @return The command to run the arm slowly.
*/
public Command runSlow() {
// Command to run the arm at a slow speed and stop it afterward
return runOnce(() -> setVoltage(3));
}

/**
* Command to run the arm at a fast speed.
*
* @return The command to run the arm quickly.
*/
public Command runFast() {
// Command to run the arm at a fast speed and stop it afterward
return runOnce(() -> setVoltage(6));
}

/**
* Command to stop the arm.
*
* @return The command to stop the arm.
*/
public Command stopCommand() {
return runOnce(() -> stop());
}

// Stop the arm motor
public void stop() {
leader.stopMotor();
Expand Down
30 changes: 30 additions & 0 deletions src/main/java/frc/robot/subsystems/Flywheel.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Flywheel extends SubsystemBase {
Expand Down Expand Up @@ -56,6 +57,35 @@ public void setVoltage(double voltage) {
leader.setControl(voltageOut.withOutput(voltage));
}

/**
* Command to run the flywheel at a slow speed.
*
* @return The command to run the flywheel slowly.
*/
public Command runSlow() {
// Command to run the flywheel at a slow speed
return runOnce(() -> setVoltage(3));
}

/**
* Command to run the flywheel at a fast speed.
*
* @return The command to run the flywheel fast.
*/
public Command runFast() {
// Command to run the flywheel at a fast speed
return runOnce(() -> setVoltage(6));
}

/**
* Command to stop the flywheel.
*
* @return The command to stop the flywheel.
*/
public Command stopCommand() {
return runOnce(() -> stop());
}

// Stop the flywheel motors
public void stop() {
leader.stopMotor();
Expand Down