Skip to content
This repository was archived by the owner on Jan 10, 2025. It is now read-only.

Commit 93fb71b

Browse files
committed
spotless apply
1 parent 63849b5 commit 93fb71b

File tree

3 files changed

+34
-35
lines changed

3 files changed

+34
-35
lines changed

src/main/java/frc/robot/config/CompConfig.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,9 @@ class CompConfig {
9292
.withStatorCurrentLimit(20))
9393
.withSlot0(new Slot0Configs().withKV(0).withKP(1.0).withKI(0).withKD(0).withKG(0))
9494
.withMotorOutput(
95-
new MotorOutputConfigs().withInverted(InvertedValue.Clockwise_Positive).withNeutralMode(NeutralModeValue.Brake)),
95+
new MotorOutputConfigs()
96+
.withInverted(InvertedValue.Clockwise_Positive)
97+
.withNeutralMode(NeutralModeValue.Brake)),
9698
new Debouncer(0.2, DebounceType.kFalling)),
9799
new ShooterConfig(
98100
18,

src/main/java/frc/robot/swerve/SnapUtil.java

Lines changed: 13 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -26,22 +26,21 @@ public static double getSubwooferAngle() {
2626

2727
public static double getClimbingAngle(ImuSubsystem imu) {
2828
var usedAngles = FmsSubsystem.isRedAlliance() ? RED_STAGE_ANGLES : BLUE_STAGE_ANGLES;
29-
if (FmsSubsystem.isRedAlliance()){
30-
var currentAngle = imu.getRobotHeading();
31-
32-
var closestAngle = RED_STAGE_ANGLES.get(0);
33-
var smallestDifference = Double.POSITIVE_INFINITY;
34-
for (var angle : usedAngles) {
35-
if (Math.abs(angle - currentAngle) < smallestDifference) {
36-
closestAngle = angle;
37-
smallestDifference = Math.abs(angle - currentAngle);
29+
if (FmsSubsystem.isRedAlliance()) {
30+
var currentAngle = imu.getRobotHeading();
31+
32+
var closestAngle = RED_STAGE_ANGLES.get(0);
33+
var smallestDifference = Double.POSITIVE_INFINITY;
34+
for (var angle : usedAngles) {
35+
if (Math.abs(angle - currentAngle) < smallestDifference) {
36+
closestAngle = angle;
37+
smallestDifference = Math.abs(angle - currentAngle);
38+
}
3839
}
39-
}
4040

41-
return closestAngle;
42-
}
43-
else{
44-
var currentAngle = imu.getRobotHeading();
41+
return closestAngle;
42+
} else {
43+
var currentAngle = imu.getRobotHeading();
4544

4645
var closestAngle = BLUE_STAGE_ANGLES.get(0);
4746
var smallestDifference = Double.POSITIVE_INFINITY;
@@ -56,8 +55,5 @@ public static double getClimbingAngle(ImuSubsystem imu) {
5655
}
5756
}
5857

59-
60-
61-
6258
private SnapUtil() {}
6359
}

src/main/java/frc/robot/vision/interpolation/InterpolatedVisionDataset.java

Lines changed: 18 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -62,31 +62,32 @@ public enum InterpolatedVisionDataset {
6262
List.of())),
6363
MADTOWN(
6464
new CameraDataset(
65-
List.of(
66-
new VisionInterpolationData(
67-
new Translation2d(15.2245, 5.522), new Translation2d(15.15, 5.57), "RED_SUBWOOFER"),
68-
new VisionInterpolationData(
69-
new Translation2d(13.0745, 5.522),
70-
new Translation2d(13.33, 5.56),
71-
"RED_PODIUM_SPEAKER_INTERSECTION")),
65+
List.of(
66+
new VisionInterpolationData(
67+
new Translation2d(15.2245, 5.522),
68+
new Translation2d(15.15, 5.57),
69+
"RED_SUBWOOFER"),
70+
new VisionInterpolationData(
71+
new Translation2d(13.0745, 5.522),
72+
new Translation2d(13.33, 5.56),
73+
"RED_PODIUM_SPEAKER_INTERSECTION")),
7274
List.of(
7375
new VisionInterpolationData(
7476
new Translation2d(1.315, 5.522), new Translation2d(1.38, 5.54), "BLUE_SUBWOOFER"),
7577
new VisionInterpolationData(
7678
new Translation2d(3.144, 5.522),
7779
new Translation2d(3.2, 5.42),
7880
"BLUE_PODIUM_SPEAKER_INTERSECTION"))),
79-
80-
8181
new CameraDataset(
82-
List.of(
83-
new VisionInterpolationData(
84-
new Translation2d(15.2245, 5.522), new Translation2d(15.15, 5.58), "RED_SUBWOOFER"),
85-
new VisionInterpolationData(
86-
new Translation2d(13.0745, 5.522),
87-
new Translation2d(13.30, 5.54),
88-
"RED_PODIUM_SPEAKER_INTERSECTION")),
89-
82+
List.of(
83+
new VisionInterpolationData(
84+
new Translation2d(15.2245, 5.522),
85+
new Translation2d(15.15, 5.58),
86+
"RED_SUBWOOFER"),
87+
new VisionInterpolationData(
88+
new Translation2d(13.0745, 5.522),
89+
new Translation2d(13.30, 5.54),
90+
"RED_PODIUM_SPEAKER_INTERSECTION")),
9091
List.of(
9192
new VisionInterpolationData(
9293
new Translation2d(1.315, 5.522), new Translation2d(1.41, 5.53), "BLUE_SUBWOOFER"),

0 commit comments

Comments
 (0)