Skip to content

Commit

Permalink
[wpiutil] Add serializable marker interfaces (#6060)
Browse files Browse the repository at this point in the history
  • Loading branch information
PeterJohnson authored Dec 23, 2023
1 parent c1178d5 commit aeb1a4a
Show file tree
Hide file tree
Showing 27 changed files with 149 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<ArmFeedforward>, StructSerializable<ArmFeedforward> {
public final double ks;
public final double kg;
public final double kv;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<DifferentialDriveWheelVoltages>,
StructSerializable<DifferentialDriveWheelVoltages> {
public double left;
public double right;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<ElevatorFeedforward>, StructSerializable<ElevatorFeedforward> {
public final double ks;
public final double kg;
public final double kv;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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<Pose2d> {
public class Pose2d
implements Interpolatable<Pose2d>, ProtobufSerializable<Pose2d>, StructSerializable<Pose2d> {
private final Translation2d m_translation;
private final Rotation2d m_rotation;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Pose3d> {
public class Pose3d
implements Interpolatable<Pose3d>, ProtobufSerializable<Pose3d>, StructSerializable<Pose3d> {
private final Translation3d m_translation;
private final Rotation3d m_rotation;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Quaternion>, StructSerializable<Quaternion> {
// Scalar r in versor form
private final double m_w;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand All @@ -28,7 +30,10 @@
*/
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
public class Rotation2d implements Interpolatable<Rotation2d> {
public class Rotation2d
implements Interpolatable<Rotation2d>,
ProtobufSerializable<Rotation2d>,
StructSerializable<Rotation2d> {
private final double m_value;
private final double m_cos;
private final double m_sin;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Rotation3d> {
public class Rotation3d
implements Interpolatable<Rotation3d>,
ProtobufSerializable<Rotation3d>,
StructSerializable<Rotation3d> {
private final Quaternion m_q;

/** Constructs a Rotation3d with a default angle of 0 degrees. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Transform2d>, StructSerializable<Transform2d> {
private final Translation2d m_translation;
private final Rotation2d m_rotation;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Transform3d>, StructSerializable<Transform3d> {
private final Translation3d m_translation;
private final Rotation3d m_rotation;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -29,7 +31,10 @@
*/
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
public class Translation2d implements Interpolatable<Translation2d> {
public class Translation2d
implements Interpolatable<Translation2d>,
ProtobufSerializable<Translation2d>,
StructSerializable<Translation2d> {
private final double m_x;
private final double m_y;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand All @@ -27,7 +29,10 @@
*/
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
public class Translation3d implements Interpolatable<Translation3d> {
public class Translation3d
implements Interpolatable<Translation3d>,
ProtobufSerializable<Translation3d>,
StructSerializable<Translation3d> {
private final double m_x;
private final double m_y;
private final double m_z;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand All @@ -14,7 +16,7 @@
*
* <p>A Twist can be used to represent a difference between two poses.
*/
public class Twist2d {
public class Twist2d implements ProtobufSerializable<Twist2d>, StructSerializable<Twist2d> {
/** Linear "dx" component. */
public double dx;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand All @@ -14,7 +16,7 @@
*
* <p>A Twist can be used to represent a difference between two poses.
*/
public class Twist3d {
public class Twist3d implements ProtobufSerializable<Twist3d>, StructSerializable<Twist3d> {
/** Linear "dx" component. */
public double dx;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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<ChassisSpeeds>, StructSerializable<ChassisSpeeds> {
/** Velocity along the x-axis. (Fwd is +) */
public double vxMetersPerSecond;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -23,7 +25,9 @@
* chassis speed.
*/
public class DifferentialDriveKinematics
implements Kinematics<DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions> {
implements Kinematics<DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions>,
ProtobufSerializable<DifferentialDriveKinematics>,
StructSerializable<DifferentialDriveKinematics> {
public final double trackWidthMeters;

public static final DifferentialDriveKinematicsProto proto =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<DifferentialDriveWheelSpeeds>,
StructSerializable<DifferentialDriveWheelSpeeds> {
/** Speed of the left side of the robot. */
public double leftMetersPerSecond;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand All @@ -33,7 +35,9 @@
* field using encoders and a gyro.
*/
public class MecanumDriveKinematics
implements Kinematics<MecanumDriveWheelSpeeds, MecanumDriveWheelPositions> {
implements Kinematics<MecanumDriveWheelSpeeds, MecanumDriveWheelPositions>,
ProtobufSerializable<MecanumDriveKinematics>,
StructSerializable<MecanumDriveKinematics> {
private final SimpleMatrix m_inverseKinematics;
private final SimpleMatrix m_forwardKinematics;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<MecanumDriveWheelPositions> {
public class MecanumDriveWheelPositions
implements WheelPositions<MecanumDriveWheelPositions>,
ProtobufSerializable<MecanumDriveWheelPositions>,
StructSerializable<MecanumDriveWheelPositions> {
/** Distance measured by the front left wheel. */
public double frontLeftMeters;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<MecanumDriveWheelSpeeds>,
StructSerializable<MecanumDriveWheelSpeeds> {
/** Speed of the front left wheel. */
public double frontLeftMetersPerSecond;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<SwerveModulePosition>, Interpolatable<SwerveModulePosition> {
implements Comparable<SwerveModulePosition>,
Interpolatable<SwerveModulePosition>,
ProtobufSerializable<SwerveModulePosition>,
StructSerializable<SwerveModulePosition> {
/** Distance measured by the wheel of the module. */
public double distanceMeters;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<SwerveModuleState> {
public class SwerveModuleState
implements Comparable<SwerveModuleState>,
ProtobufSerializable<SwerveModuleState>,
StructSerializable<SwerveModuleState> {
/** Speed of the wheel of the module. */
public double speedMetersPerSecond;

Expand Down
Loading

0 comments on commit aeb1a4a

Please sign in to comment.