mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
[wpiutil] Remove type param from ProtobufSerializable and StructSerializable (#6122)
This commit is contained in:
@@ -13,8 +13,7 @@ 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
|
||||
implements ProtobufSerializable<ArmFeedforward>, StructSerializable<ArmFeedforward> {
|
||||
public class ArmFeedforward implements ProtobufSerializable, StructSerializable {
|
||||
public final double ks;
|
||||
public final double kg;
|
||||
public final double kv;
|
||||
|
||||
@@ -10,9 +10,7 @@ import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
/** Motor voltages for a differential drive. */
|
||||
public class DifferentialDriveWheelVoltages
|
||||
implements ProtobufSerializable<DifferentialDriveWheelVoltages>,
|
||||
StructSerializable<DifferentialDriveWheelVoltages> {
|
||||
public class DifferentialDriveWheelVoltages implements ProtobufSerializable, StructSerializable {
|
||||
public double left;
|
||||
public double right;
|
||||
|
||||
|
||||
@@ -16,8 +16,7 @@ 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
|
||||
implements ProtobufSerializable<ElevatorFeedforward>, StructSerializable<ElevatorFeedforward> {
|
||||
public class ElevatorFeedforward implements ProtobufSerializable, StructSerializable {
|
||||
public final double ks;
|
||||
public final double kg;
|
||||
public final double kv;
|
||||
|
||||
@@ -25,8 +25,7 @@ import java.util.Objects;
|
||||
/** Represents a 2D pose containing translational and rotational elements. */
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
|
||||
public class Pose2d
|
||||
implements Interpolatable<Pose2d>, ProtobufSerializable<Pose2d>, StructSerializable<Pose2d> {
|
||||
public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, StructSerializable {
|
||||
private final Translation2d m_translation;
|
||||
private final Rotation2d m_rotation;
|
||||
|
||||
|
||||
@@ -19,8 +19,7 @@ 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<Pose3d>, ProtobufSerializable<Pose3d>, StructSerializable<Pose3d> {
|
||||
public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, StructSerializable {
|
||||
private final Translation3d m_translation;
|
||||
private final Rotation3d m_rotation;
|
||||
|
||||
|
||||
@@ -19,8 +19,7 @@ import java.util.Objects;
|
||||
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
|
||||
public class Quaternion
|
||||
implements ProtobufSerializable<Quaternion>, StructSerializable<Quaternion> {
|
||||
public class Quaternion implements ProtobufSerializable, StructSerializable {
|
||||
// Scalar r in versor form
|
||||
private final double m_w;
|
||||
|
||||
|
||||
@@ -31,9 +31,7 @@ import java.util.Objects;
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
|
||||
public class Rotation2d
|
||||
implements Interpolatable<Rotation2d>,
|
||||
ProtobufSerializable<Rotation2d>,
|
||||
StructSerializable<Rotation2d> {
|
||||
implements Interpolatable<Rotation2d>, ProtobufSerializable, StructSerializable {
|
||||
private final double m_value;
|
||||
private final double m_cos;
|
||||
private final double m_sin;
|
||||
|
||||
@@ -27,9 +27,7 @@ import org.ejml.dense.row.factory.DecompositionFactory_DDRM;
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
|
||||
public class Rotation3d
|
||||
implements Interpolatable<Rotation3d>,
|
||||
ProtobufSerializable<Rotation3d>,
|
||||
StructSerializable<Rotation3d> {
|
||||
implements Interpolatable<Rotation3d>, ProtobufSerializable, StructSerializable {
|
||||
private final Quaternion m_q;
|
||||
|
||||
/** Constructs a Rotation3d with a default angle of 0 degrees. */
|
||||
|
||||
@@ -15,8 +15,7 @@ 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
|
||||
implements ProtobufSerializable<Transform2d>, StructSerializable<Transform2d> {
|
||||
public class Transform2d implements ProtobufSerializable, StructSerializable {
|
||||
private final Translation2d m_translation;
|
||||
private final Rotation2d m_rotation;
|
||||
|
||||
|
||||
@@ -11,8 +11,7 @@ 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
|
||||
implements ProtobufSerializable<Transform3d>, StructSerializable<Transform3d> {
|
||||
public class Transform3d implements ProtobufSerializable, StructSerializable {
|
||||
private final Translation3d m_translation;
|
||||
private final Rotation3d m_rotation;
|
||||
|
||||
|
||||
@@ -32,9 +32,7 @@ import java.util.Objects;
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
|
||||
public class Translation2d
|
||||
implements Interpolatable<Translation2d>,
|
||||
ProtobufSerializable<Translation2d>,
|
||||
StructSerializable<Translation2d> {
|
||||
implements Interpolatable<Translation2d>, ProtobufSerializable, StructSerializable {
|
||||
private final double m_x;
|
||||
private final double m_y;
|
||||
|
||||
|
||||
@@ -30,9 +30,7 @@ import java.util.Objects;
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
|
||||
public class Translation3d
|
||||
implements Interpolatable<Translation3d>,
|
||||
ProtobufSerializable<Translation3d>,
|
||||
StructSerializable<Translation3d> {
|
||||
implements Interpolatable<Translation3d>, ProtobufSerializable, StructSerializable {
|
||||
private final double m_x;
|
||||
private final double m_y;
|
||||
private final double m_z;
|
||||
|
||||
@@ -16,7 +16,7 @@ import java.util.Objects;
|
||||
*
|
||||
* <p>A Twist can be used to represent a difference between two poses.
|
||||
*/
|
||||
public class Twist2d implements ProtobufSerializable<Twist2d>, StructSerializable<Twist2d> {
|
||||
public class Twist2d implements ProtobufSerializable, StructSerializable {
|
||||
/** Linear "dx" component. */
|
||||
public double dx;
|
||||
|
||||
|
||||
@@ -16,7 +16,7 @@ import java.util.Objects;
|
||||
*
|
||||
* <p>A Twist can be used to represent a difference between two poses.
|
||||
*/
|
||||
public class Twist3d implements ProtobufSerializable<Twist3d>, StructSerializable<Twist3d> {
|
||||
public class Twist3d implements ProtobufSerializable, StructSerializable {
|
||||
/** Linear "dx" component. */
|
||||
public double dx;
|
||||
|
||||
|
||||
@@ -30,8 +30,7 @@ import edu.wpi.first.util.struct.StructSerializable;
|
||||
* 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<ChassisSpeeds>, StructSerializable<ChassisSpeeds> {
|
||||
public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
/** Velocity along the x-axis. (Fwd is +) */
|
||||
public double vxMetersPerSecond;
|
||||
|
||||
|
||||
@@ -26,8 +26,8 @@ import edu.wpi.first.util.struct.StructSerializable;
|
||||
*/
|
||||
public class DifferentialDriveKinematics
|
||||
implements Kinematics<DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions>,
|
||||
ProtobufSerializable<DifferentialDriveKinematics>,
|
||||
StructSerializable<DifferentialDriveKinematics> {
|
||||
ProtobufSerializable,
|
||||
StructSerializable {
|
||||
public final double trackWidthMeters;
|
||||
|
||||
public static final DifferentialDriveKinematicsProto proto =
|
||||
|
||||
@@ -15,9 +15,7 @@ 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
|
||||
implements ProtobufSerializable<DifferentialDriveWheelSpeeds>,
|
||||
StructSerializable<DifferentialDriveWheelSpeeds> {
|
||||
public class DifferentialDriveWheelSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
/** Speed of the left side of the robot. */
|
||||
public double leftMetersPerSecond;
|
||||
|
||||
|
||||
@@ -36,8 +36,8 @@ import org.ejml.simple.SimpleMatrix;
|
||||
*/
|
||||
public class MecanumDriveKinematics
|
||||
implements Kinematics<MecanumDriveWheelSpeeds, MecanumDriveWheelPositions>,
|
||||
ProtobufSerializable<MecanumDriveKinematics>,
|
||||
StructSerializable<MecanumDriveKinematics> {
|
||||
ProtobufSerializable,
|
||||
StructSerializable {
|
||||
private final SimpleMatrix m_inverseKinematics;
|
||||
private final SimpleMatrix m_forwardKinematics;
|
||||
|
||||
|
||||
@@ -17,8 +17,8 @@ import java.util.Objects;
|
||||
|
||||
public class MecanumDriveWheelPositions
|
||||
implements WheelPositions<MecanumDriveWheelPositions>,
|
||||
ProtobufSerializable<MecanumDriveWheelPositions>,
|
||||
StructSerializable<MecanumDriveWheelPositions> {
|
||||
ProtobufSerializable,
|
||||
StructSerializable {
|
||||
/** Distance measured by the front left wheel. */
|
||||
public double frontLeftMeters;
|
||||
|
||||
|
||||
@@ -14,9 +14,7 @@ import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
public class MecanumDriveWheelSpeeds
|
||||
implements ProtobufSerializable<MecanumDriveWheelSpeeds>,
|
||||
StructSerializable<MecanumDriveWheelSpeeds> {
|
||||
public class MecanumDriveWheelSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
/** Speed of the front left wheel. */
|
||||
public double frontLeftMetersPerSecond;
|
||||
|
||||
|
||||
@@ -21,8 +21,8 @@ import java.util.Objects;
|
||||
public class SwerveModulePosition
|
||||
implements Comparable<SwerveModulePosition>,
|
||||
Interpolatable<SwerveModulePosition>,
|
||||
ProtobufSerializable<SwerveModulePosition>,
|
||||
StructSerializable<SwerveModulePosition> {
|
||||
ProtobufSerializable,
|
||||
StructSerializable {
|
||||
/** Distance measured by the wheel of the module. */
|
||||
public double distanceMeters;
|
||||
|
||||
|
||||
@@ -18,9 +18,7 @@ import java.util.Objects;
|
||||
|
||||
/** Represents the state of one swerve module. */
|
||||
public class SwerveModuleState
|
||||
implements Comparable<SwerveModuleState>,
|
||||
ProtobufSerializable<SwerveModuleState>,
|
||||
StructSerializable<SwerveModuleState> {
|
||||
implements Comparable<SwerveModuleState>, ProtobufSerializable, StructSerializable {
|
||||
/** Speed of the wheel of the module. */
|
||||
public double speedMetersPerSecond;
|
||||
|
||||
|
||||
@@ -11,7 +11,7 @@ import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
/** Holds the constants for a DC motor. */
|
||||
public class DCMotor implements ProtobufSerializable<DCMotor>, StructSerializable<DCMotor> {
|
||||
public class DCMotor implements ProtobufSerializable, StructSerializable {
|
||||
public final double nominalVoltageVolts;
|
||||
public final double stallTorqueNewtonMeters;
|
||||
public final double stallCurrentAmps;
|
||||
|
||||
@@ -19,7 +19,7 @@ import java.util.stream.Collectors;
|
||||
* 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<Trajectory> {
|
||||
public class Trajectory implements ProtobufSerializable {
|
||||
public static final TrajectoryProto proto = new TrajectoryProto();
|
||||
|
||||
private final double m_totalTimeSeconds;
|
||||
@@ -268,7 +268,7 @@ public class Trajectory implements ProtobufSerializable<Trajectory> {
|
||||
* 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<State> {
|
||||
public static class State implements ProtobufSerializable {
|
||||
public static final TrajectoryStateProto proto = new TrajectoryStateProto();
|
||||
|
||||
// The time elapsed since the beginning of the trajectory.
|
||||
|
||||
Reference in New Issue
Block a user