Skip to content

Commit

Permalink
spotless boohoo
Browse files Browse the repository at this point in the history
  • Loading branch information
kirbt committed Mar 30, 2024
1 parent 782ac95 commit 17f4818
Showing 1 changed file with 3 additions and 4 deletions.
7 changes: 3 additions & 4 deletions src/main/java/frc/team2412/robot/util/auto/AutoAlignment.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,8 @@ public class AutoAlignment {
private static final Subsystems s = r.subsystems;

private static Supplier<Pose2d> currentPosition = s.drivebaseWrapper::getEstimatedPosition;
private static Supplier<Pose2d> goalPosition = () -> AutoLogic.getSelectedAutoPath().getStartPose2d();
private static Supplier<Pose2d> goalPosition =
() -> AutoLogic.getSelectedAutoPath().getStartPose2d();

private static final double POSITION_TOLERANCE = 0.5;
private static final double ROTATION_TOLERANCE = 5;
Expand All @@ -36,8 +37,7 @@ public static void initShuffleboard() {
.withPosition(0, 1)
.withSize(3, 1);

tab.addBoolean(
"Correct Horizontal Position", AutoAlignment::isRobotInCorrectHorizontalPosition)
tab.addBoolean("Correct Horizontal Position", AutoAlignment::isRobotInCorrectHorizontalPosition)
.withPosition(3, 0)
.withSize(2, 1);
tab.addBoolean("Correct Vertical Position", AutoAlignment::isRobotInCorrectVerticalPosition)
Expand Down Expand Up @@ -89,7 +89,6 @@ private static String getPose2dString(Pose2d pose) {
+ " deg.)";
}


private static void initField() {
field = new Field2d();

Expand Down

0 comments on commit 17f4818

Please sign in to comment.