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 org.wpilib.math.kinematics.proto; 006 007import org.wpilib.math.geometry.Rotation2d; 008import org.wpilib.math.kinematics.SwerveModuleVelocity; 009import org.wpilib.math.proto.ProtobufSwerveModuleVelocity; 010import org.wpilib.util.protobuf.Protobuf; 011import us.hebi.quickbuf.Descriptors.Descriptor; 012 013public class SwerveModuleVelocityProto 014 implements Protobuf<SwerveModuleVelocity, ProtobufSwerveModuleVelocity> { 015 @Override 016 public Class<SwerveModuleVelocity> getTypeClass() { 017 return SwerveModuleVelocity.class; 018 } 019 020 @Override 021 public Descriptor getDescriptor() { 022 return ProtobufSwerveModuleVelocity.getDescriptor(); 023 } 024 025 @Override 026 public ProtobufSwerveModuleVelocity createMessage() { 027 return ProtobufSwerveModuleVelocity.newInstance(); 028 } 029 030 @Override 031 public SwerveModuleVelocity unpack(ProtobufSwerveModuleVelocity msg) { 032 return new SwerveModuleVelocity(msg.getVelocity(), Rotation2d.proto.unpack(msg.getAngle())); 033 } 034 035 @Override 036 public void pack(ProtobufSwerveModuleVelocity msg, SwerveModuleVelocity value) { 037 msg.setVelocity(value.velocity); 038 Rotation2d.proto.pack(msg.getMutableAngle(), value.angle); 039 } 040}