[wpimath] Add structured data support for DifferentialDriveWheelPositions (#6412)

This commit is contained in:
DeltaDizzy
2024-03-09 12:09:02 -06:00
committed by GitHub
parent 18e57f7872
commit 7bd8c44570
12 changed files with 668 additions and 58 deletions

View File

@@ -7,6 +7,8 @@ package edu.wpi.first.math.kinematics;
import static edu.wpi.first.units.Units.Meters;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.kinematics.proto.DifferentialDriveWheelPositionsProto;
import edu.wpi.first.math.kinematics.struct.DifferentialDriveWheelPositionsStruct;
import edu.wpi.first.units.Distance;
import edu.wpi.first.units.Measure;
import java.util.Objects;
@@ -20,6 +22,14 @@ public class DifferentialDriveWheelPositions
/** Distance measured by the right side. */
public double rightMeters;
/** DifferentialDriveWheelPostions struct for serialization. */
public static final DifferentialDriveWheelPositionsStruct struct =
new DifferentialDriveWheelPositionsStruct();
/** DifferentialDriveWheelPostions struct for serialization. */
public static final DifferentialDriveWheelPositionsProto proto =
new DifferentialDriveWheelPositionsProto();
/**
* Constructs a DifferentialDriveWheelPositions.
*

View File

@@ -0,0 +1,40 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package edu.wpi.first.math.kinematics.proto;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelPositions;
import edu.wpi.first.math.proto.Kinematics.ProtobufDifferentialDriveWheelPositions;
import edu.wpi.first.util.protobuf.Protobuf;
import us.hebi.quickbuf.Descriptors.Descriptor;
public class DifferentialDriveWheelPositionsProto
implements Protobuf<DifferentialDriveWheelPositions, ProtobufDifferentialDriveWheelPositions> {
@Override
public Class<DifferentialDriveWheelPositions> getTypeClass() {
return DifferentialDriveWheelPositions.class;
}
@Override
public Descriptor getDescriptor() {
return ProtobufDifferentialDriveWheelPositions.getDescriptor();
}
@Override
public ProtobufDifferentialDriveWheelPositions createMessage() {
return ProtobufDifferentialDriveWheelPositions.newInstance();
}
@Override
public DifferentialDriveWheelPositions unpack(ProtobufDifferentialDriveWheelPositions msg) {
return new DifferentialDriveWheelPositions(msg.getLeft(), msg.getRight());
}
@Override
public void pack(
ProtobufDifferentialDriveWheelPositions msg, DifferentialDriveWheelPositions value) {
msg.setLeft(value.leftMeters);
msg.setRight(value.rightMeters);
}
}

View File

@@ -0,0 +1,45 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package edu.wpi.first.math.kinematics.struct;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelPositions;
import edu.wpi.first.util.struct.Struct;
import java.nio.ByteBuffer;
public class DifferentialDriveWheelPositionsStruct
implements Struct<DifferentialDriveWheelPositions> {
@Override
public Class<DifferentialDriveWheelPositions> getTypeClass() {
return DifferentialDriveWheelPositions.class;
}
@Override
public String getTypeString() {
return "struct:DifferentialDriveWheelPositions";
}
@Override
public int getSize() {
return kSizeDouble * 2;
}
@Override
public String getSchema() {
return "double left;double right";
}
@Override
public DifferentialDriveWheelPositions unpack(ByteBuffer bb) {
double left = bb.getDouble();
double right = bb.getDouble();
return new DifferentialDriveWheelPositions(left, right);
}
@Override
public void pack(ByteBuffer bb, DifferentialDriveWheelPositions value) {
bb.putDouble(value.leftMeters);
bb.putDouble(value.rightMeters);
}
}