mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
[wpimath] Add remaining struct and protobuf implementations (#5953)
This commit is contained in:
@@ -6,6 +6,12 @@ package edu.wpi.first.math;
|
||||
|
||||
import edu.wpi.first.math.jni.EigenJNI;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.proto.MatrixProto;
|
||||
import edu.wpi.first.math.struct.MatrixStruct;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
import org.ejml.MatrixDimensionException;
|
||||
import org.ejml.data.DMatrixRMaj;
|
||||
@@ -24,7 +30,8 @@ import org.ejml.simple.SimpleMatrix;
|
||||
* @param <R> The number of rows in this matrix.
|
||||
* @param <C> The number of columns in this matrix.
|
||||
*/
|
||||
public class Matrix<R extends Num, C extends Num> {
|
||||
public class Matrix<R extends Num, C extends Num>
|
||||
implements ProtobufSerializable, StructSerializable {
|
||||
/** Storage for underlying EJML matrix. */
|
||||
protected final SimpleMatrix m_storage;
|
||||
|
||||
@@ -738,4 +745,32 @@ public class Matrix<R extends Num, C extends Num> {
|
||||
public int hashCode() {
|
||||
return Objects.hash(m_storage);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an implementation of the {@link Protobuf} interface for matrices.
|
||||
*
|
||||
* @param <R> The number of rows of the matrices this serializer processes.
|
||||
* @param <C> The number of cols of the matrices this serializer processes.
|
||||
* @param rows The number of rows of the matrices this serializer processes.
|
||||
* @param cols The number of cols of the matrices this serializer processes.
|
||||
* @return The protobuf implementation.
|
||||
*/
|
||||
public static <R extends Num, C extends Num> MatrixProto<R, C> getProto(
|
||||
Nat<R> rows, Nat<C> cols) {
|
||||
return new MatrixProto<>(rows, cols);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an implementation of the {@link Struct} interfaces for matrices.
|
||||
*
|
||||
* @param <R> The number of rows of the matrices this serializer processes.
|
||||
* @param <C> The number of cols of the matrices this serializer processes.
|
||||
* @param rows The number of rows of the matrices this serializer processes.
|
||||
* @param cols The number of cols of the matrices this serializer processes.
|
||||
* @return The struct implementation.
|
||||
*/
|
||||
public static <R extends Num, C extends Num> MatrixStruct<R, C> getStruct(
|
||||
Nat<R> rows, Nat<C> cols) {
|
||||
return new MatrixStruct<>(rows, cols);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -6,6 +6,12 @@ package edu.wpi.first.math;
|
||||
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N3;
|
||||
import edu.wpi.first.math.proto.VectorProto;
|
||||
import edu.wpi.first.math.struct.VectorStruct;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
@@ -16,7 +22,8 @@ import org.ejml.simple.SimpleMatrix;
|
||||
*
|
||||
* @param <R> The number of rows in this matrix.
|
||||
*/
|
||||
public class Vector<R extends Num> extends Matrix<R, N1> {
|
||||
public class Vector<R extends Num> extends Matrix<R, N1>
|
||||
implements ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* Constructs an empty zero vector of the given dimensions.
|
||||
*
|
||||
@@ -151,4 +158,26 @@ public class Vector<R extends Num> extends Matrix<R, N1> {
|
||||
a.get(2) * b.get(0) - a.get(0) * b.get(2),
|
||||
a.get(0) * b.get(1) - a.get(1) * b.get(0));
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an implementation of the {@link Protobuf} interface for vectors.
|
||||
*
|
||||
* @param <R> The number of rows of the vectors this serializer processes.
|
||||
* @param rows The number of rows of the vectors this serializer processes.
|
||||
* @return The protobuf implementation.
|
||||
*/
|
||||
public static final <R extends Num> VectorProto<R> getProto(Nat<R> rows) {
|
||||
return new VectorProto<>(rows);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an implementation of the {@link Struct} interface for vectors.
|
||||
*
|
||||
* @param <R> The number of rows of the vectors this serializer processes.
|
||||
* @param rows The number of rows of the vectors this serializer processes.
|
||||
* @return The struct implementation.
|
||||
*/
|
||||
public static final <R extends Num> VectorStruct<R> getStruct(Nat<R> rows) {
|
||||
return new VectorStruct<>(rows);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -5,14 +5,30 @@
|
||||
package edu.wpi.first.math.controller;
|
||||
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.controller.proto.DifferentialDriveFeedforwardProto;
|
||||
import edu.wpi.first.math.controller.struct.DifferentialDriveFeedforwardStruct;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
/** A helper class which computes the feedforward outputs for a differential drive drivetrain. */
|
||||
public class DifferentialDriveFeedforward {
|
||||
public class DifferentialDriveFeedforward implements ProtobufSerializable, StructSerializable {
|
||||
private final LinearSystem<N2, N2, N2> m_plant;
|
||||
|
||||
/** The linear velocity gain in volts per (meters per second). */
|
||||
public final double m_kVLinear;
|
||||
|
||||
/** The linear acceleration gain in volts per (meters per second squared). */
|
||||
public final double m_kALinear;
|
||||
|
||||
/** The angular velocity gain in volts per (radians per second). */
|
||||
public final double m_kVAngular;
|
||||
|
||||
/** The angular acceleration gain in volts per (radians per second squared). */
|
||||
public final double m_kAAngular;
|
||||
|
||||
/**
|
||||
* Creates a new DifferentialDriveFeedforward with the specified parameters.
|
||||
*
|
||||
@@ -25,9 +41,8 @@ public class DifferentialDriveFeedforward {
|
||||
*/
|
||||
public DifferentialDriveFeedforward(
|
||||
double kVLinear, double kALinear, double kVAngular, double kAAngular, double trackwidth) {
|
||||
m_plant =
|
||||
LinearSystemId.identifyDrivetrainSystem(
|
||||
kVLinear, kALinear, kVAngular, kAAngular, trackwidth);
|
||||
// See LinearSystemId.identifyDrivetrainSystem(double, double, double, double, double)
|
||||
this(kVLinear, kALinear, kVAngular * 2.0 / trackwidth, kAAngular * 2.0 / trackwidth);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -41,6 +56,10 @@ public class DifferentialDriveFeedforward {
|
||||
public DifferentialDriveFeedforward(
|
||||
double kVLinear, double kALinear, double kVAngular, double kAAngular) {
|
||||
m_plant = LinearSystemId.identifyDrivetrainSystem(kVLinear, kALinear, kVAngular, kAAngular);
|
||||
m_kVLinear = kVLinear;
|
||||
m_kALinear = kALinear;
|
||||
m_kVAngular = kVAngular;
|
||||
m_kAAngular = kAAngular;
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -67,4 +86,12 @@ public class DifferentialDriveFeedforward {
|
||||
var u = feedforward.calculate(r, nextR);
|
||||
return new DifferentialDriveWheelVoltages(u.get(0, 0), u.get(1, 0));
|
||||
}
|
||||
|
||||
/** DifferentialDriveFeedforward struct for serialization. */
|
||||
public static final DifferentialDriveFeedforwardStruct struct =
|
||||
new DifferentialDriveFeedforwardStruct();
|
||||
|
||||
/** DifferentialDriveFeedforward protobuf for serialization. */
|
||||
public static final DifferentialDriveFeedforwardProto proto =
|
||||
new DifferentialDriveFeedforwardProto();
|
||||
}
|
||||
|
||||
@@ -6,13 +6,17 @@ package edu.wpi.first.math.controller;
|
||||
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import edu.wpi.first.math.controller.proto.SimpleMotorFeedforwardProto;
|
||||
import edu.wpi.first.math.controller.struct.SimpleMotorFeedforwardStruct;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Unit;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.Voltage;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
/** A helper class that computes feedforward outputs for a simple permanent-magnet DC motor. */
|
||||
public class SimpleMotorFeedforward {
|
||||
public class SimpleMotorFeedforward implements ProtobufSerializable, StructSerializable {
|
||||
/** The static gain. */
|
||||
private final double ks;
|
||||
|
||||
@@ -287,4 +291,10 @@ public class SimpleMotorFeedforward {
|
||||
public double minAchievableAcceleration(double maxVoltage, double velocity) {
|
||||
return maxAchievableAcceleration(-maxVoltage, velocity);
|
||||
}
|
||||
|
||||
/** SimpleMotorFeedforward struct for serialization. */
|
||||
public static final SimpleMotorFeedforwardStruct struct = new SimpleMotorFeedforwardStruct();
|
||||
|
||||
/** SimpleMotorFeedforward protobuf for serialization. */
|
||||
public static final SimpleMotorFeedforwardProto proto = new SimpleMotorFeedforwardProto();
|
||||
}
|
||||
|
||||
@@ -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.controller.proto;
|
||||
|
||||
import edu.wpi.first.math.controller.DifferentialDriveFeedforward;
|
||||
import edu.wpi.first.math.proto.Controller.ProtobufDifferentialDriveFeedforward;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public final class DifferentialDriveFeedforwardProto
|
||||
implements Protobuf<DifferentialDriveFeedforward, ProtobufDifferentialDriveFeedforward> {
|
||||
@Override
|
||||
public Class<DifferentialDriveFeedforward> getTypeClass() {
|
||||
return DifferentialDriveFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufDifferentialDriveFeedforward.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufDifferentialDriveFeedforward createMessage() {
|
||||
return ProtobufDifferentialDriveFeedforward.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveFeedforward unpack(ProtobufDifferentialDriveFeedforward msg) {
|
||||
return new DifferentialDriveFeedforward(
|
||||
msg.getKvLinear(), msg.getKaLinear(), msg.getKvAngular(), msg.getKaAngular());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufDifferentialDriveFeedforward msg, DifferentialDriveFeedforward value) {
|
||||
msg.setKvLinear(value.m_kVLinear);
|
||||
msg.setKaLinear(value.m_kALinear);
|
||||
msg.setKvAngular(value.m_kVAngular);
|
||||
msg.setKaAngular(value.m_kAAngular);
|
||||
}
|
||||
}
|
||||
@@ -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.controller.proto;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.math.proto.Controller.ProtobufSimpleMotorFeedforward;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public final class SimpleMotorFeedforwardProto
|
||||
implements Protobuf<SimpleMotorFeedforward, ProtobufSimpleMotorFeedforward> {
|
||||
@Override
|
||||
public Class<SimpleMotorFeedforward> getTypeClass() {
|
||||
return SimpleMotorFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufSimpleMotorFeedforward.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufSimpleMotorFeedforward createMessage() {
|
||||
return ProtobufSimpleMotorFeedforward.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public SimpleMotorFeedforward unpack(ProtobufSimpleMotorFeedforward msg) {
|
||||
return new SimpleMotorFeedforward(msg.getKs(), msg.getKv(), msg.getKa(), msg.getDt());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufSimpleMotorFeedforward msg, SimpleMotorFeedforward value) {
|
||||
msg.setKs(value.getKs()).setKv(value.getKv()).setKa(value.getKa()).setDt(value.getDt());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,49 @@
|
||||
// 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.DifferentialDriveFeedforward;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public final class DifferentialDriveFeedforwardStruct
|
||||
implements Struct<DifferentialDriveFeedforward> {
|
||||
@Override
|
||||
public Class<DifferentialDriveFeedforward> getTypeClass() {
|
||||
return DifferentialDriveFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "DifferentialDriveFeedforward";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 4;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double kVLinear;double kALinear;double kVAngular;double kAAngular";
|
||||
}
|
||||
|
||||
@Override
|
||||
public DifferentialDriveFeedforward unpack(ByteBuffer bb) {
|
||||
double kVLinear = bb.getDouble();
|
||||
double kALinear = bb.getDouble();
|
||||
double kVAngular = bb.getDouble();
|
||||
double kAAngular = bb.getDouble();
|
||||
return new DifferentialDriveFeedforward(kVLinear, kALinear, kVAngular, kAAngular);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, DifferentialDriveFeedforward value) {
|
||||
bb.putDouble(value.m_kVLinear);
|
||||
bb.putDouble(value.m_kALinear);
|
||||
bb.putDouble(value.m_kVAngular);
|
||||
bb.putDouble(value.m_kAAngular);
|
||||
}
|
||||
}
|
||||
@@ -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.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public final class SimpleMotorFeedforwardStruct implements Struct<SimpleMotorFeedforward> {
|
||||
@Override
|
||||
public Class<SimpleMotorFeedforward> getTypeClass() {
|
||||
return SimpleMotorFeedforward.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "SimpleMotorFeedforward";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 4;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double ks;double kv;double ka;double dt";
|
||||
}
|
||||
|
||||
@Override
|
||||
public SimpleMotorFeedforward unpack(ByteBuffer bb) {
|
||||
double ks = bb.getDouble();
|
||||
double kv = bb.getDouble();
|
||||
double ka = bb.getDouble();
|
||||
double dt = bb.getDouble();
|
||||
return new SimpleMotorFeedforward(ks, kv, ka, dt);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, SimpleMotorFeedforward value) {
|
||||
bb.putDouble(value.getKs());
|
||||
bb.putDouble(value.getKv());
|
||||
bb.putDouble(value.getKa());
|
||||
bb.putDouble(value.getDt());
|
||||
}
|
||||
}
|
||||
@@ -4,8 +4,13 @@
|
||||
|
||||
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 {
|
||||
public class MecanumDriveMotorVoltages implements ProtobufSerializable, StructSerializable {
|
||||
/** Voltage of the front left motor. */
|
||||
public double frontLeftVoltage;
|
||||
|
||||
@@ -47,4 +52,11 @@ public class MecanumDriveMotorVoltages {
|
||||
+ "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();
|
||||
}
|
||||
|
||||
@@ -12,10 +12,15 @@ import edu.wpi.first.math.MathUsageId;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.geometry.Twist2d;
|
||||
import edu.wpi.first.math.kinematics.proto.SwerveDriveKinematicsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.SwerveDriveKinematicsStruct;
|
||||
import edu.wpi.first.units.Angle;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Arrays;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
@@ -41,7 +46,9 @@ import org.ejml.simple.SimpleMatrix;
|
||||
*/
|
||||
@SuppressWarnings("overrides")
|
||||
public class SwerveDriveKinematics
|
||||
implements Kinematics<SwerveModuleState[], SwerveModulePosition[]> {
|
||||
implements Kinematics<SwerveModuleState[], SwerveModulePosition[]>,
|
||||
ProtobufSerializable,
|
||||
StructSerializable {
|
||||
private final SimpleMatrix m_inverseKinematics;
|
||||
private final SimpleMatrix m_forwardKinematics;
|
||||
|
||||
@@ -415,4 +422,28 @@ public class SwerveDriveKinematics
|
||||
}
|
||||
return newPositions;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the locations of the modules relative to the center of rotation.
|
||||
*
|
||||
* @return The locations of the modules relative to the center of rotation. This array should not
|
||||
* be modified.
|
||||
*/
|
||||
@SuppressWarnings("PMD.MethodReturnsInternalArray")
|
||||
public Translation2d[] getModules() {
|
||||
return m_modules;
|
||||
}
|
||||
|
||||
/** SwerveDriveKinematics protobuf for serialization. */
|
||||
public static final SwerveDriveKinematicsProto proto = new SwerveDriveKinematicsProto();
|
||||
|
||||
/**
|
||||
* Creates an implementation of the {@link Struct} interface for swerve drive kinematics objects.
|
||||
*
|
||||
* @param numModules The number of modules of the kinematics objects this serializer processes.
|
||||
* @return The struct implementation.
|
||||
*/
|
||||
public static final SwerveDriveKinematicsStruct getStruct(int numModules) {
|
||||
return new SwerveDriveKinematicsStruct(numModules);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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.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);
|
||||
}
|
||||
}
|
||||
@@ -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.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||
import edu.wpi.first.math.proto.Kinematics.ProtobufSwerveDriveKinematics;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public final class SwerveDriveKinematicsProto
|
||||
implements Protobuf<SwerveDriveKinematics, ProtobufSwerveDriveKinematics> {
|
||||
@Override
|
||||
public Class<SwerveDriveKinematics> getTypeClass() {
|
||||
return SwerveDriveKinematics.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufSwerveDriveKinematics.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufSwerveDriveKinematics createMessage() {
|
||||
return ProtobufSwerveDriveKinematics.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public SwerveDriveKinematics unpack(ProtobufSwerveDriveKinematics msg) {
|
||||
return new SwerveDriveKinematics(Protobuf.unpackArray(msg.getModules(), Translation2d.proto));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufSwerveDriveKinematics msg, SwerveDriveKinematics value) {
|
||||
Protobuf.packArray(msg.getMutableModules(), value.getModules(), Translation2d.proto);
|
||||
}
|
||||
}
|
||||
@@ -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.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);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,58 @@
|
||||
// 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.SwerveDriveKinematics;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public final class SwerveDriveKinematicsStruct implements Struct<SwerveDriveKinematics> {
|
||||
private final int m_numModules;
|
||||
|
||||
/**
|
||||
* Constructs the {@link Struct} implementation.
|
||||
*
|
||||
* @param numModules the number of modules of the kinematics objects this serializer processes.
|
||||
*/
|
||||
public SwerveDriveKinematicsStruct(int numModules) {
|
||||
m_numModules = numModules;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Class<SwerveDriveKinematics> getTypeClass() {
|
||||
return SwerveDriveKinematics.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "SwerveDriveKinematics__" + m_numModules;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return Translation2d.struct.getSize() * m_numModules;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "Translation2d modules[" + m_numModules + "]";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Struct<?>[] getNested() {
|
||||
return new Struct<?>[] {Translation2d.struct};
|
||||
}
|
||||
|
||||
@Override
|
||||
public SwerveDriveKinematics unpack(ByteBuffer bb) {
|
||||
return new SwerveDriveKinematics(Struct.unpackArray(bb, m_numModules, Translation2d.struct));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, SwerveDriveKinematics value) {
|
||||
Struct.packArray(bb, value.getModules(), Translation2d.struct);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,73 @@
|
||||
// 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.proto;
|
||||
|
||||
import edu.wpi.first.math.MatBuilder;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.proto.Wpimath.ProtobufMatrix;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class MatrixProto<R extends Num, C extends Num>
|
||||
implements Protobuf<Matrix<R, C>, ProtobufMatrix> {
|
||||
private final Nat<R> m_rows;
|
||||
private final Nat<C> m_cols;
|
||||
|
||||
/**
|
||||
* Constructs the {@link Protobuf} implementation.
|
||||
*
|
||||
* @param rows The number of rows of the matrices this serializer processes.
|
||||
* @param cols The number of cols of the matrices this serializer processes.
|
||||
*/
|
||||
public MatrixProto(Nat<R> rows, Nat<C> cols) {
|
||||
m_rows = rows;
|
||||
m_cols = cols;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Class<Matrix<R, C>> getTypeClass() {
|
||||
@SuppressWarnings("unchecked")
|
||||
var clazz = (Class<Matrix<R, C>>) (Class<?>) Matrix.class;
|
||||
return clazz;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufMatrix.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufMatrix createMessage() {
|
||||
return ProtobufMatrix.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Matrix<R, C> unpack(ProtobufMatrix msg) {
|
||||
if (msg.getNumRows() != m_rows.getNum() || msg.getNumCols() != m_cols.getNum()) {
|
||||
throw new IllegalArgumentException(
|
||||
"Tried to unpack msg "
|
||||
+ msg
|
||||
+ " with "
|
||||
+ msg.getNumRows()
|
||||
+ " rows and "
|
||||
+ msg.getNumCols()
|
||||
+ " columns into Matrix with "
|
||||
+ m_rows.getNum()
|
||||
+ " rows and "
|
||||
+ m_cols.getNum()
|
||||
+ " columns");
|
||||
}
|
||||
return MatBuilder.fill(m_rows, m_cols, Protobuf.unpackArray(msg.getData()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufMatrix msg, Matrix<R, C> value) {
|
||||
msg.setNumRows(value.getNumRows());
|
||||
msg.setNumCols(value.getNumCols());
|
||||
Protobuf.packArray(msg.getMutableData(), value.getData());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,64 @@
|
||||
// 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.proto;
|
||||
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.Vector;
|
||||
import edu.wpi.first.math.proto.Wpimath.ProtobufVector;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public final class VectorProto<R extends Num> implements Protobuf<Vector<R>, ProtobufVector> {
|
||||
private final Nat<R> m_rows;
|
||||
|
||||
/**
|
||||
* Constructs the {@link Protobuf} implementation.
|
||||
*
|
||||
* @param rows The number of rows of the vectors this serializer processes.
|
||||
*/
|
||||
public VectorProto(Nat<R> rows) {
|
||||
m_rows = rows;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Class<Vector<R>> getTypeClass() {
|
||||
@SuppressWarnings("unchecked")
|
||||
var clazz = (Class<Vector<R>>) (Class<?>) Vector.class;
|
||||
return clazz;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufVector.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufVector createMessage() {
|
||||
return ProtobufVector.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Vector<R> unpack(ProtobufVector msg) {
|
||||
if (msg.getRows().length() != m_rows.getNum()) {
|
||||
throw new IllegalArgumentException(
|
||||
"Tried to unpack msg "
|
||||
+ msg
|
||||
+ " with "
|
||||
+ msg.getRows().length()
|
||||
+ " rows into Vector with "
|
||||
+ m_rows.getNum()
|
||||
+ " rows");
|
||||
}
|
||||
var storage = new SimpleMatrix(Protobuf.unpackArray(msg.getRows()));
|
||||
return new Vector<R>(storage);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufVector msg, Vector<R> value) {
|
||||
Protobuf.packArray(msg.getMutableRows(), value.getData());
|
||||
}
|
||||
}
|
||||
@@ -4,13 +4,29 @@
|
||||
|
||||
package edu.wpi.first.math.spline;
|
||||
|
||||
import edu.wpi.first.math.spline.proto.CubicHermiteSplineProto;
|
||||
import edu.wpi.first.math.spline.struct.CubicHermiteSplineStruct;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
/** Represents a hermite spline of degree 3. */
|
||||
public class CubicHermiteSpline extends Spline {
|
||||
public class CubicHermiteSpline extends Spline implements ProtobufSerializable, StructSerializable {
|
||||
private static SimpleMatrix hermiteBasis;
|
||||
private final SimpleMatrix m_coefficients;
|
||||
|
||||
/** The control vector for the initial point in the x dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] xInitialControlVector;
|
||||
|
||||
/** The control vector for the final point in the x dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] xFinalControlVector;
|
||||
|
||||
/** The control vector for the initial point in the y dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] yInitialControlVector;
|
||||
|
||||
/** The control vector for the final point in the y dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] yFinalControlVector;
|
||||
|
||||
private final ControlVector m_initialControlVector;
|
||||
private final ControlVector m_finalControlVector;
|
||||
|
||||
@@ -23,12 +39,17 @@ public class CubicHermiteSpline extends Spline {
|
||||
* @param yInitialControlVector The control vector for the initial point in the y dimension.
|
||||
* @param yFinalControlVector The control vector for the final point in the y dimension.
|
||||
*/
|
||||
@SuppressWarnings("PMD.ArrayIsStoredDirectly")
|
||||
public CubicHermiteSpline(
|
||||
double[] xInitialControlVector,
|
||||
double[] xFinalControlVector,
|
||||
double[] yInitialControlVector,
|
||||
double[] yFinalControlVector) {
|
||||
super(3);
|
||||
this.xInitialControlVector = xInitialControlVector;
|
||||
this.xFinalControlVector = xFinalControlVector;
|
||||
this.yInitialControlVector = yInitialControlVector;
|
||||
this.yFinalControlVector = yFinalControlVector;
|
||||
|
||||
// Populate the coefficients for the actual spline equations.
|
||||
// Row 0 is x coefficients
|
||||
@@ -163,4 +184,10 @@ public class CubicHermiteSpline extends Spline {
|
||||
finalVector[0], finalVector[1]
|
||||
});
|
||||
}
|
||||
|
||||
/** CubicHermiteSpline struct for serialization. */
|
||||
public static final CubicHermiteSplineProto proto = new CubicHermiteSplineProto();
|
||||
|
||||
/** CubicHermiteSpline protobuf for serialization. */
|
||||
public static final CubicHermiteSplineStruct struct = new CubicHermiteSplineStruct();
|
||||
}
|
||||
|
||||
@@ -4,13 +4,30 @@
|
||||
|
||||
package edu.wpi.first.math.spline;
|
||||
|
||||
import edu.wpi.first.math.spline.proto.QuinticHermiteSplineProto;
|
||||
import edu.wpi.first.math.spline.struct.QuinticHermiteSplineStruct;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
/** Represents a hermite spline of degree 5. */
|
||||
public class QuinticHermiteSpline extends Spline {
|
||||
public class QuinticHermiteSpline extends Spline
|
||||
implements ProtobufSerializable, StructSerializable {
|
||||
private static SimpleMatrix hermiteBasis;
|
||||
private final SimpleMatrix m_coefficients;
|
||||
|
||||
/** The control vector for the initial point in the x dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] xInitialControlVector;
|
||||
|
||||
/** The control vector for the final point in the x dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] xFinalControlVector;
|
||||
|
||||
/** The control vector for the initial point in the y dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] yInitialControlVector;
|
||||
|
||||
/** The control vector for the final point in the y dimension. DO NOT MODIFY THIS ARRAY! */
|
||||
public final double[] yFinalControlVector;
|
||||
|
||||
private final ControlVector m_initialControlVector;
|
||||
private final ControlVector m_finalControlVector;
|
||||
|
||||
@@ -23,12 +40,17 @@ public class QuinticHermiteSpline extends Spline {
|
||||
* @param yInitialControlVector The control vector for the initial point in the y dimension.
|
||||
* @param yFinalControlVector The control vector for the final point in the y dimension.
|
||||
*/
|
||||
@SuppressWarnings("PMD.ArrayIsStoredDirectly")
|
||||
public QuinticHermiteSpline(
|
||||
double[] xInitialControlVector,
|
||||
double[] xFinalControlVector,
|
||||
double[] yInitialControlVector,
|
||||
double[] yFinalControlVector) {
|
||||
super(5);
|
||||
this.xInitialControlVector = xInitialControlVector;
|
||||
this.yInitialControlVector = yInitialControlVector;
|
||||
this.xFinalControlVector = xFinalControlVector;
|
||||
this.yFinalControlVector = yFinalControlVector;
|
||||
|
||||
// Populate the coefficients for the actual spline equations.
|
||||
// Row 0 is x coefficients
|
||||
@@ -171,4 +193,10 @@ public class QuinticHermiteSpline extends Spline {
|
||||
finalVector[0], finalVector[1], finalVector[2]
|
||||
});
|
||||
}
|
||||
|
||||
/** QuinticHermiteSpline struct for serialization. */
|
||||
public static final QuinticHermiteSplineProto proto = new QuinticHermiteSplineProto();
|
||||
|
||||
/** QuinticHermiteSpline protobuf for serialization. */
|
||||
public static final QuinticHermiteSplineStruct struct = new QuinticHermiteSplineStruct();
|
||||
}
|
||||
|
||||
@@ -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.spline.proto;
|
||||
|
||||
import edu.wpi.first.math.proto.Spline.ProtobufCubicHermiteSpline;
|
||||
import edu.wpi.first.math.spline.CubicHermiteSpline;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public final class CubicHermiteSplineProto
|
||||
implements Protobuf<CubicHermiteSpline, ProtobufCubicHermiteSpline> {
|
||||
@Override
|
||||
public Class<CubicHermiteSpline> getTypeClass() {
|
||||
return CubicHermiteSpline.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufCubicHermiteSpline.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufCubicHermiteSpline createMessage() {
|
||||
return ProtobufCubicHermiteSpline.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public CubicHermiteSpline unpack(ProtobufCubicHermiteSpline msg) {
|
||||
return new CubicHermiteSpline(
|
||||
Protobuf.unpackArray(msg.getXInitial()),
|
||||
Protobuf.unpackArray(msg.getXFinal()),
|
||||
Protobuf.unpackArray(msg.getYInitial()),
|
||||
Protobuf.unpackArray(msg.getYFinal()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufCubicHermiteSpline msg, CubicHermiteSpline value) {
|
||||
Protobuf.packArray(msg.getMutableXInitial(), value.xInitialControlVector);
|
||||
Protobuf.packArray(msg.getMutableXFinal(), value.xFinalControlVector);
|
||||
Protobuf.packArray(msg.getMutableYInitial(), value.yInitialControlVector);
|
||||
Protobuf.packArray(msg.getMutableYFinal(), value.yFinalControlVector);
|
||||
}
|
||||
}
|
||||
@@ -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.spline.proto;
|
||||
|
||||
import edu.wpi.first.math.proto.Spline.ProtobufQuinticHermiteSpline;
|
||||
import edu.wpi.first.math.spline.QuinticHermiteSpline;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public final class QuinticHermiteSplineProto
|
||||
implements Protobuf<QuinticHermiteSpline, ProtobufQuinticHermiteSpline> {
|
||||
@Override
|
||||
public Class<QuinticHermiteSpline> getTypeClass() {
|
||||
return QuinticHermiteSpline.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufQuinticHermiteSpline.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufQuinticHermiteSpline createMessage() {
|
||||
return ProtobufQuinticHermiteSpline.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public QuinticHermiteSpline unpack(ProtobufQuinticHermiteSpline msg) {
|
||||
return new QuinticHermiteSpline(
|
||||
Protobuf.unpackArray(msg.getXInitial()),
|
||||
Protobuf.unpackArray(msg.getXFinal()),
|
||||
Protobuf.unpackArray(msg.getYInitial()),
|
||||
Protobuf.unpackArray(msg.getYFinal()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufQuinticHermiteSpline msg, QuinticHermiteSpline value) {
|
||||
Protobuf.packArray(msg.getMutableXInitial(), value.xInitialControlVector);
|
||||
Protobuf.packArray(msg.getMutableXFinal(), value.xFinalControlVector);
|
||||
Protobuf.packArray(msg.getMutableYInitial(), value.yInitialControlVector);
|
||||
Protobuf.packArray(msg.getMutableYFinal(), value.yFinalControlVector);
|
||||
}
|
||||
}
|
||||
@@ -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.spline.struct;
|
||||
|
||||
import edu.wpi.first.math.spline.CubicHermiteSpline;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public final class CubicHermiteSplineStruct implements Struct<CubicHermiteSpline> {
|
||||
@Override
|
||||
public Class<CubicHermiteSpline> getTypeClass() {
|
||||
return CubicHermiteSpline.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "CubicHermiteSpline";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 4 * 2;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double xInitial[2];double xFinal[2];double yInitial[2];double yFinal[2]";
|
||||
}
|
||||
|
||||
@Override
|
||||
public CubicHermiteSpline unpack(ByteBuffer bb) {
|
||||
return new CubicHermiteSpline(
|
||||
Struct.unpackDoubleArray(bb, 2),
|
||||
Struct.unpackDoubleArray(bb, 2),
|
||||
Struct.unpackDoubleArray(bb, 2),
|
||||
Struct.unpackDoubleArray(bb, 2));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, CubicHermiteSpline value) {
|
||||
Struct.packArray(bb, value.xInitialControlVector);
|
||||
Struct.packArray(bb, value.xFinalControlVector);
|
||||
Struct.packArray(bb, value.yInitialControlVector);
|
||||
Struct.packArray(bb, value.yFinalControlVector);
|
||||
}
|
||||
}
|
||||
@@ -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.spline.struct;
|
||||
|
||||
import edu.wpi.first.math.spline.QuinticHermiteSpline;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public final class QuinticHermiteSplineStruct implements Struct<QuinticHermiteSpline> {
|
||||
@Override
|
||||
public Class<QuinticHermiteSpline> getTypeClass() {
|
||||
return QuinticHermiteSpline.class;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "QuinticHermiteSpline";
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * 4 * 3;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double xInitial[3];double xFinal[3];double yInitial[3];double yFinal[3]";
|
||||
}
|
||||
|
||||
@Override
|
||||
public QuinticHermiteSpline unpack(ByteBuffer bb) {
|
||||
return new QuinticHermiteSpline(
|
||||
Struct.unpackDoubleArray(bb, 3),
|
||||
Struct.unpackDoubleArray(bb, 3),
|
||||
Struct.unpackDoubleArray(bb, 3),
|
||||
Struct.unpackDoubleArray(bb, 3));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, QuinticHermiteSpline value) {
|
||||
Struct.packArray(bb, value.xInitialControlVector);
|
||||
Struct.packArray(bb, value.xFinalControlVector);
|
||||
Struct.packArray(bb, value.yInitialControlVector);
|
||||
Struct.packArray(bb, value.yFinalControlVector);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,61 @@
|
||||
// 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.struct;
|
||||
|
||||
import edu.wpi.first.math.MatBuilder;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public final class MatrixStruct<R extends Num, C extends Num> implements Struct<Matrix<R, C>> {
|
||||
private final Nat<R> m_rows;
|
||||
private final Nat<C> m_cols;
|
||||
|
||||
/**
|
||||
* Constructs the {@link Struct} implementation.
|
||||
*
|
||||
* @param rows The number of rows of the matrices this serializer processes.
|
||||
* @param cols The number of cols of the matrices this serializer processes.
|
||||
*/
|
||||
public MatrixStruct(Nat<R> rows, Nat<C> cols) {
|
||||
m_rows = rows;
|
||||
m_cols = cols;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Class<Matrix<R, C>> getTypeClass() {
|
||||
@SuppressWarnings("unchecked")
|
||||
var clazz = (Class<Matrix<R, C>>) (Class<?>) Matrix.class;
|
||||
return clazz;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "Matrix__" + m_rows.getNum() + "_" + m_cols.getNum();
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * m_rows.getNum() * m_cols.getNum();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double data[" + (m_rows.getNum() * m_cols.getNum()) + "]";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Matrix<R, C> unpack(ByteBuffer bb) {
|
||||
return MatBuilder.fill(
|
||||
m_rows, m_cols, Struct.unpackDoubleArray(bb, m_rows.getNum() * m_cols.getNum()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, Matrix<R, C> value) {
|
||||
Struct.packArray(bb, value.getData());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,58 @@
|
||||
// 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.struct;
|
||||
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.Vector;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
import org.ejml.simple.SimpleMatrix;
|
||||
|
||||
public final class VectorStruct<R extends Num> implements Struct<Vector<R>> {
|
||||
private final int m_rows;
|
||||
|
||||
/**
|
||||
* Constructs the {@link Struct} implementation.
|
||||
*
|
||||
* @param rows The number of rows of the vectors this serializer processes.
|
||||
*/
|
||||
public VectorStruct(Nat<R> rows) {
|
||||
m_rows = rows.getNum();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Class<Vector<R>> getTypeClass() {
|
||||
@SuppressWarnings("unchecked")
|
||||
var clazz = (Class<Vector<R>>) (Class<?>) Vector.class;
|
||||
return clazz;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "Vector__" + m_rows;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return kSizeDouble * m_rows;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return "double data[" + m_rows + "]";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Vector<R> unpack(ByteBuffer bb) {
|
||||
var storage = new SimpleMatrix(Struct.unpackDoubleArray(bb, m_rows));
|
||||
return new Vector<R>(storage);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, Vector<R> value) {
|
||||
Struct.packArray(bb, value.getData());
|
||||
}
|
||||
}
|
||||
@@ -5,6 +5,7 @@
|
||||
package edu.wpi.first.math.system;
|
||||
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N10;
|
||||
@@ -26,6 +27,12 @@ import edu.wpi.first.math.numbers.N6;
|
||||
import edu.wpi.first.math.numbers.N7;
|
||||
import edu.wpi.first.math.numbers.N8;
|
||||
import edu.wpi.first.math.numbers.N9;
|
||||
import edu.wpi.first.math.system.proto.LinearSystemProto;
|
||||
import edu.wpi.first.math.system.struct.LinearSystemStruct;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Arrays;
|
||||
import java.util.Collections;
|
||||
import java.util.List;
|
||||
@@ -44,7 +51,8 @@ import org.ejml.simple.SimpleMatrix;
|
||||
* @param <Inputs> Number of inputs.
|
||||
* @param <Outputs> Number of outputs.
|
||||
*/
|
||||
public class LinearSystem<States extends Num, Inputs extends Num, Outputs extends Num> {
|
||||
public class LinearSystem<States extends Num, Inputs extends Num, Outputs extends Num>
|
||||
implements ProtobufSerializable, StructSerializable {
|
||||
/** Continuous system matrix. */
|
||||
private final Matrix<States, States> m_A;
|
||||
|
||||
@@ -361,4 +369,38 @@ public class LinearSystem<States extends Num, Inputs extends Num, Outputs extend
|
||||
"Linear System: A\n%s\n\nB:\n%s\n\nC:\n%s\n\nD:\n%s\n",
|
||||
m_A.toString(), m_B.toString(), m_C.toString(), m_D.toString());
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an implementation of the {@link Protobuf} interface for linear systems.
|
||||
*
|
||||
* @param <States> The number of states of the linear systems this serializer processes.
|
||||
* @param <Inputs> The number of inputs of the linear systems this serializer processes.
|
||||
* @param <Outputs> The number of outputs of the linear systems this serializer processes.
|
||||
* @param states The number of states of the linear systems this serializer processes.
|
||||
* @param inputs The number of inputs of the linear systems this serializer processes.
|
||||
* @param outputs The number of outputs of the linear systems this serializer processes.
|
||||
* @return The protobuf implementation.
|
||||
*/
|
||||
public static <States extends Num, Inputs extends Num, Outputs extends Num>
|
||||
LinearSystemProto<States, Inputs, Outputs> getProto(
|
||||
Nat<States> states, Nat<Inputs> inputs, Nat<Outputs> outputs) {
|
||||
return new LinearSystemProto<>(states, inputs, outputs);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an implementation of the {@link Struct} interface for linear systems.
|
||||
*
|
||||
* @param <States> The number of states of the linear systems this serializer processes.
|
||||
* @param <Inputs> The number of inputs of the linear systems this serializer processes.
|
||||
* @param <Outputs> The number of outputs of the linear systems this serializer processes.
|
||||
* @param states The number of states of the linear systems this serializer processes.
|
||||
* @param inputs The number of inputs of the linear systems this serializer processes.
|
||||
* @param outputs The number of outputs of the linear systems this serializer processes.
|
||||
* @return The struct implementation.
|
||||
*/
|
||||
public static <States extends Num, Inputs extends Num, Outputs extends Num>
|
||||
LinearSystemStruct<States, Inputs, Outputs> getStruct(
|
||||
Nat<States> states, Nat<Inputs> inputs, Nat<Outputs> outputs) {
|
||||
return new LinearSystemStruct<>(states, inputs, outputs);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,99 @@
|
||||
// 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.proto;
|
||||
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.proto.System.ProtobufLinearSystem;
|
||||
import edu.wpi.first.math.proto.Wpimath.ProtobufMatrix;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public final class LinearSystemProto<States extends Num, Inputs extends Num, Outputs extends Num>
|
||||
implements Protobuf<LinearSystem<States, Inputs, Outputs>, ProtobufLinearSystem> {
|
||||
private final Nat<States> m_states;
|
||||
private final Nat<Inputs> m_inputs;
|
||||
private final Nat<Outputs> m_outputs;
|
||||
private final Protobuf<Matrix<States, States>, ProtobufMatrix> m_AProto;
|
||||
private final Protobuf<Matrix<States, Inputs>, ProtobufMatrix> m_BProto;
|
||||
private final Protobuf<Matrix<Outputs, States>, ProtobufMatrix> m_CProto;
|
||||
private final Protobuf<Matrix<Outputs, Inputs>, ProtobufMatrix> m_DProto;
|
||||
|
||||
/**
|
||||
* Constructs the {@link Protobuf} implementation.
|
||||
*
|
||||
* @param states The number of states of the linear systems this serializer processes.
|
||||
* @param inputs The number of inputs of the linear systems this serializer processes.
|
||||
* @param outputs The number of outputs of the linear systems this serializer processes.
|
||||
*/
|
||||
public LinearSystemProto(Nat<States> states, Nat<Inputs> inputs, Nat<Outputs> outputs) {
|
||||
m_states = states;
|
||||
m_inputs = inputs;
|
||||
m_outputs = outputs;
|
||||
m_AProto = Matrix.getProto(states, states);
|
||||
m_BProto = Matrix.getProto(states, inputs);
|
||||
m_CProto = Matrix.getProto(outputs, states);
|
||||
m_DProto = Matrix.getProto(outputs, inputs);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Class<LinearSystem<States, Inputs, Outputs>> getTypeClass() {
|
||||
@SuppressWarnings("unchecked")
|
||||
var clazz = (Class<LinearSystem<States, Inputs, Outputs>>) (Class<?>) LinearSystem.class;
|
||||
return clazz;
|
||||
}
|
||||
|
||||
@Override
|
||||
public Descriptor getDescriptor() {
|
||||
return ProtobufLinearSystem.getDescriptor();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ProtobufLinearSystem createMessage() {
|
||||
return ProtobufLinearSystem.newInstance();
|
||||
}
|
||||
|
||||
@Override
|
||||
public LinearSystem<States, Inputs, Outputs> unpack(ProtobufLinearSystem msg) {
|
||||
if (msg.getNumStates() != m_states.getNum()
|
||||
|| msg.getNumInputs() != m_inputs.getNum()
|
||||
|| msg.getNumOutputs() != m_outputs.getNum()) {
|
||||
throw new IllegalArgumentException(
|
||||
"Tried to unpack msg "
|
||||
+ msg
|
||||
+ " with "
|
||||
+ msg.getNumStates()
|
||||
+ " states and "
|
||||
+ msg.getNumInputs()
|
||||
+ " inputs and "
|
||||
+ msg.getNumOutputs()
|
||||
+ " outputs into LinearSystem with "
|
||||
+ m_states.getNum()
|
||||
+ " states "
|
||||
+ m_inputs.getNum()
|
||||
+ " inputs "
|
||||
+ m_outputs.getNum()
|
||||
+ " outputs");
|
||||
}
|
||||
return new LinearSystem<>(
|
||||
m_AProto.unpack(msg.getA()),
|
||||
m_BProto.unpack(msg.getB()),
|
||||
m_CProto.unpack(msg.getC()),
|
||||
m_DProto.unpack(msg.getD()));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ProtobufLinearSystem msg, LinearSystem<States, Inputs, Outputs> value) {
|
||||
msg.setNumStates(m_states.getNum())
|
||||
.setNumInputs(m_inputs.getNum())
|
||||
.setNumOutputs(m_outputs.getNum());
|
||||
m_AProto.pack(msg.getMutableA(), value.getA());
|
||||
m_BProto.pack(msg.getMutableB(), value.getB());
|
||||
m_CProto.pack(msg.getMutableC(), value.getC());
|
||||
m_DProto.pack(msg.getMutableD(), value.getD());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,89 @@
|
||||
// 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.struct;
|
||||
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.Num;
|
||||
import edu.wpi.first.math.struct.MatrixStruct;
|
||||
import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public final class LinearSystemStruct<States extends Num, Inputs extends Num, Outputs extends Num>
|
||||
implements Struct<LinearSystem<States, Inputs, Outputs>> {
|
||||
private final int m_states;
|
||||
private final int m_inputs;
|
||||
private final int m_outputs;
|
||||
private final MatrixStruct<States, States> m_AStruct;
|
||||
private final MatrixStruct<States, Inputs> m_BStruct;
|
||||
private final MatrixStruct<Outputs, States> m_CStruct;
|
||||
private final MatrixStruct<Outputs, Inputs> m_DStruct;
|
||||
|
||||
/**
|
||||
* Constructs the {@link Struct} implementation.
|
||||
*
|
||||
* @param states The number of states of the linear systems this serializer processes.
|
||||
* @param inputs The number of inputs of the linear systems this serializer processes.
|
||||
* @param outputs The number of outputs of the linear systems this serializer processes.
|
||||
*/
|
||||
public LinearSystemStruct(Nat<States> states, Nat<Inputs> inputs, Nat<Outputs> outputs) {
|
||||
m_states = states.getNum();
|
||||
m_inputs = inputs.getNum();
|
||||
m_outputs = outputs.getNum();
|
||||
m_AStruct = Matrix.getStruct(states, states);
|
||||
m_BStruct = Matrix.getStruct(states, inputs);
|
||||
m_CStruct = Matrix.getStruct(outputs, states);
|
||||
m_DStruct = Matrix.getStruct(outputs, inputs);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Class<LinearSystem<States, Inputs, Outputs>> getTypeClass() {
|
||||
@SuppressWarnings("unchecked")
|
||||
var clazz = (Class<LinearSystem<States, Inputs, Outputs>>) (Class<?>) LinearSystem.class;
|
||||
return clazz;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeName() {
|
||||
return "LinearSystem__" + m_states + "_" + m_inputs + "_" + m_outputs;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getSize() {
|
||||
return m_AStruct.getSize() + m_BStruct.getSize() + m_CStruct.getSize() + m_DStruct.getSize();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSchema() {
|
||||
return m_AStruct.getTypeName()
|
||||
+ " a;"
|
||||
+ m_BStruct.getTypeName()
|
||||
+ " b;"
|
||||
+ m_CStruct.getTypeName()
|
||||
+ " c;"
|
||||
+ m_DStruct.getTypeName()
|
||||
+ " d";
|
||||
}
|
||||
|
||||
@Override
|
||||
public Struct<?>[] getNested() {
|
||||
return new Struct<?>[] {m_AStruct, m_BStruct, m_CStruct, m_DStruct};
|
||||
}
|
||||
|
||||
@Override
|
||||
public LinearSystem<States, Inputs, Outputs> unpack(ByteBuffer bb) {
|
||||
return new LinearSystem<>(
|
||||
m_AStruct.unpack(bb), m_BStruct.unpack(bb), m_CStruct.unpack(bb), m_DStruct.unpack(bb));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void pack(ByteBuffer bb, LinearSystem<States, Inputs, Outputs> value) {
|
||||
m_AStruct.pack(bb, value.getA());
|
||||
m_BStruct.pack(bb, value.getB());
|
||||
m_CStruct.pack(bb, value.getC());
|
||||
m_DStruct.pack(bb, value.getD());
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user