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 7c2308f935..6feadcab3b 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,6 +32,7 @@ import java.time.format.DateTimeFormatter; import java.time.temporal.TemporalAccessor; import java.util.*; +import java.util.stream.Stream; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.common.util.file.FileUtils; @@ -282,9 +283,8 @@ public boolean saveToDisk() { private HashMap loadCameraConfigs() { HashMap loadedConfigurations = new HashMap<>(); - try { - var subdirectories = - Files.list(camerasFolder.toPath()).filter(f -> f.toFile().isDirectory()).toList(); + try (Stream files = Files.list(camerasFolder.toPath())) { + var subdirectories = files.filter(f -> f.toFile().isDirectory()).toList(); for (var subdir : subdirectories) { var cameraConfigPath = Path.of(subdir.toString(), "config.json"); @@ -325,9 +325,11 @@ private HashMap loadCameraConfigs() { // Load pipelines by mapping the files within the pipelines subdir // to their deserialized equivalents var pipelineSubdirectory = Path.of(subdir.toString(), "pipelines"); - List settings = - pipelineSubdirectory.toFile().exists() - ? Files.list(pipelineSubdirectory) + List settings = Collections.emptyList(); + if (pipelineSubdirectory.toFile().exists()) { + try (Stream subdirectoryFiles = Files.list(pipelineSubdirectory)) { + settings = + subdirectoryFiles .filter(p -> p.toFile().isFile()) .map( p -> { @@ -350,8 +352,9 @@ private HashMap loadCameraConfigs() { return null; }) .filter(Objects::nonNull) - .toList() - : Collections.emptyList(); + .toList(); + } + } loadedConfig.driveModeSettings = driverMode; loadedConfig.addPipelineSettings(settings); 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 fed56d3373..d1063ded47 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 @@ -33,6 +33,7 @@ import java.util.Optional; import java.util.jar.JarEntry; import java.util.jar.JarFile; +import java.util.stream.Stream; import org.photonvision.common.configuration.NeuralNetworkPropertyManager.ModelProperties; import org.photonvision.common.hardware.Platform; import org.photonvision.common.logging.LogGroup; @@ -365,8 +366,8 @@ public void discoverModels() { models = new HashMap<>(); - try { - Files.walk(modelsDirectory.toPath()) + try (Stream files = Files.walk(modelsDirectory.toPath())) { + files .filter(Files::isRegularFile) .filter( path -> @@ -469,8 +470,8 @@ public boolean clearModels() { File modelsDirectory = ConfigManager.getInstance().getModelsDirectory(); if (modelsDirectory.exists()) { - try { - Files.walk(modelsDirectory.toPath()) + try (Stream files = Files.walk(modelsDirectory.toPath())) { + files .sorted((a, b) -> b.compareTo(a)) .forEach( path -> { diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java index dec8d7e9be..3fd8802f44 100644 --- a/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java +++ b/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java @@ -21,16 +21,12 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import edu.wpi.first.cscore.UsbCameraInfo; -import java.io.File; -import java.io.IOException; -import java.nio.file.Files; import java.nio.file.Path; -import java.util.Comparator; import java.util.List; -import org.junit.jupiter.api.AfterAll; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Order; import org.junit.jupiter.api.Test; +import org.junit.jupiter.api.io.TempDir; import org.photonvision.common.util.TestUtils; import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.camera.PVCameraInfo; @@ -39,22 +35,11 @@ import org.photonvision.vision.pipeline.ReflectivePipelineSettings; public class SQLConfigTest { - private static Path tmpDir; + @TempDir private static Path tmpDir; @BeforeAll public static void init() { TestUtils.loadLibraries(); - try { - tmpDir = Files.createTempDirectory("SQLConfigTest"); - } catch (IOException e) { - System.out.println("Couldn't create temporary directory, using current directory"); - tmpDir = Path.of("jdbc_test", "temp"); - } - } - - @AfterAll - public static void cleanUp() throws IOException { - Files.walk(tmpDir).sorted(Comparator.reverseOrder()).map(Path::toFile).forEach(File::delete); } @Test diff --git a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java index 038d1f89eb..ceaabe4ec0 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java @@ -100,6 +100,14 @@ public static Point[] getImageCorners(Size size) { /** * Gets the 10x10 (grayscale) image of a specific 36h11 AprilTag. * + *

WARNING: This creates a {@link RawFrame} instance but does not close it, which would result + * in a resource leak if the {@link Mat} is garbage-collected. Unfortunately, closing the {@code + * RawFrame} inside this function would delete the underlying data that backs the {@code + * ByteBuffer} that is passed to the {@code Mat} constructor (see comments on PR 2023 for details). + * Luckily, this method is private and is (as of Aug 2025) only used to populate the {@link + * #kTag36h11Images} static map at static-initialization time. + * * @param id The fiducial id of the desired tag */ private static Mat get36h11TagImage(int id) { 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 7aa7ff1c28..2f8ff2ef6c 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java @@ -122,6 +122,7 @@ public void clearCameras() { * @return If the camera was present and removed */ public boolean removeCamera(PhotonCameraSim cameraSim) { + @SuppressWarnings("resource") boolean success = camSimMap.remove(cameraSim.getCamera().getName()) != null; camTrfMap.remove(cameraSim); return success; diff --git a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java index 8ca6b1a67d..d2080a6f5a 100644 --- a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java +++ b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java @@ -117,31 +117,31 @@ public void testTimeSyncServerWithPhotonCamera() throws InterruptedException, IO inst.stopClient(); inst.startServer(); - var camera = new PhotonCamera(inst, "Arducam_OV2311_USB_Camera"); - PhotonCamera.setVersionCheckEnabled(false); - - for (int i = 0; i < 5; i++) { - Thread.sleep(500); - - var res = camera.getLatestResult(); - var captureTime = res.getTimestampSeconds(); - var now = Timer.getFPGATimestamp(); - - // expectTrue(captureTime < now); - - System.out.println( - "sequence " - + res.metadata.sequenceID - + " image capture " - + captureTime - + " received at " - + res.getTimestampSeconds() - + " now: " - + NetworkTablesJNI.now() / 1e6 - + " time since last pong: " - + res.metadata.timeSinceLastPong / 1e6); + try (PhotonCamera camera = new PhotonCamera(inst, "Arducam_OV2311_USB_Camera")) { + PhotonCamera.setVersionCheckEnabled(false); + + for (int i = 0; i < 5; i++) { + Thread.sleep(500); + + var res = camera.getLatestResult(); + var captureTime = res.getTimestampSeconds(); + var now = Timer.getFPGATimestamp(); + + // expectTrue(captureTime < now); + + System.out.println( + "sequence " + + res.metadata.sequenceID + + " image capture " + + captureTime + + " received at " + + res.getTimestampSeconds() + + " now: " + + NetworkTablesJNI.now() / 1e6 + + " time since last pong: " + + res.metadata.timeSinceLastPong / 1e6); + } } - HAL.shutdown(); } @@ -335,62 +335,62 @@ public void testAlerts() throws InterruptedException { Thread.sleep(20); } - // GIVEN a simulated camera - var sim = new PhotonCameraSim(camera); - // AND a result with a timeSinceLastPong in the past - PhotonPipelineResult noPongResult = - new PhotonPipelineResult( - new PhotonPipelineMetadata( - 1, 2, 3, 10 * 1000000 // 10 seconds -> us since last pong - ), - List.of(), - Optional.empty()); + // GIVEN a simulated camera AND a result with a timeSinceLastPong in the past + try (PhotonCameraSim sim = new PhotonCameraSim(camera)) { + PhotonPipelineResult noPongResult = + new PhotonPipelineResult( + new PhotonPipelineMetadata( + 1, 2, 3, 10 * 1000000 // 10 seconds -> us since last pong + ), + List.of(), + Optional.empty()); + + // Loop to hit cases past first iteration + for (int i = 0; i < 10; i++) { + // AND a PhotonCamera with a "new" result + sim.submitProcessedFrame(noPongResult); + + // WHEN we update the camera + camera.getAllUnreadResults(); + + // AND we tick SmartDashboard + SmartDashboard.updateValues(); + + // THEN the camera isn't disconnected + assertTrue( + Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0])) + .noneMatch(it -> it.equals(disconnectedCameraString))); + // AND the alert string looks like a timesync warning + assertTrue( + Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0])) + .filter(it -> it.contains("is not connected to the TimeSyncServer")) + .count() + == 1); + + Thread.sleep(20); + } - // Loop to hit cases past first iteration - for (int i = 0; i < 10; i++) { - // AND a PhotonCamera with a "new" result - sim.submitProcessedFrame(noPongResult); + final double HEARTBEAT_TIMEOUT = 0.5; - // WHEN we update the camera + // GIVEN a PhotonCamera provided new results + SimHooks.pauseTiming(); + sim.submitProcessedFrame(noPongResult); camera.getAllUnreadResults(); + // AND in a connected state + assertTrue(camera.isConnected()); - // AND we tick SmartDashboard - SmartDashboard.updateValues(); + // WHEN we wait the timeout + SimHooks.stepTiming(HEARTBEAT_TIMEOUT * 1.5); - // THEN the camera isn't disconnected - assertTrue( - Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0])) - .noneMatch(it -> it.equals(disconnectedCameraString))); - // AND the alert string looks like a timesync warning - assertTrue( - Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0])) - .filter(it -> it.contains("is not connected to the TimeSyncServer")) - .count() - == 1); + // THEN the camera will not be connected + assertFalse(camera.isConnected()); - Thread.sleep(20); + // WHEN we then provide new results + SimHooks.stepTiming(0.02); + sim.submitProcessedFrame(noPongResult); + camera.getAllUnreadResults(); + // THEN the camera will not be connected + assertTrue(camera.isConnected()); } - - final double HEARTBEAT_TIMEOUT = 0.5; - - // GIVEN a PhotonCamera provided new results - SimHooks.pauseTiming(); - sim.submitProcessedFrame(noPongResult); - camera.getAllUnreadResults(); - // AND in a connected state - assertTrue(camera.isConnected()); - - // WHEN we wait the timeout - SimHooks.stepTiming(HEARTBEAT_TIMEOUT * 1.5); - - // THEN the camera will not be connected - assertFalse(camera.isConnected()); - - // WHEN we then provide new results - SimHooks.stepTiming(0.02); - sim.submitProcessedFrame(noPongResult); - camera.getAllUnreadResults(); - // THEN the camera will not be connected - assertTrue(camera.isConnected()); } } diff --git a/photon-lib/src/test/java/org/photonvision/PhotonPoseEstimatorTest.java b/photon-lib/src/test/java/org/photonvision/PhotonPoseEstimatorTest.java index 41d17df998..2f4603a168 100644 --- a/photon-lib/src/test/java/org/photonvision/PhotonPoseEstimatorTest.java +++ b/photon-lib/src/test/java/org/photonvision/PhotonPoseEstimatorTest.java @@ -53,6 +53,7 @@ import java.util.List; import java.util.Optional; import org.junit.jupiter.api.AfterAll; +import org.junit.jupiter.api.AutoClose; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; import org.photonvision.PhotonPoseEstimator.ConstrainedSolvepnpParams; @@ -72,6 +73,7 @@ class PhotonPoseEstimatorTest { static AprilTagFieldLayout aprilTags; + @AutoClose final PhotonCameraInjector cameraOne = new PhotonCameraInjector(); @BeforeAll public static void init() throws UnsatisfiedLinkError, IOException { @@ -99,7 +101,6 @@ public static void teardown() { @Test void testLowestAmbiguityStrategy() { - PhotonCameraInjector cameraOne = new PhotonCameraInjector(); cameraOne.result = new PhotonPipelineResult( 0, @@ -185,7 +186,6 @@ void testLowestAmbiguityStrategy() { @Test void testClosestToCameraHeightStrategy() { - PhotonCameraInjector cameraOne = new PhotonCameraInjector(); cameraOne.result = new PhotonPipelineResult( 0, @@ -274,7 +274,6 @@ void testClosestToCameraHeightStrategy() { @Test void closestToReferencePoseStrategy() { - PhotonCameraInjector cameraOne = new PhotonCameraInjector(); cameraOne.result = new PhotonPipelineResult( 0, @@ -364,7 +363,6 @@ void closestToReferencePoseStrategy() { @Test void closestToLastPose() { - PhotonCameraInjector cameraOne = new PhotonCameraInjector(); cameraOne.result = new PhotonPipelineResult( 0, @@ -529,7 +527,6 @@ void closestToLastPose() { @Test void pnpDistanceTrigSolve() { - PhotonCameraInjector cameraOne = new PhotonCameraInjector(); List simTargets = aprilTags.getTags().stream() .map((AprilTag x) -> new VisionTargetSim(x.pose, TargetModel.kAprilTag36h11, x.ID)) @@ -591,7 +588,6 @@ void pnpDistanceTrigSolve() { @Test void cacheIsInvalidated() { - PhotonCameraInjector cameraOne = new PhotonCameraInjector(); var result = new PhotonPipelineResult( 0, @@ -668,7 +664,6 @@ void cacheIsInvalidated() { @Test void averageBestPoses() { - PhotonCameraInjector cameraOne = new PhotonCameraInjector(); cameraOne.result = new PhotonPipelineResult( 0, @@ -757,8 +752,7 @@ void averageBestPoses() { @Test void testMultiTagOnRioFallback() { - PhotonCameraInjector camera = new PhotonCameraInjector(); - camera.result = + cameraOne.result = new PhotonPipelineResult( 0, 11 * 1_000_000, @@ -811,7 +805,7 @@ void testMultiTagOnRioFallback() { new PhotonPoseEstimator(aprilTags, PoseStrategy.MULTI_TAG_PNP_ON_RIO, Transform3d.kZero); estimator.setMultiTagFallbackStrategy(PoseStrategy.LOWEST_AMBIGUITY); - Optional estimatedPose = estimator.update(camera.result); + Optional estimatedPose = estimator.update(cameraOne.result); Pose3d pose = estimatedPose.get().estimatedPose; // Make sure values match what we'd expect for the LOWEST_AMBIGUITY strategy assertAll( diff --git a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java index 641bbbe09c..5d7ce98fef 100644 --- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java @@ -336,14 +336,10 @@ public static void onOfflineUpdateRequest(Context ctx) { return; } - try { - Path filePath = - Paths.get(ProgramDirectoryUtilities.getProgramDirectory(), "photonvision.jar"); - File targetFile = new File(filePath.toString()); - var stream = new FileOutputStream(targetFile); - - file.content().transferTo(stream); - stream.close(); + Path targetPath = + Paths.get(ProgramDirectoryUtilities.getProgramDirectory(), "photonvision.jar"); + try (InputStream fileSteam = file.content()) { + Files.copy(fileSteam, targetPath); ctx.status(200); ctx.result( @@ -655,8 +651,8 @@ public static void onImportObjectDetectionModelRequest(Context ctx) { return; } - try (FileOutputStream out = new FileOutputStream(modelPath.toFile())) { - modelFile.content().transferTo(out); + try (InputStream modelFileStream = modelFile.content()) { + Files.copy(modelFileStream, modelPath); } ModelProperties modelProperties = diff --git a/shared/common.gradle b/shared/common.gradle index d8db6106df..8bd0f1d40b 100644 --- a/shared/common.gradle +++ b/shared/common.gradle @@ -46,9 +46,10 @@ dependencies { implementation "commons-cli:commons-cli:1.5.0" implementation "org.apache.commons:commons-exec:1.3" - testImplementation 'org.junit.jupiter:junit-jupiter-api:5.10.0' - testImplementation 'org.junit.jupiter:junit-jupiter-params:5.10.0' - testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.10.0' + testImplementation(platform('org.junit:junit-bom:5.11.4')) + testImplementation 'org.junit.jupiter:junit-jupiter-api' + testImplementation 'org.junit.jupiter:junit-jupiter-params' + testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine' } test { diff --git a/shared/javacommon.gradle b/shared/javacommon.gradle index 2810305fcd..fd357e38d1 100644 --- a/shared/javacommon.gradle +++ b/shared/javacommon.gradle @@ -145,9 +145,10 @@ dependencies { implementation group: "org.ejml", name: "ejml-simple", version: wpi.versions.ejmlVersion.get() implementation group: "us.hebi.quickbuf", name: "quickbuf-runtime", version: wpi.versions.quickbufVersion.get(); - testImplementation 'org.junit.jupiter:junit-jupiter-api:5.10.0' - testImplementation 'org.junit.jupiter:junit-jupiter-params:5.10.0' - testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.10.0' + testImplementation(platform('org.junit:junit-bom:5.11.4')) + testImplementation 'org.junit.jupiter:junit-jupiter-api' + testImplementation 'org.junit.jupiter:junit-jupiter-params' + testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine' } jacoco {