[wpiutil, ntcore] Add structured data support (#5391)

This adds support for two serialization formats for complex data types:

- Protobuf for complex objects with variable length internals that need forward and backward wire compatibility (lower speed, more flexible)
- Raw struct (ByteBuffer-style) for fixed-length objects (higher speed, less flexible)

Deserialization can be done either by creating a new object (for immutable objects) or overwriting the contents of an existing object (for mutable objects).

Implementing classes should provide inner classes that implement the Protobuf or Struct interface (in Java) or specialize the wpi::Protobuf or wpi::Struct struct (in C++). It is possible for classes to implement both. If the class itself does not implement serialization, it's possible for third parties/users to provide an implementation instead.

Uses the Google protobuf implementation for C++ and the QuickBuffers alternative protobuf implementation for Java.
This commit is contained in:
Peter Johnson
2023-10-19 21:41:47 -07:00
committed by GitHub
parent ecb7cfa9ef
commit cf54d9ccb7
133 changed files with 13506 additions and 90 deletions

View File

@@ -9,10 +9,15 @@ import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.interpolation.Interpolatable;
import edu.wpi.first.math.proto.Geometry2D.ProtobufPose2d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Collections;
import java.util.Comparator;
import java.util.List;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/** Represents a 2D pose containing translational and rotational elements. */
@JsonIgnoreProperties(ignoreUnknown = true)
@@ -305,4 +310,83 @@ public class Pose2d implements Interpolatable<Pose2d> {
return this.exp(scaledTwist);
}
}
public static final class AStruct implements Struct<Pose2d> {
@Override
public Class<Pose2d> getTypeClass() {
return Pose2d.class;
}
@Override
public String getTypeString() {
return "struct:Pose2d";
}
@Override
public int getSize() {
return Translation2d.struct.getSize() + Rotation2d.struct.getSize();
}
@Override
public String getSchema() {
return "Translation2d translation;Rotation2d rotation";
}
@Override
public Struct<?>[] getNested() {
return new Struct<?>[] {Translation2d.struct, Rotation2d.struct};
}
@Override
public Pose2d unpack(ByteBuffer bb) {
Translation2d translation = Translation2d.struct.unpack(bb);
Rotation2d rotation = Rotation2d.struct.unpack(bb);
return new Pose2d(translation, rotation);
}
@Override
public void pack(ByteBuffer bb, Pose2d value) {
Translation2d.struct.pack(bb, value.m_translation);
Rotation2d.struct.pack(bb, value.m_rotation);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Pose2d, ProtobufPose2d> {
@Override
public Class<Pose2d> getTypeClass() {
return Pose2d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufPose2d.getDescriptor();
}
@Override
public Protobuf<?, ?>[] getNested() {
return new Protobuf<?, ?>[] {Translation2d.proto, Rotation2d.proto};
}
@Override
public ProtobufPose2d createMessage() {
return ProtobufPose2d.newInstance();
}
@Override
public Pose2d unpack(ProtobufPose2d msg) {
return new Pose2d(
Translation2d.proto.unpack(msg.getTranslation()),
Rotation2d.proto.unpack(msg.getRotation()));
}
@Override
public void pack(ProtobufPose2d msg, Pose2d value) {
Translation2d.proto.pack(msg.getMutableTranslation(), value.m_translation);
Rotation2d.proto.pack(msg.getMutableRotation(), value.m_rotation);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -10,7 +10,12 @@ import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.WPIMathJNI;
import edu.wpi.first.math.interpolation.Interpolatable;
import edu.wpi.first.math.proto.Geometry3D.ProtobufPose3d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/** Represents a 3D pose containing translational and rotational elements. */
@JsonIgnoreProperties(ignoreUnknown = true)
@@ -318,4 +323,83 @@ public class Pose3d implements Interpolatable<Pose3d> {
return this.exp(scaledTwist);
}
}
public static final class AStruct implements Struct<Pose3d> {
@Override
public Class<Pose3d> getTypeClass() {
return Pose3d.class;
}
@Override
public String getTypeString() {
return "struct:Pose3d";
}
@Override
public int getSize() {
return Translation3d.struct.getSize() + Rotation3d.struct.getSize();
}
@Override
public String getSchema() {
return "Translation3d translation;Rotation3d rotation";
}
@Override
public Struct<?>[] getNested() {
return new Struct<?>[] {Translation3d.struct, Rotation3d.struct};
}
@Override
public Pose3d unpack(ByteBuffer bb) {
Translation3d translation = Translation3d.struct.unpack(bb);
Rotation3d rotation = Rotation3d.struct.unpack(bb);
return new Pose3d(translation, rotation);
}
@Override
public void pack(ByteBuffer bb, Pose3d value) {
Translation3d.struct.pack(bb, value.m_translation);
Rotation3d.struct.pack(bb, value.m_rotation);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Pose3d, ProtobufPose3d> {
@Override
public Class<Pose3d> getTypeClass() {
return Pose3d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufPose3d.getDescriptor();
}
@Override
public Protobuf<?, ?>[] getNested() {
return new Protobuf<?, ?>[] {Translation3d.proto, Rotation3d.proto};
}
@Override
public ProtobufPose3d createMessage() {
return ProtobufPose3d.newInstance();
}
@Override
public Pose3d unpack(ProtobufPose3d msg) {
return new Pose3d(
Translation3d.proto.unpack(msg.getTranslation()),
Rotation3d.proto.unpack(msg.getRotation()));
}
@Override
public void pack(ProtobufPose3d msg, Pose3d value) {
Translation3d.proto.pack(msg.getMutableTranslation(), value.m_translation);
Rotation3d.proto.pack(msg.getMutableRotation(), value.m_rotation);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -11,7 +11,12 @@ import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.Vector;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.proto.Geometry3D.ProtobufQuaternion;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
@@ -400,4 +405,74 @@ public class Quaternion {
return VecBuilder.fill(coeff * getX(), coeff * getY(), coeff * getZ());
}
public static final class AStruct implements Struct<Quaternion> {
@Override
public Class<Quaternion> getTypeClass() {
return Quaternion.class;
}
@Override
public String getTypeString() {
return "struct:Quaternion";
}
@Override
public int getSize() {
return kSizeDouble * 4;
}
@Override
public String getSchema() {
return "double w;double x;double y;double z";
}
@Override
public Quaternion unpack(ByteBuffer bb) {
double w = bb.getDouble();
double x = bb.getDouble();
double y = bb.getDouble();
double z = bb.getDouble();
return new Quaternion(w, x, y, z);
}
@Override
public void pack(ByteBuffer bb, Quaternion value) {
bb.putDouble(value.getW());
bb.putDouble(value.getX());
bb.putDouble(value.getY());
bb.putDouble(value.getZ());
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Quaternion, ProtobufQuaternion> {
@Override
public Class<Quaternion> getTypeClass() {
return Quaternion.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufQuaternion.getDescriptor();
}
@Override
public ProtobufQuaternion createMessage() {
return ProtobufQuaternion.newInstance();
}
@Override
public Quaternion unpack(ProtobufQuaternion msg) {
return new Quaternion(msg.getW(), msg.getX(), msg.getY(), msg.getZ());
}
@Override
public void pack(ProtobufQuaternion msg, Quaternion value) {
msg.setW(value.getW()).setX(value.getX()).setY(value.getY()).setZ(value.getZ());
}
}
public static final AProto proto = new AProto();
}

View File

@@ -10,8 +10,13 @@ import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.interpolation.Interpolatable;
import edu.wpi.first.math.proto.Geometry2D.ProtobufRotation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/**
* A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
@@ -256,4 +261,67 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
public Rotation2d interpolate(Rotation2d endValue, double t) {
return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1)));
}
public static final class AStruct implements Struct<Rotation2d> {
@Override
public Class<Rotation2d> getTypeClass() {
return Rotation2d.class;
}
@Override
public String getTypeString() {
return "struct:Rotation2d";
}
@Override
public int getSize() {
return kSizeDouble;
}
@Override
public String getSchema() {
return "double value";
}
@Override
public Rotation2d unpack(ByteBuffer bb) {
return new Rotation2d(bb.getDouble());
}
@Override
public void pack(ByteBuffer bb, Rotation2d value) {
bb.putDouble(value.m_value);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Rotation2d, ProtobufRotation2d> {
@Override
public Class<Rotation2d> getTypeClass() {
return Rotation2d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufRotation2d.getDescriptor();
}
@Override
public ProtobufRotation2d createMessage() {
return ProtobufRotation2d.newInstance();
}
@Override
public Rotation2d unpack(ProtobufRotation2d msg) {
return new Rotation2d(msg.getValue());
}
@Override
public void pack(ProtobufRotation2d msg, Rotation2d value) {
msg.setValue(value.m_value);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -17,8 +17,13 @@ import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.Vector;
import edu.wpi.first.math.interpolation.Interpolatable;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.proto.Geometry3D.ProtobufRotation3d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import org.ejml.dense.row.factory.DecompositionFactory_DDRM;
import us.hebi.quickbuf.Descriptors.Descriptor;
/** A rotation in a 3D coordinate frame represented by a quaternion. */
@JsonIgnoreProperties(ignoreUnknown = true)
@@ -434,4 +439,77 @@ public class Rotation3d implements Interpolatable<Rotation3d> {
public Rotation3d interpolate(Rotation3d endValue, double t) {
return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1)));
}
public static final class AStruct implements Struct<Rotation3d> {
@Override
public Class<Rotation3d> getTypeClass() {
return Rotation3d.class;
}
@Override
public String getTypeString() {
return "struct:Rotation3d";
}
@Override
public int getSize() {
return Quaternion.struct.getSize();
}
@Override
public String getSchema() {
return "Quaternion q";
}
@Override
public Struct<?>[] getNested() {
return new Struct<?>[] {Quaternion.struct};
}
@Override
public Rotation3d unpack(ByteBuffer bb) {
return new Rotation3d(Quaternion.struct.unpack(bb));
}
@Override
public void pack(ByteBuffer bb, Rotation3d value) {
Quaternion.struct.pack(bb, value.m_q);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Rotation3d, ProtobufRotation3d> {
@Override
public Class<Rotation3d> getTypeClass() {
return Rotation3d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufRotation3d.getDescriptor();
}
@Override
public Protobuf<?, ?>[] getNested() {
return new Protobuf<?, ?>[] {Quaternion.proto};
}
@Override
public ProtobufRotation3d createMessage() {
return ProtobufRotation3d.newInstance();
}
@Override
public Rotation3d unpack(ProtobufRotation3d msg) {
return new Rotation3d(Quaternion.proto.unpack(msg.getQ()));
}
@Override
public void pack(ProtobufRotation3d msg, Rotation3d value) {
Quaternion.proto.pack(msg.getMutableQ(), value.m_q);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -4,7 +4,12 @@
package edu.wpi.first.math.geometry;
import edu.wpi.first.math.proto.Geometry2D.ProtobufTransform2d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/** Represents a transformation for a Pose2d in the pose's frame. */
public class Transform2d {
@@ -163,4 +168,83 @@ public class Transform2d {
public int hashCode() {
return Objects.hash(m_translation, m_rotation);
}
public static final class AStruct implements Struct<Transform2d> {
@Override
public Class<Transform2d> getTypeClass() {
return Transform2d.class;
}
@Override
public String getTypeString() {
return "struct:Transform2d";
}
@Override
public int getSize() {
return Translation2d.struct.getSize() + Rotation2d.struct.getSize();
}
@Override
public String getSchema() {
return "Translation2d translation;Rotation2d rotation";
}
@Override
public Struct<?>[] getNested() {
return new Struct<?>[] {Translation2d.struct, Rotation2d.struct};
}
@Override
public Transform2d unpack(ByteBuffer bb) {
Translation2d translation = Translation2d.struct.unpack(bb);
Rotation2d rotation = Rotation2d.struct.unpack(bb);
return new Transform2d(translation, rotation);
}
@Override
public void pack(ByteBuffer bb, Transform2d value) {
Translation2d.struct.pack(bb, value.m_translation);
Rotation2d.struct.pack(bb, value.m_rotation);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Transform2d, ProtobufTransform2d> {
@Override
public Class<Transform2d> getTypeClass() {
return Transform2d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufTransform2d.getDescriptor();
}
@Override
public Protobuf<?, ?>[] getNested() {
return new Protobuf<?, ?>[] {Translation2d.proto, Rotation2d.proto};
}
@Override
public ProtobufTransform2d createMessage() {
return ProtobufTransform2d.newInstance();
}
@Override
public Transform2d unpack(ProtobufTransform2d msg) {
return new Transform2d(
Translation2d.proto.unpack(msg.getTranslation()),
Rotation2d.proto.unpack(msg.getRotation()));
}
@Override
public void pack(ProtobufTransform2d msg, Transform2d value) {
Translation2d.proto.pack(msg.getMutableTranslation(), value.m_translation);
Rotation2d.proto.pack(msg.getMutableRotation(), value.m_rotation);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -4,7 +4,12 @@
package edu.wpi.first.math.geometry;
import edu.wpi.first.math.proto.Geometry3D.ProtobufTransform3d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/** Represents a transformation for a Pose3d in the pose's frame. */
public class Transform3d {
@@ -173,4 +178,83 @@ public class Transform3d {
public int hashCode() {
return Objects.hash(m_translation, m_rotation);
}
public static final class AStruct implements Struct<Transform3d> {
@Override
public Class<Transform3d> getTypeClass() {
return Transform3d.class;
}
@Override
public String getTypeString() {
return "struct:Transform3d";
}
@Override
public int getSize() {
return Translation3d.struct.getSize() + Rotation3d.struct.getSize();
}
@Override
public String getSchema() {
return "Translation3d translation;Rotation3d rotation";
}
@Override
public Struct<?>[] getNested() {
return new Struct<?>[] {Translation3d.struct, Rotation3d.struct};
}
@Override
public Transform3d unpack(ByteBuffer bb) {
Translation3d translation = Translation3d.struct.unpack(bb);
Rotation3d rotation = Rotation3d.struct.unpack(bb);
return new Transform3d(translation, rotation);
}
@Override
public void pack(ByteBuffer bb, Transform3d value) {
Translation3d.struct.pack(bb, value.m_translation);
Rotation3d.struct.pack(bb, value.m_rotation);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Transform3d, ProtobufTransform3d> {
@Override
public Class<Transform3d> getTypeClass() {
return Transform3d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufTransform3d.getDescriptor();
}
@Override
public Protobuf<?, ?>[] getNested() {
return new Protobuf<?, ?>[] {Translation3d.proto, Rotation3d.proto};
}
@Override
public ProtobufTransform3d createMessage() {
return ProtobufTransform3d.newInstance();
}
@Override
public Transform3d unpack(ProtobufTransform3d msg) {
return new Transform3d(
Translation3d.proto.unpack(msg.getTranslation()),
Rotation3d.proto.unpack(msg.getRotation()));
}
@Override
public void pack(ProtobufTransform3d msg, Transform3d value) {
Translation3d.proto.pack(msg.getMutableTranslation(), value.m_translation);
Rotation3d.proto.pack(msg.getMutableRotation(), value.m_rotation);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -10,10 +10,15 @@ import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.interpolation.Interpolatable;
import edu.wpi.first.math.proto.Geometry2D.ProtobufTranslation2d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Collections;
import java.util.Comparator;
import java.util.List;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/**
* Represents a translation in 2D space. This object can be used to represent a point or a vector.
@@ -229,4 +234,70 @@ public class Translation2d implements Interpolatable<Translation2d> {
MathUtil.interpolate(this.getX(), endValue.getX(), t),
MathUtil.interpolate(this.getY(), endValue.getY(), t));
}
public static final class AStruct implements Struct<Translation2d> {
@Override
public Class<Translation2d> getTypeClass() {
return Translation2d.class;
}
@Override
public String getTypeString() {
return "struct:Translation2d";
}
@Override
public int getSize() {
return kSizeDouble * 2;
}
@Override
public String getSchema() {
return "double x;double y";
}
@Override
public Translation2d unpack(ByteBuffer bb) {
double x = bb.getDouble();
double y = bb.getDouble();
return new Translation2d(x, y);
}
@Override
public void pack(ByteBuffer bb, Translation2d value) {
bb.putDouble(value.m_x);
bb.putDouble(value.m_y);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Translation2d, ProtobufTranslation2d> {
@Override
public Class<Translation2d> getTypeClass() {
return Translation2d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufTranslation2d.getDescriptor();
}
@Override
public ProtobufTranslation2d createMessage() {
return ProtobufTranslation2d.newInstance();
}
@Override
public Translation2d unpack(ProtobufTranslation2d msg) {
return new Translation2d(msg.getX(), msg.getY());
}
@Override
public void pack(ProtobufTranslation2d msg, Translation2d value) {
msg.setX(value.m_x).setY(value.m_y);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -10,7 +10,12 @@ import com.fasterxml.jackson.annotation.JsonIgnoreProperties;
import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.interpolation.Interpolatable;
import edu.wpi.first.math.proto.Geometry3D.ProtobufTranslation3d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/**
* Represents a translation in 3D space. This object can be used to represent a point or a vector.
@@ -231,4 +236,72 @@ public class Translation3d implements Interpolatable<Translation3d> {
MathUtil.interpolate(this.getY(), endValue.getY(), t),
MathUtil.interpolate(this.getZ(), endValue.getZ(), t));
}
public static final class AStruct implements Struct<Translation3d> {
@Override
public Class<Translation3d> getTypeClass() {
return Translation3d.class;
}
@Override
public String getTypeString() {
return "struct:Translation3d";
}
@Override
public int getSize() {
return kSizeDouble * 3;
}
@Override
public String getSchema() {
return "double x;double y;double z";
}
@Override
public Translation3d unpack(ByteBuffer bb) {
double x = bb.getDouble();
double y = bb.getDouble();
double z = bb.getDouble();
return new Translation3d(x, y, z);
}
@Override
public void pack(ByteBuffer bb, Translation3d value) {
bb.putDouble(value.m_x);
bb.putDouble(value.m_y);
bb.putDouble(value.m_z);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Translation3d, ProtobufTranslation3d> {
@Override
public Class<Translation3d> getTypeClass() {
return Translation3d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufTranslation3d.getDescriptor();
}
@Override
public ProtobufTranslation3d createMessage() {
return ProtobufTranslation3d.newInstance();
}
@Override
public Translation3d unpack(ProtobufTranslation3d msg) {
return new Translation3d(msg.getX(), msg.getY(), msg.getZ());
}
@Override
public void pack(ProtobufTranslation3d msg, Translation3d value) {
msg.setX(value.m_x).setY(value.m_y).setZ(value.m_z);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -4,7 +4,12 @@
package edu.wpi.first.math.geometry;
import edu.wpi.first.math.proto.Geometry2D.ProtobufTwist2d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/**
* A change in distance along a 2D arc since the last pose update. We can use ideas from
@@ -62,4 +67,72 @@ public class Twist2d {
public int hashCode() {
return Objects.hash(dx, dy, dtheta);
}
public static final class AStruct implements Struct<Twist2d> {
@Override
public Class<Twist2d> getTypeClass() {
return Twist2d.class;
}
@Override
public String getTypeString() {
return "struct:Twist2d";
}
@Override
public int getSize() {
return kSizeDouble * 3;
}
@Override
public String getSchema() {
return "double dx;double dy;double dtheta";
}
@Override
public Twist2d unpack(ByteBuffer bb) {
double dx = bb.getDouble();
double dy = bb.getDouble();
double dtheta = bb.getDouble();
return new Twist2d(dx, dy, dtheta);
}
@Override
public void pack(ByteBuffer bb, Twist2d value) {
bb.putDouble(value.dx);
bb.putDouble(value.dy);
bb.putDouble(value.dtheta);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Twist2d, ProtobufTwist2d> {
@Override
public Class<Twist2d> getTypeClass() {
return Twist2d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufTwist2d.getDescriptor();
}
@Override
public ProtobufTwist2d createMessage() {
return ProtobufTwist2d.newInstance();
}
@Override
public Twist2d unpack(ProtobufTwist2d msg) {
return new Twist2d(msg.getDx(), msg.getDy(), msg.getDtheta());
}
@Override
public void pack(ProtobufTwist2d msg, Twist2d value) {
msg.setDx(value.dx).setDy(value.dy).setDtheta(value.dtheta);
}
}
public static final AProto proto = new AProto();
}

View File

@@ -4,7 +4,12 @@
package edu.wpi.first.math.geometry;
import edu.wpi.first.math.proto.Geometry3D.ProtobufTwist3d;
import edu.wpi.first.util.protobuf.Protobuf;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
import java.util.Objects;
import us.hebi.quickbuf.Descriptors.Descriptor;
/**
* A change in distance along a 3D arc since the last pose update. We can use ideas from
@@ -82,4 +87,84 @@ public class Twist3d {
public int hashCode() {
return Objects.hash(dx, dy, dz, rx, ry, rz);
}
public static final class AStruct implements Struct<Twist3d> {
@Override
public Class<Twist3d> getTypeClass() {
return Twist3d.class;
}
@Override
public String getTypeString() {
return "struct:Twist3d";
}
@Override
public int getSize() {
return kSizeDouble * 6;
}
@Override
public String getSchema() {
return "double dx;double dy;double dz;double rx;double ry;double rz";
}
@Override
public Twist3d unpack(ByteBuffer bb) {
double dx = bb.getDouble();
double dy = bb.getDouble();
double dz = bb.getDouble();
double rx = bb.getDouble();
double ry = bb.getDouble();
double rz = bb.getDouble();
return new Twist3d(dx, dy, dz, rx, ry, rz);
}
@Override
public void pack(ByteBuffer bb, Twist3d value) {
bb.putDouble(value.dx);
bb.putDouble(value.dy);
bb.putDouble(value.dz);
bb.putDouble(value.rx);
bb.putDouble(value.ry);
bb.putDouble(value.rz);
}
}
public static final AStruct struct = new AStruct();
public static final class AProto implements Protobuf<Twist3d, ProtobufTwist3d> {
@Override
public Class<Twist3d> getTypeClass() {
return Twist3d.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufTwist3d.getDescriptor();
}
@Override
public ProtobufTwist3d createMessage() {
return ProtobufTwist3d.newInstance();
}
@Override
public Twist3d unpack(ProtobufTwist3d msg) {
return new Twist3d(
msg.getDx(), msg.getDy(), msg.getDz(), msg.getRx(), msg.getRy(), msg.getRz());
}
@Override
public void pack(ProtobufTwist3d msg, Twist3d value) {
msg.setDx(value.dx)
.setDy(value.dy)
.setDz(value.dz)
.setRx(value.rx)
.setRy(value.ry)
.setRz(value.rz);
}
}
public static final AProto proto = new AProto();
}