Skip to content

Add CUDA accelerated apriltag detection #2076

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

Draft
wants to merge 19 commits into
base: main
Choose a base branch
from
Draft
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
4 changes: 4 additions & 0 deletions .styleguide
Original file line number Diff line number Diff line change
Expand Up @@ -39,3 +39,7 @@ includeOtherLibs {
^units/
^wpi/
}

licenseUpdateExclude {
photon-core/src/main/java/org/photonvision/jni/GpuDetectorJNI.java
}
50 changes: 40 additions & 10 deletions photon-client/src/components/dashboard/ConfigOptions.vue
Original file line number Diff line number Diff line change
Expand Up @@ -25,16 +25,46 @@ interface ConfigOption {
}

const allTabs = Object.freeze({
inputTab: { tabName: "Input", component: InputTab },
thresholdTab: { tabName: "Threshold", component: ThresholdTab },
contoursTab: { tabName: "Contours", component: ContoursTab },
apriltagTab: { tabName: "AprilTag", component: AprilTagTab },
arucoTab: { tabName: "Aruco", component: ArucoTab },
objectDetectionTab: { tabName: "Object Detection", component: ObjectDetectionTab },
outputTab: { tabName: "Output", component: OutputTab },
targetsTab: { tabName: "Targets", component: TargetsTab },
pnpTab: { tabName: "PnP", component: PnPTab },
map3dTab: { tabName: "3D", component: Map3DTab }
inputTab: {
tabName: "Input",
component: InputTab
},
thresholdTab: {
tabName: "Threshold",
component: ThresholdTab
},
contoursTab: {
tabName: "Contours",
component: ContoursTab
},
apriltagTab: {
tabName: "AprilTag",
component: AprilTagTab
},
arucoTab: {
tabName: "Aruco",
component: ArucoTab
},
objectDetectionTab: {
tabName: "Object Detection",
component: ObjectDetectionTab
},
outputTab: {
tabName: "Output",
component: OutputTab
},
targetsTab: {
tabName: "Targets",
component: TargetsTab
},
pnpTab: {
tabName: "PnP",
component: PnPTab
},
map3dTab: {
tabName: "3D",
component: Map3DTab
}
});

const selectedTabs = ref([0, 0, 0, 0]);
Expand Down
9 changes: 9 additions & 0 deletions photon-client/src/components/dashboard/tabs/AprilTagTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -88,5 +88,14 @@ const interactiveCols = computed(() =>
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ refineEdges: value }, false)
"
/>
<pv-switch
v-model="currentPipelineSettings.cudaAcceleration"
:switch-cols="interactiveCols"
label="CUDA Acceleration"
tooltip="Use CUDA acceleration for AprilTag detection, requires a compatible NVIDIA GPU and the CUDA version of OpenCV"
@update:modelValue="
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ cudaAcceleration: value }, false)
"
/>
</div>
</template>
4 changes: 3 additions & 1 deletion photon-client/src/types/PipelineTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -221,6 +221,7 @@ export interface AprilTagPipelineSettings extends PipelineSettings {
tagFamily: AprilTagFamily;
doMultiTarget: boolean;
doSingleTargetAlways: boolean;
cudaAcceleration: boolean;
}
export type ConfigurableAprilTagPipelineSettings = Partial<
Omit<AprilTagPipelineSettings, "pipelineType" | "hammingDist" | "debug">
Expand All @@ -245,7 +246,8 @@ export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = {
threads: 4,
tagFamily: AprilTagFamily.Family36h11,
doMultiTarget: false,
doSingleTargetAlways: false
doSingleTargetAlways: false,
cudaAcceleration: false
};

export interface ArucoPipelineSettings extends PipelineSettings {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* Licensed to the Apache Software Foundation (ASF) under one or more contributor license agreements.
* See the NOTICE file distributed with this work for additional information regarding copyright
* ownership. The ASF licenses this file to you under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License. You may obtain a copy of the License
* at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in
* writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific
* language governing permissions and limitations under the License.
*/

package org.photonvision.jni;

import edu.wpi.first.apriltag.AprilTagDetection;

public class GpuDetectorJNI {
static boolean libraryLoaded = false;

static {
if (!libraryLoaded) System.loadLibrary("971apriltag");
libraryLoaded = true;
}

public static native long createGpuDetector(int width, int height);

public static native void destroyGpuDetector(long handle);

public static native void setparams(
long handle,
double fx,
double cx,
double fy,
double cy,
double k1,
double k2,
double p1,
double p2,
double k3);

public static native AprilTagDetection[] processimage(long handle, long p);
}
Original file line number Diff line number Diff line change
Expand Up @@ -85,9 +85,26 @@ public class QuirkyCamera {
CameraQuirk.ArduCamCamera,
CameraQuirk.Gain,
CameraQuirk.ArduOV9782Controls),
// Innomaker OV9281 Jetson Orin MIPI
new QuirkyCamera(
-1, -1, "vi-output, ov9281 10-0060", "vi-output,_ov9821_10-0060", CameraQuirk.Gain),
new QuirkyCamera(
-1, -1, "vi-output, ov9281 9-0060", "vi-output,_ov9821_9-0060", CameraQuirk.Gain),
// Innomaker OV9281
new QuirkyCamera(
0x0c45, 0x636d, "USB Camera", "Innomaker OV9281", CameraQuirk.InnoOV9281Controls));
0x0c45, 0x636d, "USB Camera", "Innomaker OV9281", CameraQuirk.InnoOV9281Controls),
new QuirkyCamera(
-1,
-1,
"vi-output, ov9281 9-0060",
CameraQuirk.InnoOV9281Controls,
CameraQuirk.StickyFPS),
new QuirkyCamera(
-1,
-1,
"vi-output, ov9281 10-0060",
CameraQuirk.InnoOV9281Controls,
CameraQuirk.StickyFPS));

public static final QuirkyCamera DefaultCamera = new QuirkyCamera(0, 0, "");
public static final QuirkyCamera ZeroCopyPiCamera =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ protected void setUpWhiteBalanceProperties() {
}

protected void setUpExposureProperties() {
logger.debug("start usb setupexposure");
// Photonvision needs to be able to control absolute exposure. Make sure we can
// first.
var expProp =
Expand Down Expand Up @@ -231,7 +232,7 @@ public void setExposureRaw(double exposureRaw) {
@Override
public void setBrightness(int brightness) {
try {
camera.setBrightness(brightness);
softSet("brightness", brightness);
this.lastBrightness = brightness;
} catch (VideoException e) {
logger.error("Failed to set camera brightness!", e);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ public USBCameraSource(CameraConfiguration config) {
}

if (getCameraConfiguration().cameraQuirks.hasQuirks()) {
logger.info("Quirky camera detected: " + getCameraConfiguration().cameraQuirks);
logger.info("Quirky camera detected: " + getCameraConfiguration().cameraQuirks.baseName);
}

var cameraBroken = getCameraConfiguration().cameraQuirks.hasQuirk(CameraQuirk.CompletelyBroken);
Expand Down Expand Up @@ -147,6 +147,7 @@ protected GenericUSBCameraSettables createSettables(
logger.debug("Using Arducam OV9782 Settables");
settables = new ArduOV9782CameraSettables(config, camera);
} else if (quirks.hasQuirk(CameraQuirk.InnoOV9281Controls)) {
logger.debug("Using Innovision OV9782 Settables");
settables = new InnoOV9281CameraSettables(config, camera);
} else if (quirks.hasQuirk(CameraQuirk.See3Cam_24CUG)) {
settables = new See3Cam24CUGSettables(config, camera);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,10 @@
import edu.wpi.first.apriltag.AprilTagDetection;
import edu.wpi.first.apriltag.AprilTagDetector;
import java.util.List;
import org.opencv.core.Mat;
import org.photonvision.jni.GpuDetectorJNI;
import org.photonvision.vision.apriltag.AprilTagFamily;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.opencv.Releasable;
import org.photonvision.vision.pipe.CVPipe;
Expand All @@ -29,13 +32,24 @@ public class AprilTagDetectionPipe
extends CVPipe<
CVMat, List<AprilTagDetection>, AprilTagDetectionPipe.AprilTagDetectionPipeParams>
implements Releasable {
private AprilTagDetector m_detector = new AprilTagDetector();
private AprilTagDetector m_detector = null;
private GpuDetectorJNI m_cudadetector = null;
private long pointer = 0;
private boolean cudaAccelerated;

public AprilTagDetectionPipe() {
public AprilTagDetectionPipe(boolean cudaAccelerated) {
super();

m_detector.addFamily("tag16h5");
m_detector.addFamily("tag36h11");
this.cudaAccelerated = cudaAccelerated;

if (cudaAccelerated) {
m_cudadetector = new GpuDetectorJNI();
pointer = m_cudadetector.createGpuDetector(640, 480); // just a guess
} else {
m_detector = new AprilTagDetector();
m_detector.addFamily("tag16h5");
m_detector.addFamily("tag36h11");
}
}

@Override
Expand All @@ -60,24 +74,49 @@ protected List<AprilTagDetection> process(CVMat in) {
@Override
public void setParams(AprilTagDetectionPipeParams newParams) {
if (this.params == null || !this.params.equals(newParams)) {
m_detector.setConfig(newParams.detectorParams());
m_detector.setQuadThresholdParameters(newParams.quadParams());
if (cudaAccelerated) {
if (newParams.cal == null) return;

final Mat cameraMatrix = newParams.cal.getCameraIntrinsicsMat();
final Mat distCoeffs = newParams.cal.getDistCoeffsMat();
if (cameraMatrix == null || distCoeffs == null) return;
var cx = cameraMatrix.get(0, 2)[0];
var cy = cameraMatrix.get(1, 2)[0];
var fx = cameraMatrix.get(0, 0)[0];
var fy = cameraMatrix.get(1, 1)[0];
var k1 = distCoeffs.get(0, 0)[0];
var k2 = distCoeffs.get(0, 1)[0];
var k3 = distCoeffs.get(0, 4)[0];
var p1 = distCoeffs.get(0, 2)[0];
var p2 = distCoeffs.get(0, 3)[0];

m_detector.clearFamilies();
m_detector.addFamily(newParams.family().getNativeName());
m_cudadetector.setparams(pointer, fx, cx, fy, cy, k1, k2, p1, p2, k3);
} else {
m_detector.setConfig(newParams.detectorParams());
m_detector.setQuadThresholdParameters(newParams.quadParams());

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

super.setParams(newParams);
}

@Override
public void release() {
m_detector.close();
m_detector = null;
if (cudaAccelerated) {
m_cudadetector.destroyGpuDetector(pointer);
m_cudadetector = null;
} else {
m_detector.close();
m_detector = null;
}
}

public static record AprilTagDetectionPipeParams(
AprilTagFamily family,
AprilTagDetector.Config detectorParams,
AprilTagDetector.QuadThresholdParameters quadParams) {}
AprilTagDetector.QuadThresholdParameters quadParams,
CameraCalibrationCoefficients cal) {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters;

public class AprilTagPipeline extends CVPipeline<CVPipelineResult, AprilTagPipelineSettings> {
private final AprilTagDetectionPipe aprilTagDetectionPipe = new AprilTagDetectionPipe();
private final AprilTagDetectionPipe aprilTagDetectionPipe;
private final AprilTagPoseEstimatorPipe singleTagPoseEstimatorPipe =
new AprilTagPoseEstimatorPipe();
private final MultiTargetPNPPipe multiTagPNPPipe = new MultiTargetPNPPipe();
Expand All @@ -60,11 +60,13 @@ public class AprilTagPipeline extends CVPipeline<CVPipelineResult, AprilTagPipel
public AprilTagPipeline() {
super(PROCESSING_TYPE);
settings = new AprilTagPipelineSettings();
aprilTagDetectionPipe = new AprilTagDetectionPipe(settings.cudaAcceleration);
}

public AprilTagPipeline(AprilTagPipelineSettings settings) {
super(PROCESSING_TYPE);
this.settings = settings;
aprilTagDetectionPipe = new AprilTagDetectionPipe(settings.cudaAcceleration);
}

@Override
Expand Down Expand Up @@ -101,7 +103,8 @@ protected void setPipeParamsImpl() {
quadParams.deglitch = false;

aprilTagDetectionPipe.setParams(
new AprilTagDetectionPipeParams(settings.tagFamily, config, quadParams));
new AprilTagDetectionPipeParams(
settings.tagFamily, config, quadParams, frameStaticProperties.cameraCalibration));

if (frameStaticProperties.cameraCalibration != null) {
var cameraMatrix = frameStaticProperties.cameraCalibration.getCameraIntrinsicsMat();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ public class AprilTagPipelineSettings extends AdvancedPipelineSettings {
public int decisionMargin = 35;
public boolean doMultiTarget = false;
public boolean doSingleTargetAlways = false;
public boolean cudaAcceleration = false;

// 3d settings

Expand Down Expand Up @@ -64,6 +65,7 @@ public int hashCode() {
result = prime * result + decisionMargin;
result = prime * result + (doMultiTarget ? 1231 : 1237);
result = prime * result + (doSingleTargetAlways ? 1231 : 1237);
result = prime * result + (cudaAcceleration ? 1231 : 1237);
return result;
}

Expand All @@ -84,6 +86,7 @@ public boolean equals(Object obj) {
if (decisionMargin != other.decisionMargin) return false;
if (doMultiTarget != other.doMultiTarget) return false;
if (doSingleTargetAlways != other.doSingleTargetAlways) return false;
if (cudaAcceleration != other.cudaAcceleration) return false;
return true;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ public CVPipelineResult process(
sumPipeNanosElapsed += pipeProfileNanos[7] = drawOnInputResult.nanosElapsed;

pipeProfileNanos[8] = 0;
} else if (settings instanceof AprilTagPipelineSettings) {
} else if ((settings instanceof AprilTagPipelineSettings)) {
// If we are doing apriltags...
if (settings.solvePNPEnabled) {
// Draw 3d Apriltag markers (camera is calibrated and running in 3d mode)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,10 @@ public static boolean isRaspberryPi() {
return currentPlatform.isPi;
}

public static boolean isJetson() {
return Platform.isJetsonSBC();
}

public static String getPlatformName() {
if (currentPlatform.equals(UNKNOWN)) {
return UnknownPlatformString;
Expand Down
Loading