Skip to content

Commit

Permalink
[wpimath] Add a base JNI class for WPIMath (#6793)
Browse files Browse the repository at this point in the history
Co-authored-by: Joseph Eng <[email protected]>
  • Loading branch information
ThadHouse and KangarooKoala authored Jul 7, 2024
1 parent 537976c commit 1c42c1c
Show file tree
Hide file tree
Showing 8 changed files with 75 additions and 404 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*
Expand All @@ -62,32 +31,6 @@ public static native double calculate(
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() {}
}
59 changes: 1 addition & 58 deletions wpimath/src/main/java/edu/wpi/first/math/jni/DAREJNI.java
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*
Expand Down Expand Up @@ -202,32 +171,6 @@ public static native void dareABQRN(
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() {}
}
59 changes: 1 addition & 58 deletions wpimath/src/main/java/edu/wpi/first/math/jni/EigenJNI.java
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*
Expand Down Expand Up @@ -83,32 +52,6 @@ public static native void rankUpdate(
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() {}
}
59 changes: 1 addition & 58 deletions wpimath/src/main/java/edu/wpi/first/math/jni/Ellipse2dJNI.java
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*
Expand All @@ -61,32 +30,6 @@ public static native void findNearestPoint(
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() {}
}
59 changes: 1 addition & 58 deletions wpimath/src/main/java/edu/wpi/first/math/jni/Pose3dJNI.java
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*
Expand Down Expand Up @@ -109,32 +78,6 @@ public static native double[] log(
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() {}
}
Loading

0 comments on commit 1c42c1c

Please sign in to comment.