001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.math.kinematics.struct;
006
007import edu.wpi.first.math.geometry.Rotation2d;
008import edu.wpi.first.math.kinematics.SwerveModulePosition;
009import edu.wpi.first.util.struct.Struct;
010import java.nio.ByteBuffer;
011
012public class SwerveModulePositionStruct implements Struct<SwerveModulePosition> {
013  @Override
014  public Class<SwerveModulePosition> getTypeClass() {
015    return SwerveModulePosition.class;
016  }
017
018  @Override
019  public String getTypeString() {
020    return "struct:SwerveModulePosition";
021  }
022
023  @Override
024  public int getSize() {
025    return kSizeDouble + Rotation2d.struct.getSize();
026  }
027
028  @Override
029  public String getSchema() {
030    return "double distance;Rotation2d angle";
031  }
032
033  @Override
034  public Struct<?>[] getNested() {
035    return new Struct<?>[] {Rotation2d.struct};
036  }
037
038  @Override
039  public SwerveModulePosition unpack(ByteBuffer bb) {
040    double distance = bb.getDouble();
041    Rotation2d angle = Rotation2d.struct.unpack(bb);
042    return new SwerveModulePosition(distance, angle);
043  }
044
045  @Override
046  public void pack(ByteBuffer bb, SwerveModulePosition value) {
047    bb.putDouble(value.distanceMeters);
048    Rotation2d.struct.pack(bb, value.angle);
049  }
050}