Skip to content

Commit 9a0d56e

Browse files
committed
lint
1 parent 78fa48d commit 9a0d56e

File tree

11 files changed

+106
-57
lines changed

11 files changed

+106
-57
lines changed

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

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,14 @@ const getTabGroups = (): ConfigOption[][] => {
110110
return [
111111
[allTabs.inputTab],
112112
[allTabs.thresholdTab],
113-
[allTabs.contoursTab, allTabs.apriltagTab, allTabs.apriltagCudaTab, allTabs.arucoTab, allTabs.objectDetectionTab, allTabs.outputTab],
113+
[
114+
allTabs.contoursTab,
115+
allTabs.apriltagTab,
116+
allTabs.apriltagCudaTab,
117+
allTabs.arucoTab,
118+
allTabs.objectDetectionTab,
119+
allTabs.outputTab
120+
],
114121
[allTabs.targetsTab, allTabs.pnpTab, allTabs.map3dTab]
115122
];
116123
}
@@ -133,7 +140,10 @@ const tabGroups = computed<ConfigOption[][]>(() => {
133140
tabGroup.filter(
134141
(tabConfig) =>
135142
!(!allow3d && tabConfig.tabName === "3D") && //Filter out 3D tab any time 3D isn't calibrated
136-
!((!allow3d || isAprilTag || isAprilTagCuda || isAruco || isObjectDetection) && tabConfig.tabName === "PnP") && //Filter out the PnP config tab if 3D isn't available, or we're doing AprilTags
143+
!(
144+
(!allow3d || isAprilTag || isAprilTagCuda || isAruco || isObjectDetection) &&
145+
tabConfig.tabName === "PnP"
146+
) && //Filter out the PnP config tab if 3D isn't available, or we're doing AprilTags
137147
!((isAprilTag || isAprilTagCuda || isAruco || isObjectDetection) && tabConfig.tabName === "Threshold") && //Filter out threshold tab if we're doing AprilTags
138148
!((isAprilTag || isAprilTagCuda || isAruco || isObjectDetection) && tabConfig.tabName === "Contours") && //Filter out contours if we're doing AprilTags
139149
!(!isAprilTag && tabConfig.tabName === "AprilTag") && //Filter out apriltag unless we actually are doing AprilTags

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ const interactiveCols = computed(() =>
7272
<pv-switch
7373
v-if="
7474
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
75-
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
75+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
7676
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
7777
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
7878
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
@@ -89,7 +89,7 @@ const interactiveCols = computed(() =>
8989
<pv-switch
9090
v-if="
9191
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
92-
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
92+
currentPipelineSettings.pipelineType === PipelineType.AprilTagCuda ||
9393
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
9494
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
9595
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
Lines changed: 34 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,47 @@
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+
118
package org.photonvision.jni;
219

320
import edu.wpi.first.apriltag.AprilTagDetection;
4-
import java.io.IOException;
521

622
public class GpuDetectorJNI {
723
static boolean libraryLoaded = false;
824

925
static {
10-
if(!libraryLoaded)
11-
System.loadLibrary("971apriltag");
12-
libraryLoaded = true;
26+
if (!libraryLoaded) System.loadLibrary("971apriltag");
27+
libraryLoaded = true;
1328
}
14-
29+
1530
public static native long createGpuDetector(int width, int height);
31+
1632
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);
2133

34+
public static native void setparams(
35+
long handle,
36+
double fx,
37+
double cx,
38+
double fy,
39+
double cy,
40+
double k1,
41+
double k2,
42+
double p1,
43+
double p2,
44+
double k3);
45+
46+
public static native AprilTagDetection[] processimage(long handle, long p);
2247
}

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

Lines changed: 15 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -85,16 +85,26 @@ public class QuirkyCamera {
8585
CameraQuirk.ArduCamCamera,
8686
CameraQuirk.Gain,
8787
CameraQuirk.ArduOV9782Controls),
88-
// Innomaker OV9281 Jetson Orin MIPI
89-
new QuirkyCamera(-1, -1, "vi-output, ov9281 10-0060", "vi-output,_ov9821_10-0060", CameraQuirk.Gain),
90-
new QuirkyCamera(-1, -1, "vi-output, ov9281 9-0060", "vi-output,_ov9821_9-0060", CameraQuirk.Gain),
88+
// Innomaker OV9281 Jetson Orin MIPI
89+
new QuirkyCamera(
90+
-1, -1, "vi-output, ov9281 10-0060", "vi-output,_ov9821_10-0060", CameraQuirk.Gain),
91+
new QuirkyCamera(
92+
-1, -1, "vi-output, ov9281 9-0060", "vi-output,_ov9821_9-0060", CameraQuirk.Gain),
9193
// Innomaker OV9281
9294
new QuirkyCamera(
9395
0x0c45, 0x636d, "USB Camera", "Innomaker OV9281", CameraQuirk.InnoOV9281Controls),
9496
new QuirkyCamera(
95-
-1, -1, "vi-output, ov9281 9-0060", CameraQuirk.InnoOV9281Controls, CameraQuirk.StickyFPS),
97+
-1,
98+
-1,
99+
"vi-output, ov9281 9-0060",
100+
CameraQuirk.InnoOV9281Controls,
101+
CameraQuirk.StickyFPS),
96102
new QuirkyCamera(
97-
-1, -1, "vi-output, ov9281 10-0060", CameraQuirk.InnoOV9281Controls, CameraQuirk.StickyFPS));
103+
-1,
104+
-1,
105+
"vi-output, ov9281 10-0060",
106+
CameraQuirk.InnoOV9281Controls,
107+
CameraQuirk.StickyFPS));
98108

99109
public static final QuirkyCamera DefaultCamera = new QuirkyCamera(0, 0, "");
100110
public static final QuirkyCamera ZeroCopyPiCamera =

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

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ protected void setUpWhiteBalanceProperties() {
8383
}
8484

8585
protected void setUpExposureProperties() {
86-
logger.debug("start usb setupexposure");
86+
logger.debug("start usb setupexposure");
8787
// Photonvision needs to be able to control absolute exposure. Make sure we can
8888
// first.
8989
var expProp =
@@ -176,7 +176,7 @@ public void setAutoExposure(boolean cameraAutoExposure) {
176176
softSet("auto_exposure_bias", 0);
177177
softSet("iso_sensitivity_auto", 0); // Disable auto ISO adjustment
178178
softSet("iso_sensitivity", 0); // Manual ISO adjustment
179-
if(autoExposureProp != null) autoExposureProp.set(PROP_AUTO_EXPOSURE_DISABLED);
179+
if (autoExposureProp != null) autoExposureProp.set(PROP_AUTO_EXPOSURE_DISABLED);
180180

181181
// Most cameras leave exposure time absolute at the last value from their AE
182182
// algorithm.
@@ -188,7 +188,7 @@ public void setAutoExposure(boolean cameraAutoExposure) {
188188
softSet("auto_exposure_bias", 12);
189189
softSet("iso_sensitivity_auto", 1);
190190
softSet("iso_sensitivity", 1); // Manual ISO adjustment by default
191-
if(autoExposureProp != null) autoExposureProp.set(PROP_AUTO_EXPOSURE_ENABLED);
191+
if (autoExposureProp != null) autoExposureProp.set(PROP_AUTO_EXPOSURE_ENABLED);
192192
}
193193
}
194194

@@ -206,7 +206,7 @@ public double getMaxExposureRaw() {
206206
public void setExposureRaw(double exposureRaw) {
207207
if (exposureRaw >= 0.0) {
208208
try {
209-
if(autoExposureProp != null) autoExposureProp.set(PROP_AUTO_EXPOSURE_DISABLED);
209+
if (autoExposureProp != null) autoExposureProp.set(PROP_AUTO_EXPOSURE_DISABLED);
210210

211211
int propVal = (int) MathUtil.clamp(exposureRaw, minExposure, maxExposure);
212212

@@ -232,7 +232,7 @@ public void setExposureRaw(double exposureRaw) {
232232
@Override
233233
public void setBrightness(int brightness) {
234234
try {
235-
softSet("brightness", brightness);
235+
softSet("brightness", brightness);
236236
this.lastBrightness = brightness;
237237
} catch (VideoException e) {
238238
logger.error("Failed to set camera brightness!", e);

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,6 @@ public USBCameraSource(CameraConfiguration config) {
8484
}
8585

8686
if (getCameraConfiguration().cameraQuirks.hasQuirks()) {
87-
8887
logger.info("Quirky camera detected: " + getCameraConfiguration().cameraQuirks.baseName);
8988
}
9089

photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionCudaPipe.java

Lines changed: 19 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -18,13 +18,12 @@
1818
package org.photonvision.vision.pipe.impl;
1919

2020
import edu.wpi.first.apriltag.AprilTagDetection;
21-
import edu.wpi.first.apriltag.AprilTagDetector;
2221
import java.util.List;
22+
import org.opencv.core.Mat;
23+
import org.photonvision.jni.GpuDetectorJNI;
2324
import org.photonvision.vision.opencv.CVMat;
2425
import org.photonvision.vision.opencv.Releasable;
2526
import org.photonvision.vision.pipe.CVPipe;
26-
import org.photonvision.jni.GpuDetectorJNI;
27-
import org.opencv.core.Mat;
2827

2928
public class AprilTagDetectionCudaPipe
3029
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionCudaPipeParams>
@@ -35,7 +34,7 @@ public class AprilTagDetectionCudaPipe
3534
public AprilTagDetectionCudaPipe() {
3635
super();
3736

38-
handle = m_cudadetector.createGpuDetector(640,480); // just a guess
37+
handle = m_cudadetector.createGpuDetector(640, 480); // just a guess
3938
}
4039

4140
@Override
@@ -56,30 +55,30 @@ protected List<AprilTagDetection> process(CVMat in) {
5655
@Override
5756
public void setParams(AprilTagDetectionCudaPipeParams newParams) {
5857
if (this.params == null || !this.params.equals(newParams)) {
59-
if( newParams.cameraCalibrationCoefficients == null ) return;
58+
if (newParams.cameraCalibrationCoefficients == null) return;
6059

61-
final Mat cameraMatrix = newParams.cameraCalibrationCoefficients.getCameraIntrinsicsMat();
62-
final Mat distCoeffs = newParams.cameraCalibrationCoefficients.getDistCoeffsMat();
63-
if(cameraMatrix == null || distCoeffs == null) return;
64-
var cx = cameraMatrix.get(0, 2)[0];
65-
var cy = cameraMatrix.get(1, 2)[0];
66-
var fx = cameraMatrix.get(0, 0)[0];
67-
var fy = cameraMatrix.get(1, 1)[0];
68-
var k1 = distCoeffs.get(0, 0)[0];
69-
var k2 = distCoeffs.get(0, 1)[0];
70-
var k3 = distCoeffs.get(0, 4)[0];
71-
var p1 = distCoeffs.get(0, 2)[0];
72-
var p2 = distCoeffs.get(0, 3)[0];
60+
final Mat cameraMatrix = newParams.cameraCalibrationCoefficients.getCameraIntrinsicsMat();
61+
final Mat distCoeffs = newParams.cameraCalibrationCoefficients.getDistCoeffsMat();
62+
if (cameraMatrix == null || distCoeffs == null) return;
63+
var cx = cameraMatrix.get(0, 2)[0];
64+
var cy = cameraMatrix.get(1, 2)[0];
65+
var fx = cameraMatrix.get(0, 0)[0];
66+
var fy = cameraMatrix.get(1, 1)[0];
67+
var k1 = distCoeffs.get(0, 0)[0];
68+
var k2 = distCoeffs.get(0, 1)[0];
69+
var k3 = distCoeffs.get(0, 4)[0];
70+
var p1 = distCoeffs.get(0, 2)[0];
71+
var p2 = distCoeffs.get(0, 3)[0];
7372

74-
m_cudadetector.setparams(handle,fx,cx,fy,cy,k1,k2,p1,p2,k3);
73+
m_cudadetector.setparams(handle, fx, cx, fy, cy, k1, k2, p1, p2, k3);
7574
}
7675

7776
super.setParams(newParams);
7877
}
7978

8079
@Override
8180
public void release() {
82-
m_cudadetector.destroyGpuDetector(handle);
83-
m_cudadetector = null;
81+
m_cudadetector.destroyGpuDetector(handle);
82+
m_cudadetector = null;
8483
}
8584
}

photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionCudaPipeParams.java

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -21,24 +21,28 @@
2121
import org.photonvision.vision.apriltag.AprilTagFamily;
2222
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
2323

24-
2524
public class AprilTagDetectionCudaPipeParams {
2625
public final AprilTagFamily family;
2726
public final AprilTagDetector.Config detectorParams;
2827
public final CameraCalibrationCoefficients cameraCalibrationCoefficients;
2928

30-
public AprilTagDetectionCudaPipeParams(AprilTagFamily tagFamily, AprilTagDetector.Config config, CameraCalibrationCoefficients cal) {
29+
public AprilTagDetectionCudaPipeParams(
30+
AprilTagFamily tagFamily, AprilTagDetector.Config config, CameraCalibrationCoefficients cal) {
3131
this.family = tagFamily;
3232
this.detectorParams = config;
33-
this.cameraCalibrationCoefficients = cal;
33+
this.cameraCalibrationCoefficients = cal;
3434
}
3535

3636
@Override
3737
public int hashCode() {
3838
final int prime = 31;
3939
int result = 1;
4040
result = prime * result + ((family == null) ? 0 : family.hashCode());
41-
result = prime * result + ((cameraCalibrationCoefficients == null) ? 0 : cameraCalibrationCoefficients.hashCode());
41+
result =
42+
prime * result
43+
+ ((cameraCalibrationCoefficients == null)
44+
? 0
45+
: cameraCalibrationCoefficients.hashCode());
4246
result = prime * result + ((detectorParams == null) ? 0 : detectorParams.hashCode());
4347
return result;
4448
}
@@ -50,7 +54,7 @@ public boolean equals(Object obj) {
5054
if (getClass() != obj.getClass()) return false;
5155
AprilTagDetectionCudaPipeParams other = (AprilTagDetectionCudaPipeParams) obj;
5256
if (family != other.family) return false;
53-
if (cameraCalibrationCoefficients != other.cameraCalibrationCoefficients) return false;
57+
if (cameraCalibrationCoefficients != other.cameraCalibrationCoefficients) return false;
5458
if (detectorParams == null) {
5559
return other.detectorParams == null;
5660
} else return detectorParams.equals(other.detectorParams);

photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagCudaPipeline.java

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,6 @@
3737
import org.photonvision.vision.frame.Frame;
3838
import org.photonvision.vision.frame.FrameThresholdType;
3939
import org.photonvision.vision.pipe.CVPipe.CVPipeResult;
40-
import org.photonvision.vision.pipe.impl.AprilTagDetectionPipe;
4140
import org.photonvision.vision.pipe.impl.AprilTagDetectionCudaPipe;
4241
import org.photonvision.vision.pipe.impl.AprilTagDetectionCudaPipeParams;
4342
import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe;
@@ -49,7 +48,8 @@
4948
import org.photonvision.vision.target.TrackedTarget;
5049
import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters;
5150

52-
public class AprilTagCudaPipeline extends CVPipeline<CVPipelineResult, AprilTagCudaPipelineSettings> {
51+
public class AprilTagCudaPipeline
52+
extends CVPipeline<CVPipelineResult, AprilTagCudaPipelineSettings> {
5353
private final AprilTagDetectionCudaPipe aprilTagDetectionPipe = new AprilTagDetectionCudaPipe();
5454
private final AprilTagPoseEstimatorPipe singleTagPoseEstimatorPipe =
5555
new AprilTagPoseEstimatorPipe();
@@ -88,7 +88,9 @@ protected void setPipeParamsImpl() {
8888
config.refineEdges = settings.refineEdges;
8989
config.quadSigma = (float) settings.blur;
9090
config.quadDecimate = settings.decimate;
91-
aprilTagDetectionPipe.setParams(new AprilTagDetectionCudaPipeParams(settings.tagFamily, config, frameStaticProperties.cameraCalibration));
91+
aprilTagDetectionPipe.setParams(
92+
new AprilTagDetectionCudaPipeParams(
93+
settings.tagFamily, config, frameStaticProperties.cameraCalibration));
9294

9395
if (frameStaticProperties.cameraCalibration != null) {
9496
var cameraMatrix = frameStaticProperties.cameraCalibration.getCameraIntrinsicsMat();

photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -181,8 +181,8 @@ public CVPipelineResult process(
181181
sumPipeNanosElapsed += pipeProfileNanos[7] = drawOnInputResult.nanosElapsed;
182182

183183
pipeProfileNanos[8] = 0;
184-
} else if ((settings instanceof AprilTagPipelineSettings) ||
185-
(settings instanceof AprilTagCudaPipelineSettings)) {
184+
} else if ((settings instanceof AprilTagPipelineSettings)
185+
|| (settings instanceof AprilTagCudaPipelineSettings)) {
186186
// If we are doing apriltags...
187187
if (settings.solvePNPEnabled) {
188188
// Draw 3d Apriltag markers (camera is calibrated and running in 3d mode)

0 commit comments

Comments
 (0)