From 8b46ad1cab06a29ca7132df87d13197cb647a5be Mon Sep 17 00:00:00 2001 From: Declan Freeman-Gleason Date: Mon, 13 Jul 2020 19:34:31 -0700 Subject: [PATCH] UI Redesign (#22) * Rework UI into a new, responsive layout * Send two streams (only one is currently downscaled) --- 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 | 402 ++++++++++++------ .../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/ReflectivePipeline.java | 60 ++- .../pipeline/result/CVPipelineResult.java | 10 +- .../vision/processes/VisionModule.java | 44 +- .../vision/target/TrackedTarget.java | 2 +- 29 files changed, 945 insertions(+), 559 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 1ab43d09f..ca605bde5 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 da34cc3f2..ec0597198 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 d78d3ea65..3f856f260 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 c1dc30af8..da38d23b0 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 class PhotonConfiguration { 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 f94f034a9..9fdb11a0e 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 class MJPGFrameConsumer implements FrameConsumer { @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/ReflectivePipeline.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java index 58973f9ed..3631788f5 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 @@ -20,6 +20,7 @@ package org.photonvision.vision.pipeline; import java.util.List; import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; +import org.opencv.imgproc.Imgproc; import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameStaticProperties; @@ -92,10 +93,6 @@ public class ReflectivePipeline extends CVPipeline outputMatResult = outputMatPipe.apply(outputMats); - sumPipeNanosElapsed += outputMatResult.nanosElapsed; - CVPipeResult> findContoursResult = findContoursPipe.apply(hsvPipeResult.result); sumPipeNanosElapsed += findContoursResult.nanosElapsed; @@ -224,30 +220,54 @@ public class ReflectivePipeline extends CVPipeline result; + CVPipeResult drawOnInputResult, drawOnOutputResult; - CVPipeResult draw2dCrosshairResult = - draw2dCrosshairPipe.apply(Pair.of(outputMatResult.result, targetList.result)); - sumPipeNanosElapsed += draw2dCrosshairResult.nanosElapsed; + // the first is the raw input mat, the second is the hsvpipe result + // Draw on input - CVPipeResult draw2dContoursResult = + CVPipeResult draw2dCrosshairResultOnInput = + draw2dCrosshairPipe.apply(Pair.of(outputMats.first, targetList.result)); + sumPipeNanosElapsed += draw2dCrosshairResultOnInput.nanosElapsed; + + CVPipeResult draw2dContoursResultOnInput = draw2DTargetsPipe.apply( - Pair.of(draw2dCrosshairResult.result, collect2dTargetsResult.result)); - sumPipeNanosElapsed += draw2dContoursResult.nanosElapsed; + Pair.of(draw2dCrosshairResultOnInput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += draw2dCrosshairResultOnInput.nanosElapsed; if (settings.solvePNPEnabled) { - result = + drawOnInputResult = draw3dTargetsPipe.apply( - Pair.of(draw2dCrosshairResult.result, collect2dTargetsResult.result)); - sumPipeNanosElapsed += result.nanosElapsed; + Pair.of(draw2dContoursResultOnInput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += drawOnInputResult.nanosElapsed; } else { - result = draw2dContoursResult; + drawOnInputResult = draw2dContoursResultOnInput; + } + + // Draw on output + + Imgproc.cvtColor(outputMats.second, outputMats.second, Imgproc.COLOR_GRAY2BGR, 3); + CVPipeResult draw2dCrosshairResultOnOutput = + draw2dCrosshairPipe.apply(Pair.of(outputMats.second, targetList.result)); + sumPipeNanosElapsed += draw2dCrosshairResultOnOutput.nanosElapsed; + + CVPipeResult draw2dContoursResultOnOutput = + draw2DTargetsPipe.apply( + Pair.of(draw2dCrosshairResultOnOutput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += draw2dContoursResultOnOutput.nanosElapsed; + + if (settings.solvePNPEnabled) { + drawOnOutputResult = + draw3dTargetsPipe.apply( + Pair.of(draw2dContoursResultOnOutput.result, collect2dTargetsResult.result)); + sumPipeNanosElapsed += drawOnOutputResult.nanosElapsed; + } else { + drawOnOutputResult = draw2dContoursResultOnOutput; } - // TODO: Implement all the things return new CVPipelineResult( MathUtils.nanosToMillis(sumPipeNanosElapsed), collect2dTargetsResult.result, - new Frame(new CVMat(result.result), frame.frameStaticProperties)); + 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 307db2ea2..238cb5eec 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 @@ -27,12 +27,19 @@ 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 class CVPipelineResult implements Releasable { 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 c99326b94..120687ac1 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 @@ -60,12 +60,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 +85,20 @@ public class VisionModule { 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 +150,7 @@ public class VisionModule { setPipeline(visionSource.getSettables().getConfiguration().currentPipelineIndex); - dashboardStreamer.setFrameDivisor( + dashboardOutputStreamer.setFrameDivisor( pipelineManager.getCurrentPipelineSettings().outputFrameDivisor); } @@ -215,6 +225,11 @@ public class VisionModule { 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 +280,7 @@ public class VisionModule { // special case for extra tasks to perform after setting PipelineSettings if (propName.equals("outputFrameDivisor")) { - dashboardStreamer.setFrameDivisor( + dashboardOutputStreamer.setFrameDivisor( pipelineManager.getCurrentPipelineSettings().outputFrameDivisor); } @@ -322,10 +337,10 @@ public class VisionModule { 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 +370,9 @@ public class VisionModule { 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 742a9e712..a4d954cbc 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;