Skip to content

Commit

Permalink
Reduced Auton Time
Browse files Browse the repository at this point in the history
  • Loading branch information
ProgrammingSR committed Mar 9, 2024
1 parent ba24d02 commit b4eedf4
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 6 deletions.
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,9 @@ public class RobotContainer {
public RobotContainer() {
NamedCommands.registerCommand("Shoot",
new SequentialCommandGroup(
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting),
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 1.5),
new ParallelDeadlineGroup(new WaitCommand(1), new NoteOuttakeCommand(m_intakeSubsystem)),
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off)));
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.01)));

NamedCommands.registerCommand("Intake",
new SequentialCommandGroup(
Expand Down Expand Up @@ -164,9 +164,9 @@ private void configureBindings() {
// DriveConstants.kMaxAngularSpeedRadiansPerSecond - 1, 5)));

new JoystickButton(m_driverController, Button.kX.value)
.onTrue(new SequentialCommandGroup(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting),
.onTrue(new SequentialCommandGroup(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 1.5),
new NoteOuttakeCommand(m_intakeSubsystem)))
.onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off));
.onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.3));

new JoystickButton(m_operatorController, Button.kA.value)
.onTrue(new InstantCommand(() -> m_climberSubsystem.forward(),
Expand Down
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/commands/ShooterSetSpeedCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,15 +13,19 @@ public class ShooterSetSpeedCommand extends Command {
ShooterSubsystem m_ShooterSubsystem;
double m_shooterSpeed = 0;


double set_time = 1.5;
Timer m_timer = new Timer();

ShootSpeed m_shootSpeed;

/** Creates a new ShootCommand. */
public ShooterSetSpeedCommand(ShooterSubsystem shooterSubsystem, ShootSpeed shootSpeed) {
public ShooterSetSpeedCommand(ShooterSubsystem shooterSubsystem, ShootSpeed shootSpeed, double time) {
m_ShooterSubsystem = shooterSubsystem;
addRequirements(m_ShooterSubsystem);

set_time = time;

m_shootSpeed = shootSpeed;
}

Expand All @@ -47,6 +51,6 @@ public void end(boolean interrupted) {
// Returns true when the command should end.
@Override
public boolean isFinished() {
return m_timer.get() > 1.5;
return m_timer.get() > set_time;
}
}

0 comments on commit b4eedf4

Please sign in to comment.