Skip to content

Commit

Permalink
Merge branch 'master' into 2023-10-15_36h11-model
Browse files Browse the repository at this point in the history
  • Loading branch information
mcm001 committed Oct 25, 2023
2 parents 386d337 + df45bc2 commit 9b4fbc4
Show file tree
Hide file tree
Showing 20 changed files with 744 additions and 392 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -151,8 +151,8 @@ const pipelineTypesWrapper = computed<{ name: string; value: number }[]>(() => {
const pipelineTypes = [
{ name: "Reflective", value: WebsocketPipelineType.Reflective },
{ name: "Colored Shape", value: WebsocketPipelineType.ColoredShape },
{ name: "AprilTag", value: WebsocketPipelineType.AprilTag }
// { name: "Aruco", value: WebsocketPipelineType.Aruco }
{ name: "AprilTag", value: WebsocketPipelineType.AprilTag },
{ name: "Aruco", value: WebsocketPipelineType.Aruco }
];
if (useCameraSettingsStore().isDriverMode) {
Expand Down Expand Up @@ -353,8 +353,8 @@ useCameraSettingsStore().$subscribe((mutation, state) => {
:items="[
{ name: 'Reflective', value: WebsocketPipelineType.Reflective },
{ name: 'Colored Shape', value: WebsocketPipelineType.ColoredShape },
{ name: 'AprilTag', value: WebsocketPipelineType.AprilTag }
// { name: 'Aruco', value: WebsocketPipelineType.Aruco }
{ name: 'AprilTag', value: WebsocketPipelineType.AprilTag },
{ name: 'Aruco', value: WebsocketPipelineType.Aruco }
]"
/>
</v-card-text>
Expand Down
68 changes: 47 additions & 21 deletions photon-client/src/components/dashboard/tabs/ArucoTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
import { PipelineType } from "@/types/PipelineTypes";
import PvSlider from "@/components/common/pv-slider.vue";
import PvSwitch from "@/components/common/pv-switch.vue";
import PvRangeSlider from "@/components/common/pv-range-slider.vue";
import PvSelect from "@/components/common/pv-select.vue";
import { computed, getCurrentInstance } from "vue";
import { useStateStore } from "@/stores/StateStore";
Expand All @@ -20,37 +23,60 @@ const interactiveCols = computed(

<template>
<div v-if="currentPipelineSettings.pipelineType === PipelineType.Aruco">
<pv-slider
v-model="currentPipelineSettings.decimate"
<pv-select
v-model="currentPipelineSettings.tagFamily"
label="Target family"
:items="['AprilTag Family 36h11', 'AprilTag Family 25h9', 'AprilTag Family 16h5']"
:select-cols="interactiveCols"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ tagFamily: value }, false)"
/>
<pv-switch
v-model="currentPipelineSettings.useCornerRefinement"
class="pt-2"
label="Refine Corners"
tooltip="Further refine the initial corners with subpixel accuracy."
:switch-cols="interactiveCols"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ useCornerRefinement: value }, false)"
/>
<pv-range-slider
v-model="currentPipelineSettings.threshWinSizes"
label="Thresh Min/Max Size"
tooltip="The minimum and maximum adaptive threshold window size. Larger windows tend more towards global thresholding, but small windows can be weak to noise."
:min="3"
:max="255"
:slider-cols="interactiveCols"
label="Decimate"
tooltip="Increases FPS at the expense of range by reducing image resolution initially"
:min="1"
:max="8"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ decimate: value }, false)"
:step="2"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshWinSizes: value }, false)"
/>
<pv-slider
v-model="currentPipelineSettings.numIterations"
v-model="currentPipelineSettings.threshStepSize"
class="pt-2"
:slider-cols="interactiveCols"
label="Corner Iterations"
tooltip="How many iterations are going to be used in order to refine corners. Higher values are lead to more accuracy at the cost of performance"
:min="30"
:max="1000"
:step="5"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ numIterations: value }, false)"
label="Thresh Step Size"
tooltip="Smaller values will cause more steps between the min/max sizes. More, varied steps can improve detection robustness to lighting, but may decrease performance."
:min="2"
:max="128"
:step="1"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshStepSize: value }, false)"
/>
<pv-slider
v-model="currentPipelineSettings.cornerAccuracy"
v-model="currentPipelineSettings.threshConstant"
class="pt-2"
:slider-cols="interactiveCols"
label="Corner Accuracy"
tooltip="Minimum accuracy for the corners, lower is better but more performance intensive "
:min="0.01"
:max="100"
:step="0.01"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ cornerAccuracy: value }, false)"
label="Thresh Constant"
tooltip="Affects the threshold window mean value cutoff for all steps. Higher values can improve performance, but may harm detection rate."
:min="0"
:max="128"
:step="1"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshConstant: value }, false)"
/>
<pv-switch
v-model="currentPipelineSettings.debugThreshold"
class="pt-2"
label="Debug Threshold"
tooltip="Display the first threshold step to the color stream."
:switch-cols="interactiveCols"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ debugThreshold: value }, false)"
/>
</div>
</template>
6 changes: 4 additions & 2 deletions photon-client/src/components/dashboard/tabs/OutputTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,8 @@ const interactiveCols = computed(
/>
<pv-switch
v-if="
currentPipelineSettings.pipelineType === PipelineType.AprilTag &&
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
"
Expand All @@ -99,7 +100,8 @@ const interactiveCols = computed(
/>
<pv-switch
v-if="
currentPipelineSettings.pipelineType === PipelineType.AprilTag &&
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
"
Expand Down
9 changes: 6 additions & 3 deletions photon-client/src/components/dashboard/tabs/TargetsTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ const currentPipelineSettings = useCameraSettingsStore().currentPipelineSettings
</template>
<template
v-if="
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag &&
(useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag ||
useCameraSettingsStore().currentPipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
"
>
Expand Down Expand Up @@ -67,7 +68,8 @@ const currentPipelineSettings = useCameraSettingsStore().currentPipelineSettings
</template>
<template
v-if="
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag &&
(useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag ||
useCameraSettingsStore().currentPipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
"
>
Expand All @@ -80,7 +82,8 @@ const currentPipelineSettings = useCameraSettingsStore().currentPipelineSettings
</v-row>
<v-row
v-if="
currentPipelineSettings.pipelineType === PipelineType.AprilTag &&
(useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag ||
useCameraSettingsStore().currentPipelineType === PipelineType.Aruco) &&
currentPipelineSettings.doMultiTarget &&
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
Expand Down
35 changes: 26 additions & 9 deletions photon-client/src/types/PipelineTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -246,11 +246,22 @@ export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = {

export interface ArucoPipelineSettings extends PipelineSettings {
pipelineType: PipelineType.Aruco;
decimate: number;
threads: number;
numIterations: number;
cornerAccuracy: number;

tagFamily: AprilTagFamily;

threshWinSizes: WebsocketNumberPair | [number, number];
threshStepSize: number;
threshConstant: number;
debugThreshold: boolean;

useCornerRefinement: boolean;

useAruco3: boolean;
aruco3MinMarkerSideRatio: number;
aruco3MinCanonicalImgSide: number;

doMultiTarget: boolean;
doSingleTargetAlways: boolean;
}
export type ConfigurableArucoPipelineSettings = Partial<Omit<ArucoPipelineSettings, "pipelineType">> &
ConfigurablePipelineSettings;
Expand All @@ -263,11 +274,17 @@ export const DefaultArucoPipelineSettings: ArucoPipelineSettings = {
ledMode: false,
pipelineType: PipelineType.Aruco,

decimate: 1,
threads: 2,
numIterations: 100,
cornerAccuracy: 25,
useAruco3: true
tagFamily: AprilTagFamily.Family16h5,
threshWinSizes: { first: 11, second: 91 },
threshStepSize: 40,
threshConstant: 10,
debugThreshold: false,
useCornerRefinement: true,
useAruco3: false,
aruco3MinMarkerSideRatio: 0.02,
aruco3MinCanonicalImgSide: 32,
doMultiTarget: false,
doSingleTargetAlways: false
};

export type ActivePipelineSettings =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@
import org.zeroturnaround.zip.ZipUtil;

public class ConfigManager {
private static final Logger logger = new Logger(ConfigManager.class, LogGroup.General);
private static ConfigManager INSTANCE;

public static final String HW_CFG_FNAME = "hardwareConfig.json";
Expand Down Expand Up @@ -79,6 +78,8 @@ public static ConfigManager getInstance() {
return INSTANCE;
}

private static final Logger logger = new Logger(ConfigManager.class, LogGroup.General);

private void translateLegacyIfPresent(Path folderPath) {
if (!(m_provider instanceof SqlConfigProvider)) {
// Cannot import into SQL if we aren't in SQL mode rn
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,36 +24,24 @@
public class ArucoDetectionResult {
private static final Logger logger =
new Logger(ArucoDetectionResult.class, LogGroup.VisionModule);
double[] xCorners;
double[] yCorners;

int id;
private final double[] xCorners;
private final double[] yCorners;

double[] tvec, rvec;
private final int id;

public ArucoDetectionResult(
double[] xCorners, double[] yCorners, int id, double[] tvec, double[] rvec) {
public ArucoDetectionResult(double[] xCorners, double[] yCorners, int id) {
this.xCorners = xCorners;
this.yCorners = yCorners;
this.id = id;
this.tvec = tvec;
this.rvec = rvec;
// logger.debug("Creating a new detection result: " + this.toString());
}

public double[] getTvec() {
return tvec;
}

public double[] getRvec() {
return rvec;
}

public double[] getxCorners() {
public double[] getXCorners() {
return xCorners;
}

public double[] getyCorners() {
public double[] getYCorners() {
return yCorners;
}

Expand All @@ -62,11 +50,11 @@ public int getId() {
}

public double getCenterX() {
return (xCorners[0] + xCorners[1] + xCorners[2] + xCorners[3]) * .25;
return (xCorners[0] + xCorners[1] + xCorners[2] + xCorners[3]) / 4.0;
}

public double getCenterY() {
return (yCorners[0] + yCorners[1] + yCorners[2] + yCorners[3]) * .25;
return (yCorners[0] + yCorners[1] + yCorners[2] + yCorners[3]) / 4.0;
}

@Override
Expand Down

This file was deleted.

Loading

0 comments on commit 9b4fbc4

Please sign in to comment.