diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java
index 8bcb6a74cfa..d67a7816475 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java
@@ -120,6 +120,13 @@ public DifferentialDriveWheelPositions copy(DifferentialDriveWheelPositions posi
return new DifferentialDriveWheelPositions(positions.leftMeters, positions.rightMeters);
}
+ @Override
+ public void copyInto(
+ DifferentialDriveWheelPositions positions, DifferentialDriveWheelPositions output) {
+ output.leftMeters = positions.leftMeters;
+ output.rightMeters = positions.rightMeters;
+ }
+
@Override
public DifferentialDriveWheelPositions interpolate(
DifferentialDriveWheelPositions startValue,
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java
index a64c9a20091..307999d6552 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Kinematics.java
@@ -53,4 +53,13 @@ public interface Kinematics extends Interpolator
{
* @return A copy.
*/
P copy(P positions);
+
+ /**
+ * Copies the value of the wheel positions object into the output.
+ *
+ * @param positions The wheel positions object to copy. Will not be modified.
+ * @param output The output variable of the copy operation. Will have the same value as the
+ * positions object after the call.
+ */
+ void copyInto(P positions, P output);
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java
index 4589a448533..26108088c63 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveKinematics.java
@@ -266,6 +266,14 @@ public MecanumDriveWheelPositions copy(MecanumDriveWheelPositions positions) {
positions.rearRightMeters);
}
+ @Override
+ public void copyInto(MecanumDriveWheelPositions positions, MecanumDriveWheelPositions output) {
+ output.frontLeftMeters = positions.frontLeftMeters;
+ output.frontRightMeters = positions.frontRightMeters;
+ output.rearLeftMeters = positions.rearLeftMeters;
+ output.rearRightMeters = positions.rearRightMeters;
+ }
+
@Override
public MecanumDriveWheelPositions interpolate(
MecanumDriveWheelPositions startValue, MecanumDriveWheelPositions endValue, double t) {
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java
index 66ce592957d..6a09f92bffd 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java
@@ -25,7 +25,7 @@ public class Odometry