From d0b60752088893a626f1980e95004cc3c56d6592 Mon Sep 17 00:00:00 2001 From: Joseph Eng Date: Sun, 31 Dec 2023 13:51:23 -0800 Subject: [PATCH] Remove type param from ProtobufSerializable and StructSerializable --- .../java/edu/wpi/first/math/controller/ArmFeedforward.java | 3 +-- .../first/math/controller/DifferentialDriveWheelVoltages.java | 4 +--- .../edu/wpi/first/math/controller/ElevatorFeedforward.java | 3 +-- wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java | 3 +-- wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java | 3 +-- .../src/main/java/edu/wpi/first/math/geometry/Quaternion.java | 3 +-- .../src/main/java/edu/wpi/first/math/geometry/Rotation2d.java | 4 +--- .../src/main/java/edu/wpi/first/math/geometry/Rotation3d.java | 4 +--- .../main/java/edu/wpi/first/math/geometry/Transform2d.java | 3 +-- .../main/java/edu/wpi/first/math/geometry/Transform3d.java | 3 +-- .../main/java/edu/wpi/first/math/geometry/Translation2d.java | 4 +--- .../main/java/edu/wpi/first/math/geometry/Translation3d.java | 4 +--- .../src/main/java/edu/wpi/first/math/geometry/Twist2d.java | 2 +- .../src/main/java/edu/wpi/first/math/geometry/Twist3d.java | 2 +- .../java/edu/wpi/first/math/kinematics/ChassisSpeeds.java | 3 +-- .../first/math/kinematics/DifferentialDriveKinematics.java | 4 ++-- .../first/math/kinematics/DifferentialDriveWheelSpeeds.java | 4 +--- .../edu/wpi/first/math/kinematics/MecanumDriveKinematics.java | 4 ++-- .../wpi/first/math/kinematics/MecanumDriveWheelPositions.java | 4 ++-- .../wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java | 4 +--- .../edu/wpi/first/math/kinematics/SwerveModulePosition.java | 4 ++-- .../java/edu/wpi/first/math/kinematics/SwerveModuleState.java | 4 +--- .../main/java/edu/wpi/first/math/system/plant/DCMotor.java | 2 +- .../main/java/edu/wpi/first/math/trajectory/Trajectory.java | 4 ++-- wpiutil/src/main/java/edu/wpi/first/util/WPISerializable.java | 2 +- .../edu/wpi/first/util/protobuf/ProtobufSerializable.java | 2 +- .../java/edu/wpi/first/util/struct/StructSerializable.java | 2 +- 27 files changed, 32 insertions(+), 56 deletions(-) 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 5e2be2ad6ac..a69653305b7 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 @@ -13,8 +13,7 @@ * 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 - implements ProtobufSerializable, StructSerializable { +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 526d68ac084..e45195655e6 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 @@ -10,9 +10,7 @@ import edu.wpi.first.util.struct.StructSerializable; /** Motor voltages for a differential drive. */ -public class DifferentialDriveWheelVoltages - implements ProtobufSerializable, - StructSerializable { +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 9a6b1ef8e97..a83a457f923 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 @@ -16,8 +16,7 @@ * A helper class that computes feedforward outputs for a simple elevator (modeled as a motor acting * against the force of gravity). */ -public class ElevatorFeedforward - implements ProtobufSerializable, StructSerializable { +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 e824cc38c96..42740c5ffbe 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 @@ -25,8 +25,7 @@ /** Represents a 2D pose containing translational and rotational elements. */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Pose2d - implements Interpolatable, ProtobufSerializable, StructSerializable { +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 ef3597d2f02..4ed67c519fe 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 @@ -19,8 +19,7 @@ /** Represents a 3D pose containing translational and rotational elements. */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Pose3d - implements Interpolatable, ProtobufSerializable, StructSerializable { +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 41ac6b1f756..9ef0a740b07 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 @@ -19,8 +19,7 @@ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) -public class Quaternion - implements ProtobufSerializable, StructSerializable { +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 71c1e494ceb..afca0e84c51 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 @@ -31,9 +31,7 @@ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) public class Rotation2d - implements Interpolatable, - ProtobufSerializable, - StructSerializable { + 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 3cfcac6adf5..ac784ebfa2f 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 @@ -27,9 +27,7 @@ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) public class Rotation3d - implements Interpolatable, - ProtobufSerializable, - StructSerializable { + 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 f67b06cbeff..b3078129147 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 @@ -15,8 +15,7 @@ import java.util.Objects; /** Represents a transformation for a Pose2d in the pose's frame. */ -public class Transform2d - implements ProtobufSerializable, StructSerializable { +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 fcdeef25b8b..d211f7ef21b 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 @@ -11,8 +11,7 @@ import java.util.Objects; /** Represents a transformation for a Pose3d in the pose's frame. */ -public class Transform3d - implements ProtobufSerializable, StructSerializable { +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 8af696124d9..228582311e2 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 @@ -32,9 +32,7 @@ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) public class Translation2d - implements Interpolatable, - ProtobufSerializable, - StructSerializable { + 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 1b88d18fe17..af76f155c13 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 @@ -30,9 +30,7 @@ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) public class Translation3d - implements Interpolatable, - ProtobufSerializable, - StructSerializable { + 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 a656baa0169..9d353a4b1d4 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 @@ -16,7 +16,7 @@ * *

A Twist can be used to represent a difference between two poses. */ -public class Twist2d implements ProtobufSerializable, StructSerializable { +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 e5f79e4bebd..0045f29f7a6 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 @@ -16,7 +16,7 @@ * *

A Twist can be used to represent a difference between two poses. */ -public class Twist3d implements ProtobufSerializable, StructSerializable { +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 8304b137ede..a6662b95990 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 @@ -30,8 +30,7 @@ * component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum * will often have all three components. */ -public class ChassisSpeeds - implements ProtobufSerializable, StructSerializable { +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 7f39c8788f8..7711721e7f4 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 @@ -26,8 +26,8 @@ */ public class DifferentialDriveKinematics implements Kinematics, - ProtobufSerializable, - StructSerializable { + 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 5b4bb501e54..d5e317bfb88 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 @@ -15,9 +15,7 @@ import edu.wpi.first.util.struct.StructSerializable; /** Represents the wheel speeds for a differential drive drivetrain. */ -public class DifferentialDriveWheelSpeeds - implements ProtobufSerializable, - StructSerializable { +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 14829afa365..f73f8d48d4e 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 @@ -36,8 +36,8 @@ */ public class MecanumDriveKinematics implements Kinematics, - ProtobufSerializable, - StructSerializable { + 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 c22de3a8c32..5b5a02ee4e2 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 @@ -17,8 +17,8 @@ public class MecanumDriveWheelPositions implements WheelPositions, - ProtobufSerializable, - StructSerializable { + 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 73ccf295fb8..b1e6bf44234 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 @@ -14,9 +14,7 @@ import edu.wpi.first.util.protobuf.ProtobufSerializable; import edu.wpi.first.util.struct.StructSerializable; -public class MecanumDriveWheelSpeeds - implements ProtobufSerializable, - StructSerializable { +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 02803900000..cccf1466fab 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 @@ -21,8 +21,8 @@ public class SwerveModulePosition implements Comparable, Interpolatable, - ProtobufSerializable, - StructSerializable { + 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 329e6b1116b..9c6b180ca49 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 @@ -18,9 +18,7 @@ /** Represents the state of one swerve module. */ public class SwerveModuleState - implements Comparable, - ProtobufSerializable, - StructSerializable { + 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 9f5d67dbf0e..25da66ceabe 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 @@ -11,7 +11,7 @@ import edu.wpi.first.util.struct.StructSerializable; /** Holds the constants for a DC motor. */ -public class DCMotor implements ProtobufSerializable, StructSerializable { +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 ff54157bdb2..6d9ec0c6829 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 @@ -19,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 implements ProtobufSerializable { +public class Trajectory implements ProtobufSerializable { public static final TrajectoryProto proto = new TrajectoryProto(); private final double m_totalTimeSeconds; @@ -268,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 implements ProtobufSerializable { + 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 index 753f40d2078..200deb54960 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/WPISerializable.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/WPISerializable.java @@ -5,4 +5,4 @@ package edu.wpi.first.util; /** Marker interface to indicate a class is serializable using WPI serialization methods. */ -public interface WPISerializable {} +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 index 78fdf8fbff0..ac75065659c 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/protobuf/ProtobufSerializable.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/protobuf/ProtobufSerializable.java @@ -12,4 +12,4 @@ *

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 {} +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 index 93cf6f262b0..a8d1fdd8078 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/struct/StructSerializable.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/struct/StructSerializable.java @@ -12,4 +12,4 @@ *

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 {} +public interface StructSerializable extends WPISerializable {}