From aeb1a4aa33b8a9e90add64163aee72beb8faf6fa Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sat, 23 Dec 2023 08:20:26 -0800 Subject: [PATCH] [wpiutil] Add serializable marker interfaces (#6060) --- .../wpi/first/math/controller/ArmFeedforward.java | 5 ++++- .../DifferentialDriveWheelVoltages.java | 6 +++++- .../math/controller/ElevatorFeedforward.java | 5 ++++- .../java/edu/wpi/first/math/geometry/Pose2d.java | 5 ++++- .../java/edu/wpi/first/math/geometry/Pose3d.java | 5 ++++- .../edu/wpi/first/math/geometry/Quaternion.java | 5 ++++- .../edu/wpi/first/math/geometry/Rotation2d.java | 7 ++++++- .../edu/wpi/first/math/geometry/Rotation3d.java | 7 ++++++- .../edu/wpi/first/math/geometry/Transform2d.java | 5 ++++- .../edu/wpi/first/math/geometry/Transform3d.java | 5 ++++- .../wpi/first/math/geometry/Translation2d.java | 7 ++++++- .../wpi/first/math/geometry/Translation3d.java | 7 ++++++- .../java/edu/wpi/first/math/geometry/Twist2d.java | 4 +++- .../java/edu/wpi/first/math/geometry/Twist3d.java | 4 +++- .../wpi/first/math/kinematics/ChassisSpeeds.java | 5 ++++- .../kinematics/DifferentialDriveKinematics.java | 6 +++++- .../kinematics/DifferentialDriveWheelSpeeds.java | 6 +++++- .../math/kinematics/MecanumDriveKinematics.java | 6 +++++- .../kinematics/MecanumDriveWheelPositions.java | 7 ++++++- .../math/kinematics/MecanumDriveWheelSpeeds.java | 6 +++++- .../math/kinematics/SwerveModulePosition.java | 7 ++++++- .../first/math/kinematics/SwerveModuleState.java | 7 ++++++- .../edu/wpi/first/math/system/plant/DCMotor.java | 4 +++- .../edu/wpi/first/math/trajectory/Trajectory.java | 5 +++-- .../java/edu/wpi/first/util/WPISerializable.java | 8 ++++++++ .../first/util/protobuf/ProtobufSerializable.java | 15 +++++++++++++++ .../wpi/first/util/struct/StructSerializable.java | 15 +++++++++++++++ 27 files changed, 149 insertions(+), 25 deletions(-) create mode 100644 wpiutil/src/main/java/edu/wpi/first/util/WPISerializable.java create mode 100644 wpiutil/src/main/java/edu/wpi/first/util/protobuf/ProtobufSerializable.java create mode 100644 wpiutil/src/main/java/edu/wpi/first/util/struct/StructSerializable.java diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java index e7551a762b0..5e2be2ad6ac 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java @@ -6,12 +6,15 @@ import edu.wpi.first.math.controller.proto.ArmFeedforwardProto; import edu.wpi.first.math.controller.struct.ArmFeedforwardStruct; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; /** * A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting * against the force of gravity on a beam suspended at an angle). */ -public class ArmFeedforward { +public class ArmFeedforward + implements ProtobufSerializable, StructSerializable { public final double ks; public final double kg; public final double kv; diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java index ff5e81475b0..526d68ac084 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java @@ -6,9 +6,13 @@ import edu.wpi.first.math.controller.proto.DifferentialDriveWheelVoltagesProto; import edu.wpi.first.math.controller.struct.DifferentialDriveWheelVoltagesStruct; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; /** Motor voltages for a differential drive. */ -public class DifferentialDriveWheelVoltages { +public class DifferentialDriveWheelVoltages + implements ProtobufSerializable, + StructSerializable { public double left; public double right; diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java index 9ae81358581..9a6b1ef8e97 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java @@ -9,12 +9,15 @@ import edu.wpi.first.math.controller.proto.ElevatorFeedforwardProto; import edu.wpi.first.math.controller.struct.ElevatorFeedforwardStruct; import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; /** * A helper class that computes feedforward outputs for a simple elevator (modeled as a motor acting * against the force of gravity). */ -public class ElevatorFeedforward { +public class ElevatorFeedforward + implements ProtobufSerializable, StructSerializable { public final double ks; public final double kg; public final double kv; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java index 9844198462d..e824cc38c96 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java @@ -15,6 +15,8 @@ import edu.wpi.first.math.interpolation.Interpolatable; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Collections; import java.util.Comparator; import java.util.List; @@ -23,7 +25,8 @@ /** Represents a 2D pose containing translational and rotational elements. */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Pose2d implements Interpolatable { +public class Pose2d + implements Interpolatable, ProtobufSerializable, StructSerializable { private final Translation2d m_translation; private final Rotation2d m_rotation; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java index 3fd5b653b81..ef3597d2f02 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java @@ -12,12 +12,15 @@ import edu.wpi.first.math.geometry.proto.Pose3dProto; import edu.wpi.first.math.geometry.struct.Pose3dStruct; import edu.wpi.first.math.interpolation.Interpolatable; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** Represents a 3D pose containing translational and rotational elements. */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Pose3d implements Interpolatable { +public class Pose3d + implements Interpolatable, ProtobufSerializable, StructSerializable { private final Translation3d m_translation; private final Rotation3d m_rotation; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Quaternion.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Quaternion.java index 0d9ef88145a..41ac6b1f756 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Quaternion.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Quaternion.java @@ -13,11 +13,14 @@ import edu.wpi.first.math.geometry.proto.QuaternionProto; import edu.wpi.first.math.geometry.struct.QuaternionStruct; import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Quaternion { +public class Quaternion + implements ProtobufSerializable, StructSerializable { // Scalar r in versor form private final double m_w; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java index 9da3fa2ea28..71c1e494ceb 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java @@ -17,6 +17,8 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.units.Angle; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** @@ -28,7 +30,10 @@ */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Rotation2d implements Interpolatable { +public class Rotation2d + implements Interpolatable, + ProtobufSerializable, + StructSerializable { private final double m_value; private final double m_cos; private final double m_sin; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java index 25473c0927b..3cfcac6adf5 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java @@ -18,13 +18,18 @@ import edu.wpi.first.math.geometry.struct.Rotation3dStruct; import edu.wpi.first.math.interpolation.Interpolatable; import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; import org.ejml.dense.row.factory.DecompositionFactory_DDRM; /** A rotation in a 3D coordinate frame represented by a quaternion. */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Rotation3d implements Interpolatable { +public class Rotation3d + implements Interpolatable, + ProtobufSerializable, + StructSerializable { private final Quaternion m_q; /** Constructs a Rotation3d with a default angle of 0 degrees. */ diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java index e5a8255f922..f67b06cbeff 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java @@ -10,10 +10,13 @@ import edu.wpi.first.math.geometry.struct.Transform2dStruct; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** Represents a transformation for a Pose2d in the pose's frame. */ -public class Transform2d { +public class Transform2d + implements ProtobufSerializable, StructSerializable { private final Translation2d m_translation; private final Rotation2d m_rotation; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java index 6b4fe1f63c6..fcdeef25b8b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java @@ -6,10 +6,13 @@ import edu.wpi.first.math.geometry.proto.Transform3dProto; import edu.wpi.first.math.geometry.struct.Transform3dStruct; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** Represents a transformation for a Pose3d in the pose's frame. */ -public class Transform3d { +public class Transform3d + implements ProtobufSerializable, StructSerializable { private final Translation3d m_translation; private final Rotation3d m_rotation; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java index 4c8d17c8dcd..8af696124d9 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation2d.java @@ -16,6 +16,8 @@ import edu.wpi.first.math.interpolation.Interpolatable; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Collections; import java.util.Comparator; import java.util.List; @@ -29,7 +31,10 @@ */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Translation2d implements Interpolatable { +public class Translation2d + implements Interpolatable, + ProtobufSerializable, + StructSerializable { private final double m_x; private final double m_y; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java index 8d12d56512d..1b88d18fe17 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Translation3d.java @@ -16,6 +16,8 @@ import edu.wpi.first.math.interpolation.Interpolatable; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** @@ -27,7 +29,10 @@ */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Translation3d implements Interpolatable { +public class Translation3d + implements Interpolatable, + ProtobufSerializable, + StructSerializable { private final double m_x; private final double m_y; private final double m_z; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java index 1a0b6786646..a656baa0169 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist2d.java @@ -6,6 +6,8 @@ import edu.wpi.first.math.geometry.proto.Twist2dProto; import edu.wpi.first.math.geometry.struct.Twist2dStruct; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** @@ -14,7 +16,7 @@ * *

A Twist can be used to represent a difference between two poses. */ -public class Twist2d { +public class Twist2d implements ProtobufSerializable, StructSerializable { /** Linear "dx" component. */ public double dx; diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist3d.java index 8b2470f7273..e5f79e4bebd 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Twist3d.java @@ -6,6 +6,8 @@ import edu.wpi.first.math.geometry.proto.Twist3dProto; import edu.wpi.first.math.geometry.struct.Twist3dStruct; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** @@ -14,7 +16,7 @@ * *

A Twist can be used to represent a difference between two poses. */ -public class Twist3d { +public class Twist3d implements ProtobufSerializable, StructSerializable { /** Linear "dx" component. */ public double dx; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java index 759398a04c8..8304b137ede 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java @@ -18,6 +18,8 @@ import edu.wpi.first.units.Measure; import edu.wpi.first.units.Time; import edu.wpi.first.units.Velocity; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; /** * Represents the speed of a robot chassis. Although this class contains similar members compared to @@ -28,7 +30,8 @@ * component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum * will often have all three components. */ -public class ChassisSpeeds { +public class ChassisSpeeds + implements ProtobufSerializable, StructSerializable { /** Velocity along the x-axis. (Fwd is +) */ public double vxMetersPerSecond; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java index b892daa5745..7f39c8788f8 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java @@ -13,6 +13,8 @@ import edu.wpi.first.math.kinematics.struct.DifferentialDriveKinematicsStruct; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; /** * Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel @@ -23,7 +25,9 @@ * chassis speed. */ public class DifferentialDriveKinematics - implements Kinematics { + implements Kinematics, + ProtobufSerializable, + StructSerializable { public final double trackWidthMeters; public static final DifferentialDriveKinematicsProto proto = diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java index 17a48e226f3..5b4bb501e54 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java @@ -11,9 +11,13 @@ import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; import edu.wpi.first.units.Velocity; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; /** Represents the wheel speeds for a differential drive drivetrain. */ -public class DifferentialDriveWheelSpeeds { +public class DifferentialDriveWheelSpeeds + implements ProtobufSerializable, + StructSerializable { /** Speed of the left side of the robot. */ public double leftMetersPerSecond; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java index c9ff593a9fd..14829afa365 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java @@ -10,6 +10,8 @@ import edu.wpi.first.math.geometry.Twist2d; import edu.wpi.first.math.kinematics.proto.MecanumDriveKinematicsProto; import edu.wpi.first.math.kinematics.struct.MecanumDriveKinematicsStruct; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import org.ejml.simple.SimpleMatrix; /** @@ -33,7 +35,9 @@ * field using encoders and a gyro. */ public class MecanumDriveKinematics - implements Kinematics { + implements Kinematics, + ProtobufSerializable, + StructSerializable { private final SimpleMatrix m_inverseKinematics; private final SimpleMatrix m_forwardKinematics; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java index 5515802fc40..c22de3a8c32 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelPositions.java @@ -11,9 +11,14 @@ import edu.wpi.first.math.kinematics.struct.MecanumDriveWheelPositionsStruct; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; -public class MecanumDriveWheelPositions implements WheelPositions { +public class MecanumDriveWheelPositions + implements WheelPositions, + ProtobufSerializable, + StructSerializable { /** Distance measured by the front left wheel. */ public double frontLeftMeters; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java index 2297b3111aa..73ccf295fb8 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java @@ -11,8 +11,12 @@ import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; import edu.wpi.first.units.Velocity; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; -public class MecanumDriveWheelSpeeds { +public class MecanumDriveWheelSpeeds + implements ProtobufSerializable, + StructSerializable { /** Speed of the front left wheel. */ public double frontLeftMetersPerSecond; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java index 9583dbd3134..02803900000 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java @@ -13,11 +13,16 @@ import edu.wpi.first.math.kinematics.struct.SwerveModulePositionStruct; import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** Represents the state of one swerve module. */ public class SwerveModulePosition - implements Comparable, Interpolatable { + implements Comparable, + Interpolatable, + ProtobufSerializable, + StructSerializable { /** Distance measured by the wheel of the module. */ public double distanceMeters; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java index bbc3b205e59..329e6b1116b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java @@ -12,10 +12,15 @@ import edu.wpi.first.units.Distance; import edu.wpi.first.units.Measure; import edu.wpi.first.units.Velocity; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** Represents the state of one swerve module. */ -public class SwerveModuleState implements Comparable { +public class SwerveModuleState + implements Comparable, + ProtobufSerializable, + StructSerializable { /** Speed of the wheel of the module. */ public double speedMetersPerSecond; diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java index 9f9cafef7ab..9f5d67dbf0e 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java @@ -7,9 +7,11 @@ import edu.wpi.first.math.system.plant.proto.DCMotorProto; import edu.wpi.first.math.system.plant.struct.DCMotorStruct; import edu.wpi.first.math.util.Units; +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.util.struct.StructSerializable; /** Holds the constants for a DC motor. */ -public class DCMotor { +public class DCMotor implements ProtobufSerializable, StructSerializable { public final double nominalVoltageVolts; public final double stallTorqueNewtonMeters; public final double stallCurrentAmps; diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java index bc2dea3a4f2..ff54157bdb2 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java @@ -9,6 +9,7 @@ import edu.wpi.first.math.geometry.Transform2d; import edu.wpi.first.math.trajectory.proto.TrajectoryProto; import edu.wpi.first.math.trajectory.proto.TrajectoryStateProto; +import edu.wpi.first.util.protobuf.ProtobufSerializable; import java.util.ArrayList; import java.util.List; import java.util.Objects; @@ -18,7 +19,7 @@ * Represents a time-parameterized trajectory. The trajectory contains of various States that * represent the pose, curvature, time elapsed, velocity, and acceleration at that point. */ -public class Trajectory { +public class Trajectory implements ProtobufSerializable { public static final TrajectoryProto proto = new TrajectoryProto(); private final double m_totalTimeSeconds; @@ -267,7 +268,7 @@ public Trajectory concatenate(Trajectory other) { * Represents a time-parameterized trajectory. The trajectory contains of various States that * represent the pose, curvature, time elapsed, velocity, and acceleration at that point. */ - public static class State { + public static class State implements ProtobufSerializable { public static final TrajectoryStateProto proto = new TrajectoryStateProto(); // The time elapsed since the beginning of the trajectory. diff --git a/wpiutil/src/main/java/edu/wpi/first/util/WPISerializable.java b/wpiutil/src/main/java/edu/wpi/first/util/WPISerializable.java new file mode 100644 index 00000000000..753f40d2078 --- /dev/null +++ b/wpiutil/src/main/java/edu/wpi/first/util/WPISerializable.java @@ -0,0 +1,8 @@ +// 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.util; + +/** Marker interface to indicate a class is serializable using WPI serialization methods. */ +public interface WPISerializable {} diff --git a/wpiutil/src/main/java/edu/wpi/first/util/protobuf/ProtobufSerializable.java b/wpiutil/src/main/java/edu/wpi/first/util/protobuf/ProtobufSerializable.java new file mode 100644 index 00000000000..78fdf8fbff0 --- /dev/null +++ b/wpiutil/src/main/java/edu/wpi/first/util/protobuf/ProtobufSerializable.java @@ -0,0 +1,15 @@ +// 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.util.protobuf; + +import edu.wpi.first.util.WPISerializable; + +/** + * Marker interface to indicate a class is serializable using Protobuf serialization. + * + *

While this cannot be enforced by the interface, any class implementing this interface should + * provide a public final static `proto` member variable. + */ +public interface ProtobufSerializable extends WPISerializable {} diff --git a/wpiutil/src/main/java/edu/wpi/first/util/struct/StructSerializable.java b/wpiutil/src/main/java/edu/wpi/first/util/struct/StructSerializable.java new file mode 100644 index 00000000000..93cf6f262b0 --- /dev/null +++ b/wpiutil/src/main/java/edu/wpi/first/util/struct/StructSerializable.java @@ -0,0 +1,15 @@ +// 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.util.struct; + +import edu.wpi.first.util.WPISerializable; + +/** + * Marker interface to indicate a class is serializable using Struct serialization. + * + *

While this cannot be enforced by the interface, any class implementing this interface should + * provide a public final static `struct` member variable. + */ +public interface StructSerializable extends WPISerializable {}