[wpimath] Add a base JNI class for WPIMath (#6793)

Co-authored-by: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com>
This commit is contained in:
Thad House
2024-07-07 06:38:05 -07:00
committed by GitHub
parent 537976c426
commit 1c42c1c920
8 changed files with 75 additions and 404 deletions

View File

@@ -4,39 +4,8 @@
package edu.wpi.first.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** ArmFeedforward JNI. */
public final class ArmFeedforwardJNI {
static boolean libraryLoaded = false;
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException If the library could not be loaded or found.
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
public final class ArmFeedforwardJNI extends WPIMathJNI {
/**
* Obtain a feedforward voltage from a single jointed arm feedforward object.
*
@@ -62,32 +31,6 @@ public final class ArmFeedforwardJNI {
double nextVelocity,
double dt);
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
/** Utility class. */
private ArmFeedforwardJNI() {}
}

View File

@@ -4,39 +4,8 @@
package edu.wpi.first.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** DARE JNI. */
public final class DAREJNI {
static boolean libraryLoaded = false;
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException If the library could not be loaded or found.
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
public final class DAREJNI extends WPIMathJNI {
/**
* Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation.
*
@@ -202,32 +171,6 @@ public final class DAREJNI {
int inputs,
double[] S);
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
/** Utility class. */
private DAREJNI() {}
}

View File

@@ -4,39 +4,8 @@
package edu.wpi.first.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** Eigen JNI. */
public final class EigenJNI {
static boolean libraryLoaded = false;
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException If the library could not be loaded or found.
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
public final class EigenJNI extends WPIMathJNI {
/**
* Computes the matrix exp.
*
@@ -83,32 +52,6 @@ public final class EigenJNI {
public static native void solveFullPivHouseholderQr(
double[] A, int Arows, int Acols, double[] B, int Brows, int Bcols, double[] dst);
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
/** Utility class. */
private EigenJNI() {}
}

View File

@@ -4,39 +4,8 @@
package edu.wpi.first.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** Ellipse2d JNI. */
public final class Ellipse2dJNI {
static boolean libraryLoaded = false;
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException If the library could not be loaded or found.
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
public final class Ellipse2dJNI extends WPIMathJNI {
/**
* Returns the nearest point that is contained within the ellipse.
*
@@ -61,32 +30,6 @@ public final class Ellipse2dJNI {
double pointY,
double[] nearestPoint);
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
/** Utility class. */
private Ellipse2dJNI() {}
}

View File

@@ -4,39 +4,8 @@
package edu.wpi.first.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** Pose3d JNI. */
public final class Pose3dJNI {
static boolean libraryLoaded = false;
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException If the library could not be loaded or found.
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
public final class Pose3dJNI extends WPIMathJNI {
/**
* Obtain a Pose3d from a (constant curvature) velocity.
*
@@ -109,32 +78,6 @@ public final class Pose3dJNI {
double endQy,
double endQz);
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
/** Utility class. */
private Pose3dJNI() {}
}

View File

@@ -4,39 +4,8 @@
package edu.wpi.first.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** StateSpaceUtil JNI. */
public final class StateSpaceUtilJNI {
static boolean libraryLoaded = false;
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException If the library could not be loaded or found.
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
public final class StateSpaceUtilJNI extends WPIMathJNI {
/**
* Returns true if (A, B) is a stabilizable pair.
*
@@ -52,32 +21,6 @@ public final class StateSpaceUtilJNI {
*/
public static native boolean isStabilizable(int states, int inputs, double[] A, double[] B);
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
/** Utility class. */
private StateSpaceUtilJNI() {}
}

View File

@@ -4,39 +4,10 @@
package edu.wpi.first.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** TrajectoryUtil JNI. */
public final class TrajectoryUtilJNI {
static boolean libraryLoaded = false;
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException If the library could not be loaded or found.
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
public final class TrajectoryUtilJNI extends WPIMathJNI {
/**
* Loads a Pathweaver JSON.
*
@@ -71,32 +42,6 @@ public final class TrajectoryUtilJNI {
*/
public static native String serializeTrajectory(double[] elements);
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
/** Utility class. */
private TrajectoryUtilJNI() {}
}

View File

@@ -0,0 +1,68 @@
// 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.math.jni;
import edu.wpi.first.util.RuntimeLoader;
import java.io.IOException;
import java.util.concurrent.atomic.AtomicBoolean;
/** Base class for all WPIMath JNI wrappers. */
public class WPIMathJNI {
private static boolean libraryLoaded = false;
/** Sets whether JNI should be loaded in the static block. */
public static class Helper {
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
/**
* Returns true if the JNI should be loaded in the static block.
*
* @return True if the JNI should be loaded in the static block.
*/
public static boolean getExtractOnStaticLoad() {
return extractOnStaticLoad.get();
}
/**
* Sets whether the JNI should be loaded in the static block.
*
* @param load Whether the JNI should be loaded in the static block.
*/
public static void setExtractOnStaticLoad(boolean load) {
extractOnStaticLoad.set(load);
}
/** Utility class. */
private Helper() {}
}
static {
if (Helper.getExtractOnStaticLoad()) {
try {
RuntimeLoader.loadLibrary("wpimathjni");
} catch (Exception ex) {
ex.printStackTrace();
System.exit(1);
}
libraryLoaded = true;
}
}
/**
* Force load the library.
*
* @throws IOException if the library load failed
*/
public static synchronized void forceLoad() throws IOException {
if (libraryLoaded) {
return;
}
RuntimeLoader.loadLibrary("wpimathjni");
libraryLoaded = true;
}
/** Utility class. */
protected WPIMathJNI() {}
}