Skip to content

Fix 'Resource leak: <variable> is never closed' warnings #2023

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 2 commits into from
Aug 19, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -282,9 +283,8 @@ public boolean saveToDisk() {

private HashMap<String, CameraConfiguration> loadCameraConfigs() {
HashMap<String, CameraConfiguration> loadedConfigurations = new HashMap<>();
try {
var subdirectories =
Files.list(camerasFolder.toPath()).filter(f -> f.toFile().isDirectory()).toList();
try (Stream<Path> 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");
Expand Down Expand Up @@ -325,9 +325,11 @@ private HashMap<String, CameraConfiguration> loadCameraConfigs() {
// Load pipelines by mapping the files within the pipelines subdir
// to their deserialized equivalents
var pipelineSubdirectory = Path.of(subdir.toString(), "pipelines");
List<CVPipelineSettings> settings =
pipelineSubdirectory.toFile().exists()
? Files.list(pipelineSubdirectory)
List<CVPipelineSettings> settings = Collections.emptyList();
if (pipelineSubdirectory.toFile().exists()) {
try (Stream<Path> subdirectoryFiles = Files.list(pipelineSubdirectory)) {
settings =
subdirectoryFiles
.filter(p -> p.toFile().isFile())
.map(
p -> {
Expand All @@ -350,8 +352,9 @@ private HashMap<String, CameraConfiguration> loadCameraConfigs() {
return null;
})
.filter(Objects::nonNull)
.toList()
: Collections.emptyList();
.toList();
}
}

loadedConfig.driveModeSettings = driverMode;
loadedConfig.addPipelineSettings(settings);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -365,8 +366,8 @@ public void discoverModels() {

models = new HashMap<>();

try {
Files.walk(modelsDirectory.toPath())
try (Stream<Path> files = Files.walk(modelsDirectory.toPath())) {
files
.filter(Files::isRegularFile)
.filter(
path ->
Expand Down Expand Up @@ -469,8 +470,8 @@ public boolean clearModels() {
File modelsDirectory = ConfigManager.getInstance().getModelsDirectory();

if (modelsDirectory.exists()) {
try {
Files.walk(modelsDirectory.toPath())
try (Stream<Path> files = Files.walk(modelsDirectory.toPath())) {
files
.sorted((a, b) -> b.compareTo(a))
.forEach(
path -> {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,14 @@ public static Point[] getImageCorners(Size size) {
/**
* Gets the 10x10 (grayscale) image of a specific 36h11 AprilTag.
*
* <p>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 <a
* href="https://github.com/PhotonVision/photonvision/pull/2023">PR 2023</a> 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) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
148 changes: 74 additions & 74 deletions photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

Expand Down Expand Up @@ -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());
}
}
Loading
Loading