diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java b/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java index 013b19a73..1c485d6af 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java @@ -70,16 +70,12 @@ public class ConfigManager { if (INSTANCE == null) { Path rootFolder = PathManager.getInstance().getRootFolder(); switch (m_saveStrat) { - case SQL: - INSTANCE = new ConfigManager(rootFolder, new SqlConfigProvider(rootFolder)); - break; - case LEGACY: - INSTANCE = new ConfigManager(rootFolder, new LegacyConfigProvider(rootFolder)); - break; - case ATOMIC_ZIP: - // not yet done, fall through - default: - break; + case SQL -> INSTANCE = new ConfigManager(rootFolder, new SqlConfigProvider(rootFolder)); + case LEGACY -> + INSTANCE = new ConfigManager(rootFolder, new LegacyConfigProvider(rootFolder)); + case ATOMIC_ZIP -> { + // TODO: Not done yet + } } } return INSTANCE; diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/NeuralNetworkModelManager.java b/photon-core/src/main/java/org/photonvision/common/configuration/NeuralNetworkModelManager.java index f6ba9a18f..0418d5902 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/NeuralNetworkModelManager.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/NeuralNetworkModelManager.java @@ -205,13 +205,11 @@ public class NeuralNetworkModelManager { try { switch (backend.get()) { - case RKNN: + case RKNN -> { models.get(backend.get()).add(new RknnModel(model, labels)); logger.info( "Loaded model " + model.getName() + " for backend " + backend.get().toString()); - break; - default: - break; + } } } catch (IllegalArgumentException e) { logger.error("Failed to load model " + model.getName(), e); 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 994cda74d..658a617b1 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 @@ -599,9 +599,9 @@ public class SqlConfigProvider extends ConfigProvider { result.getString(Columns.CAM_PIPELINE_JSONS), dummyList.getClass()); List loadedSettings = new ArrayList<>(); - for (var str : pipelineSettings) { - if (str instanceof String) { - loadedSettings.add(JacksonUtils.deserialize((String) str, CVPipelineSettings.class)); + for (var setting : pipelineSettings) { + if (setting instanceof String str) { + loadedSettings.add(JacksonUtils.deserialize(str, CVPipelineSettings.class)); } } 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 d6c2bd310..f495a9d51 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,22 +242,7 @@ public class PigpioSocket { 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; - } - logger.error("Failed to send wave: " + error); + logger.error("Failed to send wave: " + getMessageForError(waveformId)); } } 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 7d1d5273b..52fb48a97 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 @@ public class VisionLED { 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 -> newLedMode = VisionLEDMode.kDefault; + case 0 -> newLedMode = VisionLEDMode.kOff; + case 1 -> newLedMode = VisionLEDMode.kOn; + case 2 -> newLedMode = 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); @@ -164,18 +156,10 @@ public class VisionLED { if (fromNT) { switch (newLedMode) { - case kDefault: - setStateImpl(pipelineModeSupplier.getAsBoolean()); - break; - case kOff: - setStateImpl(false); - break; - case kOn: - setStateImpl(true); - break; - case kBlink: - blinkImpl(85, -1); - break; + case kDefault -> setStateImpl(pipelineModeSupplier.getAsBoolean()); + case kOff -> setStateImpl(false); + case kOn -> setStateImpl(true); + case kBlink -> blinkImpl(85, -1); } currentLedMode = newLedMode; logger.info( @@ -183,18 +167,10 @@ public class VisionLED { } else { if (currentLedMode == VisionLEDMode.kDefault) { switch (newLedMode) { - case kDefault: - setStateImpl(pipelineModeSupplier.getAsBoolean()); - break; - case kOff: - setStateImpl(false); - break; - case kOn: - setStateImpl(true); - break; - case kBlink: - blinkImpl(85, -1); - break; + case kDefault -> setStateImpl(pipelineModeSupplier.getAsBoolean()); + case kOff -> setStateImpl(false); + case kOn -> setStateImpl(true); + case kBlink -> blinkImpl(85, -1); } } logger.info("Changing LED internal state to " + newLedMode.toString()); 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 9a6047c79..b6b43323a 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,16 +51,9 @@ public abstract class NumberCouple { @Override public boolean equals(Object obj) { - if (!(obj instanceof NumberCouple)) { - return false; - } - - var couple = (NumberCouple) obj; - if (!couple.first.equals(first)) { - return false; - } - - return couple.second.equals(second); + return obj instanceof NumberCouple couple + && couple.first.equals(first) + && couple.second.equals(second); } @JsonIgnore 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 7a168245b..189a8107b 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 @@ -135,20 +135,14 @@ public class MJPGFrameConsumer implements AutoCloseable { } private static String pixelFormatToString(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"; + case kUYVY, kUnknown, kY16, kBGRA -> "Unknown"; + }; } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java b/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java index 1cf3e0d36..260d98428 100644 --- a/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java +++ b/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java @@ -158,18 +158,19 @@ public class Contour implements Releasable { double massX = (x0A + x0B) / 2; double massY = (y0A + y0B) / 2; switch (intersectionDirection) { - case Up: + case None -> {} + case Up -> { if (intersectionY < massY) isIntersecting = true; - break; - case Down: + } + case Down -> { if (intersectionY > massY) isIntersecting = true; - break; - case Left: + } + case Left -> { if (intersectionX < massX) isIntersecting = true; - break; - case Right: + } + case Right -> { if (intersectionX > massX) isIntersecting = true; - break; + } } intersectMatA.release(); intersectMatB.release(); diff --git a/photon-core/src/main/java/org/photonvision/vision/opencv/ContourShape.java b/photon-core/src/main/java/org/photonvision/vision/opencv/ContourShape.java index 4eac4d847..cf25e2c01 100644 --- a/photon-core/src/main/java/org/photonvision/vision/opencv/ContourShape.java +++ b/photon-core/src/main/java/org/photonvision/vision/opencv/ContourShape.java @@ -17,9 +17,6 @@ package org.photonvision.vision.opencv; -import java.util.EnumSet; -import java.util.HashMap; - public enum ContourShape { Circle(0), Custom(-1), @@ -32,15 +29,12 @@ public enum ContourShape { this.sides = sides; } - private static final HashMap sidesToValueMap = new HashMap<>(); - - static { - for (var value : EnumSet.allOf(ContourShape.class)) { - sidesToValueMap.put(value.sides, value); - } - } - public static ContourShape fromSides(int sides) { - return sidesToValueMap.get(sides); + return switch (sides) { + case 0 -> Circle; + case 3 -> Triangle; + case 4 -> Quadrilateral; + default -> Custom; + }; } } 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 cdb160982..fb22c6615 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 @@ -48,13 +48,14 @@ public class Draw2dCrosshairPipe double scale = params.frameStaticProperties.imageWidth / (double) params.divisor.value / 32.0; switch (params.robotOffsetPointMode) { - case Single: + case None -> {} + case Single -> { if (params.singleOffsetPoint.x != 0 && params.singleOffsetPoint.y != 0) { x = params.singleOffsetPoint.x; y = params.singleOffsetPoint.y; } - break; - case Dual: + } + case Dual -> { if (!in.getRight().isEmpty()) { var target = in.getRight().get(0); if (target != null) { @@ -65,7 +66,7 @@ public class Draw2dCrosshairPipe y = offsetCrosshair.y; } } - break; + } } x /= (double) params.divisor.value; 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 dfadfda53..4cfc15259 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 @@ -50,23 +50,7 @@ public class FindPolygonPipe private CVShape getShape(Contour in) { int corners = getCorners(in); - - /*The contourShape enum has predefined shapes for Circles, Triangles, and Quads - meaning any shape not fitting in those predefined shapes must be a custom shape. - */ - 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 new CVShape(in, ContourShape.fromSides(corners)); } private int getCorners(Contour contour) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java index ecbe326fe..9a51f6960 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java @@ -85,19 +85,29 @@ public class ArucoPipeline extends CVPipeline { + // 2024 tag, 6.5in + tagWidth = Units.inchesToMeters(6.5); + tagModel = TargetModel.kAprilTag36h11; + yield Objdetect.DICT_APRILTAG_36h11; + } + case kTag25h9 -> Objdetect.DICT_APRILTAG_25h9; + // TODO: explicitly drop support for these + case kTag16h5, + kTagCircle21h7, + kTagCircle49h12, + kTagCustom48h11, + kTagStandard41h12, + kTagStandard52h13 -> { + // 2024 tag, 6.5in + tagWidth = Units.inchesToMeters(6.5); + tagModel = TargetModel.kAprilTag36h11; + yield Objdetect.DICT_APRILTAG_36h11; + } + }; int threshMinSize = Math.max(3, settings.threshWinSizes.getFirst()); settings.threshWinSizes.setFirst(threshMinSize); diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java index 8da870dd7..85adb4cbd 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java @@ -241,41 +241,38 @@ public class PipelineManager { * recreation after changing pipeline type */ private void recreateUserPipeline() { - // Cleanup potential old native resources before swapping over from a user - // pipeline + // Cleanup potential old native resources before swapping over from a user pipeline if (currentUserPipeline != null && !(currentPipelineIndex < 0)) { currentUserPipeline.release(); } var desiredPipelineSettings = userPipelineSettings.get(currentPipelineIndex); switch (desiredPipelineSettings.pipelineType) { - case Reflective: + case Reflective -> { logger.debug("Creating Reflective pipeline"); currentUserPipeline = new ReflectivePipeline((ReflectivePipelineSettings) desiredPipelineSettings); - break; - case ColoredShape: + } + case ColoredShape -> { logger.debug("Creating ColoredShape pipeline"); currentUserPipeline = new ColoredShapePipeline((ColoredShapePipelineSettings) desiredPipelineSettings); - break; - case AprilTag: + } + case AprilTag -> { logger.debug("Creating AprilTag pipeline"); currentUserPipeline = new AprilTagPipeline((AprilTagPipelineSettings) desiredPipelineSettings); - break; - - case Aruco: + } + case Aruco -> { logger.debug("Creating Aruco Pipeline"); currentUserPipeline = new ArucoPipeline((ArucoPipelineSettings) desiredPipelineSettings); - break; - case ObjectDetection: + } + case ObjectDetection -> { logger.debug("Creating ObjectDetection Pipeline"); currentUserPipeline = new ObjectDetectionPipeline((ObjectDetectionPipelineSettings) desiredPipelineSettings); - default: - // Can be calib3d or drivermode, both of which are special cases - break; + } + case Calib3d, DriverMode -> {} } } @@ -342,44 +339,40 @@ public class PipelineManager { } private CVPipelineSettings createSettingsForType(PipelineType type, String nickname) { - CVPipelineSettings newSettings; switch (type) { - case Reflective: - { - var added = new ReflectivePipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case ColoredShape: - { - var added = new ColoredShapePipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case AprilTag: - { - var added = new AprilTagPipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case Aruco: - { - var added = new ArucoPipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case ObjectDetection: - { - var added = new ObjectDetectionPipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - default: - { - logger.error("Got invalid pipeline type: " + type); - return null; - } + case Reflective -> { + var added = new ReflectivePipelineSettings(); + added.pipelineNickname = nickname; + return added; + } + case ColoredShape -> { + var added = new ColoredShapePipelineSettings(); + added.pipelineNickname = nickname; + return added; + } + case AprilTag -> { + var added = new AprilTagPipelineSettings(); + added.pipelineNickname = nickname; + return added; + } + case Aruco -> { + var added = new ArucoPipelineSettings(); + added.pipelineNickname = nickname; + return added; + } + case ObjectDetection -> { + var added = new ObjectDetectionPipelineSettings(); + added.pipelineNickname = nickname; + return added; + } + case Calib3d, DriverMode -> { + logger.error("Got invalid pipeline type: " + type); + return null; + } } + + // This can never happen, this is here to satisfy the compiler. + throw new IllegalStateException("Got impossible pipeline type: " + type); } private void addPipelineInternal(CVPipelineSettings settings) { diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java index cdb494300..36b2e0eea 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java @@ -587,11 +587,9 @@ public class VisionModule { // Pipelines like DriverMode and Calibrate3dPipeline have null output frames if (result.inputAndOutputFrame != null - && (pipelineManager.getCurrentPipelineSettings() instanceof AdvancedPipelineSettings)) { - streamRunnable.updateData( - result.inputAndOutputFrame, - (AdvancedPipelineSettings) pipelineManager.getCurrentPipelineSettings(), - result.targets); + && (pipelineManager.getCurrentPipelineSettings() + instanceof AdvancedPipelineSettings settings)) { + streamRunnable.updateData(result.inputAndOutputFrame, settings, result.targets); // The streamRunnable manages releasing in this case } else { consumeResults(result.inputAndOutputFrame, result.targets); @@ -615,9 +613,9 @@ public class VisionModule { } public void setTargetModel(TargetModel targetModel) { - var settings = pipelineManager.getCurrentPipeline().getSettings(); - if (settings instanceof ReflectivePipelineSettings) { - ((ReflectivePipelineSettings) settings).targetModel = targetModel; + var pipelineSettings = pipelineManager.getCurrentPipeline().getSettings(); + if (pipelineSettings instanceof ReflectivePipelineSettings settings) { + settings.targetModel = targetModel; saveAndBroadcastAll(); } else { logger.error("Cannot set target model of non-reflective pipe! Ignoring..."); 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 3737f611a..0b6f1c58c 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 @@ -55,11 +55,8 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { @Override public void onDataChangeEvent(DataChangeEvent event) { - if (event instanceof IncomingWebSocketEvent) { - var wsEvent = (IncomingWebSocketEvent) event; - - // Camera index -1 means a "multicast event" (i.e. the event is received by all - // cameras) + 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 && (wsEvent.cameraIndex == parentModule.moduleIndex || wsEvent.cameraIndex == -1)) { logger.trace("Got PSC event - propName: " + wsEvent.propertyName); @@ -93,120 +90,32 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { var currentSettings = change.getCurrentSettings(); var originContext = change.getOriginContext(); switch (propName) { - case "pipelineName": // rename current pipeline - logger.info("Changing nick to " + newPropValue); - parentModule.pipelineManager.getCurrentPipelineSettings().pipelineNickname = - (String) newPropValue; - parentModule.saveAndBroadcastAll(); - continue; - case "newPipelineInfo": // add new pipeline - var typeName = (Pair) newPropValue; - var type = typeName.getRight(); - var name = typeName.getLeft(); - - logger.info("Adding a " + type + " pipeline with name " + name); - - var addedSettings = parentModule.pipelineManager.addPipeline(type); - addedSettings.pipelineNickname = name; - parentModule.saveAndBroadcastAll(); - continue; - case "deleteCurrPipeline": - var indexToDelete = parentModule.pipelineManager.getRequestedIndex(); - logger.info("Deleting current pipe at index " + indexToDelete); - int newIndex = parentModule.pipelineManager.removePipeline(indexToDelete); - parentModule.setPipeline(newIndex); - parentModule.saveAndBroadcastAll(); - continue; - case "changePipeline": // change active pipeline - var index = (Integer) newPropValue; - if (index == parentModule.pipelineManager.getRequestedIndex()) { - logger.debug("Skipping pipeline change, index " + index + " already active"); - continue; + case "pipelineName" -> newPipelineNickname((String) newPropValue); + case "newPipelineInfo" -> newPipelineInfo((Pair) newPropValue); + case "deleteCurrPipeline" -> deleteCurrPipeline(); + case "changePipeline" -> changePipeline((Integer) newPropValue); + case "startCalibration" -> startCalibration((Map) newPropValue); + case "saveInputSnapshot" -> parentModule.saveInputSnapshot(); + case "saveOutputSnapshot" -> parentModule.saveOutputSnapshot(); + case "takeCalSnapshot" -> parentModule.takeCalibrationSnapshot(); + case "duplicatePipeline" -> duplicatePipeline((Integer) newPropValue); + case "calibrationUploaded" -> { + if (newPropValue instanceof CameraCalibrationCoefficients newCal) { + parentModule.addCalibrationToConfig(newCal); + } else { + logger.warn("Received invalid calibration data"); } - parentModule.setPipeline(index); - parentModule.saveAndBroadcastAll(); - continue; - case "startCalibration": - try { - var data = - JacksonUtils.deserialize( - (Map) newPropValue, UICalibrationData.class); - parentModule.startCalibration(data); - parentModule.saveAndBroadcastAll(); - } catch (Exception e) { - logger.error("Error deserailizing start-cal request", e); + } + case "robotOffsetPoint" -> { + if (currentSettings instanceof AdvancedPipelineSettings curAdvSettings) { + robotOffsetPoint(curAdvSettings, (Integer) newPropValue); } - continue; - case "saveInputSnapshot": - parentModule.saveInputSnapshot(); - continue; - case "saveOutputSnapshot": - parentModule.saveOutputSnapshot(); - continue; - case "takeCalSnapshot": - parentModule.takeCalibrationSnapshot(); - continue; - case "duplicatePipeline": - int idx = parentModule.pipelineManager.duplicatePipeline((Integer) newPropValue); - parentModule.setPipeline(idx); - parentModule.saveAndBroadcastAll(); - continue; - case "calibrationUploaded": - if (newPropValue instanceof CameraCalibrationCoefficients) - parentModule.addCalibrationToConfig((CameraCalibrationCoefficients) newPropValue); - continue; - case "robotOffsetPoint": - if (currentSettings instanceof AdvancedPipelineSettings) { - var curAdvSettings = (AdvancedPipelineSettings) currentSettings; - var offsetOperation = RobotOffsetPointOperation.fromIndex((int) newPropValue); - var latestTarget = parentModule.lastPipelineResultBestTarget; - - if (latestTarget != null) { - var newPoint = latestTarget.getTargetOffsetPoint(); - - switch (curAdvSettings.offsetRobotOffsetMode) { - case Single: - if (offsetOperation == RobotOffsetPointOperation.ROPO_CLEAR) { - curAdvSettings.offsetSinglePoint = new Point(); - } else if (offsetOperation == RobotOffsetPointOperation.ROPO_TAKESINGLE) { - curAdvSettings.offsetSinglePoint = newPoint; - } - break; - case Dual: - if (offsetOperation == RobotOffsetPointOperation.ROPO_CLEAR) { - curAdvSettings.offsetDualPointA = new Point(); - curAdvSettings.offsetDualPointAArea = 0; - curAdvSettings.offsetDualPointB = new Point(); - curAdvSettings.offsetDualPointBArea = 0; - } else { - // update point and area - switch (offsetOperation) { - case ROPO_TAKEFIRSTDUAL: - curAdvSettings.offsetDualPointA = newPoint; - curAdvSettings.offsetDualPointAArea = latestTarget.getArea(); - break; - case ROPO_TAKESECONDDUAL: - curAdvSettings.offsetDualPointB = newPoint; - curAdvSettings.offsetDualPointBArea = latestTarget.getArea(); - break; - default: - break; - } - } - break; - default: - break; - } - } - } - continue; - case "changePipelineType": + } + case "changePipelineType" -> { parentModule.changePipelineType((Integer) newPropValue); parentModule.saveAndBroadcastAll(); - continue; - case "isDriverMode": - parentModule.setDriverMode((Boolean) newPropValue); - continue; + } + case "isDriverMode" -> parentModule.setDriverMode((Boolean) newPropValue); } // special case for camera settables @@ -249,6 +158,104 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { } } + public void newPipelineNickname(String newNickname) { + logger.info("Changing pipeline nickname to " + newNickname); + parentModule.pipelineManager.getCurrentPipelineSettings().pipelineNickname = newNickname; + parentModule.saveAndBroadcastAll(); + } + + public void newPipelineInfo(Pair typeName) { + var type = typeName.getRight(); + var name = typeName.getLeft(); + + logger.info("Adding a " + type + " pipeline with name " + name); + + var addedSettings = parentModule.pipelineManager.addPipeline(type); + addedSettings.pipelineNickname = name; + parentModule.saveAndBroadcastAll(); + } + + public void deleteCurrPipeline() { + var indexToDelete = parentModule.pipelineManager.getRequestedIndex(); + logger.info("Deleting current pipe at index " + indexToDelete); + int newIndex = parentModule.pipelineManager.removePipeline(indexToDelete); + parentModule.setPipeline(newIndex); + parentModule.saveAndBroadcastAll(); + } + + public void changePipeline(int index) { + if (index == parentModule.pipelineManager.getRequestedIndex()) { + logger.debug("Skipping pipeline change, index " + index + " already active"); + return; + } + parentModule.setPipeline(index); + parentModule.saveAndBroadcastAll(); + } + + public void startCalibration(Map data) { + try { + var deserialized = JacksonUtils.deserialize(data, UICalibrationData.class); + parentModule.startCalibration(deserialized); + parentModule.saveAndBroadcastAll(); + } catch (Exception e) { + logger.error("Error deserailizing start-calibration request", e); + } + } + + public void duplicatePipeline(int index) { + var newIndex = parentModule.pipelineManager.duplicatePipeline(index); + parentModule.setPipeline(newIndex); + parentModule.saveAndBroadcastAll(); + } + + public void robotOffsetPoint(AdvancedPipelineSettings curAdvSettings, int offsetIndex) { + RobotOffsetPointOperation offsetOperation = RobotOffsetPointOperation.fromIndex(offsetIndex); + + var latestTarget = parentModule.lastPipelineResultBestTarget; + if (latestTarget == null) { + return; + } + + var newPoint = latestTarget.getTargetOffsetPoint(); + switch (curAdvSettings.offsetRobotOffsetMode) { + case Single -> { + switch (offsetOperation) { + case CLEAR -> curAdvSettings.offsetSinglePoint = new Point(); + case TAKE_SINGLE -> curAdvSettings.offsetSinglePoint = newPoint; + case TAKE_FIRST_DUAL, TAKE_SECOND_DUAL -> { + logger.warn("Dual point operation in single point mode"); + } + } + } + case Dual -> { + switch (offsetOperation) { + case CLEAR -> { + curAdvSettings.offsetDualPointA = new Point(); + curAdvSettings.offsetDualPointAArea = 0; + curAdvSettings.offsetDualPointB = new Point(); + curAdvSettings.offsetDualPointBArea = 0; + } + case TAKE_FIRST_DUAL -> { + // update point and area + curAdvSettings.offsetDualPointA = newPoint; + curAdvSettings.offsetDualPointAArea = latestTarget.getArea(); + } + case TAKE_SECOND_DUAL -> { + // update point and area + curAdvSettings.offsetDualPointB = newPoint; + curAdvSettings.offsetDualPointBArea = latestTarget.getArea(); + } + case TAKE_SINGLE -> { + logger.warn("Single point operation in dual point mode"); + } + } + } + case None -> { + logger.warn("Robot offset point operation requested, but no offset mode set"); + } + } + } + /** * Sets the value of a property in the given object using reflection. This method should not be * used generally and is only known to be correct in the context of `onDataChangeEvent`. @@ -281,8 +288,8 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { } else if (propType.equals(Integer.TYPE)) { propField.setInt(currentSettings, (Integer) newPropValue); } else if (propType.equals(Boolean.TYPE)) { - if (newPropValue instanceof Integer) { - propField.setBoolean(currentSettings, (Integer) newPropValue != 0); + if (newPropValue instanceof Integer intValue) { + propField.setBoolean(currentSettings, intValue != 0); } else { propField.setBoolean(currentSettings, (Boolean) newPropValue); } 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 a1299bd54..f7c7df7fe 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 @@ -84,8 +84,7 @@ public class VisionRunner { 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/target/RobotOffsetPointOperation.java b/photon-core/src/main/java/org/photonvision/vision/target/RobotOffsetPointOperation.java index 0e69fe9d8..d5aefd432 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 @@ -17,10 +17,10 @@ package org.photonvision.vision.target; public enum RobotOffsetPointOperation { - ROPO_CLEAR(0), - ROPO_TAKESINGLE(1), - ROPO_TAKEFIRSTDUAL(2), - ROPO_TAKESECONDDUAL(3); + CLEAR(0), + TAKE_SINGLE(1), + TAKE_FIRST_DUAL(2), + TAKE_SECOND_DUAL(3); public final int index; @@ -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 -> CLEAR; + case 1 -> TAKE_SINGLE; + case 2 -> TAKE_FIRST_DUAL; + case 3 -> TAKE_SECOND_DUAL; + default -> CLEAR; + }; } } diff --git a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java index 97b927136..76109878a 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java @@ -298,17 +298,12 @@ public class PhotonCamera implements AutoCloseable { */ public VisionLEDMode getLEDMode() { int value = (int) ledModeState.get(-1); - switch (value) { - case 0: - return VisionLEDMode.kOff; - case 1: - return VisionLEDMode.kOn; - case 2: - return VisionLEDMode.kBlink; - case -1: - default: - return VisionLEDMode.kDefault; - } + return switch (value) { + case 0 -> VisionLEDMode.kOff; + case 1 -> VisionLEDMode.kOn; + case 2 -> VisionLEDMode.kBlink; + default -> VisionLEDMode.kDefault; + }; } /** diff --git a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java index 77c998c08..7b518351b 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java @@ -345,46 +345,35 @@ public class PhotonPoseEstimator { PhotonPipelineResult cameraResult, Optional> cameraMatrix, Optional> distCoeffs, - PoseStrategy strat) { - Optional estimatedPose = Optional.empty(); - switch (strat) { - case LOWEST_AMBIGUITY: - estimatedPose = lowestAmbiguityStrategy(cameraResult); - break; - case CLOSEST_TO_CAMERA_HEIGHT: - estimatedPose = closestToCameraHeightStrategy(cameraResult); - break; - case CLOSEST_TO_REFERENCE_POSE: - estimatedPose = closestToReferencePoseStrategy(cameraResult, referencePose); - break; - case CLOSEST_TO_LAST_POSE: - setReferencePose(lastPose); - estimatedPose = closestToReferencePoseStrategy(cameraResult, referencePose); - break; - case AVERAGE_BEST_TARGETS: - estimatedPose = averageBestTargetsStrategy(cameraResult); - break; - case MULTI_TAG_PNP_ON_RIO: - if (cameraMatrix.isEmpty()) { - DriverStation.reportWarning( - "Camera matrix is empty for multi-tag-on-rio", - Thread.currentThread().getStackTrace()); - } else if (distCoeffs.isEmpty()) { - DriverStation.reportWarning( - "Camera matrix is empty for multi-tag-on-rio", - Thread.currentThread().getStackTrace()); - } else { - estimatedPose = multiTagOnRioStrategy(cameraResult, cameraMatrix, distCoeffs); - } - break; - case MULTI_TAG_PNP_ON_COPROCESSOR: - estimatedPose = multiTagOnCoprocStrategy(cameraResult); - break; - default: - DriverStation.reportError( - "[PhotonPoseEstimator] Unknown Position Estimation Strategy!", false); - return Optional.empty(); - } + PoseStrategy strategy) { + Optional estimatedPose = + switch (strategy) { + case LOWEST_AMBIGUITY -> lowestAmbiguityStrategy(cameraResult); + case CLOSEST_TO_CAMERA_HEIGHT -> closestToCameraHeightStrategy(cameraResult); + case CLOSEST_TO_REFERENCE_POSE -> + closestToReferencePoseStrategy(cameraResult, referencePose); + case CLOSEST_TO_LAST_POSE -> { + setReferencePose(lastPose); + yield closestToReferencePoseStrategy(cameraResult, referencePose); + } + case AVERAGE_BEST_TARGETS -> averageBestTargetsStrategy(cameraResult); + case MULTI_TAG_PNP_ON_RIO -> { + if (cameraMatrix.isEmpty()) { + DriverStation.reportWarning( + "Camera matrix is empty for multi-tag-on-rio", + Thread.currentThread().getStackTrace()); + yield Optional.empty(); + } else if (distCoeffs.isEmpty()) { + DriverStation.reportWarning( + "Camera matrix is empty for multi-tag-on-rio", + Thread.currentThread().getStackTrace()); + yield Optional.empty(); + } else { + yield multiTagOnRioStrategy(cameraResult, cameraMatrix, distCoeffs); + } + } + case MULTI_TAG_PNP_ON_COPROCESSOR -> multiTagOnCoprocStrategy(cameraResult); + }; if (estimatedPose.isPresent()) { lastPose = estimatedPose.get().estimatedPose; diff --git a/photon-lib/src/main/java/org/photonvision/simulation/VisionTargetSim.java b/photon-lib/src/main/java/org/photonvision/simulation/VisionTargetSim.java index 88d19756c..95739131e 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VisionTargetSim.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VisionTargetSim.java @@ -84,11 +84,9 @@ public class VisionTargetSim { @Override public boolean equals(Object obj) { - if (this == obj) return true; - if (obj instanceof VisionTargetSim) { - var o = (VisionTargetSim) obj; - return pose.equals(o.pose) && model.equals(o.model); - } - return false; + return this == obj + && obj instanceof VisionTargetSim o + && pose.equals(o.pose) + && model.equals(o.model); } } diff --git a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java index cb5bbc277..be5887edf 100644 --- a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java @@ -99,10 +99,9 @@ public class DataSocketHandler { objectMapper.readValue(context.data(), new TypeReference<>() {}); // Special case the current camera index - var camIndexValue = deserializedData.get("cameraIndex"); Integer cameraIndex = null; - if (camIndexValue instanceof Integer) { - cameraIndex = (Integer) camIndexValue; + if (deserializedData.get("cameraIndex") instanceof Integer camIndexValue) { + cameraIndex = camIndexValue; deserializedData.remove("cameraIndex"); } @@ -128,216 +127,182 @@ public class DataSocketHandler { } switch (socketMessageType) { - case SMT_DRIVERMODE: - { - // TODO: what is this event? - var data = (Boolean) entryValue; - var dmIsDriverEvent = - new IncomingWebSocketEvent( - DataChangeDestination.DCD_ACTIVEMODULE, - "isDriverMode", - data, - cameraIndex, - context); + case SMT_DRIVERMODE -> { + // TODO: what is this event? + var data = (Boolean) entryValue; + var dmIsDriverEvent = + new IncomingWebSocketEvent( + DataChangeDestination.DCD_ACTIVEMODULE, + "isDriverMode", + data, + cameraIndex, + context); - dcService.publishEvents(dmIsDriverEvent); - break; - } - case SMT_CHANGECAMERANAME: - { - var ccnEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "cameraNickname", - (String) entryValue, - cameraIndex, - context); - dcService.publishEvent(ccnEvent); - break; - } - case SMT_CHANGEPIPELINENAME: - { - var cpnEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "pipelineName", - (String) entryValue, - cameraIndex, - context); - dcService.publishEvent(cpnEvent); - break; - } - case SMT_ADDNEWPIPELINE: - { - // HashMap data = (HashMap) entryValue; - // var type = (PipelineType) - // data.get("pipelineType"); - // var name = (String) data.get("pipelineName"); - var arr = (ArrayList) entryValue; - var name = (String) arr.get(0); - var type = PipelineType.values()[(Integer) arr.get(1) + 2]; + dcService.publishEvents(dmIsDriverEvent); + } + case SMT_CHANGECAMERANAME -> { + var ccnEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "cameraNickname", + (String) entryValue, + cameraIndex, + context); + dcService.publishEvent(ccnEvent); + } + case SMT_CHANGEPIPELINENAME -> { + var cpnEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "pipelineName", + (String) entryValue, + cameraIndex, + context); + dcService.publishEvent(cpnEvent); + } + case SMT_ADDNEWPIPELINE -> { + // HashMap data = (HashMap) entryValue; + // var type = (PipelineType) data.get("pipelineType"); + // var name = (String) data.get("pipelineName"); + var arr = (ArrayList) entryValue; + var name = (String) arr.get(0); + var type = PipelineType.values()[(Integer) arr.get(1) + 2]; - var newPipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "newPipelineInfo", - Pair.of(name, type), - cameraIndex, - context); - dcService.publishEvent(newPipelineEvent); - break; - } - case SMT_CHANGEBRIGHTNESS: - { - HardwareManager.getInstance() - .setBrightnessPercent(Integer.parseInt(entryValue.toString())); - break; - } - case SMT_DUPLICATEPIPELINE: - { - var pipeIndex = (Integer) entryValue; + var newPipelineEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "newPipelineInfo", + Pair.of(name, type), + cameraIndex, + context); + dcService.publishEvent(newPipelineEvent); + } + case SMT_CHANGEBRIGHTNESS -> { + HardwareManager.getInstance() + .setBrightnessPercent(Integer.parseInt(entryValue.toString())); + } + case SMT_DUPLICATEPIPELINE -> { + var pipeIndex = (Integer) entryValue; - logger.info("Duplicating pipe@index" + pipeIndex + " for camera " + cameraIndex); + logger.info("Duplicating pipe@index" + pipeIndex + " for camera " + cameraIndex); - var newPipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "duplicatePipeline", - pipeIndex, - cameraIndex, - context); - dcService.publishEvent(newPipelineEvent); - break; - } - case SMT_DELETECURRENTPIPELINE: - { - var deleteCurrentPipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "deleteCurrPipeline", - 0, - cameraIndex, - context); - dcService.publishEvent(deleteCurrentPipelineEvent); - break; - } - case SMT_ROBOTOFFSETPOINT: - { - var robotOffsetPointEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "robotOffsetPoint", - (Integer) entryValue, - cameraIndex, - null); - dcService.publishEvent(robotOffsetPointEvent); - break; - } - case SMT_CURRENTCAMERA: - { - var changeCurrentCameraEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_OTHER, "changeUICamera", (Integer) entryValue); - dcService.publishEvent(changeCurrentCameraEvent); - break; - } - case SMT_CURRENTPIPELINE: - { - var changePipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "changePipeline", - (Integer) entryValue, - cameraIndex, - context); - dcService.publishEvent(changePipelineEvent); - break; - } - case SMT_STARTPNPCALIBRATION: - { - var changePipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "startCalibration", - (Map) entryValue, - cameraIndex, - context); - dcService.publishEvent(changePipelineEvent); - break; - } - case SMT_SAVEINPUTSNAPSHOT: - { - var takeInputSnapshotEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "saveInputSnapshot", - 0, - cameraIndex, - context); - dcService.publishEvent(takeInputSnapshotEvent); - break; - } - case SMT_SAVEOUTPUTSNAPSHOT: - { - var takeOutputSnapshotEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "saveOutputSnapshot", - 0, - cameraIndex, - context); - dcService.publishEvent(takeOutputSnapshotEvent); - break; - } - case SMT_TAKECALIBRATIONSNAPSHOT: - { - var takeCalSnapshotEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "takeCalSnapshot", - 0, - cameraIndex, - context); - dcService.publishEvent(takeCalSnapshotEvent); - break; - } - case SMT_PIPELINESETTINGCHANGE: - { - HashMap data = (HashMap) entryValue; + var newPipelineEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "duplicatePipeline", + pipeIndex, + cameraIndex, + context); + dcService.publishEvent(newPipelineEvent); + } + case SMT_DELETECURRENTPIPELINE -> { + var deleteCurrentPipelineEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "deleteCurrPipeline", + 0, + cameraIndex, + context); + dcService.publishEvent(deleteCurrentPipelineEvent); + } + case SMT_ROBOTOFFSETPOINT -> { + var robotOffsetPointEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "robotOffsetPoint", + (Integer) entryValue, + cameraIndex, + null); + dcService.publishEvent(robotOffsetPointEvent); + } + case SMT_CURRENTCAMERA -> { + var changeCurrentCameraEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_OTHER, "changeUICamera", (Integer) entryValue); + dcService.publishEvent(changeCurrentCameraEvent); + } + case SMT_CURRENTPIPELINE -> { + var changePipelineEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "changePipeline", + (Integer) entryValue, + cameraIndex, + context); + dcService.publishEvent(changePipelineEvent); + } + case SMT_STARTPNPCALIBRATION -> { + var changePipelineEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "startCalibration", + (Map) entryValue, + cameraIndex, + context); + dcService.publishEvent(changePipelineEvent); + } + case SMT_SAVEINPUTSNAPSHOT -> { + var takeInputSnapshotEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "saveInputSnapshot", + 0, + cameraIndex, + context); + dcService.publishEvent(takeInputSnapshotEvent); + } + case SMT_SAVEOUTPUTSNAPSHOT -> { + var takeOutputSnapshotEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "saveOutputSnapshot", + 0, + cameraIndex, + context); + dcService.publishEvent(takeOutputSnapshotEvent); + } + case SMT_TAKECALIBRATIONSNAPSHOT -> { + var takeCalSnapshotEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "takeCalSnapshot", + 0, + cameraIndex, + context); + dcService.publishEvent(takeCalSnapshotEvent); + } + case SMT_PIPELINESETTINGCHANGE -> { + HashMap data = (HashMap) entryValue; - if (data.size() >= 2) { - var cameraIndex2 = (int) data.get("cameraIndex"); - for (var dataEntry : data.entrySet()) { - if (dataEntry.getKey().equals("cameraIndex")) { - continue; - } - var pipelineSettingChangeEvent = - new IncomingWebSocketEvent( - DataChangeDestination.DCD_ACTIVEPIPELINESETTINGS, - dataEntry.getKey(), - dataEntry.getValue(), - cameraIndex2, - context); - dcService.publishEvent(pipelineSettingChangeEvent); + if (data.size() >= 2) { + var cameraIndex2 = (int) data.get("cameraIndex"); + for (var dataEntry : data.entrySet()) { + if (dataEntry.getKey().equals("cameraIndex")) { + continue; } - } else { - logger.warn("Unknown message for PSC: " + data.keySet().iterator().next()); + var pipelineSettingChangeEvent = + new IncomingWebSocketEvent( + DataChangeDestination.DCD_ACTIVEPIPELINESETTINGS, + dataEntry.getKey(), + dataEntry.getValue(), + cameraIndex2, + context); + dcService.publishEvent(pipelineSettingChangeEvent); } - break; - } - case SMT_CHANGEPIPELINETYPE: - { - var changePipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "changePipelineType", - (Integer) entryValue, - cameraIndex, - context); - dcService.publishEvent(changePipelineEvent); - break; + } else { + logger.warn("Unknown message for PSC: " + data.keySet().iterator().next()); } + } + case SMT_CHANGEPIPELINETYPE -> { + var changePipelineEvent = + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "changePipelineType", + (Integer) entryValue, + cameraIndex, + context); + dcService.publishEvent(changePipelineEvent); + } } } catch (Exception e) { logger.error("Failed to parse message!", e); 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 e7f101d15..6d467fdd9 100644 --- a/photon-server/src/main/java/org/photonvision/server/UIInboundSubscriber.java +++ b/photon-server/src/main/java/org/photonvision/server/UIInboundSubscriber.java @@ -39,8 +39,7 @@ public class UIInboundSubscriber extends DataChangeSubscriber { @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 e502b5eec..0961f1032 100644 --- a/photon-server/src/main/java/org/photonvision/server/UIOutboundSubscriber.java +++ b/photon-server/src/main/java/org/photonvision/server/UIOutboundSubscriber.java @@ -44,11 +44,9 @@ class UIOutboundSubscriber extends DataChangeSubscriber { @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); diff --git a/photon-targeting/src/main/java/org/photonvision/common/hardware/VisionLEDMode.java b/photon-targeting/src/main/java/org/photonvision/common/hardware/VisionLEDMode.java index af95fc2cb..d81a2d8c5 100644 --- a/photon-targeting/src/main/java/org/photonvision/common/hardware/VisionLEDMode.java +++ b/photon-targeting/src/main/java/org/photonvision/common/hardware/VisionLEDMode.java @@ -31,16 +31,11 @@ public enum VisionLEDMode { @Override public String toString() { - switch (this) { - case kDefault: - return "Default"; - case kOff: - return "Off"; - case kOn: - return "On"; - case kBlink: - return "Blink"; - } - return ""; + return switch (this) { + case kDefault -> "Default"; + case kOff -> "Off"; + case kOn -> "On"; + case kBlink -> "Blink"; + }; } } diff --git a/photon-targeting/src/main/java/org/photonvision/estimation/TargetModel.java b/photon-targeting/src/main/java/org/photonvision/estimation/TargetModel.java index aa77a1e5d..b06d5092d 100644 --- a/photon-targeting/src/main/java/org/photonvision/estimation/TargetModel.java +++ b/photon-targeting/src/main/java/org/photonvision/estimation/TargetModel.java @@ -175,11 +175,10 @@ public class TargetModel { @Override public boolean equals(Object obj) { - if (this == obj) return true; - if (obj instanceof TargetModel) { - var o = (TargetModel) obj; - return vertices.equals(o.vertices) && isPlanar == o.isPlanar && isSpherical == o.isSpherical; - } - return false; + return this == obj + && obj instanceof TargetModel o + && vertices.equals(o.vertices) + && isPlanar == o.isPlanar + && isSpherical == o.isSpherical; } } diff --git a/photonlib-java-examples/aimandrange/build.gradle b/photonlib-java-examples/aimandrange/build.gradle index 2e9934c89..9cf6b077c 100644 --- a/photonlib-java-examples/aimandrange/build.gradle +++ b/photonlib-java-examples/aimandrange/build.gradle @@ -3,8 +3,8 @@ plugins { id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-2" } -sourceCompatibility = JavaVersion.VERSION_11 -targetCompatibility = JavaVersion.VERSION_11 +sourceCompatibility = JavaVersion.VERSION_17 +targetCompatibility = JavaVersion.VERSION_17 def ROBOT_MAIN_CLASS = "frc.robot.Main" diff --git a/photonlib-java-examples/aimattarget/build.gradle b/photonlib-java-examples/aimattarget/build.gradle index a8782720b..87b6f168c 100644 --- a/photonlib-java-examples/aimattarget/build.gradle +++ b/photonlib-java-examples/aimattarget/build.gradle @@ -3,8 +3,8 @@ plugins { id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-2" } -sourceCompatibility = JavaVersion.VERSION_11 -targetCompatibility = JavaVersion.VERSION_11 +sourceCompatibility = JavaVersion.VERSION_17 +targetCompatibility = JavaVersion.VERSION_17 def ROBOT_MAIN_CLASS = "frc.robot.Main" diff --git a/photonlib-java-examples/poseest/build.gradle b/photonlib-java-examples/poseest/build.gradle index 69dbf3efa..6b6e18443 100644 --- a/photonlib-java-examples/poseest/build.gradle +++ b/photonlib-java-examples/poseest/build.gradle @@ -3,8 +3,8 @@ plugins { id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-2" } -sourceCompatibility = JavaVersion.VERSION_11 -targetCompatibility = JavaVersion.VERSION_11 +sourceCompatibility = JavaVersion.VERSION_17 +targetCompatibility = JavaVersion.VERSION_17 def ROBOT_MAIN_CLASS = "frc.robot.Main" diff --git a/shared/javacommon.gradle b/shared/javacommon.gradle index 0c8605b57..aa6d13f8f 100644 --- a/shared/javacommon.gradle +++ b/shared/javacommon.gradle @@ -4,8 +4,8 @@ apply plugin: 'jacoco' apply plugin: 'com.google.protobuf' java { - sourceCompatibility = JavaVersion.VERSION_11 - targetCompatibility = JavaVersion.VERSION_11 + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 } def baseArtifactId = nativeName