mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpiutil] Remove RuntimeDetector and simplify RuntimeLoader (#6600)
This commit is contained in:
@@ -17,8 +17,6 @@ import java.util.concurrent.atomic.AtomicBoolean;
|
||||
public class AprilTagJNI {
|
||||
static boolean libraryLoaded = false;
|
||||
|
||||
static RuntimeLoader<AprilTagJNI> loader = null;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
|
||||
@@ -48,10 +46,7 @@ public class AprilTagJNI {
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"apriltagjni", RuntimeLoader.getDefaultExtractionRoot(), AprilTagJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("apriltagjni");
|
||||
} catch (IOException ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
|
||||
@@ -29,15 +29,10 @@ class AprilTagDetectorTest {
|
||||
@SuppressWarnings("MemberName")
|
||||
AprilTagDetector detector;
|
||||
|
||||
static RuntimeLoader<Core> loader;
|
||||
|
||||
@BeforeAll
|
||||
static void beforeAll() {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
Core.NATIVE_LIBRARY_NAME, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary(Core.NATIVE_LIBRARY_NAME);
|
||||
} catch (IOException ex) {
|
||||
fail(ex);
|
||||
}
|
||||
|
||||
@@ -4,13 +4,13 @@
|
||||
|
||||
package edu.wpi.first.cscore;
|
||||
|
||||
import edu.wpi.first.util.RuntimeDetector;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main method. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
System.out.println(CameraServerJNI.getHostname());
|
||||
}
|
||||
|
||||
|
||||
@@ -15,8 +15,6 @@ import java.util.function.Consumer;
|
||||
public class CameraServerJNI {
|
||||
static boolean libraryLoaded = false;
|
||||
|
||||
static RuntimeLoader<CameraServerJNI> loader = null;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
|
||||
@@ -46,10 +44,7 @@ public class CameraServerJNI {
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"cscorejni", RuntimeLoader.getDefaultExtractionRoot(), CameraServerJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("cscorejni");
|
||||
} catch (IOException ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
@@ -67,10 +62,7 @@ public class CameraServerJNI {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"cscorejni", RuntimeLoader.getDefaultExtractionRoot(), CameraServerJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("cscorejni");
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -14,9 +14,6 @@ public final class OpenCvLoader {
|
||||
@SuppressWarnings("PMD.MutableStaticState")
|
||||
static boolean libraryLoaded;
|
||||
|
||||
@SuppressWarnings("PMD.MutableStaticState")
|
||||
static RuntimeLoader<Core> loader;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
|
||||
@@ -44,12 +41,9 @@ public final class OpenCvLoader {
|
||||
}
|
||||
|
||||
static {
|
||||
String opencvName = Core.NATIVE_LIBRARY_NAME;
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(opencvName, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
|
||||
loader.loadLibraryHashed();
|
||||
RuntimeLoader.loadLibrary(Core.NATIVE_LIBRARY_NAME);
|
||||
} catch (IOException ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
@@ -76,10 +70,7 @@ public final class OpenCvLoader {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
Core.NATIVE_LIBRARY_NAME, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary(Core.NATIVE_LIBRARY_NAME);
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -11,7 +11,6 @@ import java.util.concurrent.atomic.AtomicBoolean;
|
||||
/** Base class for all JNI wrappers. */
|
||||
public class JNIWrapper {
|
||||
static boolean libraryLoaded = false;
|
||||
static RuntimeLoader<JNIWrapper> loader = null;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
@@ -42,11 +41,8 @@ public class JNIWrapper {
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"wpiHaljni", RuntimeLoader.getDefaultExtractionRoot(), JNIWrapper.class);
|
||||
loader.loadLibrary();
|
||||
} catch (IOException ex) {
|
||||
RuntimeLoader.loadLibrary("wpiHaljni");
|
||||
} catch (Exception ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
}
|
||||
@@ -63,10 +59,7 @@ public class JNIWrapper {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"wpiHaljni", RuntimeLoader.getDefaultExtractionRoot(), JNIWrapper.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("wpiHaljni");
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -5,13 +5,13 @@
|
||||
package edu.wpi.first.ntcore;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.RuntimeDetector;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main method. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
NetworkTablesJNI.flush(NetworkTablesJNI.getDefaultInstance());
|
||||
}
|
||||
|
||||
|
||||
@@ -17,7 +17,6 @@ import java.util.concurrent.atomic.AtomicBoolean;
|
||||
/** NetworkTables JNI. */
|
||||
public final class NetworkTablesJNI {
|
||||
static boolean libraryLoaded = false;
|
||||
static RuntimeLoader<NetworkTablesJNI> loader = null;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
@@ -48,10 +47,7 @@ public final class NetworkTablesJNI {
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("ntcorejni");
|
||||
} catch (IOException ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
@@ -69,10 +65,7 @@ public final class NetworkTablesJNI {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("ntcorejni");
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -17,7 +17,6 @@ import java.util.concurrent.atomic.AtomicBoolean;
|
||||
/** NetworkTables JNI. */
|
||||
public final class NetworkTablesJNI {
|
||||
static boolean libraryLoaded = false;
|
||||
static RuntimeLoader<NetworkTablesJNI> loader = null;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
@@ -48,10 +47,7 @@ public final class NetworkTablesJNI {
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("ntcorejni");
|
||||
} catch (IOException ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
@@ -69,10 +65,7 @@ public final class NetworkTablesJNI {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("ntcorejni");
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -6,13 +6,13 @@ package edu.wpi.first.wpilibj.romi;
|
||||
|
||||
import edu.wpi.first.hal.HALUtil;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.RuntimeDetector;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main entry point. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
System.out.println(NetworkTablesJNI.now());
|
||||
System.out.println(HALUtil.getHALRuntimeType());
|
||||
}
|
||||
|
||||
@@ -86,10 +86,6 @@
|
||||
<Bug pattern="RV_RETURN_VALUE_IGNORED_BAD_PRACTICE" />
|
||||
<Source name="CombinedRuntimeLoader.java" />
|
||||
</Match>
|
||||
<Match>
|
||||
<Bug pattern="RV_RETURN_VALUE_IGNORED_BAD_PRACTICE" />
|
||||
<Source name="RuntimeLoader.java" />
|
||||
</Match>
|
||||
<Match>
|
||||
<Bug pattern="SF_SWITCH_FALLTHROUGH" />
|
||||
<Source name="CameraServer.java" />
|
||||
|
||||
@@ -6,13 +6,13 @@ package edu.wpi.first.wpilibj2.commands;
|
||||
|
||||
import edu.wpi.first.hal.HALUtil;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.RuntimeDetector;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main entry point. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
System.out.println(NetworkTablesJNI.now());
|
||||
System.out.println(HALUtil.getHALRuntimeType());
|
||||
}
|
||||
|
||||
@@ -6,13 +6,13 @@ package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.hal.HALUtil;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.RuntimeDetector;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main entry point. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
System.out.println(NetworkTablesJNI.now());
|
||||
System.out.println(HALUtil.getHALRuntimeType());
|
||||
}
|
||||
|
||||
@@ -11,16 +11,12 @@ import java.util.concurrent.atomic.AtomicBoolean;
|
||||
/** WPIMath JNI. */
|
||||
public final class WPIMathJNI {
|
||||
static boolean libraryLoaded = false;
|
||||
static RuntimeLoader<WPIMathJNI> loader = null;
|
||||
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"wpimathjni", RuntimeLoader.getDefaultExtractionRoot(), WPIMathJNI.class);
|
||||
loader.loadLibrary();
|
||||
} catch (IOException ex) {
|
||||
RuntimeLoader.loadLibrary("wpimathjni");
|
||||
} catch (Exception ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
}
|
||||
@@ -37,10 +33,7 @@ public final class WPIMathJNI {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"wpimathjni", RuntimeLoader.getDefaultExtractionRoot(), WPIMathJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("wpimathjni");
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -4,13 +4,13 @@
|
||||
|
||||
package edu.wpi.first.net;
|
||||
|
||||
import edu.wpi.first.util.RuntimeDetector;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main entry point. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
}
|
||||
|
||||
private DevMain() {}
|
||||
|
||||
@@ -11,7 +11,6 @@ import java.util.concurrent.atomic.AtomicBoolean;
|
||||
/** WPINet JNI. */
|
||||
public class WPINetJNI {
|
||||
static boolean libraryLoaded = false;
|
||||
static RuntimeLoader<WPINetJNI> loader = null;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
@@ -42,11 +41,8 @@ public class WPINetJNI {
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"wpinetjni", RuntimeLoader.getDefaultExtractionRoot(), WPINetJNI.class);
|
||||
loader.loadLibrary();
|
||||
} catch (IOException ex) {
|
||||
RuntimeLoader.loadLibrary("wpinetjni");
|
||||
} catch (Exception ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
}
|
||||
@@ -63,9 +59,7 @@ public class WPINetJNI {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>("wpinetjni", RuntimeLoader.getDefaultExtractionRoot(), WPINetJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("wpinetjni");
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@ public final class DevMain {
|
||||
/** Main entry point. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
}
|
||||
|
||||
private DevMain() {}
|
||||
|
||||
@@ -35,6 +35,48 @@ public final class CombinedRuntimeLoader {
|
||||
extractionDirectory = directory;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns platform path.
|
||||
*
|
||||
* @return The current platform path.
|
||||
* @throws IllegalStateException Thrown if the operating system is unknown.
|
||||
*/
|
||||
public static String getPlatformPath() {
|
||||
String filePath;
|
||||
String arch = System.getProperty("os.arch");
|
||||
|
||||
boolean intel32 = "x86".equals(arch) || "i386".equals(arch);
|
||||
boolean intel64 = "amd64".equals(arch) || "x86_64".equals(arch);
|
||||
|
||||
if (System.getProperty("os.name").startsWith("Windows")) {
|
||||
if (intel32) {
|
||||
filePath = "/windows/x86/";
|
||||
} else {
|
||||
filePath = "/windows/x86-64/";
|
||||
}
|
||||
} else if (System.getProperty("os.name").startsWith("Mac")) {
|
||||
filePath = "/osx/universal/";
|
||||
} else if (System.getProperty("os.name").startsWith("Linux")) {
|
||||
if (intel32) {
|
||||
filePath = "/linux/x86/";
|
||||
} else if (intel64) {
|
||||
filePath = "/linux/x86-64/";
|
||||
} else if (new File("/usr/local/frc/bin/frcRunRobot.sh").exists()) {
|
||||
filePath = "/linux/athena/";
|
||||
} else if ("arm".equals(arch) || "arm32".equals(arch)) {
|
||||
filePath = "/linux/arm32/";
|
||||
} else if ("aarch64".equals(arch) || "arm64".equals(arch)) {
|
||||
filePath = "/linux/arm64/";
|
||||
} else {
|
||||
filePath = "/linux/nativearm/";
|
||||
}
|
||||
} else {
|
||||
throw new IllegalStateException();
|
||||
}
|
||||
|
||||
return filePath;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets DLL directory.
|
||||
*
|
||||
@@ -47,11 +89,11 @@ public final class CombinedRuntimeLoader {
|
||||
StringBuilder msg = new StringBuilder(512);
|
||||
msg.append(libraryName)
|
||||
.append(" could not be loaded from path\n" + "\tattempted to load for platform ")
|
||||
.append(RuntimeDetector.getPlatformPath())
|
||||
.append(CombinedRuntimeLoader.getPlatformPath())
|
||||
.append("\nLast Load Error: \n")
|
||||
.append(ule.getMessage())
|
||||
.append('\n');
|
||||
if (RuntimeDetector.isWindows()) {
|
||||
if (System.getProperty("os.name").startsWith("Windows")) {
|
||||
msg.append(
|
||||
"A common cause of this error is missing the C++ runtime.\n"
|
||||
+ "Download the latest at https://support.microsoft.com/en-us/help/2977003/the-latest-supported-visual-c-downloads\n");
|
||||
@@ -78,7 +120,7 @@ public final class CombinedRuntimeLoader {
|
||||
map = mapper.readValue(stream, typeRef);
|
||||
}
|
||||
|
||||
var platformPath = Paths.get(RuntimeDetector.getPlatformPath());
|
||||
var platformPath = Paths.get(CombinedRuntimeLoader.getPlatformPath());
|
||||
var platform = platformPath.getName(0).toString();
|
||||
var arch = platformPath.getName(1).toString();
|
||||
|
||||
@@ -91,7 +133,7 @@ public final class CombinedRuntimeLoader {
|
||||
if (extractionPathString == null) {
|
||||
String hash = (String) map.get("hash");
|
||||
|
||||
var defaultExtractionRoot = RuntimeLoader.getDefaultExtractionRoot();
|
||||
var defaultExtractionRoot = CombinedRuntimeLoader.getExtractionDirectory();
|
||||
var extractionPath = Paths.get(defaultExtractionRoot, platform, arch, hash);
|
||||
extractionPathString = extractionPath.toString();
|
||||
|
||||
@@ -141,7 +183,7 @@ public final class CombinedRuntimeLoader {
|
||||
String currentPath = null;
|
||||
String oldDllDirectory = null;
|
||||
try {
|
||||
if (RuntimeDetector.isWindows()) {
|
||||
if (System.getProperty("os.name").startsWith("Windows")) {
|
||||
var extractionPathString = getExtractionDirectory();
|
||||
oldDllDirectory = setDllDirectory(extractionPathString);
|
||||
}
|
||||
@@ -180,7 +222,7 @@ public final class CombinedRuntimeLoader {
|
||||
String currentPath = "";
|
||||
|
||||
try {
|
||||
if (RuntimeDetector.isWindows()) {
|
||||
if (System.getProperty("os.name").startsWith("Windows")) {
|
||||
var extractionPathString = getExtractionDirectory();
|
||||
// Load windows, set dll directory
|
||||
currentPath = Paths.get(extractionPathString, "WindowsLoaderHelper.dll").toString();
|
||||
|
||||
@@ -1,194 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.util;
|
||||
|
||||
import java.io.File;
|
||||
|
||||
/**
|
||||
* A utility class for detecting and providing platform-specific such as OS and CPU architecture.
|
||||
*/
|
||||
public final class RuntimeDetector {
|
||||
private static String filePrefix;
|
||||
private static String fileExtension;
|
||||
private static String filePath;
|
||||
|
||||
private static synchronized void computePlatform() {
|
||||
if (fileExtension != null && filePath != null && filePrefix != null) {
|
||||
return;
|
||||
}
|
||||
|
||||
boolean intel32 = is32BitIntel();
|
||||
boolean intel64 = is64BitIntel();
|
||||
boolean arm64 = isArm64();
|
||||
|
||||
if (isWindows()) {
|
||||
filePrefix = "";
|
||||
fileExtension = ".dll";
|
||||
if (intel32) {
|
||||
filePath = "/windows/x86/";
|
||||
} else {
|
||||
filePath = "/windows/x86-64/";
|
||||
}
|
||||
} else if (isMac()) {
|
||||
filePrefix = "lib";
|
||||
fileExtension = ".dylib";
|
||||
filePath = "/osx/universal/";
|
||||
} else if (isLinux()) {
|
||||
filePrefix = "lib";
|
||||
fileExtension = ".so";
|
||||
if (intel32) {
|
||||
filePath = "/linux/x86/";
|
||||
} else if (intel64) {
|
||||
filePath = "/linux/x86-64/";
|
||||
} else if (isAthena()) {
|
||||
filePath = "/linux/athena/";
|
||||
} else if (isArm32()) {
|
||||
filePath = "/linux/arm32/";
|
||||
} else if (arm64) {
|
||||
filePath = "/linux/arm64/";
|
||||
} else {
|
||||
filePath = "/linux/nativearm/";
|
||||
}
|
||||
} else {
|
||||
throw new IllegalStateException("Failed to determine OS");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the file prefix for the current system.
|
||||
*
|
||||
* @return The file prefix.
|
||||
*/
|
||||
public static synchronized String getFilePrefix() {
|
||||
computePlatform();
|
||||
|
||||
return filePrefix;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the file extension for the current system.
|
||||
*
|
||||
* @return The file extension.
|
||||
*/
|
||||
public static synchronized String getFileExtension() {
|
||||
computePlatform();
|
||||
|
||||
return fileExtension;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the platform path for the current system.
|
||||
*
|
||||
* @return The platform path.
|
||||
*/
|
||||
public static synchronized String getPlatformPath() {
|
||||
computePlatform();
|
||||
|
||||
return filePath;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the path to the requested resource.
|
||||
*
|
||||
* @param libName Library name.
|
||||
* @return The path to the requested resource.
|
||||
*/
|
||||
public static synchronized String getLibraryResource(String libName) {
|
||||
computePlatform();
|
||||
|
||||
return filePath + filePrefix + libName + fileExtension;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the path to the hash to the requested resource.
|
||||
*
|
||||
* @param libName Library name.
|
||||
* @return The path to the hash to the requested resource.
|
||||
*/
|
||||
public static synchronized String getHashLibraryResource(String libName) {
|
||||
computePlatform();
|
||||
|
||||
return filePath + libName + ".hash";
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if hardware platform is Athena.
|
||||
*
|
||||
* @return True if hardware platform is Athena.
|
||||
*/
|
||||
public static boolean isAthena() {
|
||||
File runRobotFile = new File("/usr/local/frc/bin/frcRunRobot.sh");
|
||||
return runRobotFile.exists();
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if OS is Arm32.
|
||||
*
|
||||
* @return True if OS is Arm32.
|
||||
*/
|
||||
public static boolean isArm32() {
|
||||
String arch = System.getProperty("os.arch");
|
||||
return "arm".equals(arch) || "arm32".equals(arch);
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if architecture is Arm64.
|
||||
*
|
||||
* @return if architecture is Arm64.
|
||||
*/
|
||||
public static boolean isArm64() {
|
||||
String arch = System.getProperty("os.arch");
|
||||
return "aarch64".equals(arch) || "arm64".equals(arch);
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if OS is Linux.
|
||||
*
|
||||
* @return if OS is Linux.
|
||||
*/
|
||||
public static boolean isLinux() {
|
||||
return System.getProperty("os.name").startsWith("Linux");
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if OS is Windows.
|
||||
*
|
||||
* @return if OS is Windows.
|
||||
*/
|
||||
public static boolean isWindows() {
|
||||
return System.getProperty("os.name").startsWith("Windows");
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if OS is Mac.
|
||||
*
|
||||
* @return if OS is Mac.
|
||||
*/
|
||||
public static boolean isMac() {
|
||||
return System.getProperty("os.name").startsWith("Mac");
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if OS is 32bit Intel.
|
||||
*
|
||||
* @return if OS is 32bit Intel.
|
||||
*/
|
||||
public static boolean is32BitIntel() {
|
||||
String arch = System.getProperty("os.arch");
|
||||
return "x86".equals(arch) || "i386".equals(arch);
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if OS is 64bit Intel.
|
||||
*
|
||||
* @return if OS is 64bit Intel.
|
||||
*/
|
||||
public static boolean is64BitIntel() {
|
||||
String arch = System.getProperty("os.arch");
|
||||
return "amd64".equals(arch) || "x86_64".equals(arch);
|
||||
}
|
||||
|
||||
private RuntimeDetector() {}
|
||||
}
|
||||
@@ -4,75 +4,26 @@
|
||||
|
||||
package edu.wpi.first.util;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import java.io.InputStream;
|
||||
import java.io.OutputStream;
|
||||
import java.nio.charset.StandardCharsets;
|
||||
import java.nio.file.Files;
|
||||
import java.nio.file.Paths;
|
||||
import java.security.DigestInputStream;
|
||||
import java.security.MessageDigest;
|
||||
import java.security.NoSuchAlgorithmException;
|
||||
import java.util.Locale;
|
||||
import java.util.Scanner;
|
||||
|
||||
/**
|
||||
* Loads a native library at runtime.
|
||||
*
|
||||
* @param <T> The class to load.
|
||||
*/
|
||||
public final class RuntimeLoader<T> {
|
||||
private static String defaultExtractionRoot;
|
||||
|
||||
/**
|
||||
* Gets the default extraction root location (~/.wpilib/nativecache).
|
||||
*
|
||||
* @return The default extraction root location.
|
||||
*/
|
||||
public static synchronized String getDefaultExtractionRoot() {
|
||||
if (defaultExtractionRoot != null) {
|
||||
return defaultExtractionRoot;
|
||||
}
|
||||
String home = System.getProperty("user.home");
|
||||
defaultExtractionRoot = Paths.get(home, ".wpilib", "nativecache").toString();
|
||||
return defaultExtractionRoot;
|
||||
}
|
||||
|
||||
private final String m_libraryName;
|
||||
private final Class<T> m_loadClass;
|
||||
private final String m_extractionRoot;
|
||||
|
||||
/**
|
||||
* Creates a new library loader.
|
||||
*
|
||||
* @param libraryName Name of library to load.
|
||||
* @param extractionRoot Location from which to load the library.
|
||||
* @param cls Class whose classpath the given library belongs.
|
||||
*/
|
||||
public RuntimeLoader(String libraryName, String extractionRoot, Class<T> cls) {
|
||||
m_libraryName = libraryName;
|
||||
m_loadClass = cls;
|
||||
m_extractionRoot = extractionRoot;
|
||||
}
|
||||
|
||||
/** Loads a native library at runtime. */
|
||||
public final class RuntimeLoader {
|
||||
/**
|
||||
* Returns a load error message given the information in the provided UnsatisfiedLinkError.
|
||||
*
|
||||
* @param libraryName the name of the library that failed to load.
|
||||
* @param ule UnsatisfiedLinkError object.
|
||||
* @return A load error message.
|
||||
*/
|
||||
private String getLoadErrorMessage(UnsatisfiedLinkError ule) {
|
||||
private static String getLoadErrorMessage(String libraryName, UnsatisfiedLinkError ule) {
|
||||
StringBuilder msg = new StringBuilder(512);
|
||||
msg.append(m_libraryName)
|
||||
.append(
|
||||
" could not be loaded from path or an embedded resource.\n"
|
||||
+ "\tattempted to load for platform ")
|
||||
.append(RuntimeDetector.getPlatformPath())
|
||||
msg.append(libraryName)
|
||||
.append(" could not be loaded from path.\n" + "\tattempted to load for platform ")
|
||||
.append(CombinedRuntimeLoader.getPlatformPath())
|
||||
.append("\nLast Load Error: \n")
|
||||
.append(ule.getMessage())
|
||||
.append('\n');
|
||||
if (RuntimeDetector.isWindows()) {
|
||||
if (System.getProperty("os.name").startsWith("Windows")) {
|
||||
msg.append(
|
||||
"A common cause of this error is missing the C++ runtime.\n"
|
||||
+ "Download the latest at https://support.microsoft.com/en-us/help/2977003/the-latest-supported-visual-c-downloads\n");
|
||||
@@ -83,120 +34,18 @@ public final class RuntimeLoader<T> {
|
||||
/**
|
||||
* Loads a native library.
|
||||
*
|
||||
* @param libraryName the name of the library to load.
|
||||
* @throws IOException if the library fails to load
|
||||
*/
|
||||
public void loadLibrary() throws IOException {
|
||||
public static void loadLibrary(String libraryName) throws IOException {
|
||||
try {
|
||||
// First, try loading path
|
||||
System.loadLibrary(m_libraryName);
|
||||
System.loadLibrary(libraryName);
|
||||
} catch (UnsatisfiedLinkError ule) {
|
||||
// Then load the hash from the resources
|
||||
String hashName = RuntimeDetector.getHashLibraryResource(m_libraryName);
|
||||
String resName = RuntimeDetector.getLibraryResource(m_libraryName);
|
||||
try (InputStream hashIs = m_loadClass.getResourceAsStream(hashName)) {
|
||||
if (hashIs == null) {
|
||||
throw new IOException(getLoadErrorMessage(ule));
|
||||
}
|
||||
try (Scanner scanner = new Scanner(hashIs, StandardCharsets.UTF_8)) {
|
||||
String hash = scanner.nextLine();
|
||||
File jniLibrary = new File(m_extractionRoot, resName + "." + hash);
|
||||
try {
|
||||
// Try to load from an already extracted hash
|
||||
System.load(jniLibrary.getAbsolutePath());
|
||||
} catch (UnsatisfiedLinkError ule2) {
|
||||
// If extraction failed, extract
|
||||
try (InputStream resIs = m_loadClass.getResourceAsStream(resName)) {
|
||||
if (resIs == null) {
|
||||
throw new IOException(getLoadErrorMessage(ule));
|
||||
}
|
||||
|
||||
var parentFile = jniLibrary.getParentFile();
|
||||
if (parentFile == null) {
|
||||
throw new IOException("JNI library has no parent file");
|
||||
}
|
||||
parentFile.mkdirs();
|
||||
|
||||
try (OutputStream os = Files.newOutputStream(jniLibrary.toPath())) {
|
||||
byte[] buffer = new byte[0xFFFF]; // 64K copy buffer
|
||||
int readBytes;
|
||||
while ((readBytes = resIs.read(buffer)) != -1) { // NOPMD
|
||||
os.write(buffer, 0, readBytes);
|
||||
}
|
||||
}
|
||||
System.load(jniLibrary.getAbsolutePath());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
throw new IOException(getLoadErrorMessage(libraryName, ule));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Load a native library by directly hashing the file.
|
||||
*
|
||||
* @throws IOException if the library failed to load
|
||||
*/
|
||||
public void loadLibraryHashed() throws IOException {
|
||||
try {
|
||||
// First, try loading path
|
||||
System.loadLibrary(m_libraryName);
|
||||
} catch (UnsatisfiedLinkError ule) {
|
||||
// Then load the hash from the input file
|
||||
String resName = RuntimeDetector.getLibraryResource(m_libraryName);
|
||||
String hash;
|
||||
try (InputStream is = m_loadClass.getResourceAsStream(resName)) {
|
||||
if (is == null) {
|
||||
throw new IOException(getLoadErrorMessage(ule));
|
||||
}
|
||||
MessageDigest md;
|
||||
try {
|
||||
md = MessageDigest.getInstance("MD5");
|
||||
} catch (NoSuchAlgorithmException nsae) {
|
||||
throw new RuntimeException("Weird Hash Algorithm?");
|
||||
}
|
||||
try (DigestInputStream dis = new DigestInputStream(is, md)) {
|
||||
// Read the entire buffer once to hash
|
||||
byte[] buffer = new byte[0xFFFF];
|
||||
while (dis.read(buffer) > -1) {}
|
||||
MessageDigest digest = dis.getMessageDigest();
|
||||
byte[] digestOutput = digest.digest();
|
||||
StringBuilder builder = new StringBuilder();
|
||||
for (byte b : digestOutput) {
|
||||
builder.append(String.format("%02X", b));
|
||||
}
|
||||
hash = builder.toString().toLowerCase(Locale.ENGLISH);
|
||||
}
|
||||
}
|
||||
if (hash == null) {
|
||||
throw new IOException("Weird Hash?");
|
||||
}
|
||||
File jniLibrary = new File(m_extractionRoot, resName + "." + hash);
|
||||
try {
|
||||
// Try to load from an already extracted hash
|
||||
System.load(jniLibrary.getAbsolutePath());
|
||||
} catch (UnsatisfiedLinkError ule2) {
|
||||
// If extraction failed, extract
|
||||
try (InputStream resIs = m_loadClass.getResourceAsStream(resName)) {
|
||||
if (resIs == null) {
|
||||
throw new IOException(getLoadErrorMessage(ule));
|
||||
}
|
||||
|
||||
var parentFile = jniLibrary.getParentFile();
|
||||
if (parentFile == null) {
|
||||
throw new IOException("JNI library has no parent file");
|
||||
}
|
||||
parentFile.mkdirs();
|
||||
|
||||
try (OutputStream os = Files.newOutputStream(jniLibrary.toPath())) {
|
||||
byte[] buffer = new byte[0xFFFF]; // 64K copy buffer
|
||||
int readBytes;
|
||||
while ((readBytes = resIs.read(buffer)) != -1) { // NOPMD
|
||||
os.write(buffer, 0, readBytes);
|
||||
}
|
||||
}
|
||||
System.load(jniLibrary.getAbsolutePath());
|
||||
}
|
||||
}
|
||||
}
|
||||
private RuntimeLoader() {
|
||||
throw new IllegalStateException("This class shouldn't be instantiated");
|
||||
}
|
||||
}
|
||||
|
||||
@@ -11,7 +11,6 @@ import java.util.concurrent.atomic.AtomicBoolean;
|
||||
/** WPIUtil JNI. */
|
||||
public class WPIUtilJNI {
|
||||
static boolean libraryLoaded = false;
|
||||
static RuntimeLoader<WPIUtilJNI> loader = null;
|
||||
|
||||
/** Sets whether JNI should be loaded in the static block. */
|
||||
public static class Helper {
|
||||
@@ -42,11 +41,8 @@ public class WPIUtilJNI {
|
||||
static {
|
||||
if (Helper.getExtractOnStaticLoad()) {
|
||||
try {
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"wpiutiljni", RuntimeLoader.getDefaultExtractionRoot(), WPIUtilJNI.class);
|
||||
loader.loadLibrary();
|
||||
} catch (IOException ex) {
|
||||
RuntimeLoader.loadLibrary("wpiutiljni");
|
||||
} catch (Exception ex) {
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
}
|
||||
@@ -63,10 +59,7 @@ public class WPIUtilJNI {
|
||||
if (libraryLoaded) {
|
||||
return;
|
||||
}
|
||||
loader =
|
||||
new RuntimeLoader<>(
|
||||
"wpiutiljni", RuntimeLoader.getDefaultExtractionRoot(), WPIUtilJNI.class);
|
||||
loader.loadLibrary();
|
||||
RuntimeLoader.loadLibrary("wpiutiljni");
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
|
||||
@@ -6,13 +6,13 @@ package edu.wpi.first.wpilibj.xrp;
|
||||
|
||||
import edu.wpi.first.hal.HALUtil;
|
||||
import edu.wpi.first.networktables.NetworkTablesJNI;
|
||||
import edu.wpi.first.util.RuntimeDetector;
|
||||
import edu.wpi.first.util.CombinedRuntimeLoader;
|
||||
|
||||
public final class DevMain {
|
||||
/** Main entry point. */
|
||||
public static void main(String[] args) {
|
||||
System.out.println("Hello World!");
|
||||
System.out.println(RuntimeDetector.getPlatformPath());
|
||||
System.out.println(CombinedRuntimeLoader.getPlatformPath());
|
||||
System.out.println(NetworkTablesJNI.now());
|
||||
System.out.println(HALUtil.getHALRuntimeType());
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user