Skip to content

Commit 7d927ac

Browse files
authored
Fix 'Resource leak: <variable> is never closed' warnings (#2023)
Fix numerous places where using AutoCloseable objects without closing them. Changes: - Upgrade JUnit from 5.10.0 to 5.11.4 (so `@AutoClose` can be used) - Use `Files.copy()` to copy files - Use try-with-resources when calling `Files.list()` or `Files.walk()` - Use try-with-resources or `@AutoClose` to close `PhotonCamera` and `PhotonCameraSim` objects created by tests - Update `SQLConfigTest` to use `@TempDir` ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [ ] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [ ] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [ ] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [ ] If this PR addresses a bug, a regression test for it is added
1 parent bd2c506 commit 7d927ac

File tree

10 files changed

+119
-129
lines changed

10 files changed

+119
-129
lines changed

photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
import java.time.format.DateTimeFormatter;
3333
import java.time.temporal.TemporalAccessor;
3434
import java.util.*;
35+
import java.util.stream.Stream;
3536
import org.photonvision.common.logging.LogGroup;
3637
import org.photonvision.common.logging.Logger;
3738
import org.photonvision.common.util.file.FileUtils;
@@ -282,9 +283,8 @@ public boolean saveToDisk() {
282283

283284
private HashMap<String, CameraConfiguration> loadCameraConfigs() {
284285
HashMap<String, CameraConfiguration> loadedConfigurations = new HashMap<>();
285-
try {
286-
var subdirectories =
287-
Files.list(camerasFolder.toPath()).filter(f -> f.toFile().isDirectory()).toList();
286+
try (Stream<Path> files = Files.list(camerasFolder.toPath())) {
287+
var subdirectories = files.filter(f -> f.toFile().isDirectory()).toList();
288288

289289
for (var subdir : subdirectories) {
290290
var cameraConfigPath = Path.of(subdir.toString(), "config.json");
@@ -325,9 +325,11 @@ private HashMap<String, CameraConfiguration> loadCameraConfigs() {
325325
// Load pipelines by mapping the files within the pipelines subdir
326326
// to their deserialized equivalents
327327
var pipelineSubdirectory = Path.of(subdir.toString(), "pipelines");
328-
List<CVPipelineSettings> settings =
329-
pipelineSubdirectory.toFile().exists()
330-
? Files.list(pipelineSubdirectory)
328+
List<CVPipelineSettings> settings = Collections.emptyList();
329+
if (pipelineSubdirectory.toFile().exists()) {
330+
try (Stream<Path> subdirectoryFiles = Files.list(pipelineSubdirectory)) {
331+
settings =
332+
subdirectoryFiles
331333
.filter(p -> p.toFile().isFile())
332334
.map(
333335
p -> {
@@ -350,8 +352,9 @@ private HashMap<String, CameraConfiguration> loadCameraConfigs() {
350352
return null;
351353
})
352354
.filter(Objects::nonNull)
353-
.toList()
354-
: Collections.emptyList();
355+
.toList();
356+
}
357+
}
355358

356359
loadedConfig.driveModeSettings = driverMode;
357360
loadedConfig.addPipelineSettings(settings);

photon-core/src/main/java/org/photonvision/common/configuration/NeuralNetworkModelManager.java

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
import java.util.Optional;
3434
import java.util.jar.JarEntry;
3535
import java.util.jar.JarFile;
36+
import java.util.stream.Stream;
3637
import org.photonvision.common.configuration.NeuralNetworkPropertyManager.ModelProperties;
3738
import org.photonvision.common.hardware.Platform;
3839
import org.photonvision.common.logging.LogGroup;
@@ -365,8 +366,8 @@ public void discoverModels() {
365366

366367
models = new HashMap<>();
367368

368-
try {
369-
Files.walk(modelsDirectory.toPath())
369+
try (Stream<Path> files = Files.walk(modelsDirectory.toPath())) {
370+
files
370371
.filter(Files::isRegularFile)
371372
.filter(
372373
path ->
@@ -469,8 +470,8 @@ public boolean clearModels() {
469470
File modelsDirectory = ConfigManager.getInstance().getModelsDirectory();
470471

471472
if (modelsDirectory.exists()) {
472-
try {
473-
Files.walk(modelsDirectory.toPath())
473+
try (Stream<Path> files = Files.walk(modelsDirectory.toPath())) {
474+
files
474475
.sorted((a, b) -> b.compareTo(a))
475476
.forEach(
476477
path -> {

photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java

Lines changed: 2 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -21,16 +21,12 @@
2121
import static org.junit.jupiter.api.Assertions.assertEquals;
2222

2323
import edu.wpi.first.cscore.UsbCameraInfo;
24-
import java.io.File;
25-
import java.io.IOException;
26-
import java.nio.file.Files;
2724
import java.nio.file.Path;
28-
import java.util.Comparator;
2925
import java.util.List;
30-
import org.junit.jupiter.api.AfterAll;
3126
import org.junit.jupiter.api.BeforeAll;
3227
import org.junit.jupiter.api.Order;
3328
import org.junit.jupiter.api.Test;
29+
import org.junit.jupiter.api.io.TempDir;
3430
import org.photonvision.common.util.TestUtils;
3531
import org.photonvision.vision.camera.CameraQuirk;
3632
import org.photonvision.vision.camera.PVCameraInfo;
@@ -39,22 +35,11 @@
3935
import org.photonvision.vision.pipeline.ReflectivePipelineSettings;
4036

4137
public class SQLConfigTest {
42-
private static Path tmpDir;
38+
@TempDir private static Path tmpDir;
4339

4440
@BeforeAll
4541
public static void init() {
4642
TestUtils.loadLibraries();
47-
try {
48-
tmpDir = Files.createTempDirectory("SQLConfigTest");
49-
} catch (IOException e) {
50-
System.out.println("Couldn't create temporary directory, using current directory");
51-
tmpDir = Path.of("jdbc_test", "temp");
52-
}
53-
}
54-
55-
@AfterAll
56-
public static void cleanUp() throws IOException {
57-
Files.walk(tmpDir).sorted(Comparator.reverseOrder()).map(Path::toFile).forEach(File::delete);
5843
}
5944

6045
@Test

photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -100,6 +100,14 @@ public static Point[] getImageCorners(Size size) {
100100
/**
101101
* Gets the 10x10 (grayscale) image of a specific 36h11 AprilTag.
102102
*
103+
* <p>WARNING: This creates a {@link RawFrame} instance but does not close it, which would result
104+
* in a resource leak if the {@link Mat} is garbage-collected. Unfortunately, closing the {@code
105+
* RawFrame} inside this function would delete the underlying data that backs the {@code
106+
* ByteBuffer} that is passed to the {@code Mat} constructor (see comments on <a
107+
* href="https://github.com/PhotonVision/photonvision/pull/2023">PR 2023</a> for details).
108+
* Luckily, this method is private and is (as of Aug 2025) only used to populate the {@link
109+
* #kTag36h11Images} static map at static-initialization time.
110+
*
103111
* @param id The fiducial id of the desired tag
104112
*/
105113
private static Mat get36h11TagImage(int id) {

photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -122,6 +122,7 @@ public void clearCameras() {
122122
* @return If the camera was present and removed
123123
*/
124124
public boolean removeCamera(PhotonCameraSim cameraSim) {
125+
@SuppressWarnings("resource")
125126
boolean success = camSimMap.remove(cameraSim.getCamera().getName()) != null;
126127
camTrfMap.remove(cameraSim);
127128
return success;

photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java

Lines changed: 74 additions & 74 deletions
Original file line numberDiff line numberDiff line change
@@ -117,31 +117,31 @@ public void testTimeSyncServerWithPhotonCamera() throws InterruptedException, IO
117117
inst.stopClient();
118118
inst.startServer();
119119

120-
var camera = new PhotonCamera(inst, "Arducam_OV2311_USB_Camera");
121-
PhotonCamera.setVersionCheckEnabled(false);
122-
123-
for (int i = 0; i < 5; i++) {
124-
Thread.sleep(500);
125-
126-
var res = camera.getLatestResult();
127-
var captureTime = res.getTimestampSeconds();
128-
var now = Timer.getFPGATimestamp();
129-
130-
// expectTrue(captureTime < now);
131-
132-
System.out.println(
133-
"sequence "
134-
+ res.metadata.sequenceID
135-
+ " image capture "
136-
+ captureTime
137-
+ " received at "
138-
+ res.getTimestampSeconds()
139-
+ " now: "
140-
+ NetworkTablesJNI.now() / 1e6
141-
+ " time since last pong: "
142-
+ res.metadata.timeSinceLastPong / 1e6);
120+
try (PhotonCamera camera = new PhotonCamera(inst, "Arducam_OV2311_USB_Camera")) {
121+
PhotonCamera.setVersionCheckEnabled(false);
122+
123+
for (int i = 0; i < 5; i++) {
124+
Thread.sleep(500);
125+
126+
var res = camera.getLatestResult();
127+
var captureTime = res.getTimestampSeconds();
128+
var now = Timer.getFPGATimestamp();
129+
130+
// expectTrue(captureTime < now);
131+
132+
System.out.println(
133+
"sequence "
134+
+ res.metadata.sequenceID
135+
+ " image capture "
136+
+ captureTime
137+
+ " received at "
138+
+ res.getTimestampSeconds()
139+
+ " now: "
140+
+ NetworkTablesJNI.now() / 1e6
141+
+ " time since last pong: "
142+
+ res.metadata.timeSinceLastPong / 1e6);
143+
}
143144
}
144-
145145
HAL.shutdown();
146146
}
147147

@@ -335,62 +335,62 @@ public void testAlerts() throws InterruptedException {
335335
Thread.sleep(20);
336336
}
337337

338-
// GIVEN a simulated camera
339-
var sim = new PhotonCameraSim(camera);
340-
// AND a result with a timeSinceLastPong in the past
341-
PhotonPipelineResult noPongResult =
342-
new PhotonPipelineResult(
343-
new PhotonPipelineMetadata(
344-
1, 2, 3, 10 * 1000000 // 10 seconds -> us since last pong
345-
),
346-
List.of(),
347-
Optional.empty());
338+
// GIVEN a simulated camera AND a result with a timeSinceLastPong in the past
339+
try (PhotonCameraSim sim = new PhotonCameraSim(camera)) {
340+
PhotonPipelineResult noPongResult =
341+
new PhotonPipelineResult(
342+
new PhotonPipelineMetadata(
343+
1, 2, 3, 10 * 1000000 // 10 seconds -> us since last pong
344+
),
345+
List.of(),
346+
Optional.empty());
347+
348+
// Loop to hit cases past first iteration
349+
for (int i = 0; i < 10; i++) {
350+
// AND a PhotonCamera with a "new" result
351+
sim.submitProcessedFrame(noPongResult);
352+
353+
// WHEN we update the camera
354+
camera.getAllUnreadResults();
355+
356+
// AND we tick SmartDashboard
357+
SmartDashboard.updateValues();
358+
359+
// THEN the camera isn't disconnected
360+
assertTrue(
361+
Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0]))
362+
.noneMatch(it -> it.equals(disconnectedCameraString)));
363+
// AND the alert string looks like a timesync warning
364+
assertTrue(
365+
Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0]))
366+
.filter(it -> it.contains("is not connected to the TimeSyncServer"))
367+
.count()
368+
== 1);
369+
370+
Thread.sleep(20);
371+
}
348372

349-
// Loop to hit cases past first iteration
350-
for (int i = 0; i < 10; i++) {
351-
// AND a PhotonCamera with a "new" result
352-
sim.submitProcessedFrame(noPongResult);
373+
final double HEARTBEAT_TIMEOUT = 0.5;
353374

354-
// WHEN we update the camera
375+
// GIVEN a PhotonCamera provided new results
376+
SimHooks.pauseTiming();
377+
sim.submitProcessedFrame(noPongResult);
355378
camera.getAllUnreadResults();
379+
// AND in a connected state
380+
assertTrue(camera.isConnected());
356381

357-
// AND we tick SmartDashboard
358-
SmartDashboard.updateValues();
382+
// WHEN we wait the timeout
383+
SimHooks.stepTiming(HEARTBEAT_TIMEOUT * 1.5);
359384

360-
// THEN the camera isn't disconnected
361-
assertTrue(
362-
Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0]))
363-
.noneMatch(it -> it.equals(disconnectedCameraString)));
364-
// AND the alert string looks like a timesync warning
365-
assertTrue(
366-
Arrays.stream(SmartDashboard.getStringArray("PhotonAlerts/warnings", new String[0]))
367-
.filter(it -> it.contains("is not connected to the TimeSyncServer"))
368-
.count()
369-
== 1);
385+
// THEN the camera will not be connected
386+
assertFalse(camera.isConnected());
370387

371-
Thread.sleep(20);
388+
// WHEN we then provide new results
389+
SimHooks.stepTiming(0.02);
390+
sim.submitProcessedFrame(noPongResult);
391+
camera.getAllUnreadResults();
392+
// THEN the camera will not be connected
393+
assertTrue(camera.isConnected());
372394
}
373-
374-
final double HEARTBEAT_TIMEOUT = 0.5;
375-
376-
// GIVEN a PhotonCamera provided new results
377-
SimHooks.pauseTiming();
378-
sim.submitProcessedFrame(noPongResult);
379-
camera.getAllUnreadResults();
380-
// AND in a connected state
381-
assertTrue(camera.isConnected());
382-
383-
// WHEN we wait the timeout
384-
SimHooks.stepTiming(HEARTBEAT_TIMEOUT * 1.5);
385-
386-
// THEN the camera will not be connected
387-
assertFalse(camera.isConnected());
388-
389-
// WHEN we then provide new results
390-
SimHooks.stepTiming(0.02);
391-
sim.submitProcessedFrame(noPongResult);
392-
camera.getAllUnreadResults();
393-
// THEN the camera will not be connected
394-
assertTrue(camera.isConnected());
395395
}
396396
}

0 commit comments

Comments
 (0)