Skip to content

Commit

Permalink
fix: made feeder sequence have the intake running, and made the intak…
Browse files Browse the repository at this point in the history
…e not run while feeder speeds up for shooting
  • Loading branch information
AdleyJ committed Feb 6, 2024
1 parent 673dfa2 commit 35a726b
Show file tree
Hide file tree
Showing 5 changed files with 41 additions and 8 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package org.team1540.robot2024.commands.indexer;

import edu.wpi.first.wpilibj2.command.Command;
import org.team1540.robot2024.subsystems.indexer.Indexer;

public class OuttakeCommand extends Command {

private final Indexer indexer;

public OuttakeCommand(Indexer indexer) {
this.indexer = indexer;
addRequirements(indexer);
}

@Override
public void initialize() {
indexer.setIntakePercent(-0.5);
}

@Override
public boolean isFinished() {
return !indexer.isNoteStaged();
}

@Override
public void end(boolean interrupted) {
indexer.setIntakePercent(0);
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -3,24 +3,24 @@
import edu.wpi.first.wpilibj2.command.Command;
import org.team1540.robot2024.subsystems.indexer.Indexer;

public class PrepareIndexerForShooter extends Command {
public class PrepareFeederForShooter extends Command {

private final Indexer indexer;

public PrepareIndexerForShooter(Indexer indexer) {
public PrepareFeederForShooter(Indexer indexer) {
this.indexer = indexer;
addRequirements(indexer);
}

@Override
public void initialize() {
indexer.setFeederVelocity(1200);
indexer.setIntakePercent(-0.5);

}

@Override
public boolean isFinished() {
return indexer.isFeederAtSetpoint() && !indexer.isNoteStaged();
return indexer.isFeederAtSetpoint();
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ public StageTrampCommand(Tramp tramp, Indexer indexer) {
public void initialize() {
tramp.setPercent(0.5);
indexer.setFeederVelocity(-600);
indexer.setIntakePercent(0.5);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,18 @@

import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import org.team1540.robot2024.commands.indexer.PrepareIndexerForShooter;
import org.team1540.robot2024.commands.indexer.OuttakeCommand;
import org.team1540.robot2024.commands.indexer.PrepareFeederForShooter;
import org.team1540.robot2024.subsystems.indexer.Indexer;
import org.team1540.robot2024.subsystems.shooter.Shooter;

public class ShootSequence extends SequentialCommandGroup {
public ShootSequence(Shooter shooter, Indexer indexer) {
addCommands(
Commands.parallel(
new PrepareIndexerForShooter(indexer),
new PrepareShooterCommand(shooter)
new PrepareFeederForShooter(indexer),
new PrepareShooterCommand(shooter),
new OuttakeCommand(indexer)
),
Commands.runOnce(() -> indexer.setIntakePercent(1), indexer)
// TODO: Add a wait for having completed the shot (steady then current spike/velocity dip and then back down?)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ public boolean isFeederAtSetpoint() {
}

public void stopFeeder() {
io.setFeederVoltage(0); // shouldn't stopFeeder probably set its velocity?
io.setFeederVoltage(0);
}
public void stopIntake() {
io.setIntakeVoltage(0);
Expand Down

0 comments on commit 35a726b

Please sign in to comment.