Skip to content

Commit 2599cd6

Browse files
committed
tested multitag
1 parent 388b3fa commit 2599cd6

File tree

6 files changed

+596
-0
lines changed

6 files changed

+596
-0
lines changed
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>
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+
}
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
/*
2+
* Copyright (C) Photon Vision.
3+
*
4+
* This program is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* This program is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with this program. If not, see <https://www.gnu.org/licenses/>.
16+
*/
17+
18+
package org.photonvision.vision.pipe.impl;
19+
20+
import edu.wpi.first.apriltag.AprilTagDetection;
21+
import edu.wpi.first.apriltag.AprilTagDetector;
22+
import java.util.List;
23+
import org.photonvision.vision.opencv.CVMat;
24+
import org.photonvision.vision.opencv.Releasable;
25+
import org.photonvision.vision.pipe.CVPipe;
26+
import org.photonvision.jni.GpuDetectorJNI;
27+
import org.opencv.core.Mat;
28+
29+
public class AprilTagDetectionCudaPipe
30+
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionCudaPipeParams>
31+
implements Releasable {
32+
//private AprilTagDetector m_detector = new AprilTagDetector();
33+
private GpuDetectorJNI m_cudadetector = new GpuDetectorJNI();
34+
private long handle = 0;
35+
36+
public AprilTagDetectionCudaPipe() {
37+
super();
38+
39+
//m_detector.addFamily("tag16h5");
40+
//m_detector.addFamily("tag36h11");
41+
handle = m_cudadetector.createGpuDetector(640,480); // just a guess
42+
}
43+
44+
@Override
45+
protected List<AprilTagDetection> process(CVMat in) {
46+
if (in.getMat().empty()) {
47+
return List.of();
48+
}
49+
50+
//if (m_detector == null) {
51+
// throw new RuntimeException("Apriltag detector was released!");
52+
//}
53+
54+
var ret = m_cudadetector.processimage(handle, in.getMat().getNativeObjAddr());
55+
56+
if (ret == null) {
57+
return List.of();
58+
}
59+
60+
return List.of(ret);
61+
}
62+
63+
@Override
64+
public void setParams(AprilTagDetectionCudaPipeParams newParams) {
65+
if (this.params == null || !this.params.equals(newParams)) {
66+
//m_detector.setConfig(newParams.detectorParams);
67+
68+
//m_detector.clearFamilies();
69+
//m_detector.addFamily(newParams.family.getNativeName());
70+
71+
if( newParams.cameraCalibrationCoefficients == null ) return;
72+
73+
final Mat cameraMatrix = newParams.cameraCalibrationCoefficients.getCameraIntrinsicsMat();
74+
final Mat distCoeffs = newParams.cameraCalibrationCoefficients.getDistCoeffsMat();
75+
if(cameraMatrix == null || distCoeffs == null) return;
76+
var cx = cameraMatrix.get(0, 2)[0];
77+
var cy = cameraMatrix.get(1, 2)[0];
78+
var fx = cameraMatrix.get(0, 0)[0];
79+
var fy = cameraMatrix.get(1, 1)[0];
80+
var k1 = distCoeffs.get(0, 0)[0];
81+
var k2 = distCoeffs.get(0, 1)[0];
82+
var k3 = distCoeffs.get(0, 4)[0];
83+
var p1 = distCoeffs.get(0, 2)[0];
84+
var p2 = distCoeffs.get(0, 3)[0];
85+
86+
m_cudadetector.setparams(handle,fx,cx,fy,cy,k1,k2,p1,p2,k3);
87+
}
88+
89+
super.setParams(newParams);
90+
}
91+
92+
@Override
93+
public void release() {
94+
//m_detector.close();
95+
//m_detector = null;
96+
m_cudadetector.destroyGpuDetector(handle);
97+
m_cudadetector = null;
98+
}
99+
}
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
/*
2+
* Copyright (C) Photon Vision.
3+
*
4+
* This program is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* This program is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with this program. If not, see <https://www.gnu.org/licenses/>.
16+
*/
17+
18+
package org.photonvision.vision.pipe.impl;
19+
20+
import edu.wpi.first.apriltag.AprilTagDetector;
21+
import org.photonvision.vision.apriltag.AprilTagFamily;
22+
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
23+
24+
25+
public class AprilTagDetectionCudaPipeParams {
26+
public final AprilTagFamily family;
27+
public final AprilTagDetector.Config detectorParams;
28+
public final CameraCalibrationCoefficients cameraCalibrationCoefficients;
29+
30+
public AprilTagDetectionCudaPipeParams(AprilTagFamily tagFamily, AprilTagDetector.Config config, CameraCalibrationCoefficients cal) {
31+
this.family = tagFamily;
32+
this.detectorParams = config;
33+
this.cameraCalibrationCoefficients = cal;
34+
}
35+
36+
@Override
37+
public int hashCode() {
38+
final int prime = 31;
39+
int result = 1;
40+
result = prime * result + ((family == null) ? 0 : family.hashCode());
41+
result = prime * result + ((cameraCalibrationCoefficients == null) ? 0 : cameraCalibrationCoefficients.hashCode());
42+
result = prime * result + ((detectorParams == null) ? 0 : detectorParams.hashCode());
43+
return result;
44+
}
45+
46+
@Override
47+
public boolean equals(Object obj) {
48+
if (this == obj) return true;
49+
if (obj == null) return false;
50+
if (getClass() != obj.getClass()) return false;
51+
AprilTagDetectionCudaPipeParams other = (AprilTagDetectionCudaPipeParams) obj;
52+
if (family != other.family) return false;
53+
if (cameraCalibrationCoefficients != other.cameraCalibrationCoefficients) return false;
54+
if (detectorParams == null) {
55+
return other.detectorParams == null;
56+
} else return detectorParams.equals(other.detectorParams);
57+
}
58+
}

0 commit comments

Comments
 (0)