2020-12-26 14:12:05 -08:00
|
|
|
// 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.
|
2020-07-24 08:34:30 -07:00
|
|
|
|
2020-08-07 09:38:13 -07:00
|
|
|
package edu.wpi.first.math;
|
2020-07-24 08:34:30 -07:00
|
|
|
|
2020-12-29 22:45:16 -08:00
|
|
|
import edu.wpi.first.wpiutil.RuntimeLoader;
|
2020-07-24 08:34:30 -07:00
|
|
|
import java.io.IOException;
|
|
|
|
|
import java.util.concurrent.atomic.AtomicBoolean;
|
|
|
|
|
|
2020-08-07 09:38:13 -07:00
|
|
|
public final class WPIMathJNI {
|
2020-07-24 08:34:30 -07:00
|
|
|
static boolean libraryLoaded = false;
|
2020-08-07 09:38:13 -07:00
|
|
|
static RuntimeLoader<WPIMathJNI> loader = null;
|
2020-07-24 08:34:30 -07:00
|
|
|
|
|
|
|
|
static {
|
|
|
|
|
if (Helper.getExtractOnStaticLoad()) {
|
|
|
|
|
try {
|
2020-12-29 22:45:16 -08:00
|
|
|
loader =
|
|
|
|
|
new RuntimeLoader<>(
|
|
|
|
|
"wpimathjni", RuntimeLoader.getDefaultExtractionRoot(), WPIMathJNI.class);
|
2020-07-24 08:34:30 -07:00
|
|
|
loader.loadLibrary();
|
|
|
|
|
} catch (IOException 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;
|
|
|
|
|
}
|
2020-12-29 22:45:16 -08:00
|
|
|
loader =
|
|
|
|
|
new RuntimeLoader<>(
|
|
|
|
|
"wpimathjni", RuntimeLoader.getDefaultExtractionRoot(), WPIMathJNI.class);
|
2020-07-24 08:34:30 -07:00
|
|
|
loader.loadLibrary();
|
|
|
|
|
libraryLoaded = true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Solves the discrete alegebraic Riccati equation.
|
|
|
|
|
*
|
2020-12-29 22:45:16 -08:00
|
|
|
* @param A Array containing elements of A in row-major order.
|
|
|
|
|
* @param B Array containing elements of B in row-major order.
|
|
|
|
|
* @param Q Array containing elements of Q in row-major order.
|
|
|
|
|
* @param R Array containing elements of R in row-major order.
|
2020-07-24 08:34:30 -07:00
|
|
|
* @param states Number of states in A matrix.
|
|
|
|
|
* @param inputs Number of inputs in B matrix.
|
2020-12-29 22:45:16 -08:00
|
|
|
* @param S Array storage for DARE solution.
|
2020-07-24 08:34:30 -07:00
|
|
|
*/
|
|
|
|
|
public static native void discreteAlgebraicRiccatiEquation(
|
2020-12-29 22:45:16 -08:00
|
|
|
double[] A, double[] B, double[] Q, double[] R, int states, int inputs, double[] S);
|
2020-07-24 08:34:30 -07:00
|
|
|
|
2020-08-16 17:16:53 -07:00
|
|
|
/**
|
|
|
|
|
* Computes the matrix exp.
|
|
|
|
|
*
|
2020-12-29 22:45:16 -08:00
|
|
|
* @param src Array of elements of the matrix to be exponentiated.
|
2020-11-20 15:28:00 -08:00
|
|
|
* @param rows How many rows there are.
|
2020-12-29 22:45:16 -08:00
|
|
|
* @param dst Array where the result will be stored.
|
2020-08-16 17:16:53 -07:00
|
|
|
*/
|
|
|
|
|
public static native void exp(double[] src, int rows, double[] dst);
|
|
|
|
|
|
2020-11-20 15:28:00 -08:00
|
|
|
/**
|
|
|
|
|
* Computes the matrix pow.
|
|
|
|
|
*
|
2020-12-29 22:45:16 -08:00
|
|
|
* @param src Array of elements of the matrix to be raised to a power.
|
|
|
|
|
* @param rows How many rows there are.
|
2020-11-20 15:28:00 -08:00
|
|
|
* @param exponent The exponent.
|
2020-12-29 22:45:16 -08:00
|
|
|
* @param dst Array where the result will be stored.
|
2020-11-20 15:28:00 -08:00
|
|
|
*/
|
|
|
|
|
public static native void pow(double[] src, int rows, double exponent, double[] dst);
|
|
|
|
|
|
2020-08-16 17:16:53 -07:00
|
|
|
/**
|
|
|
|
|
* Returns true if (A, B) is a stabilizable pair.
|
|
|
|
|
*
|
2020-12-29 22:45:16 -08:00
|
|
|
* <p>(A,B) is stabilizable if and only if the uncontrollable eigenvalues of A, if any, have
|
|
|
|
|
* absolute values less than one, where an eigenvalue is uncontrollable if rank(lambda * I - A, B)
|
|
|
|
|
* < n where n is number of states.
|
2020-08-16 17:16:53 -07:00
|
|
|
*
|
|
|
|
|
* @param states the number of states of the system.
|
|
|
|
|
* @param inputs the number of inputs to the system.
|
2020-12-29 22:45:16 -08:00
|
|
|
* @param A System matrix.
|
|
|
|
|
* @param B Input matrix.
|
2020-08-16 17:16:53 -07:00
|
|
|
* @return If the system is stabilizable.
|
|
|
|
|
*/
|
|
|
|
|
public static native boolean isStabilizable(int states, int inputs, double[] A, double[] B);
|
|
|
|
|
|
2021-03-21 15:38:23 -04:00
|
|
|
/**
|
|
|
|
|
* Loads a Pathweaver JSON.
|
|
|
|
|
*
|
|
|
|
|
* @param path The path to the JSON.
|
|
|
|
|
* @return A double array with the trajectory states from the JSON.
|
|
|
|
|
*/
|
|
|
|
|
public static native double[] fromPathweaverJson(String path) throws IOException;
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Converts a trajectory into a Pathweaver JSON and saves it.
|
|
|
|
|
*
|
|
|
|
|
* @param elements The elements of the trajectory.
|
|
|
|
|
* @param path The location to save the JSON to.
|
|
|
|
|
*/
|
|
|
|
|
public static native void toPathweaverJson(double[] elements, String path) throws IOException;
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Deserializes a trajectory JSON into a double[] of trajectory elements.
|
|
|
|
|
*
|
|
|
|
|
* @param json The JSON containing the serialized trajectory.
|
|
|
|
|
* @return A double array with the trajectory states.
|
|
|
|
|
*/
|
|
|
|
|
public static native double[] deserializeTrajectory(String json);
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Serializes the trajectory into a JSON string.
|
|
|
|
|
*
|
|
|
|
|
* @param elements The elements of the trajectory.
|
|
|
|
|
* @return A JSON containing the serialized trajectory.
|
|
|
|
|
*/
|
|
|
|
|
public static native String serializeTrajectory(double[] elements);
|
|
|
|
|
|
2020-07-24 08:34:30 -07:00
|
|
|
public static class Helper {
|
|
|
|
|
private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
|
|
|
|
|
|
|
|
|
|
public static boolean getExtractOnStaticLoad() {
|
|
|
|
|
return extractOnStaticLoad.get();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public static void setExtractOnStaticLoad(boolean load) {
|
|
|
|
|
extractOnStaticLoad.set(load);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|