Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Static cropping #1610

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2,772 changes: 1,817 additions & 955 deletions photon-client/package-lock.json

Large diffs are not rendered by default.

10 changes: 8 additions & 2 deletions photon-client/src/components/dashboard/ConfigOptions.vue
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ import ThresholdTab from "@/components/dashboard/tabs/ThresholdTab.vue";
import ContoursTab from "@/components/dashboard/tabs/ContoursTab.vue";
import AprilTagTab from "@/components/dashboard/tabs/AprilTagTab.vue";
import ArucoTab from "@/components/dashboard/tabs/ArucoTab.vue";
import CropTab from "./tabs/CropTab.vue";
import ObjectDetectionTab from "@/components/dashboard/tabs/ObjectDetectionTab.vue";
import OutputTab from "@/components/dashboard/tabs/OutputTab.vue";
import TargetsTab from "@/components/dashboard/tabs/TargetsTab.vue";
Expand All @@ -25,6 +26,10 @@ const allTabs = Object.freeze({
tabName: "Input",
component: InputTab
},
cropTab: {
tabName: "Crop",
component: CropTab
},
thresholdTab: {
tabName: "Threshold",
component: ThresholdTab
Expand Down Expand Up @@ -76,6 +81,7 @@ const getTabGroups = (): ConfigOption[][] => {
return [
[
allTabs.inputTab,
allTabs.cropTab,
allTabs.thresholdTab,
allTabs.contoursTab,
allTabs.apriltagTab,
Expand All @@ -87,7 +93,7 @@ const getTabGroups = (): ConfigOption[][] => {
];
} else if (lgAndDown) {
return [
[allTabs.inputTab],
[allTabs.inputTab, allTabs.cropTab],
[
allTabs.thresholdTab,
allTabs.contoursTab,
Expand All @@ -100,7 +106,7 @@ const getTabGroups = (): ConfigOption[][] => {
];
} else if (xl) {
return [
[allTabs.inputTab],
[allTabs.inputTab, allTabs.cropTab],
[allTabs.thresholdTab],
[allTabs.contoursTab, allTabs.apriltagTab, allTabs.arucoTab, allTabs.objectDetectionTab, allTabs.outputTab],
[allTabs.targetsTab, allTabs.pnpTab, allTabs.map3dTab]
Expand Down
73 changes: 73 additions & 0 deletions photon-client/src/components/dashboard/tabs/CropTab.vue
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
<script setup lang="ts">
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
import { type AprilTagPipelineSettings, PipelineType } from "@/types/PipelineTypes";
import PvSlider from "@/components/common/pv-slider.vue";
import { computed, getCurrentInstance } from "vue";
import { useStateStore } from "@/stores/StateStore";
const currentPipelineSettings = computed<AprilTagPipelineSettings>(
() => useCameraSettingsStore().currentPipelineSettings as AprilTagPipelineSettings
);
const frame_width = computed(() => useCameraSettingsStore().currentVideoFormat.resolution.width);
const frame_height = computed(() => useCameraSettingsStore().currentVideoFormat.resolution.height);
const static_x = computed<number>({
get: () => currentPipelineSettings.value.static_x || 0,
set: (value) => useCameraSettingsStore().changeCurrentPipelineSetting({ static_x: value }, false)
});
const static_y = computed<number>({
get: () => currentPipelineSettings.value.static_y || 0,
set: (value) => useCameraSettingsStore().changeCurrentPipelineSetting({ static_y: value }, false)
});
const static_width = computed<number>({
get: () => currentPipelineSettings.value.static_width || frame_width.value,
set: (value) => useCameraSettingsStore().changeCurrentPipelineSetting({ static_width: value }, false)
});
const static_height = computed<number>({
get: () => currentPipelineSettings.value.static_height || frame_height.value,
set: (value) => useCameraSettingsStore().changeCurrentPipelineSetting({ static_height: value }, false)
});
const interactiveCols = computed(() =>
(getCurrentInstance()?.proxy.$vuetify.breakpoint.mdAndDown || false) &&
(!useStateStore().sidebarFolded || useCameraSettingsStore().isDriverMode)
? 9
: 8
);
</script>
<template>
<div v-if="currentPipelineSettings.pipelineType === PipelineType.AprilTag">
<!-- static crop -->
<span>Static Crop</span>
<pv-slider
v-model="static_x"
class="pt-2"
:slider-cols="interactiveCols"
label="X"
tooltip="The X coordinate of the top left corner of the statically cropped area"
:min="0"
:max="frame_width"
/>
<pv-slider
v-model="static_y"
:slider-cols="interactiveCols"
label="Y"
tooltip="The Y coordinate of the top left corner of the statically cropped area"
:min="0"
:max="frame_height"
/>
<pv-slider
v-model="static_width"
:slider-cols="interactiveCols"
label="Width"
tooltip="The width of the statically cropped area"
:min="1"
:max="frame_width"
/>
<pv-slider
v-model="static_height"
:slider-cols="interactiveCols"
label="Height"
tooltip="The height of the statically cropped area"
:min="1"
:max="frame_height"
/>
</div>
</template>
10 changes: 9 additions & 1 deletion photon-client/src/types/PipelineTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,10 @@ export interface PipelineSettings {

cameraAutoWhiteBalance: boolean;
cameraWhiteBalanceTemp: number;
static_x: number;
static_y: number;
static_width: number;
static_height: number;
}
export type ConfigurablePipelineSettings = Partial<
Omit<
Expand Down Expand Up @@ -144,7 +148,11 @@ export const DefaultPipelineSettings: Omit<
cameraAutoWhiteBalance: false,
cameraWhiteBalanceTemp: 4000,
cameraMinExposureRaw: 1,
cameraMaxExposureRaw: 2
cameraMaxExposureRaw: 2,
static_x: 0,
static_y: 0,
static_width: 0,
static_height: 0
};

export interface ReflectivePipelineSettings extends PipelineSettings {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
/*
* Copyright (C) Photon Vision.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed mat the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonvision.vision.pipe.impl;

import edu.wpi.first.math.MathUtil;
import org.opencv.core.Mat;
import org.opencv.core.Rect;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.pipe.CVPipe;

public class CropPipe extends CVPipe<CVMat, CVMat, Rect> {
public CropPipe() {
this.params = new Rect(0, 0, Integer.MAX_VALUE, Integer.MAX_VALUE);
}

@Override
protected CVMat process(CVMat in) {
Mat mat = in.getMat();
if (fullyCovers(params, mat)) {
return in;
}

int x = MathUtil.clamp(params.x, 0, mat.width());
int y = MathUtil.clamp(params.y, 0, mat.height());
int width = MathUtil.clamp(params.width, 0, mat.width() - x);
int height = MathUtil.clamp(params.height, 0, mat.height() - y);

return new CVMat(mat.submat(y, y + height, x, x + width));
}

/**
* Returns true if the given rectangle fully covers some given image.
*
* @param rect The rectangle to check.
* @param mat The image to check.
* @return boolean
*/
public static boolean fullyCovers(Rect rect, Mat mat) {
return rect.x <= 0 && rect.y <= 0 && rect.width >= mat.width() && rect.height >= mat.height();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
/*
* Copyright (C) Photon Vision.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/

package org.photonvision.vision.pipe.impl;

import edu.wpi.first.math.MathUtil;
import org.opencv.core.Mat;
import org.opencv.core.Rect;
import org.opencv.core.Scalar;
import org.opencv.imgproc.Imgproc;
import org.photonvision.vision.pipe.MutatingPipe;

public class DrawRectanglePipe
extends MutatingPipe<Mat, DrawRectanglePipe.DrawRectanglePipeParams> {
Scalar color;

public DrawRectanglePipe(Scalar color) {
super();
this.params = new DrawRectanglePipeParams();
this.color = color;
}

@Override
protected Void process(Mat in) {
// Draw nothing if the rectangle fully covers the image
if (CropPipe.fullyCovers(params.rect, in)) {
return null;
}

int x = MathUtil.clamp(params.rect.x, 0, in.width());
int y = MathUtil.clamp(params.rect.y, 0, in.height());
int width = MathUtil.clamp(params.rect.width, 0, in.width() - x);
int height = MathUtil.clamp(params.rect.height, 0, in.height() - y);
Rect rect = new Rect(x, y, width, height);

Imgproc.rectangle(in, rect, this.color, params.thickness);
return null;
}

public static class DrawRectanglePipeParams {
public Rect rect = new Rect(0, 0, Integer.MAX_VALUE, Integer.MAX_VALUE);
public int thickness = 2;

public DrawRectanglePipeParams() {}

public DrawRectanglePipeParams(Rect rect) {
this.rect = rect;
}

public DrawRectanglePipeParams(int x, int y, int width, int height) {
this(new Rect(x, y, width, height));
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

import java.util.Objects;
import org.opencv.core.Point;
import org.opencv.core.Rect;
import org.photonvision.common.util.numbers.DoubleCouple;
import org.photonvision.common.util.numbers.IntegerCouple;
import org.photonvision.vision.opencv.ContourGroupingMode;
Expand Down Expand Up @@ -90,6 +91,16 @@ public AdvancedPipelineSettings() {
public int cornerDetectionSideCount = 4;
public double cornerDetectionAccuracyPercentage = 10;

// Static cropping settings
public int static_x = 0;
public int static_y = 0;
public int static_width = Integer.MAX_VALUE;
public int static_height = Integer.MAX_VALUE;

public Rect getStaticCrop() {
return new Rect(static_x, static_y, static_width, static_height);
}

@Override
public boolean equals(Object o) {
if (this == o) return true;
Expand Down Expand Up @@ -124,7 +135,11 @@ public boolean equals(Object o) {
&& contourGroupingMode == that.contourGroupingMode
&& contourIntersection == that.contourIntersection
&& Objects.equals(targetModel, that.targetModel)
&& cornerDetectionStrategy == that.cornerDetectionStrategy;
&& cornerDetectionStrategy == that.cornerDetectionStrategy
&& static_x == that.static_x
&& static_y == that.static_y
&& static_width == that.static_width
&& static_height == that.static_height;
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,26 +29,31 @@
import java.util.ArrayList;
import java.util.List;
import java.util.Optional;
import org.opencv.core.Point;
import org.opencv.core.Rect;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.util.math.MathUtils;
import org.photonvision.estimation.TargetModel;
import org.photonvision.targeting.MultiTargetPNPResult;
import org.photonvision.vision.apriltag.AprilTagFamily;
import org.photonvision.vision.frame.Frame;
import org.photonvision.vision.frame.FrameThresholdType;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.pipe.CVPipe.CVPipeResult;
import org.photonvision.vision.pipe.impl.AprilTagDetectionPipe;
import org.photonvision.vision.pipe.impl.AprilTagDetectionPipeParams;
import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe;
import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams;
import org.photonvision.vision.pipe.impl.CalculateFPSPipe;
import org.photonvision.vision.pipe.impl.CropPipe;
import org.photonvision.vision.pipe.impl.MultiTargetPNPPipe;
import org.photonvision.vision.pipe.impl.MultiTargetPNPPipe.MultiTargetPNPPipeParams;
import org.photonvision.vision.pipeline.result.CVPipelineResult;
import org.photonvision.vision.target.TrackedTarget;
import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters;

public class AprilTagPipeline extends CVPipeline<CVPipelineResult, AprilTagPipelineSettings> {
private final CropPipe cropPipe = new CropPipe();
private final AprilTagDetectionPipe aprilTagDetectionPipe = new AprilTagDetectionPipe();
private final AprilTagPoseEstimatorPipe singleTagPoseEstimatorPipe =
new AprilTagPoseEstimatorPipe();
Expand All @@ -69,6 +74,9 @@ public AprilTagPipeline(AprilTagPipelineSettings settings) {

@Override
protected void setPipeParamsImpl() {
Rect staticCrop = settings.getStaticCrop();
cropPipe.setParams(staticCrop);

// Sanitize thread count - not supported to have fewer than 1 threads
settings.threads = Math.max(1, settings.threads);

Expand Down Expand Up @@ -134,8 +142,11 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting
return new CVPipelineResult(frame.sequenceID, 0, 0, List.of(), frame);
}

CVPipeResult<CVMat> croppedFrame = cropPipe.run(frame.processedImage);
sumPipeNanosElapsed += croppedFrame.nanosElapsed;

CVPipeResult<List<AprilTagDetection>> tagDetectionPipeResult;
tagDetectionPipeResult = aprilTagDetectionPipe.run(frame.processedImage);
tagDetectionPipeResult = aprilTagDetectionPipe.run(croppedFrame.output);
sumPipeNanosElapsed += tagDetectionPipeResult.nanosElapsed;

List<AprilTagDetection> detections = tagDetectionPipeResult.output;
Expand All @@ -157,8 +168,8 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting
new TrackedTarget(
detection,
null,
new TargetCalculationParameters(
false, null, null, null, null, frameStaticProperties));
new TargetCalculationParameters(false, null, null, null, null, frameStaticProperties),
new Point(settings.getStaticCrop().x, settings.getStaticCrop().y));

targetList.add(target);
}
Expand Down Expand Up @@ -216,7 +227,8 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting
detection,
tagPoseEstimate,
new TargetCalculationParameters(
false, null, null, null, null, frameStaticProperties));
false, null, null, null, null, frameStaticProperties),
new Point(settings.getStaticCrop().x, settings.getStaticCrop().y));

var correctedBestPose =
MathUtils.convertOpenCVtoPhotonTransform(target.getBestCameraToTarget3d());
Expand Down
Loading
Loading