mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
Merge branch 'main' into 2027
This commit is contained in:
@@ -18,7 +18,7 @@ plugins {
|
||||
id 'idea'
|
||||
id 'visual-studio'
|
||||
id 'net.ltgt.errorprone' version '3.1.0' apply false
|
||||
id 'com.github.johnrengelman.shadow' version '8.1.1' apply false
|
||||
id 'com.gradleup.shadow' version '8.3.4' apply false
|
||||
id 'com.diffplug.spotless' version '6.20.0' apply false
|
||||
id 'com.github.spotbugs' version '6.0.2' apply false
|
||||
}
|
||||
|
||||
@@ -22,7 +22,7 @@ application {
|
||||
mainClass = 'edu.wpi.Main'
|
||||
}
|
||||
|
||||
apply plugin: 'com.github.johnrengelman.shadow'
|
||||
apply plugin: 'com.gradleup.shadow'
|
||||
|
||||
repositories {
|
||||
maven {
|
||||
|
||||
@@ -35,7 +35,7 @@ application {
|
||||
mainClass = 'frc.robot.Main'
|
||||
}
|
||||
|
||||
apply plugin: 'com.github.johnrengelman.shadow'
|
||||
apply plugin: 'com.gradleup.shadow'
|
||||
|
||||
repositories {
|
||||
maven {
|
||||
|
||||
@@ -146,7 +146,7 @@ std::string SshSession::ExecuteResult(std::string_view cmd, int* exitStatus) {
|
||||
#if LIBSSH_VERSION_MAJOR == 0 && LIBSSH_VERSION_MINOR >= 11
|
||||
ssh_channel_get_exit_state(channel, &exitCode, nullptr, nullptr);
|
||||
#else
|
||||
ssh_channel_get_exit_status(channel);
|
||||
exitCode = ssh_channel_get_exit_status(channel);
|
||||
#endif
|
||||
INFO("{} {}", exitCode, cmd);
|
||||
|
||||
|
||||
@@ -287,6 +287,24 @@ public abstract class Command implements Sendable {
|
||||
return group;
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a new command that runs this command and the deadline in parallel, finishing (and
|
||||
* interrupting this command) when the deadline finishes.
|
||||
*
|
||||
* <p>Note: This decorator works by adding this command to a composition. The command the
|
||||
* decorator was called on cannot be scheduled independently or be added to a different
|
||||
* composition (namely, decorators), unless it is manually cleared from the list of composed
|
||||
* commands with {@link CommandScheduler#removeComposedCommand(Command)}. The command composition
|
||||
* returned from this method can be further decorated without issue.
|
||||
*
|
||||
* @param deadline the deadline of the command group
|
||||
* @return the decorated command
|
||||
* @see Command#deadlineFor
|
||||
*/
|
||||
public ParallelDeadlineGroup withDeadline(Command deadline) {
|
||||
return new ParallelDeadlineGroup(deadline, this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Decorates this command with a set of commands to run parallel to it, ending when the calling
|
||||
* command ends and interrupting all the others. Often more convenient/less-verbose than
|
||||
@@ -321,6 +339,7 @@ public abstract class Command implements Sendable {
|
||||
* @param parallel the commands to run in parallel. Note the parallel commands will be interrupted
|
||||
* when the deadline command ends
|
||||
* @return the decorated command
|
||||
* @see Command#withDeadline
|
||||
*/
|
||||
public ParallelDeadlineGroup deadlineFor(Command... parallel) {
|
||||
return new ParallelDeadlineGroup(this, parallel);
|
||||
|
||||
@@ -38,6 +38,7 @@ import java.util.function.Supplier;
|
||||
*
|
||||
* <p>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<MecanumDriveWheelSpeeds> m_currentWheelSpeeds;
|
||||
private final Consumer<MecanumDriveMotorVoltages> m_outputDriveVoltages;
|
||||
private final MecanumVoltagesConsumer m_outputDriveVoltages;
|
||||
private final Consumer<MecanumDriveWheelSpeeds> 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 class MecanumControllerCommand extends Command {
|
||||
PIDController frontRightController,
|
||||
PIDController rearRightController,
|
||||
Supplier<MecanumDriveWheelSpeeds> currentWheelSpeeds,
|
||||
Consumer<MecanumDriveMotorVoltages> outputDriveVoltages,
|
||||
MecanumVoltagesConsumer outputDriveVoltages,
|
||||
Subsystem... requirements) {
|
||||
m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand");
|
||||
m_pose = requireNonNullParam(pose, "pose", "MecanumControllerCommand");
|
||||
@@ -145,6 +145,139 @@ public class MecanumControllerCommand extends Command {
|
||||
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.
|
||||
*
|
||||
* <p>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<Pose2d> pose,
|
||||
SimpleMotorFeedforward feedforward,
|
||||
MecanumDriveKinematics kinematics,
|
||||
PIDController xController,
|
||||
PIDController yController,
|
||||
ProfiledPIDController thetaController,
|
||||
Supplier<Rotation2d> desiredRotation,
|
||||
double maxWheelVelocityMetersPerSecond,
|
||||
PIDController frontLeftController,
|
||||
PIDController rearLeftController,
|
||||
PIDController frontRightController,
|
||||
PIDController rearRightController,
|
||||
Supplier<MecanumDriveWheelSpeeds> currentWheelSpeeds,
|
||||
Consumer<MecanumDriveMotorVoltages> 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
|
||||
* 12 as a voltage output to the motor.
|
||||
*
|
||||
* <p>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.
|
||||
*
|
||||
* <p>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 MecanumVoltagesConsumer that consumes voltages of mecanum motors.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
public MecanumControllerCommand(
|
||||
Trajectory trajectory,
|
||||
Supplier<Pose2d> pose,
|
||||
SimpleMotorFeedforward feedforward,
|
||||
MecanumDriveKinematics kinematics,
|
||||
PIDController xController,
|
||||
PIDController yController,
|
||||
ProfiledPIDController thetaController,
|
||||
double maxWheelVelocityMetersPerSecond,
|
||||
PIDController frontLeftController,
|
||||
PIDController rearLeftController,
|
||||
PIDController frontRightController,
|
||||
PIDController rearRightController,
|
||||
Supplier<MecanumDriveWheelSpeeds> currentWheelSpeeds,
|
||||
MecanumVoltagesConsumer outputDriveVoltages,
|
||||
Subsystem... requirements) {
|
||||
this(
|
||||
trajectory,
|
||||
pose,
|
||||
feedforward,
|
||||
kinematics,
|
||||
xController,
|
||||
yController,
|
||||
thetaController,
|
||||
() ->
|
||||
trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(),
|
||||
maxWheelVelocityMetersPerSecond,
|
||||
frontLeftController,
|
||||
rearLeftController,
|
||||
frontRightController,
|
||||
rearRightController,
|
||||
currentWheelSpeeds,
|
||||
outputDriveVoltages,
|
||||
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
|
||||
@@ -176,6 +309,7 @@ public class MecanumControllerCommand extends Command {
|
||||
* voltages.
|
||||
* @param requirements The subsystems to require.
|
||||
*/
|
||||
@Deprecated(since = "2025", forRemoval = true)
|
||||
public MecanumControllerCommand(
|
||||
Trajectory trajectory,
|
||||
Supplier<Pose2d> pose,
|
||||
@@ -200,15 +334,15 @@ public class MecanumControllerCommand extends Command {
|
||||
xController,
|
||||
yController,
|
||||
thetaController,
|
||||
() ->
|
||||
trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(),
|
||||
maxWheelVelocityMetersPerSecond,
|
||||
frontLeftController,
|
||||
rearLeftController,
|
||||
frontRightController,
|
||||
rearRightController,
|
||||
currentWheelSpeeds,
|
||||
outputDriveVoltages,
|
||||
(frontLeft, frontRight, rearLeft, rearRight) ->
|
||||
outputDriveVoltages.accept(
|
||||
new MecanumDriveMotorVoltages(frontLeft, frontRight, rearLeft, rearRight)),
|
||||
requirements);
|
||||
}
|
||||
|
||||
@@ -400,8 +534,7 @@ public class MecanumControllerCommand extends Command {
|
||||
m_currentWheelSpeeds.get().rearRightMetersPerSecond, rearRightSpeedSetpoint);
|
||||
|
||||
m_outputDriveVoltages.accept(
|
||||
new MecanumDriveMotorVoltages(
|
||||
frontLeftOutput, frontRightOutput, rearLeftOutput, rearRightOutput));
|
||||
frontLeftOutput, frontRightOutput, rearLeftOutput, rearRightOutput);
|
||||
|
||||
} else {
|
||||
m_outputWheelSpeeds.accept(
|
||||
@@ -422,4 +555,22 @@ public class MecanumControllerCommand extends Command {
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -121,6 +121,10 @@ CommandPtr Command::OnlyIf(std::function<bool()> condition) && {
|
||||
return std::move(*this).ToPtr().OnlyIf(std::move(condition));
|
||||
}
|
||||
|
||||
CommandPtr Command::WithDeadline(CommandPtr&& deadline) && {
|
||||
return std::move(*this).ToPtr().WithDeadline(std::move(deadline));
|
||||
}
|
||||
|
||||
CommandPtr Command::DeadlineFor(CommandPtr&& parallel) && {
|
||||
return std::move(*this).ToPtr().DeadlineFor(std::move(parallel));
|
||||
}
|
||||
|
||||
@@ -168,6 +168,15 @@ CommandPtr CommandPtr::OnlyIf(std::function<bool()> condition) && {
|
||||
return std::move(*this).Unless(std::not_fn(std::move(condition)));
|
||||
}
|
||||
|
||||
CommandPtr CommandPtr::WithDeadline(CommandPtr&& deadline) && {
|
||||
AssertValid();
|
||||
std::vector<std::unique_ptr<Command>> vec;
|
||||
vec.emplace_back(std::move(m_ptr));
|
||||
m_ptr = std::make_unique<ParallelDeadlineGroup>(std::move(deadline).Unwrap(),
|
||||
std::move(vec));
|
||||
return std::move(*this);
|
||||
}
|
||||
|
||||
CommandPtr CommandPtr::DeadlineWith(CommandPtr&& parallel) && {
|
||||
AssertValid();
|
||||
std::vector<std::unique_ptr<Command>> vec;
|
||||
|
||||
@@ -309,6 +309,16 @@ class Command : public wpi::Sendable, public wpi::SendableHelper<Command> {
|
||||
[[nodiscard]]
|
||||
CommandPtr OnlyIf(std::function<bool()> condition) &&;
|
||||
|
||||
/**
|
||||
* Creates a new command that runs this command and the deadline in parallel,
|
||||
* finishing (and interrupting this command) when the deadline finishes.
|
||||
*
|
||||
* @param deadline the deadline of the command group
|
||||
* @return the decorated command
|
||||
* @see DeadlineFor
|
||||
*/
|
||||
CommandPtr WithDeadline(CommandPtr&& deadline) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a set of commands to run parallel to it, ending
|
||||
* when the calling command ends and interrupting all the others. Often more
|
||||
@@ -318,9 +328,11 @@ class Command : public wpi::Sendable, public wpi::SendableHelper<Command> {
|
||||
* @param parallel the commands to run in parallel. Note the parallel commands
|
||||
* will be interupted when the deadline command ends
|
||||
* @return the decorated command
|
||||
* @see WithDeadline
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr DeadlineFor(CommandPtr&& parallel) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a set of commands to run parallel to it, ending
|
||||
* when the last command ends. Often more convenient/less-verbose than
|
||||
|
||||
@@ -182,6 +182,16 @@ class CommandPtr final {
|
||||
[[nodiscard]]
|
||||
CommandPtr OnlyIf(std::function<bool()> condition) &&;
|
||||
|
||||
/**
|
||||
* Creates a new command that runs this command and the deadline in parallel,
|
||||
* finishing (and interrupting this command) when the deadline finishes.
|
||||
*
|
||||
* @param deadline the deadline of the command group
|
||||
* @return the decorated command
|
||||
* @see DeadlineFor
|
||||
*/
|
||||
CommandPtr WithDeadline(CommandPtr&& deadline) &&;
|
||||
|
||||
/**
|
||||
* Decorates this command with a set of commands to run parallel to it, ending
|
||||
* when the calling command ends and interrupting all the others. Often more
|
||||
|
||||
@@ -271,6 +271,57 @@ class CommandDecoratorTest extends CommandTestBase {
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void withDeadlineTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean finish = new AtomicBoolean(false);
|
||||
|
||||
Command endsBeforeGroup = Commands.none().withDeadline(Commands.waitUntil(finish::get));
|
||||
scheduler.schedule(endsBeforeGroup);
|
||||
scheduler.run();
|
||||
assertTrue(scheduler.isScheduled(endsBeforeGroup));
|
||||
finish.set(true);
|
||||
scheduler.run();
|
||||
assertFalse(scheduler.isScheduled(endsBeforeGroup));
|
||||
finish.set(false);
|
||||
|
||||
Command endsAfterGroup = Commands.idle().withDeadline(Commands.waitUntil(finish::get));
|
||||
scheduler.schedule(endsAfterGroup);
|
||||
scheduler.run();
|
||||
assertTrue(scheduler.isScheduled(endsAfterGroup));
|
||||
finish.set(true);
|
||||
scheduler.run();
|
||||
assertFalse(scheduler.isScheduled(endsAfterGroup));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void withDeadlineOrderTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean dictatorHasRun = new AtomicBoolean(false);
|
||||
AtomicBoolean dictatorWasPolled = new AtomicBoolean(false);
|
||||
Command dictator =
|
||||
new FunctionalCommand(
|
||||
() -> {},
|
||||
() -> dictatorHasRun.set(true),
|
||||
interrupted -> {},
|
||||
() -> {
|
||||
dictatorWasPolled.set(true);
|
||||
return true;
|
||||
});
|
||||
Command other =
|
||||
Commands.run(
|
||||
() ->
|
||||
assertAll(
|
||||
() -> assertTrue(dictatorHasRun.get()),
|
||||
() -> assertTrue(dictatorWasPolled.get())));
|
||||
Command group = other.withDeadline(dictator);
|
||||
scheduler.schedule(group);
|
||||
scheduler.run();
|
||||
assertAll(() -> assertTrue(dictatorHasRun.get()), () -> assertTrue(dictatorWasPolled.get()));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void alongWithTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
|
||||
@@ -221,6 +221,27 @@ TEST_F(CommandDecoratorTest, DeadlineFor) {
|
||||
EXPECT_FALSE(scheduler.IsScheduled(group));
|
||||
}
|
||||
|
||||
TEST_F(CommandDecoratorTest, WithDeadline) {
|
||||
CommandScheduler scheduler = GetScheduler();
|
||||
|
||||
bool finish = false;
|
||||
|
||||
auto dictator = WaitUntilCommand([&finish] { return finish; });
|
||||
auto endsAfter = WaitUntilCommand([] { return false; });
|
||||
|
||||
auto group = std::move(endsAfter).WithDeadline(std::move(dictator).ToPtr());
|
||||
|
||||
scheduler.Schedule(group);
|
||||
scheduler.Run();
|
||||
|
||||
EXPECT_TRUE(scheduler.IsScheduled(group));
|
||||
|
||||
finish = true;
|
||||
scheduler.Run();
|
||||
|
||||
EXPECT_FALSE(scheduler.IsScheduled(group));
|
||||
}
|
||||
|
||||
TEST_F(CommandDecoratorTest, AlongWith) {
|
||||
CommandScheduler scheduler = GetScheduler();
|
||||
|
||||
@@ -283,6 +304,33 @@ TEST_F(CommandDecoratorTest, DeadlineForOrder) {
|
||||
EXPECT_TRUE(dictatorWasPolled);
|
||||
}
|
||||
|
||||
TEST_F(CommandDecoratorTest, WithDeadlineOrder) {
|
||||
CommandScheduler scheduler = GetScheduler();
|
||||
|
||||
bool dictatorHasRun = false;
|
||||
bool dictatorWasPolled = false;
|
||||
|
||||
auto dictator =
|
||||
FunctionalCommand([] {}, [&dictatorHasRun] { dictatorHasRun = true; },
|
||||
[](bool interrupted) {},
|
||||
[&dictatorWasPolled] {
|
||||
dictatorWasPolled = true;
|
||||
return true;
|
||||
});
|
||||
auto other = RunCommand([&dictatorHasRun, &dictatorWasPolled] {
|
||||
EXPECT_TRUE(dictatorHasRun);
|
||||
EXPECT_TRUE(dictatorWasPolled);
|
||||
});
|
||||
|
||||
auto group = std::move(other).WithDeadline(std::move(dictator).ToPtr());
|
||||
|
||||
scheduler.Schedule(group);
|
||||
scheduler.Run();
|
||||
|
||||
EXPECT_TRUE(dictatorHasRun);
|
||||
EXPECT_TRUE(dictatorWasPolled);
|
||||
}
|
||||
|
||||
TEST_F(CommandDecoratorTest, AlongWithOrder) {
|
||||
CommandScheduler scheduler = GetScheduler();
|
||||
|
||||
|
||||
@@ -96,8 +96,7 @@ public class PneumaticHub implements PneumaticsBase {
|
||||
|
||||
private static DataStore getForModule(int module) {
|
||||
synchronized (m_handleLock) {
|
||||
Integer moduleBoxed = module;
|
||||
DataStore pcm = m_handleMap.get(moduleBoxed);
|
||||
DataStore pcm = m_handleMap.get(module);
|
||||
if (pcm == null) {
|
||||
pcm = new DataStore(module);
|
||||
}
|
||||
|
||||
@@ -47,8 +47,7 @@ public class PneumaticsControlModule implements PneumaticsBase {
|
||||
|
||||
private static DataStore getForModule(int module) {
|
||||
synchronized (m_handleLock) {
|
||||
Integer moduleBoxed = module;
|
||||
DataStore pcm = m_handleMap.get(moduleBoxed);
|
||||
DataStore pcm = m_handleMap.get(module);
|
||||
if (pcm == null) {
|
||||
pcm = new DataStore(module);
|
||||
}
|
||||
|
||||
@@ -129,12 +129,14 @@ public class Drivetrain {
|
||||
*/
|
||||
public void drive(
|
||||
double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
|
||||
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
|
||||
if (fieldRelative) {
|
||||
chassisSpeeds.toRobotRelativeSpeeds(m_gyro.getRotation2d());
|
||||
}
|
||||
chassisSpeeds.discretize(periodSeconds);
|
||||
var mecanumDriveWheelSpeeds = m_kinematics.toWheelSpeeds(chassisSpeeds);
|
||||
var mecanumDriveWheelSpeeds =
|
||||
m_kinematics.toWheelSpeeds(
|
||||
ChassisSpeeds.discretize(
|
||||
fieldRelative
|
||||
? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, m_gyro.getRotation2d())
|
||||
: new ChassisSpeeds(xSpeed, ySpeed, rot),
|
||||
periodSeconds));
|
||||
mecanumDriveWheelSpeeds.desaturate(kMaxSpeed);
|
||||
setSpeeds(mecanumDriveWheelSpeeds);
|
||||
}
|
||||
|
||||
@@ -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 class DriveSubsystem extends SubsystemBase {
|
||||
}
|
||||
|
||||
/** 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. */
|
||||
|
||||
@@ -141,12 +141,14 @@ public class Drivetrain {
|
||||
*/
|
||||
public void drive(
|
||||
double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
|
||||
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
|
||||
if (fieldRelative) {
|
||||
chassisSpeeds.toRobotRelativeSpeeds(m_poseEstimator.getEstimatedPosition().getRotation());
|
||||
}
|
||||
chassisSpeeds.discretize(periodSeconds);
|
||||
var mecanumDriveWheelSpeeds = m_kinematics.toWheelSpeeds(chassisSpeeds);
|
||||
var mecanumDriveWheelSpeeds =
|
||||
m_kinematics.toWheelSpeeds(
|
||||
ChassisSpeeds.discretize(
|
||||
fieldRelative
|
||||
? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, m_poseEstimator.getEstimatedPosition().getRotation())
|
||||
: new ChassisSpeeds(xSpeed, ySpeed, rot),
|
||||
periodSeconds));
|
||||
mecanumDriveWheelSpeeds.desaturate(kMaxSpeed);
|
||||
setSpeeds(mecanumDriveWheelSpeeds);
|
||||
}
|
||||
|
||||
@@ -57,12 +57,14 @@ public class Drivetrain {
|
||||
*/
|
||||
public void drive(
|
||||
double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
|
||||
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
|
||||
if (fieldRelative) {
|
||||
chassisSpeeds.toRobotRelativeSpeeds(m_gyro.getRotation2d());
|
||||
}
|
||||
chassisSpeeds.discretize(periodSeconds);
|
||||
var swerveModuleStates = m_kinematics.toWheelSpeeds(chassisSpeeds);
|
||||
var swerveModuleStates =
|
||||
m_kinematics.toSwerveModuleStates(
|
||||
ChassisSpeeds.discretize(
|
||||
fieldRelative
|
||||
? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, m_gyro.getRotation2d())
|
||||
: new ChassisSpeeds(xSpeed, ySpeed, rot),
|
||||
periodSeconds));
|
||||
SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, kMaxSpeed);
|
||||
m_frontLeft.setDesiredState(swerveModuleStates[0]);
|
||||
m_frontRight.setDesiredState(swerveModuleStates[1]);
|
||||
|
||||
@@ -118,12 +118,14 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
|
||||
*/
|
||||
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
|
||||
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
|
||||
if (fieldRelative) {
|
||||
chassisSpeeds.toRobotRelativeSpeeds(m_gyro.getRotation2d());
|
||||
}
|
||||
chassisSpeeds.discretize(DriveConstants.kDrivePeriod);
|
||||
var swerveModuleStates = DriveConstants.kDriveKinematics.toWheelSpeeds(chassisSpeeds);
|
||||
var swerveModuleStates =
|
||||
DriveConstants.kDriveKinematics.toSwerveModuleStates(
|
||||
ChassisSpeeds.discretize(
|
||||
fieldRelative
|
||||
? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, m_gyro.getRotation2d())
|
||||
: new ChassisSpeeds(xSpeed, ySpeed, rot),
|
||||
DriveConstants.kDrivePeriod));
|
||||
SwerveDriveKinematics.desaturateWheelSpeeds(
|
||||
swerveModuleStates, DriveConstants.kMaxSpeedMetersPerSecond);
|
||||
m_frontLeft.setDesiredState(swerveModuleStates[0]);
|
||||
|
||||
@@ -36,11 +36,8 @@ public class Drivetrain {
|
||||
new SwerveDriveKinematics(
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation);
|
||||
|
||||
/*
|
||||
* Here we use SwerveDrivePoseEstimator so that we can fuse odometry readings.
|
||||
* The numbers used
|
||||
* below are robot specific, and should be tuned.
|
||||
*/
|
||||
/* Here we use SwerveDrivePoseEstimator so that we can fuse odometry readings. The numbers used
|
||||
below are robot specific, and should be tuned. */
|
||||
private final SwerveDrivePoseEstimator m_poseEstimator =
|
||||
new SwerveDrivePoseEstimator(
|
||||
m_kinematics,
|
||||
@@ -69,12 +66,14 @@ public class Drivetrain {
|
||||
*/
|
||||
public void drive(
|
||||
double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
|
||||
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
|
||||
if (fieldRelative) {
|
||||
chassisSpeeds.toRobotRelativeSpeeds(m_poseEstimator.getEstimatedPosition().getRotation());
|
||||
}
|
||||
chassisSpeeds.discretize(periodSeconds);
|
||||
var swerveModuleStates = m_kinematics.toWheelSpeeds(chassisSpeeds);
|
||||
var swerveModuleStates =
|
||||
m_kinematics.toSwerveModuleStates(
|
||||
ChassisSpeeds.discretize(
|
||||
fieldRelative
|
||||
? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, m_poseEstimator.getEstimatedPosition().getRotation())
|
||||
: new ChassisSpeeds(xSpeed, ySpeed, rot),
|
||||
periodSeconds));
|
||||
SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, kMaxSpeed);
|
||||
m_frontLeft.setDesiredState(swerveModuleStates[0]);
|
||||
m_frontRight.setDesiredState(swerveModuleStates[1]);
|
||||
@@ -93,8 +92,7 @@ public class Drivetrain {
|
||||
m_backRight.getPosition()
|
||||
});
|
||||
|
||||
// Also apply vision measurements. We use 0.3 seconds in the past as an example
|
||||
// -- on
|
||||
// Also apply vision measurements. We use 0.3 seconds in the past as an example -- on
|
||||
// a real robot, this must be calculated based either on latency or timestamps.
|
||||
m_poseEstimator.addVisionMeasurement(
|
||||
ExampleGlobalMeasurementSensor.getEstimatedGlobalPose(
|
||||
|
||||
@@ -15,7 +15,7 @@ application {
|
||||
mainClass = 'edu.wpi.first.wpilibj.test.AntJunitLauncher'
|
||||
}
|
||||
|
||||
apply plugin: 'com.github.johnrengelman.shadow'
|
||||
apply plugin: 'com.gradleup.shadow'
|
||||
|
||||
repositories {
|
||||
maven {
|
||||
|
||||
@@ -26,8 +26,8 @@ public class CounterTest extends AbstractComsSetup {
|
||||
private static FakeCounterFixture counter = null;
|
||||
private static final Logger logger = Logger.getLogger(CounterTest.class.getName());
|
||||
|
||||
Integer m_input;
|
||||
Integer m_output;
|
||||
int m_input;
|
||||
int m_output;
|
||||
|
||||
@Override
|
||||
protected Logger getClassLogger() {
|
||||
@@ -40,10 +40,7 @@ public class CounterTest extends AbstractComsSetup {
|
||||
* @param input The input Port
|
||||
* @param output The output Port
|
||||
*/
|
||||
public CounterTest(Integer input, Integer output) {
|
||||
assert input != null;
|
||||
assert output != null;
|
||||
|
||||
public CounterTest(int input, int output) {
|
||||
m_input = input;
|
||||
m_output = output;
|
||||
// System.out.println("Counter Test: Input: " + input + " Output: " +
|
||||
|
||||
@@ -39,7 +39,7 @@ public class DIOCrossConnectTest extends AbstractInterruptTest {
|
||||
* @param input The port for the input wire
|
||||
* @param output The port for the output wire
|
||||
*/
|
||||
public DIOCrossConnectTest(Integer input, Integer output) {
|
||||
public DIOCrossConnectTest(int input, int output) {
|
||||
if (dio != null) {
|
||||
dio.teardown();
|
||||
}
|
||||
|
||||
@@ -51,7 +51,7 @@ public class PDPTest extends AbstractComsSetup {
|
||||
* @param mef Motor encoder fixture.
|
||||
* @param expectedCurrentDraw Expected current draw in Amps.
|
||||
*/
|
||||
public PDPTest(MotorEncoderFixture<?> mef, Double expectedCurrentDraw) {
|
||||
public PDPTest(MotorEncoderFixture<?> mef, double expectedCurrentDraw) {
|
||||
logger.fine("Constructor with: " + mef.getType());
|
||||
if (me != null && !me.equals(mef)) {
|
||||
me.teardown();
|
||||
|
||||
@@ -41,9 +41,9 @@ public class PIDTest extends AbstractComsSetup {
|
||||
private PIDController m_controller = null;
|
||||
private static MotorEncoderFixture<?> me = null;
|
||||
|
||||
private final Double m_p;
|
||||
private final Double m_i;
|
||||
private final Double m_d;
|
||||
private final double m_p;
|
||||
private final double m_i;
|
||||
private final double m_d;
|
||||
|
||||
@Override
|
||||
protected Logger getClassLogger() {
|
||||
@@ -58,7 +58,7 @@ public class PIDTest extends AbstractComsSetup {
|
||||
* @param d D gain.
|
||||
* @param mef Motor encoder fixture.
|
||||
*/
|
||||
public PIDTest(Double p, Double i, Double d, MotorEncoderFixture<?> mef) {
|
||||
public PIDTest(double p, double i, double d, MotorEncoderFixture<?> mef) {
|
||||
logger.fine("Constructor with: " + mef.getType());
|
||||
if (PIDTest.me != null && !PIDTest.me.equals(mef)) {
|
||||
PIDTest.me.teardown();
|
||||
|
||||
@@ -37,10 +37,8 @@ public class DIOCrossConnectFixture implements ITestFixture {
|
||||
* @param input The port of the {@link DigitalInput}
|
||||
* @param output The port of the {@link DigitalOutput}
|
||||
*/
|
||||
public DIOCrossConnectFixture(Integer input, Integer output) {
|
||||
assert input != null;
|
||||
assert output != null;
|
||||
assert !input.equals(output);
|
||||
public DIOCrossConnectFixture(int input, int output) {
|
||||
assert input != output;
|
||||
m_input = new DigitalInput(input);
|
||||
m_output = new DigitalOutput(output);
|
||||
m_allocated = true;
|
||||
|
||||
@@ -19,7 +19,7 @@ import us.hebi.quickbuf.RepeatedByte;
|
||||
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 @@ public final class Kinematics {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Protobuf type {@code ProtobufMecanumDriveMotorVoltages}
|
||||
*/
|
||||
public static final class ProtobufMecanumDriveMotorVoltages extends ProtoMessage<ProtobufMecanumDriveMotorVoltages> implements Cloneable {
|
||||
private static final long serialVersionUID = 0L;
|
||||
|
||||
/**
|
||||
* <code>optional double front_left = 1;</code>
|
||||
*/
|
||||
private double frontLeft;
|
||||
|
||||
/**
|
||||
* <code>optional double front_right = 2;</code>
|
||||
*/
|
||||
private double frontRight;
|
||||
|
||||
/**
|
||||
* <code>optional double rear_left = 3;</code>
|
||||
*/
|
||||
private double rearLeft;
|
||||
|
||||
/**
|
||||
* <code>optional double rear_right = 4;</code>
|
||||
*/
|
||||
private double rearRight;
|
||||
|
||||
private ProtobufMecanumDriveMotorVoltages() {
|
||||
}
|
||||
|
||||
/**
|
||||
* @return a new empty instance of {@code ProtobufMecanumDriveMotorVoltages}
|
||||
*/
|
||||
public static ProtobufMecanumDriveMotorVoltages newInstance() {
|
||||
return new ProtobufMecanumDriveMotorVoltages();
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_left = 1;</code>
|
||||
* @return whether the frontLeft field is set
|
||||
*/
|
||||
public boolean hasFrontLeft() {
|
||||
return (bitField0_ & 0x00000001) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_left = 1;</code>
|
||||
* @return this
|
||||
*/
|
||||
public ProtobufMecanumDriveMotorVoltages clearFrontLeft() {
|
||||
bitField0_ &= ~0x00000001;
|
||||
frontLeft = 0D;
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_left = 1;</code>
|
||||
* @return the frontLeft
|
||||
*/
|
||||
public double getFrontLeft() {
|
||||
return frontLeft;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_left = 1;</code>
|
||||
* @param value the frontLeft to set
|
||||
* @return this
|
||||
*/
|
||||
public ProtobufMecanumDriveMotorVoltages setFrontLeft(final double value) {
|
||||
bitField0_ |= 0x00000001;
|
||||
frontLeft = value;
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_right = 2;</code>
|
||||
* @return whether the frontRight field is set
|
||||
*/
|
||||
public boolean hasFrontRight() {
|
||||
return (bitField0_ & 0x00000002) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_right = 2;</code>
|
||||
* @return this
|
||||
*/
|
||||
public ProtobufMecanumDriveMotorVoltages clearFrontRight() {
|
||||
bitField0_ &= ~0x00000002;
|
||||
frontRight = 0D;
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_right = 2;</code>
|
||||
* @return the frontRight
|
||||
*/
|
||||
public double getFrontRight() {
|
||||
return frontRight;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double front_right = 2;</code>
|
||||
* @param value the frontRight to set
|
||||
* @return this
|
||||
*/
|
||||
public ProtobufMecanumDriveMotorVoltages setFrontRight(final double value) {
|
||||
bitField0_ |= 0x00000002;
|
||||
frontRight = value;
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_left = 3;</code>
|
||||
* @return whether the rearLeft field is set
|
||||
*/
|
||||
public boolean hasRearLeft() {
|
||||
return (bitField0_ & 0x00000004) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_left = 3;</code>
|
||||
* @return this
|
||||
*/
|
||||
public ProtobufMecanumDriveMotorVoltages clearRearLeft() {
|
||||
bitField0_ &= ~0x00000004;
|
||||
rearLeft = 0D;
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_left = 3;</code>
|
||||
* @return the rearLeft
|
||||
*/
|
||||
public double getRearLeft() {
|
||||
return rearLeft;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_left = 3;</code>
|
||||
* @param value the rearLeft to set
|
||||
* @return this
|
||||
*/
|
||||
public ProtobufMecanumDriveMotorVoltages setRearLeft(final double value) {
|
||||
bitField0_ |= 0x00000004;
|
||||
rearLeft = value;
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_right = 4;</code>
|
||||
* @return whether the rearRight field is set
|
||||
*/
|
||||
public boolean hasRearRight() {
|
||||
return (bitField0_ & 0x00000008) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_right = 4;</code>
|
||||
* @return this
|
||||
*/
|
||||
public ProtobufMecanumDriveMotorVoltages clearRearRight() {
|
||||
bitField0_ &= ~0x00000008;
|
||||
rearRight = 0D;
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_right = 4;</code>
|
||||
* @return the rearRight
|
||||
*/
|
||||
public double getRearRight() {
|
||||
return rearRight;
|
||||
}
|
||||
|
||||
/**
|
||||
* <code>optional double rear_right = 4;</code>
|
||||
* @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<ProtobufMecanumDriveMotorVoltages> 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<ProtobufMecanumDriveMotorVoltages> {
|
||||
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}
|
||||
*/
|
||||
|
||||
@@ -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}; }
|
||||
|
||||
@@ -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
|
||||
|
||||
|
||||
@@ -102,10 +102,9 @@ public class HolonomicDriveController {
|
||||
|
||||
m_poseError = trajectoryPose.relativeTo(currentPose);
|
||||
m_rotationError = desiredHeading.minus(currentPose.getRotation());
|
||||
ChassisSpeeds speeds = new ChassisSpeeds(xFF, yFF, thetaFF);
|
||||
|
||||
if (!m_enabled) {
|
||||
speeds.toRobotRelativeSpeeds(currentPose.getRotation());
|
||||
return speeds;
|
||||
return ChassisSpeeds.fromFieldRelativeSpeeds(xFF, yFF, thetaFF, currentPose.getRotation());
|
||||
}
|
||||
|
||||
// Calculate feedback velocities (based on position error).
|
||||
@@ -113,10 +112,8 @@ public class HolonomicDriveController {
|
||||
double yFeedback = m_yController.calculate(currentPose.getY(), trajectoryPose.getY());
|
||||
|
||||
// Return next output.
|
||||
speeds.vxMetersPerSecond += xFeedback;
|
||||
speeds.vyMetersPerSecond += yFeedback;
|
||||
speeds.toRobotRelativeSpeeds(currentPose.getRotation());
|
||||
return speeds;
|
||||
return ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xFF + xFeedback, yFF + yFeedback, thetaFF, currentPose.getRotation());
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -103,9 +103,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* @param omegaRadiansPerSecond Angular velocity.
|
||||
* @param dtSeconds The duration of the timestep the speeds should be applied for.
|
||||
* @return Discretized ChassisSpeeds.
|
||||
* @deprecated Use instance method instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds discretize(
|
||||
double vxMetersPerSecond,
|
||||
double vyMetersPerSecond,
|
||||
@@ -143,9 +141,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* @param omega Angular velocity.
|
||||
* @param dt The duration of the timestep the speeds should be applied for.
|
||||
* @return Discretized ChassisSpeeds.
|
||||
* @deprecated Use instance method instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds discretize(
|
||||
LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Time dt) {
|
||||
return discretize(
|
||||
@@ -166,9 +162,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* @param continuousSpeeds The continuous speeds.
|
||||
* @param dtSeconds The duration of the timestep the speeds should be applied for.
|
||||
* @return Discretized ChassisSpeeds.
|
||||
* @deprecated Use instance method instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds discretize(ChassisSpeeds continuousSpeeds, double dtSeconds) {
|
||||
return discretize(
|
||||
continuousSpeeds.vxMetersPerSecond,
|
||||
@@ -177,36 +171,6 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
dtSeconds);
|
||||
}
|
||||
|
||||
/**
|
||||
* Discretizes a continuous-time chassis speed.
|
||||
*
|
||||
* <p>This function converts this continuous-time chassis speed into a discrete-time one such that
|
||||
* when the discrete-time chassis speed is applied for one timestep, the robot moves as if the
|
||||
* velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt
|
||||
* along the y-axis, and omega * dt around the z-axis).
|
||||
*
|
||||
* <p>This is useful for compensating for translational skew when translating and rotating a
|
||||
* swerve drivetrain.
|
||||
*
|
||||
* @param dtSeconds The duration of the timestep the speeds should be applied for.
|
||||
*/
|
||||
public void discretize(double dtSeconds) {
|
||||
var desiredDeltaPose =
|
||||
new Pose2d(
|
||||
vxMetersPerSecond * dtSeconds,
|
||||
vyMetersPerSecond * dtSeconds,
|
||||
new Rotation2d(omegaRadiansPerSecond * dtSeconds));
|
||||
|
||||
// Find the chassis translation/rotation deltas in the robot frame that move the robot from its
|
||||
// current pose to the desired pose
|
||||
var twist = Pose2d.kZero.log(desiredDeltaPose);
|
||||
|
||||
// Turn the chassis translation/rotation deltas into average velocities
|
||||
vxMetersPerSecond = twist.dx / dtSeconds;
|
||||
vyMetersPerSecond = twist.dy / dtSeconds;
|
||||
omegaRadiansPerSecond = twist.dtheta / dtSeconds;
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds
|
||||
* object.
|
||||
@@ -220,9 +184,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
* @return ChassisSpeeds object representing the speeds in the robot's frame of reference.
|
||||
* @deprecated Use toRobotRelativeSpeeds instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds fromFieldRelativeSpeeds(
|
||||
double vxMetersPerSecond,
|
||||
double vyMetersPerSecond,
|
||||
@@ -247,9 +209,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
* @return ChassisSpeeds object representing the speeds in the robot's frame of reference.
|
||||
* @deprecated Use toRobotRelativeSpeeds instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds fromFieldRelativeSpeeds(
|
||||
LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Rotation2d robotAngle) {
|
||||
return fromFieldRelativeSpeeds(
|
||||
@@ -267,9 +227,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
* @return ChassisSpeeds object representing the speeds in the robot's frame of reference.
|
||||
* @deprecated Use toRobotRelativeSpeeds instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds fromFieldRelativeSpeeds(
|
||||
ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle) {
|
||||
return fromFieldRelativeSpeeds(
|
||||
@@ -279,21 +237,6 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
robotAngle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts this field-relative set of speeds into a robot-relative ChassisSpeeds object.
|
||||
*
|
||||
* @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
*/
|
||||
public void toRobotRelativeSpeeds(Rotation2d robotAngle) {
|
||||
// CW rotation into chassis frame
|
||||
var rotated =
|
||||
new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle.unaryMinus());
|
||||
vxMetersPerSecond = rotated.getX();
|
||||
vyMetersPerSecond = rotated.getY();
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds
|
||||
* object.
|
||||
@@ -307,9 +250,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
* @return ChassisSpeeds object representing the speeds in the field's frame of reference.
|
||||
* @deprecated Use toFieldRelativeSpeeds instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds fromRobotRelativeSpeeds(
|
||||
double vxMetersPerSecond,
|
||||
double vyMetersPerSecond,
|
||||
@@ -333,9 +274,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
* @return ChassisSpeeds object representing the speeds in the field's frame of reference.
|
||||
* @deprecated Use toFieldRelativeSpeeds instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds fromRobotRelativeSpeeds(
|
||||
LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Rotation2d robotAngle) {
|
||||
return fromRobotRelativeSpeeds(
|
||||
@@ -353,9 +292,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
* @return ChassisSpeeds object representing the speeds in the field's frame of reference.
|
||||
* @deprecated Use toFieldRelativeSpeeds instead.
|
||||
*/
|
||||
@Deprecated(forRemoval = true, since = "2025")
|
||||
public static ChassisSpeeds fromRobotRelativeSpeeds(
|
||||
ChassisSpeeds robotRelativeSpeeds, Rotation2d robotAngle) {
|
||||
return fromRobotRelativeSpeeds(
|
||||
@@ -365,20 +302,6 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
robotAngle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts this robot-relative set of speeds into a field-relative ChassisSpeeds object.
|
||||
*
|
||||
* @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is
|
||||
* considered to be zero when it is facing directly away from your alliance station wall.
|
||||
* Remember that this should be CCW positive.
|
||||
*/
|
||||
public void toFieldRelativeSpeeds(Rotation2d robotAngle) {
|
||||
// CCW rotation out of chassis frame
|
||||
var rotated = new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle);
|
||||
vxMetersPerSecond = rotated.getX();
|
||||
vyMetersPerSecond = rotated.getY();
|
||||
}
|
||||
|
||||
/**
|
||||
* Adds two ChassisSpeeds and returns the sum.
|
||||
*
|
||||
|
||||
@@ -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 class MecanumDriveMotorVoltages implements ProtobufSerializable, StructSe
|
||||
+ "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();
|
||||
}
|
||||
|
||||
@@ -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<MecanumDriveMotorVoltages, ProtobufMecanumDriveMotorVoltages> {
|
||||
@Override
|
||||
public Class<MecanumDriveMotorVoltages> 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);
|
||||
}
|
||||
}
|
||||
@@ -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<MecanumDriveMotorVoltages> {
|
||||
@Override
|
||||
public Class<MecanumDriveMotorVoltages> 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);
|
||||
}
|
||||
}
|
||||
@@ -8,8 +8,9 @@ import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import java.util.function.BiFunction;
|
||||
import java.util.function.DoubleFunction;
|
||||
import java.util.function.Function;
|
||||
import java.util.function.DoubleBinaryOperator;
|
||||
import java.util.function.DoubleUnaryOperator;
|
||||
import java.util.function.UnaryOperator;
|
||||
|
||||
/** Numerical integration utilities. */
|
||||
public final class NumericalIntegration {
|
||||
@@ -25,13 +26,12 @@ public final class NumericalIntegration {
|
||||
* @param dtSeconds The time over which to integrate.
|
||||
* @return the integration of dx/dt = f(x) for dt.
|
||||
*/
|
||||
@SuppressWarnings("overloads")
|
||||
public static double rk4(DoubleFunction<Double> f, double x, double dtSeconds) {
|
||||
public static double rk4(DoubleUnaryOperator f, double x, double dtSeconds) {
|
||||
final var h = dtSeconds;
|
||||
final var k1 = f.apply(x);
|
||||
final var k2 = f.apply(x + h * k1 * 0.5);
|
||||
final var k3 = f.apply(x + h * k2 * 0.5);
|
||||
final var k4 = f.apply(x + h * k3);
|
||||
final var k1 = f.applyAsDouble(x);
|
||||
final var k2 = f.applyAsDouble(x + h * k1 * 0.5);
|
||||
final var k3 = f.applyAsDouble(x + h * k2 * 0.5);
|
||||
final var k4 = f.applyAsDouble(x + h * k3);
|
||||
|
||||
return x + h / 6.0 * (k1 + 2.0 * k2 + 2.0 * k3 + k4);
|
||||
}
|
||||
@@ -45,15 +45,13 @@ public final class NumericalIntegration {
|
||||
* @param dtSeconds The time over which to integrate.
|
||||
* @return The result of Runge Kutta integration (4th order).
|
||||
*/
|
||||
@SuppressWarnings("overloads")
|
||||
public static double rk4(
|
||||
BiFunction<Double, Double, Double> f, double x, Double u, double dtSeconds) {
|
||||
public static double rk4(DoubleBinaryOperator f, double x, double u, double dtSeconds) {
|
||||
final var h = dtSeconds;
|
||||
|
||||
final var k1 = f.apply(x, u);
|
||||
final var k2 = f.apply(x + h * k1 * 0.5, u);
|
||||
final var k3 = f.apply(x + h * k2 * 0.5, u);
|
||||
final var k4 = f.apply(x + h * k3, u);
|
||||
final var k1 = f.applyAsDouble(x, u);
|
||||
final var k2 = f.applyAsDouble(x + h * k1 * 0.5, u);
|
||||
final var k3 = f.applyAsDouble(x + h * k2 * 0.5, u);
|
||||
final var k4 = f.applyAsDouble(x + h * k3, u);
|
||||
|
||||
return x + h / 6.0 * (k1 + 2.0 * k2 + 2.0 * k3 + k4);
|
||||
}
|
||||
@@ -69,7 +67,6 @@ public final class NumericalIntegration {
|
||||
* @param dtSeconds The time over which to integrate.
|
||||
* @return the integration of dx/dt = f(x, u) for dt.
|
||||
*/
|
||||
@SuppressWarnings("overloads")
|
||||
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rk4(
|
||||
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
|
||||
Matrix<States, N1> x,
|
||||
@@ -94,9 +91,8 @@ public final class NumericalIntegration {
|
||||
* @param dtSeconds The time over which to integrate.
|
||||
* @return 4th order Runge-Kutta integration of dx/dt = f(x) for dt.
|
||||
*/
|
||||
@SuppressWarnings("overloads")
|
||||
public static <States extends Num> Matrix<States, N1> rk4(
|
||||
Function<Matrix<States, N1>, Matrix<States, N1>> f, Matrix<States, N1> x, double dtSeconds) {
|
||||
UnaryOperator<Matrix<States, N1>> f, Matrix<States, N1> x, double dtSeconds) {
|
||||
final var h = dtSeconds;
|
||||
|
||||
Matrix<States, N1> k1 = f.apply(x);
|
||||
@@ -145,7 +141,6 @@ public final class NumericalIntegration {
|
||||
* @param dtSeconds The time over which to integrate.
|
||||
* @return the integration of dx/dt = f(x, u) for dt.
|
||||
*/
|
||||
@SuppressWarnings("overloads")
|
||||
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkdp(
|
||||
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
|
||||
Matrix<States, N1> x,
|
||||
@@ -166,7 +161,6 @@ public final class NumericalIntegration {
|
||||
* @param maxError The maximum acceptable truncation error. Usually a small number like 1e-6.
|
||||
* @return the integration of dx/dt = f(x, u) for dt.
|
||||
*/
|
||||
@SuppressWarnings("overloads")
|
||||
public static <States extends Num, Inputs extends Num> Matrix<States, N1> rkdp(
|
||||
BiFunction<Matrix<States, N1>, Matrix<Inputs, N1>, Matrix<States, N1>> f,
|
||||
Matrix<States, N1> x,
|
||||
@@ -291,7 +285,6 @@ public final class NumericalIntegration {
|
||||
* @param maxError The maximum acceptable truncation error. Usually a small number like 1e-6.
|
||||
* @return the integration of dx/dt = f(x, u) for dt.
|
||||
*/
|
||||
@SuppressWarnings("overloads")
|
||||
public static <Rows extends Num, Cols extends Num> Matrix<Rows, Cols> rkdp(
|
||||
BiFunction<Double, Matrix<Rows, Cols>, Matrix<Rows, Cols>> f,
|
||||
double t,
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -20,11 +20,10 @@ class ChassisSpeedsTest {
|
||||
@Test
|
||||
void testDiscretize() {
|
||||
final var target = new ChassisSpeeds(1.0, 0.0, 0.5);
|
||||
final var speeds = new ChassisSpeeds(1.0, 0.0, 0.5);
|
||||
final var duration = 1.0;
|
||||
final var dt = 0.01;
|
||||
|
||||
speeds.discretize(duration);
|
||||
final var speeds = ChassisSpeeds.discretize(target, duration);
|
||||
final var twist =
|
||||
new Twist2d(
|
||||
speeds.vxMetersPerSecond * dt,
|
||||
@@ -62,8 +61,8 @@ class ChassisSpeedsTest {
|
||||
|
||||
@Test
|
||||
void testFromFieldRelativeSpeeds() {
|
||||
final var chassisSpeeds = new ChassisSpeeds(1.0, 0.0, 0.5);
|
||||
chassisSpeeds.toRobotRelativeSpeeds(Rotation2d.kCW_Pi_2);
|
||||
final var chassisSpeeds =
|
||||
ChassisSpeeds.fromFieldRelativeSpeeds(1.0, 0.0, 0.5, Rotation2d.kCW_Pi_2);
|
||||
|
||||
assertAll(
|
||||
() -> assertEquals(0.0, chassisSpeeds.vxMetersPerSecond, kEpsilon),
|
||||
@@ -73,8 +72,8 @@ class ChassisSpeedsTest {
|
||||
|
||||
@Test
|
||||
void testFromRobotRelativeSpeeds() {
|
||||
final var chassisSpeeds = new ChassisSpeeds(1.0, 0.0, 0.5);
|
||||
chassisSpeeds.toFieldRelativeSpeeds(Rotation2d.fromDegrees(45.0));
|
||||
final var chassisSpeeds =
|
||||
ChassisSpeeds.fromRobotRelativeSpeeds(1.0, 0.0, 0.5, Rotation2d.fromDegrees(45.0));
|
||||
|
||||
assertAll(
|
||||
() -> assertEquals(1.0 / Math.sqrt(2.0), chassisSpeeds.vxMetersPerSecond, kEpsilon),
|
||||
|
||||
@@ -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<MecanumDriveMotorVoltages, ProtobufMecanumDriveMotorVoltages> {
|
||||
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);
|
||||
}
|
||||
}
|
||||
@@ -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<MecanumDriveMotorVoltages> {
|
||||
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);
|
||||
}
|
||||
}
|
||||
@@ -48,7 +48,7 @@ public class EventVector {
|
||||
public void wakeup() {
|
||||
m_lock.lock();
|
||||
try {
|
||||
for (Integer eventHandle : m_events) {
|
||||
for (int eventHandle : m_events) {
|
||||
WPIUtilJNI.setEvent(eventHandle);
|
||||
}
|
||||
} finally {
|
||||
|
||||
@@ -0,0 +1,65 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.util.struct;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
/**
|
||||
* A utility class for fetching the assigned struct of existing classes. These are usually public,
|
||||
* static, and final properties with the Struct type.
|
||||
*/
|
||||
public final class StructFetcher {
|
||||
private StructFetcher() {
|
||||
throw new UnsupportedOperationException("This is a utility class!");
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a {@link Struct} for the given {@link StructSerializable} marked class. Due to the
|
||||
* non-contractual nature of the marker this can fail. If the {@code struct} field could not be
|
||||
* accessed for any reason, an empty {@link Optional} is returned.
|
||||
*
|
||||
* @param <T> The type of the class.
|
||||
* @param clazz The class object to extract the struct from.
|
||||
* @return An optional containing the struct if it could be extracted.
|
||||
*/
|
||||
@SuppressWarnings("unchecked")
|
||||
public static <T extends StructSerializable> Optional<Struct<T>> fetchStruct(
|
||||
Class<? extends T> clazz) {
|
||||
try {
|
||||
var possibleField = Optional.ofNullable(clazz.getDeclaredField("struct"));
|
||||
return possibleField.flatMap(
|
||||
field -> {
|
||||
if (Struct.class.isAssignableFrom(field.getType())) {
|
||||
try {
|
||||
return Optional.ofNullable((Struct<T>) field.get(null));
|
||||
} catch (IllegalAccessException e) {
|
||||
return Optional.empty();
|
||||
}
|
||||
} else {
|
||||
return Optional.empty();
|
||||
}
|
||||
});
|
||||
} catch (NoSuchFieldException e) {
|
||||
return Optional.empty();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a {@link Struct} for the given class. This does not do compile time checking that the
|
||||
* class is a {@link StructSerializable}. Whenever possible it is reccomended to use {@link
|
||||
* #fetchStruct(Class)}.
|
||||
*
|
||||
* @param clazz The class object to extract the struct from.
|
||||
* @return An optional containing the struct if it could be extracted.
|
||||
*/
|
||||
@SuppressWarnings("unchecked")
|
||||
public static Optional<Struct<?>> fetchStructDynamic(Class<?> clazz) {
|
||||
if (StructSerializable.class.isAssignableFrom(clazz)) {
|
||||
return fetchStruct((Class<? extends StructSerializable>) clazz).map(struct -> struct);
|
||||
} else {
|
||||
return Optional.empty();
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -12,11 +12,10 @@ import java.nio.ByteBuffer;
|
||||
import java.util.ArrayList;
|
||||
import java.util.HashMap;
|
||||
import java.util.List;
|
||||
import java.util.Optional;
|
||||
|
||||
/** A utility class for procedurally generating {@link Struct}s from records and enums. */
|
||||
public final class ProceduralStructGenerator {
|
||||
private ProceduralStructGenerator() {
|
||||
public final class StructGenerator {
|
||||
private StructGenerator() {
|
||||
throw new UnsupportedOperationException("This is a utility class!");
|
||||
}
|
||||
|
||||
@@ -123,54 +122,6 @@ public final class ProceduralStructGenerator {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a {@link Struct} for the given {@link StructSerializable} marked class. Due to the
|
||||
* non-contractual nature of the marker this can fail. If the {@code struct} field could not be
|
||||
* accessed for any reason, an empty {@link Optional} is returned.
|
||||
*
|
||||
* @param <T> The type of the class.
|
||||
* @param clazz The class object to extract the struct from.
|
||||
* @return An optional containing the struct if it could be extracted.
|
||||
*/
|
||||
@SuppressWarnings("unchecked")
|
||||
public static <T extends StructSerializable> Optional<Struct<T>> extractClassStruct(
|
||||
Class<? extends T> clazz) {
|
||||
try {
|
||||
var possibleField = Optional.ofNullable(clazz.getDeclaredField("struct"));
|
||||
return possibleField.flatMap(
|
||||
field -> {
|
||||
if (Struct.class.isAssignableFrom(field.getType())) {
|
||||
try {
|
||||
return Optional.ofNullable((Struct<T>) field.get(null));
|
||||
} catch (IllegalAccessException e) {
|
||||
return Optional.empty();
|
||||
}
|
||||
} else {
|
||||
return Optional.empty();
|
||||
}
|
||||
});
|
||||
} catch (NoSuchFieldException e) {
|
||||
return Optional.empty();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a {@link Struct} for the given class. This does not do compile time checking that the
|
||||
* class is a {@link StructSerializable}. Whenever possible it is reccomended to use {@link
|
||||
* #extractClassStruct(Class)}.
|
||||
*
|
||||
* @param clazz The class object to extract the struct from.
|
||||
* @return An optional containing the struct if it could be extracted.
|
||||
*/
|
||||
@SuppressWarnings("unchecked")
|
||||
public static Optional<Struct<?>> extractClassStructDynamic(Class<?> clazz) {
|
||||
if (StructSerializable.class.isAssignableFrom(clazz)) {
|
||||
return extractClassStruct((Class<? extends StructSerializable>) clazz).map(struct -> struct);
|
||||
} else {
|
||||
return Optional.empty();
|
||||
}
|
||||
}
|
||||
|
||||
/** A utility for building schema syntax in a procedural manner. */
|
||||
@SuppressWarnings("PMD.AvoidStringBufferField")
|
||||
public static class SchemaBuilder {
|
||||
@@ -303,7 +254,7 @@ public final class ProceduralStructGenerator {
|
||||
* @return The generated struct.
|
||||
*/
|
||||
@SuppressWarnings({"unchecked", "PMD.AvoidAccessibilityAlteration"})
|
||||
static <R extends Record> Struct<R> genRecord(final Class<R> recordClass) {
|
||||
public static <R extends Record> Struct<R> genRecord(final Class<R> recordClass) {
|
||||
final RecordComponent[] components = recordClass.getRecordComponents();
|
||||
final SchemaBuilder schemaBuilder = new SchemaBuilder();
|
||||
final ArrayList<Struct<?>> nestedStructs = new ArrayList<>();
|
||||
@@ -329,7 +280,7 @@ public final class ProceduralStructGenerator {
|
||||
if (customStructTypeMap.containsKey(type)) {
|
||||
struct = customStructTypeMap.get(type);
|
||||
} else if (StructSerializable.class.isAssignableFrom(type)) {
|
||||
var optStruct = extractClassStructDynamic(type);
|
||||
var optStruct = StructFetcher.fetchStructDynamic(type);
|
||||
if (optStruct.isPresent()) {
|
||||
struct = optStruct.get();
|
||||
} else {
|
||||
@@ -465,7 +416,7 @@ public final class ProceduralStructGenerator {
|
||||
* @return The generated struct.
|
||||
*/
|
||||
@SuppressWarnings({"unchecked", "PMD.AvoidAccessibilityAlteration"})
|
||||
static <E extends Enum<E>> Struct<E> genEnum(Class<E> enumClass) {
|
||||
public static <E extends Enum<E>> Struct<E> genEnum(Class<E> enumClass) {
|
||||
final E[] enumVariants = enumClass.getEnumConstants();
|
||||
final Field[] allEnumFields = enumClass.getDeclaredFields();
|
||||
final SchemaBuilder schemaBuilder = new SchemaBuilder();
|
||||
@@ -516,7 +467,7 @@ public final class ProceduralStructGenerator {
|
||||
if (customStructTypeMap.containsKey(type)) {
|
||||
struct = customStructTypeMap.get(type);
|
||||
} else if (StructSerializable.class.isAssignableFrom(type)) {
|
||||
var optStruct = extractClassStructDynamic(type);
|
||||
var optStruct = StructFetcher.fetchStructDynamic(type);
|
||||
if (optStruct.isPresent()) {
|
||||
struct = optStruct.get();
|
||||
} else {
|
||||
@@ -4,15 +4,15 @@
|
||||
|
||||
package edu.wpi.first.util.struct;
|
||||
|
||||
import static edu.wpi.first.util.struct.ProceduralStructGenerator.genEnum;
|
||||
import static edu.wpi.first.util.struct.ProceduralStructGenerator.genRecord;
|
||||
import static edu.wpi.first.util.struct.StructGenerator.genEnum;
|
||||
import static edu.wpi.first.util.struct.StructGenerator.genRecord;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class ProceduralStructGeneratorTest {
|
||||
class StructGeneratorTest {
|
||||
public record CustomRecord(int int32, boolean bool, double float64, char character, short int16)
|
||||
implements StructSerializable {
|
||||
public static CustomRecord create() {
|
||||
@@ -95,8 +95,7 @@ class ProceduralStructGeneratorTest {
|
||||
|
||||
@SuppressWarnings("unchecked")
|
||||
private <S extends StructSerializable> void testStructRoundTrip(S value) {
|
||||
Struct<S> struct =
|
||||
ProceduralStructGenerator.extractClassStruct((Class<S>) value.getClass()).get();
|
||||
Struct<S> struct = StructFetcher.fetchStruct((Class<S>) value.getClass()).get();
|
||||
ByteBuffer buffer = ByteBuffer.allocate(struct.getSize());
|
||||
buffer.order(ByteOrder.LITTLE_ENDIAN);
|
||||
struct.pack(buffer, value);
|
||||
@@ -108,8 +107,7 @@ class ProceduralStructGeneratorTest {
|
||||
|
||||
@SuppressWarnings("unchecked")
|
||||
private <S extends StructSerializable> void testStructDoublePack(S value) {
|
||||
Struct<S> struct =
|
||||
ProceduralStructGenerator.extractClassStruct((Class<S>) value.getClass()).get();
|
||||
Struct<S> struct = StructFetcher.fetchStruct((Class<S>) value.getClass()).get();
|
||||
ByteBuffer buffer = ByteBuffer.allocate(struct.getSize());
|
||||
buffer.order(ByteOrder.LITTLE_ENDIAN);
|
||||
struct.pack(buffer, value);
|
||||
@@ -123,8 +121,7 @@ class ProceduralStructGeneratorTest {
|
||||
|
||||
@SuppressWarnings("unchecked")
|
||||
private <S extends StructSerializable> void testStructDoubleUnpack(S value) {
|
||||
Struct<S> struct =
|
||||
ProceduralStructGenerator.extractClassStruct((Class<S>) value.getClass()).get();
|
||||
Struct<S> struct = StructFetcher.fetchStruct((Class<S>) value.getClass()).get();
|
||||
ByteBuffer buffer = ByteBuffer.allocate(struct.getSize());
|
||||
buffer.order(ByteOrder.LITTLE_ENDIAN);
|
||||
struct.pack(buffer, value);
|
||||
Reference in New Issue
Block a user