From 38ee450117e50870f30d3aae4d94e550f23e695c Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Thu, 27 Mar 2025 08:17:07 -0400 Subject: [PATCH] Use toList instead of collect(Collectors.toList()) when the list is definitely never modified --- .../configuration/LegacyConfigProvider.java | 7 ++--- .../configuration/SqlConfigProvider.java | 2 +- .../websocket/UIPhotonConfiguration.java | 3 +-- .../common/networking/NetworkUtils.java | 26 +++++++++++++------ .../photonvision/common/util/TestUtils.java | 5 +--- .../UICameraCalibrationCoefficients.java | 5 ++-- .../USBCameras/GenericUSBCameraSettables.java | 7 ++--- .../vision/pipe/impl/Calibrate3dPipe.java | 15 +++++------ .../vision/pipe/impl/FindContoursPipe.java | 3 +-- .../vision/pipeline/Calibrate3dPipeline.java | 5 +--- .../vision/pipeline/ColoredShapePipeline.java | 3 +-- .../pipeline/ObjectDetectionPipeline.java | 5 +--- .../result/CalibrationPipelineResult.java | 3 +-- .../vision/processes/VisionModuleManager.java | 5 +--- .../pipeline/CalibrationRotationPipeTest.java | 9 +++---- .../processes/VisionModuleManagerTest.java | 8 ++---- .../java/org/photonvision/PhotonCamera.java | 3 +-- .../simulation/VisionSystemSim.java | 6 +---- 18 files changed, 47 insertions(+), 73 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java index 6c2dca8cc..f82e6f914 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java @@ -32,7 +32,6 @@ import java.time.LocalDateTime; import java.time.format.DateTimeFormatter; import java.time.temporal.TemporalAccessor; import java.util.*; -import java.util.stream.Collectors; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.common.util.file.FileUtils; @@ -280,9 +279,7 @@ class LegacyConfigProvider extends ConfigProvider { HashMap loadedConfigurations = new HashMap<>(); try { var subdirectories = - Files.list(camerasFolder.toPath()) - .filter(f -> f.toFile().isDirectory()) - .collect(Collectors.toList()); + Files.list(camerasFolder.toPath()).filter(f -> f.toFile().isDirectory()).toList(); for (var subdir : subdirectories) { var cameraConfigPath = Path.of(subdir.toString(), "config.json"); @@ -348,7 +345,7 @@ class LegacyConfigProvider extends ConfigProvider { return null; }) .filter(Objects::nonNull) - .collect(Collectors.toList()) + .toList() : Collections.emptyList(); loadedConfig.driveModeSettings = driverMode; 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 d2808bb3c..bae7c4ced 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 @@ -398,7 +398,7 @@ public class SqlConfigProvider extends ConfigProvider { } }) .filter(Objects::nonNull) - .collect(Collectors.toList()); + .toList(); statement.setString(4, JacksonUtils.serializeToString(settings)); statement.executeUpdate(); diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java index 50ec04576..4d5758bf7 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java @@ -18,7 +18,6 @@ package org.photonvision.common.dataflow.websocket; import java.util.List; -import java.util.stream.Collectors; import org.photonvision.PhotonVersion; import org.photonvision.common.configuration.NeuralNetworkModelManager; import org.photonvision.common.configuration.PhotonConfiguration; @@ -64,6 +63,6 @@ public class UIPhotonConfiguration { c.getApriltagFieldLayout()), VisionSourceManager.getInstance().getVisionModules().stream() .map(VisionModule::toUICameraConfig) - .collect(Collectors.toList())); + .toList()); } } diff --git a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java index f34d91f9a..fa24c4e66 100644 --- a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java @@ -23,7 +23,6 @@ import java.util.ArrayList; import java.util.List; import java.util.regex.Matcher; import java.util.regex.Pattern; -import java.util.stream.Collectors; import org.photonvision.common.hardware.Platform; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; @@ -108,24 +107,35 @@ public class NetworkUtils { return ret; } + /** + * Returns an immutable list of active network interfaces. + * + * @return The list. + */ public static List getAllActiveInterfaces() { // Seems like if an interface exists but isn't actually connected, the connection name will be // an empty string. Check here and only return connections with non-empty names - return getAllInterfaces().stream() - .filter(it -> !it.connName.trim().isEmpty()) - .collect(Collectors.toList()); + return getAllInterfaces().stream().filter(it -> !it.connName.trim().isEmpty()).toList(); } + /** + * Returns an immutable list of all wired network interfaces. + * + * @return The list. + */ public static List getAllWiredInterfaces() { return getAllInterfaces().stream() .filter(it -> it.nmType.equals(NMType.NMTYPE_ETHERNET)) - .collect(Collectors.toList()); + .toList(); } + /** + * Returns an immutable list of all wired and active network interfaces. + * + * @return The list. + */ public static List getAllActiveWiredInterfaces() { - return getAllWiredInterfaces().stream() - .filter(it -> !it.connName.isBlank()) - .collect(Collectors.toList()); + return getAllWiredInterfaces().stream().filter(it -> !it.connName.isBlank()).toList(); } public static NMDeviceInfo getNMinfoForConnName(String connName) { 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 bf189ff29..44e7e33ce 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 @@ -24,7 +24,6 @@ import java.awt.HeadlessException; import java.io.File; import java.io.IOException; import java.nio.file.Path; -import java.util.stream.Collectors; import org.opencv.core.Mat; import org.opencv.highgui.HighGui; import org.photonvision.jni.WpilibLoader; @@ -386,9 +385,7 @@ public class TestUtils { printTestResults(pipelineResult); System.out.println( "Found targets at " - + pipelineResult.targets.stream() - .map(TrackedTarget::getBestCameraToTarget3d) - .collect(Collectors.toList())); + + pipelineResult.targets.stream().map(TrackedTarget::getBestCameraToTarget3d).toList()); } public static Path getTestMode2023ImagePath() { diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java b/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java index 14cbfa51e..c02d48d15 100644 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java +++ b/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java @@ -18,11 +18,12 @@ package org.photonvision.vision.calibration; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Size; public class UICameraCalibrationCoefficients extends CameraCalibrationCoefficients { public int numSnapshots; + + /** Immutable list of mean errors. */ public List meanErrors; public UICameraCalibrationCoefficients( @@ -54,6 +55,6 @@ public class UICameraCalibrationCoefficients extends CameraCalibrationCoefficien .mapToDouble(it -> Math.sqrt(it.x * it.x + it.y * it.y)) .average() .orElse(0)) - .collect(Collectors.toList()); + .toList(); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java index 417dfde24..a14218fa6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java @@ -25,11 +25,9 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.util.PixelFormat; import java.util.ArrayList; import java.util.Arrays; -import java.util.Collections; import java.util.HashMap; import java.util.List; import java.util.Optional; -import java.util.stream.Collectors; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.processes.VisionSourceSettables; @@ -301,9 +299,8 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { var sortedList = videoModesList.stream() .distinct() // remove redundant video mode entries - .sorted(((a, b) -> (b.width + b.height) - (a.width + a.height))) - .collect(Collectors.toList()); - Collections.reverse(sortedList); + .sorted(((a, b) -> (a.width + a.height) - (b.width + b.height))) + .toList(); for (VideoMode videoMode : sortedList) { videoModes.put(sortedList.indexOf(videoMode), videoMode); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java index 428a64362..bfa96c5a3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java @@ -89,7 +89,7 @@ public class Calibrate3dPipe && it.imagePoints != null && it.objectPoints != null && it.size != null) - .collect(Collectors.toList()); + .toList(); CameraCalibrationCoefficients ret; var start = System.nanoTime(); @@ -134,11 +134,9 @@ public class Calibrate3dPipe double fxGuess, double fyGuess, Path imageSavePath) { - List objPointsIn = - in.stream().map(it -> it.objectPoints).collect(Collectors.toList()); - List imgPointsIn = - in.stream().map(it -> it.imagePoints).collect(Collectors.toList()); - List levelsArr = in.stream().map(it -> it.levels).collect(Collectors.toList()); + List objPointsIn = in.stream().map(it -> it.objectPoints).toList(); + List imgPointsIn = in.stream().map(it -> it.imagePoints).toList(); + List levelsArr = in.stream().map(it -> it.levels).toList(); if (objPointsIn.size() != imgPointsIn.size() || objPointsIn.size() != levelsArr.size()) { logger.error("objpts.size != imgpts.size"); @@ -223,10 +221,9 @@ public class Calibrate3dPipe double fyGuess, Path imageSavePath) { List corner_locations = - in.stream().map(it -> it.imagePoints).map(MatOfPoint2f::new).collect(Collectors.toList()); + in.stream().map(it -> it.imagePoints).map(MatOfPoint2f::new).toList(); - List levels = - in.stream().map(it -> it.levels).map(MatOfFloat::new).collect(Collectors.toList()); + List levels = in.stream().map(it -> it.levels).map(MatOfFloat::new).toList(); int imageWidth = (int) in.get(0).size.width; int imageHeight = (int) in.get(0).size.height; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java index d5564d63f..3181a637b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java @@ -19,7 +19,6 @@ package org.photonvision.vision.pipe.impl; import java.util.ArrayList; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Mat; import org.opencv.core.MatOfPoint; import org.opencv.imgproc.Imgproc; @@ -40,7 +39,7 @@ public class FindContoursPipe Imgproc.findContours( in, m_foundContours, new Mat(), Imgproc.RETR_EXTERNAL, Imgproc.CHAIN_APPROX_TC89_KCOS); - return m_foundContours.stream().map(Contour::new).collect(Collectors.toList()); + return m_foundContours.stream().map(Contour::new).toList(); } public static class FindContoursParams {} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java index d951bdaba..399869df1 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java @@ -22,7 +22,6 @@ import edu.wpi.first.math.util.Units; import java.nio.file.Path; import java.util.ArrayList; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Mat; import org.opencv.core.Point; import org.photonvision.common.dataflow.DataChangeService; @@ -166,9 +165,7 @@ public class Calibrate3dPipeline } List> getCornersList() { - return foundCornersList.stream() - .map(it -> it.imagePoints.toList()) - .collect(Collectors.toList()); + return foundCornersList.stream().map(it -> it.imagePoints.toList()).toList(); } public boolean hasEnough() { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java index 9a66708b4..fd1753f1a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java @@ -20,7 +20,6 @@ package org.photonvision.vision.pipeline; import edu.wpi.first.math.Pair; import java.util.Arrays; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Point; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; @@ -199,7 +198,7 @@ public class ColoredShapePipeline sortContoursPipe.run( filterShapeResult.output.stream() .map(shape -> new PotentialTarget(shape.getContour(), shape)) - .collect(Collectors.toList())); + .toList()); sumPipeNanosElapsed += sortContoursResult.nanosElapsed; CVPipeResult> collect2dTargetsResult = diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java index c0e9fa424..640c66759 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java @@ -19,7 +19,6 @@ package org.photonvision.vision.pipeline; import java.util.List; import java.util.Optional; -import java.util.stream.Collectors; import org.photonvision.common.configuration.NeuralNetworkModelManager; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; @@ -127,9 +126,7 @@ public class ObjectDetectionPipeline CVPipeResult> sortContoursResult = sortContoursPipe.run( - filterContoursResult.output.stream() - .map(shape -> new PotentialTarget(shape)) - .collect(Collectors.toList())); + filterContoursResult.output.stream().map(shape -> new PotentialTarget(shape)).toList()); sumPipeNanosElapsed += sortContoursResult.nanosElapsed; CVPipeResult> collect2dTargetsResult = diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java index a06bd8443..acf895c50 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java @@ -18,14 +18,13 @@ package org.photonvision.vision.pipeline.result; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Point; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.target.TrackedTarget; public class CalibrationPipelineResult extends CVPipelineResult { private static List cornersToTarget(List> corners) { - return corners.stream().map(TrackedTarget::new).collect(Collectors.toList()); + return corners.stream().map(TrackedTarget::new).toList(); } public CalibrationPipelineResult( diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java index 35c727eba..7eb3c8621 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java @@ -18,7 +18,6 @@ package org.photonvision.vision.processes; import java.util.*; -import java.util.stream.Collectors; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; @@ -67,9 +66,7 @@ public class VisionModuleManager { // Big list, which should contain every vision source (currently loaded plus the new ones being // added) List bigList = - this.getModules().stream() - .map(it -> it.getCameraConfiguration().streamIndex) - .collect(Collectors.toList()); + this.getModules().stream().map(it -> it.getCameraConfiguration().streamIndex).toList(); int idx = 0; while (bigList.contains(idx)) { diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java index 8e9f52c2b..1d7b9faa4 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java @@ -23,7 +23,6 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import java.io.IOException; import java.util.Arrays; import java.util.List; -import java.util.stream.Collectors; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; @@ -151,13 +150,13 @@ public class CalibrationRotationPipeTest { var rotatedDistortedPoints = distortedOriginalPoints.stream() .map(it -> rot.rotatePoint(it, frameProps.imageWidth, frameProps.imageHeight)) - .collect(Collectors.toList()); + .toList(); // Now let's instead rotate then distort var rotatedOriginalPoints = Arrays.stream(originalPoints) .map(it -> rot.rotatePoint(it, frameProps.imageWidth, frameProps.imageHeight)) - .collect(Collectors.toList()); + .toList(); var distortedRotatedPoints = OpenCVHelp.distortPoints( @@ -310,9 +309,7 @@ public class CalibrationRotationPipeTest { // rotate and try again var rotAngle = ImageRotationMode.DEG_90_CCW; var rotatedDistortedPoints = - distortedCorners.stream() - .map(it -> rotAngle.rotatePoint(it, 1280, 720)) - .collect(Collectors.toList()); + distortedCorners.stream().map(it -> rotAngle.rotatePoint(it, 1280, 720)).toList(); pipe.setParams( new SolvePNPPipeParams( coeffs.rotateCoefficients(rotAngle), TargetModel.kAprilTag6p5in_36h11)); diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java index 9a9195796..32d8ec762 100644 --- a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java @@ -25,7 +25,6 @@ import java.io.IOException; import java.util.Arrays; import java.util.HashMap; import java.util.List; -import java.util.stream.Collectors; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; @@ -233,15 +232,12 @@ public class VisionModuleManagerTest { var modules = List.of(testSource, testSource2, testSource3, usbSimulation, usbSimulation2).stream() .map(vmm::addSource) - .collect(Collectors.toList()); + .toList(); System.out.println( Arrays.toString( modules.stream().map(it -> it.getCameraConfiguration().streamIndex).toArray())); - var idxs = - modules.stream() - .map(it -> it.getCameraConfiguration().streamIndex) - .collect(Collectors.toList()); + var idxs = modules.stream().map(it -> it.getCameraConfiguration().streamIndex).toList(); assertTrue(usbSimulation.equals(usbSimulation)); assertTrue(!usbSimulation.equals(usbSimulation2)); diff --git a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java index 00b04b753..198c38732 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java @@ -50,7 +50,6 @@ import java.util.ArrayList; import java.util.Arrays; import java.util.List; import java.util.Optional; -import java.util.stream.Collectors; import org.opencv.core.Core; import org.photonvision.common.hardware.VisionLEDMode; import org.photonvision.common.networktables.PacketSubscriber; @@ -594,6 +593,6 @@ public class PhotonCamera implements AutoCloseable { it -> { return rootPhotonTable.getSubTable(it).getEntry("rawBytes").exists(); }) - .collect(Collectors.toList()); + .toList(); } } diff --git a/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java b/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java index b61b93946..7aa7ff1c2 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java @@ -41,7 +41,6 @@ import java.util.List; import java.util.Map; import java.util.Optional; import java.util.Set; -import java.util.stream.Collectors; import org.photonvision.PhotonCamera; import org.photonvision.estimation.TargetModel; @@ -357,10 +356,7 @@ public class VisionSystemSim { entry -> dbgField .getObject(entry.getKey()) - .setPoses( - entry.getValue().stream() - .map(t -> t.getPose().toPose2d()) - .collect(Collectors.toList()))); + .setPoses(entry.getValue().stream().map(t -> t.getPose().toPose2d()).toList())); if (robotPoseMeters == null) return;