mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Remove PathWeaver support (#7813)
Also rename file load type in glass to "Field Image JSON".
This commit is contained in:
@@ -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>>()};
|
||||
}
|
||||
Reference in New Issue
Block a user