Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 27 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,12 @@
import java.util.Optional;
import java.util.function.Supplier;

import com.ctre.phoenix.led.ColorFlowAnimation;
import com.ctre.phoenix.led.FireAnimation;
import com.ctre.phoenix.led.RainbowAnimation;
import com.ctre.phoenix.led.TwinkleAnimation;
import com.ctre.phoenix.led.ColorFlowAnimation.Direction;
import com.ctre.phoenix.led.TwinkleAnimation.TwinklePercent;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.Slot1Configs;
import com.ctre.phoenix6.signals.GravityTypeValue;
Expand Down Expand Up @@ -380,7 +386,7 @@ public ShooterPositionGroup(Measure<Angle> shooterAngle, Measure<Velocity<Angle>
Units.RotationsPerSecond.of(35), Units.RotationsPerSecond.of(35), Units.Meters.of(0.46));
public static final ShooterPositionGroup PREP_SHUFFLE = new ShooterPositionGroup(Units.Degrees.of(42),
Units.RotationsPerSecond.of(35), Units.RotationsPerSecond.of(35), Units.Meters.of(0));
public static final ShooterPositionGroup PREP_SUB = new ShooterPositionGroup(Units.Degrees.of(42),
public static final ShooterPositionGroup PREP_SUB = new ShooterPositionGroup(Units.Degrees.of(45),
Units.RotationsPerSecond.of(35), Units.RotationsPerSecond.of(35), Units.Meters.of(0));
public static final ShooterPositionGroup PREP_SPIKE = new ShooterPositionGroup(Units.Degrees.of(27),
Units.RotationsPerSecond.of(60), Units.RotationsPerSecond.of(45), Units.Meters.of(0));
Expand Down Expand Up @@ -631,4 +637,24 @@ public static class constLimelight {
public static final Measure<Angle> LL_PITCH = Units.Degrees.of(20);
public static final Measure<Angle> LL_YAW = Units.Degrees.of(0);
}

public static class constLEDs {
public static final double LED_BRIGHTNESS = 1;
public static final int LED_NUMBER = 200;

public static final int[] CLEAR_LEDS = { 0, 0, 0 };
public static final int[] INTAKING_COLOR = { 0, 0, 0 };
public static final int[] PREP_AMP_COLOR = { 200, 0, 255 };
public static final int[] PREP_SUB_BACKWARDS_COLOR = { 255, 255, 0 };
public static final int[] PREP_SPEAKER_COLOR = { 255, 130, 0 };

public static final ColorFlowAnimation STORE_FEEDER_COLOR = new ColorFlowAnimation(0, 255, 0, 0, 1, LED_NUMBER,
Direction.Forward);
public static final RainbowAnimation READY_TO_SHOOT_COLOR = new RainbowAnimation();

public static final TwinkleAnimation DISABLED_COLOR_1 = new TwinkleAnimation(0, 255, 255, 0, 0.5, LED_NUMBER / 2,
TwinklePercent.Percent100);
public static final TwinkleAnimation DISABLED_COLOR_2 = new TwinkleAnimation(255, 100, 0, 0, 0.5, LED_NUMBER / 2,
TwinklePercent.Percent100, LED_NUMBER / 2);
}
}
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ public void robotPeriodic() {
public void disabledInit() {
m_robotContainer.subStateMachine.setRobotState(RobotState.NONE);
m_robotContainer.subStateMachine.setTargetState(TargetState.PREP_NONE);
m_robotContainer.setDisabledLEDs();
}

@Override
Expand All @@ -63,6 +64,7 @@ public void disabledPeriodic() {

@Override
public void disabledExit() {
m_robotContainer.clearLEDs();
}

@Override
Expand Down
123 changes: 72 additions & 51 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import frc.robot.Constants.constControllers;
import frc.robot.Constants.constElevator;
import frc.robot.Constants.constField;
import frc.robot.Constants.constLEDs;
import frc.robot.Constants.constShooter;
import frc.robot.RobotMap.mapControllers;
import frc.robot.commands.AddVisionMeasurement;
Expand All @@ -41,6 +42,7 @@
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Elevator;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.LEDs;
import frc.robot.subsystems.Shooter;
import frc.robot.subsystems.StateMachine;
import frc.robot.subsystems.Transfer;
Expand All @@ -59,16 +61,24 @@ public class RobotContainer {
private final static Drivetrain subDrivetrain = new Drivetrain();
private final static Elevator subElevator = new Elevator();
private final static Intake subIntake = new Intake();
private final static LEDs subLEDs = new LEDs();
private final static Shooter subShooter = new Shooter();
private final static Transfer subTransfer = new Transfer();
private final static Limelight subLimelight = new Limelight();

private final Trigger gamePieceTrigger = new Trigger(() -> subTransfer.getGamePieceStored());

private final BooleanSupplier readyToShoot = (() -> subDrivetrain.isDrivetrainFacingSpeaker()
private final BooleanSupplier readyToShootOperator = (() -> subDrivetrain.isDrivetrainFacingSpeaker()
&& subShooter.readyToShoot() && subStateMachine.isCurrentStateTargetState()
&& subTransfer.getGamePieceStored());

private final BooleanSupplier readyToShootDriver = (() -> subShooter.readyToShoot()
&& subStateMachine.isCurrentStateTargetState() && subTransfer.getGamePieceStored());

private final BooleanSupplier readyToShootLEDs = (() -> subDrivetrain.isDrivetrainFacingSpeaker()
&& subShooter.readyToShoot() && subStateMachine.getRobotState() == RobotState.PREP_VISION
&& subTransfer.getGamePieceStored());

private final IntakeSource comIntakeSource = new IntakeSource(subStateMachine, subShooter, subTransfer);

SendableChooser<Command> autoChooser = new SendableChooser<>();
Expand All @@ -88,29 +98,46 @@ public RobotContainer() {
.onTrue(Commands
.deferredProxy(
() -> subStateMachine.tryState(RobotState.STORE_FEEDER, subStateMachine, subClimber, subDrivetrain,
subElevator, subIntake, subTransfer, subShooter))
subElevator, subIntake, subLEDs, subTransfer, subShooter))
.andThen(Commands.deferredProxy(
() -> subStateMachine.tryTargetState(subStateMachine, subIntake, subShooter, subTransfer,
() -> subStateMachine.tryTargetState(subStateMachine, subIntake, subLEDs, subShooter, subTransfer,
subElevator, subDrivetrain))))
.onTrue(new GamePieceRumble(conDriver, conOperator).asProxy());

new Trigger(readyToShoot).onTrue(
// new Trigger(readyToShootOperator).onTrue(
// Commands.runOnce(() -> conDriver.setRumble(RumbleType.kBothRumble,
// constControllers.DRIVER_RUMBLE)).alongWith(
// Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble,
// constControllers.OPERATOR_RUMBLE))))
// .onFalse(
// Commands.runOnce(() -> conDriver.setRumble(RumbleType.kBothRumble,
// 0)).alongWith(
// Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0))));

new Trigger(readyToShootOperator).onTrue(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble,
constControllers.OPERATOR_RUMBLE)))
.onFalse(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0)));

new Trigger(readyToShootDriver).onTrue(
Commands.runOnce(() -> conDriver.setRumble(RumbleType.kBothRumble,
constControllers.DRIVER_RUMBLE)).alongWith(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble,
constControllers.OPERATOR_RUMBLE))))
constControllers.DRIVER_RUMBLE)))
.onFalse(
Commands.runOnce(() -> conDriver.setRumble(RumbleType.kBothRumble,
0)).alongWith(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0))));
0)));

new Trigger(readyToShootLEDs)
.onTrue(Commands.runOnce(() -> subLEDs.setLEDAnimation(constLEDs.READY_TO_SHOOT_COLOR, 0)))
.onFalse(Commands.runOnce(() -> subLEDs.clearAnimation()));

subDrivetrain.resetModulesToAbsolute();

conDriver.setTriggerPressThreshold(0.2);

NamedCommands.registerCommand("Intaking", Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.INTAKING, subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake, subTransfer, subShooter))
subIntake, subLEDs, subTransfer, subShooter))
.until(gamePieceTrigger));

SmartDashboard.putNumber("Preload Only Delay", 0);
Expand All @@ -129,9 +156,9 @@ private void configureDriverBindings(SN_XboxController controller) {

// Intake from source
controller.btn_East.whileTrue(Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.INTAKE_SOURCE,
subStateMachine, subClimber, subDrivetrain, subElevator, subIntake, subTransfer, subShooter)))
subStateMachine, subClimber, subDrivetrain, subElevator, subIntake, subLEDs, subTransfer, subShooter)))
.onFalse(Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.NONE, subStateMachine, subClimber,
subDrivetrain, subElevator, subIntake, subTransfer, subShooter))
subDrivetrain, subElevator, subIntake, subLEDs, subTransfer, subShooter))
.unless(() -> comIntakeSource.getIntakeSourceGamePiece()));
}

Expand All @@ -141,93 +168,77 @@ private void configureOperatorBindings(SN_XboxController controller) {
controller.btn_LeftTrigger
.whileTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.INTAKING, subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake,
subTransfer,
subShooter)))
subIntake, subLEDs, subTransfer, subShooter)))
.onFalse(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.NONE, subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake,
subTransfer,
subShooter))
subIntake, subLEDs, subTransfer, subShooter))
.unless(gamePieceTrigger));

// Shoot
controller.btn_RightTrigger.whileTrue(
Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.SHOOTING,
subStateMachine, subClimber, subDrivetrain, subElevator, subIntake, subTransfer, subShooter)))
subStateMachine, subClimber, subDrivetrain, subElevator, subIntake, subLEDs, subTransfer, subShooter)))
.onFalse(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.NONE, subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake,
subTransfer,
subShooter))
subIntake, subLEDs, subTransfer, subShooter))
.unless(gamePieceTrigger));

// Prep with vision
controller.btn_RightBumper.onTrue(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_VISION)))
.onTrue(Commands
.deferredProxy(
() -> subStateMachine.tryState(RobotState.PREP_VISION, subStateMachine, subClimber, subDrivetrain,
subElevator, subIntake, subTransfer, subShooter)));
subElevator, subIntake, subLEDs, subTransfer, subShooter)));

// Ejecting
controller.btn_LeftBumper.whileTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.EJECTING, subStateMachine,
subClimber, subDrivetrain, subElevator,
subIntake,
subTransfer,
subShooter)))
() -> subStateMachine.tryState(RobotState.EJECTING, subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake, subLEDs, subTransfer, subShooter)))
.onFalse(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.NONE, subStateMachine, subClimber,
subDrivetrain, subElevator,
subIntake,
subTransfer,
subShooter)));
() -> subStateMachine.tryState(RobotState.NONE, subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake, subLEDs, subTransfer, subShooter)));

// Prep spike
controller.btn_X.onTrue(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_SPIKE)))
.onTrue(
Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.PREP_SPIKE, subStateMachine, subClimber, subDrivetrain,
subElevator, subIntake, subTransfer, subShooter)));
subElevator, subIntake, subLEDs, subTransfer, subShooter)));

controller.btn_B.onTrue(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_AMP)))
.onTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.PREP_AMP, subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake, subTransfer, subShooter)));
subIntake, subLEDs, subTransfer, subShooter)));

controller.btn_Y.onTrue(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_SUB_BACKWARDS)))
.onTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.PREP_SUB_BACKWARDS, subStateMachine, subClimber, subDrivetrain,
subElevator,
subIntake, subTransfer, subShooter)));
subElevator, subIntake, subLEDs, subTransfer, subShooter)));

// "Unalive Shooter"
controller.btn_A.onTrue(
Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.PREP_NONE,
subStateMachine, subClimber, subDrivetrain, subElevator, subIntake, subTransfer, subShooter))
subStateMachine, subClimber, subDrivetrain, subElevator, subIntake, subLEDs, subTransfer, subShooter))
.alongWith(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_NONE))))
.onFalse(Commands.runOnce(() -> subShooter.setShootingNeutralOutput()));

// Prep subwoofer
controller.btn_South.onTrue(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_SPEAKER)))
.onTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.PREP_SPEAKER, subStateMachine, subClimber, subDrivetrain,
subElevator,
subIntake, subTransfer, subShooter)));
subElevator, subIntake, subLEDs, subTransfer, subShooter)));

// Prep wing
controller.btn_North.onTrue(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_WING)))
.onTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.PREP_WING, subStateMachine, subClimber, subDrivetrain,
subElevator,
subIntake, subTransfer, subShooter)));
subElevator, subIntake, subLEDs, subTransfer, subShooter)));

// Prep shuffle
controller.btn_West.onTrue(Commands.runOnce(() -> subStateMachine.setTargetState(TargetState.PREP_SHUFFLE)))
.onTrue(Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.PREP_SHUFFLE, subStateMachine, subClimber, subDrivetrain,
subElevator,
subIntake, subTransfer, subShooter)));
subElevator, subIntake, subLEDs, subTransfer, subShooter)));

// Game Piece Override
controller.btn_East.onTrue(Commands.runOnce(() -> subTransfer.setGamePieceCollected(true))
Expand All @@ -254,27 +265,27 @@ private void configureAutoSelector() {

// -- Preload Sub --
autoChooser.addOption("Preload Only Amp-Side", new PreloadOnly(subStateMachine, subClimber, subDrivetrain,
subElevator, subIntake, subShooter, subTransfer, 0, preloadDelay));
subElevator, subIntake, subLEDs, subShooter, subTransfer, 0, preloadDelay));
autoChooser.setDefaultOption("Preload Only Center",
new PreloadOnly(subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake, subShooter, subTransfer,
subIntake, subLEDs, subShooter, subTransfer,
1, preloadDelay));
autoChooser.addOption("Preload Only Source-Side", new PreloadOnly(subStateMachine, subClimber, subDrivetrain,
subElevator, subIntake, subShooter, subTransfer, 2, preloadDelay));
subElevator, subIntake, subLEDs, subShooter, subTransfer, 2, preloadDelay));

autoChooser.addOption("Preload Taxi",
new PreloadTaxi(subStateMachine, subClimber, subDrivetrain, subElevator,
subIntake, subShooter, subTransfer));
subIntake, subLEDs, subShooter, subTransfer));
autoChooser.addOption("Wing Only Down", new WingOnly(subStateMachine,
subClimber, subDrivetrain, subElevator,
subIntake, subTransfer, subShooter, readyToShoot, true));
subIntake, subLEDs, subTransfer, subShooter, readyToShootOperator, true));
autoChooser.addOption("Wing Only Up", new WingOnly(subStateMachine,
subClimber, subDrivetrain, subElevator,
subIntake, subTransfer, subShooter, readyToShoot, false));
subIntake, subLEDs, subTransfer, subShooter, readyToShootOperator, false));

autoChooser.addOption("Centerline :3", new Centerline(subStateMachine,
subClimber, subDrivetrain, subElevator,
subIntake, subTransfer, subShooter, readyToShoot, false));
subIntake, subLEDs, subTransfer, subShooter, readyToShootOperator, false));

SmartDashboard.putData(autoChooser);
}
Expand Down Expand Up @@ -307,4 +318,14 @@ public static Command AddVisionMeasurement() {
.withInterruptBehavior(Command.InterruptionBehavior.kCancelIncoming).ignoringDisable(true);
}

public void setDisabledLEDs() {
subLEDs.setLEDAnimation(constLEDs.DISABLED_COLOR_1, 0);
subLEDs.setLEDAnimation(constLEDs.DISABLED_COLOR_2, 1);
}

public void clearLEDs() {
subLEDs.clearAnimation();
subLEDs.setLEDs(constLEDs.CLEAR_LEDS);
}

}
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -65,4 +65,7 @@ public static class mapTransfer {
public static final int NOTE_SENSOR_DIO = 0;
}

public static class mapLEDs {
public static final int CANDLE_CAN = 60;
}
}
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/commands/Autos/Centerline.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Elevator;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.LEDs;
import frc.robot.subsystems.Shooter;
import frc.robot.subsystems.StateMachine;
import frc.robot.subsystems.Transfer;
Expand All @@ -34,6 +35,7 @@ public class Centerline extends SequentialCommandGroup {
Drivetrain subDrivetrain;
Elevator subElevator;
Intake subIntake;
LEDs subLEDs;
Transfer subTransfer;
Shooter subShooter;

Expand Down Expand Up @@ -63,27 +65,29 @@ public SequentialCommandGroup getScoreOrHopCmd(int noteNumber) {
}

public Centerline(StateMachine subStateMachine, Climber subClimber, Drivetrain subDrivetrain, Elevator subElevator,
Intake subIntake, Transfer subTransfer, Shooter subShooter, BooleanSupplier readyToShoot, boolean goesDown) {
Intake subIntake, LEDs subLEDs, Transfer subTransfer, Shooter subShooter, BooleanSupplier readyToShoot,
boolean goesDown) {
this.subStateMachine = subStateMachine;
this.subClimber = subClimber;
this.subDrivetrain = subDrivetrain;
this.subElevator = subElevator;
this.subIntake = subIntake;
this.subLEDs = subLEDs;
this.subTransfer = subTransfer;
this.readyToShoot = readyToShoot;
this.subShooter = subShooter;
this.goesDown = goesDown;

shootSequence = () -> new ShootSequence(subStateMachine, subClimber, subDrivetrain, subElevator, subIntake,
subTransfer, subShooter, readyToShoot);
subLEDs, subTransfer, subShooter, readyToShoot);

addCommands(
Commands.runOnce(
() -> subDrivetrain.resetPoseToPose(getInitialPose().get())),

// -- PRELOAD --
Commands.deferredProxy(() -> subStateMachine.tryState(RobotState.INTAKING, subStateMachine, subClimber,
subDrivetrain, subElevator, subIntake, subTransfer, subShooter))
subDrivetrain, subElevator, subIntake, subLEDs, subTransfer, subShooter))
.until(() -> subTransfer.getGamePieceStored()),

Commands.deferredProxy(shootSequence),
Expand Down
Loading