Skip to content

Commit

Permalink
moved leds only where they need to be
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Apr 1, 2024
1 parent 2f61072 commit 256c3d0
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 27 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 @@ -92,7 +92,7 @@ public RobotContainer() {
));

// revs and intakes if necessary while aiming, then shoots
NamedCommands.registerCommand("shoot", new AutonShoot(_shooterSubsystem, _elevatorSubsystem, _ledSubsystem, _swerveSubsystem, _intakeSubsystem));
NamedCommands.registerCommand("shoot", new AutonShoot(_shooterSubsystem, _elevatorSubsystem, _swerveSubsystem, _intakeSubsystem));

// stops the shooter
NamedCommands.registerCommand("stopShooter", new SpinShooter(_shooterSubsystem, ShooterState.NONE, false));
Expand Down Expand Up @@ -160,7 +160,9 @@ private void configureBindings() {
// driver bindings
_driveController.L1().onTrue(Commands.runOnce(_swerveSubsystem::toggleSpeed, _swerveSubsystem));
_driveController.R1().onTrue(Commands.runOnce(() -> _swerveSubsystem.fieldOriented = !_swerveSubsystem.fieldOriented, _swerveSubsystem));
_driveController.cross().whileTrue(new BrakeSwerve(_swerveSubsystem, _ledSubsystem));
_driveController.cross().whileTrue(new BrakeSwerve(_swerveSubsystem)).whileTrue(Commands.run(() -> {
_ledSubsystem.blink(LEDColors.RED, LEDColors.NOTHING, 0.2);
}, _ledSubsystem));

// TESTING ONLY!!!
_driveController.triangle().onTrue(Commands.runOnce(() -> _swerveSubsystem.resetGyro(180), _swerveSubsystem));
Expand All @@ -187,7 +189,6 @@ private void configureBindings() {
_swerveSubsystem,
_shooterSubsystem,
_elevatorSubsystem,
_ledSubsystem,
() -> (UtilFuncs.GetAlliance() == Alliance.Red) ? 0 : 180,
() -> Presets.CLOSE_SHOOTER_ANGLE,
() -> Presets.CLOSE_ELEVATOR_HEIGHT
Expand All @@ -199,7 +200,6 @@ private void configureBindings() {
_swerveSubsystem,
_shooterSubsystem,
_elevatorSubsystem,
_ledSubsystem,
() -> MathUtil.applyDeadband(-_driveFilterLeftY.calculate(_driveController.getLeftY()), 0.05),
() -> MathUtil.applyDeadband(-_driveFilterLeftX.calculate(_driveController.getLeftX()), 0.05)
)
Expand Down
17 changes: 5 additions & 12 deletions src/main/java/frc/robot/commands/auto/AutoAim.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
import frc.robot.commands.shooter.SetShooter;
import frc.robot.commands.swerve.SetHeading;
import frc.robot.subsystems.ElevatorSubsystem;
import frc.robot.subsystems.LEDSubsystem;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.SwerveDriveSubsystem;

Expand Down Expand Up @@ -42,7 +41,6 @@ private AutoAim(
SwerveDriveSubsystem swerve,
ShooterSubsystem shooter,
ElevatorSubsystem elevator,
LEDSubsystem leds,
DoubleSupplier xSpeed,
DoubleSupplier ySpeed,
DoubleSupplier swerveHeading,
Expand All @@ -56,7 +54,6 @@ private AutoAim(
new SetHeading(swerve, xSpeed, ySpeed, swerveHeading, runOnce),
new SetShooter(shooter, shooterAngle, runOnce),
new SetElevator(elevator, elevatorHeight, runOnce)
// some led command here
);
}

Expand All @@ -69,11 +66,10 @@ public AutoAim(
SwerveDriveSubsystem swerve,
ShooterSubsystem shooter,
ElevatorSubsystem elevator,
LEDSubsystem leds,
DoubleSupplier xSpeed,
DoubleSupplier ySpeed
) {
this(swerve, shooter, elevator, leds, xSpeed, ySpeed, swerve::speakerHeading, shooter::speakerAngle, elevator::speakerHeight, false);
this(swerve, shooter, elevator, xSpeed, ySpeed, swerve::speakerHeading, shooter::speakerAngle, elevator::speakerHeight, false);
}

/**
Expand All @@ -85,14 +81,13 @@ public AutoAim(
SwerveDriveSubsystem swerve,
ShooterSubsystem shooter,
ElevatorSubsystem elevator,
LEDSubsystem leds,
DoubleSupplier xSpeed,
DoubleSupplier ySpeed,
DoubleSupplier swerveHeading,
DoubleSupplier shooterAngle,
DoubleSupplier elevatorHeight
) {
this(swerve, shooter, elevator, leds, xSpeed, ySpeed, swerveHeading, shooterAngle, elevatorHeight, false);
this(swerve, shooter, elevator, xSpeed, ySpeed, swerveHeading, shooterAngle, elevatorHeight, false);
}

/**
Expand All @@ -103,10 +98,9 @@ public AutoAim(
public AutoAim(
SwerveDriveSubsystem swerve,
ShooterSubsystem shooter,
ElevatorSubsystem elevator,
LEDSubsystem leds
ElevatorSubsystem elevator
) {
this(swerve, shooter, elevator, leds, () -> 0, () -> 0, swerve::speakerHeading, shooter::speakerAngle, elevator::speakerHeight, true);
this(swerve, shooter, elevator, () -> 0, () -> 0, swerve::speakerHeading, shooter::speakerAngle, elevator::speakerHeight, true);
}

/**
Expand All @@ -118,11 +112,10 @@ public AutoAim(
SwerveDriveSubsystem swerve,
ShooterSubsystem shooter,
ElevatorSubsystem elevator,
LEDSubsystem leds,
DoubleSupplier swerveHeading,
DoubleSupplier shooterAngle,
DoubleSupplier elevatorHeight
) {
this(swerve, shooter, elevator, leds, () -> 0, () -> 0, swerveHeading, shooterAngle, elevatorHeight, true);
this(swerve, shooter, elevator, () -> 0, () -> 0, swerveHeading, shooterAngle, elevatorHeight, true);
}
}
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/commands/auto/AutonShoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ public class AutonShoot extends SequentialCommandGroup {
public AutonShoot(
ShooterSubsystem shooter,
ElevatorSubsystem elevator,
LEDSubsystem leds,
SwerveDriveSubsystem swerve,
IntakeSubsystem intake
) {
Expand All @@ -39,7 +38,7 @@ public AutonShoot(
new ParallelCommandGroup(
new SpinShooter(shooter, ShooterState.SHOOT, true).andThen(new WaitUntilCommand(shooter::isRevved)),
new FeedActuate(intake, FeedMode.INTAKE).withTimeout(0.5).onlyIf(() -> !intake.hasNoteAuton()),
new AutoAim(swerve, shooter, elevator, leds)
new AutoAim(swerve, shooter, elevator)
),

new FeedActuate(intake, FeedMode.OUTTAKE).withTimeout(0.5)
Expand Down
13 changes: 4 additions & 9 deletions src/main/java/frc/robot/commands/swerve/BrakeSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.subsystems.LEDSubsystem;
import frc.robot.subsystems.SwerveDriveSubsystem;

/**
Expand All @@ -17,17 +15,15 @@
*/
public class BrakeSwerve extends Command {
private final SwerveDriveSubsystem _swerveDrive;
private final LEDSubsystem _leds;

private double _timeout = 0;
private Timer _timer = new Timer();

/** Creates a new BrakeSwerve. */
public BrakeSwerve(SwerveDriveSubsystem swerveDrive, LEDSubsystem leds) {
public BrakeSwerve(SwerveDriveSubsystem swerveDrive) {
_swerveDrive = swerveDrive;
_leds = leds;

addRequirements(_swerveDrive, _leds);
addRequirements(_swerveDrive);
}

/**
Expand All @@ -37,8 +33,8 @@ public BrakeSwerve(SwerveDriveSubsystem swerveDrive, LEDSubsystem leds) {
* - (in seconds) Will keep the drive in brake position for this
* amount of time (must be >0).
*/
public BrakeSwerve(SwerveDriveSubsystem swerveDrive, LEDSubsystem leds, double timeout) {
this(swerveDrive, leds);
public BrakeSwerve(SwerveDriveSubsystem swerveDrive, double timeout) {
this(swerveDrive);

_timeout = timeout;
}
Expand All @@ -58,7 +54,6 @@ public void execute() {
new SwerveModuleState(0, Rotation2d.fromDegrees(-45))};

_swerveDrive.setStates(states);
_leds.blink(Constants.LEDColors.RED, Constants.LEDColors.NOTHING, 0.2);
}

// Called once the command ends or is interrupted.
Expand Down

0 comments on commit 256c3d0

Please sign in to comment.