mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
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
This commit is contained in:
@@ -117,31 +117,31 @@ class PhotonCameraTest {
|
||||
inst.stopClient();
|
||||
inst.startServer();
|
||||
|
||||
var camera = new PhotonCamera(inst, "Arducam_OV2311_USB_Camera");
|
||||
PhotonCamera.setVersionCheckEnabled(false);
|
||||
try (PhotonCamera camera = new PhotonCamera(inst, "Arducam_OV2311_USB_Camera")) {
|
||||
PhotonCamera.setVersionCheckEnabled(false);
|
||||
|
||||
for (int i = 0; i < 5; i++) {
|
||||
Thread.sleep(500);
|
||||
for (int i = 0; i < 5; i++) {
|
||||
Thread.sleep(500);
|
||||
|
||||
var res = camera.getLatestResult();
|
||||
var captureTime = res.getTimestampSeconds();
|
||||
var now = Timer.getFPGATimestamp();
|
||||
var res = camera.getLatestResult();
|
||||
var captureTime = res.getTimestampSeconds();
|
||||
var now = Timer.getFPGATimestamp();
|
||||
|
||||
// expectTrue(captureTime < now);
|
||||
// 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);
|
||||
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 @@ class PhotonCameraTest {
|
||||
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
|
||||
// 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);
|
||||
}
|
||||
|
||||
final double HEARTBEAT_TIMEOUT = 0.5;
|
||||
|
||||
// GIVEN a PhotonCamera provided new results
|
||||
SimHooks.pauseTiming();
|
||||
sim.submitProcessedFrame(noPongResult);
|
||||
|
||||
// WHEN we update the camera
|
||||
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());
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user