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
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -57,5 +57,6 @@
"edu.wpi.first.math.**.proto.*",
"edu.wpi.first.math.**.struct.*",
],
"java.compile.nullAnalysis.mode": "automatic"
"java.compile.nullAnalysis.mode": "automatic",
"java.debug.settings.onBuildFailureProceed": true
}
7 changes: 3 additions & 4 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ private RobotHardware(SwerveConstants swerveConstants) {
}
}

public static final RobotType ROBOT_TYPE = Robot.isReal() ? RobotType.REAL : RobotType.REPLAY;
public static final RobotType ROBOT_TYPE = Robot.isReal() ? RobotType.REAL : RobotType.SIM;
// For replay to work properly this should match the hardware used in the log
public static final RobotHardware ROBOT_HARDWARE = RobotHardware.KELPIE;

Expand Down Expand Up @@ -685,12 +685,11 @@ public Robot() {
driver
.povUp()
.and(() -> ROBOT_TYPE == RobotType.SIM)
.onTrue(Commands.runOnce(() -> manipulator.setSecondBeambreak(true)).ignoringDisable(true));
.onTrue(Commands.runOnce(() -> manipulator.setFirstBeambreak(true)).ignoringDisable(true));
driver
.povDown()
.and(() -> ROBOT_TYPE == RobotType.SIM)
.onTrue(
Commands.runOnce(() -> manipulator.setSecondBeambreak(false)).ignoringDisable(true));
.onTrue(Commands.runOnce(() -> manipulator.setFirstBeambreak(false)).ignoringDisable(true));
driver
.povRight()
.and(() -> ROBOT_TYPE == RobotType.SIM)
Expand Down
23 changes: 17 additions & 6 deletions src/main/java/frc/robot/subsystems/Superstructure.java
Original file line number Diff line number Diff line change
Expand Up @@ -423,18 +423,24 @@ private void configureStateTransitionCommands() {
stateTriggers
.get(SuperState.SCORE_CORAL)
.and(() -> !manipulator.getFirstBeambreak() && !manipulator.getSecondBeambreak())
.and(() -> !intakeAlgaeReq.getAsBoolean() || !intakeTargetOnReef())
// .debounce(0.15)
.whileTrue(
this.extendWithClearance(
0.0, ShoulderSubsystem.SHOULDER_HP_POS, WristSubsystem.WRIST_HP_POS))
.and(() -> elevator.isNearExtension(0))
.onTrue(this.forceState(SuperState.IDLE));
.onTrue(forceState(SuperState.IDLE));

antiJamReq
.and(stateTriggers.get(SuperState.CLIMB).negate())
.and(stateTriggers.get(SuperState.PRE_CLIMB).negate())
.onTrue(forceState(SuperState.ANTI_JAM))
.onFalse(forceState(SuperState.IDLE));
stateTriggers
.get(SuperState.SCORE_CORAL)
.and(() -> !manipulator.getFirstBeambreak() && !manipulator.getSecondBeambreak())
.and(intakeAlgaeReq)
.and(() -> intakeTargetOnReef())
.onTrue(
forceState(
algaeIntakeTarget.get() == AlgaeIntakeTarget.HIGH
? SuperState.INTAKE_ALGAE_HIGH
: SuperState.INTAKE_ALGAE_LOW));

// ANTI_JAM logic
stateTriggers
Expand Down Expand Up @@ -721,6 +727,11 @@ public boolean stateIsAlgaeAlike() {
|| this.state == SuperState.SCORE_ALGAE_PROCESSOR;
}

public boolean intakeTargetOnReef() {
return this.algaeIntakeTarget.get() == AlgaeIntakeTarget.HIGH
|| this.algaeIntakeTarget.get() == AlgaeIntakeTarget.LOW;
}

private Command forceState(SuperState nextState) {
return Commands.runOnce(
() -> {
Expand Down
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/subsystems/roller/RollerIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,7 @@ public void registerSimulationCallback(Consumer<RollerIOInputsAutoLogged> callba

@Override
public void setPosition(Rotation2d rot) {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'setPosition'");
// TODO Actually simulate
}

@Override
Expand Down