mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
[wpimath] Add protobuf/struct for trivial types (#5935)
This implements de/serialization for the types that aren't templated (SwerveDriveKinematics) in C++ or where there is no trivial way to go round-trip (Splines) for the messages.
This commit is contained in:
@@ -4,6 +4,9 @@
|
||||
|
||||
package edu.wpi.first.math.controller;
|
||||
|
||||
import edu.wpi.first.math.controller.proto.ArmFeedforwardProto;
|
||||
import edu.wpi.first.math.controller.struct.ArmFeedforwardStruct;
|
||||
|
||||
/**
|
||||
* A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting
|
||||
* against the force of gravity on a beam suspended at an angle).
|
||||
@@ -14,6 +17,9 @@ public class ArmFeedforward {
|
||||
public final double kv;
|
||||
public final double ka;
|
||||
|
||||
public static final ArmFeedforwardProto proto = new ArmFeedforwardProto();
|
||||
public static final ArmFeedforwardStruct struct = new ArmFeedforwardStruct();
|
||||
|
||||
/**
|
||||
* Creates a new ArmFeedforward with the specified gains. Units of the gain values will dictate
|
||||
* units of the computed feedforward.
|
||||
|
||||
@@ -4,11 +4,19 @@
|
||||
|
||||
package edu.wpi.first.math.controller;
|
||||
|
||||
import edu.wpi.first.math.controller.proto.DifferentialDriveWheelVoltagesProto;
|
||||
import edu.wpi.first.math.controller.struct.DifferentialDriveWheelVoltagesStruct;
|
||||
|
||||
/** Motor voltages for a differential drive. */
|
||||
public class DifferentialDriveWheelVoltages {
|
||||
public double left;
|
||||
public double right;
|
||||
|
||||
public static final DifferentialDriveWheelVoltagesProto proto =
|
||||
new DifferentialDriveWheelVoltagesProto();
|
||||
public static final DifferentialDriveWheelVoltagesStruct struct =
|
||||
new DifferentialDriveWheelVoltagesStruct();
|
||||
|
||||
public DifferentialDriveWheelVoltages() {}
|
||||
|
||||
public DifferentialDriveWheelVoltages(double left, double right) {
|
||||
|
||||
@@ -6,6 +6,8 @@ package edu.wpi.first.math.controller;
|
||||
|
||||
import edu.wpi.first.math.MatBuilder;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.controller.proto.ElevatorFeedforwardProto;
|
||||
import edu.wpi.first.math.controller.struct.ElevatorFeedforwardStruct;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
|
||||
/**
|
||||
@@ -18,6 +20,9 @@ public class ElevatorFeedforward {
|
||||
public final double kv;
|
||||
public final double ka;
|
||||
|
||||
public static final ElevatorFeedforwardProto proto = new ElevatorFeedforwardProto();
|
||||
public static final ElevatorFeedforwardStruct struct = new ElevatorFeedforwardStruct();
|
||||
|
||||
/**
|
||||
* Creates a new ElevatorFeedforward with the specified gains. Units of the gain values will
|
||||
* dictate units of the computed feedforward.
|
||||
|
||||
@@ -0,0 +1,40 @@
|
||||
// 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.controller.proto;
|
||||
|
||||
import edu.wpi.first.math.controller.ArmFeedforward;
|
||||
import edu.wpi.first.math.proto.Controller.ProtobufArmFeedforward;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class ArmFeedforwardProto implements Protobuf<ArmFeedforward, ProtobufArmFeedforward> {
|
||||
@Override
|
||||
public Class<ArmFeedforward> getTypeClass() {
|
||||
return ArmFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufArmFeedforward.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufArmFeedforward createMessage() {
|
||||
return ProtobufArmFeedforward.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ArmFeedforward unpack(ProtobufArmFeedforward msg) {
|
||||
return new ArmFeedforward(msg.getKs(), msg.getKg(), msg.getKv(), msg.getKa());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufArmFeedforward msg, ArmFeedforward value) {
|
||||
msg.setKs(value.ks);
|
||||
msg.setKg(value.kg);
|
||||
msg.setKv(value.kv);
|
||||
msg.setKa(value.ka);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
// 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.controller.proto;
|
||||
|
||||
import edu.wpi.first.math.controller.DifferentialDriveWheelVoltages;
|
||||
import edu.wpi.first.math.proto.Controller.ProtobufDifferentialDriveWheelVoltages;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class DifferentialDriveWheelVoltagesProto
|
||||
implements Protobuf<DifferentialDriveWheelVoltages, ProtobufDifferentialDriveWheelVoltages> {
|
||||
@Override
|
||||
public Class<DifferentialDriveWheelVoltages> getTypeClass() {
|
||||
return DifferentialDriveWheelVoltages.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufDifferentialDriveWheelVoltages.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufDifferentialDriveWheelVoltages createMessage() {
|
||||
return ProtobufDifferentialDriveWheelVoltages.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveWheelVoltages unpack(ProtobufDifferentialDriveWheelVoltages msg) {
|
||||
return new DifferentialDriveWheelVoltages(msg.getLeft(), msg.getRight());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(
|
||||
ProtobufDifferentialDriveWheelVoltages msg, DifferentialDriveWheelVoltages value) {
|
||||
msg.setLeft(value.left);
|
||||
msg.setRight(value.right);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,41 @@
|
||||
// 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.controller.proto;
|
||||
|
||||
import edu.wpi.first.math.controller.ElevatorFeedforward;
|
||||
import edu.wpi.first.math.proto.Controller.ProtobufElevatorFeedforward;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class ElevatorFeedforwardProto
|
||||
implements Protobuf<ElevatorFeedforward, ProtobufElevatorFeedforward> {
|
||||
@Override
|
||||
public Class<ElevatorFeedforward> getTypeClass() {
|
||||
return ElevatorFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufElevatorFeedforward.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufElevatorFeedforward createMessage() {
|
||||
return ProtobufElevatorFeedforward.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ElevatorFeedforward unpack(ProtobufElevatorFeedforward msg) {
|
||||
return new ElevatorFeedforward(msg.getKs(), msg.getKg(), msg.getKv(), msg.getKa());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufElevatorFeedforward msg, ElevatorFeedforward value) {
|
||||
msg.setKs(value.ks);
|
||||
msg.setKg(value.kg);
|
||||
msg.setKv(value.kv);
|
||||
msg.setKa(value.ka);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,48 @@
|
||||
// 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.controller.struct;
|
||||
|
||||
import edu.wpi.first.math.controller.ArmFeedforward;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class ArmFeedforwardStruct implements Struct<ArmFeedforward> {
|
||||
@Override
|
||||
public Class<ArmFeedforward> getTypeClass() {
|
||||
return ArmFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:ArmFeedforward";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 4;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double ks;double kg;double kv;double ka";
|
||||
}
|
||||
|
||||
@Override
|
||||
public ArmFeedforward unpack(ByteBuffer bb) {
|
||||
double ks = bb.getDouble();
|
||||
double kg = bb.getDouble();
|
||||
double kv = bb.getDouble();
|
||||
double ka = bb.getDouble();
|
||||
return new ArmFeedforward(ks, kg, kv, ka);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, ArmFeedforward value) {
|
||||
bb.putDouble(value.ks);
|
||||
bb.putDouble(value.kg);
|
||||
bb.putDouble(value.kv);
|
||||
bb.putDouble(value.ka);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,45 @@
|
||||
// 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.controller.struct;
|
||||
|
||||
import edu.wpi.first.math.controller.DifferentialDriveWheelVoltages;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class DifferentialDriveWheelVoltagesStruct
|
||||
implements Struct<DifferentialDriveWheelVoltages> {
|
||||
@Override
|
||||
public Class<DifferentialDriveWheelVoltages> getTypeClass() {
|
||||
return DifferentialDriveWheelVoltages.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DifferentialDriveWheelVoltages";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 2;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double left;double right";
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveWheelVoltages unpack(ByteBuffer bb) {
|
||||
double left = bb.getDouble();
|
||||
double right = bb.getDouble();
|
||||
return new DifferentialDriveWheelVoltages(left, right);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, DifferentialDriveWheelVoltages value) {
|
||||
bb.putDouble(value.left);
|
||||
bb.putDouble(value.right);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,48 @@
|
||||
// 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.controller.struct;
|
||||
|
||||
import edu.wpi.first.math.controller.ElevatorFeedforward;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class ElevatorFeedforwardStruct implements Struct<ElevatorFeedforward> {
|
||||
@Override
|
||||
public Class<ElevatorFeedforward> getTypeClass() {
|
||||
return ElevatorFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:ElevatorFeedforward";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 4;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double ks;double kg;double kv;double ka";
|
||||
}
|
||||
|
||||
@Override
|
||||
public ElevatorFeedforward unpack(ByteBuffer bb) {
|
||||
double ks = bb.getDouble();
|
||||
double kg = bb.getDouble();
|
||||
double kv = bb.getDouble();
|
||||
double ka = bb.getDouble();
|
||||
return new ElevatorFeedforward(ks, kg, kv, ka);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, ElevatorFeedforward value) {
|
||||
bb.putDouble(value.ks);
|
||||
bb.putDouble(value.kg);
|
||||
bb.putDouble(value.kv);
|
||||
bb.putDouble(value.ka);
|
||||
}
|
||||
}
|
||||
@@ -11,6 +11,8 @@ import static edu.wpi.first.units.Units.Seconds;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.proto.ChassisSpeedsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.ChassisSpeedsStruct;
|
||||
import edu.wpi.first.units.Angle;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
@@ -36,6 +38,9 @@ public class ChassisSpeeds {
|
||||
/** Represents the angular velocity of the robot frame. (CCW is +) */
|
||||
public double omegaRadiansPerSecond;
|
||||
|
||||
public static final ChassisSpeedsProto proto = new ChassisSpeedsProto();
|
||||
public static final ChassisSpeedsStruct struct = new ChassisSpeedsStruct();
|
||||
|
||||
/** Constructs a ChassisSpeeds with zeros for dx, dy, and theta. */
|
||||
public ChassisSpeeds() {}
|
||||
|
||||
|
||||
@@ -9,6 +9,8 @@ import static edu.wpi.first.units.Units.Meters;
|
||||
import edu.wpi.first.math.MathSharedStore;
|
||||
import edu.wpi.first.math.MathUsageId;
|
||||
import edu.wpi.first.math.geometry.Twist2d;
|
||||
import edu.wpi.first.math.kinematics.proto.DifferentialDriveKinematicsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.DifferentialDriveKinematicsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
|
||||
@@ -24,6 +26,11 @@ public class DifferentialDriveKinematics
|
||||
implements Kinematics<DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions> {
|
||||
public final double trackWidthMeters;
|
||||
|
||||
public static final DifferentialDriveKinematicsProto proto =
|
||||
new DifferentialDriveKinematicsProto();
|
||||
public static final DifferentialDriveKinematicsStruct struct =
|
||||
new DifferentialDriveKinematicsStruct();
|
||||
|
||||
/**
|
||||
* Constructs a differential drive kinematics object.
|
||||
*
|
||||
|
||||
@@ -6,6 +6,8 @@ package edu.wpi.first.math.kinematics;
|
||||
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
|
||||
import edu.wpi.first.math.kinematics.proto.DifferentialDriveWheelSpeedsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.DifferentialDriveWheelSpeedsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
@@ -18,6 +20,11 @@ public class DifferentialDriveWheelSpeeds {
|
||||
/** Speed of the right side of the robot. */
|
||||
public double rightMetersPerSecond;
|
||||
|
||||
public static final DifferentialDriveWheelSpeedsProto proto =
|
||||
new DifferentialDriveWheelSpeedsProto();
|
||||
public static final DifferentialDriveWheelSpeedsStruct struct =
|
||||
new DifferentialDriveWheelSpeedsStruct();
|
||||
|
||||
/** Constructs a DifferentialDriveWheelSpeeds with zeros for left and right speeds. */
|
||||
public DifferentialDriveWheelSpeeds() {}
|
||||
|
||||
|
||||
@@ -8,6 +8,8 @@ import edu.wpi.first.math.MathSharedStore;
|
||||
import edu.wpi.first.math.MathUsageId;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.geometry.Twist2d;
|
||||
import edu.wpi.first.math.kinematics.proto.MecanumDriveKinematicsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.MecanumDriveKinematicsStruct;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
/**
|
||||
@@ -42,6 +44,9 @@ public class MecanumDriveKinematics
|
||||
|
||||
private Translation2d m_prevCoR = new Translation2d();
|
||||
|
||||
public static final MecanumDriveKinematicsProto proto = new MecanumDriveKinematicsProto();
|
||||
public static final MecanumDriveKinematicsStruct struct = new MecanumDriveKinematicsStruct();
|
||||
|
||||
/**
|
||||
* Constructs a mecanum drive kinematics object.
|
||||
*
|
||||
@@ -207,4 +212,20 @@ public class MecanumDriveKinematics
|
||||
m_inverseKinematics.setRow(2, 0, 1, 1, rl.getX() - rl.getY());
|
||||
m_inverseKinematics.setRow(3, 0, 1, -1, -(rr.getX() + rr.getY()));
|
||||
}
|
||||
|
||||
public Translation2d getFrontLeft() {
|
||||
return m_frontLeftWheelMeters;
|
||||
}
|
||||
|
||||
public Translation2d getFrontRight() {
|
||||
return m_frontRightWheelMeters;
|
||||
}
|
||||
|
||||
public Translation2d getRearLeft() {
|
||||
return m_rearLeftWheelMeters;
|
||||
}
|
||||
|
||||
public Translation2d getRearRight() {
|
||||
return m_rearRightWheelMeters;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,6 +7,8 @@ package edu.wpi.first.math.kinematics;
|
||||
import static edu.wpi.first.units.Units.Meters;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.kinematics.proto.MecanumDriveWheelPositionsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.MecanumDriveWheelPositionsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import java.util.Objects;
|
||||
@@ -24,6 +26,10 @@ public class MecanumDriveWheelPositions implements WheelPositions<MecanumDriveWh
|
||||
/** Distance measured by the rear right wheel. */
|
||||
public double rearRightMeters;
|
||||
|
||||
public static final MecanumDriveWheelPositionsStruct struct =
|
||||
new MecanumDriveWheelPositionsStruct();
|
||||
public static final MecanumDriveWheelPositionsProto proto = new MecanumDriveWheelPositionsProto();
|
||||
|
||||
/** Constructs a MecanumDriveWheelPositions with zeros for all member fields. */
|
||||
public MecanumDriveWheelPositions() {}
|
||||
|
||||
|
||||
@@ -6,6 +6,8 @@ package edu.wpi.first.math.kinematics;
|
||||
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
|
||||
import edu.wpi.first.math.kinematics.proto.MecanumDriveWheelSpeedsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.MecanumDriveWheelSpeedsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
@@ -24,6 +26,9 @@ public class MecanumDriveWheelSpeeds {
|
||||
/** Speed of the rear right wheel. */
|
||||
public double rearRightMetersPerSecond;
|
||||
|
||||
public static final MecanumDriveWheelSpeedsStruct struct = new MecanumDriveWheelSpeedsStruct();
|
||||
public static final MecanumDriveWheelSpeedsProto proto = new MecanumDriveWheelSpeedsProto();
|
||||
|
||||
/** Constructs a MecanumDriveWheelSpeeds with zeros for all member fields. */
|
||||
public MecanumDriveWheelSpeeds() {}
|
||||
|
||||
|
||||
@@ -9,6 +9,8 @@ import static edu.wpi.first.units.Units.Meters;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.math.kinematics.proto.SwerveModulePositionProto;
|
||||
import edu.wpi.first.math.kinematics.struct.SwerveModulePositionStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import java.util.Objects;
|
||||
@@ -22,6 +24,9 @@ public class SwerveModulePosition
|
||||
/** Angle of the module. */
|
||||
public Rotation2d angle = Rotation2d.fromDegrees(0);
|
||||
|
||||
public static final SwerveModulePositionStruct struct = new SwerveModulePositionStruct();
|
||||
public static final SwerveModulePositionProto proto = new SwerveModulePositionProto();
|
||||
|
||||
/** Constructs a SwerveModulePosition with zeros for distance and angle. */
|
||||
public SwerveModulePosition() {}
|
||||
|
||||
|
||||
@@ -7,6 +7,8 @@ package edu.wpi.first.math.kinematics;
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.proto.SwerveModuleStateProto;
|
||||
import edu.wpi.first.math.kinematics.struct.SwerveModuleStateStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
@@ -20,6 +22,9 @@ public class SwerveModuleState implements Comparable<SwerveModuleState> {
|
||||
/** Angle of the module. */
|
||||
public Rotation2d angle = Rotation2d.fromDegrees(0);
|
||||
|
||||
public static final SwerveModuleStateStruct struct = new SwerveModuleStateStruct();
|
||||
public static final SwerveModuleStateProto proto = new SwerveModuleStateProto();
|
||||
|
||||
/** Constructs a SwerveModuleState with zeros for speed and angle. */
|
||||
public SwerveModuleState() {}
|
||||
|
||||
|
||||
@@ -0,0 +1,39 @@
|
||||
// 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.ChassisSpeeds;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufChassisSpeeds;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class ChassisSpeedsProto implements Protobuf<ChassisSpeeds, ProtobufChassisSpeeds> {
|
||||
@Override
|
||||
public Class<ChassisSpeeds> getTypeClass() {
|
||||
return ChassisSpeeds.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufChassisSpeeds.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufChassisSpeeds createMessage() {
|
||||
return ProtobufChassisSpeeds.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ChassisSpeeds unpack(ProtobufChassisSpeeds msg) {
|
||||
return new ChassisSpeeds(msg.getVx(), msg.getVy(), msg.getOmega());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufChassisSpeeds msg, ChassisSpeeds value) {
|
||||
msg.setVx(value.vxMetersPerSecond);
|
||||
msg.setVy(value.vyMetersPerSecond);
|
||||
msg.setOmega(value.omegaRadiansPerSecond);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,38 @@
|
||||
// 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.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufDifferentialDriveKinematics;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class DifferentialDriveKinematicsProto
|
||||
implements Protobuf<DifferentialDriveKinematics, ProtobufDifferentialDriveKinematics> {
|
||||
@Override
|
||||
public Class<DifferentialDriveKinematics> getTypeClass() {
|
||||
return DifferentialDriveKinematics.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufDifferentialDriveKinematics.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufDifferentialDriveKinematics createMessage() {
|
||||
return ProtobufDifferentialDriveKinematics.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveKinematics unpack(ProtobufDifferentialDriveKinematics msg) {
|
||||
return new DifferentialDriveKinematics(msg.getTrackWidth());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufDifferentialDriveKinematics msg, DifferentialDriveKinematics value) {
|
||||
msg.setTrackWidth(value.trackWidthMeters);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,39 @@
|
||||
// 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.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufDifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class DifferentialDriveWheelSpeedsProto
|
||||
implements Protobuf<DifferentialDriveWheelSpeeds, ProtobufDifferentialDriveWheelSpeeds> {
|
||||
@Override
|
||||
public Class<DifferentialDriveWheelSpeeds> getTypeClass() {
|
||||
return DifferentialDriveWheelSpeeds.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufDifferentialDriveWheelSpeeds.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufDifferentialDriveWheelSpeeds createMessage() {
|
||||
return ProtobufDifferentialDriveWheelSpeeds.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveWheelSpeeds unpack(ProtobufDifferentialDriveWheelSpeeds msg) {
|
||||
return new DifferentialDriveWheelSpeeds(msg.getLeft(), msg.getRight());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufDifferentialDriveWheelSpeeds msg, DifferentialDriveWheelSpeeds value) {
|
||||
msg.setLeft(value.leftMetersPerSecond);
|
||||
msg.setRight(value.rightMetersPerSecond);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,51 @@
|
||||
// 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.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufMecanumDriveKinematics;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class MecanumDriveKinematicsProto
|
||||
implements Protobuf<MecanumDriveKinematics, ProtobufMecanumDriveKinematics> {
|
||||
@Override
|
||||
public Class<MecanumDriveKinematics> getTypeClass() {
|
||||
return MecanumDriveKinematics.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufMecanumDriveKinematics.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Protobuf<?, ?>[] getNested() {
|
||||
return new Protobuf<?, ?>[] {Translation2d.proto};
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufMecanumDriveKinematics createMessage() {
|
||||
return ProtobufMecanumDriveKinematics.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public MecanumDriveKinematics unpack(ProtobufMecanumDriveKinematics msg) {
|
||||
return new MecanumDriveKinematics(
|
||||
Translation2d.proto.unpack(msg.getFrontLeft()),
|
||||
Translation2d.proto.unpack(msg.getFrontRight()),
|
||||
Translation2d.proto.unpack(msg.getRearLeft()),
|
||||
Translation2d.proto.unpack(msg.getRearRight()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufMecanumDriveKinematics msg, MecanumDriveKinematics value) {
|
||||
Translation2d.proto.pack(msg.getMutableFrontLeft(), value.getFrontLeft());
|
||||
Translation2d.proto.pack(msg.getMutableFrontRight(), value.getFrontRight());
|
||||
Translation2d.proto.pack(msg.getMutableRearLeft(), value.getRearLeft());
|
||||
Translation2d.proto.pack(msg.getMutableRearRight(), value.getRearRight());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,42 @@
|
||||
// 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.MecanumDriveWheelPositions;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufMecanumDriveWheelPositions;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class MecanumDriveWheelPositionsProto
|
||||
implements Protobuf<MecanumDriveWheelPositions, ProtobufMecanumDriveWheelPositions> {
|
||||
@Override
|
||||
public Class<MecanumDriveWheelPositions> getTypeClass() {
|
||||
return MecanumDriveWheelPositions.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufMecanumDriveWheelPositions.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufMecanumDriveWheelPositions createMessage() {
|
||||
return ProtobufMecanumDriveWheelPositions.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public MecanumDriveWheelPositions unpack(ProtobufMecanumDriveWheelPositions msg) {
|
||||
return new MecanumDriveWheelPositions(
|
||||
msg.getFrontLeft(), msg.getFrontRight(), msg.getRearLeft(), msg.getRearRight());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufMecanumDriveWheelPositions msg, MecanumDriveWheelPositions value) {
|
||||
msg.setFrontLeft(value.frontLeftMeters);
|
||||
msg.setFrontRight(value.frontRightMeters);
|
||||
msg.setRearLeft(value.rearLeftMeters);
|
||||
msg.setRearRight(value.rearRightMeters);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,42 @@
|
||||
// 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.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufMecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class MecanumDriveWheelSpeedsProto
|
||||
implements Protobuf<MecanumDriveWheelSpeeds, ProtobufMecanumDriveWheelSpeeds> {
|
||||
@Override
|
||||
public Class<MecanumDriveWheelSpeeds> getTypeClass() {
|
||||
return MecanumDriveWheelSpeeds.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufMecanumDriveWheelSpeeds.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufMecanumDriveWheelSpeeds createMessage() {
|
||||
return ProtobufMecanumDriveWheelSpeeds.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public MecanumDriveWheelSpeeds unpack(ProtobufMecanumDriveWheelSpeeds msg) {
|
||||
return new MecanumDriveWheelSpeeds(
|
||||
msg.getFrontLeft(), msg.getFrontRight(), msg.getRearLeft(), msg.getRearRight());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufMecanumDriveWheelSpeeds msg, MecanumDriveWheelSpeeds value) {
|
||||
msg.setFrontLeft(value.frontLeftMetersPerSecond);
|
||||
msg.setFrontRight(value.frontRightMetersPerSecond);
|
||||
msg.setRearLeft(value.rearLeftMetersPerSecond);
|
||||
msg.setRearRight(value.rearRightMetersPerSecond);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,45 @@
|
||||
// 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.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufSwerveModulePosition;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class SwerveModulePositionProto
|
||||
implements Protobuf<SwerveModulePosition, ProtobufSwerveModulePosition> {
|
||||
@Override
|
||||
public Class<SwerveModulePosition> getTypeClass() {
|
||||
return SwerveModulePosition.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufSwerveModulePosition.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Protobuf<?, ?>[] getNested() {
|
||||
return new Protobuf<?, ?>[] {Rotation2d.proto};
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufSwerveModulePosition createMessage() {
|
||||
return ProtobufSwerveModulePosition.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public SwerveModulePosition unpack(ProtobufSwerveModulePosition msg) {
|
||||
return new SwerveModulePosition(msg.getDistance(), Rotation2d.proto.unpack(msg.getAngle()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufSwerveModulePosition msg, SwerveModulePosition value) {
|
||||
msg.setDistance(value.distanceMeters);
|
||||
Rotation2d.proto.pack(msg.getMutableAngle(), value.angle);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,45 @@
|
||||
// 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.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufSwerveModuleState;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class SwerveModuleStateProto
|
||||
implements Protobuf<SwerveModuleState, ProtobufSwerveModuleState> {
|
||||
@Override
|
||||
public Class<SwerveModuleState> getTypeClass() {
|
||||
return SwerveModuleState.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufSwerveModuleState.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Protobuf<?, ?>[] getNested() {
|
||||
return new Protobuf<?, ?>[] {Rotation2d.proto};
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufSwerveModuleState createMessage() {
|
||||
return ProtobufSwerveModuleState.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public SwerveModuleState unpack(ProtobufSwerveModuleState msg) {
|
||||
return new SwerveModuleState(msg.getSpeed(), Rotation2d.proto.unpack(msg.getAngle()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufSwerveModuleState msg, SwerveModuleState value) {
|
||||
msg.setSpeed(value.speedMetersPerSecond);
|
||||
Rotation2d.proto.pack(msg.getMutableAngle(), value.angle);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,46 @@
|
||||
// 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.ChassisSpeeds;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class ChassisSpeedsStruct implements Struct<ChassisSpeeds> {
|
||||
@Override
|
||||
public Class<ChassisSpeeds> getTypeClass() {
|
||||
return ChassisSpeeds.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:ChassisSpeeds";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 3;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double vx;double vy;double omega";
|
||||
}
|
||||
|
||||
@Override
|
||||
public ChassisSpeeds unpack(ByteBuffer bb) {
|
||||
double vx = bb.getDouble();
|
||||
double vy = bb.getDouble();
|
||||
double omega = bb.getDouble();
|
||||
return new ChassisSpeeds(vx, vy, omega);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, ChassisSpeeds value) {
|
||||
bb.putDouble(value.vxMetersPerSecond);
|
||||
bb.putDouble(value.vyMetersPerSecond);
|
||||
bb.putDouble(value.omegaRadiansPerSecond);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,42 @@
|
||||
// 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.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class DifferentialDriveKinematicsStruct implements Struct<DifferentialDriveKinematics> {
|
||||
@Override
|
||||
public Class<DifferentialDriveKinematics> getTypeClass() {
|
||||
return DifferentialDriveKinematics.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DifferentialDriveKinematics";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double track_width";
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveKinematics unpack(ByteBuffer bb) {
|
||||
double trackWidth = bb.getDouble();
|
||||
return new DifferentialDriveKinematics(trackWidth);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, DifferentialDriveKinematics value) {
|
||||
bb.putDouble(value.trackWidthMeters);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,44 @@
|
||||
// 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.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class DifferentialDriveWheelSpeedsStruct implements Struct<DifferentialDriveWheelSpeeds> {
|
||||
@Override
|
||||
public Class<DifferentialDriveWheelSpeeds> getTypeClass() {
|
||||
return DifferentialDriveWheelSpeeds.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DifferentialDriveWheelSpeeds";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 2;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double left;double right";
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveWheelSpeeds unpack(ByteBuffer bb) {
|
||||
double left = bb.getDouble();
|
||||
double right = bb.getDouble();
|
||||
return new DifferentialDriveWheelSpeeds(left, right);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, DifferentialDriveWheelSpeeds value) {
|
||||
bb.putDouble(value.leftMetersPerSecond);
|
||||
bb.putDouble(value.rightMetersPerSecond);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,55 @@
|
||||
// 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.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class MecanumDriveKinematicsStruct implements Struct<MecanumDriveKinematics> {
|
||||
@Override
|
||||
public Class<MecanumDriveKinematics> getTypeClass() {
|
||||
return MecanumDriveKinematics.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:MecanumDriveKinematics";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return 4 * Translation2d.struct.getSize();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "Translation2d front_left;Translation2d front_right;Translation2d rear_left;"
|
||||
+ "Translation2d rear_right";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Struct<?>[] getNested() {
|
||||
return new Struct<?>[] {Translation2d.struct};
|
||||
}
|
||||
|
||||
@Override
|
||||
public MecanumDriveKinematics unpack(ByteBuffer bb) {
|
||||
Translation2d frontLeft = Translation2d.struct.unpack(bb);
|
||||
Translation2d frontRight = Translation2d.struct.unpack(bb);
|
||||
Translation2d rearLeft = Translation2d.struct.unpack(bb);
|
||||
Translation2d rearRight = Translation2d.struct.unpack(bb);
|
||||
return new MecanumDriveKinematics(frontLeft, frontRight, rearLeft, rearRight);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, MecanumDriveKinematics value) {
|
||||
Translation2d.struct.pack(bb, value.getFrontLeft());
|
||||
Translation2d.struct.pack(bb, value.getFrontRight());
|
||||
Translation2d.struct.pack(bb, value.getRearLeft());
|
||||
Translation2d.struct.pack(bb, value.getRearRight());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,48 @@
|
||||
// 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.MecanumDriveWheelPositions;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class MecanumDriveWheelPositionsStruct implements Struct<MecanumDriveWheelPositions> {
|
||||
@Override
|
||||
public Class<MecanumDriveWheelPositions> getTypeClass() {
|
||||
return MecanumDriveWheelPositions.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:MecanumDriveWheelPositions";
|
||||
}
|
||||
|
||||
@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 MecanumDriveWheelPositions unpack(ByteBuffer bb) {
|
||||
double frontLeft = bb.getDouble();
|
||||
double frontRight = bb.getDouble();
|
||||
double rearLeft = bb.getDouble();
|
||||
double rearRight = bb.getDouble();
|
||||
return new MecanumDriveWheelPositions(frontLeft, frontRight, rearLeft, rearRight);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, MecanumDriveWheelPositions value) {
|
||||
bb.putDouble(value.frontLeftMeters);
|
||||
bb.putDouble(value.frontRightMeters);
|
||||
bb.putDouble(value.rearLeftMeters);
|
||||
bb.putDouble(value.rearRightMeters);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,48 @@
|
||||
// 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.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class MecanumDriveWheelSpeedsStruct implements Struct<MecanumDriveWheelSpeeds> {
|
||||
@Override
|
||||
public Class<MecanumDriveWheelSpeeds> getTypeClass() {
|
||||
return MecanumDriveWheelSpeeds.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:MecanumDriveWheelSpeeds";
|
||||
}
|
||||
|
||||
@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 MecanumDriveWheelSpeeds unpack(ByteBuffer bb) {
|
||||
double frontLeft = bb.getDouble();
|
||||
double frontRight = bb.getDouble();
|
||||
double rearLeft = bb.getDouble();
|
||||
double rearRight = bb.getDouble();
|
||||
return new MecanumDriveWheelSpeeds(frontLeft, frontRight, rearLeft, rearRight);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, MecanumDriveWheelSpeeds value) {
|
||||
bb.putDouble(value.frontLeftMetersPerSecond);
|
||||
bb.putDouble(value.frontRightMetersPerSecond);
|
||||
bb.putDouble(value.rearLeftMetersPerSecond);
|
||||
bb.putDouble(value.rearRightMetersPerSecond);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,50 @@
|
||||
// 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.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class SwerveModulePositionStruct implements Struct<SwerveModulePosition> {
|
||||
@Override
|
||||
public Class<SwerveModulePosition> getTypeClass() {
|
||||
return SwerveModulePosition.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:SwerveModulePosition";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble + Rotation2d.struct.getSize();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double distance;Rotation2d angle";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Struct<?>[] getNested() {
|
||||
return new Struct<?>[] {Rotation2d.struct};
|
||||
}
|
||||
|
||||
@Override
|
||||
public SwerveModulePosition unpack(ByteBuffer bb) {
|
||||
double distance = bb.getDouble();
|
||||
Rotation2d angle = Rotation2d.struct.unpack(bb);
|
||||
return new SwerveModulePosition(distance, angle);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, SwerveModulePosition value) {
|
||||
bb.putDouble(value.distanceMeters);
|
||||
Rotation2d.struct.pack(bb, value.angle);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,50 @@
|
||||
// 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.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class SwerveModuleStateStruct implements Struct<SwerveModuleState> {
|
||||
@Override
|
||||
public Class<SwerveModuleState> getTypeClass() {
|
||||
return SwerveModuleState.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:SwerveModuleState";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble + Rotation2d.struct.getSize();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double speed;Rotation2d angle";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Struct<?>[] getNested() {
|
||||
return new Struct<?>[] {Rotation2d.struct};
|
||||
}
|
||||
|
||||
@Override
|
||||
public SwerveModuleState unpack(ByteBuffer bb) {
|
||||
double speed = bb.getDouble();
|
||||
Rotation2d angle = Rotation2d.struct.unpack(bb);
|
||||
return new SwerveModuleState(speed, angle);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, SwerveModuleState value) {
|
||||
bb.putDouble(value.speedMetersPerSecond);
|
||||
Rotation2d.struct.pack(bb, value.angle);
|
||||
}
|
||||
}
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
package edu.wpi.first.math.system.plant;
|
||||
|
||||
import edu.wpi.first.math.system.plant.proto.DCMotorProto;
|
||||
import edu.wpi.first.math.system.plant.struct.DCMotorStruct;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
|
||||
/** Holds the constants for a DC motor. */
|
||||
@@ -17,6 +19,9 @@ public class DCMotor {
|
||||
public final double KvRadPerSecPerVolt;
|
||||
public final double KtNMPerAmp;
|
||||
|
||||
public static final DCMotorProto proto = new DCMotorProto();
|
||||
public static final DCMotorStruct struct = new DCMotorStruct();
|
||||
|
||||
/**
|
||||
* Constructs a DC motor.
|
||||
*
|
||||
|
||||
@@ -0,0 +1,47 @@
|
||||
// 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.system.plant.proto;
|
||||
|
||||
import edu.wpi.first.math.proto.Plant.ProtobufDCMotor;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class DCMotorProto implements Protobuf<DCMotor, ProtobufDCMotor> {
|
||||
@Override
|
||||
public Class<DCMotor> getTypeClass() {
|
||||
return DCMotor.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufDCMotor.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufDCMotor createMessage() {
|
||||
return ProtobufDCMotor.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public DCMotor unpack(ProtobufDCMotor msg) {
|
||||
return new DCMotor(
|
||||
msg.getNominalVoltage(),
|
||||
msg.getStallTorque(),
|
||||
msg.getStallCurrent(),
|
||||
msg.getFreeCurrent(),
|
||||
msg.getFreeSpeed(),
|
||||
1);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufDCMotor msg, DCMotor value) {
|
||||
msg.setNominalVoltage(value.nominalVoltageVolts);
|
||||
msg.setStallTorque(value.stallTorqueNewtonMeters);
|
||||
msg.setStallCurrent(value.stallCurrentAmps);
|
||||
msg.setFreeCurrent(value.freeCurrentAmps);
|
||||
msg.setFreeSpeed(value.freeSpeedRadPerSec);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,51 @@
|
||||
// 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.system.plant.struct;
|
||||
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class DCMotorStruct implements Struct<DCMotor> {
|
||||
@Override
|
||||
public Class<DCMotor> getTypeClass() {
|
||||
return DCMotor.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DCMotor";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 5;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double nominal_voltage;double stall_torque;double stall_current;"
|
||||
+ "double free_current;double free_speed";
|
||||
}
|
||||
|
||||
@Override
|
||||
public DCMotor unpack(ByteBuffer bb) {
|
||||
double nominalVoltage = bb.getDouble();
|
||||
double stallTorque = bb.getDouble();
|
||||
double stallCurrent = bb.getDouble();
|
||||
double freeCurrent = bb.getDouble();
|
||||
double freeSpeed = bb.getDouble();
|
||||
return new DCMotor(nominalVoltage, stallTorque, stallCurrent, freeCurrent, freeSpeed, 1);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, DCMotor value) {
|
||||
bb.putDouble(value.nominalVoltageVolts);
|
||||
bb.putDouble(value.stallTorqueNewtonMeters);
|
||||
bb.putDouble(value.stallCurrentAmps);
|
||||
bb.putDouble(value.freeCurrentAmps);
|
||||
bb.putDouble(value.freeSpeedRadPerSec);
|
||||
}
|
||||
}
|
||||
@@ -7,6 +7,8 @@ package edu.wpi.first.math.trajectory;
|
||||
import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Transform2d;
|
||||
import edu.wpi.first.math.trajectory.proto.TrajectoryProto;
|
||||
import edu.wpi.first.math.trajectory.proto.TrajectoryStateProto;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.Objects;
|
||||
@@ -17,6 +19,8 @@ import java.util.stream.Collectors;
|
||||
* represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
|
||||
*/
|
||||
public class Trajectory {
|
||||
public static final TrajectoryProto proto = new TrajectoryProto();
|
||||
|
||||
private final double m_totalTimeSeconds;
|
||||
private final List<State> m_states;
|
||||
|
||||
@@ -264,6 +268,8 @@ public class Trajectory {
|
||||
* represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
|
||||
*/
|
||||
public static class State {
|
||||
public static final TrajectoryStateProto proto = new TrajectoryStateProto();
|
||||
|
||||
// The time elapsed since the beginning of the trajectory.
|
||||
@JsonProperty("time")
|
||||
public double timeSeconds;
|
||||
|
||||
@@ -0,0 +1,52 @@
|
||||
// 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.trajectory.proto;
|
||||
|
||||
import edu.wpi.first.math.proto.Trajectory.ProtobufTrajectory;
|
||||
import edu.wpi.first.math.proto.Trajectory.ProtobufTrajectoryState;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import java.util.ArrayList;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class TrajectoryProto implements Protobuf<Trajectory, ProtobufTrajectory> {
|
||||
@Override
|
||||
public Class<Trajectory> getTypeClass() {
|
||||
return Trajectory.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufTrajectory.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Protobuf<?, ?>[] getNested() {
|
||||
return new Protobuf<?, ?>[] {Trajectory.State.proto};
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufTrajectory createMessage() {
|
||||
return ProtobufTrajectory.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Trajectory unpack(ProtobufTrajectory msg) {
|
||||
ArrayList<Trajectory.State> states = new ArrayList<>(msg.getStates().length());
|
||||
for (ProtobufTrajectoryState protoState : msg.getStates()) {
|
||||
states.add(Trajectory.State.proto.unpack(protoState));
|
||||
}
|
||||
|
||||
return new Trajectory(states);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufTrajectory msg, Trajectory value) {
|
||||
var states = msg.getMutableStates().reserve(value.getStates().size());
|
||||
for (var item : value.getStates()) {
|
||||
Trajectory.State.proto.pack(states.next(), item);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,52 @@
|
||||
// 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.trajectory.proto;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.proto.Trajectory.ProtobufTrajectoryState;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class TrajectoryStateProto implements Protobuf<Trajectory.State, ProtobufTrajectoryState> {
|
||||
@Override
|
||||
public Class<Trajectory.State> getTypeClass() {
|
||||
return Trajectory.State.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufTrajectoryState.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Protobuf<?, ?>[] getNested() {
|
||||
return new Protobuf<?, ?>[] {Pose2d.proto};
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufTrajectoryState createMessage() {
|
||||
return ProtobufTrajectoryState.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Trajectory.State unpack(ProtobufTrajectoryState msg) {
|
||||
return new Trajectory.State(
|
||||
msg.getTime(),
|
||||
msg.getVelocity(),
|
||||
msg.getAcceleration(),
|
||||
Pose2d.proto.unpack(msg.getPose()),
|
||||
msg.getCurvature());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufTrajectoryState msg, Trajectory.State value) {
|
||||
msg.setTime(value.timeSeconds);
|
||||
msg.setVelocity(value.velocityMetersPerSecond);
|
||||
msg.setAcceleration(value.accelerationMetersPerSecondSq);
|
||||
Pose2d.proto.pack(msg.getMutablePose(), value.poseMeters);
|
||||
msg.setCurvature(value.curvatureRadPerMeter);
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user