diff --git a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java index 44e7e33ce..cf29d613b 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java @@ -52,7 +52,7 @@ public class TestUtils { kRocketPanelAngleDark48in(1.2192), kRocketPanelAngleDark60in(1.524); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; @@ -90,7 +90,7 @@ public class TestUtils { kRedLoading_084in(2.1336), kRedLoading_108in(2.7432); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; @@ -110,7 +110,7 @@ public class TestUtils { kBackAmpZone_117in, kSpeakerCenter_143in; - public static double FOV = 68.5; + public static final double FOV = 68.5; public final Path path; @@ -129,7 +129,7 @@ public class TestUtils { k162_36_Straight, k383_60_Angle2; - public static double FOV = 68.5; + public static final double FOV = 68.5; public final Translation2d approxPose; public final Path path; @@ -156,7 +156,7 @@ public class TestUtils { kTerminal12ft6in(Units.feetToMeters(12.5)), kTerminal22ft6in(Units.feetToMeters(22.5)); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java b/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java index 6bae04aaf..ff463e198 100644 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java +++ b/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java @@ -110,7 +110,7 @@ public class JsonMatOfDouble implements Releasable { if (wpilibMat == null) { wpilibMat = new Matrix(new SimpleMatrix(rows, cols, true, data)); } - return (Matrix) wpilibMat; + return wpilibMat; } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java index bfe05e24a..7d923bad8 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java @@ -100,12 +100,6 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { // first. var autoExpProp = findProperty("exposure_auto", "auto_exposure"); - if (expProp.isPresent()) { - exposureAbsProp = expProp.get(); - this.minExposure = exposureAbsProp.getMin(); - this.maxExposure = exposureAbsProp.getMax(); - } - if (autoExpProp.isPresent()) { autoExposureProp = autoExpProp.get(); } @@ -278,10 +272,8 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { continue; } - if (configuration.cameraQuirks.hasQuirk(CameraQuirk.FPSCap100)) { - if (videoMode.fps > 100) { - continue; - } + if (configuration.cameraQuirks.hasQuirk(CameraQuirk.FPSCap100) && videoMode.fps > 100) { + continue; } videoModesList.add(videoMode); 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 5508154b0..82f563555 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 @@ -62,19 +62,18 @@ public class CornerDetectionPipe // find the bl/br/tr/tl corners // first, min by left/right - var list_ = Arrays.asList(points); - list_.sort(leftRightComparator); + Arrays.sort(points, leftRightComparator); // of this, we now have left and right // sort to get top and bottom - var left = new ArrayList<>(List.of(list_.get(0), list_.get(1))); - left.sort(verticalComparator); - var right = new ArrayList<>(List.of(list_.get(2), list_.get(3))); - right.sort(verticalComparator); + Point[] left = {points[0], points[1]}; + Arrays.sort(left, verticalComparator); + Point[] right = {points[2], points[3]}; + Arrays.sort(right, verticalComparator); - var tl = left.get(0); - var bl = left.get(1); - var tr = right.get(0); - var br = right.get(1); + var tl = left[0]; + var bl = left[1]; + var tr = right[0]; + var br = right[1]; return List.of(bl, br, tr, tl); } @@ -140,11 +139,9 @@ public class CornerDetectionPipe // top left and top right are the poly corners closest to the bounding box tl and tr pointList.sort(compareDistToTl); - var tl = pointList.get(0); - pointList.remove(tl); + var tl = pointList.remove(0); pointList.sort(compareDistToTr); - var tr = pointList.get(0); - pointList.remove(tr); + var tr = pointList.remove(0); // at this point we look for points on the left/right of the center of the remaining points // and maximize their distance from the center of the min area rectangle @@ -160,12 +157,13 @@ public class CornerDetectionPipe for (var p : pointList) { if (p.y > target.m_mainContour.getBoundingRect().y - + target.m_mainContour.getBoundingRect().height / 2.0) + + target.m_mainContour.getBoundingRect().height / 2.0) { if (p.x < averageXCoordinate) { leftList.add(p); } else { rightList.add(p); } + } } if (leftList.isEmpty() || rightList.isEmpty()) return null; leftList.sort(compareCenterDist); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java index 12f2ac913..37ee97733 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java @@ -67,9 +67,7 @@ public class FilterContoursPipe double x = c.getCenterPoint().x; double y = c.getCenterPoint().y; - if (Math.abs(x - meanX) > stdDevX * xTol) { - it.remove(); - } else if (Math.abs(y - meanY) > stdDevY * yTol) { + if (Math.abs(x - meanX) > stdDevX * xTol || Math.abs(y - meanY) > stdDevY * yTol) { it.remove(); } // Otherwise we're good! Keep it in diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index fb2dd3b8b..1d670cb78 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -54,7 +54,7 @@ public class FindBoardCornersPipe // Since we return results in real-time, we want to ensure it goes as fast as // possible // and fails as fast as possible. - final int findChessboardFlags = + static final int findChessboardFlags = Calib3d.CALIB_CB_NORMALIZE_IMAGE | Calib3d.CALIB_CB_ADAPTIVE_THRESH | Calib3d.CALIB_CB_FILTER_QUADS diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java index 04b1bf774..97b95b195 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java @@ -32,7 +32,5 @@ public class GrayscalePipe extends CVPipe>(); var videoModes = visionSource.getSettables().getAllVideoModes(); - for (var k : videoModes.keySet()) { + for (var k : videoModes.entrySet()) { var internalMap = new HashMap(); - internalMap.put("width", videoModes.get(k).width); - internalMap.put("height", videoModes.get(k).height); - internalMap.put("fps", videoModes.get(k).fps); + internalMap.put("width", k.getValue().width); + internalMap.put("height", k.getValue().height); + internalMap.put("fps", k.getValue().fps); internalMap.put( "pixelFormat", - ((videoModes.get(k) instanceof LibcameraGpuSource.FPSRatedVideoMode) + ((k.getValue() instanceof LibcameraGpuSource.FPSRatedVideoMode) ? "kPicam" - : videoModes.get(k).pixelFormat.toString()) + : k.getValue().pixelFormat.toString()) .substring(1)); // Remove the k prefix - temp.put(k, internalMap); + temp.put(k.getKey(), internalMap); } if (videoModes.size() == 0) { diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java index 55b173736..7a5da5331 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java @@ -55,23 +55,22 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { @Override public void onDataChangeEvent(DataChangeEvent event) { - if (event instanceof IncomingWebSocketEvent wsEvent) { - // Camera index -1 means a "multicast event" (i.e. the event is received by all cameras) - if (wsEvent.cameraUniqueName != null - && wsEvent.cameraUniqueName.equals(parentModule.uniqueName())) { - logger.trace("Got PSC event - propName: " + wsEvent.propertyName); - changeListLock.lock(); - try { - getSettingChanges() - .add( - new VisionModuleChange( - wsEvent.propertyName, - wsEvent.data, - parentModule.pipelineManager.getCurrentPipeline().getSettings(), - wsEvent.originContext)); - } finally { - changeListLock.unlock(); - } + // Camera index -1 means a "multicast event" (i.e. the event is received by all cameras) + if (event instanceof IncomingWebSocketEvent wsEvent + && wsEvent.cameraUniqueName != null + && wsEvent.cameraUniqueName.equals(parentModule.uniqueName())) { + logger.trace("Got PSC event - propName: " + wsEvent.propertyName); + changeListLock.lock(); + try { + getSettingChanges() + .add( + new VisionModuleChange( + wsEvent.propertyName, + wsEvent.data, + parentModule.pipelineManager.getCurrentPipeline().getSettings(), + wsEvent.originContext)); + } finally { + changeListLock.unlock(); } } } diff --git a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java index 9108abeba..848c7a447 100644 --- a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java @@ -112,14 +112,13 @@ public class DataSocketHandler { var socketMessageType = DataSocketMessageType.fromEntryKey(entryKey); logger.trace( - () -> - "Got WS message: [" - + socketMessageType - + "] ==> [" - + entryKey - + "], [" - + entryValue - + "]"); + "Got WS message: [" + + socketMessageType + + "] ==> [" + + entryKey + + "], [" + + entryValue + + "]"); if (socketMessageType == null) { logger.warn("Got unknown socket message type: " + entryKey); 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 6becc0000..f734f38ef 100644 --- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java @@ -641,7 +641,7 @@ public class RequestHandler { } public static void onCalibrationSnapshotRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); var width = Integer.parseInt(ctx.queryParam("width")); @@ -695,7 +695,7 @@ public class RequestHandler { } public static void onCalibrationExportRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); var width = Integer.parseInt(ctx.queryParam("width")); @@ -900,7 +900,7 @@ public class RequestHandler { } public static void onActivateMatchedCameraRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); @@ -914,7 +914,7 @@ public class RequestHandler { } public static void onAssignUnmatchedCameraRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); PVCameraInfo camera; try { @@ -934,7 +934,7 @@ public class RequestHandler { } public static void onUnassignCameraRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); diff --git a/photon-targeting/src/test/java/jni/FileLoggerTest.java b/photon-targeting/src/test/java/jni/FileLoggerTest.java index 157ee9f1e..f974825b3 100644 --- a/photon-targeting/src/test/java/jni/FileLoggerTest.java +++ b/photon-targeting/src/test/java/jni/FileLoggerTest.java @@ -15,7 +15,7 @@ * along with this program. If not, see . */ -package wpiutil_extras; +package jni; import static org.junit.jupiter.api.Assertions.fail; import static org.junit.jupiter.api.Assumptions.assumeTrue;