Skip to content

Commit d6ed57b

Browse files
a
1 parent 5fd3212 commit d6ed57b

File tree

3 files changed

+24
-23
lines changed

3 files changed

+24
-23
lines changed

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@ task(eventDeploy) {
206206
}
207207
}
208208
createVersionFile.dependsOn(eventDeploy)
209-
// project.compileJava.dependsOn(spotlessApply)
209+
project.compileJava.dependsOn(spotlessApply)
210210
project.tasks.named("compileJava") {
211211
finalizedBy("test")
212212
finalizedBy("syncOffloadClassesToBin")

src/main/java/org/curtinfrc/frc2026/Robot.java

Lines changed: 14 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,6 @@
55

66
import com.ctre.phoenix6.SignalLogger;
77
import com.ctre.phoenix6.signals.InvertedValue;
8-
9-
import choreo.util.ChoreoAllianceFlipUtil;
108
import edu.wpi.first.math.geometry.Pose2d;
119
import edu.wpi.first.math.geometry.Rotation2d;
1210
import edu.wpi.first.net.WebServer;
@@ -15,12 +13,10 @@
1513
import edu.wpi.first.wpilibj.Alert.AlertType;
1614
import edu.wpi.first.wpilibj.DataLogManager;
1715
import edu.wpi.first.wpilibj.DriverStation;
18-
import edu.wpi.first.wpilibj.DriverStation.Alliance;
1916
import edu.wpi.first.wpilibj.Filesystem;
2017
import edu.wpi.first.wpilibj.Threads;
2118
import edu.wpi.first.wpilibj2.command.Command;
2219
import edu.wpi.first.wpilibj2.command.CommandScheduler;
23-
import edu.wpi.first.wpilibj2.command.Commands;
2420
import edu.wpi.first.wpilibj2.command.Subsystem;
2521
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
2622
import edu.wpi.first.wpilibj2.command.button.Trigger;
@@ -57,7 +53,6 @@
5753
import org.curtinfrc.frc2026.subsystems.hoodedshooter.ShooterIOComp;
5854
import org.curtinfrc.frc2026.subsystems.hoodedshooter.ShooterIODev;
5955
import org.curtinfrc.frc2026.subsystems.hoodedshooter.ShooterIOSim;
60-
import org.curtinfrc.frc2026.util.FieldConstants;
6156
import org.curtinfrc.frc2026.util.GameState;
6257
import org.curtinfrc.frc2026.util.PhoenixUtil;
6358
import org.curtinfrc.frc2026.util.Repulsor.Behaviours.AutoPathBehaviour;
@@ -66,7 +61,6 @@
6661
import org.curtinfrc.frc2026.util.Repulsor.Behaviours.ShuttleRecoveryBehaviour;
6762
import org.curtinfrc.frc2026.util.Repulsor.Behaviours.TestBehaviour;
6863
import org.curtinfrc.frc2026.util.Repulsor.Commands.Triggers;
69-
import org.curtinfrc.frc2026.util.Repulsor.DriverStation.NtRepulsorDriverStation;
7064
import org.curtinfrc.frc2026.util.Repulsor.DriverStation.RepulsorDriverStation;
7165
import org.curtinfrc.frc2026.util.Repulsor.DriverStation.RepulsorDriverStationBootstrap;
7266
import org.curtinfrc.frc2026.util.Repulsor.Fallback;
@@ -391,10 +385,13 @@ public Robot() {
391385
// }
392386

393387
// } else {
394-
// // If alliance is blue, then check if it is in the alliance zone by checking the x
395-
// // value is less than the left trench opening (opponent) Then set the location to
388+
// // If alliance is blue, then check if it is in the alliance zone by checking
389+
// the x
390+
// // value is less than the left trench opening (opponent) Then set the location
391+
// to
396392
// // hub.
397-
// if (currentPosition.getX() < FieldConstants.LeftTrench.oppOpeningTopLeft.getX()) {
393+
// if (currentPosition.getX() <
394+
// FieldConstants.LeftTrench.oppOpeningTopLeft.getX()) {
398395
// drive.locationHeadingjoyStickDrive(
399396
// () -> -controller.getLeftY(),
400397
// () -> -controller.getLeftX(),
@@ -421,9 +418,11 @@ public Robot() {
421418
// });
422419
// Pose2d currentPosition = drive.getPose();
423420
// Trigger isRed =
424-
// new Trigger(() -> DriverStation.getAlliance().orElse(Alliance.Blue).equals(Alliance.Red));
421+
// new Trigger(() ->
422+
// DriverStation.getAlliance().orElse(Alliance.Blue).equals(Alliance.Red));
425423
// Trigger isBlue =
426-
// new Trigger(() -> DriverStation.getAlliance().orElse(Alliance.Red).equals(Alliance.Blue));
424+
// new Trigger(() ->
425+
// DriverStation.getAlliance().orElse(Alliance.Red).equals(Alliance.Blue));
427426

428427
// Trigger isLeft =
429428
// new Trigger(() -> currentPosition.getY() < FieldConstants.Hub.topCenterPoint.getY());
@@ -556,11 +555,13 @@ public Robot() {
556555

557556
wireRepulsor();
558557

559-
// controller.a().whileTrue(drive.alignTo(new Pose2d(Constants.FIELD_LENGTH / 2, Constants.FIELD_WIDTH / 2, new Rotation2d())));
558+
// controller.a().whileTrue(drive.alignTo(new Pose2d(Constants.FIELD_LENGTH / 2,
559+
// Constants.FIELD_WIDTH / 2, new Rotation2d())));
560560
// controller.b().whileTrue(
561561
// drive.alignTo(
562562
// ChoreoAllianceFlipUtil.flip(new Pose2d(
563-
// 15.391 - (Constants.ROBOT_X / 2), 3.84 + (Constants.ROBOT_Y / 2), new Rotation2d()))));
563+
// 15.391 - (Constants.ROBOT_X / 2), 3.84 + (Constants.ROBOT_Y / 2), new
564+
// Rotation2d()))));
564565

565566
System.out.println("Robot initialized.");
566567
}

src/main/java/org/curtinfrc/frc2026/subsystems/hoodedshooter/HoodedShooter.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -74,17 +74,17 @@ public void periodic() {
7474
Logger.recordOutput("HoodedShooter/shooterTarget", shooterTarget);
7575

7676
if (Constants.getMode() != Mode.SIM) {
77-
for (int motor = 0; motor < HOOD_MOTOR_NUMBER; motor++) {
78-
hoodMotorDisconnectedAlerts[motor].set(!hoodInputs.motorsConnected[motor]);
79-
hoodMotorTempAlerts[motor].set(hoodInputs.motorTemperatures[motor] > MOTOR_WARNING_TEMP);
80-
}
81-
for (int motor = 0; motor < SHOOTER_MOTOR_NUMBER; motor++) {
82-
shooterMotorDisconnectedAlerts[motor].set(!shooterInputs.motorsConnected[motor]);
83-
shooterMotorTempAlerts[motor].set(
84-
shooterInputs.motorTemperatures[motor] > MOTOR_WARNING_TEMP);
77+
for (int motor = 0; motor < HOOD_MOTOR_NUMBER; motor++) {
78+
hoodMotorDisconnectedAlerts[motor].set(!hoodInputs.motorsConnected[motor]);
79+
hoodMotorTempAlerts[motor].set(hoodInputs.motorTemperatures[motor] > MOTOR_WARNING_TEMP);
80+
}
81+
for (int motor = 0; motor < SHOOTER_MOTOR_NUMBER; motor++) {
82+
shooterMotorDisconnectedAlerts[motor].set(!shooterInputs.motorsConnected[motor]);
83+
shooterMotorTempAlerts[motor].set(
84+
shooterInputs.motorTemperatures[motor] > MOTOR_WARNING_TEMP);
85+
}
8586
}
8687
}
87-
}
8888

8989
public Command setHoodPosition(double position) {
9090
return run(() -> hoodIO.setPosition(position));

0 commit comments

Comments
 (0)