Skip to content

Commit a55fbce

Browse files
committed
no more enum
1 parent 627ac6c commit a55fbce

File tree

4 files changed

+21
-21
lines changed

4 files changed

+21
-21
lines changed

photon-core/src/main/java/org/photonvision/common/LoadJNI.java

Lines changed: 14 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -19,44 +19,41 @@
1919

2020
import edu.wpi.first.util.CombinedRuntimeLoader;
2121
import java.io.IOException;
22+
import java.util.HashMap;
2223
import org.photonvision.jni.LibraryLoader;
2324

2425
public class LoadJNI {
26+
private static HashMap<JNITypes, Boolean> loadedMap = new HashMap<>();
27+
2528
public enum JNITypes {
26-
RUBIK_DETECTOR(false, "tensorflowlite", "tensorflowlite_c", "external_delegate", "rubik_jni"),
27-
RKNN_DETECTOR(false, "rga", "rknnrt", "rknn_jni"),
28-
MRCAL(false, "mrcal_jni"),
29-
LIBCAMERA(false, "photonlibcamera");
29+
RUBIK_DETECTOR("tensorflowlite", "tensorflowlite_c", "external_delegate", "rubik_jni"),
30+
RKNN_DETECTOR("rga", "rknnrt", "rknn_jni"),
31+
MRCAL("mrcal_jni"),
32+
LIBCAMERA("photonlibcamera");
3033

31-
private volatile boolean hasLoaded;
3234
public final String[] libraries;
3335

34-
JNITypes(boolean hasLoaded, String... libraries) {
35-
this.hasLoaded = hasLoaded;
36+
JNITypes(String... libraries) {
3637
this.libraries = libraries;
3738
}
38-
39-
public boolean hasLoaded() {
40-
return hasLoaded;
41-
}
42-
43-
public void setHasLoaded(boolean loaded) {
44-
this.hasLoaded = loaded;
45-
}
4639
}
4740

4841
public static synchronized void forceLoad(JNITypes type) throws IOException {
4942
loadLibraries();
5043

51-
if (type.hasLoaded()) {
44+
if (loadedMap.getOrDefault(type, false)) {
5245
return;
5346
}
5447

5548
CombinedRuntimeLoader.loadLibraries(LoadJNI.class, type.libraries);
56-
type.setHasLoaded(true);
49+
loadedMap.put(type, true);
5750
}
5851

5952
public static boolean loadLibraries() {
6053
return LibraryLoader.loadWpiLibraries() && LibraryLoader.loadTargeting();
6154
}
55+
56+
public static boolean hasLoaded(JNITypes t) {
57+
return loadedMap.containsKey(t) ? false : loadedMap.get(t);
58+
}
6259
}

photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
import java.util.List;
2121
import org.photonvision.PhotonVersion;
2222
import org.photonvision.common.LoadJNI;
23+
import org.photonvision.common.LoadJNI.JNITypes;
2324
import org.photonvision.common.configuration.NeuralNetworkModelManager;
2425
import org.photonvision.common.configuration.PhotonConfiguration;
2526
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
@@ -52,8 +53,8 @@ public static UIPhotonConfiguration programStateToUi(PhotonConfiguration c) {
5253
new UIGeneralSettings(
5354
PhotonVersion.versionString,
5455
// TODO add support for other types of GPU accel
55-
LoadJNI.JNITypes.LIBCAMERA.hasLoaded() ? "Zerocopy Libcamera Working" : "",
56-
LoadJNI.JNITypes.MRCAL.hasLoaded(),
56+
LoadJNI.hasLoaded(JNITypes.LIBCAMERA) ? "Zerocopy Libcamera Working" : "",
57+
LoadJNI.hasLoaded(JNITypes.MRCAL),
5758
c.neuralNetworkPropertyManager().getModels(),
5859
NeuralNetworkModelManager.getInstance().getSupportedBackends(),
5960
c.getHardwareConfig().deviceName.isEmpty()

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

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
import org.opencv.core.*;
2929
import org.opencv.imgcodecs.Imgcodecs;
3030
import org.photonvision.common.LoadJNI;
31+
import org.photonvision.common.LoadJNI.JNITypes;
3132
import org.photonvision.common.logging.LogGroup;
3233
import org.photonvision.common.logging.Logger;
3334
import org.photonvision.common.util.math.MathUtils;
@@ -94,7 +95,7 @@ protected CameraCalibrationCoefficients process(CalibrationInput in) {
9495
CameraCalibrationCoefficients ret;
9596
var start = System.nanoTime();
9697

97-
if (LoadJNI.JNITypes.MRCAL.hasLoaded() && params.useMrCal) {
98+
if (LoadJNI.hasLoaded(JNITypes.MRCAL) && params.useMrCal) {
9899
logger.debug("Calibrating with mrcal!");
99100
ret =
100101
calibrateMrcal(

photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
import java.util.regex.Pattern;
2929
import java.util.stream.Stream;
3030
import org.photonvision.common.LoadJNI;
31+
import org.photonvision.common.LoadJNI.JNITypes;
3132
import org.photonvision.common.configuration.CameraConfiguration;
3233
import org.photonvision.common.configuration.ConfigManager;
3334
import org.photonvision.common.dataflow.DataChangeService;
@@ -301,7 +302,7 @@ protected List<PVCameraInfo> getConnectedCameras() {
301302
.filter(c -> !(String.join("", c.otherPaths()).contains("csi-video")))
302303
.filter(c -> !c.name().equals("unicam"))
303304
.forEach(cameraInfos::add);
304-
if (LoadJNI.JNITypes.LIBCAMERA.hasLoaded()) {
305+
if (LoadJNI.hasLoaded(JNITypes.LIBCAMERA)) {
305306
// find all CSI cameras (Raspberry Pi cameras)
306307
Stream.of(LibCameraJNI.getCameraNames())
307308
.map(

0 commit comments

Comments
 (0)