Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/main'
Browse files Browse the repository at this point in the history
# Conflicts:
#	src/main/java/frc/robot/RobotContainer.java
#	src/main/java/frc/robot/commands/ShooterCommands.java
  • Loading branch information
GBKP committed Apr 5, 2024
2 parents a947bf9 + 15c6d50 commit 3e286a2
Show file tree
Hide file tree
Showing 4 changed files with 56 additions and 40 deletions.
65 changes: 29 additions & 36 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,9 @@
import edu.wpi.first.wpilibj.RobotState;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.*;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;
Expand All @@ -54,7 +56,6 @@
import frc.robot.subsystems.lights.LEDs;
import frc.robot.subsystems.shooter.*;
import frc.robot.util.Mode;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardBoolean;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;
Expand Down Expand Up @@ -207,55 +208,52 @@ public String getCameraName() {
);
NamedCommands.registerCommand(
"Zero Feeder",
FeederCommands.feedToBeamBreak(feeder).asProxy()
// STOP THE FEEDER ONCE DONE, WAIT FOR SHOOTER TAKE OVER
.andThen(Commands.runOnce(() -> {
feeder.runVolts(0.0);
}))
FeederCommands.feedToBeamBreak(feeder)
);
NamedCommands.registerCommand(
"Zero Hood",
ShooterCommands.simpleHoodZero(shooter).asProxy()
ShooterCommands.simpleHoodZero(shooter)
);
NamedCommands.registerCommand(
"Auto Point",
ShooterCommands.autoAim(shooter, drive, feeder).asProxy()
);
NamedCommands.registerCommand(
"Shoot When Ready",

sequence(
waitUntil(feeder::getBeamBroken),
sequence(
waitUntil(() -> (shooter.allAtSetpoint() && (shooter.getShooterVelocityRPM() > 1000))),
feedToShooter(feeder).asProxy()
feedToShooter(feeder)
)
.onlyWhile(() -> {
Logger.recordOutput("Sanity Check", feeder.getBeamBroken());
return feeder.getBeamBroken();
})
).finallyDo(interupted -> {
System.out.println("AH SAANTITY lCHECK OVER");
}));
;
.onlyWhile(() -> !feeder.getBeamBroken())
.withTimeout(3.0)
).raceWith(SpecializedCommands.timeoutDuringAutoSim(3.0))
);
NamedCommands.registerCommand(
"Shoot",
sequence(
feedToBeamBreak(feeder).asProxy(),
feedToBeamBreak(feeder),
waitUntil(() -> (shooter.allAtSetpoint() && (shooter.getShooterVelocityRPM() > 1000))),
feedToShooter(feeder).asProxy()
feedToShooter(feeder)
)
.deadlineWith(ShooterCommands.JustShoot(shooter).asProxy())
.deadlineWith(ShooterCommands.JustShoot(shooter))
.withTimeout(8.0));
NamedCommands.registerCommand(
"Intake Note",
smartIntakeCommand(intake, feeder).raceWith(
feedToBeamBreak(feeder)
)
.andThen(feedToBeamBreak(feeder).withTimeout(8.0)).until(() -> feeder.getBeamBroken()).asProxy()
smartIntakeCommand(intake, feeder)
.andThen(either(
none(),
race(
feedToBeamBreak(feeder).withTimeout(5),
IntakeCommands.flushIntakeWithoutTheArmExtendedOutward(intake, feeder)
),
feeder::getBeamBroken
)).withTimeout(3.0)
);
NamedCommands.registerCommand(
"Intake",
intakeCommand(intake).asProxy()
intakeCommand(intake)
.withTimeout(1.0)
);
autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser());
Expand Down Expand Up @@ -291,8 +289,8 @@ private void configureButtonBindings() {
() -> (-driverController.getLeftY() * (invertX.get()?-1:1)),
() -> (-driverController.getLeftX() * (invertY.get()?-1:1)),
() -> (-driverController.getRightX()) * (invertOmega.get()?-1:1)));
intake.setDefaultCommand(IntakeCommands.idleCommand(intake).withName("Intake Idle"));
feeder.setDefaultCommand(new RunCommand(() -> feeder.runVolts(0.0), feeder).withName("Stop Feeder"));
intake.setDefaultCommand(IntakeCommands.idleCommand(intake));
feeder.setDefaultCommand(new RunCommand(() -> feeder.runVolts(0.0), feeder));
shooter.setDefaultCommand(
either(
ShooterCommands.shooterIdle(shooter),
Expand All @@ -302,7 +300,7 @@ private void configureButtonBindings() {
ShooterCommands.shooterIdle(shooter)
).withName("Default Command"),
shooter::hasZeroed
).withName("Shooter Default")
)

);
// CLIMB DEFAULT COMMAND
Expand Down Expand Up @@ -350,12 +348,6 @@ private void configureButtonBindings() {
feeder::getBeamBroken
)
);
driverController
.rightBumper()
.whileTrue(DriveCommands.intakeAlign(drive,
() -> (-driverController.getLeftY() * (invertX.get()?-1:1)),
() -> (-driverController.getLeftX() * (invertY.get()?-1:1)),
() -> (-driverController.getRightX()) * (invertOmega.get()?-1:1)));

operatorController
.povLeft()
Expand All @@ -371,8 +363,9 @@ private void configureButtonBindings() {
parallel(
ShooterCommands.humanPlayerIntake(shooter),
FeederCommands.humanPlayerIntake(feeder)
).onlyWhile(() -> !feeder.getBeamBroken()),
).until(feeder::getBeamBroken),
parallel(
ShooterCommands.humanPlayerIntake(shooter),
FeederCommands.humanPlayerIntake(feeder)
).until(() -> !feeder.getBeamBroken())
).andThen(FeederCommands.feedToBeamBreak(feeder))
Expand Down
11 changes: 8 additions & 3 deletions src/main/java/frc/robot/commands/FeederCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ public static Command idleFeeder(Feeder feeder) {
zeroToBeamBreak(feeder)
),
feeder::getBeamBroken
)
).beforeStarting(()-> feeder.setState(Feeder.State.none))
);
}
public static Command feedToShooter(Feeder feeder) {
Expand All @@ -29,7 +29,9 @@ public static Command feedToShooter(Feeder feeder) {
run(() -> feeder.runVolts(9), feeder)
.withTimeout(0.5),
runOnce(() -> feeder.runVolts(0.0))
);
)
.beforeStarting(()->feeder.setState(Feeder.State.feedingShooter))
.finallyDo(interrupted -> feeder.setState(Feeder.State.none));
}

public static Command flushFeeder(Feeder feeder) {
Expand Down Expand Up @@ -58,7 +60,10 @@ public static Command feedToBeamBreak(Feeder feeder) {
feeder::getBeamBroken
)
),
feeder::getBeamBroken);
feeder::getBeamBroken)
.beforeStarting(()-> feeder.setState(Feeder.State.zeroingNote))
.finallyDo(interrupted -> feeder.setState(Feeder.State.none));

}

private static Command slowToBeam(Feeder feeder) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/ShooterCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ public static void construct() {
distanceToRPM.put(3.506, 4000.0);
distanceToRPM.put(4.25, 4200.0);
distanceToRPM.put(1000.0,
5000.0);
4000.0);
}

public static LoggedDashboardBoolean retractAfterShot = new LoggedDashboardBoolean("Aim/Retract After Shooting", true);
Expand Down
18 changes: 18 additions & 0 deletions src/main/java/frc/robot/subsystems/feeder/Feeder.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,24 @@ public class Feeder extends SubsystemBase {
private final ProfiledPIDController pidController;
double offset = 0.0;

private State state = State.none;

public enum State {
feedingShooter,
intaking,
zeroingNote,
humanPlayerIntake,
none
}

public State getState() {
return state;
}

public void setState(State state) {
this.state = state;
}

Debouncer debouncer = new Debouncer(.05, kBoth);
Debouncer debouncer2 = new Debouncer(.05, kBoth);

Expand Down

0 comments on commit 3e286a2

Please sign in to comment.