Package edu.wpi.first.math
Class WPIMathJNI
java.lang.Object
edu.wpi.first.math.WPIMathJNI
public final class WPIMathJNI extends Object
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
WPIMathJNI.Helper
-
Constructor Summary
Constructors Constructor Description WPIMathJNI()
-
Method Summary
Modifier and Type Method Description static double[]
deserializeTrajectory(String json)
Deserializes a trajectory JSON into a double[] of trajectory elements.static void
discreteAlgebraicRiccatiEquation(double[] A, double[] B, double[] Q, double[] R, int states, int inputs, double[] S)
Solves the discrete alegebraic Riccati equation.static void
exp(double[] src, int rows, double[] dst)
Computes the matrix exp.static void
forceLoad()
Force load the library.static double[]
fromPathweaverJson(String path)
Loads a Pathweaver JSON.static boolean
isStabilizable(int states, int inputs, double[] A, double[] B)
Returns true if (A, B) is a stabilizable pair.static void
pow(double[] src, int rows, double exponent, double[] dst)
Computes the matrix pow.static void
rankUpdate(double[] mat, int rows, double[] vec, double sigma, boolean lowerTriangular)
Performs an inplace rank one update (or downdate) of an upper triangular Cholesky decomposition matrix.static String
serializeTrajectory(double[] elements)
Serializes the trajectory into a JSON string.static void
solveFullPivHouseholderQr(double[] A, int Arows, int Acols, double[] B, int Brows, int Bcols, double[] dst)
Solves the least-squares problem Ax=B using a QR decomposition with full pivoting.static void
toPathweaverJson(double[] elements, String path)
Converts a trajectory into a Pathweaver JSON and saves it.
-
Constructor Details
-
WPIMathJNI
public WPIMathJNI()
-
-
Method Details
-
forceLoad
Force load the library.- Throws:
IOException
- If the library could not be loaded or found.
-
discreteAlgebraicRiccatiEquation
public static void discreteAlgebraicRiccatiEquation(double[] A, double[] B, double[] Q, double[] R, int states, int inputs, double[] S)Solves the discrete alegebraic Riccati equation.- Parameters:
A
- Array containing elements of A in row-major order.B
- Array containing elements of B in row-major order.Q
- Array containing elements of Q in row-major order.R
- Array containing elements of R in row-major order.states
- Number of states in A matrix.inputs
- Number of inputs in B matrix.S
- Array storage for DARE solution.
-
exp
Computes the matrix exp.- Parameters:
src
- Array of elements of the matrix to be exponentiated.rows
- How many rows there are.dst
- Array where the result will be stored.
-
pow
Computes the matrix pow.- Parameters:
src
- Array of elements of the matrix to be raised to a power.rows
- How many rows there are.exponent
- The exponent.dst
- Array where the result will be stored.
-
isStabilizable
Returns true if (A, B) is a stabilizable pair.(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 the number of states.
- Parameters:
states
- the number of states of the system.inputs
- the number of inputs to the system.A
- System matrix.B
- Input matrix.- Returns:
- If the system is stabilizable.
-
fromPathweaverJson
Loads a Pathweaver JSON.- Parameters:
path
- The path to the JSON.- Returns:
- A double array with the trajectory states from the JSON.
- Throws:
IOException
- if the JSON could not be read.
-
toPathweaverJson
Converts a trajectory into a Pathweaver JSON and saves it.- Parameters:
elements
- The elements of the trajectory.path
- The location to save the JSON to.- Throws:
IOException
- if the JSON could not be written.
-
deserializeTrajectory
Deserializes a trajectory JSON into a double[] of trajectory elements.- Parameters:
json
- The JSON containing the serialized trajectory.- Returns:
- A double array with the trajectory states.
-
serializeTrajectory
Serializes the trajectory into a JSON string.- Parameters:
elements
- The elements of the trajectory.- Returns:
- A JSON containing the serialized trajectory.
-
rankUpdate
public static void rankUpdate(double[] mat, int rows, double[] vec, double sigma, boolean lowerTriangular)Performs an inplace rank one update (or downdate) of an upper triangular Cholesky decomposition matrix.- Parameters:
mat
- Array of elements of the matrix to be updated.lowerTriangular
- Whether mat is lower triangular.rows
- How many rows there are.vec
- Vector to use for the rank update.sigma
- Sigma value to use for the rank update.
-
solveFullPivHouseholderQr
public static void solveFullPivHouseholderQr(double[] A, int Arows, int Acols, double[] B, int Brows, int Bcols, double[] dst)Solves the least-squares problem Ax=B using a QR decomposition with full pivoting.- Parameters:
A
- Array of elements of the A matrix.Arows
- Number of rows of the A matrix.Acols
- Number of rows of the A matrix.B
- Array of elements of the B matrix.Brows
- Number of rows of the B matrix.Bcols
- Number of rows of the B matrix.dst
- Array to store solution in. If A is m-n and B is m-p, dst is n-p.
-