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

Commit 1b3445f

Browse files
FRCTeam3255-Shared-K11-20S0L0GUYWu-Fan-529
authored
Fixed the command (#66)
Co-authored-by: Evan Grinnell <155865196+S0L0GUY@users.noreply.github.com> Co-authored-by: Wu-Fan-529 <176576491+Wu-Fan-529@users.noreply.github.com>
1 parent 8948ebb commit 1b3445f

File tree

4 files changed

+5
-7
lines changed

4 files changed

+5
-7
lines changed

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ public class RobotContainer {
3535
private final HasGP com_StageGP = new HasGP(subStager);
3636
private final Shoot com_Shoot = new Shoot(subStager, subShooter);
3737
private final intakeHopper com_IntakeHopper = new intakeHopper(subHopper, subStager);
38-
private final EjectGP com_EjectGP = new EjectGP(subIntake, subHopper);
38+
private final EjectGP com_EjectGP = new EjectGP(subIntake);
3939

4040
public RobotContainer() {
4141
subDrivetrain.setDefaultCommand(com_Drive);

src/main/java/frc/robot/commands/EjectGP.java

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -6,18 +6,15 @@
66

77
import edu.wpi.first.wpilibj2.command.Command;
88
import frc.robot.Constants;
9-
import frc.robot.subsystems.Hopper;
109
import frc.robot.subsystems.Intake;
1110

1211
public class EjectGP extends Command {
1312
/** Creates a new EjectGP. */
1413

1514
Intake globalIntake;
16-
Hopper globalHopper;
1715

18-
public EjectGP(Intake subIntake, Hopper subHopper) {
16+
public EjectGP(Intake subIntake) {
1917
// Use addRequirements() here to declare subsystem dependencies.
20-
this.globalHopper = subHopper;
2118
this.globalIntake = subIntake;
2219
}
2320

@@ -35,7 +32,6 @@ public void execute() {
3532
// Called once the command ends or is interrupted.
3633
@Override
3734
public void end(boolean interrupted) {
38-
globalHopper.setOrientationMotorNuetralOutput();
3935
globalIntake.setIntakeNuetralOutput();
4036
}
4137

src/main/java/frc/robot/commands/IntakeGround.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ public void initialize() {
3030
@Override
3131
public void execute() {
3232
// if Stager is full
33-
if (globalStager.getHasGP()) {
33+
if (!globalStager.getHasGP()) {
3434
globalIntake.setIntakeVelocity(0);
3535
} else {
3636
globalIntake.setIntakeVelocity(Constants.constIntake.INTAKE_VELOCITY);

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

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
// import com.ctre.phoenix6.hardware.TalonSRX;
1010

1111
import edu.wpi.first.wpilibj.DigitalInput;
12+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1213
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1314
import frc.robot.RobotMap;
1415

@@ -44,5 +45,6 @@ public boolean getHasGP() {
4445
@Override
4546
public void periodic() {
4647
// This method will be called once per scheduler run
48+
SmartDashboard.putBoolean("hasGP", !getHasGP());
4749
}
4850
}

0 commit comments

Comments
 (0)