From 8591dc198d433d90862c265814cdeaa92eae3b45 Mon Sep 17 00:00:00 2001 From: Declan Freeman-Gleason Date: Mon, 13 Jul 2020 17:24:24 -0700 Subject: [PATCH 1/2] Rework UI into a new, responsive layout --- photon-client/src/App.vue | 141 +++++-- .../src/assets/{logo.png => logoLarge.png} | Bin photon-client/src/assets/logoSmall.png | Bin 0 -> 34730 bytes .../src/components/common/cv-image.vue | 21 +- .../src/components/common/cv-input.vue | 6 +- .../src/components/common/cv-range-slider.vue | 5 +- .../src/components/common/cv-select.vue | 10 +- .../src/components/common/cv-slider.vue | 17 +- .../src/components/pipeline/3D/MiniMap.vue | 66 +-- .../pipeline/CameraAndPipelineSelect.vue | 80 ++-- .../src/mixins/global/dataHandleMixin.js | 10 + photon-client/src/plugins/vuetify.js | 18 +- photon-client/src/router.js | 10 +- photon-client/src/store/index.js | 18 +- photon-client/src/theme.js | 8 + photon-client/src/views/DocsView.vue | 14 +- photon-client/src/views/PipelineView.vue | 398 ++++++++++++------ .../src/views/PipelineViews/ContoursTab.vue | 113 ++--- .../src/views/PipelineViews/InputTab.vue | 26 +- .../src/views/PipelineViews/OutputTab.vue | 11 +- .../PipelineViews/{3D.vue => PnPTab.vue} | 158 ++++--- .../src/views/PipelineViews/TargetsTab.vue | 100 +++++ .../src/views/PipelineViews/ThresholdTab.vue | 149 ++++--- .../configuration/PhotonConfiguration.java | 3 +- .../frame/consumer/MJPGFrameConsumer.java | 2 +- .../vision/pipeline/CVPipelineSettings.java | 2 + .../vision/pipeline/ReflectivePipeline.java | 154 ++++--- .../pipeline/result/CVPipelineResult.java | 10 +- .../vision/processes/VisionModule.java | 43 +- .../vision/target/TrackedTarget.java | 2 +- 30 files changed, 993 insertions(+), 602 deletions(-) rename photon-client/src/assets/{logo.png => logoLarge.png} (100%) create mode 100644 photon-client/src/assets/logoSmall.png create mode 100644 photon-client/src/theme.js rename photon-client/src/views/PipelineViews/{3D.vue => PnPTab.vue} (57%) create mode 100644 photon-client/src/views/PipelineViews/TargetsTab.vue diff --git a/photon-client/src/App.vue b/photon-client/src/App.vue index 1ab43d09f6..ca605bde5c 100644 --- a/photon-client/src/App.vue +++ b/photon-client/src/App.vue @@ -1,36 +1,86 @@ \ No newline at end of file diff --git a/photon-client/src/views/PipelineViews/ContoursTab.vue b/photon-client/src/views/PipelineViews/ContoursTab.vue index da34cc3f25..ec05971986 100644 --- a/photon-client/src/views/PipelineViews/ContoursTab.vue +++ b/photon-client/src/views/PipelineViews/ContoursTab.vue @@ -1,55 +1,58 @@ + + \ No newline at end of file diff --git a/photon-client/src/views/PipelineViews/ThresholdTab.vue b/photon-client/src/views/PipelineViews/ThresholdTab.vue index d78d3ea650..3f856f2602 100644 --- a/photon-client/src/views/PipelineViews/ThresholdTab.vue +++ b/photon-client/src/views/PipelineViews/ThresholdTab.vue @@ -1,76 +1,75 @@ - - \ No newline at end of file + \ No newline at end of file diff --git a/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java b/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java index c1dc30af8a..da38d23b0b 100644 --- a/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java +++ b/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java @@ -93,6 +93,7 @@ public static class UICameraConfiguration { public int currentPipelineIndex; public List pipelineNicknames; public HashMap> videoFormatList; - public int streamPort; + public int outputStreamPort; + public int inputStreamPort; } } diff --git a/photon-server/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java b/photon-server/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java index f94f034a94..9fdb11a0e0 100644 --- a/photon-server/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java +++ b/photon-server/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java @@ -50,7 +50,7 @@ public void setFrameDivisor(FrameDivisor divisor) { @Override public void accept(Frame frame) { - if (!frame.image.getMat().empty()) { + if (frame != null && !frame.image.getMat().empty()) { if (divisor != FrameDivisor.NONE) { var tempMat = new Mat(); Imgproc.resize( diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java index b8c1629c94..f5c51bb7e7 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java @@ -19,6 +19,8 @@ import com.fasterxml.jackson.annotation.JsonSubTypes; import com.fasterxml.jackson.annotation.JsonTypeInfo; + +import java.util.List; import java.util.Objects; import org.photonvision.vision.frame.FrameDivisor; import org.photonvision.vision.opencv.ImageFlipMode; diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java index 58973f9ed5..3fcbedc39c 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java @@ -18,8 +18,11 @@ package org.photonvision.vision.pipeline; import java.util.List; + import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; +import org.opencv.imgcodecs.Imgcodecs; +import org.opencv.imgproc.Imgproc; import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameStaticProperties; @@ -46,7 +49,9 @@ import org.photonvision.vision.target.PotentialTarget; import org.photonvision.vision.target.TrackedTarget; -/** Represents a pipeline for tracking retro-reflective targets. */ +/** + * Represents a pipeline for tracking retro-reflective targets. + */ public class ReflectivePipeline extends CVPipeline { private final RotateImagePipe rotateImagePipe = new RotateImagePipe(); @@ -78,89 +83,86 @@ public ReflectivePipeline(ReflectivePipelineSettings settings) { @Override protected void setPipeParams( - FrameStaticProperties frameStaticProperties, ReflectivePipelineSettings settings) { + FrameStaticProperties frameStaticProperties, ReflectivePipelineSettings settings) { RotateImagePipe.RotateImageParams rotateImageParams = - new RotateImagePipe.RotateImageParams(settings.inputImageRotationMode); + new RotateImagePipe.RotateImageParams(settings.inputImageRotationMode); rotateImagePipe.setParams(rotateImageParams); ErodeDilatePipe.ErodeDilateParams erodeDilateParams = - new ErodeDilatePipe.ErodeDilateParams(settings.erode, settings.dilate, 5); + new ErodeDilatePipe.ErodeDilateParams(settings.erode, settings.dilate, 5); // TODO: add kernel size to pipeline settings erodeDilatePipe.setParams(erodeDilateParams); HSVPipe.HSVParams hsvParams = - new HSVPipe.HSVParams(settings.hsvHue, settings.hsvSaturation, settings.hsvValue); + new HSVPipe.HSVParams(settings.hsvHue, settings.hsvSaturation, settings.hsvValue); hsvPipe.setParams(hsvParams); - OutputMatPipe.OutputMatParams outputMatParams = - new OutputMatPipe.OutputMatParams(settings.outputShowThresholded); - outputMatPipe.setParams(outputMatParams); - FindContoursPipe.FindContoursParams findContoursParams = - new FindContoursPipe.FindContoursParams(); + new FindContoursPipe.FindContoursParams(); findContoursPipe.setParams(findContoursParams); SpeckleRejectPipe.SpeckleRejectParams speckleRejectParams = - new SpeckleRejectPipe.SpeckleRejectParams(settings.contourSpecklePercentage); + new SpeckleRejectPipe.SpeckleRejectParams(settings.contourSpecklePercentage); speckleRejectPipe.setParams(speckleRejectParams); FilterContoursPipe.FilterContoursParams filterContoursParams = - new FilterContoursPipe.FilterContoursParams( - settings.contourArea, - settings.contourRatio, - settings.contourExtent, - frameStaticProperties); + new FilterContoursPipe.FilterContoursParams( + settings.contourArea, + settings.contourRatio, + settings.contourExtent, + frameStaticProperties); filterContoursPipe.setParams(filterContoursParams); GroupContoursPipe.GroupContoursParams groupContoursParams = - new GroupContoursPipe.GroupContoursParams( - settings.contourGroupingMode, settings.contourIntersection); + new GroupContoursPipe.GroupContoursParams( + settings.contourGroupingMode, settings.contourIntersection); groupContoursPipe.setParams(groupContoursParams); SortContoursPipe.SortContoursParams sortContoursParams = - new SortContoursPipe.SortContoursParams(settings.contourSortMode, frameStaticProperties, 5); + new SortContoursPipe.SortContoursParams(settings.contourSortMode, frameStaticProperties, 5); sortContoursPipe.setParams(sortContoursParams); Collect2dTargetsPipe.Collect2dTargetsParams collect2dTargetsParams = - new Collect2dTargetsPipe.Collect2dTargetsParams( - frameStaticProperties, - settings.offsetRobotOffsetMode, - settings.offsetDualLineM, - settings.offsetDualLineB, - settings.offsetCalibrationPoint.toPoint(), - settings.contourTargetOffsetPointEdge, - settings.contourTargetOrientation); + new Collect2dTargetsPipe.Collect2dTargetsParams( + frameStaticProperties, + settings.offsetRobotOffsetMode, + settings.offsetDualLineM, + settings.offsetDualLineB, + settings.offsetCalibrationPoint.toPoint(), + settings.contourTargetOffsetPointEdge, + settings.contourTargetOrientation); collect2dTargetsPipe.setParams(collect2dTargetsParams); var params = - new CornerDetectionPipe.CornerDetectionPipeParameters( - settings.cornerDetectionStrategy, - settings.cornerDetectionUseConvexHulls, - settings.cornerDetectionExactSideCount, - settings.cornerDetectionSideCount, - settings.cornerDetectionAccuracyPercentage); + new CornerDetectionPipe.CornerDetectionPipeParameters( + settings.cornerDetectionStrategy, + settings.cornerDetectionUseConvexHulls, + settings.cornerDetectionExactSideCount, + settings.cornerDetectionSideCount, + settings.cornerDetectionAccuracyPercentage); cornerDetectionPipe.setParams(params); Draw2dTargetsPipe.Draw2dContoursParams draw2dContoursParams = - new Draw2dTargetsPipe.Draw2dContoursParams(settings.outputShowMultipleTargets); + new Draw2dTargetsPipe.Draw2dContoursParams(settings.outputShowMultipleTargets); draw2DTargetsPipe.setParams(draw2dContoursParams); Draw2dCrosshairPipe.Draw2dCrosshairParams draw2dCrosshairParams = - new Draw2dCrosshairPipe.Draw2dCrosshairParams( - settings.offsetRobotOffsetMode, settings.offsetCalibrationPoint); + new Draw2dCrosshairPipe.Draw2dCrosshairParams( + settings.offsetRobotOffsetMode, settings.offsetCalibrationPoint); draw2dCrosshairPipe.setParams(draw2dCrosshairParams); var draw3dContoursParams = - new Draw3dTargetsPipe.Draw3dContoursParams( - settings.cameraCalibration, settings.targetModel); + new Draw3dTargetsPipe.Draw3dContoursParams( + settings.cameraCalibration, settings.targetModel); draw3dTargetsPipe.setParams(draw3dContoursParams); var solvePNPParams = - new SolvePNPPipe.SolvePNPPipeParams( - settings.cameraCalibration, settings.cameraPitch, settings.targetModel); + new SolvePNPPipe.SolvePNPPipeParams( + settings.cameraCalibration, settings.cameraPitch, settings.targetModel); solvePNPPipe.setParams(solvePNPParams); } + @SuppressWarnings("DuplicatedCode") @Override public CVPipelineResult process(Frame frame, ReflectivePipelineSettings settings) { setPipeParams(frame.frameStaticProperties, settings); @@ -180,33 +182,31 @@ public CVPipelineResult process(Frame frame, ReflectivePipelineSettings settings sumPipeNanosElapsed += hsvPipeResult.nanosElapsed; // mat leak fix attempt + // the first is the raw input mat, the second is the hsvpipe result outputMats.first = rawInputMat; outputMats.second = hsvPipeResult.result; - CVPipeResult outputMatResult = outputMatPipe.apply(outputMats); - sumPipeNanosElapsed += outputMatResult.nanosElapsed; - CVPipeResult> findContoursResult = findContoursPipe.apply(hsvPipeResult.result); sumPipeNanosElapsed += findContoursResult.nanosElapsed; CVPipeResult> speckleRejectResult = - speckleRejectPipe.apply(findContoursResult.result); + speckleRejectPipe.apply(findContoursResult.result); sumPipeNanosElapsed += speckleRejectResult.nanosElapsed; CVPipeResult> filterContoursResult = - filterContoursPipe.apply(speckleRejectResult.result); + filterContoursPipe.apply(speckleRejectResult.result); sumPipeNanosElapsed += filterContoursResult.nanosElapsed; CVPipeResult> groupContoursResult = - groupContoursPipe.apply(filterContoursResult.result); + groupContoursPipe.apply(filterContoursResult.result); sumPipeNanosElapsed += groupContoursResult.nanosElapsed; CVPipeResult> sortContoursResult = - sortContoursPipe.apply(groupContoursResult.result); + sortContoursPipe.apply(groupContoursResult.result); sumPipeNanosElapsed += sortContoursResult.nanosElapsed; CVPipeResult> collect2dTargetsResult = - collect2dTargetsPipe.apply(sortContoursResult.result); + collect2dTargetsPipe.apply(sortContoursResult.result); sumPipeNanosElapsed += collect2dTargetsResult.nanosElapsed; CVPipeResult> targetList; @@ -224,30 +224,54 @@ public CVPipelineResult process(Frame frame, ReflectivePipelineSettings settings targetList = collect2dTargetsResult; } - CVPipeResult result; + CVPipeResult drawOnInputResult, drawOnOutputResult; + + // the first is the raw input mat, the second is the hsvpipe result + // Draw on input + + CVPipeResult draw2dCrosshairResultOnInput = + draw2dCrosshairPipe.apply(Pair.of(outputMats.first, targetList.result)); + sumPipeNanosElapsed += draw2dCrosshairResultOnInput.nanosElapsed; + + CVPipeResult draw2dContoursResultOnInput = + draw2DTargetsPipe.apply( + Pair.of(draw2dCrosshairResultOnInput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += draw2dCrosshairResultOnInput.nanosElapsed; + + if (settings.solvePNPEnabled) { + drawOnInputResult = + draw3dTargetsPipe.apply( + Pair.of(draw2dContoursResultOnInput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += drawOnInputResult.nanosElapsed; + } else { + drawOnInputResult = draw2dContoursResultOnInput; + } + + // Draw on output - CVPipeResult draw2dCrosshairResult = - draw2dCrosshairPipe.apply(Pair.of(outputMatResult.result, targetList.result)); - sumPipeNanosElapsed += draw2dCrosshairResult.nanosElapsed; + Imgproc.cvtColor(outputMats.second, outputMats.second, Imgproc.COLOR_GRAY2BGR, 3); + CVPipeResult draw2dCrosshairResultOnOutput = + draw2dCrosshairPipe.apply(Pair.of(outputMats.second, targetList.result)); + sumPipeNanosElapsed += draw2dCrosshairResultOnOutput.nanosElapsed; - CVPipeResult draw2dContoursResult = - draw2DTargetsPipe.apply( - Pair.of(draw2dCrosshairResult.result, collect2dTargetsResult.result)); - sumPipeNanosElapsed += draw2dContoursResult.nanosElapsed; + CVPipeResult draw2dContoursResultOnOutput = + draw2DTargetsPipe.apply( + Pair.of(draw2dCrosshairResultOnOutput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += draw2dContoursResultOnOutput.nanosElapsed; if (settings.solvePNPEnabled) { - result = - draw3dTargetsPipe.apply( - Pair.of(draw2dCrosshairResult.result, collect2dTargetsResult.result)); - sumPipeNanosElapsed += result.nanosElapsed; + drawOnOutputResult = + draw3dTargetsPipe.apply( + Pair.of(draw2dContoursResultOnOutput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += drawOnOutputResult.nanosElapsed; } else { - result = draw2dContoursResult; + drawOnOutputResult = draw2dContoursResultOnOutput; } - // TODO: Implement all the things return new CVPipelineResult( - MathUtils.nanosToMillis(sumPipeNanosElapsed), - collect2dTargetsResult.result, - new Frame(new CVMat(result.result), frame.frameStaticProperties)); + MathUtils.nanosToMillis(sumPipeNanosElapsed), + collect2dTargetsResult.result, + new Frame(new CVMat(outputMats.second), frame.frameStaticProperties), + new Frame(new CVMat(outputMats.first), frame.frameStaticProperties)); } } diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java index 307db2ea24..a1a8be704c 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java @@ -18,6 +18,7 @@ package org.photonvision.vision.pipeline.result; import java.util.List; + import org.photonvision.vision.frame.Frame; import org.photonvision.vision.opencv.Releasable; import org.photonvision.vision.target.TrackedTarget; @@ -27,12 +28,18 @@ public class CVPipelineResult implements Releasable { public final double processingMillis; public final List targets; public final Frame outputFrame; + public final Frame inputFrame; - public CVPipelineResult(double processingMillis, List targets, Frame outputFrame) { + public CVPipelineResult(double processingMillis, List targets, Frame outputFrame, Frame inputFrame) { this.processingMillis = processingMillis; this.targets = targets; this.outputFrame = Frame.copyFrom(outputFrame); + this.inputFrame = inputFrame != null ? Frame.copyFrom(inputFrame) : null; + } + + public CVPipelineResult(double processingMillis, List targets, Frame outputFrame) { + this(processingMillis, targets, outputFrame, null); } public boolean hasTargets() { @@ -44,6 +51,7 @@ public void release() { tt.release(); } outputFrame.release(); + if(inputFrame != null) inputFrame.release(); } public double getLatencyMillis() { diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java index c99326b946..6a4c0a9ac9 100644 --- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java +++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java @@ -21,6 +21,7 @@ import edu.wpi.first.wpilibj.MedianFilter; import java.util.*; import org.apache.commons.lang3.tuple.Pair; +import org.opencv.imgcodecs.Imgcodecs; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.configuration.PhotonConfiguration; @@ -60,12 +61,13 @@ public class VisionModule { private final LinkedList frameConsumers = new LinkedList<>(); private final NTDataPublisher ntConsumer; private final int moduleIndex; - private final MJPGFrameConsumer uiStreamer; + private long lastUIResultUpdateTime = 0; private long lastRunTime = 0; private MedianFilter fpsAverager = new MedianFilter(10); - private MJPGFrameConsumer dashboardStreamer; + private MJPGFrameConsumer dashboardOutputStreamer; + private MJPGFrameConsumer dashboardInputStreamer; public VisionModule(PipelineManager pipelineManager, VisionSource visionSource, int index) { logger = @@ -84,11 +86,18 @@ public VisionModule(PipelineManager pipelineManager, VisionSource visionSource, DataChangeService.getInstance().addSubscriber(new VisionSettingChangeSubscriber()); - dashboardStreamer = - new MJPGFrameConsumer(visionSource.getSettables().getConfiguration().uniqueName); - uiStreamer = new MJPGFrameConsumer(visionSource.getSettables().getConfiguration().nickname); - addFrameConsumer(dashboardStreamer); - addFrameConsumer(uiStreamer); + dashboardOutputStreamer = + new MJPGFrameConsumer( + visionSource.getSettables().getConfiguration().uniqueName + "-output"); + dashboardInputStreamer = + new MJPGFrameConsumer(visionSource.getSettables().getConfiguration().uniqueName + "-input"); + + addResultConsumer(result -> { + dashboardInputStreamer.accept(result.inputFrame); + }); + addResultConsumer(result -> { + dashboardOutputStreamer.accept(result.outputFrame); + }); ntConsumer = new NTDataPublisher( @@ -140,7 +149,7 @@ public VisionModule(PipelineManager pipelineManager, VisionSource visionSource, setPipeline(visionSource.getSettables().getConfiguration().currentPipelineIndex); - dashboardStreamer.setFrameDivisor( + dashboardOutputStreamer.setFrameDivisor( pipelineManager.getCurrentPipelineSettings().outputFrameDivisor); } @@ -215,6 +224,11 @@ public void onDataChangeEvent(DataChangeEvent event) { setPipeline(index); saveAndBroadcast(); return; + case "selectedOutputs": + // 0 indicates normal, 1 indicates thresholded + var outputs = (ArrayList) newPropValue; + // TODO + return; } // special case for camera settables @@ -265,7 +279,7 @@ public void onDataChangeEvent(DataChangeEvent event) { // special case for extra tasks to perform after setting PipelineSettings if (propName.equals("outputFrameDivisor")) { - dashboardStreamer.setFrameDivisor( + dashboardOutputStreamer.setFrameDivisor( pipelineManager.getCurrentPipelineSettings().outputFrameDivisor); } @@ -322,10 +336,10 @@ private void setCameraNickname(String newName) { visionSource.getSettables().getConfiguration().nickname = newName; ntConsumer.updateCameraNickname(newName); - frameConsumers.remove(dashboardStreamer); - dashboardStreamer = + frameConsumers.remove(dashboardOutputStreamer); + dashboardOutputStreamer = new MJPGFrameConsumer(visionSource.getSettables().getConfiguration().nickname); - frameConsumers.add(dashboardStreamer); + frameConsumers.add(dashboardOutputStreamer); saveAndBroadcast(); } @@ -355,8 +369,9 @@ public PhotonConfiguration.UICameraConfiguration toUICameraConfig() { temp.put(k, internalMap); } ret.videoFormatList = temp; - ret.streamPort = dashboardStreamer.getCurrentStreamPort(); - // ret.uiStreamPort = uiStreamer.getCurrentStreamPort(); + ret.outputStreamPort = dashboardOutputStreamer.getCurrentStreamPort(); + ret.inputStreamPort = dashboardInputStreamer.getCurrentStreamPort(); + // ret.uiStreamPort = uiStreamer.getCurrentStreamPort(); return ret; } diff --git a/photon-server/src/main/java/org/photonvision/vision/target/TrackedTarget.java b/photon-server/src/main/java/org/photonvision/vision/target/TrackedTarget.java index 742a9e7126..a4d954cbc6 100644 --- a/photon-server/src/main/java/org/photonvision/vision/target/TrackedTarget.java +++ b/photon-server/src/main/java/org/photonvision/vision/target/TrackedTarget.java @@ -43,7 +43,7 @@ public class TrackedTarget implements Releasable { private double m_yaw; private double m_area; - private Pose2d m_robotRelativePose; + private Pose2d m_robotRelativePose = new Pose2d(); private Mat m_cameraRelativeTvec, m_cameraRelativeRvec; From 59630a0c8bc4328e654c1a4962d70d065962d13d Mon Sep 17 00:00:00 2001 From: Declan Freeman-Gleason Date: Mon, 13 Jul 2020 19:09:14 -0700 Subject: [PATCH 2/2] Run spotless --- .../vision/pipeline/CVPipelineSettings.java | 2 - .../vision/pipeline/ReflectivePipeline.java | 114 +++++++++--------- .../pipeline/result/CVPipelineResult.java | 6 +- .../vision/processes/VisionModule.java | 15 +-- 4 files changed, 66 insertions(+), 71 deletions(-) diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java index f5c51bb7e7..b8c1629c94 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java @@ -19,8 +19,6 @@ import com.fasterxml.jackson.annotation.JsonSubTypes; import com.fasterxml.jackson.annotation.JsonTypeInfo; - -import java.util.List; import java.util.Objects; import org.photonvision.vision.frame.FrameDivisor; import org.photonvision.vision.opencv.ImageFlipMode; diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java index 3fcbedc39c..3631788f50 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java @@ -18,10 +18,8 @@ package org.photonvision.vision.pipeline; import java.util.List; - import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; -import org.opencv.imgcodecs.Imgcodecs; import org.opencv.imgproc.Imgproc; import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.frame.Frame; @@ -49,9 +47,7 @@ import org.photonvision.vision.target.PotentialTarget; import org.photonvision.vision.target.TrackedTarget; -/** - * Represents a pipeline for tracking retro-reflective targets. - */ +/** Represents a pipeline for tracking retro-reflective targets. */ public class ReflectivePipeline extends CVPipeline { private final RotateImagePipe rotateImagePipe = new RotateImagePipe(); @@ -83,82 +79,82 @@ public ReflectivePipeline(ReflectivePipelineSettings settings) { @Override protected void setPipeParams( - FrameStaticProperties frameStaticProperties, ReflectivePipelineSettings settings) { + FrameStaticProperties frameStaticProperties, ReflectivePipelineSettings settings) { RotateImagePipe.RotateImageParams rotateImageParams = - new RotateImagePipe.RotateImageParams(settings.inputImageRotationMode); + new RotateImagePipe.RotateImageParams(settings.inputImageRotationMode); rotateImagePipe.setParams(rotateImageParams); ErodeDilatePipe.ErodeDilateParams erodeDilateParams = - new ErodeDilatePipe.ErodeDilateParams(settings.erode, settings.dilate, 5); + new ErodeDilatePipe.ErodeDilateParams(settings.erode, settings.dilate, 5); // TODO: add kernel size to pipeline settings erodeDilatePipe.setParams(erodeDilateParams); HSVPipe.HSVParams hsvParams = - new HSVPipe.HSVParams(settings.hsvHue, settings.hsvSaturation, settings.hsvValue); + new HSVPipe.HSVParams(settings.hsvHue, settings.hsvSaturation, settings.hsvValue); hsvPipe.setParams(hsvParams); FindContoursPipe.FindContoursParams findContoursParams = - new FindContoursPipe.FindContoursParams(); + new FindContoursPipe.FindContoursParams(); findContoursPipe.setParams(findContoursParams); SpeckleRejectPipe.SpeckleRejectParams speckleRejectParams = - new SpeckleRejectPipe.SpeckleRejectParams(settings.contourSpecklePercentage); + new SpeckleRejectPipe.SpeckleRejectParams(settings.contourSpecklePercentage); speckleRejectPipe.setParams(speckleRejectParams); FilterContoursPipe.FilterContoursParams filterContoursParams = - new FilterContoursPipe.FilterContoursParams( - settings.contourArea, - settings.contourRatio, - settings.contourExtent, - frameStaticProperties); + new FilterContoursPipe.FilterContoursParams( + settings.contourArea, + settings.contourRatio, + settings.contourExtent, + frameStaticProperties); filterContoursPipe.setParams(filterContoursParams); GroupContoursPipe.GroupContoursParams groupContoursParams = - new GroupContoursPipe.GroupContoursParams( - settings.contourGroupingMode, settings.contourIntersection); + new GroupContoursPipe.GroupContoursParams( + settings.contourGroupingMode, settings.contourIntersection); groupContoursPipe.setParams(groupContoursParams); SortContoursPipe.SortContoursParams sortContoursParams = - new SortContoursPipe.SortContoursParams(settings.contourSortMode, frameStaticProperties, 5); + new SortContoursPipe.SortContoursParams(settings.contourSortMode, frameStaticProperties, 5); sortContoursPipe.setParams(sortContoursParams); Collect2dTargetsPipe.Collect2dTargetsParams collect2dTargetsParams = - new Collect2dTargetsPipe.Collect2dTargetsParams( - frameStaticProperties, - settings.offsetRobotOffsetMode, - settings.offsetDualLineM, - settings.offsetDualLineB, - settings.offsetCalibrationPoint.toPoint(), - settings.contourTargetOffsetPointEdge, - settings.contourTargetOrientation); + new Collect2dTargetsPipe.Collect2dTargetsParams( + frameStaticProperties, + settings.offsetRobotOffsetMode, + settings.offsetDualLineM, + settings.offsetDualLineB, + settings.offsetCalibrationPoint.toPoint(), + settings.contourTargetOffsetPointEdge, + settings.contourTargetOrientation); collect2dTargetsPipe.setParams(collect2dTargetsParams); var params = - new CornerDetectionPipe.CornerDetectionPipeParameters( - settings.cornerDetectionStrategy, - settings.cornerDetectionUseConvexHulls, - settings.cornerDetectionExactSideCount, - settings.cornerDetectionSideCount, - settings.cornerDetectionAccuracyPercentage); + new CornerDetectionPipe.CornerDetectionPipeParameters( + settings.cornerDetectionStrategy, + settings.cornerDetectionUseConvexHulls, + settings.cornerDetectionExactSideCount, + settings.cornerDetectionSideCount, + settings.cornerDetectionAccuracyPercentage); cornerDetectionPipe.setParams(params); Draw2dTargetsPipe.Draw2dContoursParams draw2dContoursParams = - new Draw2dTargetsPipe.Draw2dContoursParams(settings.outputShowMultipleTargets); + new Draw2dTargetsPipe.Draw2dContoursParams(settings.outputShowMultipleTargets); draw2DTargetsPipe.setParams(draw2dContoursParams); Draw2dCrosshairPipe.Draw2dCrosshairParams draw2dCrosshairParams = - new Draw2dCrosshairPipe.Draw2dCrosshairParams( - settings.offsetRobotOffsetMode, settings.offsetCalibrationPoint); + new Draw2dCrosshairPipe.Draw2dCrosshairParams( + settings.offsetRobotOffsetMode, settings.offsetCalibrationPoint); draw2dCrosshairPipe.setParams(draw2dCrosshairParams); var draw3dContoursParams = - new Draw3dTargetsPipe.Draw3dContoursParams( - settings.cameraCalibration, settings.targetModel); + new Draw3dTargetsPipe.Draw3dContoursParams( + settings.cameraCalibration, settings.targetModel); draw3dTargetsPipe.setParams(draw3dContoursParams); var solvePNPParams = - new SolvePNPPipe.SolvePNPPipeParams( - settings.cameraCalibration, settings.cameraPitch, settings.targetModel); + new SolvePNPPipe.SolvePNPPipeParams( + settings.cameraCalibration, settings.cameraPitch, settings.targetModel); solvePNPPipe.setParams(solvePNPParams); } @@ -190,23 +186,23 @@ public CVPipelineResult process(Frame frame, ReflectivePipelineSettings settings sumPipeNanosElapsed += findContoursResult.nanosElapsed; CVPipeResult> speckleRejectResult = - speckleRejectPipe.apply(findContoursResult.result); + speckleRejectPipe.apply(findContoursResult.result); sumPipeNanosElapsed += speckleRejectResult.nanosElapsed; CVPipeResult> filterContoursResult = - filterContoursPipe.apply(speckleRejectResult.result); + filterContoursPipe.apply(speckleRejectResult.result); sumPipeNanosElapsed += filterContoursResult.nanosElapsed; CVPipeResult> groupContoursResult = - groupContoursPipe.apply(filterContoursResult.result); + groupContoursPipe.apply(filterContoursResult.result); sumPipeNanosElapsed += groupContoursResult.nanosElapsed; CVPipeResult> sortContoursResult = - sortContoursPipe.apply(groupContoursResult.result); + sortContoursPipe.apply(groupContoursResult.result); sumPipeNanosElapsed += sortContoursResult.nanosElapsed; CVPipeResult> collect2dTargetsResult = - collect2dTargetsPipe.apply(sortContoursResult.result); + collect2dTargetsPipe.apply(sortContoursResult.result); sumPipeNanosElapsed += collect2dTargetsResult.nanosElapsed; CVPipeResult> targetList; @@ -230,18 +226,18 @@ public CVPipelineResult process(Frame frame, ReflectivePipelineSettings settings // Draw on input CVPipeResult draw2dCrosshairResultOnInput = - draw2dCrosshairPipe.apply(Pair.of(outputMats.first, targetList.result)); + draw2dCrosshairPipe.apply(Pair.of(outputMats.first, targetList.result)); sumPipeNanosElapsed += draw2dCrosshairResultOnInput.nanosElapsed; CVPipeResult draw2dContoursResultOnInput = - draw2DTargetsPipe.apply( - Pair.of(draw2dCrosshairResultOnInput.result, collect2dTargetsResult.result)); + draw2DTargetsPipe.apply( + Pair.of(draw2dCrosshairResultOnInput.result, collect2dTargetsResult.result)); sumPipeNanosElapsed += draw2dCrosshairResultOnInput.nanosElapsed; if (settings.solvePNPEnabled) { drawOnInputResult = - draw3dTargetsPipe.apply( - Pair.of(draw2dContoursResultOnInput.result, collect2dTargetsResult.result)); + draw3dTargetsPipe.apply( + Pair.of(draw2dContoursResultOnInput.result, collect2dTargetsResult.result)); sumPipeNanosElapsed += drawOnInputResult.nanosElapsed; } else { drawOnInputResult = draw2dContoursResultOnInput; @@ -251,27 +247,27 @@ public CVPipelineResult process(Frame frame, ReflectivePipelineSettings settings Imgproc.cvtColor(outputMats.second, outputMats.second, Imgproc.COLOR_GRAY2BGR, 3); CVPipeResult draw2dCrosshairResultOnOutput = - draw2dCrosshairPipe.apply(Pair.of(outputMats.second, targetList.result)); + draw2dCrosshairPipe.apply(Pair.of(outputMats.second, targetList.result)); sumPipeNanosElapsed += draw2dCrosshairResultOnOutput.nanosElapsed; CVPipeResult draw2dContoursResultOnOutput = - draw2DTargetsPipe.apply( - Pair.of(draw2dCrosshairResultOnOutput.result, collect2dTargetsResult.result)); + draw2DTargetsPipe.apply( + Pair.of(draw2dCrosshairResultOnOutput.result, collect2dTargetsResult.result)); sumPipeNanosElapsed += draw2dContoursResultOnOutput.nanosElapsed; if (settings.solvePNPEnabled) { drawOnOutputResult = - draw3dTargetsPipe.apply( - Pair.of(draw2dContoursResultOnOutput.result, collect2dTargetsResult.result)); + draw3dTargetsPipe.apply( + Pair.of(draw2dContoursResultOnOutput.result, collect2dTargetsResult.result)); sumPipeNanosElapsed += drawOnOutputResult.nanosElapsed; } else { drawOnOutputResult = draw2dContoursResultOnOutput; } return new CVPipelineResult( - MathUtils.nanosToMillis(sumPipeNanosElapsed), - collect2dTargetsResult.result, - new Frame(new CVMat(outputMats.second), frame.frameStaticProperties), - new Frame(new CVMat(outputMats.first), frame.frameStaticProperties)); + MathUtils.nanosToMillis(sumPipeNanosElapsed), + collect2dTargetsResult.result, + new Frame(new CVMat(outputMats.second), frame.frameStaticProperties), + new Frame(new CVMat(outputMats.first), frame.frameStaticProperties)); } } diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java index a1a8be704c..238cb5eec3 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/result/CVPipelineResult.java @@ -18,7 +18,6 @@ package org.photonvision.vision.pipeline.result; import java.util.List; - import org.photonvision.vision.frame.Frame; import org.photonvision.vision.opencv.Releasable; import org.photonvision.vision.target.TrackedTarget; @@ -30,7 +29,8 @@ public class CVPipelineResult implements Releasable { public final Frame outputFrame; public final Frame inputFrame; - public CVPipelineResult(double processingMillis, List targets, Frame outputFrame, Frame inputFrame) { + public CVPipelineResult( + double processingMillis, List targets, Frame outputFrame, Frame inputFrame) { this.processingMillis = processingMillis; this.targets = targets; @@ -51,7 +51,7 @@ public void release() { tt.release(); } outputFrame.release(); - if(inputFrame != null) inputFrame.release(); + if (inputFrame != null) inputFrame.release(); } public double getLatencyMillis() { diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java index 6a4c0a9ac9..120687ac1d 100644 --- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java +++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java @@ -21,7 +21,6 @@ import edu.wpi.first.wpilibj.MedianFilter; import java.util.*; import org.apache.commons.lang3.tuple.Pair; -import org.opencv.imgcodecs.Imgcodecs; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.configuration.PhotonConfiguration; @@ -92,12 +91,14 @@ public VisionModule(PipelineManager pipelineManager, VisionSource visionSource, dashboardInputStreamer = new MJPGFrameConsumer(visionSource.getSettables().getConfiguration().uniqueName + "-input"); - addResultConsumer(result -> { - dashboardInputStreamer.accept(result.inputFrame); - }); - addResultConsumer(result -> { - dashboardOutputStreamer.accept(result.outputFrame); - }); + addResultConsumer( + result -> { + dashboardInputStreamer.accept(result.inputFrame); + }); + addResultConsumer( + result -> { + dashboardOutputStreamer.accept(result.outputFrame); + }); ntConsumer = new NTDataPublisher(