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

Cropping mechanism #1602

Open
wants to merge 12 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
3 changes: 2 additions & 1 deletion photon-client/package-lock.json

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

7 changes: 7 additions & 0 deletions photon-client/src/components/dashboard/ConfigOptions.vue
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@ 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 +27,10 @@ const allTabs = Object.freeze({
tabName: "Input",
component: InputTab
},
cropTab:{
tabName: "Crop",
component: CropTab
},
thresholdTab: {
tabName: "Threshold",
component: ThresholdTab
Expand Down Expand Up @@ -100,6 +106,7 @@ const getTabGroups = (): ConfigOption[][] => {
];
} else if (xl) {
return [

[allTabs.inputTab],
[allTabs.thresholdTab],
[allTabs.contoursTab, allTabs.apriltagTab, allTabs.arucoTab, allTabs.objectDetectionTab, allTabs.outputTab],
Expand Down
77 changes: 77 additions & 0 deletions photon-client/src/components/dashboard/tabs/CropTab.vue
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
<script setup lang="ts">
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
import { type AprilTagPipelineSettings, type ColoredShapePipelineSettings, PipelineType } from "@/types/PipelineTypes";

Check warning on line 3 in photon-client/src/components/dashboard/tabs/CropTab.vue

View workflow job for this annotation

GitHub Actions / PhotonClient Lint and Formatting

'ColoredShapePipelineSettings' is defined but never used
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>({

Check warning on line 16 in photon-client/src/components/dashboard/tabs/CropTab.vue

View workflow job for this annotation

GitHub Actions / PhotonClient Lint and Formatting

'static_y' is assigned a value but never used
get: () => currentPipelineSettings.value.static_y || 0,
set: (value) => useCameraSettingsStore().changeCurrentPipelineSetting({ static_y: value }, false)
});
const static_width = computed<number>({

Check warning on line 20 in photon-client/src/components/dashboard/tabs/CropTab.vue

View workflow job for this annotation

GitHub Actions / PhotonClient Lint and Formatting

'static_width' is assigned a value but never used
get: () => currentPipelineSettings.value.static_width || frame_width.value,
set: (value) => useCameraSettingsStore().changeCurrentPipelineSetting({ static_width: value - static_x.value }, false)
});
const static_height = computed<number>({

Check warning on line 24 in photon-client/src/components/dashboard/tabs/CropTab.vue

View workflow job for this annotation

GitHub Actions / PhotonClient Lint and Formatting

'static_height' is assigned a value but never used
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="currentPipelineSettings.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="currentPipelineSettings.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="currentPipelineSettings.static_width"
:slider-cols="interactiveCols"
label="Width"
tooltip="The width of the statically cropped area"
:min="1"
:max="frame_width"

/>
<pv-slider
v-model="currentPipelineSettings.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 @@ -208,6 +208,10 @@ export const DefaultColoredShapePipelineSettings: ColoredShapePipelineSettings =
};

export interface AprilTagPipelineSettings extends PipelineSettings {
static_x: number;
static_y: number;
static_width: number;
static_height: number;
pipelineType: PipelineType.AprilTag;
hammingDist: number;
numIterations: number;
Expand Down Expand Up @@ -244,7 +248,11 @@ export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = {
threads: 4,
tagFamily: AprilTagFamily.Family36h11,
doMultiTarget: false,
doSingleTargetAlways: false
doSingleTargetAlways: false,
static_x: 0,
static_y: 0,
static_width: 0,
static_height: 0
};

export interface ArucoPipelineSettings extends PipelineSettings {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,62 +15,62 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/

package org.photonvision.vision.pipe.impl;
package org.photonvision.vision.pipe.impl;

import edu.wpi.first.apriltag.AprilTagDetection;
import edu.wpi.first.apriltag.AprilTagDetector;
import java.util.List;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.opencv.Releasable;
import org.photonvision.vision.pipe.CVPipe;

public class AprilTagDetectionPipe
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionPipeParams>
implements Releasable {
private AprilTagDetector m_detector = new AprilTagDetector();

public AprilTagDetectionPipe() {
super();

m_detector.addFamily("tag16h5");
m_detector.addFamily("tag36h11");
}

@Override
protected List<AprilTagDetection> process(CVMat in) {
if (in.getMat().empty()) {
return List.of();
}

if (m_detector == null) {
throw new RuntimeException("Apriltag detector was released!");
}

var ret = m_detector.detect(in.getMat());

if (ret == null) {
return List.of();
}

return List.of(ret);
}

@Override
public void setParams(AprilTagDetectionPipeParams newParams) {
if (this.params == null || !this.params.equals(newParams)) {
m_detector.setConfig(newParams.detectorParams);
m_detector.setQuadThresholdParameters(newParams.quadParams);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sus


m_detector.clearFamilies();
m_detector.addFamily(newParams.family.getNativeName());
}

super.setParams(newParams);
}

@Override
public void release() {
m_detector.close();
m_detector = null;
}
}
import edu.wpi.first.apriltag.AprilTagDetection;
import edu.wpi.first.apriltag.AprilTagDetector;
import java.util.List;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.opencv.Releasable;
import org.photonvision.vision.pipe.CVPipe;
public class AprilTagDetectionPipe
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionPipeParams>
implements Releasable {
private AprilTagDetector m_detector = new AprilTagDetector();
public AprilTagDetectionPipe() {
super();
m_detector.addFamily("tag16h5");
m_detector.addFamily("tag36h11");
}
@Override
protected List<AprilTagDetection> process(CVMat in) {
if (in.getMat().empty()) {
return List.of();
}
if (m_detector == null) {
throw new RuntimeException("Apriltag detector was released!");
}
var ret = m_detector.detect(in.getMat());
if (ret == null) {
return List.of();
}
return List.of(ret);
}
@Override
public void setParams(AprilTagDetectionPipeParams newParams) {
if (this.params == null || !this.params.equals(newParams)) {
m_detector.setConfig(newParams.detectorParams);

m_detector.clearFamilies();
m_detector.addFamily(newParams.family.getNativeName());
}

super.setParams(newParams);
}

@Override
public void release() {
m_detector.close();
m_detector = null;
}
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This file should not have changed.

Original file line number Diff line number Diff line change
Expand Up @@ -15,48 +15,39 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/

package org.photonvision.vision.pipe.impl;
package org.photonvision.vision.pipe.impl;

import edu.wpi.first.apriltag.AprilTagDetector;
import org.photonvision.vision.apriltag.AprilTagFamily;

public class AprilTagDetectionPipeParams {
public final AprilTagFamily family;
public final AprilTagDetector.Config detectorParams;
public final AprilTagDetector.QuadThresholdParameters quadParams;

public AprilTagDetectionPipeParams(
AprilTagFamily tagFamily,
AprilTagDetector.Config config,
AprilTagDetector.QuadThresholdParameters quadParams) {
this.family = tagFamily;
this.detectorParams = config;
this.quadParams = quadParams;
}

@Override
public int hashCode() {
final int prime = 31;
int result = 1;
result = prime * result + ((family == null) ? 0 : family.hashCode());
result = prime * result + ((detectorParams == null) ? 0 : detectorParams.hashCode());
result = prime * result + ((quadParams == null) ? 0 : quadParams.hashCode());
return result;
}

@Override
public boolean equals(Object obj) {
if (this == obj) return true;
if (obj == null) return false;
if (getClass() != obj.getClass()) return false;
AprilTagDetectionPipeParams other = (AprilTagDetectionPipeParams) obj;
if (family != other.family) return false;
if (detectorParams == null) {
if (other.detectorParams != null) return false;
} else if (!detectorParams.equals(other.detectorParams)) return false;
if (quadParams == null) {
if (other.quadParams != null) return false;
} else if (!quadParams.equals(other.quadParams)) return false;
return true;
}
}
import edu.wpi.first.apriltag.AprilTagDetector;
import org.photonvision.vision.apriltag.AprilTagFamily;

public class AprilTagDetectionPipeParams {
public final AprilTagFamily family;
public final AprilTagDetector.Config detectorParams;

public AprilTagDetectionPipeParams(AprilTagFamily tagFamily, AprilTagDetector.Config config) {
this.family = tagFamily;
this.detectorParams = config;
}

@Override
public int hashCode() {
final int prime = 31;
int result = 1;
result = prime * result + ((family == null) ? 0 : family.hashCode());
result = prime * result + ((detectorParams == null) ? 0 : detectorParams.hashCode());
return result;
}

@Override
public boolean equals(Object obj) {
if (this == obj) return true;
if (obj == null) return false;
if (getClass() != obj.getClass()) return false;
AprilTagDetectionPipeParams other = (AprilTagDetectionPipeParams) obj;
if (family != other.family) return false;
if (detectorParams == null) {
return other.detectorParams == null;
} else return detectorParams.equals(other.detectorParams);
}
}

Loading
Loading