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.proto;
006
007import edu.wpi.first.math.geometry.Rotation2d;
008import edu.wpi.first.math.kinematics.SwerveModuleState;
009import edu.wpi.first.math.proto.Kinematics.ProtobufSwerveModuleState;
010import edu.wpi.first.util.protobuf.Protobuf;
011import us.hebi.quickbuf.Descriptors.Descriptor;
012
013public class SwerveModuleStateProto
014    implements Protobuf<SwerveModuleState, ProtobufSwerveModuleState> {
015  @Override
016  public Class<SwerveModuleState> getTypeClass() {
017    return SwerveModuleState.class;
018  }
019
020  @Override
021  public Descriptor getDescriptor() {
022    return ProtobufSwerveModuleState.getDescriptor();
023  }
024
025  @Override
026  public Protobuf<?, ?>[] getNested() {
027    return new Protobuf<?, ?>[] {Rotation2d.proto};
028  }
029
030  @Override
031  public ProtobufSwerveModuleState createMessage() {
032    return ProtobufSwerveModuleState.newInstance();
033  }
034
035  @Override
036  public SwerveModuleState unpack(ProtobufSwerveModuleState msg) {
037    return new SwerveModuleState(msg.getSpeed(), Rotation2d.proto.unpack(msg.getAngle()));
038  }
039
040  @Override
041  public void pack(ProtobufSwerveModuleState msg, SwerveModuleState value) {
042    msg.setSpeed(value.speedMetersPerSecond);
043    Rotation2d.proto.pack(msg.getMutableAngle(), value.angle);
044  }
045}