From acbdd8f48a99c0642bda0971537fbd4911a39395 Mon Sep 17 00:00:00 2001 From: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com> Date: Tue, 10 Oct 2023 13:31:58 -0400 Subject: [PATCH] Formatting fixes --- .../networktables/NTDataPublisher.java | 8 ++------ .../common/hardware/VisionLED.java | 6 +----- .../common/networking/NetworkUtils.java | 4 ++-- .../photonvision/common/util/ShellExec.java | 2 +- .../org/photonvision/raspi/LibCameraJNI.java | 4 ++-- .../vision/camera/FileVisionSource.java | 3 ++- .../vision/camera/USBCameraSource.java | 3 ++- .../frame/provider/FileFrameProvider.java | 6 +----- .../frame/provider/USBFrameProvider.java | 6 +----- .../impl/AprilTagDetectionPipeParams.java | 3 +-- .../vision/pipe/impl/CornerDetectionPipe.java | 10 +++------- .../pipe/impl/GPUAcceleratedHSVPipe.java | 20 +++++++++++++------ .../vision/processes/PipelineManager.java | 5 +---- .../vision/target/TrackedTarget.java | 6 +++--- .../vision/videoStream/SocketVideoStream.java | 3 +-- .../videoStream/SocketVideoStreamManager.java | 3 +-- .../common/util/LogFileManagementTest.java | 9 ++------- .../processes/VisionModuleManagerTest.java | 5 ++++- .../vision/target/TargetCalculationsTest.java | 3 ++- 19 files changed, 46 insertions(+), 63 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java index 8b67ae7cd9..56bae44bd7 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java @@ -181,8 +181,7 @@ public void accept(CVPipelineResult result) { } // Something in the result can sometimes be null -- so check probably too many things - if ( - result.inputAndOutputFrame != null + if (result.inputAndOutputFrame != null && result.inputAndOutputFrame.frameStaticProperties != null && result.inputAndOutputFrame.frameStaticProperties.cameraCalibration != null) { var fsp = result.inputAndOutputFrame.frameStaticProperties; @@ -214,10 +213,7 @@ public static List simpleFromTrackedTargets(List getAllInterfaces() { } 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 + // 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()); diff --git a/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java b/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java index e7b353751d..c8433ec158 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java +++ b/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java @@ -22,7 +22,7 @@ import org.photonvision.common.logging.Logger; /** Execute external process and optionally read output buffer. */ -@SuppressWarnings({"unused" }) +@SuppressWarnings({"unused"}) public class ShellExec { private static final Logger logger = new Logger(ShellExec.class, LogGroup.General); diff --git a/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java index 5dc40ce667..a75ae2e579 100644 --- a/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java +++ b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java @@ -168,8 +168,8 @@ public static native boolean setThresholds( public static native boolean awaitNewFrame(); /** - * Get a pointer to the most recent color mat generated. Call this immediately after awaitNewFrame, - * and call only once per new frame! + * Get a pointer to the most recent color mat generated. Call this immediately after + * awaitNewFrame, and call only once per new frame! */ public static native long takeColorFrame(); diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java index 4c743e321b..951135fcf4 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java @@ -34,7 +34,8 @@ public class FileVisionSource extends VisionSource { public FileVisionSource(CameraConfiguration cameraConfiguration) { super(cameraConfiguration); - var calibration = !cameraConfiguration.calibrations.isEmpty() + var calibration = + !cameraConfiguration.calibrations.isEmpty() ? cameraConfiguration.calibrations.get(0) : null; frameProvider = diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java index 8929a042a1..ad235da26a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java @@ -268,7 +268,8 @@ public HashMap getAllVideoModes() { } for (VideoMode videoMode : modes) { // Filter grey modes - if (videoMode.pixelFormat == VideoMode.PixelFormat.kGray || videoMode.pixelFormat == VideoMode.PixelFormat.kUnknown) { + if (videoMode.pixelFormat == VideoMode.PixelFormat.kGray + || videoMode.pixelFormat == VideoMode.PixelFormat.kUnknown) { continue; } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java index 2514bbaabd..315e4e3de3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java @@ -111,11 +111,7 @@ public CapturedFrame getInputMat() { } lastGetMillis = System.currentTimeMillis(); - return new CapturedFrame( - out, - properties, - MathUtils.wpiNanoTime() - ); + return new CapturedFrame(out, properties, MathUtils.wpiNanoTime()); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java index 20770fdd4f..03459c197d 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java @@ -48,11 +48,7 @@ public CapturedFrame getInputMat() { time = MathUtils.wpiNanoTime(); } - return new CapturedFrame( - mat, - settables.getFrameStaticProperties(), - time - ); + return new CapturedFrame(mat, settables.getFrameStaticProperties(), time); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java index 96031f866d..ab52d7bcfb 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java @@ -47,7 +47,6 @@ public boolean equals(Object obj) { if (family != other.family) return false; if (detectorParams == null) { return other.detectorParams == null; - } else - return detectorParams.equals(other.detectorParams); + } else return detectorParams.equals(other.detectorParams); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java index c7cddde140..ff7f6fd3ea 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java @@ -18,9 +18,7 @@ package org.photonvision.vision.pipe.impl; import edu.wpi.first.math.geometry.Translation2d; - import java.util.*; - import org.opencv.core.MatOfPoint2f; import org.opencv.core.Point; import org.opencv.imgproc.Imgproc; @@ -41,11 +39,9 @@ protected List process(List targetList) { for (var target : targetList) { // detect corners. Might implement more algorithms later but // APPROX_POLY_DP_AND_EXTREME_CORNERS should be year agnostic - if (Objects.requireNonNull(params.cornerDetectionStrategy) == DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS) { - var targetCorners = detectExtremeCornersByApproxPolyDp( - target, - params.calculateConvexHulls - ); + if (Objects.requireNonNull(params.cornerDetectionStrategy) + == DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS) { + var targetCorners = detectExtremeCornersByApproxPolyDp(target, params.calculateConvexHulls); target.setTargetCorners(targetCorners); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java index 810b0d4542..5b49faf641 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java @@ -299,7 +299,9 @@ public GPUAcceleratedHSVPipe(PBOMode pboMode) { gl.glBindBuffer(GL_ARRAY_BUFFER, vertexVBOIds.get(0)); gl.glBufferData( GL_ARRAY_BUFFER, - (long) vertexBuffer.capacity() * Float.BYTES, vertexBuffer, GL_STATIC_DRAW); + (long) vertexBuffer.capacity() * Float.BYTES, + vertexBuffer, + GL_STATIC_DRAW); // Set up pixel unpack buffer (a PBO to transfer image data to the GPU) if (pboMode != PBOMode.NONE) { @@ -391,13 +393,17 @@ protected Mat process(Mat in) { gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(0)); gl.glBufferData( GLES3.GL_PIXEL_PACK_BUFFER, - (long) in.width() * in.height(), null, GLES3.GL_STREAM_READ); + (long) in.width() * in.height(), + null, + GLES3.GL_STREAM_READ); if (pboMode == PBOMode.DOUBLE_BUFFERED) { gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(1)); gl.glBufferData( GLES3.GL_PIXEL_PACK_BUFFER, - (long) in.width() * in.height(), null, GLES3.GL_STREAM_READ); + (long) in.width() * in.height(), + null, + GLES3.GL_STREAM_READ); } } } @@ -463,7 +469,9 @@ protected Mat process(Mat in) { // This causes the previous data in the PBO to be discarded gl.glBufferData( GLES3.GL_PIXEL_UNPACK_BUFFER, - (long) in.width() * in.height() * 3, null, GLES3.GL_STREAM_DRAW); + (long) in.width() * in.height() * 3, + null, + GLES3.GL_STREAM_DRAW); // Map the buffer of GPU memory into a place that's accessible by us var buf = @@ -531,8 +539,8 @@ private Mat saveMatPBO(GLES3 gl, int width, int height, boolean doubleBuffered) // Map the PBO into the CPU's memory gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(packNextIndex)); var buf = - gl.glMapBufferRange(GLES3.GL_PIXEL_PACK_BUFFER, 0, - (long) width * height, GLES3.GL_MAP_READ_BIT); + gl.glMapBufferRange( + GLES3.GL_PIXEL_PACK_BUFFER, 0, (long) width * height, GLES3.GL_MAP_READ_BIT); buf.get(outputBytes); outputMat.put(0, 0, outputBytes); gl.glUnmapBuffer(GLES3.GL_PIXEL_PACK_BUFFER); diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java index dae815a1ce..e4f6df3a97 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java @@ -397,10 +397,7 @@ private static String createUniqueName( var parenEnd = uniqueName.length() - 1; var number = Integer.parseInt(uniqueName.substring(parenStart + 1, parenEnd)) + 1; - uniqueName = new StringBuilder(uniqueName.substring( - 0, - parenStart + 1 - ) + number + ")"); + uniqueName = new StringBuilder(uniqueName.substring(0, parenStart + 1) + number + ")"); } else { uniqueName.append(" (1)"); } diff --git a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java index 9af48bbf38..72c5cdf600 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java @@ -126,8 +126,7 @@ public TrackedTarget( 0, bestPose.getTranslation().getX(), bestPose.getTranslation().getY(), - bestPose.getTranslation().getZ() - ); + bestPose.getTranslation().getZ()); setCameraRelativeTvec(tvec); // Opencv expects a 3d vector with norm = angle and direction = axis @@ -183,7 +182,8 @@ public TrackedTarget(ArucoDetectionResult result, TargetCalculationParameters pa VecBuilder.fill(result.getRvec()[0], result.getRvec()[1], result.getRvec()[2]); Rotation3d rotation = new Rotation3d(axisangle, axisangle.normF()); - m_bestCameraToTarget3d = MathUtils.convertOpenCVtoPhotonTransform(new Transform3d(translation, rotation)); + m_bestCameraToTarget3d = + MathUtils.convertOpenCVtoPhotonTransform(new Transform3d(translation, rotation)); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java index bb5cd17dc4..dae270e9f6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java +++ b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java @@ -53,8 +53,7 @@ public SocketVideoStream(int portID) { this.portID = portID; oldSchoolServer = new MJPGFrameConsumer( - CameraServerJNI.getHostname() + "_Port_" + portID + "_MJPEG_Server", - portID); + CameraServerJNI.getHostname() + "_Port_" + portID + "_MJPEG_Server", portID); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java index 4bc07089eb..ceb84feab6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java @@ -61,8 +61,7 @@ public void addSubscription(WsContext user, int streamPortID) { userSubscriptions.put(user, streamPortID); stream.addUser(); } else { - logger.error( - "User attempted to subscribe to non-existent port " + streamPortID); + logger.error("User attempted to subscribe to non-existent port " + streamPortID); } } diff --git a/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java b/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java index caa8edaa5c..e834874641 100644 --- a/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java +++ b/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java @@ -58,19 +58,14 @@ public void fileCleanupTest() { // Confirm new log files were created Assertions.assertTrue( - Logger.MAX_LOGS_TO_KEEP + 5 <= countLogFiles(testDir), - "Not enough log files discovered" - ); + Logger.MAX_LOGS_TO_KEEP + 5 <= countLogFiles(testDir), "Not enough log files discovered"); // Run the log cleanup routine Logger.cleanLogs(Path.of(testDir)); // Confirm we deleted log files Assertions.assertEquals( - Logger.MAX_LOGS_TO_KEEP, - countLogFiles(testDir), - "Not enough log files deleted" - ); + Logger.MAX_LOGS_TO_KEEP, countLogFiles(testDir), "Not enough log files deleted"); // Clean uptest directory org.photonvision.common.util.file.FileUtils.deleteDirectory(Path.of(testDir)); 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 e0c0288d04..e0a8376159 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 @@ -168,7 +168,10 @@ public void testMultipleStreamIndex() { var modules = vmm.addSources(List.of(testSource, testSource2, testSource3)); System.out.println( - Arrays.toString(modules.stream().map(it -> it.visionSource.getCameraConfiguration().streamIndex).toArray())); + Arrays.toString( + modules.stream() + .map(it -> it.visionSource.getCameraConfiguration().streamIndex) + .toArray())); var idxs = modules.stream() .map(it -> it.visionSource.getCameraConfiguration().streamIndex) diff --git a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java index 10152c5ab9..0dd36d90e9 100644 --- a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java @@ -34,7 +34,8 @@ public class TargetCalculationsTest { private static final Size imageSize = new Size(800, 600); - private static final Point imageCenterPoint = new Point(imageSize.width / 2, imageSize.height / 2); + private static final Point imageCenterPoint = + new Point(imageSize.width / 2, imageSize.height / 2); private static final double diagFOV = Math.toRadians(70.0); private static final FrameStaticProperties props =