Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
7a86d58
elastic camera fix
RobototesProgrammers Oct 18, 2025
c8fcedc
autoScore stuff
RobototesProgrammers Oct 18, 2025
3cf57f5
Merge branch 'GGCOMPB' of https://github.com/robototes/Reefscape2025 …
RobototesProgrammers Oct 18, 2025
1014c22
l1 auto align
RobototesProgrammers Oct 18, 2025
0d2405e
ee
RobototesProgrammers Oct 18, 2025
f0f2c2f
Merge branch 'GGCOMPB' of https://github.com/robototes/Reefscape2025 …
RobototesProgrammers Oct 18, 2025
e00f827
c
RobototesProgrammers Oct 18, 2025
088c917
super jank code to get auto l1 auto extake
RobototesProgrammers Oct 18, 2025
e1b832a
c
RobototesProgrammers Oct 18, 2025
c183519
ds changes
RobototesProgrammers Oct 19, 2025
0bcbd20
quick hand off fix
RobototesProgrammers Oct 19, 2025
3212b7e
Merge branch 'GGCOMPB' of https://github.com/robototes/Reefscape2025 …
RobototesProgrammers Oct 19, 2025
b2d6687
log + spot
Jetblackdragon Oct 20, 2025
820357e
current limits for motors
Jetblackdragon Oct 20, 2025
9f58805
Velocity control
Jetblackdragon Oct 20, 2025
7bc2597
VC
Jetblackdragon Oct 20, 2025
7d02c1d
aarta sketchy drivebase change
RobototesProgrammers Oct 21, 2025
3c38d31
rebump up of drive motor current limits
Jetblackdragon Oct 21, 2025
7fc3da1
Code Clean up for get coral branch height
Jetblackdragon Oct 21, 2025
4663bbb
Removed auto score rubmle
Jetblackdragon Oct 21, 2025
f6a454b
Correct use of ipScore repeat prescoreswing
Jetblackdragon Oct 21, 2025
ba0ce5f
Added comments for the in place scoring
Jetblackdragon Oct 21, 2025
f3d86c8
Consolidated all autoAligns into 1
Jetblackdragon Oct 21, 2025
7e367e7
Merge branch 'GGCOMPB' into drivebt2
Jetblackdragon Oct 21, 2025
05605ae
Added static classes to check for alliance side.
Jetblackdragon Oct 21, 2025
f4a5bae
shop testing changes 10/23
RobototesProgrammers Oct 24, 2025
f7b07a7
SPTOELSSSSS
RobototesProgrammers Oct 24, 2025
acb8bde
Timing fix
RobototesProgrammers Oct 24, 2025
8b80718
elastic layout override
RobototesProgrammers Oct 25, 2025
7124258
pre comp changes
RobototesProgrammers Oct 25, 2025
0e252e2
double jump auto
RobototesProgrammers Nov 7, 2025
0cd8b06
Merge branch 'pre-WASS-fixes/changes' of https://github.com/robototes…
RobototesProgrammers Nov 18, 2025
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
920 changes: 564 additions & 356 deletions src/main/deploy/elastic-layout.json

Large diffs are not rendered by default.

81 changes: 81 additions & 0 deletions src/main/deploy/pathplanner/autos/Double-Bump-JK.auto

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

54 changes: 54 additions & 0 deletions src/main/deploy/pathplanner/paths/DoubleBump.path

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

123 changes: 77 additions & 46 deletions src/main/java/frc/robot/Controls.java
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,7 @@ public class Controls {
new SwerveRequest.FieldCentric()
.withDeadband(0.0001)
.withRotationalDeadband(0.0001)
.withDriveRequestType(
DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
.withDriveRequestType(DriveRequestType.Velocity);

private final Telemetry logger = new Telemetry(MaxSpeed);

Expand Down Expand Up @@ -112,6 +111,14 @@ public Controls(Subsystems s, Sensors sensors, SuperStructure superStructure) {
configureGroundSpinnyBindings();
configureGroundArmBindings();
configureSoloControllerBindings();
Shuffleboard.getTab("Elevator")
.addBoolean("Intaking mode Algae", () -> intakeMode == ScoringMode.ALGAE);
Shuffleboard.getTab("Elevator")
.addString("Scoring Mode", () -> getSoloScoringMode().toString());
}

public SoloScoringMode getSoloScoringMode() {
return soloScoringMode;
}

private Trigger connected(CommandXboxController controller) {
Expand Down Expand Up @@ -287,7 +294,7 @@ private void configureSuperStructureBindings() {
Commands.deferredProxy(
() ->
switch (scoringMode) {
case CORAL -> getCoralBranchHeightCommand();
case CORAL -> getCoralBranchHeightCommand("2C");
case ALGAE -> Commands.sequence(
superStructure.algaeProcessorScore(
driverController.rightBumper()),
Expand Down Expand Up @@ -394,12 +401,7 @@ private void configureSuperStructureBindings() {
case ALGAE -> soloScoringMode = SoloScoringMode.ALGAE_IN_CLAW;
}
})
.withName("Set solo scoring mode"));

sensors
.armSensor
.inClaw()
.and(RobotModeTriggers.teleop())
.withName("Set solo scoring mode"))
.onFalse(
Commands.runOnce(
() -> {
Expand All @@ -423,7 +425,7 @@ private void configureSuperStructureBindings() {
() -> {
Command scoreCommand =
switch (scoringMode) {
case CORAL -> getCoralBranchHeightCommand();
case CORAL -> getCoralBranchHeightCommand("2C");
case ALGAE -> Commands.sequence(
BargeAlign.bargeScore(
s.drivebaseSubsystem,
Expand All @@ -448,30 +450,55 @@ private Command getAlgaeIntakeCommand() {
};
}

private Command getCoralBranchHeightCommand() {
return switch (branchHeight) {
case CORAL_LEVEL_FOUR -> superStructure.coralLevelFour(driverController.rightBumper());
case CORAL_LEVEL_THREE -> superStructure.coralLevelThree(driverController.rightBumper());
case CORAL_LEVEL_TWO -> superStructure.coralLevelTwo(driverController.rightBumper());
case CORAL_LEVEL_ONE -> superStructure.coralLevelOne(driverController.rightBumper());
};
}

private Command getSoloCoralBranchHeightCommand() {
return switch (branchHeight) {
case CORAL_LEVEL_FOUR -> superStructure
.coralLevelFour(soloController.rightBumper())
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_THREE -> superStructure
.coralLevelThree(soloController.rightBumper())
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_TWO -> superStructure
.coralLevelTwo(soloController.rightBumper())
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_ONE -> superStructure
.coralLevelOne(soloController.rightBumper())
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
};
private Command getCoralBranchHeightCommand(String version) {
if (version.equals("SL")) {
return switch (branchHeight) {
case CORAL_LEVEL_FOUR -> superStructure
.coralLevelFour(soloController.rightBumper())
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_THREE -> superStructure
.coralLevelThree(
soloController.rightBumper(),
() -> AutoAlign.poseInPlace(AutoAlign.AlignType.LEFTB))
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_TWO -> superStructure
.coralLevelTwo(
soloController.rightBumper(),
() -> AutoAlign.poseInPlace(AutoAlign.AlignType.LEFTB))
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_ONE -> superStructure
.coralLevelOne(
soloController.rightBumper(), () -> AutoAlign.poseInPlace(AutoAlign.AlignType.L1LB))
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
};
} else if (version.equals("SR")) {
return switch (branchHeight) {
case CORAL_LEVEL_FOUR -> superStructure
.coralLevelFour(soloController.rightBumper())
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_THREE -> superStructure
.coralLevelThree(
soloController.rightBumper(),
() -> AutoAlign.poseInPlace(AutoAlign.AlignType.RIGHTB))
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_TWO -> superStructure
.coralLevelTwo(
soloController.rightBumper(),
() -> AutoAlign.poseInPlace(AutoAlign.AlignType.RIGHTB))
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
case CORAL_LEVEL_ONE -> superStructure
.coralLevelOne(
soloController.rightBumper(), () -> AutoAlign.poseInPlace(AutoAlign.AlignType.L1RB))
.andThen(() -> soloScoringMode = soloScoringMode.NO_GAME_PIECE);
};
} else {
return switch (branchHeight) {
case CORAL_LEVEL_FOUR -> superStructure.coralLevelFour(driverController.rightBumper());
case CORAL_LEVEL_THREE -> superStructure.coralLevelThree(driverController.rightBumper());
case CORAL_LEVEL_TWO -> superStructure.coralLevelTwo(driverController.rightBumper());
case CORAL_LEVEL_ONE -> superStructure.coralLevelOne(driverController.rightBumper());
};
}
}

private void configureElevatorBindings() {
Expand Down Expand Up @@ -806,12 +833,12 @@ private void configureAutoAlignBindings() {
.rightTrigger()
.and(() -> scoringMode == ScoringMode.CORAL)
.and(() -> branchHeight != BranchHeight.CORAL_LEVEL_ONE)
.whileTrue(AutoAlign.autoAlignRight(s.drivebaseSubsystem, this));
.whileTrue(AutoAlign.autoAlign(s.drivebaseSubsystem, this, AutoAlign.AlignType.RIGHTB));
driverController
.leftTrigger()
.and(() -> scoringMode == ScoringMode.CORAL)
.and(() -> branchHeight != BranchHeight.CORAL_LEVEL_ONE)
.whileTrue(AutoAlign.autoAlignLeft(s.drivebaseSubsystem, this));
.whileTrue(AutoAlign.autoAlign(s.drivebaseSubsystem, this, AutoAlign.AlignType.LEFTB));
}

private void configureGroundSpinnyBindings() {
Expand Down Expand Up @@ -926,7 +953,7 @@ private void configureSoloControllerBindings() {
switch (soloScoringMode) {
case CORAL_IN_CLAW -> {
scoreCommand =
getSoloCoralBranchHeightCommand()
getCoralBranchHeightCommand("SL")
.until(
() ->
soloController.a().getAsBoolean()
Expand Down Expand Up @@ -968,7 +995,12 @@ private void configureSoloControllerBindings() {
.leftTrigger()
.and(() -> soloScoringMode == soloScoringMode.CORAL_IN_CLAW)
.and(() -> branchHeight != BranchHeight.CORAL_LEVEL_ONE)
.whileTrue(AutoAlign.autoAlignLeft(s.drivebaseSubsystem, this));
.whileTrue(AutoAlign.autoAlign(s.drivebaseSubsystem, this, AutoAlign.AlignType.LEFTB));
soloController
.leftTrigger()
.and(() -> soloScoringMode == soloScoringMode.CORAL_IN_CLAW)
.and(() -> branchHeight == BranchHeight.CORAL_LEVEL_ONE)
.whileTrue(AutoAlign.autoAlign(s.drivebaseSubsystem, this, AutoAlign.AlignType.L1LB));
// Processor + Auto align right + Select scoring mode Coral
soloController
.rightTrigger()
Expand All @@ -977,7 +1009,7 @@ private void configureSoloControllerBindings() {
() -> {
Command scoreCommand =
switch (soloScoringMode) {
case CORAL_IN_CLAW -> getSoloCoralBranchHeightCommand()
case CORAL_IN_CLAW -> getCoralBranchHeightCommand("SR")
.until(
() ->
soloController.a().getAsBoolean()
Expand Down Expand Up @@ -1005,7 +1037,12 @@ private void configureSoloControllerBindings() {
.rightTrigger()
.and(() -> soloScoringMode == soloScoringMode.CORAL_IN_CLAW)
.and(() -> branchHeight != BranchHeight.CORAL_LEVEL_ONE)
.whileTrue(AutoAlign.autoAlignRight(s.drivebaseSubsystem, this));
.whileTrue(AutoAlign.autoAlign(s.drivebaseSubsystem, this, AutoAlign.AlignType.RIGHTB));
soloController
.rightTrigger()
.and(() -> soloScoringMode == soloScoringMode.CORAL_IN_CLAW)
.and(() -> branchHeight == BranchHeight.CORAL_LEVEL_ONE)
.whileTrue(AutoAlign.autoAlign(s.drivebaseSubsystem, this, AutoAlign.AlignType.L1RB));
// Ground Intake
soloController
.leftBumper()
Expand Down Expand Up @@ -1095,11 +1132,5 @@ private void configureSoloControllerBindings() {
.startMovingVoltage(
() -> Volts.of(ElevatorSubsystem.UP_VOLTAGE * -soloController.getLeftY()))
.withName("Elevator Manual Control"));
// Ready to score rumble
Trigger readyToScore = new Trigger(() -> AutoAlign.poseInPlace());
readyToScore.onTrue(
Commands.runOnce(() -> soloController.setRumble(RumbleType.kBothRumble, 1.0)));
readyToScore.onFalse(
Commands.runOnce(() -> soloController.setRumble(RumbleType.kBothRumble, 0.0)));
}
}
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 @@ -13,6 +13,7 @@
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
Expand Down Expand Up @@ -52,6 +53,7 @@ protected Robot() {
PDH = new PowerDistribution(Hardware.PDH_ID, ModuleType.kRev);
LiveWindow.disableAllTelemetry();
LiveWindow.enableTelemetry(PDH);
RobotController.setBrownoutVoltage(6.3);

sensors = new Sensors();
subsystems = new Subsystems(sensors);
Expand Down
Loading