mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Disambiguate wpimath JNI functions (#6695)
Each collection of JNI functions now has its own class.
This commit is contained in:
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "edu_wpi_first_math_WPIMathJNI.h"
|
||||
#include "edu_wpi_first_math_jni_ArmFeedforwardJNI.h"
|
||||
#include "frc/controller/ArmFeedforward.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
@@ -14,12 +14,12 @@ using namespace wpi::java;
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_ArmFeedforwardJNI
|
||||
* Method: calculate
|
||||
* Signature: (DDDDDDDD)D
|
||||
*/
|
||||
JNIEXPORT jdouble JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_calculate
|
||||
Java_edu_wpi_first_math_jni_ArmFeedforwardJNI_calculate
|
||||
(JNIEnv* env, jclass, jdouble ks, jdouble kv, jdouble ka, jdouble kg,
|
||||
jdouble currentAngle, jdouble currentVelocity, jdouble nextVelocity,
|
||||
jdouble dt)
|
||||
@@ -8,8 +8,8 @@
|
||||
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "WPIMathJNI_Exceptions.h"
|
||||
#include "edu_wpi_first_math_WPIMathJNI.h"
|
||||
#include "Exceptions.h"
|
||||
#include "edu_wpi_first_math_jni_DAREJNI.h"
|
||||
#include "frc/DARE.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
@@ -17,12 +17,12 @@ using namespace wpi::java;
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_DAREJNI
|
||||
* Method: dareDetailABQR
|
||||
* Signature: ([D[D[D[DII[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_dareDetailABQR
|
||||
Java_edu_wpi_first_math_jni_DAREJNI_dareDetailABQR
|
||||
(JNIEnv* env, jclass, jdoubleArray A, jdoubleArray B, jdoubleArray Q,
|
||||
jdoubleArray R, jint states, jint inputs, jdoubleArray S)
|
||||
{
|
||||
@@ -54,12 +54,12 @@ Java_edu_wpi_first_math_WPIMathJNI_dareDetailABQR
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_DAREJNI
|
||||
* Method: dareDetailABQRN
|
||||
* Signature: ([D[D[D[D[DII[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_dareDetailABQRN
|
||||
Java_edu_wpi_first_math_jni_DAREJNI_dareDetailABQRN
|
||||
(JNIEnv* env, jclass, jdoubleArray A, jdoubleArray B, jdoubleArray Q,
|
||||
jdoubleArray R, jdoubleArray N, jint states, jint inputs, jdoubleArray S)
|
||||
{
|
||||
@@ -95,12 +95,12 @@ Java_edu_wpi_first_math_WPIMathJNI_dareDetailABQRN
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_DAREJNI
|
||||
* Method: dareABQR
|
||||
* Signature: ([D[D[D[DII[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_dareABQR
|
||||
Java_edu_wpi_first_math_jni_DAREJNI_dareABQR
|
||||
(JNIEnv* env, jclass, jdoubleArray A, jdoubleArray B, jdoubleArray Q,
|
||||
jdoubleArray R, jint states, jint inputs, jdoubleArray S)
|
||||
{
|
||||
@@ -133,12 +133,12 @@ Java_edu_wpi_first_math_WPIMathJNI_dareABQR
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_DAREJNI
|
||||
* Method: dareABQRN
|
||||
* Signature: ([D[D[D[D[DII[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_dareABQRN
|
||||
Java_edu_wpi_first_math_jni_DAREJNI_dareABQRN
|
||||
(JNIEnv* env, jclass, jdoubleArray A, jdoubleArray B, jdoubleArray Q,
|
||||
jdoubleArray R, jdoubleArray N, jint states, jint inputs, jdoubleArray S)
|
||||
{
|
||||
@@ -10,19 +10,19 @@
|
||||
#include <unsupported/Eigen/MatrixFunctions>
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "edu_wpi_first_math_WPIMathJNI.h"
|
||||
#include "edu_wpi_first_math_jni_EigenJNI.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_EigenJNI
|
||||
* Method: exp
|
||||
* Signature: ([DI[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_exp
|
||||
Java_edu_wpi_first_math_jni_EigenJNI_exp
|
||||
(JNIEnv* env, jclass, jdoubleArray src, jint rows, jdoubleArray dst)
|
||||
{
|
||||
JSpan<const jdouble> arrayBody{env, src};
|
||||
@@ -37,12 +37,12 @@ Java_edu_wpi_first_math_WPIMathJNI_exp
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_EigenJNI
|
||||
* Method: pow
|
||||
* Signature: ([DID[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_pow
|
||||
Java_edu_wpi_first_math_jni_EigenJNI_pow
|
||||
(JNIEnv* env, jclass, jdoubleArray src, jint rows, jdouble exponent,
|
||||
jdoubleArray dst)
|
||||
{
|
||||
@@ -58,12 +58,12 @@ Java_edu_wpi_first_math_WPIMathJNI_pow
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_EigenJNI
|
||||
* Method: rankUpdate
|
||||
* Signature: ([DI[DDZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_rankUpdate
|
||||
Java_edu_wpi_first_math_jni_EigenJNI_rankUpdate
|
||||
(JNIEnv* env, jclass, jdoubleArray mat, jint rows, jdoubleArray vec,
|
||||
jdouble sigma, jboolean lowerTriangular)
|
||||
{
|
||||
@@ -84,12 +84,12 @@ Java_edu_wpi_first_math_WPIMathJNI_rankUpdate
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_EigenJNI
|
||||
* Method: solveFullPivHouseholderQr
|
||||
* Signature: ([DII[DII[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_solveFullPivHouseholderQr
|
||||
Java_edu_wpi_first_math_jni_EigenJNI_solveFullPivHouseholderQr
|
||||
(JNIEnv* env, jclass, jdoubleArray A, jint Arows, jint Acols, jdoubleArray B,
|
||||
jint Brows, jint Bcols, jdoubleArray dst)
|
||||
{
|
||||
@@ -7,7 +7,7 @@
|
||||
#include <wpi/array.h>
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "edu_wpi_first_math_WPIMathJNI.h"
|
||||
#include "edu_wpi_first_math_jni_Ellipse2dJNI.h"
|
||||
#include "frc/geometry/Ellipse2d.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
@@ -15,12 +15,12 @@ using namespace wpi::java;
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Method: ellipse2dFindNearestPoint
|
||||
* Class: edu_wpi_first_math_jni_Ellipse2dJNI
|
||||
* Method: findNearestPoint
|
||||
* Signature: (DDDDDDD[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_ellipse2dFindNearestPoint
|
||||
Java_edu_wpi_first_math_jni_Ellipse2dJNI_findNearestPoint
|
||||
(JNIEnv* env, jclass, jdouble centerX, jdouble centerY, jdouble centerHeading,
|
||||
jdouble xSemiAxis, jdouble ySemiAxis, jdouble pointX, jdouble pointY,
|
||||
jdoubleArray nearestPoint)
|
||||
@@ -2,7 +2,7 @@
|
||||
// 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.
|
||||
|
||||
#include "WPIMathJNI_Exceptions.h"
|
||||
#include "Exceptions.h"
|
||||
|
||||
#include <jni.h>
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "edu_wpi_first_math_WPIMathJNI.h"
|
||||
#include "edu_wpi_first_math_jni_Pose3dJNI.h"
|
||||
#include "frc/geometry/Pose3d.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
@@ -14,12 +14,12 @@ using namespace wpi::java;
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Method: expPose3d
|
||||
* Class: edu_wpi_first_math_jni_Pose3dJNI
|
||||
* Method: exp
|
||||
* Signature: (DDDDDDDDDDDDD)[D
|
||||
*/
|
||||
JNIEXPORT jdoubleArray JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_expPose3d
|
||||
Java_edu_wpi_first_math_jni_Pose3dJNI_exp
|
||||
(JNIEnv* env, jclass, jdouble poseX, jdouble poseY, jdouble poseZ,
|
||||
jdouble poseQw, jdouble poseQx, jdouble poseQy, jdouble poseQz,
|
||||
jdouble twistDx, jdouble twistDy, jdouble twistDz, jdouble twistRx,
|
||||
@@ -42,12 +42,12 @@ Java_edu_wpi_first_math_WPIMathJNI_expPose3d
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Method: logPose3d
|
||||
* Class: edu_wpi_first_math_jni_Pose3dJNI
|
||||
* Method: log
|
||||
* Signature: (DDDDDDDDDDDDDD)[D
|
||||
*/
|
||||
JNIEXPORT jdoubleArray JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_logPose3d
|
||||
Java_edu_wpi_first_math_jni_Pose3dJNI_log
|
||||
(JNIEnv* env, jclass, jdouble startX, jdouble startY, jdouble startZ,
|
||||
jdouble startQw, jdouble startQx, jdouble startQy, jdouble startQz,
|
||||
jdouble endX, jdouble endY, jdouble endZ, jdouble endQw, jdouble endQx,
|
||||
@@ -7,7 +7,7 @@
|
||||
#include <Eigen/Core>
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "edu_wpi_first_math_WPIMathJNI.h"
|
||||
#include "edu_wpi_first_math_jni_StateSpaceUtilJNI.h"
|
||||
#include "frc/StateSpaceUtil.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
@@ -15,12 +15,12 @@ using namespace wpi::java;
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_StateSpaceUtilJNI
|
||||
* Method: isStabilizable
|
||||
* Signature: (II[D[D)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_isStabilizable
|
||||
Java_edu_wpi_first_math_jni_StateSpaceUtilJNI_isStabilizable
|
||||
(JNIEnv* env, jclass, jint states, jint inputs, jdoubleArray aSrc,
|
||||
jdoubleArray bSrc)
|
||||
{
|
||||
@@ -8,8 +8,8 @@
|
||||
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "WPIMathJNI_Exceptions.h"
|
||||
#include "edu_wpi_first_math_WPIMathJNI.h"
|
||||
#include "Exceptions.h"
|
||||
#include "edu_wpi_first_math_jni_TrajectoryUtilJNI.h"
|
||||
#include "frc/trajectory/TrajectoryUtil.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
@@ -57,12 +57,12 @@ frc::Trajectory CreateTrajectoryFromElements(std::span<const double> elements) {
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: fromPathweaverJson
|
||||
* Signature: (Ljava/lang/String;)[D
|
||||
*/
|
||||
JNIEXPORT jdoubleArray JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_fromPathweaverJson
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_fromPathweaverJson
|
||||
(JNIEnv* env, jclass, jstring path)
|
||||
{
|
||||
try {
|
||||
@@ -77,12 +77,12 @@ Java_edu_wpi_first_math_WPIMathJNI_fromPathweaverJson
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: toPathweaverJson
|
||||
* Signature: ([DLjava/lang/String;)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_toPathweaverJson
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_toPathweaverJson
|
||||
(JNIEnv* env, jclass, jdoubleArray elements, jstring path)
|
||||
{
|
||||
try {
|
||||
@@ -96,12 +96,12 @@ Java_edu_wpi_first_math_WPIMathJNI_toPathweaverJson
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: deserializeTrajectory
|
||||
* Signature: (Ljava/lang/String;)[D
|
||||
*/
|
||||
JNIEXPORT jdoubleArray JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_deserializeTrajectory
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_deserializeTrajectory
|
||||
(JNIEnv* env, jclass, jstring json)
|
||||
{
|
||||
try {
|
||||
@@ -116,12 +116,12 @@ Java_edu_wpi_first_math_WPIMathJNI_deserializeTrajectory
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_WPIMathJNI
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: serializeTrajectory
|
||||
* Signature: ([D)Ljava/lang/String;
|
||||
*/
|
||||
JNIEXPORT jstring JNICALL
|
||||
Java_edu_wpi_first_math_WPIMathJNI_serializeTrajectory
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_serializeTrajectory
|
||||
(JNIEnv* env, jclass, jdoubleArray elements)
|
||||
{
|
||||
try {
|
||||
Reference in New Issue
Block a user