mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpimath] Remove PathWeaver support (#7813)
Also rename file load type in glass to "Field Image JSON".
This commit is contained in:
@@ -14,7 +14,6 @@ file(
|
||||
src/main/native/cpp/jni/Exceptions.cpp
|
||||
src/main/native/cpp/jni/Pose3dJNI.cpp
|
||||
src/main/native/cpp/jni/StateSpaceUtilJNI.cpp
|
||||
src/main/native/cpp/jni/TrajectoryUtilJNI.cpp
|
||||
)
|
||||
|
||||
# Java bindings
|
||||
|
||||
@@ -1,47 +0,0 @@
|
||||
// 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 java.io.IOException;
|
||||
|
||||
/** TrajectoryUtil JNI. */
|
||||
public final class TrajectoryUtilJNI extends WPIMathJNI {
|
||||
/**
|
||||
* Loads a Pathweaver JSON.
|
||||
*
|
||||
* @param path The path to the JSON.
|
||||
* @return A double array with the trajectory states from the JSON.
|
||||
* @throws IOException if the JSON could not be read.
|
||||
*/
|
||||
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.
|
||||
* @throws IOException if the JSON could not be written.
|
||||
*/
|
||||
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);
|
||||
|
||||
/** Utility class. */
|
||||
private TrajectoryUtilJNI() {}
|
||||
}
|
||||
@@ -1,131 +0,0 @@
|
||||
// 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.trajectory;
|
||||
|
||||
import edu.wpi.first.math.MathSharedStore;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.jni.TrajectoryUtilJNI;
|
||||
import java.io.IOException;
|
||||
import java.nio.file.Path;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
/** Trajectory utilities. */
|
||||
public final class TrajectoryUtil {
|
||||
private TrajectoryUtil() {
|
||||
throw new UnsupportedOperationException("This is a utility class!");
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a trajectory from a double[] of elements.
|
||||
*
|
||||
* @param elements A double[] containing the raw elements of the trajectory.
|
||||
* @return A trajectory created from the elements.
|
||||
*/
|
||||
private static Trajectory createTrajectoryFromElements(double[] elements) {
|
||||
// Make sure that the elements have the correct length.
|
||||
if (elements.length % 7 != 0) {
|
||||
throw new TrajectorySerializationException(
|
||||
"An error occurred when converting trajectory elements into a trajectory.");
|
||||
}
|
||||
|
||||
// Create a list of states from the elements.
|
||||
List<Trajectory.State> states = new ArrayList<>();
|
||||
for (int i = 0; i < elements.length; i += 7) {
|
||||
states.add(
|
||||
new Trajectory.State(
|
||||
elements[i],
|
||||
elements[i + 1],
|
||||
elements[i + 2],
|
||||
new Pose2d(elements[i + 3], elements[i + 4], new Rotation2d(elements[i + 5])),
|
||||
elements[i + 6]));
|
||||
}
|
||||
return new Trajectory(states);
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a double[] of elements from the given trajectory.
|
||||
*
|
||||
* @param trajectory The trajectory to retrieve raw elements from.
|
||||
* @return A double[] of elements from the given trajectory.
|
||||
*/
|
||||
private static double[] getElementsFromTrajectory(Trajectory trajectory) {
|
||||
// Create a double[] of elements and fill it from the trajectory states.
|
||||
double[] elements = new double[trajectory.getStates().size() * 7];
|
||||
|
||||
for (int i = 0; i < trajectory.getStates().size() * 7; i += 7) {
|
||||
var state = trajectory.getStates().get(i / 7);
|
||||
elements[i] = state.time;
|
||||
elements[i + 1] = state.velocity;
|
||||
elements[i + 2] = state.acceleration;
|
||||
elements[i + 3] = state.pose.getX();
|
||||
elements[i + 4] = state.pose.getY();
|
||||
elements[i + 5] = state.pose.getRotation().getRadians();
|
||||
elements[i + 6] = state.curvature;
|
||||
}
|
||||
return elements;
|
||||
}
|
||||
|
||||
private static int pathWeaverTrajectoryInstances;
|
||||
|
||||
/**
|
||||
* Imports a Trajectory from a JSON file exported from PathWeaver.
|
||||
*
|
||||
* @param path The path of the json file to import from
|
||||
* @return The trajectory represented by the file.
|
||||
* @throws IOException if reading from the file fails.
|
||||
*/
|
||||
public static Trajectory fromPathweaverJson(Path path) throws IOException {
|
||||
MathSharedStore.reportUsage(
|
||||
"Trajectory.PathWeaver", String.valueOf(++pathWeaverTrajectoryInstances));
|
||||
return createTrajectoryFromElements(TrajectoryUtilJNI.fromPathweaverJson(path.toString()));
|
||||
}
|
||||
|
||||
/**
|
||||
* Exports a Trajectory to a PathWeaver-style JSON file.
|
||||
*
|
||||
* @param trajectory The trajectory to export
|
||||
* @param path The path of the file to export to
|
||||
* @throws IOException if writing to the file fails.
|
||||
*/
|
||||
public static void toPathweaverJson(Trajectory trajectory, Path path) throws IOException {
|
||||
TrajectoryUtilJNI.toPathweaverJson(getElementsFromTrajectory(trajectory), path.toString());
|
||||
}
|
||||
|
||||
/**
|
||||
* Deserializes a Trajectory from JSON exported from PathWeaver.
|
||||
*
|
||||
* @param json The string containing the serialized JSON
|
||||
* @return the trajectory represented by the JSON
|
||||
* @throws TrajectorySerializationException if deserialization of the string fails.
|
||||
*/
|
||||
public static Trajectory deserializeTrajectory(String json) {
|
||||
return createTrajectoryFromElements(TrajectoryUtilJNI.deserializeTrajectory(json));
|
||||
}
|
||||
|
||||
/**
|
||||
* Serializes a Trajectory to PathWeaver-style JSON.
|
||||
*
|
||||
* @param trajectory The trajectory to export
|
||||
* @return The string containing the serialized JSON
|
||||
* @throws TrajectorySerializationException if serialization of the trajectory fails.
|
||||
*/
|
||||
public static String serializeTrajectory(Trajectory trajectory) {
|
||||
return TrajectoryUtilJNI.serializeTrajectory(getElementsFromTrajectory(trajectory));
|
||||
}
|
||||
|
||||
/** Exception for trajectory serialization failure. */
|
||||
public static class TrajectorySerializationException extends RuntimeException {
|
||||
/**
|
||||
* Constructs a TrajectorySerializationException.
|
||||
*
|
||||
* @param message The exception message.
|
||||
*/
|
||||
public TrajectorySerializationException(String message) {
|
||||
super(message);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -18,10 +18,7 @@ JException trajectorySerializationEx;
|
||||
|
||||
static const JExceptionInit exceptions[] = {
|
||||
{"java/lang/IllegalArgumentException", &illegalArgEx},
|
||||
{"java/io/IOException", &ioEx},
|
||||
{"edu/wpi/first/math/trajectory/"
|
||||
"TrajectoryUtil$TrajectorySerializationException",
|
||||
&trajectorySerializationEx}};
|
||||
{"java/io/IOException", &ioEx}};
|
||||
|
||||
extern "C" {
|
||||
|
||||
|
||||
@@ -1,139 +0,0 @@
|
||||
// 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.
|
||||
|
||||
#include <jni.h>
|
||||
|
||||
#include <exception>
|
||||
#include <vector>
|
||||
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "Exceptions.h"
|
||||
#include "edu_wpi_first_math_jni_TrajectoryUtilJNI.h"
|
||||
#include "frc/trajectory/TrajectoryUtil.h"
|
||||
|
||||
using namespace wpi::java;
|
||||
|
||||
std::vector<double> GetElementsFromTrajectory(
|
||||
const frc::Trajectory& trajectory) {
|
||||
std::vector<double> elements;
|
||||
elements.reserve(trajectory.States().size() * 7);
|
||||
|
||||
for (auto&& state : trajectory.States()) {
|
||||
elements.push_back(state.t.value());
|
||||
elements.push_back(state.velocity.value());
|
||||
elements.push_back(state.acceleration.value());
|
||||
elements.push_back(state.pose.X().value());
|
||||
elements.push_back(state.pose.Y().value());
|
||||
elements.push_back(state.pose.Rotation().Radians().value());
|
||||
elements.push_back(state.curvature.value());
|
||||
}
|
||||
|
||||
return elements;
|
||||
}
|
||||
|
||||
frc::Trajectory CreateTrajectoryFromElements(std::span<const double> elements) {
|
||||
// Make sure that the elements have the correct length.
|
||||
assert(elements.size() % 7 == 0);
|
||||
|
||||
// Create a vector of states from the elements.
|
||||
std::vector<frc::Trajectory::State> states;
|
||||
states.reserve(elements.size() / 7);
|
||||
|
||||
for (size_t i = 0; i < elements.size(); i += 7) {
|
||||
states.emplace_back(frc::Trajectory::State{
|
||||
units::second_t{elements[i]},
|
||||
units::meters_per_second_t{elements[i + 1]},
|
||||
units::meters_per_second_squared_t{elements[i + 2]},
|
||||
frc::Pose2d{units::meter_t{elements[i + 3]},
|
||||
units::meter_t{elements[i + 4]},
|
||||
units::radian_t{elements[i + 5]}},
|
||||
units::curvature_t{elements[i + 6]}});
|
||||
}
|
||||
|
||||
return frc::Trajectory(states);
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: fromPathweaverJson
|
||||
* Signature: (Ljava/lang/String;)[D
|
||||
*/
|
||||
JNIEXPORT jdoubleArray JNICALL
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_fromPathweaverJson
|
||||
(JNIEnv* env, jclass, jstring path)
|
||||
{
|
||||
try {
|
||||
auto trajectory =
|
||||
frc::TrajectoryUtil::FromPathweaverJson(JStringRef{env, path}.c_str());
|
||||
std::vector<double> elements = GetElementsFromTrajectory(trajectory);
|
||||
return MakeJDoubleArray(env, elements);
|
||||
} catch (std::exception& e) {
|
||||
ioEx.Throw(env, e.what());
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: toPathweaverJson
|
||||
* Signature: ([DLjava/lang/String;)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_toPathweaverJson
|
||||
(JNIEnv* env, jclass, jdoubleArray elements, jstring path)
|
||||
{
|
||||
try {
|
||||
auto trajectory =
|
||||
CreateTrajectoryFromElements(JSpan<const jdouble>{env, elements});
|
||||
frc::TrajectoryUtil::ToPathweaverJson(trajectory,
|
||||
JStringRef{env, path}.c_str());
|
||||
} catch (std::exception& e) {
|
||||
ioEx.Throw(env, e.what());
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: deserializeTrajectory
|
||||
* Signature: (Ljava/lang/String;)[D
|
||||
*/
|
||||
JNIEXPORT jdoubleArray JNICALL
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_deserializeTrajectory
|
||||
(JNIEnv* env, jclass, jstring json)
|
||||
{
|
||||
try {
|
||||
auto trajectory = frc::TrajectoryUtil::DeserializeTrajectory(
|
||||
JStringRef{env, json}.c_str());
|
||||
std::vector<double> elements = GetElementsFromTrajectory(trajectory);
|
||||
return MakeJDoubleArray(env, elements);
|
||||
} catch (std::exception& e) {
|
||||
trajectorySerializationEx.Throw(env, e.what());
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_jni_TrajectoryUtilJNI
|
||||
* Method: serializeTrajectory
|
||||
* Signature: ([D)Ljava/lang/String;
|
||||
*/
|
||||
JNIEXPORT jstring JNICALL
|
||||
Java_edu_wpi_first_math_jni_TrajectoryUtilJNI_serializeTrajectory
|
||||
(JNIEnv* env, jclass, jdoubleArray elements)
|
||||
{
|
||||
try {
|
||||
auto trajectory =
|
||||
CreateTrajectoryFromElements(JSpan<const jdouble>{env, elements});
|
||||
return MakeJString(env,
|
||||
frc::TrajectoryUtil::SerializeTrajectory(trajectory));
|
||||
} catch (std::exception& e) {
|
||||
trajectorySerializationEx.Throw(env, e.what());
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
@@ -1,53 +0,0 @@
|
||||
// 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.
|
||||
|
||||
#include "frc/trajectory/TrajectoryUtil.h"
|
||||
|
||||
#include <string>
|
||||
#include <system_error>
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <wpi/MemoryBuffer.h>
|
||||
#include <wpi/json.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
using namespace frc;
|
||||
|
||||
void TrajectoryUtil::ToPathweaverJson(const Trajectory& trajectory,
|
||||
std::string_view path) {
|
||||
std::error_code error_code;
|
||||
|
||||
wpi::raw_fd_ostream output{path, error_code};
|
||||
if (error_code) {
|
||||
throw std::runtime_error(fmt::format("Cannot open file: {}", path));
|
||||
}
|
||||
|
||||
wpi::json json = trajectory.States();
|
||||
output << json;
|
||||
output.flush();
|
||||
}
|
||||
|
||||
Trajectory TrajectoryUtil::FromPathweaverJson(std::string_view path) {
|
||||
auto fileBuffer = wpi::MemoryBuffer::GetFile(path);
|
||||
if (!fileBuffer) {
|
||||
throw std::runtime_error(fmt::format("Cannot open file: {}", path));
|
||||
}
|
||||
|
||||
wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer());
|
||||
|
||||
wpi::math::MathSharedStore::ReportUsage(
|
||||
"Trajectory.PathWeaver", std::to_string(++pathWeaverTrajectoryInstances));
|
||||
|
||||
return Trajectory{json.get<std::vector<Trajectory::State>>()};
|
||||
}
|
||||
|
||||
std::string TrajectoryUtil::SerializeTrajectory(const Trajectory& trajectory) {
|
||||
wpi::json json = trajectory.States();
|
||||
return json.dump();
|
||||
}
|
||||
|
||||
Trajectory TrajectoryUtil::DeserializeTrajectory(std::string_view jsonStr) {
|
||||
wpi::json json = wpi::json::parse(jsonStr);
|
||||
return Trajectory{json.get<std::vector<Trajectory::State>>()};
|
||||
}
|
||||
@@ -1,61 +0,0 @@
|
||||
// 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.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
|
||||
#include <wpi/SymbolExports.h>
|
||||
|
||||
#include "frc/trajectory/Trajectory.h"
|
||||
|
||||
namespace frc {
|
||||
/**
|
||||
* Trajectory utilities.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT TrajectoryUtil {
|
||||
public:
|
||||
TrajectoryUtil() = delete;
|
||||
|
||||
/**
|
||||
* Exports a Trajectory to a PathWeaver-style JSON file.
|
||||
*
|
||||
* @param trajectory the trajectory to export
|
||||
* @param path the path of the file to export to
|
||||
*/
|
||||
static void ToPathweaverJson(const Trajectory& trajectory,
|
||||
std::string_view path);
|
||||
/**
|
||||
* Imports a Trajectory from a JSON file exported from PathWeaver.
|
||||
*
|
||||
* @param path The path of the json file to import from.
|
||||
*
|
||||
* @return The trajectory represented by the file.
|
||||
*/
|
||||
static Trajectory FromPathweaverJson(std::string_view path);
|
||||
|
||||
/**
|
||||
* Deserializes a Trajectory from JSON exported from PathWeaver.
|
||||
*
|
||||
* @param trajectory the trajectory to export
|
||||
*
|
||||
* @return the string containing the serialized JSON
|
||||
*/
|
||||
static std::string SerializeTrajectory(const Trajectory& trajectory);
|
||||
|
||||
/**
|
||||
* Serializes a Trajectory to PathWeaver-style JSON.
|
||||
*
|
||||
* @param jsonStr the string containing the serialized JSON
|
||||
*
|
||||
* @return the trajectory represented by the JSON
|
||||
*/
|
||||
static Trajectory DeserializeTrajectory(std::string_view jsonStr);
|
||||
|
||||
private:
|
||||
// Usage reporting for PathWeaver Trajectory instances
|
||||
inline static int pathWeaverTrajectoryInstances = 0;
|
||||
};
|
||||
} // namespace frc
|
||||
@@ -1,16 +0,0 @@
|
||||
// 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 static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
public class TrajectoryUtilJNITest {
|
||||
@Test
|
||||
public void testLink() {
|
||||
assertDoesNotThrow(TrajectoryUtilJNI::forceLoad);
|
||||
}
|
||||
}
|
||||
@@ -1,30 +0,0 @@
|
||||
// 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.trajectory;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.trajectory.constraint.DifferentialDriveKinematicsConstraint;
|
||||
import java.util.List;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class TrajectoryJsonTest {
|
||||
@Test
|
||||
void deserializeMatches() {
|
||||
var config =
|
||||
List.of(new DifferentialDriveKinematicsConstraint(new DifferentialDriveKinematics(0.5), 3));
|
||||
var trajectory = TrajectoryGeneratorTest.getTrajectory(config);
|
||||
|
||||
var deserialized =
|
||||
assertDoesNotThrow(
|
||||
() ->
|
||||
TrajectoryUtil.deserializeTrajectory(
|
||||
TrajectoryUtil.serializeTrajectory(trajectory)));
|
||||
|
||||
assertEquals(trajectory.getStates(), deserialized.getStates());
|
||||
}
|
||||
}
|
||||
@@ -1,21 +0,0 @@
|
||||
// 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.
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
#include "frc/trajectory/TrajectoryConfig.h"
|
||||
#include "frc/trajectory/TrajectoryUtil.h"
|
||||
#include "trajectory/TestTrajectory.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
TEST(TrajectoryJsonTest, DeserializeMatches) {
|
||||
TrajectoryConfig config{12_fps, 12_fps_sq};
|
||||
auto trajectory = TestTrajectory::GetTrajectory(config);
|
||||
|
||||
Trajectory deserialized;
|
||||
EXPECT_NO_THROW(deserialized = TrajectoryUtil::DeserializeTrajectory(
|
||||
TrajectoryUtil::SerializeTrajectory(trajectory)));
|
||||
EXPECT_EQ(trajectory.States(), deserialized.States());
|
||||
}
|
||||
Reference in New Issue
Block a user