Change Java JSON to Avaje Jsonb (#8721)

Jackson is a very heavy library; it supports loads of features that we
don't need, and historically has caused issues due to long class loading
times (a little over 2 seconds to load AprilTagFieldLayout). This often
manifests as a help request in the form of "my robot disables when I do
X, but doesn't disable when doing X in subsequent attempts until code
restart." While SC has brought down Jackson loading times significantly,
with AprilTagFieldLayout loads taking only 330 milliseconds, that's
still a rather long delay, and while libraries should handle any JSON
loading ahead of time to prevent delays in auto/teleop, it would still
be good to make the worst case better to reduce user frustration.
Benchmarks indicate using [Avaje
Jsonb](https://github.com/avaje/avaje-jsonb) to load AprilTagFieldLayout
only takes ~70 ms, a fair chunk of which isn't actually in Avaje Jsonb
(~4 ms is spent on using getResourceAsStream to retrieve the JSON file,
~8 ms is spent on just loading the AprilTag class and its dependencies).

Note that all times listed are end-to-end, meaning nothing else was done
except for the operation being benchmarked, and doing arithmetic on them
can be flawed due to some classes being loaded twice, i.e.,
getResourceAsStream and `new AprilTag()` likely load some of the same
JDK classes and so subtracting both from the Avaje Jsonb load time is
likely slightly incorrect because class loading is being double counted.
For our purposes, it's likely accurate enough and is mostly just for
contextualization.

Benchmarks were run on a Raspberry Pi CM5 with 2 GB of RAM. Source code
for the
[results](https://github.com/user-attachments/files/26471452/benchmark.txt)
can be found in the "Fastjson2" commit
(2456d15ca8ebd17635e607cd40bf8816e77869a1).

Avaje Jsonb uses code generation via annotation processors to generate
the classes needed to do JSON serde and uses service providers to find
them, which will require downstream changes in robot projects, as the
different service providers in each library must be merged together for
Avaje Jsonb to function. We will use the Gradle shadow plugin, as its
already used by the installer and therefore adds zero additional
dependencies.
This commit is contained in:
Gold856
2026-04-11 02:21:00 -04:00
committed by GitHub
parent 346cd9ed9c
commit 2102a543d1
32 changed files with 294 additions and 298 deletions

View File

@@ -242,15 +242,17 @@ wpilib_jni_java_library(
maven_artifact_name = "wpimath-java",
maven_group_id = "org.wpilib.wpimath",
native_libs = [":wpimathjni"],
plugins = [
"//:avaje_jsonb_generator",
],
resource_strip_prefix = "wpimath/src/main/proto",
resources = glob(["src/main/proto/**"]),
visibility = ["//visibility:public"],
deps = [
"//wpiunits:wpiunits-java",
"//wpiutil:wpiutil-java",
"@maven//:com_fasterxml_jackson_core_jackson_annotations",
"@maven//:com_fasterxml_jackson_core_jackson_core",
"@maven//:com_fasterxml_jackson_core_jackson_databind",
"@maven//:io_avaje_avaje_json_core",
"@maven//:io_avaje_avaje_jsonb",
"@maven//:org_ejml_ejml_core",
"@maven//:org_ejml_ejml_ddense",
"@maven//:org_ejml_ejml_simple",

View File

@@ -64,7 +64,7 @@ if(WITH_JAVA)
endif()
file(GLOB EJML_JARS "${WPILIB_BINARY_DIR}/wpimath/thirdparty/ejml/*.jar")
file(GLOB JACKSON_JARS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/*.jar")
file(GLOB AVAJE_JARS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/avaje/*.jar")
file(GLOB QUICKBUF_JAR ${WPILIB_BINARY_DIR}/wpiutil/thirdparty/quickbuf/*.jar)
set(CMAKE_JNI_TARGET true)
@@ -74,7 +74,7 @@ if(WITH_JAVA)
add_jar(
wpimath_jar
${JAVA_SOURCES}
INCLUDE_JARS wpiutil_jar wpiunits_jar ${EJML_JARS} ${JACKSON_JARS} ${QUICKBUF_JAR}
INCLUDE_JARS wpiutil_jar wpiunits_jar ${EJML_JARS} ${AVAJE_JARS} ${QUICKBUF_JAR}
OUTPUT_NAME wpimath
OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest}
GENERATE_NATIVE_HEADERS wpimath_jni_headers

View File

@@ -88,9 +88,10 @@ nativeUtils.exportsConfigs {
}
dependencies {
annotationProcessor libs.avaje.jsonb.generator
api project(":wpiunits")
api libs.avaje.jsonb
api libs.bundles.ejml
api libs.bundles.jackson
api libs.quickbuf.runtime
}

View File

@@ -6,10 +6,7 @@ package org.wpilib.math.geometry;
import static org.wpilib.units.Units.Meters;
import com.fasterxml.jackson.annotation.JsonAutoDetect;
import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.Collection;
import java.util.Collections;
import java.util.Comparator;
@@ -26,8 +23,7 @@ import org.wpilib.util.protobuf.ProtobufSerializable;
import org.wpilib.util.struct.StructSerializable;
/** Represents a 2D pose containing translational and rotational elements. */
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@Json
public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, StructSerializable {
/**
* A preallocated Pose2d representing the origin.
@@ -36,7 +32,10 @@ public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, Str
*/
public static final Pose2d kZero = new Pose2d();
@Json.Property("translation")
private final Translation2d m_translation;
@Json.Property("rotation")
private final Rotation2d m_rotation;
/** Constructs a pose at the origin facing toward the positive X axis. */
@@ -51,10 +50,8 @@ public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, Str
* @param translation The translational component of the pose.
* @param rotation The rotational component of the pose.
*/
@JsonCreator
public Pose2d(
@JsonProperty(required = true, value = "translation") Translation2d translation,
@JsonProperty(required = true, value = "rotation") Rotation2d rotation) {
@Json.Creator
public Pose2d(Translation2d translation, Rotation2d rotation) {
m_translation = translation;
m_rotation = rotation;
}
@@ -129,7 +126,6 @@ public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, Str
*
* @return The translational component of the pose.
*/
@JsonProperty
public Translation2d getTranslation() {
return m_translation;
}
@@ -175,7 +171,6 @@ public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, Str
*
* @return The rotational component of the pose.
*/
@JsonProperty
public Rotation2d getRotation() {
return m_rotation;
}

View File

@@ -6,10 +6,7 @@ package org.wpilib.math.geometry;
import static org.wpilib.units.Units.Meters;
import com.fasterxml.jackson.annotation.JsonAutoDetect;
import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.Collection;
import java.util.Collections;
import java.util.Comparator;
@@ -26,8 +23,7 @@ import org.wpilib.util.protobuf.ProtobufSerializable;
import org.wpilib.util.struct.StructSerializable;
/** Represents a 3D pose containing translational and rotational elements. */
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@Json
public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, StructSerializable {
/**
* A preallocated Pose3d representing the origin.
@@ -36,7 +32,10 @@ public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, Str
*/
public static final Pose3d kZero = new Pose3d();
@Json.Property("translation")
private final Translation3d m_translation;
@Json.Property("rotation")
private final Rotation3d m_rotation;
/** Constructs a pose at the origin facing toward the positive X axis. */
@@ -51,10 +50,8 @@ public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, Str
* @param translation The translational component of the pose.
* @param rotation The rotational component of the pose.
*/
@JsonCreator
public Pose3d(
@JsonProperty(required = true, value = "translation") Translation3d translation,
@JsonProperty(required = true, value = "rotation") Rotation3d rotation) {
@Json.Creator
public Pose3d(Translation3d translation, Rotation3d rotation) {
m_translation = translation;
m_rotation = rotation;
}
@@ -143,7 +140,6 @@ public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, Str
*
* @return The translational component of the pose.
*/
@JsonProperty
public Translation3d getTranslation() {
return m_translation;
}
@@ -207,7 +203,6 @@ public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, Str
*
* @return The rotational component of the pose.
*/
@JsonProperty
public Rotation3d getRotation() {
return m_rotation;
}

View File

@@ -4,10 +4,7 @@
package org.wpilib.math.geometry;
import com.fasterxml.jackson.annotation.JsonAutoDetect;
import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.Objects;
import org.wpilib.math.geometry.proto.QuaternionProto;
import org.wpilib.math.geometry.struct.QuaternionStruct;
@@ -18,16 +15,15 @@ import org.wpilib.util.protobuf.ProtobufSerializable;
import org.wpilib.util.struct.StructSerializable;
/** Represents a quaternion. */
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@Json
public class Quaternion implements ProtobufSerializable, StructSerializable {
// Scalar r in versor form
private final double m_w;
@Json.Ignore private final double m_w;
// Vector v in versor form
private final double m_x;
private final double m_y;
private final double m_z;
@Json.Ignore private final double m_x;
@Json.Ignore private final double m_y;
@Json.Ignore private final double m_z;
/** Constructs a quaternion with a default angle of 0 degrees. */
public Quaternion() {
@@ -45,12 +41,12 @@ public class Quaternion implements ProtobufSerializable, StructSerializable {
* @param y Y component of the quaternion.
* @param z Z component of the quaternion.
*/
@JsonCreator
@Json.Creator
public Quaternion(
@JsonProperty(required = true, value = "W") double w,
@JsonProperty(required = true, value = "X") double x,
@JsonProperty(required = true, value = "Y") double y,
@JsonProperty(required = true, value = "Z") double z) {
@Json.Alias("W") double w,
@Json.Alias("X") double x,
@Json.Alias("Y") double y,
@Json.Alias("Z") double z) {
m_w = w;
m_x = x;
m_y = y;
@@ -291,7 +287,7 @@ public class Quaternion implements ProtobufSerializable, StructSerializable {
*
* @return W component of the quaternion.
*/
@JsonProperty(value = "W")
@Json.Property(value = "W")
public double getW() {
return m_w;
}
@@ -301,7 +297,7 @@ public class Quaternion implements ProtobufSerializable, StructSerializable {
*
* @return X component of the quaternion.
*/
@JsonProperty(value = "X")
@Json.Property(value = "X")
public double getX() {
return m_x;
}
@@ -311,7 +307,7 @@ public class Quaternion implements ProtobufSerializable, StructSerializable {
*
* @return Y component of the quaternion.
*/
@JsonProperty(value = "Y")
@Json.Property(value = "Y")
public double getY() {
return m_y;
}
@@ -321,7 +317,7 @@ public class Quaternion implements ProtobufSerializable, StructSerializable {
*
* @return Z component of the quaternion.
*/
@JsonProperty(value = "Z")
@Json.Property(value = "Z")
public double getZ() {
return m_z;
}

View File

@@ -6,10 +6,7 @@ package org.wpilib.math.geometry;
import static org.wpilib.units.Units.Radians;
import com.fasterxml.jackson.annotation.JsonAutoDetect;
import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.Objects;
import org.wpilib.math.geometry.proto.Rotation2dProto;
import org.wpilib.math.geometry.struct.Rotation2dStruct;
@@ -27,8 +24,7 @@ import org.wpilib.util.struct.StructSerializable;
/**
* A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
*/
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@Json
public class Rotation2d
implements Interpolatable<Rotation2d>, ProtobufSerializable, StructSerializable {
/**
@@ -80,8 +76,8 @@ public class Rotation2d
*/
public static final Rotation2d k180deg = kPi;
private final double m_cos;
private final double m_sin;
@Json.Ignore private final double m_cos;
@Json.Ignore private final double m_sin;
/** Constructs a Rotation2d with a default angle of 0 degrees. */
public Rotation2d() {
@@ -94,8 +90,8 @@ public class Rotation2d
*
* @param value The value of the angle in radians.
*/
@JsonCreator
public Rotation2d(@JsonProperty(required = true, value = "radians") double value) {
@Json.Creator
public Rotation2d(@Json.Alias(value = "radians") double value) {
m_cos = Math.cos(value);
m_sin = Math.sin(value);
}
@@ -300,7 +296,7 @@ public class Rotation2d
*
* @return The radian value of the Rotation2d constrained within [-π, π].
*/
@JsonProperty
@Json.Property("radians")
public double getRadians() {
return Math.atan2(m_sin, m_cos);
}

View File

@@ -6,10 +6,7 @@ package org.wpilib.math.geometry;
import static org.wpilib.units.Units.Radians;
import com.fasterxml.jackson.annotation.JsonAutoDetect;
import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.Objects;
import org.wpilib.math.geometry.proto.Rotation3dProto;
import org.wpilib.math.geometry.struct.Rotation3dStruct;
@@ -68,8 +65,7 @@ import org.wpilib.util.struct.StructSerializable;
* rotation. A neat property is that applying a series of rotations extrinsically is the same as
* applying the same series in the opposite order intrinsically.
*/
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@Json
public class Rotation3d
implements Interpolatable<Rotation3d>, ProtobufSerializable, StructSerializable {
/**
@@ -79,6 +75,7 @@ public class Rotation3d
*/
public static final Rotation3d kZero = new Rotation3d();
@Json.Property("quaternion")
private final Quaternion m_q;
/** Constructs a Rotation3d representing no rotation. */
@@ -91,8 +88,8 @@ public class Rotation3d
*
* @param q The quaternion.
*/
@JsonCreator
public Rotation3d(@JsonProperty(required = true, value = "quaternion") Quaternion q) {
@Json.Creator
public Rotation3d(@Json.Alias("quaternion") Quaternion q) {
m_q = q.normalize();
}
@@ -393,7 +390,6 @@ public class Rotation3d
*
* @return The quaternion representation of the Rotation3d.
*/
@JsonProperty(value = "quaternion")
public Quaternion getQuaternion() {
return m_q;
}

View File

@@ -6,10 +6,7 @@ package org.wpilib.math.geometry;
import static org.wpilib.units.Units.Meters;
import com.fasterxml.jackson.annotation.JsonAutoDetect;
import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.Collection;
import java.util.Collections;
import java.util.Comparator;
@@ -31,8 +28,7 @@ import org.wpilib.util.struct.StructSerializable;
* <p>This assumes that you are using conventional mathematical axes. When the robot is at the
* origin facing in the positive X direction, forward is positive X and left is positive Y.
*/
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@Json
public class Translation2d
implements Interpolatable<Translation2d>, ProtobufSerializable, StructSerializable {
/**
@@ -42,7 +38,10 @@ public class Translation2d
*/
public static final Translation2d kZero = new Translation2d();
@Json.Property("x")
private final double m_x;
@Json.Property("y")
private final double m_y;
/** Constructs a Translation2d with X and Y components equal to zero. */
@@ -56,10 +55,8 @@ public class Translation2d
* @param x The x component of the translation.
* @param y The y component of the translation.
*/
@JsonCreator
public Translation2d(
@JsonProperty(required = true, value = "x") double x,
@JsonProperty(required = true, value = "y") double y) {
@Json.Creator
public Translation2d(double x, double y) {
m_x = x;
m_y = y;
}
@@ -130,7 +127,6 @@ public class Translation2d
*
* @return The X component of the translation.
*/
@JsonProperty
public double getX() {
return m_x;
}
@@ -140,7 +136,6 @@ public class Translation2d
*
* @return The Y component of the translation.
*/
@JsonProperty
public double getY() {
return m_y;
}

View File

@@ -6,10 +6,7 @@ package org.wpilib.math.geometry;
import static org.wpilib.units.Units.Meters;
import com.fasterxml.jackson.annotation.JsonAutoDetect;
import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.Collection;
import java.util.Collections;
import java.util.Comparator;
@@ -32,8 +29,7 @@ import org.wpilib.util.struct.StructSerializable;
* origin facing in the positive X direction, forward is positive X, left is positive Y, and up is
* positive Z.
*/
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@Json
public class Translation3d
implements Interpolatable<Translation3d>, ProtobufSerializable, StructSerializable {
/**
@@ -43,8 +39,13 @@ public class Translation3d
*/
public static final Translation3d kZero = new Translation3d();
@Json.Property("x")
private final double m_x;
@Json.Property("y")
private final double m_y;
@Json.Property("z")
private final double m_z;
/** Constructs a Translation3d with X, Y, and Z components equal to zero. */
@@ -59,11 +60,8 @@ public class Translation3d
* @param y The y component of the translation.
* @param z The z component of the translation.
*/
@JsonCreator
public Translation3d(
@JsonProperty(required = true, value = "x") double x,
@JsonProperty(required = true, value = "y") double y,
@JsonProperty(required = true, value = "z") double z) {
@Json.Creator
public Translation3d(double x, double y, double z) {
m_x = x;
m_y = y;
m_z = z;
@@ -152,7 +150,6 @@ public class Translation3d
*
* @return The X component of the translation.
*/
@JsonProperty
public double getX() {
return m_x;
}
@@ -162,7 +159,6 @@ public class Translation3d
*
* @return The Y component of the translation.
*/
@JsonProperty
public double getY() {
return m_y;
}
@@ -172,7 +168,6 @@ public class Translation3d
*
* @return The Z component of the translation.
*/
@JsonProperty
public double getZ() {
return m_z;
}

View File

@@ -4,7 +4,7 @@
package org.wpilib.math.trajectory;
import com.fasterxml.jackson.annotation.JsonProperty;
import io.avaje.jsonb.Json;
import java.util.ArrayList;
import java.util.List;
import java.util.Objects;
@@ -256,23 +256,23 @@ public class Trajectory implements ProtobufSerializable {
public static final TrajectoryStateProto proto = new TrajectoryStateProto();
/** The time elapsed since the beginning of the trajectory in seconds. */
@JsonProperty("time")
@Json.Property("time")
public double time;
/** The velocity at that point of the trajectory in meters per second. */
@JsonProperty("velocity")
@Json.Property("velocity")
public double velocity;
/** The acceleration at that point of the trajectory in m/s². */
@JsonProperty("acceleration")
@Json.Property("acceleration")
public double acceleration;
/** The pose at that point of the trajectory. */
@JsonProperty("pose")
@Json.Property("pose")
public Pose2d pose;
/** The curvature at that point of the trajectory in rad/m. */
@JsonProperty("curvature")
@Json.Property("curvature")
public double curvature;
/** Default constructor. */