Skip to content
This repository was archived by the owner on Jul 20, 2025. It is now read-only.

Commit 222f5e1

Browse files
authored
tried my best to make the eject command🦟™️ (#33)
* tried my best to make the eject command🦟™️ * added making it stop once done🦟™️
1 parent 312e2ce commit 222f5e1

File tree

3 files changed

+60
-1
lines changed

3 files changed

+60
-1
lines changed

src/main/java/frc/robot/RobotContainer.java

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import edu.wpi.first.wpilibj2.command.Command;
1010
import edu.wpi.first.wpilibj2.command.Commands;
1111
import frc.robot.commands.Drive;
12+
import frc.robot.commands.EjectGP;
1213
import frc.robot.commands.IntakeGround;
1314
import frc.robot.commands.PrepShooter;
1415
import frc.robot.commands.Shoot;
@@ -27,7 +28,8 @@ public class RobotContainer {
2728
private final Hopper subHopper = new Hopper();
2829
private final Shooter subShooter = new Shooter();
2930
private final Stager subStager = new Stager();
30-
private final Drive com_Drive = new Drive(subDrivetrain, m_driverController.axis_LeftY, m_driverController.axis_RightX);
31+
private final Drive com_Drive = new Drive(subDrivetrain, m_driverController.axis_LeftY,
32+
m_driverController.axis_RightX);
3133
private final IntakeGround com_IntakeGround = new IntakeGround(subIntake, subHopper);
3234
private final PrepShooter com_PrepShooter = new PrepShooter(subShooter);
3335
private final StageGP com_StageGP = new StageGP(subStager);
@@ -43,7 +45,11 @@ private void configureBindings() {
4345
m_driverController.btn_LeftBumper.whileTrue(new intakeHopper(subHopper));
4446
m_driverController.btn_X.whileTrue(com_PrepShooter);
4547
m_driverController.btn_A.whileTrue(com_StageGP);
48+
49+
m_driverController.btn_RightBumper.whileTrue(new EjectGP(subIntake, subHopper));
50+
4651
m_driverController.btn_Y.onTrue(com_Shoot);
52+
4753
}
4854

4955
public Command getAutonomousCommand() {
Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
// Copyright (c) FIRST and other WPILib contributors.
2+
// Open Source Software; you can modify and/or share it under the terms of
3+
// the WPILib BSD license file in the root directory of this project.
4+
5+
package frc.robot.commands;
6+
7+
import edu.wpi.first.wpilibj2.command.Command;
8+
import frc.robot.subsystems.Hopper;
9+
import frc.robot.subsystems.Intake;
10+
11+
public class EjectGP extends Command {
12+
/** Creates a new EjectGP. */
13+
14+
Intake globalIntake;
15+
Hopper globalHopper;
16+
17+
public EjectGP(Intake subIntake, Hopper subHopper) {
18+
// Use addRequirements() here to declare subsystem dependencies.
19+
this.globalHopper = subHopper;
20+
this.globalIntake = subIntake;
21+
}
22+
23+
// Called when the command is initially scheduled.
24+
@Override
25+
public void initialize() {
26+
globalIntake.setTopMotorVelocity(-0.5);
27+
globalIntake.setBottomMotorVelocity(-0.5);
28+
}
29+
30+
// Called every time the scheduler runs while the command is scheduled.
31+
@Override
32+
public void execute() {
33+
}
34+
35+
// Called once the command ends or is interrupted.
36+
@Override
37+
public void end(boolean interrupted) {
38+
globalHopper.setHopperMotorNuetralOutput();
39+
globalIntake.setIntakeNuetralOutput(0);
40+
}
41+
42+
// Returns true when the command should end.
43+
@Override
44+
public boolean isFinished() {
45+
return false;
46+
}
47+
}

src/main/java/frc/robot/subsystems/Intake.java

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,12 @@ public void setBottomMotorVelocity(double velocity) {
2727
topMotor.set(velocity);
2828
}
2929

30+
public void setIntakeNuetralOutput(double velocity) {
31+
topMotor.set(0);
32+
bottomMotor.set(0);
33+
34+
}
35+
3036
@Override
3137
public void periodic() {
3238
// This method will be called once per scheduler run

0 commit comments

Comments
 (0)