Skip to content

Commit

Permalink
Formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
ReeledWarrior14 committed Mar 20, 2024
1 parent 387ce79 commit 91980c2
Showing 1 changed file with 14 additions and 14 deletions.
28 changes: 14 additions & 14 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
import com.pathplanner.lib.util.ReplanningConfig;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
Expand All @@ -20,7 +19,6 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
import edu.wpi.first.wpilibj2.command.RepeatCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
Expand Down Expand Up @@ -77,15 +75,16 @@ public RobotContainer() {
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted)));

NamedCommands.registerCommand("Prep-Speed - 60%",
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Prep, 0.01));
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Prep, 0.01));

NamedCommands.registerCommand("Spin up Shooter",
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 0.01));
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 0.01));

NamedCommands.registerCommand("Spin down Shooter",
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.01));
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.01));

NamedCommands.registerCommand("Outtake", new ParallelDeadlineGroup(new WaitCommand(0.25), new NoteOuttakeCommand(m_intakeSubsystem)));
NamedCommands.registerCommand("Outtake",
new ParallelDeadlineGroup(new WaitCommand(0.25), new NoteOuttakeCommand(m_intakeSubsystem)));

NamedCommands.registerCommand("Intake in",
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted));
Expand Down Expand Up @@ -176,7 +175,8 @@ private void configureBindings() {
// DriveConstants.kMaxAngularSpeedRadiansPerSecond - 1, 5)));

new JoystickButton(m_driverController, Button.kX.value)
.onTrue(new SequentialCommandGroup(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, ShooterConstants.kShooterOnTime),
.onTrue(new SequentialCommandGroup(
new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, ShooterConstants.kShooterOnTime),
new ParallelDeadlineGroup(new WaitCommand(1), new NoteOuttakeCommand(m_intakeSubsystem))))
.onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, ShooterConstants.kShooterOffTime));

Expand Down Expand Up @@ -251,13 +251,13 @@ public Command getAutonomousCommand() {
return autoChooser.getSelected();

// return new SequentialCommandGroup(
// new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 3),
// new ParallelDeadlineGroup(new WaitCommand(1.5), new NoteOuttakeCommand(m_intakeSubsystem)),
// new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.01)
// , new ParallelDeadlineGroup(new WaitCommand(20), new RepeatCommand(new InstantCommand(() -> m_robotDrive.autonDrive(new ChassisSpeeds(3, 0, 0)))))
// );


// new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 3),
// new ParallelDeadlineGroup(new WaitCommand(1.5), new
// NoteOuttakeCommand(m_intakeSubsystem)),
// new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.01)
// , new ParallelDeadlineGroup(new WaitCommand(20), new RepeatCommand(new
// InstantCommand(() -> m_robotDrive.autonDrive(new ChassisSpeeds(3, 0, 0)))))
// );

}
}

0 comments on commit 91980c2

Please sign in to comment.