From cc41a0ed2458720555d8aff86fbfc52db3e17a22 Mon Sep 17 00:00:00 2001
From: Wispy <101812473+WispySparks@users.noreply.github.com>
Date: Sun, 8 Dec 2024 19:05:06 -0600
Subject: [PATCH] [wpilib] Replace MecanumDriveMotorVoltages with a functional
interface (#6760)
---
.../command/MecanumControllerCommand.java | 169 ++++-
.../subsystems/DriveSubsystem.java | 15 +-
.../edu/wpi/first/math/proto/Kinematics.java | 601 ++----------------
.../cpp/wpimath/protobuf/kinematics.npb.cpp | 516 +++++++--------
.../cpp/wpimath/protobuf/kinematics.npb.h | 28 +-
.../kinematics/MecanumDriveMotorVoltages.java | 15 +-
.../proto/MecanumDriveMotorVoltagesProto.java | 42 --
.../MecanumDriveMotorVoltagesStruct.java | 48 --
wpimath/src/main/proto/kinematics.proto | 7 -
.../MecanumDriveMotorVoltagesProtoTest.java | 27 -
.../MecanumDriveMotorVoltagesStructTest.java | 25 -
11 files changed, 453 insertions(+), 1040 deletions(-)
delete mode 100644 wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java
delete mode 100644 wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java
delete mode 100644 wpimath/src/test/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProtoTest.java
delete mode 100644 wpimath/src/test/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStructTest.java
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
index 70978c63f12..ee52cfa9c36 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
@@ -38,6 +38,7 @@
*
*
This class is provided by the NewCommands VendorDep
*/
+@SuppressWarnings("removal")
public class MecanumControllerCommand extends Command {
private final Timer m_timer = new Timer();
private final boolean m_usePID;
@@ -53,7 +54,7 @@ public class MecanumControllerCommand extends Command {
private final PIDController m_frontRightController;
private final PIDController m_rearRightController;
private final Supplier m_currentWheelSpeeds;
- private final Consumer m_outputDriveVoltages;
+ private final MecanumVoltagesConsumer m_outputDriveVoltages;
private final Consumer m_outputWheelSpeeds;
private double m_prevFrontLeftSpeedSetpoint; // m/s
private double m_prevRearLeftSpeedSetpoint; // m/s
@@ -84,8 +85,7 @@ public class MecanumControllerCommand extends Command {
* @param frontRightController The front right wheel velocity PID.
* @param rearRightController The rear right wheel velocity PID.
* @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds.
- * @param outputDriveVoltages A MecanumDriveMotorVoltages object containing the output motor
- * voltages.
+ * @param outputDriveVoltages A MecanumVoltagesConsumer that consumes voltages of mecanum motors.
* @param requirements The subsystems to require.
*/
@SuppressWarnings("this-escape")
@@ -104,7 +104,7 @@ public MecanumControllerCommand(
PIDController frontRightController,
PIDController rearRightController,
Supplier currentWheelSpeeds,
- Consumer outputDriveVoltages,
+ MecanumVoltagesConsumer outputDriveVoltages,
Subsystem... requirements) {
m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand");
m_pose = requireNonNullParam(pose, "pose", "MecanumControllerCommand");
@@ -145,6 +145,73 @@ public MecanumControllerCommand(
addRequirements(requirements);
}
+ /**
+ * Constructs a new MecanumControllerCommand that when executed will follow the provided
+ * trajectory. PID control and feedforward are handled internally. Outputs are scaled from -12 to
+ * 12 as a voltage output to the motor.
+ *
+ * Note: The controllers will *not* set the outputVolts to zero upon completion of the path
+ * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
+ *
+ * @param trajectory The trajectory to follow.
+ * @param pose A function that supplies the robot pose - use one of the odometry classes to
+ * provide this.
+ * @param feedforward The feedforward to use for the drivetrain.
+ * @param kinematics The kinematics for the robot drivetrain.
+ * @param xController The Trajectory Tracker PID controller for the robot's x position.
+ * @param yController The Trajectory Tracker PID controller for the robot's y position.
+ * @param thetaController The Trajectory Tracker PID controller for angle for the robot.
+ * @param desiredRotation The angle that the robot should be facing. This is sampled at each time
+ * step.
+ * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel.
+ * @param frontLeftController The front left wheel velocity PID.
+ * @param rearLeftController The rear left wheel velocity PID.
+ * @param frontRightController The front right wheel velocity PID.
+ * @param rearRightController The rear right wheel velocity PID.
+ * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds.
+ * @param outputDriveVoltages A MecanumDriveMotorVoltages object containing the output motor
+ * voltages.
+ * @param requirements The subsystems to require.
+ */
+ @Deprecated(since = "2025", forRemoval = true)
+ public MecanumControllerCommand(
+ Trajectory trajectory,
+ Supplier pose,
+ SimpleMotorFeedforward feedforward,
+ MecanumDriveKinematics kinematics,
+ PIDController xController,
+ PIDController yController,
+ ProfiledPIDController thetaController,
+ Supplier desiredRotation,
+ double maxWheelVelocityMetersPerSecond,
+ PIDController frontLeftController,
+ PIDController rearLeftController,
+ PIDController frontRightController,
+ PIDController rearRightController,
+ Supplier currentWheelSpeeds,
+ Consumer outputDriveVoltages,
+ Subsystem... requirements) {
+ this(
+ trajectory,
+ pose,
+ feedforward,
+ kinematics,
+ xController,
+ yController,
+ thetaController,
+ desiredRotation,
+ maxWheelVelocityMetersPerSecond,
+ frontLeftController,
+ rearLeftController,
+ frontRightController,
+ rearRightController,
+ currentWheelSpeeds,
+ (frontLeft, frontRight, rearLeft, rearRight) ->
+ outputDriveVoltages.accept(
+ new MecanumDriveMotorVoltages(frontLeft, frontRight, rearLeft, rearRight)),
+ requirements);
+ }
+
/**
* Constructs a new MecanumControllerCommand that when executed will follow the provided
* trajectory. PID control and feedforward are handled internally. Outputs are scaled from -12 to
@@ -172,8 +239,7 @@ public MecanumControllerCommand(
* @param frontRightController The front right wheel velocity PID.
* @param rearRightController The rear right wheel velocity PID.
* @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds.
- * @param outputDriveVoltages A MecanumDriveMotorVoltages object containing the output motor
- * voltages.
+ * @param outputDriveVoltages A MecanumVoltagesConsumer that consumes voltages of mecanum motors.
* @param requirements The subsystems to require.
*/
public MecanumControllerCommand(
@@ -190,7 +256,7 @@ public MecanumControllerCommand(
PIDController frontRightController,
PIDController rearRightController,
Supplier currentWheelSpeeds,
- Consumer outputDriveVoltages,
+ MecanumVoltagesConsumer outputDriveVoltages,
Subsystem... requirements) {
this(
trajectory,
@@ -212,6 +278,74 @@ public MecanumControllerCommand(
requirements);
}
+ /**
+ * Constructs a new MecanumControllerCommand that when executed will follow the provided
+ * trajectory. PID control and feedforward are handled internally. Outputs are scaled from -12 to
+ * 12 as a voltage output to the motor.
+ *
+ * Note: The controllers will *not* set the outputVolts to zero upon completion of the path
+ * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
+ *
+ *
Note 2: The final rotation of the robot will be set to the rotation of the final pose in the
+ * trajectory. The robot will not follow the rotations from the poses at each timestep. If
+ * alternate rotation behavior is desired, the other constructor with a supplier for rotation
+ * should be used.
+ *
+ * @param trajectory The trajectory to follow.
+ * @param pose A function that supplies the robot pose - use one of the odometry classes to
+ * provide this.
+ * @param feedforward The feedforward to use for the drivetrain.
+ * @param kinematics The kinematics for the robot drivetrain.
+ * @param xController The Trajectory Tracker PID controller for the robot's x position.
+ * @param yController The Trajectory Tracker PID controller for the robot's y position.
+ * @param thetaController The Trajectory Tracker PID controller for angle for the robot.
+ * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel.
+ * @param frontLeftController The front left wheel velocity PID.
+ * @param rearLeftController The rear left wheel velocity PID.
+ * @param frontRightController The front right wheel velocity PID.
+ * @param rearRightController The rear right wheel velocity PID.
+ * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds.
+ * @param outputDriveVoltages A MecanumDriveMotorVoltages object containing the output motor
+ * voltages.
+ * @param requirements The subsystems to require.
+ */
+ @Deprecated(since = "2025", forRemoval = true)
+ public MecanumControllerCommand(
+ Trajectory trajectory,
+ Supplier pose,
+ SimpleMotorFeedforward feedforward,
+ MecanumDriveKinematics kinematics,
+ PIDController xController,
+ PIDController yController,
+ ProfiledPIDController thetaController,
+ double maxWheelVelocityMetersPerSecond,
+ PIDController frontLeftController,
+ PIDController rearLeftController,
+ PIDController frontRightController,
+ PIDController rearRightController,
+ Supplier currentWheelSpeeds,
+ Consumer outputDriveVoltages,
+ Subsystem... requirements) {
+ this(
+ trajectory,
+ pose,
+ feedforward,
+ kinematics,
+ xController,
+ yController,
+ thetaController,
+ maxWheelVelocityMetersPerSecond,
+ frontLeftController,
+ rearLeftController,
+ frontRightController,
+ rearRightController,
+ currentWheelSpeeds,
+ (frontLeft, frontRight, rearLeft, rearRight) ->
+ outputDriveVoltages.accept(
+ new MecanumDriveMotorVoltages(frontLeft, frontRight, rearLeft, rearRight)),
+ requirements);
+ }
+
/**
* Constructs a new MecanumControllerCommand that when executed will follow the provided
* trajectory. The user should implement a velocity PID on the desired output wheel velocities.
@@ -403,8 +537,7 @@ public void execute() {
m_currentWheelSpeeds.get().rearRightMetersPerSecond, rearRightSpeedSetpoint);
m_outputDriveVoltages.accept(
- new MecanumDriveMotorVoltages(
- frontLeftOutput, frontRightOutput, rearLeftOutput, rearRightOutput));
+ frontLeftOutput, frontRightOutput, rearLeftOutput, rearRightOutput);
} else {
m_outputWheelSpeeds.accept(
@@ -425,4 +558,22 @@ public void end(boolean interrupted) {
public boolean isFinished() {
return m_timer.hasElapsed(m_trajectory.getTotalTimeSeconds());
}
+
+ /** A consumer to represent an operation on the voltages of a mecanum drive. */
+ @FunctionalInterface
+ public interface MecanumVoltagesConsumer {
+ /**
+ * Accepts the voltages to perform some operation with them.
+ *
+ * @param frontLeftVoltage The voltage of the front left motor.
+ * @param frontRightVoltage The voltage of the front right motor.
+ * @param rearLeftVoltage The voltage of the rear left motor.
+ * @param rearRightVoltage The voltage of the rear left motor.
+ */
+ void accept(
+ double frontLeftVoltage,
+ double frontRightVoltage,
+ double rearLeftVoltage,
+ double rearRightVoltage);
+ }
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
index b3f9b3462ab..d6ff1eb734f 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.subsystems;
import edu.wpi.first.math.geometry.Pose2d;
-import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
@@ -125,11 +124,15 @@ public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelativ
}
/** Sets the front left drive MotorController to a voltage. */
- public void setDriveMotorControllersVolts(MecanumDriveMotorVoltages volts) {
- m_frontLeft.setVoltage(volts.frontLeftVoltage);
- m_rearLeft.setVoltage(volts.rearLeftVoltage);
- m_frontRight.setVoltage(volts.frontRightVoltage);
- m_rearRight.setVoltage(volts.rearRightVoltage);
+ public void setDriveMotorControllersVolts(
+ double frontLeftVoltage,
+ double frontRightVoltage,
+ double rearLeftVoltage,
+ double rearRightVoltage) {
+ m_frontLeft.setVoltage(frontLeftVoltage);
+ m_rearLeft.setVoltage(rearLeftVoltage);
+ m_frontRight.setVoltage(frontRightVoltage);
+ m_rearRight.setVoltage(rearRightVoltage);
}
/** Resets the drive encoders to currently read a position of 0. */
diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java
index 5494f0b6752..8db878799f9 100644
--- a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java
+++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java
@@ -19,7 +19,7 @@
import us.hebi.quickbuf.RepeatedMessage;
public final class Kinematics {
- private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(3427,
+ private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(3021,
"ChBraW5lbWF0aWNzLnByb3RvEgl3cGkucHJvdG8aEGdlb21ldHJ5MmQucHJvdG8iTQoVUHJvdG9idWZD" +
"aGFzc2lzU3BlZWRzEg4KAnZ4GAEgASgBUgJ2eBIOCgJ2eRgCIAEoAVICdnkSFAoFb21lZ2EYAyABKAFS" +
"BW9tZWdhIkYKI1Byb3RvYnVmRGlmZmVyZW50aWFsRHJpdmVLaW5lbWF0aWNzEh8KC3RyYWNrX3dpZHRo" +
@@ -31,53 +31,46 @@ public final class Kinematics {
"GAIgASgLMiAud3BpLnByb3RvLlByb3RvYnVmVHJhbnNsYXRpb24yZFIKZnJvbnRSaWdodBI9CglyZWFy" +
"X2xlZnQYAyABKAsyIC53cGkucHJvdG8uUHJvdG9idWZUcmFuc2xhdGlvbjJkUghyZWFyTGVmdBI/Cgpy" +
"ZWFyX3JpZ2h0GAQgASgLMiAud3BpLnByb3RvLlByb3RvYnVmVHJhbnNsYXRpb24yZFIJcmVhclJpZ2h0" +
- "Ip8BCiFQcm90b2J1Zk1lY2FudW1Ecml2ZU1vdG9yVm9sdGFnZXMSHQoKZnJvbnRfbGVmdBgBIAEoAVIJ" +
- "ZnJvbnRMZWZ0Eh8KC2Zyb250X3JpZ2h0GAIgASgBUgpmcm9udFJpZ2h0EhsKCXJlYXJfbGVmdBgDIAEo" +
- "AVIIcmVhckxlZnQSHQoKcmVhcl9yaWdodBgEIAEoAVIJcmVhclJpZ2h0IqABCiJQcm90b2J1Zk1lY2Fu" +
- "dW1Ecml2ZVdoZWVsUG9zaXRpb25zEh0KCmZyb250X2xlZnQYASABKAFSCWZyb250TGVmdBIfCgtmcm9u" +
- "dF9yaWdodBgCIAEoAVIKZnJvbnRSaWdodBIbCglyZWFyX2xlZnQYAyABKAFSCHJlYXJMZWZ0Eh0KCnJl" +
- "YXJfcmlnaHQYBCABKAFSCXJlYXJSaWdodCKdAQofUHJvdG9idWZNZWNhbnVtRHJpdmVXaGVlbFNwZWVk" +
- "cxIdCgpmcm9udF9sZWZ0GAEgASgBUglmcm9udExlZnQSHwoLZnJvbnRfcmlnaHQYAiABKAFSCmZyb250" +
- "UmlnaHQSGwoJcmVhcl9sZWZ0GAMgASgBUghyZWFyTGVmdBIdCgpyZWFyX3JpZ2h0GAQgASgBUglyZWFy" +
- "UmlnaHQiWwodUHJvdG9idWZTd2VydmVEcml2ZUtpbmVtYXRpY3MSOgoHbW9kdWxlcxgBIAMoCzIgLndw",
- "aS5wcm90by5Qcm90b2J1ZlRyYW5zbGF0aW9uMmRSB21vZHVsZXMibwocUHJvdG9idWZTd2VydmVNb2R1" +
- "bGVQb3NpdGlvbhIaCghkaXN0YW5jZRgBIAEoAVIIZGlzdGFuY2USMwoFYW5nbGUYAiABKAsyHS53cGku" +
- "cHJvdG8uUHJvdG9idWZSb3RhdGlvbjJkUgVhbmdsZSJmChlQcm90b2J1ZlN3ZXJ2ZU1vZHVsZVN0YXRl" +
- "EhQKBXNwZWVkGAEgASgBUgVzcGVlZBIzCgVhbmdsZRgCIAEoCzIdLndwaS5wcm90by5Qcm90b2J1ZlJv" +
- "dGF0aW9uMmRSBWFuZ2xlQhoKGGVkdS53cGkuZmlyc3QubWF0aC5wcm90b0qNDwoGEgQAAEQBCggKAQwS" +
- "AwAAEgoICgECEgMCABIKCQoCAwASAwQAGgoICgEIEgMGADEKCQoCCAESAwYAMQoKCgIEABIECAAMAQoK" +
- "CgMEAAESAwgIHQoLCgQEAAIAEgMJAhAKDAoFBAACAAUSAwkCCAoMCgUEAAIAARIDCQkLCgwKBQQAAgAD" +
- "EgMJDg8KCwoEBAACARIDCgIQCgwKBQQAAgEFEgMKAggKDAoFBAACAQESAwoJCwoMCgUEAAIBAxIDCg4P" +
- "CgsKBAQAAgISAwsCEwoMCgUEAAICBRIDCwIICgwKBQQAAgIBEgMLCQ4KDAoFBAACAgMSAwsREgoKCgIE" +
- "ARIEDgAQAQoKCgMEAQESAw4IKwoLCgQEAQIAEgMPAhkKDAoFBAECAAUSAw8CCAoMCgUEAQIAARIDDwkU" +
- "CgwKBQQBAgADEgMPFxgKCgoCBAISBBIAFQEKCgoDBAIBEgMSCCwKCwoEBAICABIDEwISCgwKBQQCAgAF" +
- "EgMTAggKDAoFBAICAAESAxMJDQoMCgUEAgIAAxIDExARCgsKBAQCAgESAxQCEwoMCgUEAgIBBRIDFAII" +
- "CgwKBQQCAgEBEgMUCQ4KDAoFBAICAQMSAxQREgoKCgIEAxIEFwAaAQoKCgMEAwESAxcILwoLCgQEAwIA" +
- "EgMYAhIKDAoFBAMCAAUSAxgCCAoMCgUEAwIAARIDGAkNCgwKBQQDAgADEgMYEBEKCwoEBAMCARIDGQIT" +
- "CgwKBQQDAgEFEgMZAggKDAoFBAMCAQESAxkJDgoMCgUEAwIBAxIDGRESCgoKAgQEEgQcACEBCgoKAwQE" +
- "ARIDHAgmCgsKBAQEAgASAx0CJwoMCgUEBAIABhIDHQIXCgwKBQQEAgABEgMdGCIKDAoFBAQCAAMSAx0l" +
- "JgoLCgQEBAIBEgMeAigKDAoFBAQCAQYSAx4CFwoMCgUEBAIBARIDHhgjCgwKBQQEAgEDEgMeJicKCwoE" +
- "BAQCAhIDHwImCgwKBQQEAgIGEgMfAhcKDAoFBAQCAgESAx8YIQoMCgUEBAICAxIDHyQlCgsKBAQEAgMS" +
- "AyACJwoMCgUEBAIDBhIDIAIXCgwKBQQEAgMBEgMgGCIKDAoFBAQCAwMSAyAlJgoKCgIEBRIEIwAoAQoK" +
- "CgMEBQESAyMIKQoLCgQEBQIAEgMkAhgKDAoFBAUCAAUSAyQCCAoMCgUEBQIAARIDJAkTCgwKBQQFAgAD",
- "EgMkFhcKCwoEBAUCARIDJQIZCgwKBQQFAgEFEgMlAggKDAoFBAUCAQESAyUJFAoMCgUEBQIBAxIDJRcY" +
- "CgsKBAQFAgISAyYCFwoMCgUEBQICBRIDJgIICgwKBQQFAgIBEgMmCRIKDAoFBAUCAgMSAyYVFgoLCgQE" +
- "BQIDEgMnAhgKDAoFBAUCAwUSAycCCAoMCgUEBQIDARIDJwkTCgwKBQQFAgMDEgMnFhcKCgoCBAYSBCoA" +
- "LwEKCgoDBAYBEgMqCCoKCwoEBAYCABIDKwIYCgwKBQQGAgAFEgMrAggKDAoFBAYCAAESAysJEwoMCgUE" +
- "BgIAAxIDKxYXCgsKBAQGAgESAywCGQoMCgUEBgIBBRIDLAIICgwKBQQGAgEBEgMsCRQKDAoFBAYCAQMS" +
- "AywXGAoLCgQEBgICEgMtAhcKDAoFBAYCAgUSAy0CCAoMCgUEBgICARIDLQkSCgwKBQQGAgIDEgMtFRYK" +
- "CwoEBAYCAxIDLgIYCgwKBQQGAgMFEgMuAggKDAoFBAYCAwESAy4JEwoMCgUEBgIDAxIDLhYXCgoKAgQH" +
- "EgQxADYBCgoKAwQHARIDMQgnCgsKBAQHAgASAzICGAoMCgUEBwIABRIDMgIICgwKBQQHAgABEgMyCRMK" +
- "DAoFBAcCAAMSAzIWFwoLCgQEBwIBEgMzAhkKDAoFBAcCAQUSAzMCCAoMCgUEBwIBARIDMwkUCgwKBQQH" +
- "AgEDEgMzFxgKCwoEBAcCAhIDNAIXCgwKBQQHAgIFEgM0AggKDAoFBAcCAgESAzQJEgoMCgUEBwICAxID" +
- "NBUWCgsKBAQHAgMSAzUCGAoMCgUEBwIDBRIDNQIICgwKBQQHAgMBEgM1CRMKDAoFBAcCAwMSAzUWFwoK" +
- "CgIECBIEOAA6AQoKCgMECAESAzgIJQoLCgQECAIAEgM5Ai0KDAoFBAgCAAQSAzkCCgoMCgUECAIABhID" +
- "OQsgCgwKBQQIAgABEgM5ISgKDAoFBAgCAAMSAzkrLAoKCgIECRIEPAA/AQoKCgMECQESAzwIJAoLCgQE" +
- "CQIAEgM9AhYKDAoFBAkCAAUSAz0CCAoMCgUECQIAARIDPQkRCgwKBQQJAgADEgM9FBUKCwoEBAkCARID" +
- "PgIfCgwKBQQJAgEGEgM+AhQKDAoFBAkCAQESAz4VGgoMCgUECQIBAxIDPh0eCgoKAgQKEgRBAEQBCgoK" +
- "AwQKARIDQQghCgsKBAQKAgASA0ICEwoMCgUECgIABRIDQgIICgwKBQQKAgABEgNCCQ4KDAoFBAoCAAMS" +
- "A0IREgoLCgQECgIBEgNDAh8KDAoFBAoCAQYSA0MCFAoMCgUECgIBARIDQxUaCgwKBQQKAgEDEgNDHR5i" +
- "BnByb3RvMw==");
+ "IqABCiJQcm90b2J1Zk1lY2FudW1Ecml2ZVdoZWVsUG9zaXRpb25zEh0KCmZyb250X2xlZnQYASABKAFS" +
+ "CWZyb250TGVmdBIfCgtmcm9udF9yaWdodBgCIAEoAVIKZnJvbnRSaWdodBIbCglyZWFyX2xlZnQYAyAB" +
+ "KAFSCHJlYXJMZWZ0Eh0KCnJlYXJfcmlnaHQYBCABKAFSCXJlYXJSaWdodCKdAQofUHJvdG9idWZNZWNh" +
+ "bnVtRHJpdmVXaGVlbFNwZWVkcxIdCgpmcm9udF9sZWZ0GAEgASgBUglmcm9udExlZnQSHwoLZnJvbnRf" +
+ "cmlnaHQYAiABKAFSCmZyb250UmlnaHQSGwoJcmVhcl9sZWZ0GAMgASgBUghyZWFyTGVmdBIdCgpyZWFy" +
+ "X3JpZ2h0GAQgASgBUglyZWFyUmlnaHQiWwodUHJvdG9idWZTd2VydmVEcml2ZUtpbmVtYXRpY3MSOgoH" +
+ "bW9kdWxlcxgBIAMoCzIgLndwaS5wcm90by5Qcm90b2J1ZlRyYW5zbGF0aW9uMmRSB21vZHVsZXMibwoc" +
+ "UHJvdG9idWZTd2VydmVNb2R1bGVQb3NpdGlvbhIaCghkaXN0YW5jZRgBIAEoAVIIZGlzdGFuY2USMwoF" +
+ "YW5nbGUYAiABKAsyHS53cGkucHJvdG8uUHJvdG9idWZSb3RhdGlvbjJkUgVhbmdsZSJmChlQcm90b2J1",
+ "ZlN3ZXJ2ZU1vZHVsZVN0YXRlEhQKBXNwZWVkGAEgASgBUgVzcGVlZBIzCgVhbmdsZRgCIAEoCzIdLndw" +
+ "aS5wcm90by5Qcm90b2J1ZlJvdGF0aW9uMmRSBWFuZ2xlQhoKGGVkdS53cGkuZmlyc3QubWF0aC5wcm90" +
+ "b0qZDQoGEgQAAD0BCggKAQwSAwAAEgoICgECEgMCABIKCQoCAwASAwQAGgoICgEIEgMGADEKCQoCCAES" +
+ "AwYAMQoKCgIEABIECAAMAQoKCgMEAAESAwgIHQoLCgQEAAIAEgMJAhAKDAoFBAACAAUSAwkCCAoMCgUE" +
+ "AAIAARIDCQkLCgwKBQQAAgADEgMJDg8KCwoEBAACARIDCgIQCgwKBQQAAgEFEgMKAggKDAoFBAACAQES" +
+ "AwoJCwoMCgUEAAIBAxIDCg4PCgsKBAQAAgISAwsCEwoMCgUEAAICBRIDCwIICgwKBQQAAgIBEgMLCQ4K" +
+ "DAoFBAACAgMSAwsREgoKCgIEARIEDgAQAQoKCgMEAQESAw4IKwoLCgQEAQIAEgMPAhkKDAoFBAECAAUS" +
+ "Aw8CCAoMCgUEAQIAARIDDwkUCgwKBQQBAgADEgMPFxgKCgoCBAISBBIAFQEKCgoDBAIBEgMSCCwKCwoE" +
+ "BAICABIDEwISCgwKBQQCAgAFEgMTAggKDAoFBAICAAESAxMJDQoMCgUEAgIAAxIDExARCgsKBAQCAgES" +
+ "AxQCEwoMCgUEAgIBBRIDFAIICgwKBQQCAgEBEgMUCQ4KDAoFBAICAQMSAxQREgoKCgIEAxIEFwAaAQoK" +
+ "CgMEAwESAxcILwoLCgQEAwIAEgMYAhIKDAoFBAMCAAUSAxgCCAoMCgUEAwIAARIDGAkNCgwKBQQDAgAD" +
+ "EgMYEBEKCwoEBAMCARIDGQITCgwKBQQDAgEFEgMZAggKDAoFBAMCAQESAxkJDgoMCgUEAwIBAxIDGRES" +
+ "CgoKAgQEEgQcACEBCgoKAwQEARIDHAgmCgsKBAQEAgASAx0CJwoMCgUEBAIABhIDHQIXCgwKBQQEAgAB" +
+ "EgMdGCIKDAoFBAQCAAMSAx0lJgoLCgQEBAIBEgMeAigKDAoFBAQCAQYSAx4CFwoMCgUEBAIBARIDHhgj" +
+ "CgwKBQQEAgEDEgMeJicKCwoEBAQCAhIDHwImCgwKBQQEAgIGEgMfAhcKDAoFBAQCAgESAx8YIQoMCgUE" +
+ "BAICAxIDHyQlCgsKBAQEAgMSAyACJwoMCgUEBAIDBhIDIAIXCgwKBQQEAgMBEgMgGCIKDAoFBAQCAwMS" +
+ "AyAlJgoKCgIEBRIEIwAoAQoKCgMEBQESAyMIKgoLCgQEBQIAEgMkAhgKDAoFBAUCAAUSAyQCCAoMCgUE" +
+ "BQIAARIDJAkTCgwKBQQFAgADEgMkFhcKCwoEBAUCARIDJQIZCgwKBQQFAgEFEgMlAggKDAoFBAUCAQES" +
+ "AyUJFAoMCgUEBQIBAxIDJRcYCgsKBAQFAgISAyYCFwoMCgUEBQICBRIDJgIICgwKBQQFAgIBEgMmCRIK" +
+ "DAoFBAUCAgMSAyYVFgoLCgQEBQIDEgMnAhgKDAoFBAUCAwUSAycCCAoMCgUEBQIDARIDJwkTCgwKBQQF",
+ "AgMDEgMnFhcKCgoCBAYSBCoALwEKCgoDBAYBEgMqCCcKCwoEBAYCABIDKwIYCgwKBQQGAgAFEgMrAggK" +
+ "DAoFBAYCAAESAysJEwoMCgUEBgIAAxIDKxYXCgsKBAQGAgESAywCGQoMCgUEBgIBBRIDLAIICgwKBQQG" +
+ "AgEBEgMsCRQKDAoFBAYCAQMSAywXGAoLCgQEBgICEgMtAhcKDAoFBAYCAgUSAy0CCAoMCgUEBgICARID" +
+ "LQkSCgwKBQQGAgIDEgMtFRYKCwoEBAYCAxIDLgIYCgwKBQQGAgMFEgMuAggKDAoFBAYCAwESAy4JEwoM" +
+ "CgUEBgIDAxIDLhYXCgoKAgQHEgQxADMBCgoKAwQHARIDMQglCgsKBAQHAgASAzICLQoMCgUEBwIABBID" +
+ "MgIKCgwKBQQHAgAGEgMyCyAKDAoFBAcCAAESAzIhKAoMCgUEBwIAAxIDMissCgoKAgQIEgQ1ADgBCgoK" +
+ "AwQIARIDNQgkCgsKBAQIAgASAzYCFgoMCgUECAIABRIDNgIICgwKBQQIAgABEgM2CREKDAoFBAgCAAMS" +
+ "AzYUFQoLCgQECAIBEgM3Ah8KDAoFBAgCAQYSAzcCFAoMCgUECAIBARIDNxUaCgwKBQQIAgEDEgM3HR4K" +
+ "CgoCBAkSBDoAPQEKCgoDBAkBEgM6CCEKCwoEBAkCABIDOwITCgwKBQQJAgAFEgM7AggKDAoFBAkCAAES" +
+ "AzsJDgoMCgUECQIAAxIDOxESCgsKBAQJAgESAzwCHwoMCgUECQIBBhIDPAIUCgwKBQQJAgEBEgM8FRoK" +
+ "DAoFBAkCAQMSAzwdHmIGcHJvdG8z");
static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("kinematics.proto", "wpi.proto", descriptorData, Geometry2D.getDescriptor());
@@ -91,17 +84,15 @@ public final class Kinematics {
static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveKinematics_descriptor = descriptor.internalContainedType(368, 292, "ProtobufMecanumDriveKinematics", "wpi.proto.ProtobufMecanumDriveKinematics");
- static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveMotorVoltages_descriptor = descriptor.internalContainedType(663, 159, "ProtobufMecanumDriveMotorVoltages", "wpi.proto.ProtobufMecanumDriveMotorVoltages");
+ static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveWheelPositions_descriptor = descriptor.internalContainedType(663, 160, "ProtobufMecanumDriveWheelPositions", "wpi.proto.ProtobufMecanumDriveWheelPositions");
- static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveWheelPositions_descriptor = descriptor.internalContainedType(825, 160, "ProtobufMecanumDriveWheelPositions", "wpi.proto.ProtobufMecanumDriveWheelPositions");
+ static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveWheelSpeeds_descriptor = descriptor.internalContainedType(826, 157, "ProtobufMecanumDriveWheelSpeeds", "wpi.proto.ProtobufMecanumDriveWheelSpeeds");
- static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveWheelSpeeds_descriptor = descriptor.internalContainedType(988, 157, "ProtobufMecanumDriveWheelSpeeds", "wpi.proto.ProtobufMecanumDriveWheelSpeeds");
+ static final Descriptors.Descriptor wpi_proto_ProtobufSwerveDriveKinematics_descriptor = descriptor.internalContainedType(985, 91, "ProtobufSwerveDriveKinematics", "wpi.proto.ProtobufSwerveDriveKinematics");
- static final Descriptors.Descriptor wpi_proto_ProtobufSwerveDriveKinematics_descriptor = descriptor.internalContainedType(1147, 91, "ProtobufSwerveDriveKinematics", "wpi.proto.ProtobufSwerveDriveKinematics");
+ static final Descriptors.Descriptor wpi_proto_ProtobufSwerveModulePosition_descriptor = descriptor.internalContainedType(1078, 111, "ProtobufSwerveModulePosition", "wpi.proto.ProtobufSwerveModulePosition");
- static final Descriptors.Descriptor wpi_proto_ProtobufSwerveModulePosition_descriptor = descriptor.internalContainedType(1240, 111, "ProtobufSwerveModulePosition", "wpi.proto.ProtobufSwerveModulePosition");
-
- static final Descriptors.Descriptor wpi_proto_ProtobufSwerveModuleState_descriptor = descriptor.internalContainedType(1353, 102, "ProtobufSwerveModuleState", "wpi.proto.ProtobufSwerveModuleState");
+ static final Descriptors.Descriptor wpi_proto_ProtobufSwerveModuleState_descriptor = descriptor.internalContainedType(1191, 102, "ProtobufSwerveModuleState", "wpi.proto.ProtobufSwerveModuleState");
/**
* @return this proto file's descriptor.
@@ -2043,506 +2034,6 @@ static class FieldNames {
}
}
- /**
- * Protobuf type {@code ProtobufMecanumDriveMotorVoltages}
- */
- public static final class ProtobufMecanumDriveMotorVoltages extends ProtoMessage implements Cloneable {
- private static final long serialVersionUID = 0L;
-
- /**
- * optional double front_left = 1;
- */
- private double frontLeft;
-
- /**
- * optional double front_right = 2;
- */
- private double frontRight;
-
- /**
- * optional double rear_left = 3;
- */
- private double rearLeft;
-
- /**
- * optional double rear_right = 4;
- */
- private double rearRight;
-
- private ProtobufMecanumDriveMotorVoltages() {
- }
-
- /**
- * @return a new empty instance of {@code ProtobufMecanumDriveMotorVoltages}
- */
- public static ProtobufMecanumDriveMotorVoltages newInstance() {
- return new ProtobufMecanumDriveMotorVoltages();
- }
-
- /**
- * optional double front_left = 1;
- * @return whether the frontLeft field is set
- */
- public boolean hasFrontLeft() {
- return (bitField0_ & 0x00000001) != 0;
- }
-
- /**
- * optional double front_left = 1;
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages clearFrontLeft() {
- bitField0_ &= ~0x00000001;
- frontLeft = 0D;
- return this;
- }
-
- /**
- * optional double front_left = 1;
- * @return the frontLeft
- */
- public double getFrontLeft() {
- return frontLeft;
- }
-
- /**
- * optional double front_left = 1;
- * @param value the frontLeft to set
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages setFrontLeft(final double value) {
- bitField0_ |= 0x00000001;
- frontLeft = value;
- return this;
- }
-
- /**
- * optional double front_right = 2;
- * @return whether the frontRight field is set
- */
- public boolean hasFrontRight() {
- return (bitField0_ & 0x00000002) != 0;
- }
-
- /**
- * optional double front_right = 2;
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages clearFrontRight() {
- bitField0_ &= ~0x00000002;
- frontRight = 0D;
- return this;
- }
-
- /**
- * optional double front_right = 2;
- * @return the frontRight
- */
- public double getFrontRight() {
- return frontRight;
- }
-
- /**
- * optional double front_right = 2;
- * @param value the frontRight to set
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages setFrontRight(final double value) {
- bitField0_ |= 0x00000002;
- frontRight = value;
- return this;
- }
-
- /**
- * optional double rear_left = 3;
- * @return whether the rearLeft field is set
- */
- public boolean hasRearLeft() {
- return (bitField0_ & 0x00000004) != 0;
- }
-
- /**
- * optional double rear_left = 3;
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages clearRearLeft() {
- bitField0_ &= ~0x00000004;
- rearLeft = 0D;
- return this;
- }
-
- /**
- * optional double rear_left = 3;
- * @return the rearLeft
- */
- public double getRearLeft() {
- return rearLeft;
- }
-
- /**
- * optional double rear_left = 3;
- * @param value the rearLeft to set
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages setRearLeft(final double value) {
- bitField0_ |= 0x00000004;
- rearLeft = value;
- return this;
- }
-
- /**
- * optional double rear_right = 4;
- * @return whether the rearRight field is set
- */
- public boolean hasRearRight() {
- return (bitField0_ & 0x00000008) != 0;
- }
-
- /**
- * optional double rear_right = 4;
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages clearRearRight() {
- bitField0_ &= ~0x00000008;
- rearRight = 0D;
- return this;
- }
-
- /**
- * optional double rear_right = 4;
- * @return the rearRight
- */
- public double getRearRight() {
- return rearRight;
- }
-
- /**
- * optional double rear_right = 4;
- * @param value the rearRight to set
- * @return this
- */
- public ProtobufMecanumDriveMotorVoltages setRearRight(final double value) {
- bitField0_ |= 0x00000008;
- rearRight = value;
- return this;
- }
-
- @Override
- public ProtobufMecanumDriveMotorVoltages copyFrom(
- final ProtobufMecanumDriveMotorVoltages other) {
- cachedSize = other.cachedSize;
- if ((bitField0_ | other.bitField0_) != 0) {
- bitField0_ = other.bitField0_;
- frontLeft = other.frontLeft;
- frontRight = other.frontRight;
- rearLeft = other.rearLeft;
- rearRight = other.rearRight;
- }
- return this;
- }
-
- @Override
- public ProtobufMecanumDriveMotorVoltages mergeFrom(
- final ProtobufMecanumDriveMotorVoltages other) {
- if (other.isEmpty()) {
- return this;
- }
- cachedSize = -1;
- if (other.hasFrontLeft()) {
- setFrontLeft(other.frontLeft);
- }
- if (other.hasFrontRight()) {
- setFrontRight(other.frontRight);
- }
- if (other.hasRearLeft()) {
- setRearLeft(other.rearLeft);
- }
- if (other.hasRearRight()) {
- setRearRight(other.rearRight);
- }
- return this;
- }
-
- @Override
- public ProtobufMecanumDriveMotorVoltages clear() {
- if (isEmpty()) {
- return this;
- }
- cachedSize = -1;
- bitField0_ = 0;
- frontLeft = 0D;
- frontRight = 0D;
- rearLeft = 0D;
- rearRight = 0D;
- return this;
- }
-
- @Override
- public ProtobufMecanumDriveMotorVoltages clearQuick() {
- if (isEmpty()) {
- return this;
- }
- cachedSize = -1;
- bitField0_ = 0;
- return this;
- }
-
- @Override
- public boolean equals(Object o) {
- if (o == this) {
- return true;
- }
- if (!(o instanceof ProtobufMecanumDriveMotorVoltages)) {
- return false;
- }
- ProtobufMecanumDriveMotorVoltages other = (ProtobufMecanumDriveMotorVoltages) o;
- return bitField0_ == other.bitField0_
- && (!hasFrontLeft() || ProtoUtil.isEqual(frontLeft, other.frontLeft))
- && (!hasFrontRight() || ProtoUtil.isEqual(frontRight, other.frontRight))
- && (!hasRearLeft() || ProtoUtil.isEqual(rearLeft, other.rearLeft))
- && (!hasRearRight() || ProtoUtil.isEqual(rearRight, other.rearRight));
- }
-
- @Override
- public void writeTo(final ProtoSink output) throws IOException {
- if ((bitField0_ & 0x00000001) != 0) {
- output.writeRawByte((byte) 9);
- output.writeDoubleNoTag(frontLeft);
- }
- if ((bitField0_ & 0x00000002) != 0) {
- output.writeRawByte((byte) 17);
- output.writeDoubleNoTag(frontRight);
- }
- if ((bitField0_ & 0x00000004) != 0) {
- output.writeRawByte((byte) 25);
- output.writeDoubleNoTag(rearLeft);
- }
- if ((bitField0_ & 0x00000008) != 0) {
- output.writeRawByte((byte) 33);
- output.writeDoubleNoTag(rearRight);
- }
- }
-
- @Override
- protected int computeSerializedSize() {
- int size = 0;
- if ((bitField0_ & 0x00000001) != 0) {
- size += 9;
- }
- if ((bitField0_ & 0x00000002) != 0) {
- size += 9;
- }
- if ((bitField0_ & 0x00000004) != 0) {
- size += 9;
- }
- if ((bitField0_ & 0x00000008) != 0) {
- size += 9;
- }
- return size;
- }
-
- @Override
- @SuppressWarnings("fallthrough")
- public ProtobufMecanumDriveMotorVoltages mergeFrom(final ProtoSource input) throws IOException {
- // Enabled Fall-Through Optimization (QuickBuffers)
- int tag = input.readTag();
- while (true) {
- switch (tag) {
- case 9: {
- // frontLeft
- frontLeft = input.readDouble();
- bitField0_ |= 0x00000001;
- tag = input.readTag();
- if (tag != 17) {
- break;
- }
- }
- case 17: {
- // frontRight
- frontRight = input.readDouble();
- bitField0_ |= 0x00000002;
- tag = input.readTag();
- if (tag != 25) {
- break;
- }
- }
- case 25: {
- // rearLeft
- rearLeft = input.readDouble();
- bitField0_ |= 0x00000004;
- tag = input.readTag();
- if (tag != 33) {
- break;
- }
- }
- case 33: {
- // rearRight
- rearRight = input.readDouble();
- bitField0_ |= 0x00000008;
- tag = input.readTag();
- if (tag != 0) {
- break;
- }
- }
- case 0: {
- return this;
- }
- default: {
- if (!input.skipField(tag)) {
- return this;
- }
- tag = input.readTag();
- break;
- }
- }
- }
- }
-
- @Override
- public void writeTo(final JsonSink output) throws IOException {
- output.beginObject();
- if ((bitField0_ & 0x00000001) != 0) {
- output.writeDouble(FieldNames.frontLeft, frontLeft);
- }
- if ((bitField0_ & 0x00000002) != 0) {
- output.writeDouble(FieldNames.frontRight, frontRight);
- }
- if ((bitField0_ & 0x00000004) != 0) {
- output.writeDouble(FieldNames.rearLeft, rearLeft);
- }
- if ((bitField0_ & 0x00000008) != 0) {
- output.writeDouble(FieldNames.rearRight, rearRight);
- }
- output.endObject();
- }
-
- @Override
- public ProtobufMecanumDriveMotorVoltages mergeFrom(final JsonSource input) throws IOException {
- if (!input.beginObject()) {
- return this;
- }
- while (!input.isAtEnd()) {
- switch (input.readFieldHash()) {
- case 127514064:
- case -324277155: {
- if (input.isAtField(FieldNames.frontLeft)) {
- if (!input.trySkipNullValue()) {
- frontLeft = input.readDouble();
- bitField0_ |= 0x00000001;
- }
- } else {
- input.skipUnknownField();
- }
- break;
- }
- case -336370317:
- case -1456996218: {
- if (input.isAtField(FieldNames.frontRight)) {
- if (!input.trySkipNullValue()) {
- frontRight = input.readDouble();
- bitField0_ |= 0x00000002;
- }
- } else {
- input.skipUnknownField();
- }
- break;
- }
- case -854852661:
- case -712874558: {
- if (input.isAtField(FieldNames.rearLeft)) {
- if (!input.trySkipNullValue()) {
- rearLeft = input.readDouble();
- bitField0_ |= 0x00000004;
- }
- } else {
- input.skipUnknownField();
- }
- break;
- }
- case -724967720:
- case -618613823: {
- if (input.isAtField(FieldNames.rearRight)) {
- if (!input.trySkipNullValue()) {
- rearRight = input.readDouble();
- bitField0_ |= 0x00000008;
- }
- } else {
- input.skipUnknownField();
- }
- break;
- }
- default: {
- input.skipUnknownField();
- break;
- }
- }
- }
- input.endObject();
- return this;
- }
-
- @Override
- public ProtobufMecanumDriveMotorVoltages clone() {
- return new ProtobufMecanumDriveMotorVoltages().copyFrom(this);
- }
-
- @Override
- public boolean isEmpty() {
- return ((bitField0_) == 0);
- }
-
- public static ProtobufMecanumDriveMotorVoltages parseFrom(final byte[] data) throws
- InvalidProtocolBufferException {
- return ProtoMessage.mergeFrom(new ProtobufMecanumDriveMotorVoltages(), data).checkInitialized();
- }
-
- public static ProtobufMecanumDriveMotorVoltages parseFrom(final ProtoSource input) throws
- IOException {
- return ProtoMessage.mergeFrom(new ProtobufMecanumDriveMotorVoltages(), input).checkInitialized();
- }
-
- public static ProtobufMecanumDriveMotorVoltages parseFrom(final JsonSource input) throws
- IOException {
- return ProtoMessage.mergeFrom(new ProtobufMecanumDriveMotorVoltages(), input).checkInitialized();
- }
-
- /**
- * @return factory for creating ProtobufMecanumDriveMotorVoltages messages
- */
- public static MessageFactory getFactory() {
- return ProtobufMecanumDriveMotorVoltagesFactory.INSTANCE;
- }
-
- /**
- * @return this type's descriptor.
- */
- public static Descriptors.Descriptor getDescriptor() {
- return Kinematics.wpi_proto_ProtobufMecanumDriveMotorVoltages_descriptor;
- }
-
- private enum ProtobufMecanumDriveMotorVoltagesFactory implements MessageFactory {
- INSTANCE;
-
- @Override
- public ProtobufMecanumDriveMotorVoltages create() {
- return ProtobufMecanumDriveMotorVoltages.newInstance();
- }
- }
-
- /**
- * Contains name constants used for serializing JSON
- */
- static class FieldNames {
- static final FieldName frontLeft = FieldName.forField("frontLeft", "front_left");
-
- static final FieldName frontRight = FieldName.forField("frontRight", "front_right");
-
- static final FieldName rearLeft = FieldName.forField("rearLeft", "rear_left");
-
- static final FieldName rearRight = FieldName.forField("rearRight", "rear_right");
- }
- }
-
/**
* Protobuf type {@code ProtobufMecanumDriveWheelPositions}
*/
diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp
index 65087413758..ad404212b9c 100644
--- a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp
+++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp
@@ -78,283 +78,243 @@ static const uint8_t file_descriptor[] {
0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61,0x6e,
0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64,0x52,
0x09,0x72,0x65,0x61,0x72,0x52,0x69,0x67,0x68,0x74,
-0x22,0x9f,0x01,0x0a,0x21,0x50,0x72,0x6f,0x74,0x6f,
+0x22,0xa0,0x01,0x0a,0x22,0x50,0x72,0x6f,0x74,0x6f,
0x62,0x75,0x66,0x4d,0x65,0x63,0x61,0x6e,0x75,0x6d,
-0x44,0x72,0x69,0x76,0x65,0x4d,0x6f,0x74,0x6f,0x72,
-0x56,0x6f,0x6c,0x74,0x61,0x67,0x65,0x73,0x12,0x1d,
-0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x5f,0x6c,0x65,
-0x66,0x74,0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x09,
-0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65,0x66,0x74,0x12,
-0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e,0x74,0x5f,0x72,
-0x69,0x67,0x68,0x74,0x18,0x02,0x20,0x01,0x28,0x01,
-0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x52,0x69,0x67,
-0x68,0x74,0x12,0x1b,0x0a,0x09,0x72,0x65,0x61,0x72,
-0x5f,0x6c,0x65,0x66,0x74,0x18,0x03,0x20,0x01,0x28,
-0x01,0x52,0x08,0x72,0x65,0x61,0x72,0x4c,0x65,0x66,
-0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65,0x61,0x72,0x5f,
-0x72,0x69,0x67,0x68,0x74,0x18,0x04,0x20,0x01,0x28,
-0x01,0x52,0x09,0x72,0x65,0x61,0x72,0x52,0x69,0x67,
-0x68,0x74,0x22,0xa0,0x01,0x0a,0x22,0x50,0x72,0x6f,
-0x74,0x6f,0x62,0x75,0x66,0x4d,0x65,0x63,0x61,0x6e,
-0x75,0x6d,0x44,0x72,0x69,0x76,0x65,0x57,0x68,0x65,
-0x65,0x6c,0x50,0x6f,0x73,0x69,0x74,0x69,0x6f,0x6e,
-0x73,0x12,0x1d,0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74,
-0x5f,0x6c,0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28,
-0x01,0x52,0x09,0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65,
-0x66,0x74,0x12,0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e,
-0x74,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20,
-0x01,0x28,0x01,0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74,
-0x52,0x69,0x67,0x68,0x74,0x12,0x1b,0x0a,0x09,0x72,
-0x65,0x61,0x72,0x5f,0x6c,0x65,0x66,0x74,0x18,0x03,
-0x20,0x01,0x28,0x01,0x52,0x08,0x72,0x65,0x61,0x72,
-0x4c,0x65,0x66,0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65,
-0x61,0x72,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x04,
-0x20,0x01,0x28,0x01,0x52,0x09,0x72,0x65,0x61,0x72,
-0x52,0x69,0x67,0x68,0x74,0x22,0x9d,0x01,0x0a,0x1f,
-0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x4d,0x65,
-0x63,0x61,0x6e,0x75,0x6d,0x44,0x72,0x69,0x76,0x65,
-0x57,0x68,0x65,0x65,0x6c,0x53,0x70,0x65,0x65,0x64,
-0x73,0x12,0x1d,0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74,
-0x5f,0x6c,0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28,
-0x01,0x52,0x09,0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65,
-0x66,0x74,0x12,0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e,
-0x74,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20,
-0x01,0x28,0x01,0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74,
-0x52,0x69,0x67,0x68,0x74,0x12,0x1b,0x0a,0x09,0x72,
-0x65,0x61,0x72,0x5f,0x6c,0x65,0x66,0x74,0x18,0x03,
-0x20,0x01,0x28,0x01,0x52,0x08,0x72,0x65,0x61,0x72,
-0x4c,0x65,0x66,0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65,
-0x61,0x72,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x04,
-0x20,0x01,0x28,0x01,0x52,0x09,0x72,0x65,0x61,0x72,
-0x52,0x69,0x67,0x68,0x74,0x22,0x5b,0x0a,0x1d,0x50,
-0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x53,0x77,0x65,
-0x72,0x76,0x65,0x44,0x72,0x69,0x76,0x65,0x4b,0x69,
-0x6e,0x65,0x6d,0x61,0x74,0x69,0x63,0x73,0x12,0x3a,
-0x0a,0x07,0x6d,0x6f,0x64,0x75,0x6c,0x65,0x73,0x18,
-0x01,0x20,0x03,0x28,0x0b,0x32,0x20,0x2e,0x77,0x70,
-0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,
-0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61,0x6e,
-0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64,0x52,
-0x07,0x6d,0x6f,0x64,0x75,0x6c,0x65,0x73,0x22,0x6f,
-0x0a,0x1c,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,
-0x53,0x77,0x65,0x72,0x76,0x65,0x4d,0x6f,0x64,0x75,
-0x6c,0x65,0x50,0x6f,0x73,0x69,0x74,0x69,0x6f,0x6e,
-0x12,0x1a,0x0a,0x08,0x64,0x69,0x73,0x74,0x61,0x6e,
-0x63,0x65,0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x08,
-0x64,0x69,0x73,0x74,0x61,0x6e,0x63,0x65,0x12,0x33,
-0x0a,0x05,0x61,0x6e,0x67,0x6c,0x65,0x18,0x02,0x20,
-0x01,0x28,0x0b,0x32,0x1d,0x2e,0x77,0x70,0x69,0x2e,
+0x44,0x72,0x69,0x76,0x65,0x57,0x68,0x65,0x65,0x6c,
+0x50,0x6f,0x73,0x69,0x74,0x69,0x6f,0x6e,0x73,0x12,
+0x1d,0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x5f,0x6c,
+0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28,0x01,0x52,
+0x09,0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65,0x66,0x74,
+0x12,0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e,0x74,0x5f,
+0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20,0x01,0x28,
+0x01,0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x52,0x69,
+0x67,0x68,0x74,0x12,0x1b,0x0a,0x09,0x72,0x65,0x61,
+0x72,0x5f,0x6c,0x65,0x66,0x74,0x18,0x03,0x20,0x01,
+0x28,0x01,0x52,0x08,0x72,0x65,0x61,0x72,0x4c,0x65,
+0x66,0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65,0x61,0x72,
+0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x04,0x20,0x01,
+0x28,0x01,0x52,0x09,0x72,0x65,0x61,0x72,0x52,0x69,
+0x67,0x68,0x74,0x22,0x9d,0x01,0x0a,0x1f,0x50,0x72,
+0x6f,0x74,0x6f,0x62,0x75,0x66,0x4d,0x65,0x63,0x61,
+0x6e,0x75,0x6d,0x44,0x72,0x69,0x76,0x65,0x57,0x68,
+0x65,0x65,0x6c,0x53,0x70,0x65,0x65,0x64,0x73,0x12,
+0x1d,0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x5f,0x6c,
+0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28,0x01,0x52,
+0x09,0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65,0x66,0x74,
+0x12,0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e,0x74,0x5f,
+0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20,0x01,0x28,
+0x01,0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x52,0x69,
+0x67,0x68,0x74,0x12,0x1b,0x0a,0x09,0x72,0x65,0x61,
+0x72,0x5f,0x6c,0x65,0x66,0x74,0x18,0x03,0x20,0x01,
+0x28,0x01,0x52,0x08,0x72,0x65,0x61,0x72,0x4c,0x65,
+0x66,0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65,0x61,0x72,
+0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x04,0x20,0x01,
+0x28,0x01,0x52,0x09,0x72,0x65,0x61,0x72,0x52,0x69,
+0x67,0x68,0x74,0x22,0x5b,0x0a,0x1d,0x50,0x72,0x6f,
+0x74,0x6f,0x62,0x75,0x66,0x53,0x77,0x65,0x72,0x76,
+0x65,0x44,0x72,0x69,0x76,0x65,0x4b,0x69,0x6e,0x65,
+0x6d,0x61,0x74,0x69,0x63,0x73,0x12,0x3a,0x0a,0x07,
+0x6d,0x6f,0x64,0x75,0x6c,0x65,0x73,0x18,0x01,0x20,
+0x03,0x28,0x0b,0x32,0x20,0x2e,0x77,0x70,0x69,0x2e,
0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,
-0x6f,0x62,0x75,0x66,0x52,0x6f,0x74,0x61,0x74,0x69,
-0x6f,0x6e,0x32,0x64,0x52,0x05,0x61,0x6e,0x67,0x6c,
-0x65,0x22,0x66,0x0a,0x19,0x50,0x72,0x6f,0x74,0x6f,
-0x62,0x75,0x66,0x53,0x77,0x65,0x72,0x76,0x65,0x4d,
-0x6f,0x64,0x75,0x6c,0x65,0x53,0x74,0x61,0x74,0x65,
-0x12,0x14,0x0a,0x05,0x73,0x70,0x65,0x65,0x64,0x18,
-0x01,0x20,0x01,0x28,0x01,0x52,0x05,0x73,0x70,0x65,
-0x65,0x64,0x12,0x33,0x0a,0x05,0x61,0x6e,0x67,0x6c,
-0x65,0x18,0x02,0x20,0x01,0x28,0x0b,0x32,0x1d,0x2e,
-0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,
-0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x52,0x6f,
-0x74,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64,0x52,0x05,
-0x61,0x6e,0x67,0x6c,0x65,0x42,0x1a,0x0a,0x18,0x65,
-0x64,0x75,0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72,
-0x73,0x74,0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72,
-0x6f,0x74,0x6f,0x4a,0x8d,0x0f,0x0a,0x06,0x12,0x04,
-0x00,0x00,0x44,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12,
-0x03,0x00,0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12,
-0x03,0x02,0x00,0x12,0x0a,0x09,0x0a,0x02,0x03,0x00,
-0x12,0x03,0x04,0x00,0x1a,0x0a,0x08,0x0a,0x01,0x08,
-0x12,0x03,0x06,0x00,0x31,0x0a,0x09,0x0a,0x02,0x08,
-0x01,0x12,0x03,0x06,0x00,0x31,0x0a,0x0a,0x0a,0x02,
-0x04,0x00,0x12,0x04,0x08,0x00,0x0c,0x01,0x0a,0x0a,
-0x0a,0x03,0x04,0x00,0x01,0x12,0x03,0x08,0x08,0x1d,
-0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x00,0x12,0x03,
-0x09,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,
-0x00,0x05,0x12,0x03,0x09,0x02,0x08,0x0a,0x0c,0x0a,
-0x05,0x04,0x00,0x02,0x00,0x01,0x12,0x03,0x09,0x09,
-0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x03,
-0x12,0x03,0x09,0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,
-0x00,0x02,0x01,0x12,0x03,0x0a,0x02,0x10,0x0a,0x0c,
-0x0a,0x05,0x04,0x00,0x02,0x01,0x05,0x12,0x03,0x0a,
-0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,
-0x01,0x12,0x03,0x0a,0x09,0x0b,0x0a,0x0c,0x0a,0x05,
-0x04,0x00,0x02,0x01,0x03,0x12,0x03,0x0a,0x0e,0x0f,
-0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x02,0x12,0x03,
-0x0b,0x02,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,
-0x02,0x05,0x12,0x03,0x0b,0x02,0x08,0x0a,0x0c,0x0a,
-0x05,0x04,0x00,0x02,0x02,0x01,0x12,0x03,0x0b,0x09,
-0x0e,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x03,
-0x12,0x03,0x0b,0x11,0x12,0x0a,0x0a,0x0a,0x02,0x04,
-0x01,0x12,0x04,0x0e,0x00,0x10,0x01,0x0a,0x0a,0x0a,
-0x03,0x04,0x01,0x01,0x12,0x03,0x0e,0x08,0x2b,0x0a,
-0x0b,0x0a,0x04,0x04,0x01,0x02,0x00,0x12,0x03,0x0f,
-0x02,0x19,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,
-0x05,0x12,0x03,0x0f,0x02,0x08,0x0a,0x0c,0x0a,0x05,
-0x04,0x01,0x02,0x00,0x01,0x12,0x03,0x0f,0x09,0x14,
-0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x03,0x12,
-0x03,0x0f,0x17,0x18,0x0a,0x0a,0x0a,0x02,0x04,0x02,
-0x12,0x04,0x12,0x00,0x15,0x01,0x0a,0x0a,0x0a,0x03,
-0x04,0x02,0x01,0x12,0x03,0x12,0x08,0x2c,0x0a,0x0b,
-0x0a,0x04,0x04,0x02,0x02,0x00,0x12,0x03,0x13,0x02,
-0x12,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x05,
-0x12,0x03,0x13,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,
-0x02,0x02,0x00,0x01,0x12,0x03,0x13,0x09,0x0d,0x0a,
-0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x03,0x12,0x03,
-0x13,0x10,0x11,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,
-0x01,0x12,0x03,0x14,0x02,0x13,0x0a,0x0c,0x0a,0x05,
-0x04,0x02,0x02,0x01,0x05,0x12,0x03,0x14,0x02,0x08,
-0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x01,0x01,0x12,
-0x03,0x14,0x09,0x0e,0x0a,0x0c,0x0a,0x05,0x04,0x02,
-0x02,0x01,0x03,0x12,0x03,0x14,0x11,0x12,0x0a,0x0a,
-0x0a,0x02,0x04,0x03,0x12,0x04,0x17,0x00,0x1a,0x01,
-0x0a,0x0a,0x0a,0x03,0x04,0x03,0x01,0x12,0x03,0x17,
-0x08,0x2f,0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x00,
-0x12,0x03,0x18,0x02,0x12,0x0a,0x0c,0x0a,0x05,0x04,
-0x03,0x02,0x00,0x05,0x12,0x03,0x18,0x02,0x08,0x0a,
-0x0c,0x0a,0x05,0x04,0x03,0x02,0x00,0x01,0x12,0x03,
-0x18,0x09,0x0d,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,
-0x00,0x03,0x12,0x03,0x18,0x10,0x11,0x0a,0x0b,0x0a,
-0x04,0x04,0x03,0x02,0x01,0x12,0x03,0x19,0x02,0x13,
-0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01,0x05,0x12,
-0x03,0x19,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x03,
-0x02,0x01,0x01,0x12,0x03,0x19,0x09,0x0e,0x0a,0x0c,
-0x0a,0x05,0x04,0x03,0x02,0x01,0x03,0x12,0x03,0x19,
-0x11,0x12,0x0a,0x0a,0x0a,0x02,0x04,0x04,0x12,0x04,
-0x1c,0x00,0x21,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x04,
-0x01,0x12,0x03,0x1c,0x08,0x26,0x0a,0x0b,0x0a,0x04,
-0x04,0x04,0x02,0x00,0x12,0x03,0x1d,0x02,0x27,0x0a,
-0x0c,0x0a,0x05,0x04,0x04,0x02,0x00,0x06,0x12,0x03,
-0x1d,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,
-0x00,0x01,0x12,0x03,0x1d,0x18,0x22,0x0a,0x0c,0x0a,
-0x05,0x04,0x04,0x02,0x00,0x03,0x12,0x03,0x1d,0x25,
-0x26,0x0a,0x0b,0x0a,0x04,0x04,0x04,0x02,0x01,0x12,
-0x03,0x1e,0x02,0x28,0x0a,0x0c,0x0a,0x05,0x04,0x04,
-0x02,0x01,0x06,0x12,0x03,0x1e,0x02,0x17,0x0a,0x0c,
-0x0a,0x05,0x04,0x04,0x02,0x01,0x01,0x12,0x03,0x1e,
-0x18,0x23,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x01,
-0x03,0x12,0x03,0x1e,0x26,0x27,0x0a,0x0b,0x0a,0x04,
-0x04,0x04,0x02,0x02,0x12,0x03,0x1f,0x02,0x26,0x0a,
-0x0c,0x0a,0x05,0x04,0x04,0x02,0x02,0x06,0x12,0x03,
-0x1f,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,
-0x02,0x01,0x12,0x03,0x1f,0x18,0x21,0x0a,0x0c,0x0a,
-0x05,0x04,0x04,0x02,0x02,0x03,0x12,0x03,0x1f,0x24,
-0x25,0x0a,0x0b,0x0a,0x04,0x04,0x04,0x02,0x03,0x12,
-0x03,0x20,0x02,0x27,0x0a,0x0c,0x0a,0x05,0x04,0x04,
-0x02,0x03,0x06,0x12,0x03,0x20,0x02,0x17,0x0a,0x0c,
-0x0a,0x05,0x04,0x04,0x02,0x03,0x01,0x12,0x03,0x20,
-0x18,0x22,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x03,
-0x03,0x12,0x03,0x20,0x25,0x26,0x0a,0x0a,0x0a,0x02,
-0x04,0x05,0x12,0x04,0x23,0x00,0x28,0x01,0x0a,0x0a,
-0x0a,0x03,0x04,0x05,0x01,0x12,0x03,0x23,0x08,0x29,
-0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x00,0x12,0x03,
-0x24,0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,
-0x00,0x05,0x12,0x03,0x24,0x02,0x08,0x0a,0x0c,0x0a,
-0x05,0x04,0x05,0x02,0x00,0x01,0x12,0x03,0x24,0x09,
-0x13,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x00,0x03,
-0x12,0x03,0x24,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,
-0x05,0x02,0x01,0x12,0x03,0x25,0x02,0x19,0x0a,0x0c,
-0x0a,0x05,0x04,0x05,0x02,0x01,0x05,0x12,0x03,0x25,
-0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x01,
-0x01,0x12,0x03,0x25,0x09,0x14,0x0a,0x0c,0x0a,0x05,
-0x04,0x05,0x02,0x01,0x03,0x12,0x03,0x25,0x17,0x18,
-0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x02,0x12,0x03,
-0x26,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,
-0x02,0x05,0x12,0x03,0x26,0x02,0x08,0x0a,0x0c,0x0a,
-0x05,0x04,0x05,0x02,0x02,0x01,0x12,0x03,0x26,0x09,
-0x12,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x02,0x03,
-0x12,0x03,0x26,0x15,0x16,0x0a,0x0b,0x0a,0x04,0x04,
-0x05,0x02,0x03,0x12,0x03,0x27,0x02,0x18,0x0a,0x0c,
-0x0a,0x05,0x04,0x05,0x02,0x03,0x05,0x12,0x03,0x27,
-0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x03,
-0x01,0x12,0x03,0x27,0x09,0x13,0x0a,0x0c,0x0a,0x05,
-0x04,0x05,0x02,0x03,0x03,0x12,0x03,0x27,0x16,0x17,
-0x0a,0x0a,0x0a,0x02,0x04,0x06,0x12,0x04,0x2a,0x00,
-0x2f,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x06,0x01,0x12,
-0x03,0x2a,0x08,0x2a,0x0a,0x0b,0x0a,0x04,0x04,0x06,
-0x02,0x00,0x12,0x03,0x2b,0x02,0x18,0x0a,0x0c,0x0a,
-0x05,0x04,0x06,0x02,0x00,0x05,0x12,0x03,0x2b,0x02,
-0x08,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x00,0x01,
-0x12,0x03,0x2b,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04,
-0x06,0x02,0x00,0x03,0x12,0x03,0x2b,0x16,0x17,0x0a,
-0x0b,0x0a,0x04,0x04,0x06,0x02,0x01,0x12,0x03,0x2c,
-0x02,0x19,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x01,
-0x05,0x12,0x03,0x2c,0x02,0x08,0x0a,0x0c,0x0a,0x05,
-0x04,0x06,0x02,0x01,0x01,0x12,0x03,0x2c,0x09,0x14,
-0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x01,0x03,0x12,
-0x03,0x2c,0x17,0x18,0x0a,0x0b,0x0a,0x04,0x04,0x06,
-0x02,0x02,0x12,0x03,0x2d,0x02,0x17,0x0a,0x0c,0x0a,
-0x05,0x04,0x06,0x02,0x02,0x05,0x12,0x03,0x2d,0x02,
-0x08,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x02,0x01,
-0x12,0x03,0x2d,0x09,0x12,0x0a,0x0c,0x0a,0x05,0x04,
-0x06,0x02,0x02,0x03,0x12,0x03,0x2d,0x15,0x16,0x0a,
-0x0b,0x0a,0x04,0x04,0x06,0x02,0x03,0x12,0x03,0x2e,
-0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x03,
-0x05,0x12,0x03,0x2e,0x02,0x08,0x0a,0x0c,0x0a,0x05,
-0x04,0x06,0x02,0x03,0x01,0x12,0x03,0x2e,0x09,0x13,
-0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x03,0x03,0x12,
-0x03,0x2e,0x16,0x17,0x0a,0x0a,0x0a,0x02,0x04,0x07,
-0x12,0x04,0x31,0x00,0x36,0x01,0x0a,0x0a,0x0a,0x03,
-0x04,0x07,0x01,0x12,0x03,0x31,0x08,0x27,0x0a,0x0b,
-0x0a,0x04,0x04,0x07,0x02,0x00,0x12,0x03,0x32,0x02,
-0x18,0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x00,0x05,
-0x12,0x03,0x32,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,
-0x07,0x02,0x00,0x01,0x12,0x03,0x32,0x09,0x13,0x0a,
-0x0c,0x0a,0x05,0x04,0x07,0x02,0x00,0x03,0x12,0x03,
-0x32,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,0x07,0x02,
-0x01,0x12,0x03,0x33,0x02,0x19,0x0a,0x0c,0x0a,0x05,
-0x04,0x07,0x02,0x01,0x05,0x12,0x03,0x33,0x02,0x08,
-0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x01,0x01,0x12,
-0x03,0x33,0x09,0x14,0x0a,0x0c,0x0a,0x05,0x04,0x07,
-0x02,0x01,0x03,0x12,0x03,0x33,0x17,0x18,0x0a,0x0b,
-0x0a,0x04,0x04,0x07,0x02,0x02,0x12,0x03,0x34,0x02,
-0x17,0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x02,0x05,
-0x12,0x03,0x34,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,
-0x07,0x02,0x02,0x01,0x12,0x03,0x34,0x09,0x12,0x0a,
-0x0c,0x0a,0x05,0x04,0x07,0x02,0x02,0x03,0x12,0x03,
-0x34,0x15,0x16,0x0a,0x0b,0x0a,0x04,0x04,0x07,0x02,
-0x03,0x12,0x03,0x35,0x02,0x18,0x0a,0x0c,0x0a,0x05,
-0x04,0x07,0x02,0x03,0x05,0x12,0x03,0x35,0x02,0x08,
-0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x03,0x01,0x12,
-0x03,0x35,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x07,
-0x02,0x03,0x03,0x12,0x03,0x35,0x16,0x17,0x0a,0x0a,
-0x0a,0x02,0x04,0x08,0x12,0x04,0x38,0x00,0x3a,0x01,
-0x0a,0x0a,0x0a,0x03,0x04,0x08,0x01,0x12,0x03,0x38,
-0x08,0x25,0x0a,0x0b,0x0a,0x04,0x04,0x08,0x02,0x00,
-0x12,0x03,0x39,0x02,0x2d,0x0a,0x0c,0x0a,0x05,0x04,
-0x08,0x02,0x00,0x04,0x12,0x03,0x39,0x02,0x0a,0x0a,
-0x0c,0x0a,0x05,0x04,0x08,0x02,0x00,0x06,0x12,0x03,
-0x39,0x0b,0x20,0x0a,0x0c,0x0a,0x05,0x04,0x08,0x02,
-0x00,0x01,0x12,0x03,0x39,0x21,0x28,0x0a,0x0c,0x0a,
-0x05,0x04,0x08,0x02,0x00,0x03,0x12,0x03,0x39,0x2b,
-0x2c,0x0a,0x0a,0x0a,0x02,0x04,0x09,0x12,0x04,0x3c,
-0x00,0x3f,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x09,0x01,
-0x12,0x03,0x3c,0x08,0x24,0x0a,0x0b,0x0a,0x04,0x04,
-0x09,0x02,0x00,0x12,0x03,0x3d,0x02,0x16,0x0a,0x0c,
-0x0a,0x05,0x04,0x09,0x02,0x00,0x05,0x12,0x03,0x3d,
-0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02,0x00,
-0x01,0x12,0x03,0x3d,0x09,0x11,0x0a,0x0c,0x0a,0x05,
-0x04,0x09,0x02,0x00,0x03,0x12,0x03,0x3d,0x14,0x15,
-0x0a,0x0b,0x0a,0x04,0x04,0x09,0x02,0x01,0x12,0x03,
-0x3e,0x02,0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02,
-0x01,0x06,0x12,0x03,0x3e,0x02,0x14,0x0a,0x0c,0x0a,
-0x05,0x04,0x09,0x02,0x01,0x01,0x12,0x03,0x3e,0x15,
-0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02,0x01,0x03,
-0x12,0x03,0x3e,0x1d,0x1e,0x0a,0x0a,0x0a,0x02,0x04,
-0x0a,0x12,0x04,0x41,0x00,0x44,0x01,0x0a,0x0a,0x0a,
-0x03,0x04,0x0a,0x01,0x12,0x03,0x41,0x08,0x21,0x0a,
-0x0b,0x0a,0x04,0x04,0x0a,0x02,0x00,0x12,0x03,0x42,
-0x02,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x0a,0x02,0x00,
-0x05,0x12,0x03,0x42,0x02,0x08,0x0a,0x0c,0x0a,0x05,
-0x04,0x0a,0x02,0x00,0x01,0x12,0x03,0x42,0x09,0x0e,
-0x0a,0x0c,0x0a,0x05,0x04,0x0a,0x02,0x00,0x03,0x12,
-0x03,0x42,0x11,0x12,0x0a,0x0b,0x0a,0x04,0x04,0x0a,
-0x02,0x01,0x12,0x03,0x43,0x02,0x1f,0x0a,0x0c,0x0a,
-0x05,0x04,0x0a,0x02,0x01,0x06,0x12,0x03,0x43,0x02,
-0x14,0x0a,0x0c,0x0a,0x05,0x04,0x0a,0x02,0x01,0x01,
-0x12,0x03,0x43,0x15,0x1a,0x0a,0x0c,0x0a,0x05,0x04,
-0x0a,0x02,0x01,0x03,0x12,0x03,0x43,0x1d,0x1e,0x62,
-0x06,0x70,0x72,0x6f,0x74,0x6f,0x33,
+0x6f,0x62,0x75,0x66,0x54,0x72,0x61,0x6e,0x73,0x6c,
+0x61,0x74,0x69,0x6f,0x6e,0x32,0x64,0x52,0x07,0x6d,
+0x6f,0x64,0x75,0x6c,0x65,0x73,0x22,0x6f,0x0a,0x1c,
+0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x53,0x77,
+0x65,0x72,0x76,0x65,0x4d,0x6f,0x64,0x75,0x6c,0x65,
+0x50,0x6f,0x73,0x69,0x74,0x69,0x6f,0x6e,0x12,0x1a,
+0x0a,0x08,0x64,0x69,0x73,0x74,0x61,0x6e,0x63,0x65,
+0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x08,0x64,0x69,
+0x73,0x74,0x61,0x6e,0x63,0x65,0x12,0x33,0x0a,0x05,
+0x61,0x6e,0x67,0x6c,0x65,0x18,0x02,0x20,0x01,0x28,
+0x0b,0x32,0x1d,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72,
+0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f,0x62,
+0x75,0x66,0x52,0x6f,0x74,0x61,0x74,0x69,0x6f,0x6e,
+0x32,0x64,0x52,0x05,0x61,0x6e,0x67,0x6c,0x65,0x22,
+0x66,0x0a,0x19,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,
+0x66,0x53,0x77,0x65,0x72,0x76,0x65,0x4d,0x6f,0x64,
+0x75,0x6c,0x65,0x53,0x74,0x61,0x74,0x65,0x12,0x14,
+0x0a,0x05,0x73,0x70,0x65,0x65,0x64,0x18,0x01,0x20,
+0x01,0x28,0x01,0x52,0x05,0x73,0x70,0x65,0x65,0x64,
+0x12,0x33,0x0a,0x05,0x61,0x6e,0x67,0x6c,0x65,0x18,
+0x02,0x20,0x01,0x28,0x0b,0x32,0x1d,0x2e,0x77,0x70,
+0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,
+0x6f,0x74,0x6f,0x62,0x75,0x66,0x52,0x6f,0x74,0x61,
+0x74,0x69,0x6f,0x6e,0x32,0x64,0x52,0x05,0x61,0x6e,
+0x67,0x6c,0x65,0x42,0x1a,0x0a,0x18,0x65,0x64,0x75,
+0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72,0x73,0x74,
+0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72,0x6f,0x74,
+0x6f,0x4a,0x99,0x0d,0x0a,0x06,0x12,0x04,0x00,0x00,
+0x3d,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12,0x03,0x00,
+0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12,0x03,0x02,
+0x00,0x12,0x0a,0x09,0x0a,0x02,0x03,0x00,0x12,0x03,
+0x04,0x00,0x1a,0x0a,0x08,0x0a,0x01,0x08,0x12,0x03,
+0x06,0x00,0x31,0x0a,0x09,0x0a,0x02,0x08,0x01,0x12,
+0x03,0x06,0x00,0x31,0x0a,0x0a,0x0a,0x02,0x04,0x00,
+0x12,0x04,0x08,0x00,0x0c,0x01,0x0a,0x0a,0x0a,0x03,
+0x04,0x00,0x01,0x12,0x03,0x08,0x08,0x1d,0x0a,0x0b,
+0x0a,0x04,0x04,0x00,0x02,0x00,0x12,0x03,0x09,0x02,
+0x10,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x05,
+0x12,0x03,0x09,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,
+0x00,0x02,0x00,0x01,0x12,0x03,0x09,0x09,0x0b,0x0a,
+0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x03,0x12,0x03,
+0x09,0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,
+0x01,0x12,0x03,0x0a,0x02,0x10,0x0a,0x0c,0x0a,0x05,
+0x04,0x00,0x02,0x01,0x05,0x12,0x03,0x0a,0x02,0x08,
+0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x01,0x12,
+0x03,0x0a,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x00,
+0x02,0x01,0x03,0x12,0x03,0x0a,0x0e,0x0f,0x0a,0x0b,
+0x0a,0x04,0x04,0x00,0x02,0x02,0x12,0x03,0x0b,0x02,
+0x13,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x05,
+0x12,0x03,0x0b,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,
+0x00,0x02,0x02,0x01,0x12,0x03,0x0b,0x09,0x0e,0x0a,
+0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x03,0x12,0x03,
+0x0b,0x11,0x12,0x0a,0x0a,0x0a,0x02,0x04,0x01,0x12,
+0x04,0x0e,0x00,0x10,0x01,0x0a,0x0a,0x0a,0x03,0x04,
+0x01,0x01,0x12,0x03,0x0e,0x08,0x2b,0x0a,0x0b,0x0a,
+0x04,0x04,0x01,0x02,0x00,0x12,0x03,0x0f,0x02,0x19,
+0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x05,0x12,
+0x03,0x0f,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01,
+0x02,0x00,0x01,0x12,0x03,0x0f,0x09,0x14,0x0a,0x0c,
+0x0a,0x05,0x04,0x01,0x02,0x00,0x03,0x12,0x03,0x0f,
+0x17,0x18,0x0a,0x0a,0x0a,0x02,0x04,0x02,0x12,0x04,
+0x12,0x00,0x15,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x02,
+0x01,0x12,0x03,0x12,0x08,0x2c,0x0a,0x0b,0x0a,0x04,
+0x04,0x02,0x02,0x00,0x12,0x03,0x13,0x02,0x12,0x0a,
+0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x05,0x12,0x03,
+0x13,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,
+0x00,0x01,0x12,0x03,0x13,0x09,0x0d,0x0a,0x0c,0x0a,
+0x05,0x04,0x02,0x02,0x00,0x03,0x12,0x03,0x13,0x10,
+0x11,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x01,0x12,
+0x03,0x14,0x02,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x02,
+0x02,0x01,0x05,0x12,0x03,0x14,0x02,0x08,0x0a,0x0c,
+0x0a,0x05,0x04,0x02,0x02,0x01,0x01,0x12,0x03,0x14,
+0x09,0x0e,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x01,
+0x03,0x12,0x03,0x14,0x11,0x12,0x0a,0x0a,0x0a,0x02,
+0x04,0x03,0x12,0x04,0x17,0x00,0x1a,0x01,0x0a,0x0a,
+0x0a,0x03,0x04,0x03,0x01,0x12,0x03,0x17,0x08,0x2f,
+0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x00,0x12,0x03,
+0x18,0x02,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,
+0x00,0x05,0x12,0x03,0x18,0x02,0x08,0x0a,0x0c,0x0a,
+0x05,0x04,0x03,0x02,0x00,0x01,0x12,0x03,0x18,0x09,
+0x0d,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x00,0x03,
+0x12,0x03,0x18,0x10,0x11,0x0a,0x0b,0x0a,0x04,0x04,
+0x03,0x02,0x01,0x12,0x03,0x19,0x02,0x13,0x0a,0x0c,
+0x0a,0x05,0x04,0x03,0x02,0x01,0x05,0x12,0x03,0x19,
+0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01,
+0x01,0x12,0x03,0x19,0x09,0x0e,0x0a,0x0c,0x0a,0x05,
+0x04,0x03,0x02,0x01,0x03,0x12,0x03,0x19,0x11,0x12,
+0x0a,0x0a,0x0a,0x02,0x04,0x04,0x12,0x04,0x1c,0x00,
+0x21,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x04,0x01,0x12,
+0x03,0x1c,0x08,0x26,0x0a,0x0b,0x0a,0x04,0x04,0x04,
+0x02,0x00,0x12,0x03,0x1d,0x02,0x27,0x0a,0x0c,0x0a,
+0x05,0x04,0x04,0x02,0x00,0x06,0x12,0x03,0x1d,0x02,
+0x17,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x00,0x01,
+0x12,0x03,0x1d,0x18,0x22,0x0a,0x0c,0x0a,0x05,0x04,
+0x04,0x02,0x00,0x03,0x12,0x03,0x1d,0x25,0x26,0x0a,
+0x0b,0x0a,0x04,0x04,0x04,0x02,0x01,0x12,0x03,0x1e,
+0x02,0x28,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x01,
+0x06,0x12,0x03,0x1e,0x02,0x17,0x0a,0x0c,0x0a,0x05,
+0x04,0x04,0x02,0x01,0x01,0x12,0x03,0x1e,0x18,0x23,
+0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x01,0x03,0x12,
+0x03,0x1e,0x26,0x27,0x0a,0x0b,0x0a,0x04,0x04,0x04,
+0x02,0x02,0x12,0x03,0x1f,0x02,0x26,0x0a,0x0c,0x0a,
+0x05,0x04,0x04,0x02,0x02,0x06,0x12,0x03,0x1f,0x02,
+0x17,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x02,0x01,
+0x12,0x03,0x1f,0x18,0x21,0x0a,0x0c,0x0a,0x05,0x04,
+0x04,0x02,0x02,0x03,0x12,0x03,0x1f,0x24,0x25,0x0a,
+0x0b,0x0a,0x04,0x04,0x04,0x02,0x03,0x12,0x03,0x20,
+0x02,0x27,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x03,
+0x06,0x12,0x03,0x20,0x02,0x17,0x0a,0x0c,0x0a,0x05,
+0x04,0x04,0x02,0x03,0x01,0x12,0x03,0x20,0x18,0x22,
+0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x03,0x03,0x12,
+0x03,0x20,0x25,0x26,0x0a,0x0a,0x0a,0x02,0x04,0x05,
+0x12,0x04,0x23,0x00,0x28,0x01,0x0a,0x0a,0x0a,0x03,
+0x04,0x05,0x01,0x12,0x03,0x23,0x08,0x2a,0x0a,0x0b,
+0x0a,0x04,0x04,0x05,0x02,0x00,0x12,0x03,0x24,0x02,
+0x18,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x00,0x05,
+0x12,0x03,0x24,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,
+0x05,0x02,0x00,0x01,0x12,0x03,0x24,0x09,0x13,0x0a,
+0x0c,0x0a,0x05,0x04,0x05,0x02,0x00,0x03,0x12,0x03,
+0x24,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,
+0x01,0x12,0x03,0x25,0x02,0x19,0x0a,0x0c,0x0a,0x05,
+0x04,0x05,0x02,0x01,0x05,0x12,0x03,0x25,0x02,0x08,
+0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x01,0x01,0x12,
+0x03,0x25,0x09,0x14,0x0a,0x0c,0x0a,0x05,0x04,0x05,
+0x02,0x01,0x03,0x12,0x03,0x25,0x17,0x18,0x0a,0x0b,
+0x0a,0x04,0x04,0x05,0x02,0x02,0x12,0x03,0x26,0x02,
+0x17,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x02,0x05,
+0x12,0x03,0x26,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,
+0x05,0x02,0x02,0x01,0x12,0x03,0x26,0x09,0x12,0x0a,
+0x0c,0x0a,0x05,0x04,0x05,0x02,0x02,0x03,0x12,0x03,
+0x26,0x15,0x16,0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,
+0x03,0x12,0x03,0x27,0x02,0x18,0x0a,0x0c,0x0a,0x05,
+0x04,0x05,0x02,0x03,0x05,0x12,0x03,0x27,0x02,0x08,
+0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x03,0x01,0x12,
+0x03,0x27,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x05,
+0x02,0x03,0x03,0x12,0x03,0x27,0x16,0x17,0x0a,0x0a,
+0x0a,0x02,0x04,0x06,0x12,0x04,0x2a,0x00,0x2f,0x01,
+0x0a,0x0a,0x0a,0x03,0x04,0x06,0x01,0x12,0x03,0x2a,
+0x08,0x27,0x0a,0x0b,0x0a,0x04,0x04,0x06,0x02,0x00,
+0x12,0x03,0x2b,0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,
+0x06,0x02,0x00,0x05,0x12,0x03,0x2b,0x02,0x08,0x0a,
+0x0c,0x0a,0x05,0x04,0x06,0x02,0x00,0x01,0x12,0x03,
+0x2b,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,
+0x00,0x03,0x12,0x03,0x2b,0x16,0x17,0x0a,0x0b,0x0a,
+0x04,0x04,0x06,0x02,0x01,0x12,0x03,0x2c,0x02,0x19,
+0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x01,0x05,0x12,
+0x03,0x2c,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x06,
+0x02,0x01,0x01,0x12,0x03,0x2c,0x09,0x14,0x0a,0x0c,
+0x0a,0x05,0x04,0x06,0x02,0x01,0x03,0x12,0x03,0x2c,
+0x17,0x18,0x0a,0x0b,0x0a,0x04,0x04,0x06,0x02,0x02,
+0x12,0x03,0x2d,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,
+0x06,0x02,0x02,0x05,0x12,0x03,0x2d,0x02,0x08,0x0a,
+0x0c,0x0a,0x05,0x04,0x06,0x02,0x02,0x01,0x12,0x03,
+0x2d,0x09,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,
+0x02,0x03,0x12,0x03,0x2d,0x15,0x16,0x0a,0x0b,0x0a,
+0x04,0x04,0x06,0x02,0x03,0x12,0x03,0x2e,0x02,0x18,
+0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x03,0x05,0x12,
+0x03,0x2e,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x06,
+0x02,0x03,0x01,0x12,0x03,0x2e,0x09,0x13,0x0a,0x0c,
+0x0a,0x05,0x04,0x06,0x02,0x03,0x03,0x12,0x03,0x2e,
+0x16,0x17,0x0a,0x0a,0x0a,0x02,0x04,0x07,0x12,0x04,
+0x31,0x00,0x33,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x07,
+0x01,0x12,0x03,0x31,0x08,0x25,0x0a,0x0b,0x0a,0x04,
+0x04,0x07,0x02,0x00,0x12,0x03,0x32,0x02,0x2d,0x0a,
+0x0c,0x0a,0x05,0x04,0x07,0x02,0x00,0x04,0x12,0x03,
+0x32,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,
+0x00,0x06,0x12,0x03,0x32,0x0b,0x20,0x0a,0x0c,0x0a,
+0x05,0x04,0x07,0x02,0x00,0x01,0x12,0x03,0x32,0x21,
+0x28,0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x00,0x03,
+0x12,0x03,0x32,0x2b,0x2c,0x0a,0x0a,0x0a,0x02,0x04,
+0x08,0x12,0x04,0x35,0x00,0x38,0x01,0x0a,0x0a,0x0a,
+0x03,0x04,0x08,0x01,0x12,0x03,0x35,0x08,0x24,0x0a,
+0x0b,0x0a,0x04,0x04,0x08,0x02,0x00,0x12,0x03,0x36,
+0x02,0x16,0x0a,0x0c,0x0a,0x05,0x04,0x08,0x02,0x00,
+0x05,0x12,0x03,0x36,0x02,0x08,0x0a,0x0c,0x0a,0x05,
+0x04,0x08,0x02,0x00,0x01,0x12,0x03,0x36,0x09,0x11,
+0x0a,0x0c,0x0a,0x05,0x04,0x08,0x02,0x00,0x03,0x12,
+0x03,0x36,0x14,0x15,0x0a,0x0b,0x0a,0x04,0x04,0x08,
+0x02,0x01,0x12,0x03,0x37,0x02,0x1f,0x0a,0x0c,0x0a,
+0x05,0x04,0x08,0x02,0x01,0x06,0x12,0x03,0x37,0x02,
+0x14,0x0a,0x0c,0x0a,0x05,0x04,0x08,0x02,0x01,0x01,
+0x12,0x03,0x37,0x15,0x1a,0x0a,0x0c,0x0a,0x05,0x04,
+0x08,0x02,0x01,0x03,0x12,0x03,0x37,0x1d,0x1e,0x0a,
+0x0a,0x0a,0x02,0x04,0x09,0x12,0x04,0x3a,0x00,0x3d,
+0x01,0x0a,0x0a,0x0a,0x03,0x04,0x09,0x01,0x12,0x03,
+0x3a,0x08,0x21,0x0a,0x0b,0x0a,0x04,0x04,0x09,0x02,
+0x00,0x12,0x03,0x3b,0x02,0x13,0x0a,0x0c,0x0a,0x05,
+0x04,0x09,0x02,0x00,0x05,0x12,0x03,0x3b,0x02,0x08,
+0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02,0x00,0x01,0x12,
+0x03,0x3b,0x09,0x0e,0x0a,0x0c,0x0a,0x05,0x04,0x09,
+0x02,0x00,0x03,0x12,0x03,0x3b,0x11,0x12,0x0a,0x0b,
+0x0a,0x04,0x04,0x09,0x02,0x01,0x12,0x03,0x3c,0x02,
+0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02,0x01,0x06,
+0x12,0x03,0x3c,0x02,0x14,0x0a,0x0c,0x0a,0x05,0x04,
+0x09,0x02,0x01,0x01,0x12,0x03,0x3c,0x15,0x1a,0x0a,
+0x0c,0x0a,0x05,0x04,0x09,0x02,0x01,0x03,0x12,0x03,
+0x3c,0x1d,0x1e,0x62,0x06,0x70,0x72,0x6f,0x74,0x6f,
+0x33,
};
static const char file_name[] = "kinematics.proto";
static const char wpi_proto_ProtobufChassisSpeeds_name[] = "wpi.proto.ProtobufChassisSpeeds";
@@ -387,12 +347,6 @@ pb_filedesc_t wpi_proto_ProtobufMecanumDriveKinematics::file_descriptor(void) no
PB_BIND(wpi_proto_ProtobufMecanumDriveKinematics, wpi_proto_ProtobufMecanumDriveKinematics, AUTO)
-static const char wpi_proto_ProtobufMecanumDriveMotorVoltages_name[] = "wpi.proto.ProtobufMecanumDriveMotorVoltages";
-std::string_view wpi_proto_ProtobufMecanumDriveMotorVoltages::msg_name(void) noexcept { return wpi_proto_ProtobufMecanumDriveMotorVoltages_name; }
-pb_filedesc_t wpi_proto_ProtobufMecanumDriveMotorVoltages::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; }
-PB_BIND(wpi_proto_ProtobufMecanumDriveMotorVoltages, wpi_proto_ProtobufMecanumDriveMotorVoltages, AUTO)
-
-
static const char wpi_proto_ProtobufMecanumDriveWheelPositions_name[] = "wpi.proto.ProtobufMecanumDriveWheelPositions";
std::string_view wpi_proto_ProtobufMecanumDriveWheelPositions::msg_name(void) noexcept { return wpi_proto_ProtobufMecanumDriveWheelPositions_name; }
pb_filedesc_t wpi_proto_ProtobufMecanumDriveWheelPositions::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; }
diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h
index e55103ffb80..cbb27afc08c 100644
--- a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h
+++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h
@@ -63,17 +63,6 @@ typedef struct _wpi_proto_ProtobufMecanumDriveKinematics {
pb_callback_t rear_right;
} wpi_proto_ProtobufMecanumDriveKinematics;
-typedef struct _wpi_proto_ProtobufMecanumDriveMotorVoltages {
- static const pb_msgdesc_t* msg_descriptor(void) noexcept;
- static std::string_view msg_name(void) noexcept;
- static pb_filedesc_t file_descriptor(void) noexcept;
-
- double front_left;
- double front_right;
- double rear_left;
- double rear_right;
-} wpi_proto_ProtobufMecanumDriveMotorVoltages;
-
typedef struct _wpi_proto_ProtobufMecanumDriveWheelPositions {
static const pb_msgdesc_t* msg_descriptor(void) noexcept;
static std::string_view msg_name(void) noexcept;
@@ -129,7 +118,6 @@ typedef struct _wpi_proto_ProtobufSwerveModuleState {
#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_init_default {0, 0}
#define wpi_proto_ProtobufDifferentialDriveWheelPositions_init_default {0, 0}
#define wpi_proto_ProtobufMecanumDriveKinematics_init_default {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}}
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_init_default {0, 0, 0, 0}
#define wpi_proto_ProtobufMecanumDriveWheelPositions_init_default {0, 0, 0, 0}
#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_init_default {0, 0, 0, 0}
#define wpi_proto_ProtobufSwerveDriveKinematics_init_default {{{NULL}, NULL}}
@@ -140,7 +128,6 @@ typedef struct _wpi_proto_ProtobufSwerveModuleState {
#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_init_zero {0, 0}
#define wpi_proto_ProtobufDifferentialDriveWheelPositions_init_zero {0, 0}
#define wpi_proto_ProtobufMecanumDriveKinematics_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}}
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_init_zero {0, 0, 0, 0}
#define wpi_proto_ProtobufMecanumDriveWheelPositions_init_zero {0, 0, 0, 0}
#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_init_zero {0, 0, 0, 0}
#define wpi_proto_ProtobufSwerveDriveKinematics_init_zero {{{NULL}, NULL}}
@@ -160,10 +147,6 @@ typedef struct _wpi_proto_ProtobufSwerveModuleState {
#define wpi_proto_ProtobufMecanumDriveKinematics_front_right_tag 2
#define wpi_proto_ProtobufMecanumDriveKinematics_rear_left_tag 3
#define wpi_proto_ProtobufMecanumDriveKinematics_rear_right_tag 4
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_front_left_tag 1
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_front_right_tag 2
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_rear_left_tag 3
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_rear_right_tag 4
#define wpi_proto_ProtobufMecanumDriveWheelPositions_front_left_tag 1
#define wpi_proto_ProtobufMecanumDriveWheelPositions_front_right_tag 2
#define wpi_proto_ProtobufMecanumDriveWheelPositions_rear_left_tag 3
@@ -215,14 +198,6 @@ X(a, CALLBACK, OPTIONAL, MESSAGE, rear_right, 4)
#define wpi_proto_ProtobufMecanumDriveKinematics_rear_left_MSGTYPE wpi_proto_ProtobufTranslation2d
#define wpi_proto_ProtobufMecanumDriveKinematics_rear_right_MSGTYPE wpi_proto_ProtobufTranslation2d
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_FIELDLIST(X, a) \
-X(a, STATIC, SINGULAR, DOUBLE, front_left, 1) \
-X(a, STATIC, SINGULAR, DOUBLE, front_right, 2) \
-X(a, STATIC, SINGULAR, DOUBLE, rear_left, 3) \
-X(a, STATIC, SINGULAR, DOUBLE, rear_right, 4)
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_CALLBACK NULL
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_DEFAULT NULL
-
#define wpi_proto_ProtobufMecanumDriveWheelPositions_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, DOUBLE, front_left, 1) \
X(a, STATIC, SINGULAR, DOUBLE, front_right, 2) \
@@ -264,12 +239,11 @@ X(a, CALLBACK, OPTIONAL, MESSAGE, angle, 2)
/* wpi_proto_ProtobufSwerveDriveKinematics_size depends on runtime parameters */
/* wpi_proto_ProtobufSwerveModulePosition_size depends on runtime parameters */
/* wpi_proto_ProtobufSwerveModuleState_size depends on runtime parameters */
-#define WPI_PROTO_KINEMATICS_NPB_H_MAX_SIZE wpi_proto_ProtobufMecanumDriveMotorVoltages_size
+#define WPI_PROTO_KINEMATICS_NPB_H_MAX_SIZE wpi_proto_ProtobufMecanumDriveWheelPositions_size
#define wpi_proto_ProtobufChassisSpeeds_size 27
#define wpi_proto_ProtobufDifferentialDriveKinematics_size 9
#define wpi_proto_ProtobufDifferentialDriveWheelPositions_size 18
#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_size 18
-#define wpi_proto_ProtobufMecanumDriveMotorVoltages_size 36
#define wpi_proto_ProtobufMecanumDriveWheelPositions_size 36
#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_size 36
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
index 8bc91b1d8e6..51249d4fc3a 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
@@ -4,13 +4,9 @@
package edu.wpi.first.math.kinematics;
-import edu.wpi.first.math.kinematics.proto.MecanumDriveMotorVoltagesProto;
-import edu.wpi.first.math.kinematics.struct.MecanumDriveMotorVoltagesStruct;
-import edu.wpi.first.util.protobuf.ProtobufSerializable;
-import edu.wpi.first.util.struct.StructSerializable;
-
/** Represents the motor voltages for a mecanum drive drivetrain. */
-public class MecanumDriveMotorVoltages implements ProtobufSerializable, StructSerializable {
+@Deprecated(since = "2025", forRemoval = true)
+public class MecanumDriveMotorVoltages {
/** Voltage of the front left motor. */
public double frontLeftVoltage;
@@ -52,11 +48,4 @@ public String toString() {
+ "Rear Left: %.2f V, Rear Right: %.2f V)",
frontLeftVoltage, frontRightVoltage, rearLeftVoltage, rearRightVoltage);
}
-
- /** MecanumDriveMotorVoltages struct for serialization. */
- public static final MecanumDriveMotorVoltagesStruct struct =
- new MecanumDriveMotorVoltagesStruct();
-
- /** MecanumDriveMotorVoltages protobuf for serialization. */
- public static final MecanumDriveMotorVoltagesProto proto = new MecanumDriveMotorVoltagesProto();
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java
deleted file mode 100644
index 0b5f0c2583b..00000000000
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java
+++ /dev/null
@@ -1,42 +0,0 @@
-// 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.math.kinematics.proto;
-
-import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
-import edu.wpi.first.math.proto.Kinematics.ProtobufMecanumDriveMotorVoltages;
-import edu.wpi.first.util.protobuf.Protobuf;
-import us.hebi.quickbuf.Descriptors.Descriptor;
-
-public final class MecanumDriveMotorVoltagesProto
- implements Protobuf {
- @Override
- public Class getTypeClass() {
- return MecanumDriveMotorVoltages.class;
- }
-
- @Override
- public Descriptor getDescriptor() {
- return ProtobufMecanumDriveMotorVoltages.getDescriptor();
- }
-
- @Override
- public ProtobufMecanumDriveMotorVoltages createMessage() {
- return ProtobufMecanumDriveMotorVoltages.newInstance();
- }
-
- @Override
- public MecanumDriveMotorVoltages unpack(ProtobufMecanumDriveMotorVoltages msg) {
- return new MecanumDriveMotorVoltages(
- msg.getFrontLeft(), msg.getFrontRight(), msg.getRearLeft(), msg.getRearRight());
- }
-
- @Override
- public void pack(ProtobufMecanumDriveMotorVoltages msg, MecanumDriveMotorVoltages value) {
- msg.setFrontLeft(value.frontLeftVoltage);
- msg.setFrontRight(value.frontRightVoltage);
- msg.setRearLeft(value.rearLeftVoltage);
- msg.setRearRight(value.rearRightVoltage);
- }
-}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java
deleted file mode 100644
index 8078e0a7b16..00000000000
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java
+++ /dev/null
@@ -1,48 +0,0 @@
-// 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.math.kinematics.struct;
-
-import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
-import edu.wpi.first.util.struct.Struct;
-import java.nio.ByteBuffer;
-
-public final class MecanumDriveMotorVoltagesStruct implements Struct {
- @Override
- public Class getTypeClass() {
- return MecanumDriveMotorVoltages.class;
- }
-
- @Override
- public String getTypeName() {
- return "MecanumDriveMotorVoltages";
- }
-
- @Override
- public int getSize() {
- return kSizeDouble * 4;
- }
-
- @Override
- public String getSchema() {
- return "double front_left;double front_right;double rear_left;double rear_right";
- }
-
- @Override
- public MecanumDriveMotorVoltages unpack(ByteBuffer bb) {
- double front_left = bb.getDouble();
- double front_right = bb.getDouble();
- double rear_left = bb.getDouble();
- double rear_right = bb.getDouble();
- return new MecanumDriveMotorVoltages(front_left, front_right, rear_left, rear_right);
- }
-
- @Override
- public void pack(ByteBuffer bb, MecanumDriveMotorVoltages value) {
- bb.putDouble(value.frontLeftVoltage);
- bb.putDouble(value.frontRightVoltage);
- bb.putDouble(value.rearLeftVoltage);
- bb.putDouble(value.rearRightVoltage);
- }
-}
diff --git a/wpimath/src/main/proto/kinematics.proto b/wpimath/src/main/proto/kinematics.proto
index 4cb3b055a23..2a31b2d7c65 100644
--- a/wpimath/src/main/proto/kinematics.proto
+++ b/wpimath/src/main/proto/kinematics.proto
@@ -33,13 +33,6 @@ message ProtobufMecanumDriveKinematics {
ProtobufTranslation2d rear_right = 4;
}
-message ProtobufMecanumDriveMotorVoltages {
- double front_left = 1;
- double front_right = 2;
- double rear_left = 3;
- double rear_right = 4;
-}
-
message ProtobufMecanumDriveWheelPositions {
double front_left = 1;
double front_right = 2;
diff --git a/wpimath/src/test/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProtoTest.java b/wpimath/src/test/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProtoTest.java
deleted file mode 100644
index 0aaac653f42..00000000000
--- a/wpimath/src/test/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProtoTest.java
+++ /dev/null
@@ -1,27 +0,0 @@
-// 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.math.kinematics.proto;
-
-import static org.junit.jupiter.api.Assertions.assertEquals;
-
-import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
-import edu.wpi.first.math.proto.Kinematics.ProtobufMecanumDriveMotorVoltages;
-import edu.wpi.first.wpilibj.ProtoTestBase;
-
-@SuppressWarnings("PMD.TestClassWithoutTestCases")
-class MecanumDriveMotorVoltagesProtoTest
- extends ProtoTestBase {
- MecanumDriveMotorVoltagesProtoTest() {
- super(new MecanumDriveMotorVoltages(1.2, 3.1, 2.5, -0.1), MecanumDriveMotorVoltages.proto);
- }
-
- @Override
- public void checkEquals(MecanumDriveMotorVoltages testData, MecanumDriveMotorVoltages data) {
- assertEquals(testData.frontLeftVoltage, data.frontLeftVoltage);
- assertEquals(testData.frontRightVoltage, data.frontRightVoltage);
- assertEquals(testData.rearLeftVoltage, data.rearLeftVoltage);
- assertEquals(testData.rearRightVoltage, data.rearRightVoltage);
- }
-}
diff --git a/wpimath/src/test/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStructTest.java b/wpimath/src/test/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStructTest.java
deleted file mode 100644
index a53fbbadd4d..00000000000
--- a/wpimath/src/test/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStructTest.java
+++ /dev/null
@@ -1,25 +0,0 @@
-// 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.math.kinematics.struct;
-
-import static org.junit.jupiter.api.Assertions.assertEquals;
-
-import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
-import edu.wpi.first.wpilibj.StructTestBase;
-
-@SuppressWarnings("PMD.TestClassWithoutTestCases")
-class MecanumDriveMotorVoltagesStructTest extends StructTestBase {
- MecanumDriveMotorVoltagesStructTest() {
- super(new MecanumDriveMotorVoltages(1.2, 3.1, 2.5, -0.1), MecanumDriveMotorVoltages.struct);
- }
-
- @Override
- public void checkEquals(MecanumDriveMotorVoltages testData, MecanumDriveMotorVoltages data) {
- assertEquals(testData.frontLeftVoltage, data.frontLeftVoltage);
- assertEquals(testData.frontRightVoltage, data.frontRightVoltage);
- assertEquals(testData.rearLeftVoltage, data.rearLeftVoltage);
- assertEquals(testData.rearRightVoltage, data.rearRightVoltage);
- }
-}