Skip to content
Open
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
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,8 @@

public final class Constants {
public static class constControllers {
public static final double OPERATOR_RUMBLE = 0.3;
public static final double OPERATOR_RUMBLE = 1;
public static final double DRIVER_RUMBLE = .3;
public static final double DRIVER_LEFT_STICK_DEADBAND = 0.05;
public static final boolean SILENCE_JOYSTICK_WARNINGS = true;
}
Expand Down Expand Up @@ -857,8 +858,10 @@ public static class constLED {
LED_CONFIG.brightnessScalar = 1;
}
// LED strip😎
public static final int[] NONE_COLOR = { 0, 0, 255 };
public static final RainbowAnimation NONE_ANIMATION = new RainbowAnimation(MAX_VOLTAGE, MAX_VOLTAGE, 0);
public static final StrobeAnimation READY_TO_SHOOT_ANIMATION = new StrobeAnimation(0, 255, 0, 0, .5, 192);
public static final StrobeAnimation ALIGNING_ANIMATION = new StrobeAnimation(255, 0, 0, 0, 0.5, 192);
public static final int[] PREP_CLIMB = { 0, 0, 0 };
public static final int[] CLIMB = { 0, 0, 0 };
public static final int[] PREP_CORAL_ZERO = { 0, 0, 0 };
Expand Down
29 changes: 27 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,8 @@ public class RobotContainer {
private final Trigger isReadyToScoreReefFeedback = new Trigger(() -> (subDrivetrain.atLastDesiredFieldPosition()
&& subMotion.atLastDesiredMechPosition()));
private final Trigger isReadyToScoreNetFeedback = new Trigger(() -> (subDrivetrain.atLastDesiredFieldPosition()));
private final Trigger isAttemptingAlignFeedback = new Trigger(
() -> (subMotion.atLastDesiredMechPosition() && !subDrivetrain.atLastDesiredFieldPosition()));
private final Trigger hasCoralTrigger = new Trigger(() -> subRotors.hasCoral() && !subRotors.hasAlgae());
private final Trigger hasAlgaeTrigger = new Trigger(() -> !subRotors.hasCoral() && subRotors.hasAlgae());
private final Trigger hasBothTrigger = new Trigger(() -> subRotors.hasCoral() && subRotors.hasAlgae());
Expand All @@ -89,6 +91,10 @@ public class RobotContainer {
private final Trigger isInClimbState = new Trigger(
() -> subStateMachine.getRobotState() == RobotState.CLIMBING
|| subStateMachine.getRobotState() == RobotState.PREP_CLIMB);
private final Trigger isInReefAutoDriveLeft = new Trigger(
() -> subDriverStateMachine.getDriverState() == DriverStateMachine.DriverState.REEF_AUTO_DRIVING_LEFT);
private final Trigger isInReefAutoDriveRight = new Trigger(
() -> subDriverStateMachine.getDriverState() == DriverStateMachine.DriverState.REEF_AUTO_DRIVING_RIGHT);

Command TRY_NONE = Commands.deferredProxy(
() -> subStateMachine.tryState(RobotState.NONE));
Expand Down Expand Up @@ -443,6 +449,7 @@ public Command getAutonomousCommand() {
return autoChooser.getSelected();

}

private void configOperatorBindings() {
// Add operator bindings here if needed
conOperator.btn_LeftTrigger
Expand Down Expand Up @@ -548,14 +555,32 @@ public void configFeedback() {
.onTrue(Commands.runOnce(() -> subLED.setLED(constLED.READY_TO_SHOOT_ANIMATION, 0)))
.whileTrue(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, constControllers.OPERATOR_RUMBLE)))
.whileTrue(
Commands.runOnce(() -> conDriver.setRumble(RumbleType.kBothRumble, constControllers.DRIVER_RUMBLE)))
.onFalse(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0)))
.onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
.onFalse(Commands.runOnce(() -> subLED.setLED(constLED.NONE_COLOR)));
isReadyToScoreNetFeedback
.onTrue(Commands.runOnce(() -> subLED.setLED(constLED.READY_TO_SHOOT_ANIMATION, 0)))
.whileTrue(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, constControllers.OPERATOR_RUMBLE)))
.onFalse(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0)))
.onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
.onFalse(Commands.runOnce(() -> subLED.setLED(constLED.NONE_COLOR)));
isAttemptingAlignFeedback
.whileTrue(Commands.runOnce(() -> subLED.setLED(constLED.ALIGNING_ANIMATION, 0)))
.onFalse(Commands.runOnce(() -> subLED.setLED(constLED.NONE_COLOR)));

// isInCSAutoDriveState
// .onTrue(Commands.runOnce(() -> subLED.setLED(constLED.ALIGNING_ANIMATION)))
// .onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
// isInProcessorAutoDriveState
// .onTrue(Commands.runOnce(() -> subLED.setLED(constLED.ALIGNING_ANIMATION)))
// .onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
// isInReefAutoDriveLeft
// .onTrue(Commands.runOnce(() -> subLED.setLED(constLED.ALIGNING_ANIMATION)))
// .onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
// isInReefAutoDriveRight
// .onTrue(Commands.runOnce(() -> subLED.setLED(constLED.ALIGNING_ANIMATION)))
// .onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
}

public boolean allZeroed() {
Expand Down