diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java b/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java index fac672636c..566c2fb118 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java @@ -37,7 +37,7 @@ public class PhotonConfiguration { private final HardwareSettings hardwareSettings; private NetworkConfig networkConfig; private AprilTagFieldLayout atfl; - private HashMap cameraConfigurations; + private final HashMap cameraConfigurations; public PhotonConfiguration( HardwareConfig hardwareConfig, diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java index 883b3607d8..4e5ef6c18d 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java @@ -131,10 +131,11 @@ private void initDatabase() { try { createGlobalTableStatement = conn.createStatement(); String sql = - "CREATE TABLE IF NOT EXISTS global (\n" - + " filename TINYTEXT PRIMARY KEY,\n" - + " contents mediumtext NOT NULL\n" - + ");"; + """ + CREATE TABLE IF NOT EXISTS global ( + filename TINYTEXT PRIMARY KEY, + contents mediumtext NOT NULL + );"""; createGlobalTableStatement.execute(sql); } catch (SQLException e) { logger.error("Err creating global table", e); @@ -144,13 +145,14 @@ private void initDatabase() { try { createCameraTableStatement = conn.createStatement(); var sql = - "CREATE TABLE IF NOT EXISTS cameras (\n" - + " unique_name TINYTEXT PRIMARY KEY,\n" - + " config_json text NOT NULL,\n" - + " drivermode_json text NOT NULL,\n" - + " otherpaths_json text NOT NULL,\n" - + " pipeline_jsons mediumtext NOT NULL\n" - + ");"; + """ + CREATE TABLE IF NOT EXISTS cameras ( + unique_name TINYTEXT PRIMARY KEY, + config_json text NOT NULL, + drivermode_json text NOT NULL, + otherpaths_json text NOT NULL, + pipeline_jsons mediumtext NOT NULL + );"""; createCameraTableStatement.execute(sql); } catch (SQLException e) { logger.error("Err creating cameras table", e); diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java index a62e0f3b4c..ad9ece3329 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java @@ -49,7 +49,7 @@ public class NetworkTablesManager { private boolean m_isRetryingConnection = false; - private StringSubscriber m_fieldLayoutSubscriber = + private final StringSubscriber m_fieldLayoutSubscriber = kRootTable.getStringTopic(kFieldLayoutName).subscribe(""); private NetworkTablesManager() { diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/GPIOBase.java b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/GPIOBase.java index a1d25be98f..09fe34a149 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/GPIOBase.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/GPIOBase.java @@ -27,7 +27,7 @@ public abstract class GPIOBase { private static final Logger logger = new Logger(GPIOBase.class, LogGroup.General); private static final ShellExec runCommand = new ShellExec(true, true); - protected static HashMap commands = + protected static final HashMap commands = new HashMap<>() { { put("setState", ""); diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioPulse.java b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioPulse.java index 6d0ff0d1ea..bfa6e2feae 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioPulse.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioPulse.java @@ -18,9 +18,9 @@ package org.photonvision.common.hardware.GPIO.pi; public class PigpioPulse { - int gpioOn; - int gpioOff; - int delayMicros; + final int gpioOn; + final int gpioOff; + final int delayMicros; /** * Initialises a pulse. diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioSocket.java b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioSocket.java index d6c2bd310d..853b931078 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioSocket.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/pi/PigpioSocket.java @@ -242,21 +242,14 @@ public void generateAndSendWaveform(int pulseTimeMillis, int blinks, int... pins waveSendOnce(waveformId); } } else { - String error = ""; - switch (waveformId) { - case PI_EMPTY_WAVEFORM: - error = "Waveform empty"; - break; - case PI_TOO_MANY_CBS: - error = "Too many CBS"; - break; - case PI_TOO_MANY_OOL: - error = "Too many OOL"; - break; - case PI_NO_WAVEFORM_ID: - error = "No waveform ID"; - break; - } + String error = + switch (waveformId) { + case PI_EMPTY_WAVEFORM -> "Waveform empty"; + case PI_TOO_MANY_CBS -> "Too many CBS"; + case PI_TOO_MANY_OOL -> "Too many OOL"; + case PI_NO_WAVEFORM_ID -> "No waveform ID"; + default -> ""; + }; logger.error("Failed to send wave: " + error); } } diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java b/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java index 7d1d5273b3..2d629ed584 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java @@ -134,25 +134,17 @@ void onLedModeChange(NetworkTableEvent entryNotification) { var newLedModeRaw = (int) entryNotification.valueData.value.getInteger(); logger.debug("Got LED mode " + newLedModeRaw); if (newLedModeRaw != currentLedMode.value) { - VisionLEDMode newLedMode; - switch (newLedModeRaw) { - case -1: - newLedMode = VisionLEDMode.kDefault; - break; - case 0: - newLedMode = VisionLEDMode.kOff; - break; - case 1: - newLedMode = VisionLEDMode.kOn; - break; - case 2: - newLedMode = VisionLEDMode.kBlink; - break; - default: - logger.warn("User supplied invalid LED mode, falling back to Default"); - newLedMode = VisionLEDMode.kDefault; - break; - } + VisionLEDMode newLedMode = + switch (newLedModeRaw) { + case -1 -> VisionLEDMode.kDefault; + case 0 -> VisionLEDMode.kOff; + case 1 -> VisionLEDMode.kOn; + case 2 -> VisionLEDMode.kBlink; + default -> { + logger.warn("User supplied invalid LED mode, falling back to Default"); + yield VisionLEDMode.kDefault; + } + }; setInternal(newLedMode, true); if (modeConsumer != null) modeConsumer.accept(newLedMode.value); diff --git a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java index 593b4fbfcf..55d94b7f74 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java @@ -84,7 +84,7 @@ public enum WPI2019Image { kRocketPanelAngleDark48in(1.2192), kRocketPanelAngleDark60in(1.524); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; @@ -122,7 +122,7 @@ public enum WPI2020Image { kRedLoading_084in(2.1336), kRedLoading_108in(2.7432); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; @@ -143,7 +143,7 @@ public enum WPI2023Apriltags { k162_36_Straight, k383_60_Angle2; - public static double FOV = 68.5; + public static final double FOV = 68.5; public final Translation2d approxPose; public final Path path; @@ -170,7 +170,7 @@ public enum WPI2022Image { kTerminal12ft6in(Units.feetToMeters(12.5)), kTerminal22ft6in(Units.feetToMeters(22.5)); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; diff --git a/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java b/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java index 9a6047c797..174f9553bf 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java +++ b/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java @@ -51,11 +51,10 @@ public void set(T first, T second) { @Override public boolean equals(Object obj) { - if (!(obj instanceof NumberCouple)) { + if (!(obj instanceof NumberCouple couple)) { return false; } - var couple = (NumberCouple) obj; if (!couple.first.equals(first)) { return false; } diff --git a/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java index 8a12aeabfa..fb9c0481f0 100644 --- a/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java +++ b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java @@ -71,25 +71,16 @@ public enum SensorModel { Unknown; public String getFriendlyName() { - switch (this) { - case Disconnected: - return "Disconnected Camera"; - case OV5647: - return "Camera Module v1"; - case IMX219: - return "Camera Module v2"; - case IMX708: - return "Camera Module v3"; - case IMX477: - return "HQ Camera"; - case OV9281: - return "OV9281"; - case OV7251: - return "OV7251"; - case Unknown: - default: - return "Unknown Camera"; - } + return switch (this) { + case Disconnected -> "Disconnected Camera"; + case OV5647 -> "Camera Module v1"; + case IMX219 -> "Camera Module v2"; + case IMX708 -> "Camera Module v3"; + case IMX477 -> "HQ Camera"; + case OV9281 -> "OV9281"; + case OV7251 -> "OV7251"; + default -> "Unknown Camera"; + }; } } diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java b/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java index 05737ed293..a42d072d99 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java @@ -113,7 +113,7 @@ public static QuirkyCamera getQuirkyCamera(int usbVid, int usbPid, String baseNa // If we have a quirkycamera we need to copy the quirks from our predefined object and create // a quirkycamera object with the baseName. if (qc.usbVid == usbVid && qc.usbPid == usbPid && matchesBaseName) { - List quirks = new ArrayList(); + List quirks = new ArrayList<>(); for (var q : CameraQuirk.values()) { if (qc.hasQuirk(q)) quirks.add(q); } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/FrameStaticProperties.java b/photon-core/src/main/java/org/photonvision/vision/frame/FrameStaticProperties.java index cedda04d22..91f43c1d18 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/FrameStaticProperties.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/FrameStaticProperties.java @@ -33,7 +33,7 @@ public class FrameStaticProperties { public final Point centerPoint; public final double horizontalFocalLength; public final double verticalFocalLength; - public CameraCalibrationCoefficients cameraCalibration; + public final CameraCalibrationCoefficients cameraCalibration; /** * Instantiates a new Frame static properties. diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java index a9f9151828..ad86f53e38 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java @@ -39,8 +39,8 @@ public class FileSaveFrameConsumer implements Consumer { private static final String FILE_EXTENSION = ".jpg"; private static final String NT_SUFFIX = "SaveImgCmd"; - DateFormat df = new SimpleDateFormat("yyyy-MM-dd"); - DateFormat tf = new SimpleDateFormat("hhmmssSS"); + final DateFormat df = new SimpleDateFormat("yyyy-MM-dd"); + final DateFormat tf = new SimpleDateFormat("hhmmssSS"); private final NetworkTable rootTable; private NetworkTable subTable; diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java index aa6727e4e4..ea9dad8827 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java @@ -228,20 +228,14 @@ private static String videoModeToString(VideoMode mode) { } private static String pixelFormatToString(VideoMode.PixelFormat pixelFormat) { - switch (pixelFormat) { - case kMJPEG: - return "MJPEG"; - case kYUYV: - return "YUYV"; - case kRGB565: - return "RGB565"; - case kBGR: - return "BGR"; - case kGray: - return "Gray"; - default: - return "Unknown"; - } + return switch (pixelFormat) { + case kMJPEG -> "MJPEG"; + case kYUYV -> "YUYV"; + case kRGB565 -> "RGB565"; + case kBGR -> "BGR"; + case kGray -> "Gray"; + default -> "Unknown"; + }; } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java index 034ae6615e..f31b8b6230 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java @@ -31,9 +31,9 @@ public abstract class CpuImageProcessor implements FrameProvider { protected static class CapturedFrame { - CVMat colorImage; - FrameStaticProperties staticProps; - long captureTimestamp; + final CVMat colorImage; + final FrameStaticProperties staticProps; + final long captureTimestamp; public CapturedFrame( CVMat colorImage, FrameStaticProperties staticProps, long captureTimestampNanos) { diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java index 03459c197d..cf9a1a4e3e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java @@ -25,10 +25,8 @@ public class USBFrameProvider extends CpuImageProcessor { private final CvSink cvSink; - @SuppressWarnings("SpellCheckingInspection") private final VisionSourceSettables settables; - @SuppressWarnings("SpellCheckingInspection") public USBFrameProvider(CvSink sink, VisionSourceSettables visionSettables) { cvSink = sink; cvSink.setEnabled(true); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/CVPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/CVPipe.java index d941f51cd0..056d98131e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/CVPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/CVPipe.java @@ -26,7 +26,7 @@ * @param

Parameters type for the pipe */ public abstract class CVPipe { - protected CVPipeResult result = new CVPipeResult<>(); + protected final CVPipeResult result = new CVPipeResult<>(); protected P params; public void setParams(P params) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java index 3c6563e182..67f8b5e99d 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java @@ -39,7 +39,7 @@ public AprilTagPoseEstimatorPipe() { super(); } - MatOfPoint2f temp = new MatOfPoint2f(); + final MatOfPoint2f temp = new MatOfPoint2f(); @Override protected AprilTagPoseEstimate process(AprilTagDetection in) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java index 34b1384e92..9363879006 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java @@ -35,7 +35,7 @@ public class ArucoDetectionPipeParams { * *

E.g. 36h11 -> 11 * errorCorrectionRate = Max error bits */ - public double errorCorrectionRate = 0; + public final double errorCorrectionRate = 0; /** * If obtained corners should be iteratively refined. This should always be on for 3D estimation. @@ -51,7 +51,7 @@ public class ArucoDetectionPipeParams { */ public double refinementMinErrorPx = 0.005; - public boolean debugRefineWindow = false; + public final boolean debugRefineWindow = false; /** * If the 'Aruco3' speedup should be used. This is similar to AprilTag's 'decimate' value, but diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java index 113da4d357..cf173e664b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java @@ -24,7 +24,7 @@ public class CalculateFPSPipe extends CVPipe { private final LinearFilter fpsFilter = LinearFilter.movingAverage(20); - StopWatch clock = new StopWatch(); + final StopWatch clock = new StopWatch(); @Override protected Integer process(Void in) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java index bed3c6b5ef..cf8f5c319c 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java @@ -33,9 +33,9 @@ public class CornerDetectionPipe List, List, CornerDetectionPipe.CornerDetectionPipeParameters> { - Comparator leftRightComparator = Comparator.comparingDouble(point -> point.x); - Comparator verticalComparator = Comparator.comparingDouble(point -> point.y); - MatOfPoint2f polyOutput = new MatOfPoint2f(); + final Comparator leftRightComparator = Comparator.comparingDouble(point -> point.x); + final Comparator verticalComparator = Comparator.comparingDouble(point -> point.y); + final MatOfPoint2f polyOutput = new MatOfPoint2f(); @Override protected List process(List targetList) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java index 53f5852e72..d91605a758 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java @@ -90,8 +90,8 @@ protected Void process(Pair> in) { } public static class Draw2dCrosshairParams { - public boolean showCrosshair = true; - public Color crosshairColor = Color.GREEN; + public final boolean showCrosshair = true; + public final Color crosshairColor = Color.GREEN; public final boolean shouldDraw; public final FrameStaticProperties frameStaticProperties; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java index 3365a5cf3e..56034f76e3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java @@ -34,7 +34,7 @@ public class Draw2dTargetsPipe extends MutatingPipe>, Draw2dTargetsPipe.Draw2dTargetsParams> { - MatOfPoint tempMat = new MatOfPoint(); + final MatOfPoint tempMat = new MatOfPoint(); private static final Logger logger = new Logger(Draw2dTargetsPipe.class, LogGroup.General); @Override @@ -217,22 +217,22 @@ private void dividePoint(Point p) { } public static class Draw2dTargetsParams { - public double kPixelsToText = 0.0025; - public double kPixelsToThickness = 0.008; - public double kPixelsToOffset = 0.04; - public double kPixelsToBoxThickness = 0.007; - public double kPixelsToCentroidRadius = 0.03; - public boolean showCentroid = true; + public final double kPixelsToText = 0.0025; + public final double kPixelsToThickness = 0.008; + public final double kPixelsToOffset = 0.04; + public final double kPixelsToBoxThickness = 0.007; + public final double kPixelsToCentroidRadius = 0.03; + public final boolean showCentroid = true; public boolean showRotatedBox = true; public boolean showShape = false; public boolean showMaximumBox = true; - public boolean showContourNumber = true; - public Color centroidColor = Color.GREEN; // Color.decode("#ff5ebf"); + public final boolean showContourNumber = true; + public final Color centroidColor = Color.GREEN; // Color.decode("#ff5ebf"); public Color rotatedBoxColor = Color.BLUE; - public Color maximumBoxColor = Color.RED; - public Color shapeOutlineColour = Color.MAGENTA; - public Color textColor = Color.GREEN; - public Color circleColor = Color.RED; + public final Color maximumBoxColor = Color.RED; + public final Color shapeOutlineColour = Color.MAGENTA; + public final Color textColor = Color.GREEN; + public final Color circleColor = Color.RED; public final boolean showMultipleTargets; public final boolean shouldDraw; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java index 99927ea0f1..b5c1499bfd 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java @@ -36,7 +36,7 @@ public class Draw3dTargetsPipe extends MutatingPipe>, Draw3dTargetsPipe.Draw3dContoursParams> { - Logger logger = new Logger(Draw3dTargetsPipe.class, LogGroup.VisionModule); + final Logger logger = new Logger(Draw3dTargetsPipe.class, LogGroup.VisionModule); @Override protected Void process(Pair> in) { @@ -283,12 +283,12 @@ private void dividePointList(List points) { } public static class Draw3dContoursParams { - public int radius = 2; - public Color color = Color.RED; + public final int radius = 2; + public final Color color = Color.RED; public final boolean shouldDraw; public boolean shouldDrawHull = true; - public boolean shouldDrawBox = true; + public final boolean shouldDrawBox = true; public final TargetModel targetModel; public final CameraCalibrationCoefficients cameraCalibrationCoefficients; public final FrameDivisor divisor; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java index 1e7616c44f..0f0121b7a3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java @@ -28,7 +28,7 @@ public class FilterContoursPipe extends CVPipe, List, FilterContoursPipe.FilterContoursParams> { - List m_filteredContours = new ArrayList<>(); + final List m_filteredContours = new ArrayList<>(); @Override protected List process(List in) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index 678566c707..4966314418 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -51,8 +51,8 @@ public class FindBoardCornersPipe private final MatOfPoint2f boardCorners = new MatOfPoint2f(); // Intermediate result mat's - Mat smallerInFrame = new Mat(); - MatOfPoint2f smallerBoardCorners = new MatOfPoint2f(); + final Mat smallerInFrame = new Mat(); + final MatOfPoint2f smallerBoardCorners = new MatOfPoint2f(); // SubCornerPix params private final Size zeroZone = new Size(-1, -1); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java index dfadfda53f..a05cca5738 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java @@ -57,16 +57,12 @@ private CVShape getShape(Contour in) { if (ContourShape.fromSides(corners) == null) { return new CVShape(in, ContourShape.Custom); } - switch (ContourShape.fromSides(corners)) { - case Circle: - return new CVShape(in, ContourShape.Circle); - case Triangle: - return new CVShape(in, ContourShape.Triangle); - case Quadrilateral: - return new CVShape(in, ContourShape.Quadrilateral); - } - - return new CVShape(in, ContourShape.Custom); + return switch (ContourShape.fromSides(corners)) { + case Circle -> new CVShape(in, ContourShape.Circle); + case Triangle -> new CVShape(in, ContourShape.Triangle); + case Quadrilateral -> new CVShape(in, ContourShape.Quadrilateral); + default -> new CVShape(in, ContourShape.Custom); + }; } private int getCorners(Contour contour) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java index 5b49faf641..cdfbf5adec 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java @@ -17,7 +17,6 @@ package org.photonvision.vision.pipe.impl; -import static com.jogamp.opengl.GL.*; import static com.jogamp.opengl.GL2ES2.*; import com.jogamp.opengl.*; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/RotateImagePipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/RotateImagePipe.java index 172eda5e01..30643e7932 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/RotateImagePipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/RotateImagePipe.java @@ -45,9 +45,9 @@ protected Void process(Mat in) { } public static class RotateImageParams { - public static RotateImageParams DEFAULT = new RotateImageParams(ImageRotationMode.DEG_0); + public static final RotateImageParams DEFAULT = new RotateImageParams(ImageRotationMode.DEG_0); - public ImageRotationMode rotation; + public final ImageRotationMode rotation; public RotateImageParams() { rotation = DEFAULT.rotation; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java index 411642c89b..74efdfc483 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java @@ -38,30 +38,30 @@ public AdvancedPipelineSettings() { public IntegerCouple hsvHue = new IntegerCouple(50, 180); public IntegerCouple hsvSaturation = new IntegerCouple(50, 255); public IntegerCouple hsvValue = new IntegerCouple(50, 255); - public boolean hueInverted = false; + public final boolean hueInverted = false; public boolean outputShouldDraw = true; public boolean outputShowMultipleTargets = false; - public DoubleCouple contourArea = new DoubleCouple(0.0, 100.0); - public DoubleCouple contourRatio = new DoubleCouple(0.0, 20.0); - public DoubleCouple contourFullness = new DoubleCouple(0.0, 100.0); - public int contourSpecklePercentage = 5; + public final DoubleCouple contourArea = new DoubleCouple(0.0, 100.0); + public final DoubleCouple contourRatio = new DoubleCouple(0.0, 20.0); + public final DoubleCouple contourFullness = new DoubleCouple(0.0, 100.0); + public final int contourSpecklePercentage = 5; // the order in which to sort contours to find the most desirable - public ContourSortMode contourSortMode = ContourSortMode.Largest; + public final ContourSortMode contourSortMode = ContourSortMode.Largest; // the edge (or not) of the target to consider the center point (Top, Bottom, Left, Right, // Center) - public TargetOffsetPointEdge contourTargetOffsetPointEdge = TargetOffsetPointEdge.Center; + public final TargetOffsetPointEdge contourTargetOffsetPointEdge = TargetOffsetPointEdge.Center; // orientation of the target in terms of aspect ratio - public TargetOrientation contourTargetOrientation = TargetOrientation.Landscape; + public final TargetOrientation contourTargetOrientation = TargetOrientation.Landscape; // the mode in which to offset target center point based on the camera being offset on the // robot // (None, Single Point, Dual Point) - public RobotOffsetPointMode offsetRobotOffsetMode = RobotOffsetPointMode.None; + public final RobotOffsetPointMode offsetRobotOffsetMode = RobotOffsetPointMode.None; // the point set by the user in Single Point Offset mode (maybe double too? idr) public Point offsetSinglePoint = new Point(); @@ -83,19 +83,18 @@ public AdvancedPipelineSettings() { public TargetModel targetModel = TargetModel.k2020HighGoalOuter; // Corner detection settings - public CornerDetectionPipe.DetectionStrategy cornerDetectionStrategy = + public final CornerDetectionPipe.DetectionStrategy cornerDetectionStrategy = CornerDetectionPipe.DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS; public boolean cornerDetectionUseConvexHulls = true; - public boolean cornerDetectionExactSideCount = false; - public int cornerDetectionSideCount = 4; + public final boolean cornerDetectionExactSideCount = false; + public final int cornerDetectionSideCount = 4; public double cornerDetectionAccuracyPercentage = 10; @Override public boolean equals(Object o) { if (this == o) return true; - if (!(o instanceof AdvancedPipelineSettings)) return false; + if (!(o instanceof AdvancedPipelineSettings that)) return false; if (!super.equals(o)) return false; - AdvancedPipelineSettings that = (AdvancedPipelineSettings) o; return outputShouldDraw == that.outputShouldDraw && outputShowMultipleTargets == that.outputShowMultipleTargets && contourSpecklePercentage == that.contourSpecklePercentage diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java index 5d2abe1a07..79b549c354 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java @@ -167,7 +167,7 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting AprilTagPoseEstimate tagPoseEstimate = null; // Do single-tag estimation when "always enabled" or if a tag was not used for multitag if (settings.doSingleTargetAlways - || !multiTagResult.fiducialIDsUsed.contains(Integer.valueOf(detection.getId()))) { + || !multiTagResult.fiducialIDsUsed.contains(detection.getId())) { var poseResult = singleTagPoseEstimatorPipe.run(detection); sumPipeNanosElapsed += poseResult.nanosElapsed; tagPoseEstimate = poseResult.output; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java index 31da770127..925af8b775 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java @@ -24,16 +24,16 @@ @JsonTypeName("AprilTagPipelineSettings") public class AprilTagPipelineSettings extends AdvancedPipelineSettings { public AprilTagFamily tagFamily = AprilTagFamily.kTag16h5; - public int decimate = 1; - public double blur = 0; + public final int decimate = 1; + public final double blur = 0; public int threads = 4; // Multiple threads seems to be better performance on most platforms - public boolean debug = false; - public boolean refineEdges = true; - public int numIterations = 40; - public int hammingDist = 0; - public int decisionMargin = 35; - public boolean doMultiTarget = false; - public boolean doSingleTargetAlways = false; + public final boolean debug = false; + public final boolean refineEdges = true; + public final int numIterations = 40; + public final int hammingDist = 0; + public final int decisionMargin = 35; + public final boolean doMultiTarget = false; + public final boolean doSingleTargetAlways = false; // 3d settings diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java index 2690034db4..ca087c8920 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java @@ -26,21 +26,21 @@ public class ArucoPipelineSettings extends AdvancedPipelineSettings { public AprilTagFamily tagFamily = AprilTagFamily.kTag16h5; - public IntegerCouple threshWinSizes = new IntegerCouple(11, 91); + public final IntegerCouple threshWinSizes = new IntegerCouple(11, 91); public int threshStepSize = 40; - public double threshConstant = 10; - public boolean debugThreshold = false; + public final double threshConstant = 10; + public final boolean debugThreshold = false; - public boolean useCornerRefinement = true; - public int refineNumIterations = 30; - public double refineMinErrorPx = 0.005; + public final boolean useCornerRefinement = true; + public final int refineNumIterations = 30; + public final double refineMinErrorPx = 0.005; - public boolean useAruco3 = false; - public double aruco3MinMarkerSideRatio = 0.02; - public int aruco3MinCanonicalImgSide = 32; + public final boolean useAruco3 = false; + public final double aruco3MinMarkerSideRatio = 0.02; + public final int aruco3MinCanonicalImgSide = 32; - public boolean doMultiTarget = false; - public boolean doSingleTargetAlways = false; + public final boolean doMultiTarget = false; + public final boolean doSingleTargetAlways = false; public ArucoPipelineSettings() { super(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java index f836e30999..884da4e044 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java @@ -37,12 +37,12 @@ public class CVPipelineSettings implements Cloneable { public int pipelineIndex = 0; public PipelineType pipelineType = PipelineType.DriverMode; - public ImageRotationMode inputImageRotationMode = ImageRotationMode.DEG_0; + public final ImageRotationMode inputImageRotationMode = ImageRotationMode.DEG_0; public String pipelineNickname = "New Pipeline"; public boolean cameraAutoExposure = false; // manual exposure only used if cameraAutoExposure is false public double cameraExposure = 20; - public int cameraBrightness = 50; + public final int cameraBrightness = 50; // Currently only used by a few cameras (notably the zero-copy Pi Camera driver) with the Gain // quirk public int cameraGain = 75; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java index 62db7bc9ee..77970e7cde 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java @@ -27,12 +27,12 @@ @JsonTypeName("ColoredShapePipelineSettings") public class ColoredShapePipelineSettings extends AdvancedPipelineSettings { public ContourShape contourShape = ContourShape.Triangle; - public DoubleCouple contourPerimeter = new DoubleCouple(0, Double.MAX_VALUE); + public final DoubleCouple contourPerimeter = new DoubleCouple(0, Double.MAX_VALUE); public double accuracyPercentage = 10.0; // Circle detection public int circleDetectThreshold = 5; - public IntegerCouple contourRadius = new IntegerCouple(0, 100); - public int minDist = 20; + public final IntegerCouple contourRadius = new IntegerCouple(0, 100); + public final int minDist = 20; public int maxCannyThresh = 90; public int circleAccuracy = 20; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipelineSettings.java index b06dcaddef..27db559617 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipelineSettings.java @@ -21,8 +21,8 @@ @JsonTypeName("ReflectivePipelineSettings") public class ReflectivePipelineSettings extends AdvancedPipelineSettings { - public double contourFilterRangeX = 2; - public double contourFilterRangeY = 2; + public final double contourFilterRangeX = 2; + public final double contourFilterRangeY = 2; public ReflectivePipelineSettings() { super(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/UICalibrationData.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/UICalibrationData.java index 287e271974..5f65fad8ec 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/UICalibrationData.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/UICalibrationData.java @@ -21,7 +21,7 @@ public class UICalibrationData { public final int videoModeIndex; - public int count; + public final int count; public final int minCount; public final boolean hasEnough; public final double squareSizeIn; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java index 4186fd91e5..bbc8577bd9 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java @@ -31,7 +31,7 @@ public class CVPipelineResult implements Releasable { public final double fps; public final List targets; public final Frame inputAndOutputFrame; - public MultiTargetPNPResult multiTagResult; + public final MultiTargetPNPResult multiTagResult; public CVPipelineResult( double processingNanos, double fps, List targets, Frame inputFrame) { diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java index e824ce89dc..318c60f7d5 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java @@ -50,8 +50,7 @@ public VisionModuleChangeSubscriber(VisionModule parentModule) { @Override public void onDataChangeEvent(DataChangeEvent event) { - if (event instanceof IncomingWebSocketEvent) { - var wsEvent = (IncomingWebSocketEvent) event; + if (event instanceof IncomingWebSocketEvent wsEvent) { // Camera index -1 means a "multicast event" (i.e. the event is received by all cameras) if (wsEvent.cameraIndex != null @@ -126,8 +125,7 @@ public void onDataChangeEvent(DataChangeEvent event) { parentModule.addCalibrationToConfig((CameraCalibrationCoefficients) newPropValue); return; case "robotOffsetPoint": - if (currentSettings instanceof AdvancedPipelineSettings) { - var curAdvSettings = (AdvancedPipelineSettings) currentSettings; + if (currentSettings instanceof AdvancedPipelineSettings curAdvSettings) { var offsetOperation = RobotOffsetPointOperation.fromIndex((int) newPropValue); var latestTarget = parentModule.lastPipelineResultBestTarget; diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java index 60acc0d391..6f086c6db6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java @@ -77,8 +77,7 @@ private void update() { var wantedProcessType = pipeline.getThresholdType(); frameSupplier.requestFrameThresholdType(wantedProcessType); var settings = pipeline.getSettings(); - if (settings instanceof AdvancedPipelineSettings) { - var advanced = (AdvancedPipelineSettings) settings; + if (settings instanceof AdvancedPipelineSettings advanced) { var hsvParams = new HSVPipe.HSVParams( advanced.hsvHue, advanced.hsvSaturation, advanced.hsvValue, advanced.hueInverted); diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java index 970b1a6ae7..ba10ec2002 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java @@ -22,6 +22,7 @@ import java.util.ArrayList; import java.util.Arrays; import java.util.Collection; +import java.util.HashSet; import java.util.List; import java.util.concurrent.CopyOnWriteArrayList; import java.util.function.Supplier; @@ -429,7 +430,7 @@ private List filterAllowedDevices(List allDevices) for (String p : otherDevice.otherPaths) { otherPaths.add(p.split("index")[0]); } - if (paths.containsAll(otherPaths)) { + if (new HashSet<>(paths).containsAll(otherPaths)) { if (otherDevice.dev >= device.dev) { badDevices.add(otherDevice); } else { diff --git a/photon-core/src/main/java/org/photonvision/vision/target/RobotOffsetPointOperation.java b/photon-core/src/main/java/org/photonvision/vision/target/RobotOffsetPointOperation.java index 0e69fe9d8f..fde166d34b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/RobotOffsetPointOperation.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/RobotOffsetPointOperation.java @@ -29,17 +29,12 @@ public enum RobotOffsetPointOperation { } public static RobotOffsetPointOperation fromIndex(int index) { - switch (index) { - case 0: - return ROPO_CLEAR; - case 1: - return ROPO_TAKESINGLE; - case 2: - return ROPO_TAKEFIRSTDUAL; - case 3: - return ROPO_TAKESECONDDUAL; - default: - return ROPO_CLEAR; - } + return switch (index) { + case 0 -> ROPO_CLEAR; + case 1 -> ROPO_TAKESINGLE; + case 2 -> ROPO_TAKEFIRSTDUAL; + case 3 -> ROPO_TAKESECONDDUAL; + default -> ROPO_CLEAR; + }; } } diff --git a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java index 7b23d3a600..b9ee35c988 100644 --- a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java @@ -38,8 +38,8 @@ public class TargetCalculationsTest { - private static Size imageSize = new Size(800, 600); - private static Point imageCenterPoint = + private static final Size imageSize = new Size(800, 600); + private static final Point imageCenterPoint = new Point(imageSize.width / 2.0 - 0.5, imageSize.height / 2.0 - 0.5); private static final double diagFOV = Math.toRadians(70.0); @@ -116,7 +116,7 @@ private static Stream testYawPitchCalcArgs() { Arguments.of(-45, -20)); } - private static double[] testCameraMatrix = {240, 0, 320, 0, 240, 320, 0, 0, 1}; + private static final double[] testCameraMatrix = {240, 0, 320, 0, 240, 320, 0, 0, 1}; @ParameterizedTest @MethodSource("testYawPitchCalcArgs") diff --git a/photon-server/src/main/java/org/photonvision/Main.java b/photon-server/src/main/java/org/photonvision/Main.java index f01e431d30..9fb01d5c63 100644 --- a/photon-server/src/main/java/org/photonvision/Main.java +++ b/photon-server/src/main/java/org/photonvision/Main.java @@ -106,7 +106,7 @@ private static boolean handleArgs(String[] args) throws ParseException { if (cmd.hasOption("path")) { Path p = Path.of(System.getProperty("PATH_PREFIX", "") + cmd.getOptionValue("path")); - logger.info("Loading from Path " + p.toAbsolutePath().toString()); + logger.info("Loading from Path " + p.toAbsolutePath()); testModeFolder = p; } } diff --git a/photon-server/src/main/java/org/photonvision/server/Server.java b/photon-server/src/main/java/org/photonvision/server/Server.java index c77d03fe7e..8f6a6f3d43 100644 --- a/photon-server/src/main/java/org/photonvision/server/Server.java +++ b/photon-server/src/main/java/org/photonvision/server/Server.java @@ -34,9 +34,7 @@ public static void start(int port) { javalinConfig.showJavalinBanner = false; javalinConfig.staticFiles.add("web"); javalinConfig.plugins.enableCors( - corsContainer -> { - corsContainer.add(CorsPluginConfig::anyHost); - }); + corsContainer -> corsContainer.add(CorsPluginConfig::anyHost)); javalinConfig.requestLogger.http( (ctx, ms) -> { diff --git a/photon-server/src/main/java/org/photonvision/server/UIInboundSubscriber.java b/photon-server/src/main/java/org/photonvision/server/UIInboundSubscriber.java index 5f1e125a4b..0b55ce7947 100644 --- a/photon-server/src/main/java/org/photonvision/server/UIInboundSubscriber.java +++ b/photon-server/src/main/java/org/photonvision/server/UIInboundSubscriber.java @@ -38,8 +38,7 @@ public UIInboundSubscriber() { @Override public void onDataChangeEvent(DataChangeEvent event) { - if (event instanceof IncomingWebSocketEvent) { - var incomingWSEvent = (IncomingWebSocketEvent) event; + if (event instanceof IncomingWebSocketEvent incomingWSEvent) { if (incomingWSEvent.propertyName.equals("userConnected") || incomingWSEvent.propertyName.equals("sendFullSettings")) { // Send full settings diff --git a/photon-server/src/main/java/org/photonvision/server/UIOutboundSubscriber.java b/photon-server/src/main/java/org/photonvision/server/UIOutboundSubscriber.java index e502b5eec9..7ebe346f3f 100644 --- a/photon-server/src/main/java/org/photonvision/server/UIOutboundSubscriber.java +++ b/photon-server/src/main/java/org/photonvision/server/UIOutboundSubscriber.java @@ -33,7 +33,7 @@ * DO NOT use logging in this class. If you do, the logs will recurse forever! */ class UIOutboundSubscriber extends DataChangeSubscriber { - Logger logger = new Logger(UIOutboundSubscriber.class, LogGroup.WebServer); + final Logger logger = new Logger(UIOutboundSubscriber.class, LogGroup.WebServer); private final DataSocketHandler socketHandler; @@ -44,11 +44,9 @@ public UIOutboundSubscriber(DataSocketHandler socketHandler) { @Override public void onDataChangeEvent(DataChangeEvent event) { - if (event instanceof OutgoingUIEvent) { - var thisEvent = (OutgoingUIEvent) event; + if (event instanceof OutgoingUIEvent thisEvent) { try { - if (event.data instanceof HashMap) { - var data = (HashMap) event.data; + if (event.data instanceof HashMap data) { socketHandler.broadcastMessage(data, thisEvent.originContext); } else { socketHandler.broadcastMessage(event.data, thisEvent.originContext);