Skip to content

Commit

Permalink
brought back auton to when it was working
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Mar 29, 2024
1 parent e51c1f4 commit 43cec34
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 18 deletions.
17 changes: 15 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.button.CommandPS4Controller;
import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller;
import frc.robot.Constants.Presets;
Expand Down Expand Up @@ -205,10 +206,22 @@ public void teleopInit() {
/** @return The Command to schedule for auton. */
public Command getAutonCommand() {
AutonShoot.reset();

_swerveSubsystem.fieldOriented = false; // make sure swerve is robot-relative for pathplanner to work
_shooterSubsystem.setShooterState(ShooterState.SHOOT);
_shooterSubsystem.setShooterState(ShooterState.IDLE);

// Command test = new SequentialCommandGroup(
// NamedCommands.getCommand("shoot"),
// NamedCommands.getCommand("actuateOut").withTimeout(1),
// NamedCommands.getCommand("actuateInFast"),
// new AutonShoot(_shooterSubsystem, _elevatorSubsystem, _ledSubsystem, _swerveSubsystem, _intakeSubsystem),
// new FeedActuate(_intakeSubsystem, ActuatorState.OUT, FeedMode.INTAKE).withTimeout(2),
// NamedCommands.getCommand("actuateIn").withTimeout(2),
// new AutonShoot(_shooterSubsystem, _elevatorSubsystem, _ledSubsystem, _swerveSubsystem, _intakeSubsystem)
// );

// return null
// return test;
return _autonChooser.getSelected();
// return null;
}
}
19 changes: 6 additions & 13 deletions src/main/java/frc/robot/commands/auto/AutonShoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,7 @@
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class AutonShoot extends SequentialCommandGroup {
/** If the note is intaked all the way to shoot. */
public static boolean isIntaked = false;

/** If the shooter is revved all the way to shoot. */
public static boolean isRevved = false;
public static boolean canShoot = false;

/** Creates a new AutonShoot. */
public AutonShoot(
Expand All @@ -43,13 +39,11 @@ public AutonShoot(
new ParallelCommandGroup(
// This command will squeeze the note while revving up the shooter. It will only run if the note can't be shot right away.
new ParallelCommandGroup(
new SpinShooter(shooter, ShooterState.SHOOT, true).andThen(new WaitCommand(2)).andThen(
() -> isRevved = true
).onlyIf(() -> !isRevved),
new FeedActuate(intake, FeedMode.INTAKE).onlyIf(() -> !isIntaked).withTimeout(1)
),
new SpinShooter(shooter, ShooterState.SHOOT, true).andThen(new WaitCommand(2)), //.andThen(() -> System.out.println("REVVED")),
new FeedActuate(intake, FeedMode.INTAKE).withTimeout(1)//.andThen(() -> System.out.println("INTAKED"))
).onlyIf(() -> !canShoot),

new AutoAim(swerve, shooter, elevator, leds)
new AutoAim(swerve, shooter, elevator, leds) //.withTimeout(1).andThen(() -> System.out.println("AIMED"))
),

new FeedActuate(intake, FeedMode.OUTTAKE).withTimeout(1),
Expand All @@ -59,8 +53,7 @@ public AutonShoot(

/** Resets this command for re-testing auton. */
public static void reset() {
isIntaked = false;
isRevved = false;
canShoot = false;
}

private double headingPreset() {
Expand Down
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/commands/intake/FeedActuate.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,7 @@ public void initialize() {
_intake.feed(_feedMode);
_intake.actuate(_actuatorState);

// if not squished, can't shoot, else can (FOR AUTON)
if (_runOnce && _actuatorState == ActuatorState.STOWED) AutonShoot.isIntaked = false;
if (!_runOnce && _actuatorState == ActuatorState.STOWED) AutonShoot.isIntaked = true;
AutonShoot.canShoot = !_runOnce;
}

// Called every time the scheduler runs while the command is scheduled.
Expand Down

0 comments on commit 43cec34

Please sign in to comment.