Interface Struct<T>

Type Parameters:
T - object type
All Known Implementing Classes:
ArmFeedforwardStruct, ChassisSpeedsStruct, CubicHermiteSplineStruct, DCMotorStruct, DifferentialDriveFeedforwardStruct, DifferentialDriveKinematicsStruct, DifferentialDriveWheelPositionsStruct, DifferentialDriveWheelSpeedsStruct, DifferentialDriveWheelVoltagesStruct, ElevatorFeedforwardStruct, Ellipse2dStruct, LinearSystemStruct, MatrixStruct, MecanumDriveKinematicsStruct, MecanumDriveWheelPositionsStruct, MecanumDriveWheelSpeedsStruct, Pose2dStruct, Pose3dStruct, QuaternionStruct, QuinticHermiteSplineStruct, Rectangle2dStruct, Rotation2dStruct, Rotation3dStruct, SimpleMotorFeedforwardStruct, SwerveDriveKinematicsStruct, SwerveModulePositionStruct, SwerveModuleStateStruct, Transform2dStruct, Transform3dStruct, Translation2dStruct, Translation3dStruct, Twist2dStruct, Twist3dStruct, VectorStruct

public interface Struct<T>
Interface for raw struct serialization.

This is designed for serializing small fixed-size data structures in the fastest and most compact means possible. Serialization consists of making relative put() calls to a ByteBuffer and deserialization consists of making relative get() calls from a ByteBuffer.

Idiomatically, classes that support raw struct serialization should provide a static final member named "struct" that provides an instance of an implementation of this interface.

  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    static final int
    Serialized size of a "bool" value.
    static final int
    Serialized size of an "double" or "float64" value.
    static final int
    Serialized size of an "float" or "float32" value.
    static final int
    Serialized size of an "int16" or "uint16" value.
    static final int
    Serialized size of an "int32" or "uint32" value.
    static final int
    Serialized size of an "int64" or "uint64" value.
    static final int
    Serialized size of an "int8" or "uint8" value.
  • Method Summary

    Modifier and Type
    Method
    Description
    default T
    clone(T obj)
    Creates a (deep) clone of the object.
    default Struct<?>[]
    Gets the list of struct types referenced by this struct.
    Gets the schema.
    int
    Gets the serialized size (in bytes).
    Gets the Class object for the stored value.
    Gets the type name (e.g.
    default String
    Gets the type string (e.g.
    default boolean
    Returns whether or not objects are cloneable using the clone() method.
    default boolean
    Returns whether or not objects are immutable.
    void
    pack(ByteBuffer bb, T value)
    Puts object contents to a ByteBuffer starting at the current position.
    static void
    packArray(ByteBuffer bb, double[] arr)
    Puts array contents to a ByteBuffer starting at the current position.
    static <T> void
    packArray(ByteBuffer bb, T[] arr, Struct<T> struct)
    Puts array contents to a ByteBuffer starting at the current position.
    Deserializes an object from a raw struct serialized ByteBuffer starting at the current position.
    static <T> T[]
    unpackArray(ByteBuffer bb, int size, Struct<T> struct)
    Deserializes an array from a raw struct serialized ByteBuffer starting at the current position.
    static double[]
    Deserializes a double array from a raw struct serialized ByteBuffer starting at the current position.
    default void
    Updates object contents from a raw struct serialized ByteBuffer starting at the current position.
  • Field Details

  • Method Details

    • getTypeClass

      Gets the Class object for the stored value.
      Returns:
      Class
    • getTypeName

      Gets the type name (e.g. for schemas of other structs). This should be globally unique among structs.
      Returns:
      type name
    • getTypeString

      default String getTypeString()
      Gets the type string (e.g. for NetworkTables). This should be globally unique and start with "struct:".
      Returns:
      type string
    • getSize

      int getSize()
      Gets the serialized size (in bytes). This should always be a constant.
      Returns:
      serialized size
    • getSchema

      Gets the schema.
      Returns:
      schema
    • getNested

      default Struct<?>[] getNested()
      Gets the list of struct types referenced by this struct.
      Returns:
      list of struct types
    • unpack

      Deserializes an object from a raw struct serialized ByteBuffer starting at the current position. Will increment the ByteBuffer position by getStructSize() bytes. Will not otherwise modify the ByteBuffer (e.g. byte order will not be changed).
      Parameters:
      bb - ByteBuffer
      Returns:
      New object
    • pack

      void pack(ByteBuffer bb, T value)
      Puts object contents to a ByteBuffer starting at the current position. Will increment the ByteBuffer position by getStructSize() bytes. Will not otherwise modify the ByteBuffer (e.g. byte order will not be changed).
      Parameters:
      bb - ByteBuffer
      value - object to serialize
    • unpackInto

      default void unpackInto(T out, ByteBuffer bb)
      Updates object contents from a raw struct serialized ByteBuffer starting at the current position. Will increment the ByteBuffer position by getStructSize() bytes. Will not otherwise modify the ByteBuffer (e.g. byte order will not be changed).

      Immutable classes cannot and should not implement this function. The default implementation throws UnsupportedOperationException.

      Parameters:
      out - object to update
      bb - ByteBuffer
      Throws:
      UnsupportedOperationException - if the object is immutable
    • unpackArray

      static <T> T[] unpackArray(ByteBuffer bb, int size, Struct<T> struct)
      Deserializes an array from a raw struct serialized ByteBuffer starting at the current position. Will increment the ByteBuffer position by size * struct.size() bytes. Will not otherwise modify the ByteBuffer (e.g. byte order will not be changed).
      Type Parameters:
      T - Object type
      Parameters:
      bb - ByteBuffer
      size - Size of the array
      struct - Struct implementation
      Returns:
      Deserialized array
    • unpackDoubleArray

      static double[] unpackDoubleArray(ByteBuffer bb, int size)
      Deserializes a double array from a raw struct serialized ByteBuffer starting at the current position. Will increment the ByteBuffer position by size * kSizeDouble bytes. Will not otherwise modify the ByteBuffer (e.g. byte order will not be changed).
      Parameters:
      bb - ByteBuffer
      size - Size of the array
      Returns:
      Double array
    • packArray

      static <T> void packArray(ByteBuffer bb, T[] arr, Struct<T> struct)
      Puts array contents to a ByteBuffer starting at the current position. Will increment the ByteBuffer position by size * struct.size() bytes. Will not otherwise modify the ByteBuffer (e.g. byte order will not be changed).
      Type Parameters:
      T - Object type
      Parameters:
      bb - ByteBuffer
      arr - Array to serialize
      struct - Struct implementation
    • packArray

      static void packArray(ByteBuffer bb, double[] arr)
      Puts array contents to a ByteBuffer starting at the current position. Will increment the ByteBuffer position by size * kSizeDouble bytes. Will not otherwise modify the ByteBuffer (e.g. byte order will not be changed).
      Parameters:
      bb - ByteBuffer
      arr - Array to serialize
    • isImmutable

      default boolean isImmutable()
      Returns whether or not objects are immutable. Immutable objects must also be comparable using the equals() method. Default implementation returns false.
      Returns:
      True if object is immutable
    • isCloneable

      default boolean isCloneable()
      Returns whether or not objects are cloneable using the clone() method. Cloneable objects must also be comparable using the equals() method. Default implementation returns false.
      Returns:
      True if object is cloneable
    • clone

      default T clone(T obj) throws CloneNotSupportedException
      Creates a (deep) clone of the object. May also return the object directly if the object is immutable. Default implementation throws CloneNotSupportedException. Typically this should be implemented by implementing clone() on the object itself, and calling it from here.
      Parameters:
      obj - object to clone
      Returns:
      Clone of object (if immutable, may be same object)
      Throws:
      CloneNotSupportedException - if clone not supported