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.kinematics.MecanumDriveWheelPositions;
008import edu.wpi.first.util.struct.Struct;
009import java.nio.ByteBuffer;
010
011public class MecanumDriveWheelPositionsStruct implements Struct<MecanumDriveWheelPositions> {
012  @Override
013  public Class<MecanumDriveWheelPositions> getTypeClass() {
014    return MecanumDriveWheelPositions.class;
015  }
016
017  @Override
018  public String getTypeString() {
019    return "struct:MecanumDriveWheelPositions";
020  }
021
022  @Override
023  public int getSize() {
024    return kSizeDouble * 4;
025  }
026
027  @Override
028  public String getSchema() {
029    return "double front_left;double front_right;double rear_left;double rear_right";
030  }
031
032  @Override
033  public MecanumDriveWheelPositions unpack(ByteBuffer bb) {
034    double frontLeft = bb.getDouble();
035    double frontRight = bb.getDouble();
036    double rearLeft = bb.getDouble();
037    double rearRight = bb.getDouble();
038    return new MecanumDriveWheelPositions(frontLeft, frontRight, rearLeft, rearRight);
039  }
040
041  @Override
042  public void pack(ByteBuffer bb, MecanumDriveWheelPositions value) {
043    bb.putDouble(value.frontLeftMeters);
044    bb.putDouble(value.frontRightMeters);
045    bb.putDouble(value.rearLeftMeters);
046    bb.putDouble(value.rearRightMeters);
047  }
048}