Skip to content

Commit 810d3ad

Browse files
authored
Merge pull request #1 from FRC-Team-4143/cuda
Cuda
2 parents 0179615 + 4c5a6d9 commit 810d3ad

20 files changed

+709
-13
lines changed

photon-client/src/components/dashboard/CameraAndPipelineSelectCard.vue

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,7 @@ const validNewPipelineTypes = computed(() => {
130130
{ name: "Reflective", value: WebsocketPipelineType.Reflective },
131131
{ name: "Colored Shape", value: WebsocketPipelineType.ColoredShape },
132132
{ name: "AprilTag", value: WebsocketPipelineType.AprilTag },
133+
{ name: "AprilTagCuda", value: WebsocketPipelineType.AprilTagCuda },
133134
{ name: "Aruco", value: WebsocketPipelineType.Aruco }
134135
];
135136
if (useSettingsStore().general.supportedBackends.length > 0) {
@@ -168,6 +169,7 @@ const pipelineTypesWrapper = computed<{ name: string; value: number }[]>(() => {
168169
{ name: "Reflective", value: WebsocketPipelineType.Reflective },
169170
{ name: "Colored Shape", value: WebsocketPipelineType.ColoredShape },
170171
{ name: "AprilTag", value: WebsocketPipelineType.AprilTag },
172+
{ name: "AprilTagCuda", value: WebsocketPipelineType.AprilTagCuda },
171173
{ name: "Aruco", value: WebsocketPipelineType.Aruco }
172174
];
173175
if (useSettingsStore().general.supportedBackends.length > 0) {
@@ -224,6 +226,9 @@ useCameraSettingsStore().$subscribe((mutation, state) => {
224226
case PipelineType.AprilTag:
225227
pipelineType.value = WebsocketPipelineType.AprilTag;
226228
break;
229+
case PipelineType.AprilTagCuda:
230+
pipelineType.value = WebsocketPipelineType.AprilTagCuda;
231+
break;
227232
case PipelineType.Aruco:
228233
pipelineType.value = WebsocketPipelineType.Aruco;
229234
break;

photon-client/src/components/dashboard/ConfigOptions.vue

Lines changed: 13 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ import InputTab from "@/components/dashboard/tabs/InputTab.vue";
77
import ThresholdTab from "@/components/dashboard/tabs/ThresholdTab.vue";
88
import ContoursTab from "@/components/dashboard/tabs/ContoursTab.vue";
99
import AprilTagTab from "@/components/dashboard/tabs/AprilTagTab.vue";
10+
import AprilTagCudaTab from "@/components/dashboard/tabs/AprilTagCudaTab.vue";
1011
import ArucoTab from "@/components/dashboard/tabs/ArucoTab.vue";
1112
import ObjectDetectionTab from "@/components/dashboard/tabs/ObjectDetectionTab.vue";
1213
import OutputTab from "@/components/dashboard/tabs/OutputTab.vue";
@@ -37,6 +38,10 @@ const allTabs = Object.freeze({
3738
tabName: "AprilTag",
3839
component: AprilTagTab
3940
},
41+
apriltagCudaTab: {
42+
tabName: "AprilTagCuda",
43+
component: AprilTagCudaTab
44+
},
4045
arucoTab: {
4146
tabName: "Aruco",
4247
component: ArucoTab
@@ -79,6 +84,7 @@ const getTabGroups = (): ConfigOption[][] => {
7984
allTabs.thresholdTab,
8085
allTabs.contoursTab,
8186
allTabs.apriltagTab,
87+
allTabs.apriltagCudaTab,
8288
allTabs.arucoTab,
8389
allTabs.objectDetectionTab,
8490
allTabs.outputTab
@@ -92,6 +98,7 @@ const getTabGroups = (): ConfigOption[][] => {
9298
allTabs.thresholdTab,
9399
allTabs.contoursTab,
94100
allTabs.apriltagTab,
101+
allTabs.apriltagCudaTab,
95102
allTabs.arucoTab,
96103
allTabs.objectDetectionTab,
97104
allTabs.outputTab
@@ -102,7 +109,7 @@ const getTabGroups = (): ConfigOption[][] => {
102109
return [
103110
[allTabs.inputTab],
104111
[allTabs.thresholdTab],
105-
[allTabs.contoursTab, allTabs.apriltagTab, allTabs.arucoTab, allTabs.objectDetectionTab, allTabs.outputTab],
112+
[allTabs.contoursTab, allTabs.apriltagTab, allTabs.apriltagCudaTab, allTabs.arucoTab, allTabs.objectDetectionTab, allTabs.outputTab],
106113
[allTabs.targetsTab, allTabs.pnpTab, allTabs.map3dTab]
107114
];
108115
}
@@ -115,6 +122,7 @@ const tabGroups = computed<ConfigOption[][]>(() => {
115122
116123
const allow3d = useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled;
117124
const isAprilTag = useCameraSettingsStore().currentWebsocketPipelineType === WebsocketPipelineType.AprilTag;
125+
const isAprilTagCuda = useCameraSettingsStore().currentWebsocketPipelineType === WebsocketPipelineType.AprilTagCuda;
118126
const isAruco = useCameraSettingsStore().currentWebsocketPipelineType === WebsocketPipelineType.Aruco;
119127
const isObjectDetection =
120128
useCameraSettingsStore().currentWebsocketPipelineType === WebsocketPipelineType.ObjectDetection;
@@ -124,10 +132,11 @@ const tabGroups = computed<ConfigOption[][]>(() => {
124132
tabGroup.filter(
125133
(tabConfig) =>
126134
!(!allow3d && tabConfig.tabName === "3D") && //Filter out 3D tab any time 3D isn't calibrated
127-
!((!allow3d || isAprilTag || isAruco || isObjectDetection) && tabConfig.tabName === "PnP") && //Filter out the PnP config tab if 3D isn't available, or we're doing AprilTags
128-
!((isAprilTag || isAruco || isObjectDetection) && tabConfig.tabName === "Threshold") && //Filter out threshold tab if we're doing AprilTags
129-
!((isAprilTag || isAruco || isObjectDetection) && tabConfig.tabName === "Contours") && //Filter out contours if we're doing AprilTags
135+
!((!allow3d || isAprilTag || isAprilTagCuda || isAruco || isObjectDetection) && tabConfig.tabName === "PnP") && //Filter out the PnP config tab if 3D isn't available, or we're doing AprilTags
136+
!((isAprilTag || isAprilTagCuda || isAruco || isObjectDetection) && tabConfig.tabName === "Threshold") && //Filter out threshold tab if we're doing AprilTags
137+
!((isAprilTag || isAprilTagCuda || isAruco || isObjectDetection) && tabConfig.tabName === "Contours") && //Filter out contours if we're doing AprilTags
130138
!(!isAprilTag && tabConfig.tabName === "AprilTag") && //Filter out apriltag unless we actually are doing AprilTags
139+
!(!isAprilTagCuda && tabConfig.tabName === "AprilTagCuda") && //Filter out apriltag unless we actually are doing AprilTags
131140
!(!isAruco && tabConfig.tabName === "Aruco") &&
132141
!(!isObjectDetection && tabConfig.tabName === "Object Detection") //Filter out aruco unless we actually are doing Aruco
133142
)
Lines changed: 93 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,93 @@
1+
<script setup lang="ts">
2+
import { PipelineType } from "@/types/PipelineTypes";
3+
import PvSelect from "@/components/common/pv-select.vue";
4+
import PvSlider from "@/components/common/pv-slider.vue";
5+
import PvSwitch from "@/components/common/pv-switch.vue";
6+
import { computed, getCurrentInstance } from "vue";
7+
import { useStateStore } from "@/stores/StateStore";
8+
import type { ActivePipelineSettings } from "@/types/PipelineTypes";
9+
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
10+
11+
// TODO fix pipeline typing in order to fix this, the store settings call should be able to infer that only valid pipeline type settings are exposed based on pre-checks for the entire config section
12+
// Defer reference to store access method
13+
const currentPipelineSettings = computed<ActivePipelineSettings>(
14+
() => useCameraSettingsStore().currentPipelineSettings
15+
);
16+
17+
const interactiveCols = computed(() =>
18+
(getCurrentInstance()?.proxy.$vuetify.breakpoint.mdAndDown || false) &&
19+
(!useStateStore().sidebarFolded || useCameraSettingsStore().isDriverMode)
20+
? 9
21+
: 8
22+
);
23+
</script>
24+
25+
<template>
26+
<div v-if="currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda">
27+
<pv-select
28+
v-model="currentPipelineSettings.tagFamily"
29+
label="Target family"
30+
:items="['AprilTag 36h11 (6.5in)', 'AprilTag 25h9 (6in)', 'AprilTag 16h5 (6in)']"
31+
:select-cols="interactiveCols"
32+
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ tagFamily: value }, false)"
33+
/>
34+
<pv-slider
35+
v-model="currentPipelineSettings.decimate"
36+
class="pt-2"
37+
:slider-cols="interactiveCols"
38+
label="Decimate"
39+
tooltip="Increases FPS at the expense of range by reducing image resolution initially"
40+
:min="1"
41+
:max="8"
42+
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ decimate: value }, false)"
43+
/>
44+
<pv-slider
45+
v-model="currentPipelineSettings.blur"
46+
class="pt-2"
47+
:slider-cols="interactiveCols"
48+
label="Blur"
49+
tooltip="Gaussian blur added to the image, high FPS cost for slightly decreased noise"
50+
:min="0"
51+
:max="5"
52+
:step="0.1"
53+
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ blur: value }, false)"
54+
/>
55+
<pv-slider
56+
v-model="currentPipelineSettings.threads"
57+
class="pt-2"
58+
:slider-cols="interactiveCols"
59+
label="Threads"
60+
tooltip="Number of threads spawned by the AprilTag detector"
61+
:min="1"
62+
:max="8"
63+
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threads: value }, false)"
64+
/>
65+
<pv-switch
66+
v-model="currentPipelineSettings.refineEdges"
67+
class="pt-2"
68+
label="Refine Edges"
69+
tooltip="Further refines the AprilTag corner position initial estimate, suggested left on"
70+
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ refineEdges: value }, false)"
71+
/>
72+
<pv-slider
73+
v-model="currentPipelineSettings.decisionMargin"
74+
class="pt-2 pb-4"
75+
:slider-cols="interactiveCols"
76+
label="Decision Margin Cutoff"
77+
tooltip="Tags with a 'margin' (decoding quality score) less than this wil be rejected. Increase this to reduce the number of false positive detections"
78+
:min="0"
79+
:max="250"
80+
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ decisionMargin: value }, false)"
81+
/>
82+
<pv-slider
83+
v-model="currentPipelineSettings.numIterations"
84+
class="pt-2 pb-4"
85+
:slider-cols="interactiveCols"
86+
label="Pose Estimation Iterations"
87+
tooltip="Number of iterations the pose estimation algorithm will run, 50-100 is a good starting point"
88+
:min="0"
89+
:max="500"
90+
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ numIterations: value }, false)"
91+
/>
92+
</div>
93+
</template>

photon-client/src/components/dashboard/tabs/OutputTab.vue

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ import { useStateStore } from "@/stores/StateStore";
1010
const isTagPipeline = computed(
1111
() =>
1212
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag ||
13+
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTagCuda ||
1314
useCameraSettingsStore().currentPipelineType === PipelineType.Aruco
1415
);
1516
@@ -69,6 +70,7 @@ const interactiveCols = computed(() =>
6970
<pv-switch
7071
v-if="
7172
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
73+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
7274
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
7375
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
7476
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
@@ -83,6 +85,7 @@ const interactiveCols = computed(() =>
8385
<pv-switch
8486
v-if="
8587
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
88+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
8689
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
8790
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
8891
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled

photon-client/src/components/dashboard/tabs/TargetsTab.vue

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ const resetCurrentBuffer = () => {
4242
<th
4343
v-if="
4444
currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
45+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
4546
currentPipelineSettings.pipelineType === PipelineType.Aruco
4647
"
4748
class="text-center white--text"
@@ -66,6 +67,7 @@ const resetCurrentBuffer = () => {
6667
<template
6768
v-if="
6869
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
70+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
6971
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
7072
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
7173
"
@@ -83,6 +85,7 @@ const resetCurrentBuffer = () => {
8385
<td
8486
v-if="
8587
currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
88+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
8689
currentPipelineSettings.pipelineType === PipelineType.Aruco
8790
"
8891
class="text-center"
@@ -115,6 +118,7 @@ const resetCurrentBuffer = () => {
115118
<template
116119
v-if="
117120
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
121+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
118122
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
119123
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
120124
"
@@ -131,6 +135,7 @@ const resetCurrentBuffer = () => {
131135
<v-container
132136
v-if="
133137
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
138+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
134139
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
135140
currentPipelineSettings.doMultiTarget &&
136141
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&

photon-client/src/types/PipelineTypes.ts

Lines changed: 44 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,8 @@ export enum PipelineType {
66
ColoredShape = 3,
77
AprilTag = 4,
88
Aruco = 5,
9-
ObjectDetection = 6
9+
ObjectDetection = 6,
10+
AprilTagCuda = 7
1011
}
1112

1213
export enum AprilTagFamily {
@@ -246,6 +247,46 @@ export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = {
246247
doSingleTargetAlways: false
247248
};
248249

250+
export interface AprilTagCudaPipelineSettings extends PipelineSettings {
251+
pipelineType: PipelineType.AprilTagCuda;
252+
hammingDist: number;
253+
numIterations: number;
254+
decimate: number;
255+
blur: number;
256+
decisionMargin: number;
257+
refineEdges: boolean;
258+
debug: boolean;
259+
threads: number;
260+
tagFamily: AprilTagFamily;
261+
doMultiTarget: boolean;
262+
doSingleTargetAlways: boolean;
263+
}
264+
export type ConfigurableAprilTagCudaPipelineSettings = Partial<
265+
Omit<AprilTagCudaPipelineSettings, "pipelineType" | "hammingDist" | "debug">
266+
> &
267+
ConfigurablePipelineSettings;
268+
export const DefaultAprilTagCudaPipelineSettings: AprilTagCudaPipelineSettings = {
269+
...DefaultPipelineSettings,
270+
cameraGain: 75,
271+
targetModel: TargetModel.AprilTag6p5in_36h11,
272+
ledMode: false,
273+
outputShowMultipleTargets: true,
274+
cameraExposureRaw: 20,
275+
pipelineType: PipelineType.AprilTagCuda,
276+
277+
hammingDist: 0,
278+
numIterations: 40,
279+
decimate: 1,
280+
blur: 0,
281+
decisionMargin: 35,
282+
refineEdges: true,
283+
debug: false,
284+
threads: 4,
285+
tagFamily: AprilTagFamily.Family36h11,
286+
doMultiTarget: false,
287+
doSingleTargetAlways: false
288+
};
289+
249290
export interface ArucoPipelineSettings extends PipelineSettings {
250291
pipelineType: PipelineType.Aruco;
251292

@@ -337,6 +378,7 @@ export type ActivePipelineSettings =
337378
| AprilTagPipelineSettings
338379
| ArucoPipelineSettings
339380
| ObjectDetectionPipelineSettings
381+
| AprilTagCudaPipelineSettings
340382
| Calibration3dPipelineSettings;
341383

342384
export type ActiveConfigurablePipelineSettings =
@@ -345,4 +387,5 @@ export type ActiveConfigurablePipelineSettings =
345387
| ConfigurableAprilTagPipelineSettings
346388
| ConfigurableArucoPipelineSettings
347389
| ConfigurableObjectDetectionPipelineSettings
390+
| ConfigurableAprilTagCudaPipelineSettings
348391
| ConfigurableCalibration3dPipelineSettings;

photon-client/src/types/WebsocketDataTypes.ts

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -115,5 +115,6 @@ export enum WebsocketPipelineType {
115115
ColoredShape = 1,
116116
AprilTag = 2,
117117
Aruco = 3,
118-
ObjectDetection = 4
118+
ObjectDetection = 4,
119+
AprilTagCuda = 5
119120
}
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
package org.photonvision.jni;
2+
3+
import edu.wpi.first.apriltag.AprilTagDetection;
4+
import java.io.IOException;
5+
6+
public class GpuDetectorJNI {
7+
static boolean libraryLoaded = false;
8+
9+
static {
10+
if(!libraryLoaded)
11+
System.loadLibrary("971apriltag");
12+
libraryLoaded = true;
13+
}
14+
15+
public static native long createGpuDetector(int width, int height);
16+
public static native void destroyGpuDetector(long handle);
17+
public static native void setparams(long handle, double fx, double cx,
18+
double fy, double cy, double k1, double k2, double p1,
19+
double p2, double k3);
20+
public static native AprilTagDetection[] processimage(long handle, long p);
21+
22+
}

photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,9 @@ public class QuirkyCamera {
8686
CameraQuirk.ArduCamCamera,
8787
CameraQuirk.Gain,
8888
CameraQuirk.ArduOV9782Controls),
89+
// Innomaker OV9281 Jetson Orin MIPI
90+
new QuirkyCamera(-1, -1, "vi-output, ov9281 10-0060", "vi-output,_ov9821_10-0060", CameraQuirk.Gain),
91+
new QuirkyCamera(-1, -1, "vi-output, ov9281 9-0060", "vi-output,_ov9821_9-0060", CameraQuirk.Gain),
8992
// Innomaker OV9281
9093
new QuirkyCamera(
9194
0x0c45, 0x636d, "USB Camera", "Innomaker OV9281", CameraQuirk.InnoOV9281Controls),

photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -247,7 +247,8 @@ public void setExposureRaw(double exposureRaw) {
247247
@Override
248248
public void setBrightness(int brightness) {
249249
try {
250-
camera.setBrightness(brightness);
250+
//camera.setBrightness(brightness);
251+
softSet("brightness", brightness);
251252
this.lastBrightness = brightness;
252253
} catch (VideoException e) {
253254
logger.error("Failed to set camera brightness!", e);
@@ -287,6 +288,7 @@ private void cacheVideoModes() {
287288

288289
modes = camera.enumerateVideoModes();
289290

291+
290292
for (VideoMode videoMode : modes) {
291293
// Filter grey modes
292294
if (/*videoMode.pixelFormat == PixelFormat.kGray

0 commit comments

Comments
 (0)