Skip to content

Commit

Permalink
Finished the command and button to use the command for the coral outtake
Browse files Browse the repository at this point in the history
  • Loading branch information
Nathanael7639 committed Jan 8, 2025
1 parent 4beedf4 commit c48ca0f
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 2 deletions.
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,12 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.commands.ResetGyro;
import frc.robot.commands.RunCoralOuttake;
import frc.robot.constants.SWERVE;
import frc.robot.constants.USB;
import frc.robot.generated.TunerConstants;
import frc.robot.subsystems.CommandSwerveDrivetrain;
import frc.robot.subsystems.CoralOuttake;
import frc.robot.utils.Telemetry;

/**
Expand All @@ -30,6 +32,7 @@ public class RobotContainer {
// The robot's subsystems and commands are defined here...
private final CommandSwerveDrivetrain m_swerveDrive = TunerConstants.createDrivetrain();
private final Telemetry m_telemetry = new Telemetry();
private final CoralOuttake m_coralOuttake = new CoralOuttake();

// Replace with CommandPS4Controller or CommandJoystick if needed
private final Joystick leftJoystick = new Joystick(USB.leftJoystick);
Expand Down Expand Up @@ -97,6 +100,7 @@ private void configureBindings() {
// // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed,
// // cancelling on release.
// m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand());
m_driverController.leftBumper().whileTrue(new RunCoralOuttake(m_coralOuttake, 0.5));
}

/**
Expand Down
14 changes: 12 additions & 2 deletions src/main/java/frc/robot/commands/runCoralOuttake.java
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.CoralOuttake;

public class runCoralOuttake {
public class RunCoralOuttake extends Command {
private final CoralOuttake m_coralOuttake;
private final double m_desiredPercentOutput;

public runCoralOuttake(CoralOuttake coralOuttake, double desiredPercentOutput) {
public RunCoralOuttake(CoralOuttake coralOuttake, double desiredPercentOutput) {
m_coralOuttake = coralOuttake;
m_desiredPercentOutput = desiredPercentOutput;
}
Expand All @@ -18,4 +19,13 @@ public void initialize() {
public void execute() {
m_coralOuttake.setDesiredPercentOutput(m_desiredPercentOutput);
}

public void end(boolean interrupted) {
m_coralOuttake.setDesiredPercentOutput(0);
m_coralOuttake.setOuttakingState(false);
}

public boolean isFinished() {
return false;
}
}

0 comments on commit c48ca0f

Please sign in to comment.